From 93de9848e386447a6a7cade8875118852afdf139 Mon Sep 17 00:00:00 2001 From: Nithya Date: Wed, 9 Jun 2021 12:41:20 -0400 Subject: [PATCH 0001/1686] Added *.bib file --- README.md | 5 +++++ references.bib | 9 +++++++++ 2 files changed, 14 insertions(+) create mode 100644 references.bib diff --git a/README.md b/README.md index 60eff197a..a83b013c9 100644 --- a/README.md +++ b/README.md @@ -95,3 +95,8 @@ GTSAM is open source under the BSD license, see the [`LICENSE`](LICENSE) and [`L Please see the [`examples/`](examples) directory and the [`USAGE`](USAGE.md) file for examples on how to use GTSAM. GTSAM was developed in the lab of [Frank Dellaert](http://www.cc.gatech.edu/~dellaert) at the [Georgia Institute of Technology](http://www.gatech.edu), with the help of many contributors over the years, see [THANKS](THANKS.md). + +## GTSAM Citation + +Use the following to cite GTSAM: + diff --git a/references.bib b/references.bib new file mode 100644 index 000000000..52c00325e --- /dev/null +++ b/references.bib @@ -0,0 +1,9 @@ +@misc{gtsam, + author = {Borg Lab}, + title = {{GTSAM}}, + month = jul, + year = 2020, + doi = {}, + version = {4.0.3}, + url = {} + } \ No newline at end of file From 1c00d130f5a96616b9d8dc99ec27506e71a17cf3 Mon Sep 17 00:00:00 2001 From: Nithya Date: Fri, 11 Jun 2021 11:25:21 -0400 Subject: [PATCH 0002/1686] additional citations --- README.md | 3 --- references.bib | 23 +++++++++++++++++++---- 2 files changed, 19 insertions(+), 7 deletions(-) diff --git a/README.md b/README.md index a83b013c9..cb7b3d464 100644 --- a/README.md +++ b/README.md @@ -96,7 +96,4 @@ Please see the [`examples/`](examples) directory and the [`USAGE`](USAGE.md) fil GTSAM was developed in the lab of [Frank Dellaert](http://www.cc.gatech.edu/~dellaert) at the [Georgia Institute of Technology](http://www.gatech.edu), with the help of many contributors over the years, see [THANKS](THANKS.md). -## GTSAM Citation - -Use the following to cite GTSAM: diff --git a/references.bib b/references.bib index 52c00325e..5468204cc 100644 --- a/references.bib +++ b/references.bib @@ -1,9 +1,24 @@ @misc{gtsam, - author = {Borg Lab}, + author = {{Borg Lab}}, title = {{GTSAM}}, month = jul, year = 2020, - doi = {}, version = {4.0.3}, - url = {} - } \ No newline at end of file + url = {https://github.com/borglab/gtsam} + } + +@article{imu-preintegration, + author = {{Christian Forster and Luca Carlone and Frank Dellaert and Davide Scaramuzza}}, + title = {{IMU preintegration on Manifold for Efficient Visual-Inertial Maximum-a-Posteriori Estimation}}, + year = 2015 + +} + +@techreport{factorgraphs, + author = {Frank Dellaert}, + title = {{Factor Graphs and GTSAM: A Hands-On Introduction}}, + number = {GT-RIM-CP\&R-2012-002}, + month = jul, + year = 2012 + +} \ No newline at end of file From 5e735e10f7c2b731b831c5f1ffec7631f0fc90e6 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 16 Sep 2021 13:03:11 -0400 Subject: [PATCH 0003/1686] minor improvements to CombinedImuFactor --- examples/CombinedImuFactorsExample.cpp | 15 ++++++++------- gtsam/navigation/CombinedImuFactor.cpp | 5 +++++ 2 files changed, 13 insertions(+), 7 deletions(-) diff --git a/examples/CombinedImuFactorsExample.cpp b/examples/CombinedImuFactorsExample.cpp index 9211a4d5f..49cdb6835 100644 --- a/examples/CombinedImuFactorsExample.cpp +++ b/examples/CombinedImuFactorsExample.cpp @@ -60,13 +60,14 @@ namespace po = boost::program_options; po::variables_map parseOptions(int argc, char* argv[]) { po::options_description desc; - desc.add_options()("help,h", "produce help message")( - "data_csv_path", po::value()->default_value("imuAndGPSdata.csv"), - "path to the CSV file with the IMU data")( - "output_filename", - po::value()->default_value("imuFactorExampleResults.csv"), - "path to the result file to use")("use_isam", po::bool_switch(), - "use ISAM as the optimizer"); + desc.add_options()("help,h", "produce help message") // help message + ("data_csv_path", po::value()->default_value("imuAndGPSdata.csv"), + "path to the CSV file with the IMU data") // path to the data file + ("output_filename", + po::value()->default_value("imuFactorExampleResults.csv"), + "path to the result file to use") // filename to save results to + ("use_isam", po::bool_switch(), + "use ISAM as the optimizer"); // flag for ISAM optimizer po::variables_map vm; po::store(po::parse_command_line(argc, argv, desc), vm); diff --git a/gtsam/navigation/CombinedImuFactor.cpp b/gtsam/navigation/CombinedImuFactor.cpp index ca1c5b93a..12e8ccea8 100644 --- a/gtsam/navigation/CombinedImuFactor.cpp +++ b/gtsam/navigation/CombinedImuFactor.cpp @@ -93,6 +93,11 @@ void PreintegratedCombinedMeasurements::resetIntegration() { //------------------------------------------------------------------------------ void PreintegratedCombinedMeasurements::integrateMeasurement( const Vector3& measuredAcc, const Vector3& measuredOmega, double dt) { + if (dt <= 0) { + throw std::runtime_error( + "PreintegratedCombinedMeasurements::integrateMeasurement: dt <=0"); + } + // Update preintegrated measurements. Matrix9 A; // overall Jacobian wrt preintegrated measurements (df/dx) Matrix93 B, C; From 9dbb431db9562c61cb442da0a89b6a6ab933222e Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 16 Sep 2021 19:00:08 -0400 Subject: [PATCH 0004/1686] account for bias on position in jacobians of CombinedImuFactor --- gtsam/navigation/CombinedImuFactor.cpp | 16 +++++++++++----- 1 file changed, 11 insertions(+), 5 deletions(-) diff --git a/gtsam/navigation/CombinedImuFactor.cpp b/gtsam/navigation/CombinedImuFactor.cpp index 12e8ccea8..28d96d343 100644 --- a/gtsam/navigation/CombinedImuFactor.cpp +++ b/gtsam/navigation/CombinedImuFactor.cpp @@ -99,7 +99,7 @@ void PreintegratedCombinedMeasurements::integrateMeasurement( } // Update preintegrated measurements. - Matrix9 A; // overall Jacobian wrt preintegrated measurements (df/dx) + Matrix9 A; // Jacobian wrt preintegrated measurements without bias (df/dx) Matrix93 B, C; PreintegrationType::update(measuredAcc, measuredOmega, dt, &A, &B, &C); @@ -110,8 +110,8 @@ void PreintegratedCombinedMeasurements::integrateMeasurement( // and preintegrated measurements // Single Jacobians to propagate covariance - // TODO(frank): should we not also account for bias on position? Matrix3 theta_H_biasOmega = -C.topRows<3>(); + Matrix3 pos_H_biasAcc = -B.middleRows<3>(3); Matrix3 vel_H_biasAcc = -B.bottomRows<3>(); // overall Jacobian wrt preintegrated measurements (df/dx) @@ -119,6 +119,7 @@ void PreintegratedCombinedMeasurements::integrateMeasurement( F.setZero(); F.block<9, 9>(0, 0) = A; F.block<3, 3>(0, 12) = theta_H_biasOmega; + F.block<3, 3>(3, 9) = pos_H_biasAcc; F.block<3, 3>(6, 9) = vel_H_biasAcc; F.block<6, 6>(9, 9) = I_6x6; @@ -129,15 +130,19 @@ void PreintegratedCombinedMeasurements::integrateMeasurement( const Matrix3& iCov = p().integrationCovariance; // first order uncertainty propagation - // Optimized matrix multiplication (1/dt) * G * measurementCovariance * + // Optimized matrix multiplication: (1/dt) * G * measurementCovariance * // G.transpose() Eigen::Matrix G_measCov_Gt; G_measCov_Gt.setZero(15, 15); + Matrix3 aCov_updated = (aCov + p().biasAccOmegaInt.block<3, 3>(0, 0)); + // BLOCK DIAGONAL TERMS - D_t_t(&G_measCov_Gt) = dt * iCov; + D_t_t(&G_measCov_Gt) = ((1 / dt) * pos_H_biasAcc + * aCov_updated + * (pos_H_biasAcc.transpose())) + (dt * iCov); D_v_v(&G_measCov_Gt) = (1 / dt) * vel_H_biasAcc - * (aCov + p().biasAccOmegaInt.block<3, 3>(0, 0)) + * aCov_updated * (vel_H_biasAcc.transpose()); D_R_R(&G_measCov_Gt) = (1 / dt) * theta_H_biasOmega * (wCov + p().biasAccOmegaInt.block<3, 3>(3, 3)) @@ -150,6 +155,7 @@ void PreintegratedCombinedMeasurements::integrateMeasurement( * theta_H_biasOmega.transpose(); D_v_R(&G_measCov_Gt) = temp; D_R_v(&G_measCov_Gt) = temp.transpose(); + preintMeasCov_ = F * preintMeasCov_ * F.transpose() + G_measCov_Gt; } From 7e48962f99cfa3e1e716a05d59eeb667da34c732 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Fri, 17 Sep 2021 13:28:42 -0400 Subject: [PATCH 0005/1686] Add unit test for checking covariance of CombinedImuFactor --- gtsam/navigation/CombinedImuFactor.cpp | 5 ++- .../tests/testCombinedImuFactor.cpp | 42 +++++++++++++++++++ 2 files changed, 45 insertions(+), 2 deletions(-) diff --git a/gtsam/navigation/CombinedImuFactor.cpp b/gtsam/navigation/CombinedImuFactor.cpp index 28d96d343..216140dbc 100644 --- a/gtsam/navigation/CombinedImuFactor.cpp +++ b/gtsam/navigation/CombinedImuFactor.cpp @@ -130,8 +130,7 @@ void PreintegratedCombinedMeasurements::integrateMeasurement( const Matrix3& iCov = p().integrationCovariance; // first order uncertainty propagation - // Optimized matrix multiplication: (1/dt) * G * measurementCovariance * - // G.transpose() + // Optimized matrix mult: (1/dt) * G * measurementCovariance * G.transpose() Eigen::Matrix G_measCov_Gt; G_measCov_Gt.setZero(15, 15); @@ -144,9 +143,11 @@ void PreintegratedCombinedMeasurements::integrateMeasurement( D_v_v(&G_measCov_Gt) = (1 / dt) * vel_H_biasAcc * aCov_updated * (vel_H_biasAcc.transpose()); + D_R_R(&G_measCov_Gt) = (1 / dt) * theta_H_biasOmega * (wCov + p().biasAccOmegaInt.block<3, 3>(3, 3)) * (theta_H_biasOmega.transpose()); + D_a_a(&G_measCov_Gt) = dt * p().biasAccCovariance; D_g_g(&G_measCov_Gt) = dt * p().biasOmegaCovariance; diff --git a/gtsam/navigation/tests/testCombinedImuFactor.cpp b/gtsam/navigation/tests/testCombinedImuFactor.cpp index 2bbc2cc7c..dc9ae288a 100644 --- a/gtsam/navigation/tests/testCombinedImuFactor.cpp +++ b/gtsam/navigation/tests/testCombinedImuFactor.cpp @@ -203,6 +203,48 @@ TEST(CombinedImuFactor, PredictRotation) { EXPECT(assert_equal(expectedPose, actual.pose(), tol)); } +/* ************************************************************************* */ +// Testing covariance to check if all the jacobians are accounted for. +TEST(CombinedImuFactor, CheckCovariance) { + auto params = PreintegrationCombinedParams::MakeSharedU(9.81); + + params->setAccelerometerCovariance(pow(0.01, 2) * I_3x3); + params->setGyroscopeCovariance(pow(1.75e-4, 2) * I_3x3); + params->setIntegrationCovariance(pow(0.0, 2) * I_3x3); + params->setOmegaCoriolis(Vector3::Zero()); + + imuBias::ConstantBias currentBias; + + PreintegratedCombinedMeasurements actual(params, currentBias); + + // Measurements + Vector3 measuredAcc(0.1577, -0.8251, 9.6111); + Vector3 measuredOmega(-0.0210, 0.0311, 0.0145); + double deltaT = 0.01; + + actual.integrateMeasurement(measuredAcc, measuredOmega, deltaT); + + Eigen::Matrix expected; + expected << 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // + 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // + 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // + 0, 0, 0, 2.50025e-07, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // + 0, 0, 0, 0, 2.50025e-07, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // + 0, 0, 0, 0, 0, 2.50025e-07, 0, 0, 0, 0, 0, 0, 0, 0, 0, // + 0, 0, 0, 0, 0, 0, 0.010001, 0, 0, 0, 0, 0, 0, 0, 0, // + 0, 0, 0, 0, 0, 0, 0, 0.010001, 0, 0, 0, 0, 0, 0, 0, // + 0, 0, 0, 0, 0, 0, 0, 0, 0.010001, 0, 0, 0, 0, 0, 0, // + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, // + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, // + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, // + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, // + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, // + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01; + + // regression + EXPECT(assert_equal(expected, actual.preintMeasCov())); +} + /* ************************************************************************* */ int main() { TestResult tr; From b0fcd17140cd3a9fb9abde60e4d52d18139a7145 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Fri, 17 Sep 2021 14:19:41 -0400 Subject: [PATCH 0006/1686] additional comments to make understanding the code easier --- gtsam/navigation/CombinedImuFactor.cpp | 2 +- gtsam/navigation/ImuFactor.cpp | 6 ++++-- 2 files changed, 5 insertions(+), 3 deletions(-) diff --git a/gtsam/navigation/CombinedImuFactor.cpp b/gtsam/navigation/CombinedImuFactor.cpp index 216140dbc..1e99db17c 100644 --- a/gtsam/navigation/CombinedImuFactor.cpp +++ b/gtsam/navigation/CombinedImuFactor.cpp @@ -100,7 +100,7 @@ void PreintegratedCombinedMeasurements::integrateMeasurement( // Update preintegrated measurements. Matrix9 A; // Jacobian wrt preintegrated measurements without bias (df/dx) - Matrix93 B, C; + Matrix93 B, C; // Jacobian of state wrpt accel bias and omega bias respectively. PreintegrationType::update(measuredAcc, measuredOmega, dt, &A, &B, &C); // Update preintegrated measurements covariance: as in [2] we consider a first diff --git a/gtsam/navigation/ImuFactor.cpp b/gtsam/navigation/ImuFactor.cpp index 28c0461b1..9b6affaaf 100644 --- a/gtsam/navigation/ImuFactor.cpp +++ b/gtsam/navigation/ImuFactor.cpp @@ -59,7 +59,7 @@ void PreintegratedImuMeasurements::integrateMeasurement( // Update preintegrated measurements (also get Jacobian) Matrix9 A; // overall Jacobian wrt preintegrated measurements (df/dx) - Matrix93 B, C; + Matrix93 B, C; // Jacobian of state wrpt accel bias and omega bias respectively. PreintegrationType::update(measuredAcc, measuredOmega, dt, &A, &B, &C); // first order covariance propagation: @@ -73,11 +73,13 @@ void PreintegratedImuMeasurements::integrateMeasurement( const Matrix3& iCov = p().integrationCovariance; // (1/dt) allows to pass from continuous time noise to discrete time noise + // Update the uncertainty on the state (matrix A in [4]). preintMeasCov_ = A * preintMeasCov_ * A.transpose(); + // These 2 updates account for uncertainty on the IMU measurement (matrix B in [4]). preintMeasCov_.noalias() += B * (aCov / dt) * B.transpose(); preintMeasCov_.noalias() += C * (wCov / dt) * C.transpose(); - // NOTE(frank): (Gi*dt)*(C/dt)*(Gi'*dt), with Gi << Z_3x3, I_3x3, Z_3x3 + // NOTE(frank): (Gi*dt)*(C/dt)*(Gi'*dt), with Gi << Z_3x3, I_3x3, Z_3x3 (9x3 matrix) preintMeasCov_.block<3, 3>(3, 3).noalias() += iCov * dt; } From 5656308e9d4ed1af3d3623717b3c19709f51852b Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Fri, 17 Sep 2021 14:20:10 -0400 Subject: [PATCH 0007/1686] no need to assign negative to jacobians as they cancel out later --- gtsam/navigation/CombinedImuFactor.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/gtsam/navigation/CombinedImuFactor.cpp b/gtsam/navigation/CombinedImuFactor.cpp index 1e99db17c..24e2e3016 100644 --- a/gtsam/navigation/CombinedImuFactor.cpp +++ b/gtsam/navigation/CombinedImuFactor.cpp @@ -110,9 +110,9 @@ void PreintegratedCombinedMeasurements::integrateMeasurement( // and preintegrated measurements // Single Jacobians to propagate covariance - Matrix3 theta_H_biasOmega = -C.topRows<3>(); - Matrix3 pos_H_biasAcc = -B.middleRows<3>(3); - Matrix3 vel_H_biasAcc = -B.bottomRows<3>(); + Matrix3 theta_H_biasOmega = C.topRows<3>(); + Matrix3 pos_H_biasAcc = B.middleRows<3>(3); + Matrix3 vel_H_biasAcc = B.bottomRows<3>(); // overall Jacobian wrt preintegrated measurements (df/dx) Eigen::Matrix F; From 810f97305fa53be6d24d1945b234c2cbde652fec Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Fri, 17 Sep 2021 14:21:39 -0400 Subject: [PATCH 0008/1686] add details about noise propagation for CombinedImuFactor in ImuFactor.pdf --- doc/ImuFactor.lyx | 155 +++++++++++++++++++++++++++++++++++++++------- doc/ImuFactor.pdf | Bin 198168 -> 225325 bytes 2 files changed, 133 insertions(+), 22 deletions(-) diff --git a/doc/ImuFactor.lyx b/doc/ImuFactor.lyx index 0922a3e9c..bba8f212a 100644 --- a/doc/ImuFactor.lyx +++ b/doc/ImuFactor.lyx @@ -1,7 +1,9 @@ -#LyX 2.0 created this file. For more info see http://www.lyx.org/ -\lyxformat 413 +#LyX 2.3 created this file. For more info see http://www.lyx.org/ +\lyxformat 544 \begin_document \begin_header +\save_transient_properties true +\origin unavailable \textclass article \use_default_options true \maintain_unincluded_children false @@ -9,16 +11,18 @@ \language_package default \inputencoding auto \fontencoding global -\font_roman default -\font_sans default -\font_typewriter default +\font_roman "default" "default" +\font_sans "default" "default" +\font_typewriter "default" "default" +\font_math "auto" "auto" \font_default_family default \use_non_tex_fonts false \font_sc false \font_osf false -\font_sf_scale 100 -\font_tt_scale 100 - +\font_sf_scale 100 100 +\font_tt_scale 100 100 +\use_microtype false +\use_dash_ligatures true \graphics default \default_output_format default \output_sync 0 @@ -29,16 +33,26 @@ \use_hyperref false \papersize default \use_geometry true -\use_amsmath 1 -\use_esint 1 -\use_mhchem 1 -\use_mathdots 1 +\use_package amsmath 1 +\use_package amssymb 1 +\use_package cancel 1 +\use_package esint 1 +\use_package mathdots 1 +\use_package mathtools 1 +\use_package mhchem 1 +\use_package stackrel 1 +\use_package stmaryrd 1 +\use_package undertilde 1 \cite_engine basic +\cite_engine_type default +\biblio_style plain \use_bibtopic false \use_indices false \paperorientation portrait \suppress_date false +\justification true \use_refstyle 1 +\use_minted 0 \index Index \shortcut idx \color #008000 @@ -51,7 +65,10 @@ \tocdepth 3 \paragraph_separation indent \paragraph_indentation default -\quotes_language english +\is_math_indent 0 +\math_numbering_side default +\quotes_style english +\dynamic_quotes 0 \papercolumns 1 \papersides 1 \paperpagestyle default @@ -69,7 +86,7 @@ The new IMU Factor \end_layout \begin_layout Author -Frank Dellaert +Frank Dellaert & Varun Agrawal \end_layout \begin_layout Standard @@ -244,7 +261,7 @@ X(t)=\left\{ R_{0},P_{0}+V_{0}t,V_{0}\right\} then the differential equation describing the trajectory is \begin_inset Formula \[ -\dot{X}(t)=\left[0_{3x3},V_{0},0_{3x1}\right],\,\,\,\,\, X(0)=\left\{ R_{0},P_{0},V_{0}\right\} +\dot{X}(t)=\left[0_{3x3},V_{0},0_{3x1}\right],\,\,\,\,\,X(0)=\left\{ R_{0},P_{0},V_{0}\right\} \] \end_inset @@ -592,6 +609,7 @@ Lie Group Methods \begin_inset CommandInset citation LatexCommand cite key "Iserles00an" +literal "true" \end_inset @@ -602,7 +620,7 @@ key "Iserles00an" , \begin_inset Formula \begin{equation} -\dot{R}(t)=F(R,t),\,\,\,\, R(0)=R_{0}\label{eq:diffSo3} +\dot{R}(t)=F(R,t),\,\,\,\,R(0)=R_{0}\label{eq:diffSo3} \end{equation} \end_inset @@ -947,8 +965,8 @@ Or, as another way to state this, if we solve the differential equations \begin_inset Formula \begin{eqnarray*} \dot{\theta}(t) & = & H(\theta)^{-1}\,\omega^{b}(t)\\ -\dot{p}(t) & = & R_{0}^{T}\, V_{0}+v(t)\\ -\dot{v}(t) & = & R_{0}^{T}\, g+R_{b}^{0}(t)a^{b}(t) +\dot{p}(t) & = & R_{0}^{T}\,V_{0}+v(t)\\ +\dot{v}(t) & = & R_{0}^{T}\,g+R_{b}^{0}(t)a^{b}(t) \end{eqnarray*} \end_inset @@ -1015,7 +1033,7 @@ v(t)=v_{g}(t)+v_{a}(t) evolving as \begin_inset Formula \begin{eqnarray*} -\dot{v}_{g}(t) & = & R_{i}^{T}\, g\\ +\dot{v}_{g}(t) & = & R_{i}^{T}\,g\\ \dot{v}_{a}(t) & = & R_{b}^{i}(t)a^{b}(t) \end{eqnarray*} @@ -1041,7 +1059,7 @@ p(t)=p_{i}(t)+p_{g}(t)+p_{v}(t) evolving as \begin_inset Formula \begin{eqnarray*} -\dot{p}_{i}(t) & = & R_{i}^{T}\, V_{i}\\ +\dot{p}_{i}(t) & = & R_{i}^{T}\,V_{i}\\ \dot{p}_{g}(t) & = & v_{g}(t)=R_{i}^{T}gt\\ \dot{p}_{v}(t) & = & v_{a}(t) \end{eqnarray*} @@ -1096,7 +1114,7 @@ Predict the NavState from \begin_inset Formula \[ -X_{j}=\mathcal{R}_{X_{i}}(\zeta(t_{ij}))=\left\{ \Phi_{R_{0}}\left(\theta(t_{ij})\right),P_{i}+V_{i}t_{ij}+\frac{gt_{ij}^{2}}{2}+R_{i}\, p_{v}(t_{ij}),V_{i}+gt_{ij}+R_{i}\, v_{a}(t_{ij})\right\} +X_{j}=\mathcal{R}_{X_{i}}(\zeta(t_{ij}))=\left\{ \Phi_{R_{0}}\left(\theta(t_{ij})\right),P_{i}+V_{i}t_{ij}+\frac{gt_{ij}^{2}}{2}+R_{i}\,p_{v}(t_{ij}),V_{i}+gt_{ij}+R_{i}\,v_{a}(t_{ij})\right\} \] \end_inset @@ -1372,7 +1390,7 @@ B_{k}=\left[\begin{array}{c} 0_{3\times3}\\ R_{k}\frac{\Delta_{t}}{2}^{2}\\ R_{k}\Delta_{t} -\end{array}\right],\,\,\,\, C_{k}=\left[\begin{array}{c} +\end{array}\right],\,\,\,\,C_{k}=\left[\begin{array}{c} H(\theta_{k})^{-1}\Delta_{t}\\ 0_{3\times3}\\ 0_{3\times3} @@ -1382,6 +1400,99 @@ H(\theta_{k})^{-1}\Delta_{t}\\ \end_inset +\end_layout + +\begin_layout Subsubsection* +Combined IMU Factor +\end_layout + +\begin_layout Standard +We can similarly account for bias drift over time, as is commonly seen in + commercial grade IMUs. + This is accomplished via the +\emph on +CombinedImuFactor +\emph default + which is a 6-way factor between the previous +\emph on +pose/velocity/bias +\emph default + and the +\emph on +pose/velocity/bias +\emph default + at the next timestep. + +\end_layout + +\begin_layout Standard +We expand the state vector as +\begin_inset Formula $\zeta_{k}=[\theta_{k},p_{k},v_{k},a_{k}^{b}, \omega_{k}^{b}]$ +\end_inset + +. + For the jacobian +\begin_inset Formula $F_{k}$ +\end_inset + + of +\begin_inset Formula $f$ +\end_inset + + wrpt this new +\begin_inset Formula $\zeta$ +\end_inset + +, we get a +\begin_inset Formula $15\times15$ +\end_inset + + matrix. + The top-left +\begin_inset Formula $9\times9$ +\end_inset + + is the same as +\begin_inset Formula $A_{k}$ +\end_inset + +, thus we only have the jacobians wrpt the biases left to account for. +\end_layout + +\begin_layout Standard +Conveniently, the jacobians of the pose and velocity wrpt the biases are + already computed in the +\emph on +ImuFactor +\emph default +derivation as matrices +\begin_inset Formula $B_{k}$ +\end_inset + + and +\begin_inset Formula $C_{k}$ +\end_inset + +, while they are identity matrices wrpt the biases themselves. + Thus, we can easily plug-in the values from the previous section to give + us the final result +\end_layout + +\begin_layout Standard +\begin_inset Formula +\[ +F_{k}=\left[\begin{array}{ccccc} +I_{3\times3}-\frac{\Delta_{t}}{2}\Skew{\omega_{k}^{b}} & & & & H(\theta_{k})^{-1}\Delta_{t}\\ +R_{k}\Skew{-a_{k}^{b}}H(\theta_{k})\frac{\Delta_{t}}{2}^{2} & I_{3\times3} & I_{3\times3}\Delta_{t} & R_{k}\frac{\Delta_{t}}{2}^{2}\\ +R_{k}\Skew{-a_{k}^{b}}H(\theta_{k})\Delta_{t} & & I_{3\times3} & R_{k}\Delta_{t}\\ + & & & I_{3\times3}\\ + & & & & I_{3\times3} +\end{array}\right] +\] + +\end_inset + + \end_layout \begin_layout Standard diff --git a/doc/ImuFactor.pdf b/doc/ImuFactor.pdf index 0b13c1f5948de38aa6454732ca20367cc630c62c..37badae9cc979302341b1dbac23e03b5be7445d9 100644 GIT binary patch delta 155716 zcmZs?Q*b71(6t-ewv8t?C$>59#J2Iowr$(CZQIVo6DRxq{#}3VgKu};Ro%z;(Y1Q5 zPLD>Y*++~ggJ5N0CP`{opaC+*&d5NppakDOV)!OP$jP~X$4&C)?@yeI^NYp6&CUXh zObqshuS>e%EBh+5*!5p_Ri0m#AP+X0sg!A*uE3M^5v@6XlBs8R z!iV=Nv)%48!H2~pVf+Y2xp+&C9buu=BaMGMPov^lC9%M#H1cSSgN`zAHP*`Tp0azD zw$VYn#MtTlFTS!Z_AgMV1#tv8Q#%u97bjCA+y9yD|5(AXu#hm5{LjG8562{DYG>|Z zLBht$!bb96CABP20B`WE?YG4|sJiKOAToI$L*p6-(pUm8M2GITLi zy19p~@o#a^17F{J`YeB8)o;TCH52I{27v?Rz^Aq!l(5W`VYr)n`nc~rdU94>{|pPm{DWx;!1n z!#J?s*Wqs~Lokk|5i839T7QJyAsgsugl{qmhRZ)~YG9GGb%WzBu8p-K!N*c*@cz9p zmN2A805es=UfGk(udJ5xuUY8AvbPJ*@e=XitFFhO&;YJ_9&3~VWExMj6=0xwiQ1DO18Ld_F`Dpcu*C}CKuyBV)a z-AAi>cDj(0!=*TeCw*QE0cL+U@f?cjAHAwbuc3>&!C4|q1#`ZlixbrpXhuE+Yh2`{G`Zm<@9Zc$J zf$p!PEKnb3x;S7PHd~xr-*6EKy=Z?cy>x7SJitR#GA(G2%Flq32?{+8*orpt+(V9c1c>f)Zw$fSoRmsI|;8;Domc4}(!l0+PhheE|RbRp^4? zHh>`MSKF&m6JK!pp+OfjC&`@g*bV45c$>CuKMX2DD=#)$&~(GCTgp%QW1G4_byE0^ zTMuNmE3_IWP3^YHM`0}>OHbtyH%aVrLB&rB4?zAqs)OZ%w!TQ%8GaHyI2{@q7>F$o zf8QyAY56iz3+K49&>XOHwN?1g88nEL2eDS*VUkC{&&l1!O~N3Ti$jalKm_*&zj+5#RE1iwb*^dBx`fgU2*y^T#3#uOM!sQS6L`{c zfNU)C|4v1$CsB+Iz=fbA4T3{^w&VDfX^3+9mN??Uf%LWxqf)Q~Q@4Ew40>c! z7g-Fb@pW`YubzBAPjWz$vkz# z*t_kiCt#ZyPx1izgSqnqGnI;VWR+g}IEU(hp1Qt497feJU=!=k?=hhWv-`{`(N zs)Xt858`EFIy^G9_7!FRku;=lZ)(|^5{R3WA08{gbiUZ0taKo=%nP{}UvZv;<|qaz*aLO6N=1C?>QTi}NUv2?wU zLbQ}_0^!G8M3KLRJU)q>ZuM}}mDxEdi6)gD01Qu@wM((eqD~#HVl@BaU!ZfFW4nLm zEM2tx1iJEi;_TUP?c>^klXGUn#Kx>)cowtAijws#-f&5WE>s(5Y_Ju4YjJE7dV=ic z56`G0>3=RCZ%nFzZMo7)`Vv8!)r**n-~lyf4g*F*{}{V@2}4#nqz7q?c>3lnqG=O* zr4Awper(Xm2b~k=W{hFjqC8Fj*avXq8F*lVB_rLxBrq7Uo0RVB%ncR${#+BUfhFQv z_A3haia4_TyuDdB58E5OV@*CvFQzG26;BZ79d0x3xXsBe=L$!qiCo_n}$ZXIn-oe zKRc-YIH8 zNr3P(xW&ju9yF1$yHNz~EI5u{Sl#?l^B9PG=@uPCHCLrII^9>ukX{>~Q=^_dGA$I) zry{atnlkmykhn3m3s!}s!6sNn?c}hSN3dFuihVx^M&pdAa;F{SRQSX`#*JAePo(rI zR6}oOPc3QfKc2jchw&bQR&`Mz-(ziyX4;4kVSyzqc7_t3SY6kwMwxi+KK5@!+I!Sj z92^wL*sKQt45AU!{R1fBAUt$jrQN~bjUUnRDa)Rv1s8Gs)bfVEx(gy^4l^AH=^Lax z1hjO3(XDr+0nnVzGG@clyif6PEQ7c|6iYJU;%MZOs*11!$ceccPz>@DB2axL9juEA z8(*2q<$XzBLy#<@Aa9E)c)(u0lgQu zZ2P+wiQC*r&pfMOk7%yO{Qlj~c?5C6^jwlHL4FB26vIHxH|m%h8cq>_{5(2mv|U4d z1V3+%d`o>T%vs7UXO0~v$ls1clK>{{Q8&a!mbCOrl!S46bzsS%#2bw|X={aZi0=%v z84a^f;*$qDawSQSrHn&sX7@lIe|GsujpI3 z9V!U}ZwmSgAx|lJZ&3-X{bBch4&$Et{*}((oM0$f(OH^OGzM~^$*zx%nD2~z z1a@}WMV7i-!BrJ$gX%DNx@MXwagr^4gmdJ>zCb8xh%+bN_ar$mkdIoTxfBqLMPh}7{w`vqbd6WUb~dNj zR?oAqK7%z%5ob6NxTLV_0bra0NWOGwp9o&!*~5S_#CqF-G4+JGh`+-m$v)KBQ%{qC z)pkXp32BGfC|ZR1urBRHF3q(MXq)>b%y)%^Xqnby*3$*A;PZN{Cn@KxxsZv0GW6HP zHT`k`O5~YIOiG7->vftyqAohEas)H`gZCLURu$WPdqRKlG(hxsICbgHK-FckAJbo;*>ERwUws?UQ-tkiyilL30j0GVjWQJGB)uZq4-+v#C_Ej;^ z>(~xo0|xeZjCzAv=Tn>0c5 z5_NrLP#q4>H?uiA{Zh%U*&;z&vJD>FA*8D6gk*D-_Dnx!-S^BLevk+9hyx$P;({z+ z(gKTOCW3n|&MX45&mn6Q)dIxj@f-(*FCrS}${Z=j;LGYN)fMs<2$e8IDmwNEP*k1$ zRl|#f`Mw#2FSRe9W?s(rKC#!+w#fgttYPK&-?E04o0H}L$hw{1I&nv>n0|Q%2fY*L znFn8qWXSSa;*C=|JoT{^`=jH(%3qA|Y9pWw0eaZe5u@vwpRw@B>Yzy#e-9jeQ3KQMAHc`?jX>4HY#7zg#=0rnx4dpZ)sD{q;#}sfZEsdnb$1x^p*kq#9_$njk=9NjpR70AH5kJAWgf~c8uU02 zrEH$h3q+S#NcK;}88GirX6h%BGbKLTHc_^%Iz+^D!oGd5z?6k;V$c$IodxkSINg_M zhYJ97C{`%({_!aLg=Gp(?@rG=9GJBaS4~)(G}8|@YC%vE!3-tI;$@kWk7R2`K)^J4 z*^;Nks43QzYmq&sY{#9WR#P>M8i_0?7LotQ1V~CLdDX=BD?3to`ouvQY6%QMMYRO1;`_s1Q0lNU6N6KY?qzh#R)6$lk6xhpSvb8zVLN z0gNcUA33mzlmd8{8d>;d`KC3uQ$k_gF<>I=SF)UY2SqA=yaiewr9HgM8RDAeHK(^J z3+^N-3d@^4@iOmE1N2dGb)B8Ed-$!#UMl3`KEBDE&bFVUGM1gISgtAXft6|7bn8gdD3?|yzj$+C@efhVC(Zp&HHcxcR}Ze^|6U)Vqj0eiuW zD5@`th&yw5M0_8%rv19!&SqYS6p$EJW>2E}h@^y&6ee}{K9cIz;-w9vNf#xIl4el? zuXuV%Mtl7eD8lgmZecRlkP_5M&azfh;#HOpch=-wsFc`{c|xr(pj8h1y%U_u9A`|! z5x+vQcmbhT?O1t&|H8C3fPYE#1mZX2Y_t4@9|!d>duklk;?j=sCy->Uy7~6i8;;cb zJ9u|e%F8)tNU4LiT0?0hfy8oOBl!^P#%+WCH%&bl>h2O0Ks*F`LAq1%B^fT(;ilvl ze#;QI(#m_S{QOO%4Cl^J<*WFBvWDjef9|8L8D@-=ymp4dgSE)y@8r8?1Z>jTbA`Z- z71x#S0mL!gHHP`1FY-KV<&#L+fK%$l;wsCzCUm0kRwYr&z{y{qVX zGK*)y(?Wuh(Pf9|2)8!ZFWR@|14Ystg9#2FWR=3pI5_Bnf*l3@MX9xM1M&`_I#DFr zkJ1_&hj(}MWu~$n5BFmhfg)b54gaby)e;Wlk7z-JEZDoI$BN@Dq{96xie-dWlO*zv zjjA)^%`2ia+7*IPOs;Cb^D11?8tZR?)u(COxYy%2(~M-Hzf1mL`K(+1J0U$aRv7Fh z$>nk6u_I|V+=obGi^lO>IDuHHpQk0F&ah|wX(tMURWm5aRx)LPPnInW% zcX~)Ckk6_#?sgE(Ks0_$@CGGB&_CjLp5txeG)n?_h<@#&9KH%k-s``|>F-GjZ7uVH$hc=!z@Rd4~nq$iY2#AGu1XK}y zh6jr%c;>25$$%A9Hha};+J2r+!LxGJ%&^($DbTa?1}ZBKWP>fAJ|=;Bp`mKW zKfXm@6lOIS#%K;IflT}%T1$##tBahP!C7ah)@>2#;=>PD9Wc2a3L}YaYMEqnBNmvho8R^r26Jy9yWhqEjj)k+EBl_F+GWIo6n6_3MVO{0D{h89mR?J zX2v6Pe?XXwP3>-TIUoa=E!nxAWrGdyx&hw?o=hCWqbR2<7vO8?iOxejv6cncx|f9< zw>FbEtG`zHXz!$Ws%WDLCtH`jv*-=xB$iQr((x6TGi+3T?LV{)GoZHTd43nNtdT<@u7A*8;bhkI*87EKpS0_Teb zw$9x5z z1>+Wqc$x4C4DN>2r=*&1Ae#?}8|lqN`}oXg0J22M)qk48SeH5toi;~283@>)i(t{6Uro=D+2D`;0pRk}UZ{WbQtuN+H&p@pZ9{g&&;&5+Wp>S*p+@ zJi6C{vq*a=6{Nll$^vzt#vb*DiEG4zR@HOttY4h(Z#G}DRa_v~_G%(wKHRJRL!w9T z$#1$DW)T_I!-g3B^BPxr5_Yy+(G@?T9YvxFbI_Di9BGSVq1(CoIT5|A3qllNuyUt_ z1O9~ukTAn$TYjwUmdn#)S0&HSQN11_EOk1@OPzPrmx0u=xhODh1~9eot)D< z#JDhfER~1rGVUFsIA!mmPDQo1DR{$ZZEW(ia6B$YGVOaSf9TbF5+-DFyOzYMnarA~C z$ct}_+N69gV)*}S7I1O=zf^sqtK>&sK>*Tp??sR+pxN8Q}Tv}&))l)|Ue@*-S3W$uUYuQNriMiWU zT$y%4Wgm5V`TYEn=R34~mvdn=t3t;1SN~=Rb$H(EuO}%}Tb5DOJ zLppMEr%y)vUGxI@X{~qDTKiULp_xM1VPlBUlL?=2kUT11k#vif9zh!3r~Nk?EE`3_G>j%eZnNSim@M0bVs5Gvcf3p@>?)#9%4G5oF&;Tz zHEB@MKheA~GgVv$)gdRlxt*#ryA?e;ulbRgb(C{ZndGlN9#`ek#p z6jsCTh0A=C!eH2}DAdBZb6{^+lk!bF>ix~iF0oH{hL+Xz35UHv1&Tg9-5IFCoO8gh zz=?uv6pF8~MBZfvl^g%%b%T;S%Rb?9$u)xzRzw*|&qWvG6agX+0uFt2_f@&IWCPgO zs|d_smu@+`0J_s)kRUTG<->E56_RX|k?364pjl zz`e0^4Sc@$(W_Le%e$;f_?ctHYb}b)4%3?v(FpV}4zPjR{%|`Bt>peco>lV|TWCzv zqBVxM70= zRgND_uXOn`TUx6V?R)%F!n<~m?d(sJi!C*NfB0>i>jHaj*V1umWsz5iGMTV8%O76l zs4HVAcA$pGMx3|R`>+MN+#`W|CS_D7h~a+40ic}bRE6pXfMpwU`X*{4529Sm{zYFA zoyk0S?70<`p_Z*Aw_wb-Easo=7X169W@~}d9xoWj&7FQ*rKL+x+?_Il#iqDDPiisl z#(XZBoUjDuL~;W9AJtaUTvby0h;lx&gj`}!H;~&HTtr+Qi_T=e#~T4_r7#;ccQLMn z_RxjHNr=WkGixhhLkkQ-U#kn%Q=Cd_^!z6n>y^LL0h~T8;xzxS2Qpu-{-9z=N*ryO z70lNUfnJntZX+M3(Z=(ysainWH7jBpnLimuJ6DRgUvwg*3*X2Z8MF|_Rikk=y~MK7 zG;qONf^EGwiOadLJL4!S6}j;|y*p?4<6wb%mw2Ho3jm*tOtb4PIb?}ZtHeDzz*)pl zTH^**$ijJ319Da$&H#z-SkG*%3`cc9K?oKa``cKAgb?C@fp4~uwRosa*;Kx<>3PXA z`!4}=ya0S!-Y!-)tjyezZm1ezQ9|^QR+KOcYy~e2@>>m={n) z%nWdDMapT;Bf)|yN&9eREW75TNr-M53%Z-@?e+Wj!FCN*8{`^51~vo$2{(o?1vpZghDa6(*nsE+`rX$WP0FiCEW`khL0%LaV(!)mC^YK z{zVsn)l9jhb9khbGQ^G~llZ3^LTAI=bbM4@+GVYo691*akDH`hTcXCc0lI^PgB0+{ z9fO_z4KPhN8LG~b7aR;{ZsG(zPcIl&`Z63SkQKiFdWFFsk(2<5$1{O%2SYhNMMnnB z!4rGK*k z_U_cmc2x(=bhoI}_edW*V~=a;8Vz>%{guC{)ZG`+_`51^#fG$-518*?O?Nxj-={bI z)0pq?%=$J_VTVGT0nDlC6m?_9%A0{!-M}Nxx|!?RB+Z|d*V_?~aurs-E83tkexB`k zV?Hz}7v)*aIKfH}#yNVvpA*+P;|y_;Sy_q0q%!iX^j%$S@mZ_AkGV8^lD*$m|D&E| z)B^SG6vpv;z1{<{HekBHhjDcNW3m2ARYy212Dog%m13a$3^dc*Eo}Db&nIH#giJqc z_eHN-sb|8jFkoiKO3^XD?{y_~lXY-?HlA-Ed2fKK`jxEU*J%kaBz{3$AJxdVW9wc6 znf~VWHQ>tY)o+zrLLCkSp47%B&g0lD1DIaGA3MXbB2NDMjGf{v_}Y39HJGkdDFK+Q?200^zfRvnD*ixhkI{6-(m-i{khc)|dEO&r3QOaJM37yGulqQ=n{ zmr({e_!w7zsC0ImXHQ+(GMArLY=O7yT&KQAsM(^9w|UpJ7}cun({kU<^(klv5pXn> zfB0vq@AJZX?fS;wE6RhpfX~mZQM1fF+s|_P3V9VdGLBW>-oG^}|_pTe0ZYw%~!D#QBowc7_bb7NA~%nD!dbun$j7 zTQQ$d{j3ie8m5K3&DARA!)cn0K+xK=Papg6PTd@YH1+45)C8FDcq*uE8v^` zk1gY*_%ul7Rk+a7A(R2)kUmw&rnM0M45G+pwG?60tm(;v%C2u4oLG9slcn)CyOCcB z5G%vy7it_rEQ;O|i<4wgM=PXLh9`avKh}MkW(B=_ipug{ z|NT7293=mU7&t_aEHfjl{E~zSZ*;Wks}Vlq`j#atJGw78zr_6LpZj{w*2AM%5%sjM@{U|17I>g< zt`ZW1U2~I${?AQ&Jx<|M<8xJ{j6kX!#Lq~@JY4mY3qgdM$e6Tn;-lORc;sg@+2xe8 zhC?%;^C6yg=O|*M1v)&crk$ezn-nL_St=Ix_j>ZK2|X)pl#lq-5p@Dmc+k$^1F_u# zw>6NP+3ncxnn;-}eaK_(O!;ivKluth=Mg3S6Ytrcm6G^As}lB$tR-WWX`|Wit?%WZ zg6qH6C0_4OvPZj%1NVnG;P^Cxg9ZVQ&u_j7YJQEJNpd2394?5#fU$R50_85$;bM1_@b9$!{={!ISKrhOEp0VFaOOG=Y?TuAJJ-^jFyHoNAq)m}4+?j_Gg zl$oiczyjjo`J1DxEkZ50pYeY9I?i6EHe$)a`2Y>h@)W)tcza1E;KJK>&h3^5NxWlx z?tG|T9sfJLkKr}UL$P4k=BTG)(CpUI;Tp^%D7Az0HX>*6Q~|awr|RBvgXDv~kP(~H z-hgR(yHP$mDt06}QZ4WKE?hn+`us?^%3-+oRGiu$p=R$Y!Bp=mqVXP6>W;Rja-g>( z#Ak01{j8(I#>l}eP?Rl*P51(m?aa}0!S~L0&~+AJf;He9CA{&as9FT^^PsWfzt~I{ zT^8R<6!c3ClZ(GuL&V8Qd3=B9S;=T)JD$tl1wteP=Ty6>_~NyGYKG+35`f1eH55Nj ztn8qhrZ3zJJMn3DBp51;s^mr8u)G)Cnm8q5K7j|1i}%(*#8(cYVtL|MW!QvSg{rA` z4&~G(MT9B~JAPK?fu>s73_&~#QXh(5WzZmhaWgcRKdgWC-zlag$FB3~Qy>U&#rtMb zw#fe{YgsvX{*PI7qpR(FG>YoCR%f`|AIY8jAvKBIKo8hzaYU#ebY^AZEynk2P1Bi6xBYG4{$73@ww&nl(+TGG zS>$t)$8ZD0PCnb&o%`|~;%l7Nv4a&2#GkvVs&4F&YHVqy&))W=!roZi`#=^AbCSen z=j+Vp;2)hJ1BT&FMcSBpmixbKqk{Q18nj*fopIMP1OtWx(^C()d}{sSNfYy$JX-*Q z?{9~l0tV62#pz%Q1kkt4BSyc)yRw8uF7&7ajE#YgVmvi`>J3IXtoZ?5Mg$wYZ;Lue#MiIpFql@KeE`Io-a z1TGvC3nckG`;@h^qD=2*}o` zfK=dsQU@f=i-7DteqGcPK)1B2L$A5buo|nNB(gD-@Z;d>=bs)9R03{@9y0j9-$Ci| zCW|kTP6I}uOVU-?nSs%c4?}p@q0~wse3t5Lsc8q5=0v(h99ekNrA@iJqe0SZ5U9Hx zZWV2(vsyzdlJtW03nTA<(VBc1dM5^)M;#JpQ3OijJ(j-BZyQ($ z?T@(M_POqvqVvOZluaeH;d;BVB*%a_FP?DPU8JXn4{Cz% zhhR)l9Zfvrk}O5ulC?z~G}{zAs|v`TwO-Q0g}@l1q3l7!z3@V<&&)|7?Hm?micC(J za|kMPd-WERz|{(n7^#ES?Xi%j7yzPn&=sd#j6aW+>t-x|oY0}BSydZuWW-OR0P0Ch z&V<34UnPe>(fYLmy*@sY+54ejIV_*wkNV9I8tdL~ZY{+)qI_$aA~v_HYEf_C)w3Q4 z`nViDRUYu;&wO=rRWgo9HQBhQs}C zUf$^9D^P|!7eNh*E@@Ay?E9!}h-Lu-elA!PujCzyF7;4yLmJqx?qT3}&{7isMYvdn z2k;q2e6}_d9D#GACx>b2Mj%NGu37Ng8~a~~SO-ZO?!Em&O~*$IuJ|UmzN6PqfamTR zIuc?ba`HQj0m=gP9h=_IBPmUZ-yzj7$PdPRBxdN;)7=IWt_CCCfSLs6JFXhFvXO`u6&CR^nw2wDcaf4pfs#ud&aM{QtSVOo zCeTw#sexsG50un_xHph=$d(JHx64wf0Bx9Q6LCKw$nq?WH(&Z**5J1EUxAG*{!yc# znrSB9RL$U?Hz0HGqQI0>iOVw%dCXP~^Tm!{Gq{ ze|xPvy4703NWs*^RTNO)=L89>%TZcM^4A4~4Yw9?i!u9UFYp%ym@uYkxONgI&cU-M zo)#70aK=gPmWaV*c6`RLz+o3#XUxgze8J*8O_^N2I=6$PhO#C_aFon3zrH8l{s=0S zyMN*G#n>l<#WOmnxXoK&tL@&^B)5kcFO2akSD%+QF0kH;Js30W1>#^Bez~d#zM%5z z@1Bv|k<)1B5ikfmGThU35XFdG=|AhSZp#=+Cidbnf5bPlQ4z)@8YLW$6yjWX#dBVM z*u+D-mGKvm>sK^<@pWht`miUnh(X;grzL8(pYx!xqRQ_v`hh*KGy5UE?*YDPk5=8+ zuvBR?>Fy`wB5D>o*z`eDo7b=#WAZ#nu(=&=C5$sA3ShC2=;1T$-7VCEJNR2yz^4zm zG_n=Ra};YlgB8g~x8-6B&d(Xj4f28(&4T|Js0H-&2dST-98E)3S?Lxirl-YC)7a`?Q(tvyuHvT3pZWjOtasd#lhpha8ljVMU?Gn2mytIW6*RyZFM`>rv#}oaR(0vI3yA< z%*77{eoj{^j9-~!K{z6U?V@>cxz#ZU(ck}ce;)0OM;jtk!t@Ed5}th$=+?|tNHnku z+y?8Qbw|owB7mD6a4t$+wNu3s%fQ(zO%%f>EOIF${zqa(3NgoQiZKdyom6Z`H`6eX zJiw#eqZ7Juc>UZ!oy zH_<21AlVB~W>9G#W=dPgYtRNkY%~(HB%;xaL9%~rGMDZSt?pl!4-=)X%COR0KuIDI zOugOo-q}&qKx-`|?o)7GNz)6Y8)`4Dn1B{;u77UEh<#`ynOHy0i8)JXTwm8Xv9voJ zeVaT_^3<&Y9}au|SXjf_n+2w^)YqLGsd z&+}QY1a!X9JOovfqINkw!6qnQCekzUM=R7aFgNRN7=p_crjX__>024+JAcoZvVb#- zSe^Y|Z%Zyz^$NAy3OY&0&|M>bcWZlJHwNE_Srq{{y?k&R1{3c&0?YmFwG@L!IPL9j zqV0=>9b5l~g49pxEgZ^+2PR7EU8|$E3A37^n?lMf0b(($1F*#xMOG}URe35o6W=^` z_9ob@osl&Fjz`-AIu92W*NG<5I3Oq-th!WI4~83kccCL5^TN(?vC`%V?347K)_aVl z_v00{*yJ%lcFHzk2NKH$M!b^3V5Ylcy0X-XaY_S*J!C4M_Ra}UW@r;?qF4Vt$JGt{ zJw=DOi}uSlzEBO&qT2~}hCFpWTN#43zyD}vj)eRuoK$n&6O#t*Wc5gK4g@{EfCGeZ zY(RjHB2KjCXU%R{7|0=}dTL4_#`FbS-J}3h!}eSo>gg-)+@G_Y_j4%lf4(ab)Dt!* zN!YP!>+v&fNT&L{@p(_Gw!?aCs?t34oH8^?AIv@=$BeoapITCQJ7~MDR`tl$H@eUj z)2$&%esq)&5~rJFb%Ln)ft1;a6b2?0J%zIio2i;x@}@a;wvPqhL)FE@9q1?`Xss00}@Z-9J>6;SoMo_2zSdygd>`YWtoB`(E}Ihf1iJeuGPW z3-=gqD32iX=~Z^1!2J|S?9#6|4YKp0_NTJK>QDJAV3n4kN+{_=*UW?QrvbNxzu_Ev zW!^3NdVS2BmSW2OSJ@Z@76P@4dukuC%~W-OTg;% zhi~w&$;wPj2>Dd^l^2i5g{T$|x&K{@IBOvSH#<%>SzyACZv+3$uEQrJU) zja~fefNf-F{Q+>EJbn6qr{&l<|9{eQT-==ha|86uO$q$Z+Kbz2|DV8IK`Rq0T0^%% z>$xcQx_DRB3Jb;1*Lq~est2*K)gW|u)90jFLaz&ItD|M4EUYuM)*x7r|kSNgG z_xbF$LJmd(3O`Y|PqtY&JwpsHg1L0!nZYv!>jk}X$;na3pf}GXdV$?QaaZ>THV zNu43G9BX||uPZzhMHiqR{ZQl=RZVJy$T?jk2Lx?{3=eVekO&(t{O<)(?v14$OQCe2O!dc=#A=gK~NrvLf z;@(AUCo<7h6}io?xUXpv*TKw(qbK?UeMv;6$^3t`sFt#-H0>Q&gKqt#m=F7V6zz`X z!3r{DV2QCOrm75TdtLh(OfbL+^XX90+UK&Y|MEfp>etiep&Pd3cn?~I^S1K~m#{bYM$MY>4~+;4zud~@p7jYXWD=9{jl$v!nH$5I=8gXX)P=ZafiLIH$j+%E1v#`ib)j1>2Cv(T$b4EK_n_Lj z0h1?v%gL9{rLX79kjj@XXCVWnEAM>Doux>u1*yo=V6}&q5-=3-S4&PbM^(FJ_f*4y z3p_R6@}c+^sb}GZIJuJV-E0Sg!{+vFqqD!JPW*1uNyf-rPUbsZr4 zC(gCi6+Q+YyP@X^B|=R;QK5+k7(_xP1~cP@_y&t?!&(`=jb5qtYF%SkA>PU1Ci&SH z{O+i1o-bhIGg0QX;D$s2o(_-J$EcwA!HO1!=BNt6#FK(PwN7(kHaoix7KTR0Qw+Xb z;nRELfw?B*uK8ui(p&P%fG;WfirNy|l769~w}h zP^lwI{?5lIA0^Vk5~bI`Z@*pl&wqEMyrZH4fg?~R_m5Xm!@VX39)+)`f#V&`);fPK zqghw!GGzL%6^QBAwv$O>Y90@%4{;CT4dsfH3;0l&R|}{^B7?!MCP2nv39Q#fL|EAM zsH39}{*4H_!j6xBSrMZM6kgFmPY~`fgQXrVh$Yl+%`a?6EGFo^HD~6euGGCUrteF0 zzddW@*zs&fVK8+CN@p+2xQP&qZyuLd%M1F2!;=RYG+f;MV9W?`_Y1?}@E$=`RIa`~ zR;JICWoZ!pE!!?^`AEZu-z(HTsddu0dB{^{`BNHb!kuXf(Gt;JT14Jq#N5M9?zz=Q z*KH{0Y?|gQp5*5so!W(aJU3kb{dIXh$ynetm`T4j(Fywsgzt?C7d*4`r?aQr3>I^o zw>VmKuy&K^RCc*?JDPy4*0o01n|QCevtTruozND zhR>+V1@JHTK*umElUt=5so7s*Y(vFcZ16~t6(=}qR0MQOLFLge`K)m7^dP&^-jh$l zYNIxo>R^jW;qd}WrAQE_j_b0|FvEcU9O%1)AL#urtTrZS#8AA@YTpTPWlf>gBlAHo zz0QHS`54)QQMR)U(fWoas~MJ8%XwK);N{&vRZCfKVDj&Ei-4>jHG$6O`o{D(AoP7P zNF^fvU=nFp(fF)azTr#LAdy8?v)1ftDo$pnMoRfQPhvWO#4x|au>RSBvsOma(~Vx1 z;$w*b)E>rdK&g7~$=X=gHjrg+I;vKL_5fl$!940)@`(U)i9Zfn4&R!Hr%Z5Swx3QI z1h1(c_?^RKPAG0@lRFr3?pImdM#ow8-j{j;r7l}Juekm+N@QoL_IPA}7fE#?y9KB5 zI=8pO7^(j3!5iT6D5`wseX!{-Pa{#N&{ezBFx+Z6lSk9cy5=ziBVU85EzIA!UKooG*v=Z#G!5RFEdXXy*^N}tvWGn>bl4hyiQKKib= z(^8-JKY2&u9woT76BBh593_GK*riSaV$SBLxa{pxxH}*=6lG=_tHHy%qr7NZr@NbmD$j3_Syx8J{-W62J&E@RmN_9Cv(U%6h>85d{ zu%0QXGj+-%i34hJ#DT$@-S~N!wS&4%BIudxzA**@*=S`yafLChKha3*qeVk0wx`53 z0WOkT8&W*FB0szq4vq(L7B6Wm0C|^BfFwr`Zr}bIm&Y;9C3-Y)gMbx4PRbxT9m7&}HsV>u*3X{fvKh~pY!Y>V%TpnCk>L)cmt z1QKgpPrAFeJrG}7-PR%c%Vv;7OG$sgVvfUPu%D1-_4=O!mXtSx5}7Sxe7k`V50G>O zmxR#V|B^o>Ijp4*!HR_tSTt<#OGQq&Mws#6Hb+#+2%_BK(jVvsK@LFH9Nfnv=G33n zK+`IxC1G2xH#3eOf;4Wo8`81y{2g5j`JM{HTJr|F@$uZi=)O0OXsmM@O@hv*+DHUk zy~Kn2L^(yI7&?|eVmpe;IK@|ah4C#*@5FkCYdHTOCKLbPV|g~7|INv4%bd2%79 zM+U7|^8fxHvd*bF&^GGQv2EM7&5o^(ZFKA>>e#kzb<(jqwr$(iyfsr(-&D=P{SWrR zUUyyV+MM)Q=ZgpTmp$A5JMFLbd_bnNY%=<8)OC;2U&7<6QT3m^{+-B5CLcVz7TICP zcCG8e2gd*WIdvUdU)i$ieS_YfY%5sXohN}&8fQy_ZOfNN-v9b#cm@33>LjQW zr7fWvk2`$fraOT9^9SKOuZEb*XMq4FxQHbYX9E>oVpO%i)vu*rjTUQ=Y`d=lj>}(< zA#L}R=xFT5wSV+?n$Anp&$`kOI%$rlc*G@pYK;1XVk@)VFjD8IH=ea_5C`RuiW^8qsTh@23-B{A^3j$XEuYVq z9^~?<&qi&#RNn4_{Ykd0Lw+z2BX?hZQFhv}+ODBvuU_cxyWYMq%uWD)rvKX>N%IqG zaO{?ixnKHSKb~z`aOo}?52Ad6b3q9`5`+RTK|LgL1KGH;BCKcM`Qk-QmLVy?hI41d zOV&XE8^N@e_GNf9*_wTeqBNuq));DX6kW|hg5k0CEE(N z+vT6(By^jwF_b!ba2p7LnkkOIlKt?Pwr2q_~joB091*nsx;` zsE(XQ(`+S%VyW^cF9WP)EvuMVb~6Y87Sy&k+bq~oVI+e!$4}|MiD`V5NC%$K&h3!A z)UNlPblkeXH|^3w=qNP@9C+!LG;K@xWNfQ{)madI%U6$h7jpiKll&p%0SsRj0>+5d zTTg4^o$Asw9tuG43uy)Jx3=|>zBA}Xd6mr&S8LKF{(C{Sy~?dk;7JgnQ(+Eow~?23 z9~4=%U9D$;|5wU}N`B?Cgrc~xVc)^SivT6-K&C98<6;AIfTe?Zr&D;#+_26y2PFk2 z-iM^wb3B{M&8k5CUI*P znSw=laSOiCUWEu&dE(M3fkz{^ABY00*O>JPJW_+Op-Nbj7g#Pon79cjb^WAAR{Tld z?!?)=j0hm2E0)s6lqf-*=!!4XcZBnp5*$uVymP39%wN%TuqVV4R~L=X5tB|w0?twv=IV6JW7|t0;8x2l~W!WZA5wTJa}dcOI!WsF)aK!{Oy!h#$)0$ZV`!q2tj+LO;UR?jgqKEE z2p_+|FY{GW(^2M#4S(?ESN}LZi3KlN>aHA6muUx>iuMtz#;R`gQUk}?ZoBG;g=+!2 z)-+6W73(g=!E5pHxuJNj$bd@X+3Qo)$SVMw*sf35^7FQ8CL4e-{xq`h}O%ZTZO=@M<;t^jPy)$0Ufa zHRh!;48SvheRE1PTdK7)!@doPYiCq-qtp+(PlHTygB)I8(2n}CpRCfLgWNaJ? z?1ZsK15+b;`49Ew-F#WyJa?sw!>qGM5cEE0afI&LvR zpiDX$UGq|s30ILhC{S#YfzqZ$1^N@<{bxi^!polx0{zB(DiAKOEh$FZ({OvZUbUC%on~1U<}8P0kEpNa+-;MeU5U zu}^WdgwPK(OWxQ3{*={YGFH9p+Y6!M zm_!jgT%_zNsUU?}eHz8%L`j(`SW8yB1d1W-AHhk2fC% zk%mt5HPZ@`gC~uHWEJG4i%ak3h8X6+@0cd1ZA?&&D*I2);Ufj0unEm!l_?EK#d%jX zg9mWAH*GEE-a2F(D_3&=(zsLysBecg+Y6%_mePGftRzJ>iNSd74A~|n3od7*n519d zo%Nr4;kI9m&ma@!_XMqE6=%675=|bsxON^>$y5JVz|S`#33VopG8P*#$zkt`;A>qe zckUjQIGtS+v{(n4F)<2LepPkK9ij+fB*n0w@;Mc2tt6XL-#x)!{moOc9QawiV;3I0 zJRC8N!JI2+7xbHJ8S?7U3iQ1#!c;oq!TiyKB=#*tE>-JlF=KoUhNCtM#wS@FtqE+?ruZi7aD?XX?oHFM8h7o0c>?uybTLjT79shv(@s}_y^vkFs zEBl|~(CRcpl`4@_A7R!JB@QgN1#P=Fv{HhEuVtLrd)wlC${L=O;70m4G@k#WyhOSe?w`Te`JJ;vym4Er5K{ps+P{3a?i1K!Z6XU zyzH*|cnx#`omLRO&D{iE#YjlW9=fHF9fJc<<#ufUQMf$2qx8j%!B=eSq{2rHDsHrW zdW)z>mE=cjV-GRR_#p7fi#(Y~GG`?MY)8!mb=wWSA=Ae~jDaYvJBFnXm@kYks!@2! z-4PEI-c`JTi0lDy`xik*XLSX%#{kP%MhBm?0QUvZtPC5cJqo=mTPCk1U7B?Utw@?v zIq@_+x&W8Z`74TR_~IN#?YI=@O91Lf*Qs_ z*&Q~F0taMc@jswQ00eADxwx4wO^E;j?=!cqBh1mU*1*t(lN<-vZsg*~zZ9~6Vxl+! z#+0u^XUd_;W0A^|ql3QHJ!3k9YV|$u8xw1}4OOSXs*3O1^S*U?8Bj;c*j>#wp+JE5 z{mQXT)p;%$!5ZXZ$aGe#jq?5^Ac`6+Tyu1(Y~r%p0JrV=OCLp5o$BUAysa5~$67|$ zlu*sc%|*RR@5x4WE=0S3UASgfX-{3 zKWBZq)gD+&qer8bb-q7YYcOS-YKo>Qwvq{qy(anS@YD&0aX$w(8EzlCc-rbp-yaB` z=eQ~p1i@80lLzxl#J5#ln(AC;C0l2cl6jB2PnA|S)Dd5{17na=Smy5^Z?zCT*a~BO zH3|P3-#b_M!q}Y0;wDH+{_z@P%Q(wGMQjII(Bm)ZzE{NTkhg&i&ib3 z_GDsvx5icvbL)uAQqXPw^?E|!U`nvlHXnbkQrsqm5NoG?3tq|-&&s7XLPJ1+#N<@j z8wVHi9di_!0JMdRVnC~J2U|rqtv8z$8@Zv#qX$8fB^N`)dGR(DZ1fztkYPfcr<3~* zrniSvvcl%ZS?3;53Pf=z$^45ZB{#Xb=9^ItKXaKf3J=^573-FR1r0YEW;@y;-*IEG zBDku^kE%?`ma3v8xhCyuwE^@x*jYHa%on`0E!XWnk`*&>Lo}Kwq(suUPQ=h zR$0In{n)r^(V+ia&!a??vk8hVb+j~<*#)6z1m1)Ej8nW>5-NdE1raHTQ`*%o6%l)s zs3ima^1OItQeO>zlpSFzpxOnKzn;cNRY7EDizJ;o6-AU+i-rNUtfDQ8@Zm{pUv^V# zc6%KS0}RD}HHnV5tW7Rs$vVnHsgwBidM3?b71k|Ej-A2gHPk|>EJ3ehbC+$<@%^C% zspY;UMJ$9PAAHmEO!}b|6JB~e?-FUsI&?V(>9q|(h=iJ^b0KKtaX6MkUl$h~VzueO z&=?(7Z1{wnT(+FCT{$mb&6e$z_@a)$LG9>C#FnYdN#}>G3 zvyU$l$E*}dq~1xN)No;Jb(EWZl=;U9r{O!+Pv+~f0{aI2TSVd`>MWR>&t0RO%N_{m z1>i!>$NKz^6Ic(>Qb%FJ@jVgVx#9Zol{4%~`58X@u zU5_u;xdm;_(@|%vcy=&^+)=uM&M~u@qH%DoMDZb%EC|x8c9K_?BnA8xHX3U6X9;B2 zU$^LSPypfsiF+XgYml*0O&QnOp0-!+8g^FGD4Om0_2C zs32vhY4GUmi9DBamy&0$XdsDt6X4P3b$73|?9uTrLUBua_Jo=^b7r z^Chk}d+>A4bh5XI`?XE!l4P}~tN)p(nHKwVQ^m}$jGuToq?DR?#J)Og_nnmzBh!HO z2WFt!1W8^f;rb{oojb8*bhOj@aU{tp#*y9082Tu;tZ8B*j5HKRPMl6c2mlFX%zkH& zR(7Ngmu{gSw;zj(T-;MipKEcPV6zstSvs}n)X(c_!q!Vt`>u>Nib6}vob|+n*RN<+ z`r&H<24}^JkCHnf=PzT>SeJ7pO#EB)=N>9|`Jf?`+a1S(=w#9kyeJ6J8;>oT1M#5R z3s-927xqW~9q$;2g)OMJ2&h6km5q{6&5VMJ|L_If!^R-tWE7!IfolBnjEQXsnHrMu zhm#%oQAUya*MGFgSm{ZUhfO6{6gElu`rkNv5^XHU$r~eE60J5r=3E8sR2kKS3Dj8V z6Zd^`Wt85dq~r<3QKBPE`y0LJvu-mu^o$0;a&jgo;xPlC&7T4^i)=l09B@h8f16<%*SCC1m(#`W4p3I564wwaBXIx-JcTeS@Y3d zw+94WKJrTUQO@5Of!FkD$f4D&_U0jtqZ0bNwvb^uh-H6#I1J9caHpr2`xQTm=wCrS4tA3QjLaB__}HE&v8FD3Ir>a z9Bf6KaSejl6Ek|0$w00llJ+$IPCDgT>eWdZdBZ!e^OijMO>p#`TzJklWb;* zPmUm}Aap3$@%&U> z4F4AK;aZx)1TXIMdO)abEkIi9>q*wHodTNKVc=Sz+CdfqSbXB|2V$2*r~{Dx;UNTh zeUn2br3)e)(e;m>o}P|^y1E|+03w$Z>8l{QM(Khg_yS^O{36minEAVK&aVSHkI2wmy?J5a zJ4ZWTj_txl03}$*2NKjzUGZ%FK&CAtZ2kbo6<>bvUo0&*eH52gnKI0*R*1>}<;?+gl~ zTZ8ohSa+>P=GeM0A}?{?#7JktoCDt&p!0d?{Rl6XOl~8=uA(5NJ;@GZgVW}pH-n$w zHP73m-`pABV|U-`Z$0#?H%`uPlNn!5FT_Z$Q2busr?({f$SVUl<)TEPeTUn%Q2D|Z zT8L)gPflOl8lj*7@sQ}+;M8dkG_1Q8h)I&!wutwjRUs~zDQy#9(zvvIQ&oMxp+JyxE z+Y9`nH-I1@=)1z;WH)hBFgpk6d9mxgs#O%Z?&&8|L`Av_5-gu3{LsDV84-51z6ACA z0ssDa;py}~{r0>L0&xeXV>+cEUM(q3AQaN4CI%b_)*8 zn9;^YZiVYjnlTRRGC3wZch^*VH2Hb{SYJ83bo%DUG*8{~JI zX&{RL=dNGD*rUrW{3#-RAob53^NoNTnUr8sAm}<*Fw%gti_%ayOu^B{UIR`5_-HZ< z64YcK;<(wQ@T=80!l1n*$Kj{sga3+HP8y9GXMR~NdS0Nb(`Gd!_;-i(hF5pIC#z{=6^NiyQlCGuD`|UH;>O0w@G|ft=3zq|3snQ4%^-_olpIHl)vCZW0aJRJQ5*f2Q-mhR4ur>5d z3|jNrdJed@MQlF(GG8x`@X58lY5emwdc#k4)&AL$>t_xD!C;9gK3s+qOY zL&9070adQpk4hX0MXSusrF6hlr4V*HUxPJR7jXbmFWSUpIZetsAYR%qLeS;iQnSQ> zT(_*-Qk@D7MSF7`=rlVm$d04V5s0;b=FOMxaFSV#E-U($8LO_;(diQ> zxSc)A`Aq$&1$01ve3s~+AoW0Irvntx|e zY#re#wU-ZF0bvmAXew=cP=$dd&Q!~{d3e1A2fBi=n9@lelSm;Cnf6@|p#9xlcjup) z`HT=5sUasc+^2JS$inb1D>lmg_R&g%Y(;wSRP!8tm;Uh~$+w%+VUP*t`mltcy z!h8{X_0a)C!*y_$i4K;i#_sn-yIKirR8^_I5h!#v_4!{+-udaMu9P3&s5E`EYh;fJem48pyxPxs& z8gL%L0#LKl^CFImbZ)UgI ztA#@u2a2xlD{pXZ9Y?vZa~j1Z<*Y7~z}}79J`T-gADv|I@77%2)(KEj8r%i*OAIF^>?8O0-nB!&~uA*6{@alYBjycRz5o`B@A!%4? z+*mGxk-d_e?$&1X|N6>}nf6U^w_}3z?6OWLm!t*g(r7X9(YQfGFPTpg$fw64Of^-u zCjL?9$4w^!u4j9Z{*`OIG?tvZa`C*TqWM1@q&@cUu`wqq62NcB!|;BPo$7J2Pux&p z$1&$*mOBs`q#5Lz(J(52Q{_n%hZL_@MJsj*G*fVWz#2{XMuVQU#fh zV|X`-v2{d@GwTk zs~ce;YPSqN9sEzl370pYR zKjJ^^dV!Jw4ZNVPfw355XdUg>fBtoZj&7G`{j99KREgWMK_xxb%8k3k0u_a^x@D&7!}lggLD+hO!+zSuxOfJ(RH0HPbB%XOyWR&HZ`Y531;Z zg8s!1tdIkB>A5*B=O#;Na+K#<_)cPL2urMHnT#EeJZ7@gda5ek!#N33cJ2A;950{% zqtuM_Tb<2yhjKAGWa+?yAGnzCEH`D=VB*-OZ#~9lqVkqw#p>AgdUI9T=t#;U==Fqq zPvA=I<9dPwZ-RHYh^I@Z8qK33*1d(IeBf&NznsEy=;%5vGJCla&H3$q%jL1ct7u1h zLZYg1Ulw>K3W435FPLtYoy+dNo#z-J{PiIkD^Mia*JJ3UOvgIg90@V~ec|~y%w|8H zE{)pX62_eLjnD2zHt_crXRLqzJ$sLvcRz2$ZNwjOi%pQ#r^{p+>9r57&V`Wkcw|+E zHE(viU-Mw7_$CLgzWTl=sjLRhe$;~DD5$U2D_V4he^5aA5^fgiBRSZoFH5R{C|8}+ z#A-7s=qA0}tgK^S)bitG>AShjJ;+6JGI1Ncq~2~=O}_!qq(?IP7D-vl9RfL14C}r6 z0H?}d>M5&6qAqe0^@b&si#z2Mq`x>2{448|j(PdP4vnwyi;825Gmkcm45gO>wC>5D z_uOQ?pgZG`(4f*eXJa=_q@UFvVZzhAx8Z{~Jcxw%%0 zbuX5P?uQz)O3BvJFBvAI0eMa3^La1VYJ16VKjm4pC(T#I25GqRe~3^dnactG9mQ(%1aYIH{25N9hudCC;lxN4TwT`)O;{sRM3nmR;}g(WP-0{zjv`3 z1-;z!oX@~=(EmPp4tE@JjuN~z`Ox$=YBNSN2*TNg!(2@95>Wd7OJa1_O-h70`_9CA zaOPn%@FI65c>f$jP?4V~T_qp$nyXagGW*>`pFmf#vHH)Nn%wR;24zkFIT_1fnU+!! z--tvaCTz^ow4-=tH|-J$@J2u;@rH*(e&Up6_po4!Gl#YR`(z3kZSfPO!TMWU0o+D? z94?c$nxHzQs_;aJiEKd0fqQV>GehKPGNQi2sio|i3z7APwZ-867!Yl`*G&6c(IC}@ z1gU^3Z)?+huz- z%Pc~{n<{EDYD2ERw5*wlWdw_vy|E@rwA+*xdSm5eRaSs@LB|nJkhm1MCwmFbNJ|%? zGeG)puj>-9%v~hbgGn~^Rm*R+&_hT+4LQST!%%Yt#?UJ0Q8$O_PHGdqW^mcnZEzk( z*=JnF7WW6oV{qmI?|Kxb-5V=sR{v&3*@b1=(|?#1E#)>U@cgHTzGhRX`#TLut~uMk zeO`hT5ot%1WtC$CtYYMrI7!r7!*@Jg{2=03hw?#_PpW}cb+T>Q(wtxIRB6qq!#|5> zKt~v>OT3l)Y)f+%;6*uDCA-|cmFd@N)tZv8KlKN8{#iT%z0Z$syl)Vz?V!;oy7ig# zqS{EFLh%tK&ykDCF%avEEAr(9UHo+o8}nd^N@acohhM?waV!{<2-S<;nL)rj$bN;_C8dXV|yDjJO{P<3TTToB<7hudI5% zleCs%EAYVX!6MgT#@)=DaeHp^MHx)Wi6JA4Wg8CgKU~J7U-ES~neUjSz&A91%B+of zR#;Ck3on-yf4vN5D|j?k8acRk5ev7Qfb|xXYcGrkj(Xh?rve02n&F8URDX_c3Cgp} zMcM2<4}qw1kSfqg%x@;ROmpK-1Y-2{Km7OQMPYf$Mal;Tnq(H*kjUI`qP^Ut4jmn- zAvM`m^0yA!!>JtfUH+-tn>hE20Njtng-Os%ZKrwFQyiC5My875MZIwxlwSN>a>g7E z`6v|~D3z*7!b}QEn5ie*iaR_L@1~12u!~1R;_HWQGHEzNjtJ3I?aqUSE3QE0btS8Z zwxcv5Axx`$^=kvG$c|dSl-cZpz>~!!Ib95LO8&Y><vg!qLC|^DWQgGcaQg_h6|2KL^CsGfs?px zSDI?4VkJg!FAIieLx1$St2Aa+N>y4|QdgZfH}7yoP*7Y_$Pl+kGbCNl8@;#6@E46G zaMoN;^#H$*#v6UISh-d&wb0e__`?R5?&8*CX{@HDzy)Jo>aymv7PL$c^5Z0umFW7LPM@vSjA3?<1gZ3#8 zcb{cz+UBsXGC5dB5weEOuRm*_w%M~hz>7~#`Y~20coRAPr2V@xvec=$7BULx`HY$z zIR|VjOF$pD_#hT&)_!;um+6MY#gp2eDglc75S8eQptthe;AtGf=Fqhlc-S!3Zh=11 z(d>opel!&mB-54z-q0%<9==CXqW3QuO3-VxHBUbY%>3R(G`(aGW;7ng`uSBYVCbL` zmz3CwhJ&jarwF=ALz<~%%cv{wFn{(Q@BQc-qWF@emRd-a=D0=Uv(t(sOep@U^)nA3ANMs>;@CaI~A)Tsy2lHBfX( zm>ToB=xJa^*Rp=9p|@V*wex2jh(=~Ynna;~C^L{pol~DhC3dOnk`gb(%gj`mW^vfp zH0j;sSQ6simi%u?RWJ+Yua8WQdV-N`ckQXJ{RV^Z>-d>>f)U10^hH4joynNY+pTTh ze2M&s726Vbm9o*)k~c0}@QNyCA0uNG(nyG2i5k5A_88^{`Zd@O-%4!{e3Y+N(3U<5 ztEOjmmRW`GJ4Q_`A3Y^xsBbR{9~~X%xCDf~XRk{uD9c~MU2{=rNZ6Mo!YiWV7>?lS z3yEz+*LbbI=oGn>NQA_clHO{@v8X@cj(2uNm>6LTk{MpaO09U|6WRtopJRZovBKKh zy9=PUgNkdsxfd}Mc7}igZ9lT+oVk)pq=m=n==w45T%Vocz{oE`5o&^mD%W)-;YLXM zKX*qjE(IJG#%N*Z;*fcEN_kW*CpABLCt2pS3IV@ z!^ITAtp++8c+}fsj^H;(kB$O2xW^vTh5Ivp6vHu9lbDS-8k&rN^S#|Iq%BLbdFuuV zEeZW6+T)?>?_3R^(25LS)(yhRI$hO8)Vl%_#iBx^JEV;|6nxyn6oCl}jMITGZv`{- zjZg6rbi`ot`_qU;xwUAzx8su|qpulvxmK7nfHfr4HEv`SM7 z((vc=KwWY$d^WTiGtbRCW7kM`!xS1s*U>L_EYV-ubxdo&amy20GzFPaFVQP6=o6=U zorR5@-mT$&(K|%Wdx$K8%>>hX5`v?n=Ca1*F zFO#|j40|L~)Ae9MOcibue)5{S?qc!;JA!e|L#+?-axeSKxG>%gShuz#D{T;F(q;FIDozmfM!*)Ot zOpWX)A8Y-uw>T>ar8L|c3Q+P~ok~ zG;$QeB)~fS@oNcZFDAK`_no#}*7~aO>P-Mc3R!lk17$kb7lx&P=*rx`nt-1UeL9w6 z(g^dIet)a4A*#LJ3}tKcuqwIjU~)fhoz3l`*0L3_ zDKV?0gWuNNif}>Thda8l;SUc=PY@bV@fc0baep#ZH{Z}ScaO4=SdnnpG~jC;8vp4z z2GlJIghh&o{XE{$-D8|?Q=;a)>Pe4*?nCbIQjCU3q&hYj|UW;kk}RVkYA!JO(`{mOuUWaLea0;Ot)A)}v*ZC@y`z^H7}2 zmkmMlXpZhEZoZYroFmaJi!(kDqP^L zp-^tGJ6Y1jmCPq+*n+Q!a~M6S(A`dM;%pWZ?Zc$;$PthUD^07Bbwfd$ZnFn00o=414-I&gp)I`%%}$r5G^K@(AkJtRp zSA=if7+PH2a&r^NrK-Y4A8K&l8y$pn1Rr{ErWEMlTGOG=5Gl-_ z&b3eLrB%yp-9zl_C^1%2oOlCx8;(uS=-5~`ObkB1WeOVfZCLFdG?3`)fbLQzhEsh~ ztO&Tw#np`SCw?C%An%`f;-TlFp@CY=2Cp+u=!Uf0phqEvea{=MiYEy`A0sUrjKOHn z(Bldu3vuK&jm(5*&}>qibg6nrdWHv|bgKzJ1k>>Hj-GWWjB=qLGfR79DhA)%uXS^I zqnp;k$=aP!Dji5DN7&PFTeBw=^S$=?SlcTGEeZ&PItTPK+()sPdI$%WV zz4r;Bq!tnhQqXF%9ao)`$+#)h@wDbZ#~2U7T!Prk!gIP@FDFKU*UC_g7~YehJ$m>R zZE_Wmo4%{E!Ih`j`Anh8o9Z{?u;KN8k$Z9ty0sNpS5D=j<@Y}T@(;SMEZ%xcde$G7 zJ-Bnfz&i6ly1uR^+9W=R5mp|Cqc#v&ZNV(&ta3J&SO-~)C|FPmGPN508F~@V#{5-M=g) zI_W=$gH;W}tt*iLd~@6T()?06+FM?Q*+vd7H*pL!E!5&Fn`)Z{70`NWx!aZ}cj4T(K_dTp{@`gc(Fx>5F=ldl8;4(qZTa9Tejc(H? zoiN9v#!<|3{>TzE#QZ&9Gs`%6rQr0WlF^uy5dOwmZ*n>T+R;b-rkYCrGAqqZx)!lV zVOLL8$qNYQe@e=0X7MDQg|-T9dzwzO!Qx_b}4&0Q+iT6^wiF_F`B&F9dgtPCa_3c_;MR5 zdZHKs*q?S{Sh!fz?PJkW#t`~!bx&XXNUU+=`f-`Sb+kNlrcm}lWp&;iKZW-soniG_ z!m;RlBIoheErT7j#*tlQiALXYBkvMf?0vgcrK63kkYz4IqJx{RqGgM$zh6rnbexJV z;25wKR@D5l8fIS8c^Bq{Ruas(>ycCKa&Nj2uDL|a(RVQ!~u~tG;v`4Ye#`U%%_8Ljxm$8YI2kYQ+FD%AYT* zZp(6rvC`~*3q^XHZRGWWpYm5Qabr>7)LOL(2`HtIaJ5*l%NqFq@XTBJ?#~th6 z_UQe(E^N#%@7&%OQAy?NU+*kqR#qW(tE+x|GGW6>cM6Hlc%Gym5i>&dCo5JO^HJAK zkOnOTF1X-DaEiFC19gvj3IRCoe6pTJ8lXAt*nD_LMs$%2o|JTbf&~ zL?_FSN{2?im>*{d(~xoq)xegVLFC-a6^0o-sc-*w!rsl-84j^=c|kC7g%Gaf zJ`J4`9-Tm%Jp~4Z}2-%R{s3XVw3yobB8n-s4+k z<;P8R{P+hq;Yjm`hDYGE*)vMBE*ZV86AO0)u1Oo}m~rc(jRpV%6EI|jM(T0|3cb>`TSz|7^aszk zfD|7?7LQ^{A|=!?sgO*iL~6)InnL}5>MV-{znT(8 zJta_AG{EI`xaO+xQltSt5*W-RIt!@q+9xN97WzSRXG$2R`8sj`EAb1etTp$w-+r7J zDaY+l7`W$oz}P|G#XRg@B;K`}XHqr%HB%)z0IKqSiZ$T567So=(^z0-c6UhN^$Lzp zyd>jc*cU6dv80w6F;yvjHi}1AgQ9q;=YqtkxhqIX#oyh$Km}Rpy<$(2SMG=AkCO3Bm@cI7P_G(Rdb_ti4Qb`sC_GGTKmiP8Z zgRs$P&d%g(uRVZeVxVEm_Yd~+WME$(Xq-pt32ndi!v3(&x{~U4hI08(^7;#@FA`tw z0zhawxUR;Ekc?(=$J=2`5 z;VT`vqKR+!8JyRw4wc-Z0j8gA#EVn^HM@wG)0 zIHF&o%Ib^VX{T)u{T@NmfJ7a6Zb=-cK65F8>}o$`3^epuI@T~Y5jFTSz2&OA{}`Ts zP9dEH=Rv^%)VV{KTZ#I(6CTN;ABHlgUcT6JSJXnzq@1YHo^!y-Ry|) zN_lKwiV15b8&@MQEJ0oM&5o=W!lRoG3Uqf|tK_4^D$$g5S=w?LT=w7TQ4f@3!`&3Q zAs-}B9Q!JVxLBX}0w%2%QxK2y4W|Tnd^$yJ6=NW}cEGE<=utdORc49?A^zQSw^<3F zjwtA-L0Nhb-z+ zRWYs_%5|M-dJjjunS(z$sP;_4YE_!#rxkL?4EK{2#_INwlBd@FUO(LHs@0Bvr|~9Q z}I^shH^x?1s&s(tMF!H4Ea-#GLM=~fATfVsR|>O!y^sI2!9yCW z`g58A~lrfN-pjD?{EqE`8224!6qXU zipvF<3R_^=ZRANavK@OJrDg8U%_1%jjY?iOUeaxF91$wso?&guOi3mNv8sRbG(*N$ zeR8eiG72AMAkO3MH;Bq3Pu~C3U7Ofm+xS{JI6--d(i-HzFk6k(L8occH~>%#bXIO| z_Wwc7SXo(k*wTLe2c1E%v9WWd?e2im0L_rf*{5hs(a;{$y*pP}8=IRsprO4+!Qw&U zPSiXQFjsgKe|?;mLHa2B4*x?_IxMHZwKjFt5enNIEu%XA0xOk0m?35 zplJTCg7f?ZA?O4n@CCcL08w;z|N6$^Yli_Tp4b%C1TohP2qMQhiIgWlJvlf8Yi#)4 zS^PRp9k7)M+S@lhJ^T^IFR}r80@la@4W2wn+9DE`7M*(Z1fn13#p> zB&;DNI${#(g*QTOgb30%6xit16v6J5a}Fr&L=#zrh54G-K2-v@=rwEtb*gv%AiQF} z-VPMm5zd}uWF#cap6D|msYmR^Ged?bAERjy6Cj-caj9Q)6nF8_8pZ}(01ub=uC~Fb zKH`)taI=4lphwJzUyHd_CGaD#dt+yCjo+JO>(?yIYN=4VGJJeIAbluW2iuP_fqDU{ z%%;yK?=DS_eX&GFc|8!eC@W)c9_X45igs&8@lE*324~Dk*f6ie6HqXqH}y?T_qQ&f z0aGCPWhIR3*Ec^66nlk}0fL_0G^7vTY=Rt+C1wSXPm!hGG+;!i_UK9kY?yitb_ape*y9uj-uv}_ea*a&?XANbblLUA z`fb`{C%e}UWiuxaxPP=NiuKQ;?+o-$A{p%-7(+XKP~mQmhi&%&1LYaPUv&FDzK4BF zu^?Z^DXX7?oQ-Bo<(vUGV)~K1nF@WB}lH#xEh>IfIPFGFyUt8LH{;>1&|_Y4Ct&MBZ?U^NROD01tb+^>uO712^(94%*Xa8PyO8M}f75+Pdl+6N_ds8qIyVY2XYP^Fz*n^U zV&k#@n-w2_5L;>NgKhjnka`)=OVXpBS>XU~5H3#LnQefKIY0s3Z2u-M_j_=le{kcD z@#e6tIrJmg#K3a20^~qV&6m(y|r%=mUD!oA$88+{YyhFzFFlB6$WnJzqfVcG6(K z5uNVAR{(-cH|a&&9*G0%?K9Yq&=2RH;G zpl_W%s5h@!KiT20(sVq*^}iOrZFf^0n3!Klfb0W!{4etF+g`B1ToJj0L0)OOKBJDc zot7+{Uuejw*ZckR9NTWfZ1pb;?advV1wFDBK=~Mgo<|#+64BX^-fC*;H)V^&*NMwZ z$(M${l>}_HK=#ASd99ji&eNdJYm(|ZUZCGWt)To>Zpro`H%onq?KZzqgF(8Ay z^7i^uz96TW#eN^~T1`~YGo)9)XX9#+#QbnlQ;K;%+0%;6*)S7fA(RoGQZ!MJL9eZV zFQGHgsIsO&Dh@qojCcL6`t#3bJw-9?51@Z`PWk2NHXVS=;kPdSeZ-Xa?tQ#iuEd63?2hsGl#uM0KC&bC(6}d5=Px z*Xt6&ZxUMr=I$QMeIqziRHyX60AfI$zj$(e&tv>58qQR{Zp>iK+k0Re2R#SzsythC zq@JCB6%g5SNt9<&u2Z+snBkXE*w&+TXe=E0Zw6`{Af_ zdsg8QE-@6dsl^wZ_u;FCe@>^XYMQKgB+Tc3>+RVdBnzrzEeUrDho)EzT`l3e?Xk|! z4<5{=@=`Q(g^S94ia&(Hd>4%uqzZe8s{O_AKm2O)=d5j4y`hIf&BR=dp~>7`hNUuX zA8OJ$e~m~FS^ zoh5ch9@{Kj>1tHFhWkq>q)gbTQy-doT}m`u`v7Tj_klM#=bNW&o;rA-j3hmRXa`h9 zGnbT2F+YW@#0f=EW0;+e^>e%MJp)C5ly!(+Afn|yRwN?Sw$Lmc?qF?f%DD!P8kck) zMKFs%4Hg~N#?z!Yx&lTOEBs<_t)#*@lmes_inhmx4Fq^Kf=fZk8nR zGLo%i7+q%G#)DFZCn?tBTr-^7x9T~-QC(u{jR(S$>yHkS(4EhtvjFk z8@06Ta;tK?Qy6BLUdy+9sy?lMt9roe-?fY+W?v^QyHHlRRnF08FCUF{_u*Y9Oqw&g z=>fpF@lWuMkbt>l$gqo%gM|8ZB|%#uj3Vc1D{I0GCTio6*hMkG=kou}o0q_Ih|sPYcG zRv0BpV|H_Vr(Dk2OX$7kmXMYkHp9!9-pcqHt*;xcZ0ec6W4w4>v^QTd3Ez@|aAe|o z)9B152U0;RTCyE8(fjirjG%Ss(Vn>5MxAS=VkFs|Q82!wdNns8R;bJANxuKanL^3x zTje&1t8)t_U$xk(wun$WIEyu zni5KEyF#V-Cp(^QKf|WiaohbBFEem?^U>Sr2O2kO0k5IvHd^8pu6R^5^ zwFu~UOm)v-EX1FG-Yfb#Dx;X<%uT22Vy!>Dj&Dcv+ELzr=JhYjtubl8Hiu-BBZ{eV z9OkiQLCKtxCpB_;kx`{>TVg0H&rizs89c5U!a9^cw|GxP$-GBE!nQBHEu-vK5UB*h zE$B$Z>Po!!+tXo)gIm!YTm}&_=bZ+u6`g8e<2U0MwztZEL=V80wyR~a?zbz!P5FD? zzKp{sqwfG^ z{9DdCh0R5yg@6QClefp8T&-dY#=1i;x{)Wi)`XB_N{{X{(M*EyyuUs7Znt~bwq_|ub# zquMv&Or3C;t-Nt#y>w$b*{JybtMgY4K^wVvw zOM|DLI4)D@sMg-QHH8)Qp1L%yopOqctL<8if1dxyAlj8b44TetyMheu$Yn|QRzM}G z@MzF=`qw~G6S)|Ibr5Q%390UC2rVanw+D8Ky*J7(^$e%(DNe1&YDoW)D!;{Z{&z~% z&p9~5W4b+zGT6qeY@f}%N~6?kkiv(OjMS66Nn{vHS3p|$=h6EnDu631(|l#Kpn_0M z8m&5&7Dc|;DnurYw7DZgm%@yPLH%ESILG?VK)<${h1aNsk=G0QVQP0jk;i3!ptYqx z9bG;}olPqSbzdq#Jj)SvMYlwd6 z)6FcKcQ~CsgAd-}ADbyv0|{luO4lj9@xdmI-B@#hoQ zWZdrl%L}lORwkhyZhN+4gHbtVa*pJfGqX(QJVOa>{ZTp^e8P#VcgQ z8@}%{Ncv)4n#S+WLvmo!DsJr^CFXvVCnAxjWVutY-|ja>$Rq`#uCCvmlt{0e8-@p3 z->7+V`^$yo;`tuD(tW6Z7hIMlo5RJ_$D!ns_{p<)`LKJlDQ84EU1o@I!;vzcc5KO` za>HNhB*Mw3&?@nG+2G0sdlJ!TL;thH6HlEP9U@{_x%Fl&QP#DuIY5A1gPPx%7ne5t z&cUma0n|Vg;Xd@kuKP;2I8v!sL&AhqL&Ds?b z?+0gD7xiDCi!Ffh%3M+~O@AJNR|2{b(Y~raY(vCV;8~Q=z$uZbqVT3`_$HQ3>Y#ATn}Pcw9eHfG&6 z6kf1J3%=4MqC++L@=IU`0;f=8Cw74ASymS$P0ubnEI8hRx2*0A6H_vf^j3@R%UL$2 zV75@4GYNQM$1MP2uO!KlsMibN86!?bc8;I#b^cZuAi5KOIqA(Ismav&I$w>W=N%bv z2u720427#qAw_vXu>#S{`vm|9kOt4v`|wzGb0wRr3+q zeTJ~a;;6iTF^Rt>0>?Fg>Tv(h_LkDCFMx3j)>AuwGTs?xO#@A$pSI;Kp~N)hXj6oq z;oA~U;DGL6s5dwPSu%mIjka}aO1b(j%`3zyyu8}B1%Nx`bvqqA0aoq9DxuBWU0==X5d(A2Eo+YoJn;y*J_V>dQH zA@}uvG*VUW8F6SVhTQbFF;Z|ptakk3ef*X}vwI$TZGiC#6*BeWt5S?*I!Rm60G>3V zU`@hD($?dV>aKIK#0tVJq;&K0dVdz&H1YSA5urcq9d)7WmFX{H5nP~}il~;&<|o1W zK6cAyT)y@&?xdAwEp+nsxsUHRYAC+fKji&?npW!`KJrQWgdkn@@l<%+$$Z}gC1An! zQ1vaWSyt0Y#YUa1|16@L8t0g0D$I z+w*c_D{%qV6G4w}n>APuGk!g~)ANB*wT>>@dp(d7@+IPbLe>8@Cs|j~ z=kTM!q_IlYjmK0rWBFE=@3FwaJcEcl!%`b0@JQ_ zsSUp^HR)Y(AGER9sq(Gag2}fpvWi!NJY@(49s`H1a69rY&ZpwVT-M@&>-tzAw{rjP z)t#P;_NmjOZ`k@Sm_JCReq9N~MlV^Bz0xRzT?HhHL$FW}SxV!WaT&H+%u5S@hFWa5 zCio3!irk(NHTMYl6%&Ypv3j)>OU(7CcRXx{5*t;647XrBBT1YGg7UrK(l#xO_q2`PS~=&rtZzm&+@Q8528gFR*gqsntl5^DxIC* z?LpiHe`HQZf|}>O3%XD;4<^9&vm3778xp(EkNED__udm@_f)qL{#Dv{aF}b%M|LnH zx(|Aly{JKn_hn@AFm|L!^WK|dawit0DcZsOd)QM&GZBDUeKAe9S<0t>lhuwP*HY0I z_mS3q6QhR@j0t#ikLtsl#VQuoAxz6{U)O@O9VwBb7mKu!+PtSOZ4PY4%y(kq-0Ed= zr_zLaaP;oHR+~%9Ct>aw+h7K5uAaF?^*D{Y=lydnTO4&wA2FMJbqrtOuJEos&J3j0($|eCVA^`eapzulM0k?UvC< zX}>Ls?<=4(mF{- z-PO@`&+U5|0xKO^r8#D%J$zTZa@nVX4HLHJ66g9JxS=a(+o(Q_^4nVjvU2ZWsS=17 zD%Uj-J3S+3UwJ`H#EwBo*Vb%Dxh-7edH&PT^Se#p#<7l+!mMv zk>Nbm=aWoQ7oD|$ZX!?P>MsawA`DxnIb99L{`Oh7usn``Uoj2$@+M^jF_~3pi|KGc zB@sq7D(YSG7jiRWKPSmMMYRNu#TH~v3HDT;QC?~4b*-}32$eIm+HUC1Aq2E@TYr&} zYO;-8W?iV$f?+Vxgr8y|3jurhJu;(&8>lo(<4sCJ|E#)3(MO5afCn~sch6j%akYIj zLT+4u96vpO>2LCw#S+N8GtKbqiVlL+&i0L@(@SU=2n&`K!_c0? z5E#-iy@weRnf=VqD9`SPKiyzN>9c@`c*>={hQ@bUSHr_9xW02Kip#YB8))3+Hp+vXNd2)JVoGDc1~435sfOi zcQY%0lKVm(z+s{ z$-^Id6Vz1)9bKAD*)!LhS!c7a^`mWd$HbyUw+|6vnZA~h8W81yP=2$|fEN*!xE*4G zt3u&Y(WCEOC{!3qOW=|!C~hS$Nn*wp9^i+6%wh+C=JhrjvA@6=eT>LdXj4-0 zF5Qdob{%S6(^kpf#JYHSu;whZf;4T|Ex%zdMk?cg(&yx(T{@zi#Z&lmDPUuzv{7e& zGjqS{K%D1SHe|+8Z(t=N>?mnjv6b69;(YOmoL7krBIb40j#nUQk%vK$yy1x|&S>Vq z)#;jzv^CMdt&6k~EKHy^qM1$+{eJJ#lDH|9(23*rM*);wlWOGTkyXN#$U9ywiHQR* znhc%w2dJoFafFg8k9kHk)^Dur8NQK!sqc!s@pz%tmQj)+#q77ICNcD&^oPd_{@$Yy zeDM!bLXk;Khr|${Gj9Q8v|5f-gy@6EBRM$6Rqyoo2?2;=ESH%UORSZV!#AWItCRIt z=UrTIu+Xm2&wT+jG^j@D_tjJu7&fIc9Hj5(UL6-}u&Q{*0cu7SSgOdcpd@^MvE~ft zR(8z%8z#lKioM|8^TJX7%2Bg0t<0K?h^*_$qGx(P?yk$WBQ}5Be>lc?HtS$iw}`x- zEmb5zzsXFlPp>PO`MPP5^QjQK=a*^)^IOv9KK^^aS)lF=#s`dnZ4-Zn>Pn6$1)G~I zW8HLTyptaXn01HxC25{Qm789FUVhpH-$E5W>>TS66XY~My?KA)j~~bY=XE$&om8Xx zMMYuAtt^+`v4^bHCm?-Cdn8TdPG*Zoyts1;6(zL+_RPi|I$xKv2V7$oA%qDPB{Wd| zN}o!SRjis7mla76@y+C>>ykM?VmJJ+{BL>#z8{YXzPa$H*>QhG!7#jkOIr-vmxWx_ zTcF>uk~b_RxlK#cQ^ht~-HotZ5*W{U?0+YvaR?3{SLq!Vn@%x&TJwKZq70>DUq0b2 ziZcj0h3kiL!N! zP9K3-AK-Ewrz@n$dN>X9+tp#%A;Ha|X}_kRy=Gv}b5qau>xao64b*Og80^d%$>v%8 zsO{gj4tU-0D3{9B8v$kn0=TFeAskhSBYX$dEN-$&g`@nH1)nZ|f(e#SyvP-S{q;{gkE#aDN&Q;;FAth z(8anc*&g9CW3oifu0QQADHnpTX+H`EM@fMXMAK z!^HV*)QV?`YD4hCdu$HlgWC5%uU%7OyKG7BxG49HNG1`b4x(J6)t^YPTP zRVD2tK8VL2n&0hVmsQi;mgioTLLGEss+N8+(06UFd51IFmf7`qAgOkm?s6G>5MIyp zQTaje2w7L7aOGOWkI9WP#tC=f%LUS6?(6QLCRZ^^AVzyn&c-l;>;amIy*@a07)y#r zqc@(GpbIj8AV8nS+RMmDIV;KUzvJMkxiWTywxu6j+Q>^E-5PEr)8`!gaih4W^fD`J zheHkjuvVMRN(?9#0XlDWJXVvlSqfW6Nojjyht}Pw*R6-p?_tRkk){H5c<7YT;5;%n z`x>fFo;G^J?RyGjUD$>ap2M=7%bQbLlS~Pg)?A zLnr(wRi&v!a(E7}xcF@@ndYgm-Li7Bq$GmwWTCG7d^~n*7K)Uo5PC%(MT7M>f#QNT zo6RFE*L&->^&~6%5%zoyO>|=A38QT2_kw)5Ik{^4qH6oR3&g~|8&`pjagn!Y*NdSw zGdvW33YgM1di9x#ZagX58gRj^PJkOOg7WVQw~16=3Xk-ktMhoPR*-59o_C zFr#kgM0}c&1T<0cvx;Wd)HDI#`7n_A3*)l#?UjGFtM%fG71jw6fnsb^OGW5JhcoWe zsQrEbA5kW%_IwruK_w(2S2vM;oNc)$o=60LM_cHTYULiRXPw>)*D2({GmUe7)4C1L zGJH3+G~mZIZ04-B+YG^B-_sJfkM{2q_t;y|O!2bJK$_p>$E&b%^Ii*jr{YHU2rcwG6gja(7)H)3+xsIKn&8%&;VWDV9F&f;p_IKk^xGf{M7@0$6=8{ulPj#*dZ_>4vIFIf z19aK#sYUdXLXu@#ssBRj7XDfMEUZmJE zjj-=9VG{-Kl6y!W0}YHG@fXX(N1G$m$xXPUvL8|@>VK?f`u5M1b}@a9qNQvRtnexb zB$M-JQ#cErZh-$A1pJZuaHauMZ+VR(a#*yw6(L2HgRBzaF6A`sn(w(4X0PG}ns@4`#73DPK zEaLZ=pE=+vOfzreMq8o#kG=-K%5aE^pMtvy^6;Ljex4odQsVBh^ylg|WuOYk`GA&T zTGMoMzwgUV8ros9lwzV24CyC`Lp_~;n0)?>Su>g+ zUw2JBm!L^8v+BNMzL)X3H&;g`%UijEDd?1*nqh{0oTn5I4a6)`0Phh`m7_i>mf&T| z`eYpYPI&`~-I<|NMTvW0$??65q2nAw&X6LqW#^=n zYF@S%5ka)O*2&!y`Ma2YnIb2WKR`7l$6Z{npBe1J$y(tX?jy$M`X&t zm#G-u*LPjd?0h_UGE-EM)uq&yMMR0+rx-3NPInAboWt6fL-g~~)(;sceEFEJ27Ojw z{nOI8F!?M@96*YHIU?jI!CO24E~cX;ZV7HV{yUTdXp+R)^rpJg2qTRo8vXn(mu(+= zN<5f5B5v(`*<-wAh#glS6#EsU!dI-=E1PZ{6j1+1hBekOAnCxy+J_1@8UlCe^`sn~ z{cU9z4I+f5bKS1-Q?xO7&}Qz#BJw{9bUlxJbDIsyY5N8w56qxd}V zC6UBdFE&@wjyNk6{Vz46_!71_6*h3trZ*)@ODGG8)8CfDU^l)!{Rpa}MI94- ztI~@yT_T;9flrA4k_XX$p2@%D;(xRva}#`M>(pI3Qv>zEbDiiAij&+ZG~svLNd+PEVaYQ*lAF5c zmwvmDW!=U3{Nu+Y8c3<~a;3$j#^*7$XHHlstv2~dr(Hho29!lf6u7F$OKDmb^GSAN2)zi&q=T2Qp}A=LmD-68ZBtl1g7d;Idu08qVT<^O9+73N znXpoSFj{7ydc#--;*xZ$|=zIRK-ko3i*{0wertz<$aMb=>*4qT4LQSfB;-5{C1r*!9c2I@ynShexK)lM774 zflSmE3+Q%O`()LBjGRRy+bVgw(SoNTBE&#KFj{LBw<6cezd4;hNhw|r=wzie3lgV) zP+hNtE^AsPNJW)9zbX%v;++ zR{;c!B$n@)`ux#;<_tyV?E_TXJn$s^je4!MdT(K8drU@r7b^_w*FHa+?r0Uk7py8K zhFJ3i&OLF$YwYC3bjao;ok?gan4qq*=GEZO2AIe)E)>M>^y=CVhK#9 z`bI?9qV~O-QEGk3R%{eygHR{)lMes@d$I5aT}|dPDqfuNBMdCtm+}srGy3@MMc#Xa z%ElEHqo&mk2oAS$e0)`~$&rH2Zb>#tC5$3i4TpCN?gT$_+K?r?!D!(mls`g$ut&2u z>LviEj!M)taxM@4`Oi4dS?xF}X&PZGDrWY#ry(VK_=}y=xO{PAwGp2t9$PkqeXUU{97^z+k;R-F z%O*V&N%t!1j;)C0j@^j|M>YF@2Sma_t(!RZx66gsCfGJ_sXoNDj<&*By(>+v+t0Rm zpj+RYb3Vf)!7p=@>4YZ6%bV2uA)}w%r%%l>Z{&M8qUCWcW*?Uhx9><=|?;?bO z+(iaC*tUpx9={Y-y}XZxz5Z!6bV^e1BRW~Kr44BE_$D{fDPWBCQ0;numprYm3OAgN zfhc+H6A2^t?m{UiTFjG_#8(hFkCDXna4QO04>W?D_>w3~FJJ-`6#p zCZ-U<-np2;sh0f@JL6jzbDd~AYw%43wwoLuR&aHCfc%VqKi)5 z&K(~xO7u86qwEjz9Bc-E=1<`!#e{tcHYN%PBllw%3+l2=%fc>XP|#suhRyheLq(^& zv-?OYQ2)KkTd3fSo;BTnVvDc<_VK=pCZ@YSOot{$T$z|Nl`i&Ju%nFbE(aA09=_t; zqfatxgEUzkAS@)BjN+s8PJ1O^BR?tGDIk`X7v5b=AT#6g=&784j_`r)*;+LSHyH`B zc?yaLypz)P$R=J9b10|$Me4@rv-OdlX4%7;z6b5=UCWqnwnI|PL;U2(0w+_gndXcx zCxr(U+MVc-rh+k}0F*8S{;HWH8&&*{vB-ku8i0_D04WRiz`0KW&h*3wmvC74?D`t~D8O15$GO=2GvONX6C)Kim zRhN5p{DIz%nVI?phl;`I;B&ouZKkQA1qqNDQ+vGSW5wD<@9ed;#@%P6@7Uvrb>jx( zKR#vWyxNveZjSQ7;>+IXay!9+_WC%(9Y~OBfR%pe1S2!{S5VZA z5G2T-6ehd&^mC+Lw2PN*u7^?7Kq*>3Igxj!A0bvm-A}a@f!dHQU?*X^QUaw@>6gte1;^+qNEw(4SfV0i}U2B$*X<2k<$R{r(7!6h3 zIk|h0N6C<@^`EdAbH+VJJBRTSRway($J$y8S}kQ0Hl*@4)_^hM^K6-BAK2rhA@x4$ zC#J#ClgbX#qxHULZ+{lrdcM&rCyCq>;a(8qo-O5rlW(${)OL*; zpX?8Rh$Gl~yaAtQUsLmzgud~MNwIZ<+&Xp6XuDMp%3#noqlA2J%D#R=YusVLgkiia z+_YeINQf6GPJG>rzG=pXgI00-xzli4K6#{_x42^1vnOV#?8dDSIK^`t%Cv28&gROw zGy~fz(b_9CiVmM`I(2$aPIN1j&aS5lFfCz!P_jpsaWAV1{G<=nedDKOoF(krO~@~0AIY$?gZe~6uT9v{dW-Y& zlP9Kt{!1j6FKg|R)}Aw$xbozR!Q~}-Pg4r8j(PXYs}=xvPmK2qEj(dx`Z8Hn?UaUp zJt7u48k!!cj;uoWDJ_Jj!_TKTzoguW{2T7k=!@sGqsVER>(`BIJ~_TEw@+lAX{_Ze z6LR#`mQphyEhNJFr023Be`okOyTVp)E)JrVU)n~uFEXZz_(B($71nVJ<-McW)S(& zM{+D1%XKw^O7r@+HfWjWb~|DtvMc7H+Wuba0lUVLAqFVovOA3yBt7Hy=dwkAE+MT% zJguEbk68Ep_(dFCN{t`9zm|^RX8Mi2Y_G?p^-Xr@ZhB1Z&w;wS3c^|1Dz1(9NxU0Q zd%Er6IvzO7_}zpqK)v?3(Y2`*5g(0Sa_7)5>e%_40#dT;wwM$H`h&>4h~R@sQc34f zg;1>KsfTJqfh<%9c-RNj()zc5{=vprh@hwiH#nlt(m>UB_qjQe#G_@lJ&Y!@`)^ZT zd!3!)x+>x*@BE1Jve?>>{mEd~ul)U4x$i>DNk03hKHW*YbgynbhiF}IC$S>usuo9o zuLlYv)3JB#>mmGt4CQ`Nv|lDKwdWLA@=!lD(6?P4EDu8Q7S=0%Byzel5H8eH->e@3 zk5?)1D2^pOyL*@9rhK|gnVPO6Ed`TqX(JK;A7QAGB*k@Ol59obZ9alGBq_YlVSN41u`};HaM5z-~lIpY`bHSE?u@Q zT(+^xRZrQrZQHhO+q-sQmu=g&ZQHi-z1@9J-#9nE$Ul=Y#~f>Btjt)kND0O4?Oaqm z9ZVT%8R;0f0Lo%Q8jK8_tN;c&W*AaZVJA~V7fX9P5knVKE`YkJ2|(G@0l>%vU}9ik zgdqh8+dFtVS(;n804R)qDgSK*sM#2rSlU`T0o3em?A;Y{5F`KwL{EzD&K+gZ*15o_KAtk`X)a;*VR~s8SLt9e-g|NM?gR6_F6F}D9 z#MH?SAY^Z20uc3oa51$rF*W(0XhT~|8_)mW`2Q0j>0E9B zH6#rGdj3b!{l8H{LiQfsv`kFw09s~7HUJ|#6ElF5nZfse!8LYuax%4Z`8VzV^zuLY zzsJec)Wg&mW^LKtm^;KOr8%t3PqbjR9GrS~+CY_hnGtwps{2M8*>cdrME~##`(6b* z*BuUTCeVm~clUBf^1g}4FwPY2cw#b!FhX}3`?ZL;+}y8v>s>MLtu8|E8cYq#)>sbg zCi2cDZGA0BfohT^Bm2Bs%CUqOS)4J(ptQXY9BKQ{>cXR)IHfK*O1joJoasJw71FFl zX#TYk|LfiwNO*4WF5C?%mcB)PS)jvVxK{4|qhb4huk#J25NcbX5&I}+&Gxp;sbang zQQ)759hu#=%^XM^rEoGbxwV#n0&>P~|K!YOm^Tb~0())#4 z+*U9Gy;gg?6z#{W?bVj~Q5-Wxk_mL97G$({5s^$A+0DHA9Vthcq^Ed+O&xd*jz`<7 zRyH5F3Fc$?R*W;Y9Bl(}w%4D~9=cp_wiiWz{-;t}L zInrL8KVx}MJa!PbjiOaJ>kJTG?D58PO9~T;^kJ*3Ea%wjkHedjZ{ke`x+!5DVw?}| z^&FS;iNZ(Jqf>ITSU}6=+H!xjcRfj$z!76$C7RtC+F1CUgy=^}XBntKemDp7&Wjg+ zA<0j=NV!0ZpqFCBbA=bXC*gqYsjQm(MGyiy^3~CprU0P{h!Os2coSiUNh-kM)*9(T z!%Jq*5e(8C8V$^I5Mi|t2ngfS=hI(KyJxC?Q?pW8c1CaB_=Om^M6JOo6wv*NS+cR_ z?8>||@#0h;dS_!#kjCKtZ>v_&Pcy%N8FbW|)u@n=??I zZuJdp7}r*fq3Pv6sVc#8*`w-g{kx0FsX0qT@MBOe(F$z&JcFNeQ;RdUwBEmejhzY$ za%6Kkdb^rk*nL*iMI2uaqKc&AsMx4WV1;=dJf8XPv$%AIcf}+};O9P4Qi&6A9=b(& z9$UDr&Vgi~!%b@jRO8aV^)rbPVC`*$kk=+*;$og-*PKMIoZx1IHoX6J9PwR+G87m4 zTo%kv6Vc-L5%QecAO=nHYjf6rz!8wYyY*M9XLmffqn3|=olSbLRRgT(2B<$I{#p4s zONI>x+s(*mzV?AH3$1Q-LQo&@!g+%u*+dG}vbr^pG)8lp(`E8f#&VzoHg_O6kzh-g z(5*){cYu+guX8>L4n@_Z5?7XPQIqPNWz-L*>L)j8m&iwWdzX*z=nPzcl9-5PmgF!rQjIJcXYK@gfE4|JX9^H|1BNoG6R$JD!G_tNjY zfwMR08BOV1a&b9`BVPr}TbEXGd>Dtl-7*1jotaP3y=+d*Hh(;Sy*N)}C31ZMNMCo`*1TK7N>8iF)9zqb$L#o#}@8#Rx%`dWvz~M@5FH#Y{$&D&$B&kPb#s5TrdVB2nd|f2+ zZ%t;f{sUmpe773o-{MP|8p`(PDc+LUT}v3{VuYGV=ya7cYZ{- zd0v606K8diaA3+o$8@Y2dI0q`eo~Bzbcfb|!&nx}Z^GS)Koan|2J54Xo2)%UZ5_-p zAt}LOBkBDV#oVL>v!MRON-;d!_pYr-1WBg=Jq%5}JvIr{pSG3_pG|>6Jt#g%s zMrJ^HS7tOu*AG>83Y33iZfN+uNXH``Dhs+KMb-4m?z1Dp=}6vH8)_NrKJCP@&tKH< z(TTwcyV>U{;@7gJpK>949$yv7Ifq;`Ks??(V1e=r-N5Su{8$v{H$0|_n8Ptre)}Iu z%T{TEg*_r%O$BHL-WxFO!@1wCN^AswGQNkdz_2hD9FBNyFaaph7Hh8rHzAlU)sq%= zkZ~L!E?04Nkr?tnnBaj2_b zY>F!t!=E^Nley3FvH+H+&Xc&uDa$kfn^jnHwz=1W=L`KY}SjU^>atsvha7@`vDuOJBlZ{ZDE`-AMP!#N=f@-b@01#62Q2( z*j{QkYxlxJRz_M&3>5j(`?x95S;HnzduF{Ixi;aNB2H$vzJpo|_=;wKe}v~yGPyq@ zi$~wuB)NwUi8vUXm_hhY`% zk>4}?jF!AXWzk)AMOa$38SFBT+sx)=yv!oqD$3riMd%K|Q$MB@JN1JjZH5rf*EPWh zQg)}STayY|g${!o<-=Ql_0!^jU&oc=Bp1xzFxZPSRC9lh=uvY{$*O1yg49%rN9E4^ zSd|*A{=RJtC_(V`BZ+Lqel*e-uD3)XK$V%(84LnKlDbs8RP_1qDeTEB@R?zgTm1fj z3Q|P@1I1%ap3anic~D($Yhn<`ef?l{AS$qEcN3J}1qO5wDLZa|;*+k+gVq3tjQ?`s z97oH>?&YD-<$CVwV6l^`zP;CgaaL7!T@VnSYBf>|Dw$fX(4xMxr-8Tw!OQnVQz85_ z)e`#5RDq!AXg#jzZ!zL}7@AWa8`#KGBdjQ-I6WpmTE3t&r3*vUeI#O|Wf!7t6Ek%t ze)38huLgs;$ble#-3c5K-XJ;-^x3BmM^UL2p<>*GUxE5^NPd=Z`zFnvb!gSdl=J=t zS59I)Uaf%$jLH-pM3tb0eCatWN<^UYDNM+TRA%yMx9L5Qe2Zrc0au;1F2w#F2I?RF z@os4BO3B?cZW}}VV7SYOh2%a0Eh%l@iPk*{y#gmA? zL0(Gpa*##N4GHvI0vYWgmBkcWFB(ql_>LjAW79I-N+Y(bGfPMPu})5Di%Qk#6|kG} zIbv-laZ|W|0sX4N2lZZzUpr&F`f!RPZg}a`iFbh>^WoqRl^4hgZ+G88IJW8E)R*z5 zj^Vf&<5v3Ek_6Fc2={BuZ)}Xk?CZu(5(>CQ1y8B+`BVZN5)oZrk$VC*4yUL} zdlu45Qav7e@ao$)fTyj_mI38lw;@gzM*@;S$wm0Sa$~(D6;csTjzF-pe)!KX{Ls)< zL+TiRv1liU1gZmbC}Bip@BDQt2@5SC|Jf!g8nl_zx#!ia>m1EIZiN%t)yd$aTX!eTlpr^PqHZu`wdv}OivuEmsNDA-KRO56!$@Tm)6q=yD4a4z9|c-a zc@h(QjO#K7Ly(Mfz|R_NR7E zAsZ+NPMg9bK^j*c3KaKs!*puPBpjUqV8{|Pj$3$=w70N(Pi zF@S7Hzh#6xPS_}i@F6jEx^7w0f2sg~TVhm!hh6&Z_9fxNP!Wvu8*zlStejx(9>)bq z=m8n^x25HY_AO!Er%?G}2>wqGT&u;?5@8eG$@3dfI1Tr~!rON_t#s{iz7`Jhli?le z0GF@+eZi%O$;8+?PS6+DDDL_~1>W-22L0Z6!i-V@|D*JdQAi&J40zpfopVrsQ&;v4 zEOxuVM9&Teg_(3nreA!T3?3e$D3*^8_ks-@=~*Vux(b^-y`!`)qQ`K8@A{qI&PKek ztu<76Bn_h{y?hW_iMn5N0~m-fzhh9>dY(YYuWuQvw!$!)8hW1VEM0E5plQ}uXe(3E zP1Y?*5^-HY+`QhUtYgg36p&7TlMtM-mb&)D`EbIspLjd#Zhb7WhmxjhAlwa5L(z*^ zp7`7<#Ew@x<}-WN@b)7zhhrwXJKVU z)?`J!8WqfZd%`SAOUB2{c^rnoMp7EiJo}pu36EM}ddwzaG~}%(;bRSdsSQQ>f3!YL zgEFtlw;RC*uJs!w^e_i(KjJ{yM_Ddy{y@?#KUiC{HE$9-4M3r}k}?E6vS*1X zUo!~@-+(cjuRImhsB})^&+4w%$zlzoh!k@jho!aCJrJ&x;%?>hhQXE|hLRMazJrap z)z$RCU05oWeCc}jr*FA`il{-GgMgx1(B=>eGpRPe)?jS(kV9DCCXbn+ygoY!TW^S= z12s#q7IVf5+j=`5(FvlJ8&e`8jYXxXedMeE7N+}J#S6?Sk1n(yM>)KF%k9K<--{x_ zQGhqA80b4ErjL=n_%WJiVSqrb;&HFVDU^*^ZPjN+HuKb))SV!Izn($*%4Q^+rTY~M znHaA2H&mT_?N|N;(O_Vh=k)R0P>vn`iV_m%TREq=R1Nc=gO72ogf43E>5OlfkY#(w zXWqa^jMaWzF_nH4^8*PgK(ebQoBPuO}GjK;n(zyhgL{yn&?BP;Ts#<5FdJT zFY93fL4g_~Xz+l4!fBr~qFvoI%wnZ|b^o)72yf%KS+Q-0%f8^@d@Rbp0!QtmuGw)p zQOCwW`mXo5;+o>0lZr!Ce~L^y`2!B)ogn0dLBAZ9>Pg$Yg%C3vu(3b>Ce5KX9oE) zPkLAChckQ=mYA>_J}|0Yy3XSLy(`w}Vo+0 z;v)wLpL#oCXgB);e_P&CvPNW%i|7H-e9p^RTnKPs@J|IWh0C?bR6CU2Sz?U^19F9GF@E0PBoMWLS2q?oTwHj$F zbhe{WgiI!tjSS(GL zQSa6VlH7NO_8%FD?)PhfXJtbed?9&JxIszeZigpIRTvuZ za$ARczc`TKP@>x?Mq`}Yyz+O&;nF6PNtnb-Lv&PZz!F=zj={@>nVqcI7KAWOwXhwV z&O7-pL#N#iR;q%(t1-XNE1>~f4jA`T54PVq9{?+0#ti-#rT2d$;U1;e7QE1b5o=JKt@z;*FB zdr-H7e|pJZWaBQ7`#);HLg?>F25~h>{DLjbBlihtr=NGOd6xYV!OMpPq~~bRb0R_L z2x5M0UW$1uL6>@pg;wBloJkIm4%3eX(^ZQ%XLzhTZXWA-Kr4b3u1W_-e|Lc`I-vBe zX)E;Eizghp{e)ljS`A!{gT5QSze!CTcn0-4e^gt0Aw90VG*bRfq`BKuQ$jfIU8%k{ zmwvk|fD{wj`1yDH;X(u}r?`n~Dv3aV-M#pPNyD>fYeR(va!3Ts!U`{eYXsNb z8M$nWXgTMo{X^|lGH7WY8yN-iIg1M=c)UH zxPC3Ecb`6eGf6|mHPw&7^tjGvokXRfAuMh zg(QvCy-GVQxF*m7QPAsMGSKl6p#J6VW}w8#?x2R>1$M$|Pvs6Hz$ z4%FQD9jI+2Tn1T&)$ILy4VLyIL`hZ6)vR4W?NWE~^HkG>kAow(u9t~s!Wo;*dSs9% zw%+*+&Q+Yu|I2C#j1G1oMGI)%>N6tP=x;# zl#Sguo9wRg7clrhn${G&mZU>JO@5*FtzMAf~L;>A*t;g0@e+y_=1rcme z{ni}wz08UmhU~*`G@VVDkkfT3Rcl)vD^JWs6=!3LxD3`gorE2X-jKvJG1}<#2Wt%X%M9b8gY!G zo{iv|NKI}`Lp}Ld3>#_hf2)D0%r=^2VyiOZHoWV+vloCMyQ8U&*fzb!jW~@&9Hvob z$yehE-8$yqbhiO5`ybeo->9&=v1J+Yxi94{AI_QliQ0aVucG{-EorUD_@sN4>NB?% z%+1I#sqCSzJ0}k~H0_1qRdrlNRq{Gvn!1Oc0l|S=nkwRLyK}O?f6OZ3C7Nk3+UpgNZca^;|v6hOKUEm!771E+e+n^H51f(3w3QrM2 zz_Z>80T+~wsG#O!t&Z3xW z9syW3os79DCo!2>D{oa`%h+DjWjO!XSy2C`c&=AU36a4zSyGA$Y zi!Sb@8LPa_f5i>thL|((X{&T>iuxNb-PiHDCJ;^_Op+yKizuLCZhecOF@VBA_~#_> zB($`68b9#WnTxYU8ymlT!_}n?Klv6`9klm03M`KDy-8jf`KVEcMp*z_v36(LI4Bed zqakGaXa&2myd>sug*Oy>;fKfGGnELnexuCA723$Ue}2MPb*rPj$w~-79drLrj+yJYM7M@97JoEKi9`ETnbb={IB<=L& zE_NEGc|WuT=jLs}uzp8ztqa%pg9+XX107)s;bE?lcU3@cln@Tax*gwWfdE}H2&2~# zCCByi@WMbZ{DE6}TSF%sjtd5b-S1q3`P_VLf6Ztubo?I)gsp8lUL$UzfU0}U6m=Cr z2+fe&4p?eDKI>M{WG$VvhMX6t!n2L(gMf5h%&c%#c(f<3c*hfyMoA62TLFd1+k8o4 zpG?{1uSxWk<&`k-1V;$D16K503bj>JHRXl0N%0Pns-KE9(;k3ZwmE)FoGW7scg$ko ze=wwk*;>lTnIL7$4t%Qf7^)!WK^7-u+FWNv>-RF#?h1!(M^TxYxDDq zQ+yuWy|RCl#oRP|K%joVXK(;ol)bnyx=)|*}B*Q8{t$OCPu zDwf4DM-WwV)P#D=z6?a4f6a3D43dh#o*{6@-N(CGa6m!*;4Ue(;_1lI6A zj1DUkZo#a&5Rsgen6uog_14aHAts?^!Z;a}zEWwxfY^RS!C`a{eMO``+)UMpv(NJi zGgUyfMz7NUxib|KI%r=(F^9`tMk9y*D*H&IZJujA7u`IoHza}^fA{qlC6XH?qi7DO zui1zBYb&fe)R6(sl?TpClFe1B#l&PzD`i$r{a5_feZlTn*ZsRJAURGeB{7(CWZFYw zCKlue*g&ZLdNdo=9tgJ1qrpx`@XcIF6D~YwYX;iH`3V0JC(vU}4CeycINzei3{pI0 za$J5dKZQIQ?;&gNe_D2~D$$d@_K-_^XIh2AwGh6Yd{*GnO(}zI`Yh`5PTnpRFBB&= z;yA?j`Ec?*iw&X@cXO?+j*|64vthSc7gnSX_WB%L?zOGWj+XER-H8KrTYd|(kfh^p zaxV&@G`+b?DS-ly{#Y=Jzu&F?6Oux$qK`%syxu|6Pf%kCe>ZWmAVCuTAWK}j?J5P7 zjJh+@vWwp8bJO3K(%%xn)V)2&8zLWQNeu$(gWRy<$gM+!N<#%VjurF%%I zNB~Q#9QpMle*@T=m3<9O%e3~nKnPJDOZX!vnw0&UyYb{FDPKO5Vh7{O*+?&+R;~+l z<=uNg`12_Q*3CGYC z1I~`fnJY&EB*btQIhr9#2~sG9(_{;R&a)a8{BV{t_z)sr5wi297k9Z`5S=*0>zmw+2}e${yRm{JT&)OlXjyh0Y6E6uQg~-$*=?Nyk(4 zP3#M%MyrpP?|~{~0})s0Rjz*@`s7i%#3A2X)k%c+;8;4u*<6a?j!g#B{rU$v&7d%< zpe0{$o`ds;20#II%{58|VHMQ__{Mfp--;eAfAVS=%B$r~uJ^uTgXa8mCbbxsR#CH6 zX(REQ`p^nPzr`TXFOcfZHhZTiibwE^2O{ z!9>YooB5J{GkVF;MgC{|z{jd-~ojUt3dz1#a8?mTqY~Bo2{^ z)Wt-<3|Kkje%E{hZZcfh3!1Gjc&X%@skLQEUt^)vU1#-_tM8*}gqd22`l5e!MX+MJ zwPTrMSgc@vmSGqw(+xW|H!fzYg(>cVe}%>lu(1I0nXg~cV9juFTN)S~D-ecT0p0D| ziZZEJiK+mIHqf=5lU4i1gcqqNu7hSlf2@6?V{gdz_lGlp2_TYYMp_GBVhb0Y9klml zk9`NFP@1mDP9LD?^xsp8;cw78xoz;T)0U+X}-lr!_ova;#0lh(K`6q>j-467$A(o<~lN{d^W=>c}Z1rP0H=G zPRc~7@_JIjm{seBBc3fkSH55!JwMx{tZN$S2>VLLKJ*2O`3|f2q)G5m)Fm- znmbOra%D}tZ)WFS&L-GTV&w!qY(-1tk&Z!3iDi1W?%=|WP)+{CLSD6k+B5LsrZE^0 zpG;z^c}!bFQu+!PIk_#b6@Ykr(`zsB&zF4pbQH<>Aa~T=8~VEjCT!hW$|Ie?X!$y{ zoTqW-j&IqW;f}GjBt2hle+6tmn4;b}*ciyKMR6$y208$IC7sYJ3VHgV!|$e?q3P({LiA-vM#f zY32H}97tlTJ*R}awx((Bc<+EDD7TaxDY{IF^jH)2To@CTo``z#^&2_WfEqX|r?)4% z)2r=A%l*VF!+rg%b5;j1fW^24`r_47X7xfU)A&%*_*#C|Aitke9u$Qw?|GJ<=}*Ku zd}VWKn-!AGG|4K8e=)G8ksJ>SET((A49Z@FMIEXRsY>Y*@0=5Hl=IR<<@?Ct=L2t5 zdFk%rwA#u?T*NrDmq}3y9kf26nDMPkjlH6E7=`&Lx#XGf0H2f^KX!ZdF<#~?TT6M0 zL5{nJ7hlx8f1s@k_8n%~-9{0F*VF8d-IlkvfU1ap6a8h?hYHVuyQ?~w+9aaIKX1!W zCa0|CMj?21f9yz_T7LWs?9;CBDnT3#n-42pjOmH--q`I%y9o3z5*u}pwCoA*uA$Ib zPh&;(6yb#pxTRB*gsVQwDnj`hpuQP9=0;>PLe-}TRA&brkU#J47o&s>a({u0l z*kE|$s%lEj84Yd<^}D$X#S7Xonr_6YiAv187ASNsD|{)6BqI#D}rFo}o^#z@U{@yr~29L`ceKVMCmNbgl*l9!YkijixgU#3h9( zlezR3-EUEcYdhzv%Kx&Z5`(URsks;_yIbCEWq$}H*%quQ;~}PmGAu?A7tb6KVE;n8 z-OJc;i6v_vZ&aRry=8Sp$rYZQ$a^}~%$)NQf8#^^644w9Ke(=0A;795Jm_U8_d<0$$pdY z+~sZO9MJT`Eg!M{creTj>a$Z+)eT#ayRYnL)&q33FF_>|5w#McZ*I-2$NrqBf)kO( z_DZ}(FH~l~qHpF-C)wdmy|!F8FOptkf2R~r0d+d0tYolwuK(pxb`Kzqe_W(^4jM?K zzP`)a%6<*TgZLH~f>BwZhE^t;c^dAAEo8m15{*f*Eu;0pS`IyMJPkBwPS-KDT`YM?>Xc9a!S~S%emxy*F1iUA}{tk;~vuXe=*sxPEE$+ z0KQn%p>3^jfc5j3kjj!4T*a@g$aNl<67X>X)061yx+sdD_ZA~!kkRkwepz&vnY!nm z6wZB}C$dLvGt*YW$PLjC3>SEztMc>?8NPQrCwa1JP3rL`i7fA=qdVc$+Z5~Dy+=wYM94!;hzE~8P}G%=+3Dhi`gUD1;p z{VVbWIWWpE9B=xNb2VOX)qJD_lvncei!g{cf>m8}N~}kOaUkoZ9Q;8Yy2-~n#bWOg zAbsUvLbe&kqcN9L@3iStqlD)8F-Fw~Wnu!4DCZBXPDJ_qUDvkvf7H`%$1%B?Z`+ex zH!fHvxvkn7pCnT*gJ=;(K_ZCQU{%~Mb=Btb@E;m%cb#xf0axZH0Fg3${K30Fr3SbO zPD-HHl6gF^ILb~0GnegfSq1XQ z;v$adw?h&}=aDFs2Xyo|+fP!z?jeZg>K zJMMV0{Uw8t1>dcx4Hvx2>CJ<#Z=*OJL2cD(O{N^DOR&D}TuCPrv!RE1gwUKp#myA+ z4FR})My%>SD=c-3h+!|Wc-h(#1K@$Izk-a?)7DjAu<7w=4r(|uKN^2cAL`9S9>*(R zLasa}r#Yg|e^x=`xe`o|R%toodJNWJ=d*n3vAs^(D?|0iH;Hene=deV@WlX9?1g|0x_khnLPaB7wrVO;bsGLC@#LA^p+lO~iz zz+qcQL}wc2tY3)%<}bsUtc0Bs0YLfaRDl}jW-!vH=C;>i`0KQLj?Pi=GAsvWD#B6P zV`9T_pnyl#m8~LhR#wA41^&Tp3qF2HY}rhz9znb)90yn zUSz1m84L+Sp3FbeZy5z$?i?4l~2)=YwltwKZ|JxM1ma%T&_mjzDpRo^d&%t&1J~ ztheS5N<*{rN={3XwBR4o^QOn%VovQN_U8)D&HHty?=a~>o=vXX@%y#7mcEc*3|ela ze=PD7IiPmFwM>rK4_ekE@~{u;r(0^I{JboA{UkY%*kAF_YX#nGG!aMgg)(5WfJMJ! z@?=6TTJK=*(H9gt>G-Dt&n_an?@z2_hK%?w6wVGYw$Vq|?<)F(l)f+Qks*q0j&AQ^ zKb{+uZ?bXd?MU`hfC<^Su-*PkTCR?If4xD#UIpM|z#qGB{Sb9Zk0p4T2h;qr)dv1Z zqM6*XXcHZ&SUkH%cxm%NU5IL0{j$JQ35%F@x2}uCCWvb?s^%=3L$2l0L7!i6Si-~< zx?(a6=;COUKZss9)c$m6yfg`CPKIdL$_?A>$Npz96~5pFP2J?sh@E-jB6qYce>en% zBYUD?>m)He*mzMl;9+PfOv)O39)|<@cn%-nJr8eZOXC(<9#LTwR!rnES`)Ja{j;Qm z8lT&ZwU;|VtSqSmEjpX(2>F~~npb!0|FJ_$FUyw~2n~NU?G2B{%+B}|(yI6On))FAlkenC|t3mM;QBc_D%Y_JMHpwMT_#q3~~pRPGIZA`?g! zF>aZQ@R?$s*lAOYH_a(30t&|qSI!VNJ!zve+@K7#gFu;e-9^IWud+`4Ei)oK|%AQGy6uPDEm8+ zA;F4zS(kf}*XFW1m@7D0iy0FZ=HlXci1x7NlzxkA>k>tO^iaLcxMoe{sU(aW)bY;_ zsWdi;)pa(MC~16Gf9hQ7Rcf3juL?Nz|32C!SA)$ZkRsQ`7-N*KKm+#FZh;#?BAt|i5G{}aQobbgZjU66}$_9fox_jW>3thdnlwWcz-)y zsl!3RXsaL6vVjSYJdgErG5%-ECadF^X;T=w?ecCJe~>aNO8g{9wRo!7Bgr2`tra)3 zWQ~7D_;Y%;BV@ExRK`=+wxDCneotBflVANy#I@QS@wS_@`giV-9AJHD--eKQqcIU} z&oF^_(KoD86bx^iD|_b)$9Cp8KlqZt&lzoZ8`HXX@i4EfkM-LU8xWC!w={o8qymya zLwW`we`1xPG~JfuT4N>o!D6uTQPbT*-x_2P7E?HAlp;e=E?e`@2chts_kpbKPD4el zcv>fQg4NJuo$TTt6FgM@Z88?9WN4AMc%JUBjU7@EXlo^a?W?sX#S2yS00Tv#a+Jd_ zDSVgFfz+H3SFM3ftOVKdef8s((}0&-qge5dQL|*&m8?&lKKgiTm3;Om>P&Y2w$dUoYF529g^Wa*3;gG=pb$leD)5p-jalh z=@eTh(Qmx~4v&^_3C(w1{El}~?|tj_UQx$u`z@P0xr^c0**WBp;`kQfbtgmSe}mhw z@BHK4_-i4iS1{YCnYfClDTuk+oth(&lN{(5L!I?{&irN2{7^dL`Ilw|R<5Kb2sSYo zFtIetihaIE!1y?V+=c#I-$6M&e|bgNFr%_b<&iyOxAIYfRF+q}XAfT=T@no7PZwD- ziN6X?;S?8r8Z7=w094Rxt26L+e>$F-hn;B!s6~2whR(opd+j=y?5^R8$Rk;-Oor{WFQt97 zDkw7r#JcQn^({I&iqKF(F zS2!0cP|!hE6&psqY_3BzCfFq5Nk%{qJ2BsS!(PM^vy4lsb~Ohnm3^(L>tXB#h&(>V zPQR?zSc^})Fl`F?V??q=+uh`~W3650n`D{Q?%HLl2}-yTyD~-rTXFh3=k0o|UdR0D z;T_WJOBgAaTQ2!6e?LApyJ*@ND2&9wvDiroc4j4oNPA9nGC13%V*#Wv}fu1&!I9MFe_&i*~+bFoyI<@tLfdJ@};X1C?gcRD)cBR{uKi z-(yXyLqZVP|9w_}Zu0Z+ngLu|N3EOPR~FuxqkX*h%4x$Z_yzyA!m+W^(;w^um!QoB z($mUO-g-tRf3Lxq3Yr^{CsVO-#hiL?fL16|u0-H%zn?k2htoNhlU=aCSPl%TYR&eN zYEl|ghGl0UUE`$GZ(*wV=3Q8raJt)XLQW7sqCm~mj}sGIpaXOV$$zmPar4b|sG|G= zd4NqqAL~9BbMu;J{(V~u)9TDHrGb!_)7LGE-?d~wf4v!S5^&J!c0OIDh=D9(PPN0> zRZ4*hEP9_@^@lJE5AB*sM>MlI&M2+v#VaqyQaC zuN4~_f6fAXT>n_FHuTJNg9~3l|6X5BQ(pGOUF-2|=s~B=U<3w?Ujfwj|IfuG$N%RK zHb;YVZJy>A?#DfW-n??umS}@7+?)USIgn>>1PMx(CJ}mZg9Y(^OVORBu0@aM8|E>Q zApI@ZpBo_zZY6x!%z58+rTxfn&E=q*6Oj#Yf0TXjnYy}i&JxEUDe5Sb ze_#$F84}TBVqkLGCv6p@oS5dW*uxuE$2cpDswmnr+!!w1J?Rgt2-!`wk{QJ_9bNlD zW}{7X2!+3AestVjHh?aY4*mw~167xySu>g#y(Te#9zY6+*>{yf8l^ir)cTbftelun;t#!ZaPu}H(KL67+Axa zaTqE&Km_>j{VyHlOq$;0`@Py@aR<$gW}K1pdw(!Yi0a)IGJ#O@$z+I??A=t4J$q=n zo12VPb*E(#hV+|<^}7Vfb+H#)3XDI@}L?JsK zm0aQ5P2`sb2j3(a*7vTMTMuU|u*1&>?1i&B>=b)4W)Ki)F2k0VaM>^9lt618!z`?d zL8aM3naUixNY;-2`*E|yq|8C0e`EyH++?pd^d2FSgcj+7Kz1$p5=8R!_@G$3gAsOr zT-_j_*m(5!mkV~jRQRNGx|YZ&hmf79;*1=M7LkRV8-XK>DDZZT$MgF{MQJKP>^v=t zR>An4vuu$KsBe5;5db;4u@#P8{EVq+>RlodOhUFi5Mn!^1at66?)|gY7I z53Se|J5+SUu1~~HfeoH7^!X{ouPKXG-@TR|oib;>Y zix*GjAaDLf|0N~ zkwM|%A~i@DgjMw?JvdTp)K8fHLTK1bOAuQHv1|*0K&dNioj2qrjVirpz6KW|cl!~K zF8)-@t0m)#OwuaSA6X@YdmtH#Q9Ch!tWHr8F3~iYVktr;CIo9I^`85B?hLfhSAYN= zR(}D{S^4MJ2~MSuf4-`UQJDUWZLVI6yO3(jVmJk*Y{pAr9NkipFFhNB9Bl*p`o8(d z9h|)z-mtSvMupFe;gFO7;976i^E}xw)G^#TG$x!-)?E~~))}vSF-{JS{7Ij$nHS)s zAs<-hO$j}bNywGlNk#NBWfqo?;!XJ48igaMJm_`*G>Q7%fB(Ekh#+F2O_wUs*;e~6 zp?y0%n-c2fi_b5J?zPntJnhMj=7zMTQ};@R)ts#j=(OTH8S0pVH>0xAqi}!aLXhPZ zP}^DLG9h*oe>R4%p@uv4_BjhiLGpalzR1iJopC)!ZgKHP4!Je|_)12;e5&`R4M}Y1 zT_cl4d{Cf3f0We0&|?wbU)gAY?CD3g1u9Q723%-GjVQ)&%l{k7Mf8f~dPdbAfs|u; zYX=G|J5jm;kn2k$wUc;Zc9S76VSqXkM+C+x0TC=AmdGc@5Qi%*y@qJ0r^?A^JaEMX z$CtC<$O33oTuN!QNMy}mtcRahEw~*%{zI7*w|11nfAgk6OuPste1uj8IN4u4SdDH6 z@#1d|3{(K;t*04u;VQhimEagTS;ycfjO#(fV{?>qSl^tJx7^IG=gaAiE_~3X8`e0y z3?(;!n~f@LNBq66K?xb-9kn27@DW_f5BDt~lLwk6LeC@g2q_Cz^3s&d>5)XwuT=%x zj5_RSf0K7ExzZ)c^FVcQfH{z)W&;XAet7xTp$axxh4d69lxUNKMySGsV zJwjGX$Jwnt=tL|s4kxx2-Zi?XrSEUmi))u&2&m2@EqxPD@1 z-J~Hhb5`xi`?jpYb5}EC0A=!EjJ@H32Cr08e*wDfOI!y``O58W2_%6~cx~f2Iyv20A^4e22> zbPRK`IYfC;H$mQD2^;&DTRfwQYtpdGeso~chvr)?-uBX;h;<7UXgPx~H@=J3^k zXBDv7m1&|;Y561s_OV8sCc46%3U4<9e^rR;QC+v|AUxC~Y7(#w86Oir(uj$!#x*Sx8GcB{kClf&J&9HlymfBc#Z=lyNCWfav zpxY5Pjpxvawr0gn+^UezzRJWS@5@&_($L*a&s^g7c_=W@-EHw{!K`VBVYTT>|TMsRkpYSk;#CAPx|*u}8WCJ$DG=fN@hOjhQ(!bfz)lXk=ObE$t3?oG7Y7IcS!&8Z ztKz4SSZslU&|Ca{QE~T0a~FU{e{)F2zz|QWxmPiE0+-RW6IeqfCm@H>5NlIPaDBL( z5$t{t7tzik0K2}>DKbjolkN$}m-CPePa5uqGjF*yPdrq`G{e? z8PM>N*C~K_e8%&dgI@rysM$D0%_^v&%gx@R4EfG|Ltk?}HY(Y8ktfpC|G(Gd18?iq z93t?&X&AusJ{xEWeMnV37OX5 zQ)?ZSJh1Ka6r~=%J*ZhD(Pig90GYnv6aIv=_tJM+=WbzMipg!y>w_(3-CN|_bcT7Y zR!6vh^WRZXn$O;D9;|zkbD$G?+Hc>{!3PdJk|kOD5~}w;_FfD=e}1NKQI~;mdK|%( z39v}YzPE<)Hnv$Cvu>TC7<-#tN;4B$-6F$J&8wAY(wdmAPO8d+8o_$1K6ta&8+TXA zwNO->+|T-@aXEogvS=4Uw`@qSlw>^C0Mu^Lpv9Z|xt_K23M?3X20^t2QnBawC=^}8 zGpB$1w-~xusMXrHf2eS#`zOu(yGaU2Wj@m7)k-{P<3fPIgq80xkP;Zg;C$a}a5K+E zuQ25Po=G=)*aJk|a7_eIWj4I@Gt~0sWVjo*)6tkOEPpW^lD)q={^Kxv9Ng5`kynbs zPG8=C^f*If;G*`G9)Gte~IWUypaodpBbqPQ%& zg0PDRIUU_(V`?6q=rvXk?@yC{=+9Q}sCv;5XBSRKy(GbeGn{4gTP@YE*=+Py&>T>> z5$fmo0ivX+f7ig_r35JRkg4aqnyJ(k^&gQr0=_plY38}xKAJ&se;}w1c1=4(m}%4v zIj1dnG2s^;?+27~Uf`(s7A%DNPw2m#_)S1?z}s}&V;PqV|GgT3#Sr1~>Au2QPHjs} z?>X94>!s7^&(ap+?Uw5es75yceYF~pt_iQqnFuase@UlaCx@NKC5CAN-<+KrTi#Aq zijVz(8w~sB#S49o%NuE1#Z&Wj zc{x0!)`BIf^lhnI)GiJ|JXiwErpYLh1M3VG(jsT} z!L+z5e^KJ!isn$*vfyzHlUSR_*r9$!fZ9O$=3v!`3ameZM18h1S_?)*M?=64zzW8% z$|(_coqH&BF?)}(J|7kY7HzP`f1_3NpYXMp)(Z8M!BDvA5RAd3pO=IRtfxdwJZo<3 zQ_@=;j&TKSm3?DOueN?63CEUl*j2*RJGM;Qf4sklw9Xa2ZsE4;GqRF_Pt*WI>hS*# zdX{F`^bq!=>jOrk%g|7!Cp4NBFZqMd0qGPX225t^y8wHd4parV2Q=*Pesr$=?tD;c zkt^!7=BJI7V=Fh`aUA<#EjL1Q!TtuJOmGV6Yq~2Yo8syz95G%>>6pvL$#6+5|9t_V zf2Z&O$cfFC*Z=XatHsHaa|xeZ=>V!WD*CO_pgkmIZ6_D}w8dp8Q<5yc_@~h}(^U}?B6K(xExH__=!oN?yKjit!)=0WvX71Hx1PKz2^}7)ZLoS$kGe*p3 z{utf5*B7bx^lZ2=rru2xnyn^>(%DX0f2}&6z%B@`ivB$Udo*?-#~j;P8 zD)15ov4*EWj{aT=YN7&1;W9b3K}S#x$CS44&v{uY9F*?@jU>yMX-~?en5Vn8!SUw5 zRffBPw)I+xfeZ0?jrl8DJHbkeG`+I+h6cLO*;X+JKkcI2qftEMZ$F%%9p#mHk=RI~ zb6o1J3}UNvXO#)`8nAU~u967Me|mJDW0Ju0VaVHmx0H7NcWS%GS4Sv+j|-!T9uG)? z4J@ImjkrXKkMj@rp{ERwn^RorNx|EXW9;J(_vn|IP1Hppl-+HT!1|_MNePgpF=Ln<_*6tx`3VorA;5qdvBesw#)*Mcv=OdCVxO@ao%IKdx zG0@XtpWNQKV@Gj^q56XhcxQiV@pcX2{%Uf64TR8tv+a{-ah|$hSD%06e?#})&9VJ> z32uzIK9hVI;FbhpU-Gege_I|^w87uyW!}NI!Nz2v@Q(kp%s~CdBGCeZzgC)tjO)z9tFJ_+aq47j|L^mc={gdcL)&Vk%2FPM_d&%Ir zh2GMj=5zXkt*+`n=4K~>&uY0R^o7wM?<6Hu3AC_jBjIxX6VAGHOR}CM;~$x2C_O0) z_MxJoyzT30e;QDJIVdq6l$k)dW8)J9pw1fOZTU(FWB-D664=&R=K_9p+Ocg}W=&e?@wWwLB^qy6#C zIrK}12n;aPT?sl#A(50<8*U&S2J&x&)F8{w$NmIs{(aU%;GfDLT?R&sjaTo`E{$bc zV)JRcp-tU$PK^};lnx^WrIoapAJ1A1z#8Db4CON~V)QOEjWgHHlUq}!Tq0|Y52J}O zF@N6VxLdF(?4i{X1%KlMPO% z+lRLr+4(v1$^UMLRj%EoW^Hs3z#6UphYGV7vqb>fGPZ-d4QIp_gQ#k{muy=E^9LHEj?5#H&rLtR1iH z2?}J5fXheye9=LxhERnU`Lda4X+^{if1S=rr})a*_0)%?!C^`9rmBATt_w7%(ObcILkm@OyjBxYcg4u{^e66xI~nREO}20e;u_4me+Hs_g6HC_|ce`EH- z+8!q|!jQO7uq$N2;--RVV-HbInG=HH=)eR&sv2;VR99*f5heQI-Rb&3byP)AF>(dOG<~)uup%zR!u-I!wo}z zJD_;vnBhZ-;`M{X0_G3@M3*DERnH&WYDdcj2w?lsA&j=xc1|ywOLGJdoueH^U8We` zjteuIlP8+7NzC)2K#euUkdT)^S|A?7;3u%O*+l3A$f4ZB`z(ox&#dfle><}NYa|)t z5}%X6HbH`L69XM&0R)zkL*9M|GczMT26SIarYa&+#uSFZGb()erwD`^!#&fA5ehD- zAWqU2*=laH4duE!>$glEv>62l2@{5Yd$*l#2J4fK%uO@ z7po-zbU=&0?AQ1O@|2g?=_A?!|9_4NNcmnl0SIuzel@**+RhMx2Enr7c~U$M%1-if z1k-JwTBmfL-E%`(bqB1f!FrZ4WWrA9*){VMDgRwdu0WU8C7XKUtznQmyy@oOwgwrMg(O(;y}*&zkfV~bJsz? zDK~jW97n$vIcn*UT9HA%Cfc#J^4@yZp~+L7{#%H;HtOJ@d`zy>8e*bW_a-PylY@xPKrHQt*#k>m%v3hunhnZTFWWcBm7k9~IBhRNOJZ_wj9_hS znaV!q;K#jabW&TpilOLs=RpHRo!hQd!?JCr$ygt8#=N zP9wHZZDmOK>7Q&4ugfD3o_~fYM0*^+<8L~6jnbmFz{!hm%2PQ+b!XomTG|+JsQ+tl z{L%tJYF4bKSh^ll?__&Oo%kY#jszHNK*-%I;j{(zQXk%9O`a^OvO|`qv@x-A*?p(i zRfWs9NSdxqDfH7%zke1ZshZQ|p{H$d_KhNwXH2p*GcqN;R4VA1GS|W!j4&W%kWf2t zGupS^aM5$QM`Cm|I2m}|c(5Y2V7R%ElG#*A_`Q5NfD`d8sNlH`gzO(DeiKBvWqln( zHJ+<_mRAxa!FsoWf5WfJGiutCz;LNATV7vBKxo@bGjpYKn|~qJp{KMxB=9Vjm_Poy zU8YN63>}Vwd5T3utDOIF7hChATPPM>0x&rJRBSMyaf(?xyubnGj%8;fOdK8(1*!#x zM*DroO==SSf5%`=rdVH8G2<;P3D;4sDGim)Xr2dpImGiR{w1z^j?2~*B<4ODIg zFRH~D-=KWiT|8KbXpTN^{H(!tLIgptbPKMK){ok>Tn5eEkps4?E@WF+Fa$NO=(Q_; z?cyfSt7hqv@Jf8sPd*c}QGWZgTG#XIM4I5*av&#$!GBQ8vGloNDP+OSIrUXPkO&V5 z-1%bo8C5$0D*qSXli9<*ynJO)K{$j~9ERg&SeExd2k`mci*-N2ZUZ3eBACOc->`e@XO^0&DX%<`aXzI>>`TAC?HR3)_> z7>}gs&VLw&+a3{_(81^*P}BLO!LQ{wL*)>i=3ri|3_Ltmul?z%?AF%92C7R-OB?3S zKLk}Ja<%gUCEXrx?4lT;&p~%8Kv5(}+qD(R4N#v`Nrl5eaas4~r3AE@?M04#h)N~- z0avp;Y5_E_WK#Dj4(+a91c?!Hy6B)67G#l1Wok!tv?kuQAD|n<8g61kb+Ykj-T%j z27f7IXav09Xd*q}ZD$)%0+$CDjr1j7q?RsOS(kc!AzO^A*&2ihKvmlNL2CrzIy~9J zua$mpRSw@La*67A5vOtQi%7=nl~{ZH+b1k0m%aht&X!Q63Z2wqnnu5=SrHvoYHdJ} z1^JuX56NuX&=r56$qMCVI{6uk(@nDI27hmrp&4+{p?vou#Q6~al&1m;^$gy7)PO-! zn?a4L0f;JE@x>z^ib+=a)tfG)R?V)Au~W5ui829PLu|Yglifw7C|h>d@eUZK3)LCN zDbf$8;g(xl=k-4}Le<{w6YetmlyCfr&<1dRTA*mbxr}HE#N)q>HPG;PVDN*zbAM82 zwYa*_t$_QVs1Sr|%)l`ThGQ5H_&3kyQ)19O1YczO=R=?h^zcvCKwB%QTA9OE9Aq{a zACVEJrm$%^NAEsiPcwws6q|p;wuk)0lYqTAd{Y+oof&mT;NtBXNA+LoE(@lnZ_)j0 zYrwE~glT$AjdnX4^rHVcp9!nJgnuQx_F#o8v4=IGl$t=gMUO5jkEIwA>mHO`ppdgp zrnIEi7u8q=_Xm@AI;iQ2Ep(+0OT5?O?RGL36CY*7dsk0MokCy`>zO4TAk)dFBliJ% zMDYAp&GM0bOg_IOfDC{M^rWvSCu12@@wp~u)|M>de!;lIoE0k#8mxkGKYus>nD{^m{tGUT+ zCNU=Du(^anV&CPsaBg8KI)AeeoNe+3Sfq^|P_-NA{}l>&RjR!a!QKG&CC;~m-|M`$ zG8cxf&B2y(fUui5q)3lsRQ2qhxeNdRm zpEs~)v!?W+_Dn&dxOFAp>jQf=onprbF6$EgbMO)}887BMy98v6OMg4Xg3fK|WpYn~ zimIsF4-;kghlJ61me7SLe_pyF3Aj}<3;sxiLHBer(m>Pm47^qZo!Qy`Lmi(<=5apJ4BpeR)jzdDXgOBrfV1M$|bvDC#_3% z4K04$IzWFDPF#CrFk-@0ZmHY1OGnJ2qD^~t#*Hlyx~7=wJPmut5OsT_z-n@bTM)EZ6F z(a*rnR)Y*%&Y_H;>}?mxxUE21set;?^i82rKtlTPXj2G%HIq^VER=TmB_vbA7QF8| z4HH`b^#HxvV22IDD$h?=oSeXY%DvmWW65djp5wY_b`H#2u7or0I7<8Smr%bjmV6&^ zG?dMy|4(>Fy?^3EeSWEWVFsJ}r0OU?GZ(`JGtHMI;a{&jakJDB0pmiwfSt>Ps}1N) zVEz)ujc-ETtc*0?CoaD2I6zPJ)MQeFQY z)H{YsfPZ5XT|AfwKnyAz;TSR10(7rgh#a)`s2=DmS_GWza!8n5ab2-C;gJ2O8Yfb7 zI!NRFoLCvDpd6MHw7+?4LEtq1nU@XcVkb|&ekv9a5e1$2znc8A6C)J~s*~9$vW>L2Ncoq1Q`P#X!x%+W zSE-hP`cA!d6LDGh)VkKDTdOyP@TDuIr-qHbP?P-=wCw{G!&ueQzy+07=`SDdgk2;M zB7YYHsJXd6^5$hA;BS*>(ye^`JKwdEDgYgwZjxm*EQi>B&P=){U^Qc_+VCb{xLv;# z;{lIay59z=T9BA0w)1tn%#VM`T#)37k*So$RY4ksbU|zyH91TbBw@kEE~PYDv33-3 zFsK{J1i^VsQ4)%axc5}!<^}dThizMlrhl59+XMpKQ$c941%q-3P1T=6O&6|BA3QuC z6%m11Um#$SZ{hC4wdv*|Sbr%hM@NE$^0GCi=vU4WW(09(`|rC3x}NABqBs=J4+ULN zY9ssuk=s&=k;u3tZNfREgd2EH|L-|cG2(6fBSc`X&(W_~J08|b%!!um8T_*VOn>on zv+2)IM;UNF-q?&j!bQOeg4N~$_4cl*mP5zH^kdpZ1AkP_`ib3#A&4oFIu$lUYL>*< zQ0A3|U%QA0V5j!(-r+CevQ11xVfB~dG9bVKJEBdys-DoD^OpW=fKIomE4Pi^70cdj zADYjjux&?WS#FQ+E$o;)r@l>gB7ccm@N4u2hg0Sy7us{1IvNd2vK8F8S@qu!E&dO= z&{EYkIWLp!h4?=EBZu*{q4D8AW5-1jFI3#&*4TeH>hH0uyYI}k;Et&$VyuR7_y1lx z`}__u|BE@L%1b@J__F@MA=4Y$AP3%kM{G_V=VD^#s)~d6hOfx}#LF(wQGYo6X~wSa zqAUVHP?{G^e`(5@KaDW3y@{U^(^g%=52C+~t1c?s!Lb z=>}i2NE@@hZ9RfDBW<{Wy(=tpD(6$zq^?=#=fhc^$u^JviXOnkAJy5uZlSjjV}Q( za(ybwsu<*S)FSOski)o=e`=StpW)2wN)|u3wKPp1H$!`c)sffBjMG8V2_J*p(K+_M z81dgv>LrPRp>Sd@kH5gGP6X&>ls1(A9*sG`rL88`VGR%lxR&Z}FMl^zz^8C^IEtAA zns2u$;@VVg>Vs#2M}HG-3*KD_N%r))Fa}(*+Q%GJm(;M9v)_+ND<78O(q;?kH+W`r z!Whjn=W2XQ1Ww>_nIIv1z`+sp4|h&p`wdV$-KNvqIn*;z%R7wEe0G$0?1wFS#XK0G z=-_M)@ZmeDsT;8Me>NE~)B0q6TP=DSv)PDs7|Ex&&8}@?;)@xXgc6?EfUzG(V#8b17oFt7K#>!^3(4avMoDW&NrQI|tU z_{emI)p~unjm@>mD8B_y79 zdM0Mc^S-KpP=EL7Ew|7Am}Y~V7+@H2fl_b3+Puz7=eZ2S)*6K zq<5WzmKHO7_=KP>{KpdiK@QF*0rP3m;m^Mo0!=Wm)QAT)B_>-qt?|eW%ZNCAyRTjm zv!mH_1=p3C1HdQ}u1zdc8AqDHD&B`C@ZWb1qCV2qh$#jTkl5jJy_a!XWSbz(Bsxh- zy-=C{GV2uUxY+@s;RH5jQe73NK7$ZfA68G9WoJI5L-UQ~?wO zIXE^mld;h#e{FbWP+aY@HEzK@=-?1^a0wFJ-Q5OfaCdjt;2PXXa0tO226qnxcb6~c zJ@=ejx9Y3?r)72Z>h<)N+B6iB4q#VxFGmoN8OXxM4^Wd7)dq5MvH{pwI8bP4#GFAU zuGS73T&+L=3u`+NKuk$lM@CT!Krf}J0gwWL zLCz+20A)8*J8Lt5ytNq!>;hr{SU5NX?EdWl%pAbx*8k$pHA(y}W0Q7$~WB{0hEdHY1 z?Ccax>_Gr}F$a4`H&>7|K*7NrgfbG2g zr{UjW{%OamA|;`&CdK&QHTWkj0XB0mw+34R)Lj26YT|7E-@rd6tvvyHY%Kp;61IO`|FI1I7bPm{;OWE64&((ea{##kKyEH}03VRc@Bh#> zb8~hEfnEQR{qHRQ@&8#T5Xci`hO)fiU?vc1lkp?G!e63zx)PpodeT^faRCUuIMIEs zhh^PwWp1>0N_3@8RN#S1Iu&FpxOK8Ae{=Pn(j)s?yTGcKu1E z@UbD%@C;7#qrI6T+(`a#VC7HaoY{FtwX#lSf>=_(SmW~cUU@EBP*`GrOKVqyyr)ezn&-w`{bTxI`uMJG5oO#N2mu=VNfAy-Ctq-iWdjZ;pEw8KZ9GBnsB~>Gw{O|%X^{$h1 zkWWlW&e9Q1WESCxps-R559o_trFzCMP*cv-lQ2Ab$HFPwMzM1xEhT%l>vd$q$k)80 zF2DrgVY?kMN5nAhR_JE;41+Uo5ly0H%Qd6GF zo|kVSGy?u1S6?J5Z?7ys@^>D&&{-3tSe3VD{~{1Dv7p&8*5NNoUP0 z#~)E;RiB_>T)TLY9waiwU|pF97+qX0c@dBgl|y+%C<%O16A|>H>-U2s+bff|-4H@# z4U8_zM9vzZdvm7(+3*M!e@&lDB1+iBUY@Xr-%55RxZ>a;UYV)>QVrQ0+*7PMwreYo z8p!H`FjoGr>m4Gc_nlNBvgj_!vzLjyu(qRi4m>ftk-w}-zwnWxNZ6x#J#cLgZk;bv z-_zk2Rerg+$q=rjq!YZ3NT6dp9BA8oDog7Qu1}%C1P;{*B9-g6f3hr!@RLk?J)_&> zj{36EAQem_0Nwf$&fzBuQhX;JLaEnd9f~;E?mAx@3P?k>vnAD$!!h# zCWUL+;HHd4KkOFzX8Dc&B#TS zOo=^i#YvXS#F7Lx14-5vI+@kKxh+WY@ z7OxoE#@+hDdT%%4&7OJG3;4G^8K3mBR&9{r2sLwxZ_pJJLB^CzuNHI=%UoG=I`0(tO>RZLkE=+TY=Tcf96dY^)iC3Fv^^8p9{M3 zQYjM!-6x+JN3r0RODL#-y1nmBPMz6b%QDD+Rm1SiYqd<=*Hu_x9vz!chZmF&78S0ixu;XntjCbi`je^*uT+J6qJSLy#EMMHIB9Es6SffT2C zB~|GlfvSZO3iIgn%k3PBE>=cx)aZj)ttg4UpvC-D55ElKLi50ZLCrSAEB=@2D<+6s z*f;2v@a3gYdC`*uvLE`LHTG3_#pR1iYbp4-theZ`5*V<3 zazGQI!jOn!{8PvUIHqPO*Iyw1csclCe*y3O6@9TGevHrK@LCFkd#?!IkPz*>O$sN; zWPnymA7~;@8AzSCEquKdUYZA{}Bgc(7QU<_&p zsXdcv@m*UNZO7&e|DrQL6kZh+e}H$-;oVeW+N!LMSCx8%I!Ci5Tlby8P8{^;W;g4n~^%_ zx?%$=Ww1N-=%pu;moGh!z<3I$(TGQ5H&s5)KtJf-B~#A3j^8Hl3pCdp*=&B4iny=D z;TblJjgm!CuJjIuOzE#Y_z8sE$q4to z^xG}1l|g3JPf3R$m7d1nB2#sIy>qwJckXCe+khbcjKW(dz+~RCchcN zUgM@kqR!Z*5BIX$f14nFw3TBFMkpajHoh;bPov$(D3kE6EoN1TpVOOYt>Otd z+HbJY6ysRMf3gY~Qy>k(Ra!HlH^b|_MKWlU(<&p&Md5E%GZC2_F>i}FrZ2W`HVzds zRka?;nL9BvdfKvVeZlEa8&PMRD`S1iwJ;z2Xg+z9B<5QWf=alMP5<&|#$D2ukLwO| zk)gTG#!VV;hb9&H)9BFIer0W&&_e_7T=%{QcxSVNe{TpoZfh2vh~eV?rlfctfF?n9 zWc2a$#NnG${p(|!67nvJ_V6m;YfkeO0g&0YZF3;&}WIm*Jy|gwRZKfXi zThn^3PX~g~tj9+x*o(P|k;MRQQz#esj-+x>8RvK70QyZ;Ora}3TfDJb^OY=$5GF8U%&*m5MYQ~wi$ z>-KKL-*@t0;%k<}wJQ^=F;xx9D>aj=f;fzie_wz9WzNEJ&6uA{*pQs~<)LC^*}PTU zhYZY>U{{?Ff)I4oS5AA7R+nAVxyieLO7s=NvWSvY_7T2%=-P;g3a}ECvUVBx8~fP2 ze+^%6VNhQDM*6T>t@U?R*-v#M{O66$-dZPv@oKyn=LuzHz_)U+hAdNvr!(#|4qo?~ ze=|?PkK75*Ku1^M_8c@q~jg&JyL3%Wl?^1++a zVwpijNzpJYUV9O(n49O~4kC5dH@`PeIjWOb)C9_R-L9r#s&A4-TfOpd%BbG1&Ni&J zXkL4D*TcuUB=bb!B?Y*NSzGMJOB0>4e~Q}EkJLEv3|$yH-Y`i(95i~_f}Joop{igH zhnpzj_etP0`wcK`xfUEx!XQ30$y(NND-7D9%$}w}kI^Mp-Ou!}VGCTx9~h%xK|*|O z6&6v#nvKLYGMyN3u+eK~^0o5-Tx?#SD$;|uab%p0pSTh58~A1jCVI$FR~WmCe|>{v zAN@l5hS1iBi#`M-WzNFY507wp=TO8`)_VhvfYL4%=|g!`jYtUb(j-%P8^s+YV9b{* zDmSOR^iPwS`z*UM2#85{NGyJBRd}?lE4fma*0}{QbBuAM4tp6CGV9v)8z1}er-hM~ zG5A4F#o`Z6gqmqT-8+?cQ>-ooe*?43SG>m7;K3`~R-qF(PgefL2Xp-zuN=>c0VbH% z`W8kK_MFG0J-SxusQr$(BRiLox!BgSq`JTsEptsjIVVu6YwT`;hq?W ziGRqACOxLmEhEq{8i&^0f7Df$gldCxy-rhoIU_wW+!BaS;kETZ%4In?}-a?_U+_w?WLiz zq~LVKV@IC0t@#@Jjoa~u&MvyrKof{kN;MZ%*npjtS?>V;$C0Tle`$&Gn%nUwIs#Hg zX(}N=4!5O6tH+hpFx?*8bO6w{ysyLe0ADrcIT>{2P-jL)+JhF5pFi`Nwd zkC*OoSR}TKmA1!-P_)d-y{)CSTmIh3$cQnD_P1Axox=xz81sctbU?=UGzdwP@7FK1 z7&x5Ux4=vkvi?6Ee~^C6KjxkeU-oPy2}*<@kj=5KDLD>VmE4uP?usQ>)6IV)6c8fNmlnT(MhO(uZ`@8tseJR?;5Ayon_$Tyg(M->CwSDTqT4vT7?)D#_3 zj~?8Sijv(+W5|iTzIF|-f9wpz2tQHA@Ju|WX8_QzqIfOcfAE;#ZEMesruXvlG>ayD zh9};-**pQnV?CXM8!-RTJs&Xh%zjs_nJ7L-yht9JvvMY;-03}2HZ~sad-Id^jU~JV zI(O3M!NQnY0lehJ=Ah8_f8Sz|(N8>-p`p`{mfOs)YwE$iS#0kOg z9p~_CY}DsHW={$Fh1kYLHipllSV3x&MI86Tq%=0%131$c_w9#$(ahdOmUd zIlj@_BD0j(_v0%f0>UYLbnxWfk6(QZy+5*ION?N#_PD4fSohuOi5L=&^a<5uYj${`1mpGj2{jGm zCV0>se;u{|){#mYbLXd`$r~ZbRM{dOCNmVo?T*44zz}m%`ph5QXB!yK?f}h(b?=x8 zA^$vdRrLh(q5i<|YdT|mT(oLsY*0^=#C@8d+@HxnT3af$vnmdfu&3tArzN+ChQ)%i zh{%DfQtrLSyL6je4w`zN%0}5t))yAV)?6xRe;?rW+pj@u5rPIp% ztRbIAkDyXJyy$}d2t{cd20JK)LG~$<731#WxotEKvTGbX5>yL%Kl<=|rto)%+;*bP zbL3fHY%}#pgP@}<;fQE-{NXdrrgPz%%-lN{_}L;Ah~2uzz@n;UXopO)go;vg7>bw+ ze=3cqJtQ+7h~AU}!%9V_)J*WUO(i*wDfC?fCj15QQCb3*^L?DFfsN*$&2w#A; zPkyHTc6Ly9ke4_`ao=Riylt3iir^A!EPLDkMM1+Pqhs# z-1^+Ul(0D85j^F`vA6uWGr#b8qR-C_e~xK!f|DbG^9OVuTjV1I(4?!N2rXpB@TO$Z|Fi@HU7E> zL(l#a83BHUGI%sGvNqA|X>MRfhA%seJq`oht;-CTZ*Ax6%Ex#HTEwEIKt0ITe}2Oc z*KcAzkCUC8GlmA2d$=v*3TKYY1)Fqq%iERAUqNcBF+cd{{OZG9-Ytm7N8MybK41x` zt$ssXE5tonSQ6mD6{uE}nP4xv&nl6?Y$zWZri!}NQ*U&rvp|%}7#~&IE^*r+U4E(Gf7eb<{Wxa~t(4k0eCF#y3-Og6=53~wBx{%b?!@gF z$ltsufm)MU^3teNqoNEqg~v{24|QnP=y!8#QMwipw^!@btAA+oyA|=RFkgPmxjwuk zoVTZ$sTGl!CL#g?p0*1g#5Gje$Js*`gR4Jz)%!HnMVkFBx}@5XY2jFff6ta5lN<)> z!>;d=YmMD(p7h7WA31=fQixYnKCDllVv28p1a%C*Q|zCFA(EQ-ETPMru9u1r z9#R}$5^z1fE?!opJ0~YcwZkW;fZChKiyzjEZvgMP`vq-*5lZp(lq@XcmmU-m?Kj2nkDG?# ztJJW1S8d-I4@RAt@rTwcx>t%tDeIVGZj7=FYE8zog|5NeaUODp!8dwlmctw6=FxrRmXI zrmKhmxR>W_+uqN-7p3F&WLRA=H{L?fnx*S$zj`-lL$M5#yOj4Z)ZW)%M#?NkHcW?k!8sEufiHig?vO3taV$we>Q5N=x=heONgT%;>IBW zE!*r&6lXO}BVeJ6#hCjWm4SZ(e^vdkhq^O++UBI%=nKiu@JoaqN15ek+7wvF%H4un#Wd0JtW6x(?bCHRcZKpmzj`px_6%V=uX{zLDP z3SXYv)iYju-rls&Py#eB?~gMRj73YGYHbGiULg}($Pd{F&h{G4z7gqO1$@Jmq{x*-&v}I{hnw6_h}7KONOa)K$BmxB&8kBYA+$k45IvmbsV1VG;lvkcM33s zo*}td$ilSri=*4Iev&uyKp_z#6dq!t0{*8~e{|u9>?Y`WB2o;Rcx0P5$3wV&9`%Ov z)WDkKiD+pzFML*Y`yDg=#Vw_l`lQkpsJTfjkS^!iZ_i;@U0dh!U8QrsEgiXn(P>n2 zpAqe$@0tU_l!!;?A^-P3;nq)_J}#Z8YDuNL;l99%Jm)F=WE#vNK7xo+!E=RT+`Ho2 ze*vDTJ)g=8^go;~0beHU40Ma9)VCVUMV57!o?+0OdL0GQUvQOBeW{;`CL*LUnyJ?!X%GQ;0sRTOV_&`V1ciC{?j$YQ~6bpp4 z$0`G0d>dcyVzCmHNmf$6mF+oIA_|A zXEangZ1l|C$1*YtnXmoU+?s>Z)g03*mTgzWA4*uA^!FBMD7sd=D12v=6}YD-e~)b7 z%1MO1m9H9(s|N#j_&>5yk<_oR7pr(7FUC0)qXir7@Rd3AnqCHvV+%vQ2S|P7>Nlko zsa{|IS-=w7^D&~MCc2gz@Wa8MVv(R{KKF&yGtmSm0Ufq$l4DXi0!2|6q2THF7%$wK zPI@qb<(QqyHwlnue%W;wul!@(Lh^E@zf0@*L!9suN z@nI!^c1C|6VA%{>&~kO`o!#l0Gh^JYT7_n;%5Mq{0g@yszmD8zZ9kFh$2LKxre~;p zgdykW1l~|PjWj9ur!~c8>(0eZ4)Y&g(+iWyP-auP%PzL&zp@F#oiK$Rrbsckd45#< zDYjzQA?x7{Xft4|KQM6peZzM$Nkhr%MBg(4}E3rVv{twG&VBbW%*-qIVQAr%?@ ztv*DjeVKZ@fkL-Y7U8G%06Hs|5mDdrM>5j!Ds6)@f6YZ9g{){k-5Z>d zP>jRjyAPCzCkQ{DJmgGTw%AG3MIU|O{2zp%@V9iaFCf6UYGc49Qnt;+lJ{`t_8vy0 zscEu&{}`_fUouYg2>C|WvkF6t>G;B&dxUOE>Z;)TwmqN&k}I6jwh>0DO*c2LEVL63 zUts%8@cu@#sZ=wxe_hn)^!ACe)^B#hTK1Qpp=W^O)DFH}bc|bptOtM?@d#YYNMZiP zVe)(~0$yDW7tyWi6vr4e+Njo906&ttp= zR|gHG@X*Ug9AmoQ=vlL^)4kaB)!z&8&8&V1`>nIy*5vZzPhJs1LPx9?#$C~;uim0> zI8S=5UP{HXe_q5m0Gpl`tdfgjb9m2*B8rl-vBBZg-C@Id8M{~a(ys6P8LB0AOK#QW ze5l@P?_=Y#>Q;uuGI=nGa~cmJ^z2=k$vUg~_A^Zcw_^v#%0>s!b=r}9oz}&IYDC{T zlb^9~LD4ydSzDg1?<^8!&qy;MD|SZAUwK(P<#YkTe=fleaLM1-KOn?e|G*GyPQaYV z>BuF;M{t#;@9Q+FRT@cT`w{XX$V(`fJvs|fAFLytk@?hP5PLOyK(JY)dbr-R1&%yt zX?7Rn?iCU!jVQKAgX$D*wJMFL(%`_F-|Y0kNE1*0C`l#o3_8m$@?eq5-Fa7Gf1;K# zpN!oCe?qA3s=T&-4-0HKzw;WX3h5$!7VxfTAoR@?H|qRmJZd+`Ps@_yX;{igtHyW% zz9tg0G8P2m#@Tt3XSJo~vdT#?*l0-i5_HSOvao*2m}=6QNcN)lnu7!8(f6H>I`hw| zuHKr4nUN4c-U?o^E=E#HxEBVuJjh=;wlGwve>}&Ad=A4Hj|7`r#&e7pKJo579Y;)0 z=!3+XGeTJu*}dG~ru3LUi;;EMgb;-cD&r9M+p@iD7yJA;!DiMd12RI|5J53*xHgT$ z%`oyTNJIN>1}z$#FKOQ$`IC?+#ofOyx7%}*rjBY|E{D$Jj#xCGGLWX`tJ)?^<>`(` zf02x8ir_yU+$saDM;7hzb-drMu#cK__0KluZ){;s%%C5QWxfmW|JI`O=p=94^Ebra??tasx#j5;Oa|01Q z>RF(UEf?ien~2l5f~YL-Y*5SS(9by4T#5&VR*EVjenh2skXz+!ha%p@5b;a#of+br ztRL9N!&vw!>s=e?-fejKf~v@{l1tH?6O+0|9=~#D;aj0MYP%O6l7+@Mvt0Y)e}}BV zREAFYmHkM%CCEw5fec`+tXNcp+Z4#+z!zi0m2x-wO`qa;@I&60@Vw}`>dwm%i~TRe zPDD3cs&L~srAF=ZX=T7cA<2NdEMX$#-n(&OVlQgj$DKM$EE~jS#DECao-9`P!PlI0 z)>M78@vZfI2$~=m+Nl@b7P%9re>pC(sAnTAf7YhDB5zVkQ1(EQg-TsLJTJ+sPWw5@ z1!N;1E$D3W1y_|-yoO*VfM1^nk9rp*jVf!)&%jyTJZw*aPEujwQxPElhxf3ox%E)A_+ zlnMrG8_RhtnJ`oov=;dD;VOT^${B2CDgx zsz6b&%&eN2$3ve_=^ClrRN8wTH7VU>O(Nzv90n-Xx zWTXKE<^Bla6(ZcbZAIz=dEY8d4NrG+@|4H0s)}k|B!-tbTtTwb)nB87(}BXZvoN9e zrM`%_{oFueE_+qww9qd$AuFls%cFFboZkC%b`C5UQKMN-*bIfj$v-RjXBnhu02<0x(}XURcet_>9PF0&xy)Qml3#$ zVu8VU4_Jf~=LscdYKgBi^r9%y<23pCZM#xBC)IZy6=NVP#TSiF%5=v26x1d2 zBFXeI`Le4%18H4k+P{Nz{SE8U}kA!3J{i8(3F%D2T+L1sRG1J z?M$5vZ2$_cMmCnl02xbTQ#)r`%6M&4wKjn5V&RqXwn;JXW{!e!_0GIz-HirMTjQ(r= zH|pf^Z;K9wkr7~GY3u?pGBvlfgQ5Q)-X!hJ>;Y{5cAL05{3rAeAm@MZ0Vw|AkP={G zYW7dItBsAEp{*%^LfGEc!PUjo2_S24V(MfEP_nl*w14|gmZ7bsjpzSw-v7yvbTRyg z2SGdYf0$$Vx69I5%+kZuM8VSKAF9m^ZT_L?Uw(Ddf1iu2sfnel?Z4|y|Ka1G6E(57 zv+?{tTmI9=zc!?omXnef6QusH0R9ygwKKLiv9vP>D7*Z_rJ<9_e;xk{D;Qe-TRr~) z^B*+<7=QooTGr6T$z(f$a|N}jrAY}swtN2yo)+1$8ugIamE;fiq3v;#GQn- z#lLpql)B`|Sz6z4rU%ruh;tU9MK?zLulwsD;RV5aaJQsb`W8i%feuIEnvbj$?VP(y z9e=cU5+uo?w8-FGo?v};sM0AB=?Fw{lz9OW#%5+T$Zp8+PU6(B0zn-&qm(Z|e$&Gh z3S$w77v{OuXBenJa;EDX8(BRMIVo96w;piI|>QUgox z?QvsrHXZN3ag+H%+5^%%!-cvTDp1kqCx41n^q~$^r775`Gu!e$g($FyI>f-LI-g!D z+Yi=DSmQY!IOyI~q(gI|V;_V;Wrkd5cKYDAVGPD0k-eMgeM8HrM9yIa)YgAD{cuTo z7*HJQ?jUy47Cd79&>1q;EDxvCFM-Na{(K2AH~{n5(T3oagqf|F7EHDCdR{mQA%F8I zw_^v9V`yD9CfyC~r!8yswUl~}u8Qnv92OS^Euj077szT|?17yfMjHFX(6Z8Wp_=_& zt%UW*D`VzdxmYh_S%WI8%!T!=W}U`AqwZ<)$Ko3J^|vpUwFS zEi&PrA$QM?{zF?w9mv~%$`FTJPh>j1`od%AJ&Lr=24t6bgQqAd6eU?x7W;-zbDxv+ zhG4pJc-{NMGLd$fEcu7*PQOF)_b=rj(7*VKLQ^oF`J(5{KzG8P5rwi-b$`I_3mrLX z?Pk#-lP{JJv6%^m!^=^zkU%doZHJpdt)IkkOl7H5@@lIR8r)eoe(VW797M@%2 zg7b;5xcRnL6J1|>sKu}7Kz|-b=@Y+|Gj;3A%O}uR8Qrk9bZj;sryb$QlKW+4Z>iV) z<&vXQ_(-t&>rd+O)jT>-?ytq|cvHiUw-qwHhR?!@+_Ad*oFy@5=Zc*k5 z9=!O2G-m;gsreB?qNcVdl&n3CK<;Qv5;1AnSSS6n>`tRqQL zw_qU2#}hL+gs+b#k6MG`=&}pO$SCoyc_^IlojFB>3c5~L;Y)Y-nK-jmi|8s~#t#}A z+Rh4bSrjQc&J)#9yj{Gi!W0Wbt-leXf0G!+8=MQ)XvatdU_(C?7SOUk|LL423hu?lV$pZ?e6BBL zShRwwW4Z88hKQfB_ zv^!JYp|F>-M~M|66*`un2>!gLuPii+Z}Do>bTF-qr-?{+k{p9mhXl%7wAIel1XfKM zNpFgHyFIALV1F2I9h-G*NezpkgL+-2FMhwvUo=nhLw_6~@!$io$ilSA=NV}yll+3y zZ2Pe=8^aZm8slXQjzJp*=PXpgzUqieerzTWT~Y(|56SqHzyl%m&|yMI_VbRnQ#$2cH&KG3;O-gw#E zJi^ZG{d&jF9rDicD<>MBXssYm*`_o}dE5uZcFVj^af1*ghmj#uxmP_c_bFL@vXdPZ7RtQW_ywLG(w6y@QB253vAZH zY1BYD@%8W?5t@Dc$@&x&78#rK4nMB6&()kkG`^Gkgv)iw&1kqPZ(9l)nHi zW`FIwr>%4b)Z?h{u>Ee)E9{H-f8q|jyh<+koPQ=x`FFP*MoD#Tt!el>8 zDsP|gtr!bN%D+38zde|fQo0%STxF9;6V-&U>R*2&BrH>LPn1~n;ML+Wm88#ge9Bxv ziBi&+!|jsg`N;rhz_A_ME`4WO*jXGO=;1^Hg{)k0p9~SaZ#I$r}o5 zT1{48zWnY{25m;si7eg>bbA|-SAe6o+SS8=Z+KlVK6xNah1~ti+X|gTsX{qcvAr!v zWD$Qr{JW)@`Y$hA6_t=o3d&ln#iT2_^)3C%mf;=Z?o-2Gu< zv14Pu-f|T(L7)qX-F&Cf^`Ib7>BI~vb=1mgN8?-&*NcjPY#tK7+k(Bmr36Jx_ihDr zC>Uh*B)AWmaMJiVS67o2aEEw%ka^>xEDC=lFE#(W13|rIiNJu4$uO+&52E>-_2hhb zrA+k?K`KdArddD@Gf6FZR|-Pjpd-W<te1o*Fp+Da35{2oMU1?Mrp>K@9x71QM=2ag*PmP}BP4&U z-#KtPaJkaoN+DVS+nJWcZKGR|m(%n&qVMNnf8J|^FJNT@66A5?74dxrrsODa8iWE| zzd$Z5nGfv)put0$rr}Qn{(kFZK~qn3jPu@Hp+x0$(4-L?G}#&*_;;^Df`y~msLf*n z{TvWXaqa$g|{93vG z}6rIeX@!DZ&4g0h1vb?zGh{O+XHGZ%;5vLm)AS8toMjwBm@F-flASDKs z7-$}&Ls)+J0SmtAzr-uo)ubTkLw}RQG)8;*YrzMYfzcgIe~ zQRZC-jI1AuR3|V{N5p^oh)yHQ=ohZ|{OAR0LLfUhN8adma)y0HVUW>M0YY8BJyT&Q z0ZE2)_=oAnA1sQ8Lsa3j7a@JQ=3N$$coXuA-_PF^E>P}(y^>B3N5UOw}>*MKFWqP$o-qKo*d8rf$UUASHjfIeq5$t1GKc^qYxi zuO>g7z_yI|ps(@=x74&gVUJKscN^{hq%`??Umcc$>pCAUNaG1$C@GA{Xks`})1W*G zR$71Kp<7LkLD@x+9IwJ+x+!GBj|+1hRYJiykex9Rd+;F=ytWMxS)?ta4X0KbttYv5 z98A=?h(i*z`&oaZzRW7{hGcd_f6&KyaS8U^nv^d7p(t{AopFHmM%0-bx3{vA$8rA%yvL&v^x>AUqx z2b7kRv|@+KPx#YY4w4_s={2-1NvlNnP)EI(d@8Z|IX>g zsL$0)W;Y$6!V58r6HEw-qSQx)hQF7G;6YidyjmAD{v^5T8TuYPEun@Kc_(xqs9-NQ zb@YF<2;ysS?R1I?4>DXaMb5RuIg4{^PnS)ObK)RTC_(3}#2U{vHJxOW+OoEz2TRb5 z%%Ha1rm1oMXCn;Ccb}Tqm@ZmLta`|5x5n}g?rq#oZn{*;7Ini8o=e>TpmVVR>EDzks3 zo}u_H1wpTR&z`to?nbQ6D<4Yqf}m-h)p;x4I|dbt?OR=xvHJXP@4nyJhWUE80rK_Z zI1JQORrYJyT>>8*f$d{q%-s-Mp@sCZg)@A7woQ#5&SOk z3w-TCXFGrJ`R(sir`+B2N|yR`_N#}x4db~f441Kj2?8d|0ef1KbhesH4nGhi;@TqY>Yh|LrSW>%TpG0{b19D6%Pv&qu+##YE=FNjLrP_0htCghPt$m>~2>e z1D-n|S~vOc#~PX%A0=C)hACGsg!7i3n9Z{?Q{(He493PeSdJgW^pl69lva#zonfzz zFhIm)Y{c20CmA=PYzMniFcyDgz+7YU=cbTz{?Gw7Z7DJ;H2u8#TLN-m8qH zP#k{@#8Wui>jPL!I`i@*z5~i!noT|RT?0bY&6Oee=y6#88lR>K1oD3vy^0GveMb;u z7VK3+p|NiscOC~H|Jn+kqUH3Ez72{}Y>w_sLV$-PQ}srf@YE)*SF729cv@yWTj6^A z6N*WOmTDQ-%BCU>0XLl*#rqlGCD4e*yIs{ZqWAM8j>|y2iG2WcaECO_5WEe^ib<2e z-=UT?Am&R~)_bWCoX&qSIiS)aXUB!e*FH)@zpIG0=;<-E$FNx?G+Ynt-0a8?TS&kA zVZ8SSVn>xm8dW1439dmf%|w>`CcXR{UpBv)&z1o8^6H3EPV#R@_8Fk?$z7LT!o&F% zq&U!#@TRPdhDw1=h;O=0^xTjoUa+SC3I8rWP`C0kaFZd<<4%9K>xyV1vI>8tD?+fF zXiJRSmDgm$XL4gJ`O>U)Idzi>1&*`LlDz2cYNy5H@qFs zsAU{)HX3H`tEPV^Dve%CJ((Vvn`I9z*9Tm2P4Uku#o^l26TRGCPZ+u(je}o5qWlMa zbhzwiAhV8rrAwY+`3;!Y;%bpnsKl!Qoqogvz3IxLTx5uwcBck01GFb8H2oC1@F&xu zgE}Cs2nE(37(d^nyYjW8`$dBelh!g+%@YBA9{!!hU>tu!%a{J_om*BvUA3$tymq+! zn`W6r8wYCyLTUBDlNETYE)GUv%9b9{b$>_-S;}^q*Tb3f1z!rBlg$>aH+PJpDX9?X zyCl1+UM<>HnhXI*4He^7SQOkXcKda~Ja09E-YbIr3G1@}-XBPY@PVTj!WR9WIN=J> z>RfRR_5pvKREY?uzx3K4U!mL9m_TX{+miI{HZgnwJBN3RCAVFv!%~@gHsxBeaHg`3 zLntb%f_BnUi&9c4ie?{nPW(CD`+3J-NQ8|Pm7<=`}FrY(aL{rWnZLc$p1tOJDzKl5jZu@37Z$* z9}{~d8#`N$I^}E0bgr#NgH_}=&8m5n-wu5ffVQAxDQWG->yE=A0h)*rSosEm9Ct;I z-j_M{(n)JQ%bWJ`twxIM6B>yMlpT=|a@;kkS||Ox$ydHag{&>$e8| z&_y4BQ>-+-a9cqwj=P@6*E42xs(h}Ci9PqN+vzhacyH=jhM92DSBHE^f@!HQ5hIh% z-YB&*+Esl?9H<4mFaGh195TU{R!84=?uCDzM0h9~CreKtyd#h2Au0r)QC{4XDQoTW z{i8D?{zG!f=`vs%VH6Ea!17HZCg(NWmOW(}2qJT|LFH032W`CYF(t>D$K8b`nrqB1 zhco^oE*z~JAlSzJf&_~T%Kc7$czTfagRt^e$O$T;Ta*N5Fxl!myQvkSyL}dui#dNO z6J#^gk9k??)-DVy<*DXn7m9a37+EOb3h4`~gt@12uA=P(<=E~y94>?T!P$7nLFe6X zL$#%daYuUNdP~gvf^kYM$se>+z@D3h9dAgxDxjbIc#&{GGx=6wbCpn94hj9bu2}RP03Wcy6+Lpz9v}oU`HU-{;JZhC1MxqnNwI3Bw?; z9V3f3{NyJ%pj$mUfqO~RI{?|uNG%n+bf~Bxi9boe>8%IPp^PR&+owql55j*`icwVh z{RUDBLLZ9#q&}&S-6z`88)Gjx-GQz6AWC*`SW>s1l!FZ-Si?m|SAB4}aBqSks^0&@ zDmp0yVNVmOeisb63t@}g<)iBoWxZJsi31K|T0ow-S+zk{j+SZ^rd1UbUM)?3f8c3s z;uWzVfE_RcVCG-kG1lnm#s`0zWrS4G3tQeP00O%l`w=65`A2PSzF>4NxBxWOCVQhz zg-v2#c-t?=Sy;x7*VP)BP6|s(_C|toY1nW_VRKSRFp{4!1J7DvF?hCC_2?|maziSRpShsV+$59WP}uN>{@@3i7o4Ha=SS^ z=*$$H)cU+Sb!!uz8Db;=wT|4FxGN2fC2>3QKq~7<>g6&?q1FzBw-tJ3Zhfm-UxBmL zYb{)DAXTt>e$`G#iuArSTa!WSyj+oBy$1WxJEsn_vXSV}J>Nr4N1I&@@U$JZzj!>ZB94~Zu^||c2@YF>b9h@#LDvqCO}de5YK*k ztwlEP=$c_X{>Kx=FHpTo`$8?Yn*#aj#7{pJTaSxqzfNu^4@p&j9lX1QV-L+fZx{|* zu)E%aLc;Mx0`HGs{bzOB@DE`aX7xtABDkJ(W;8To3-I3bSL%Ogew;S@1{avBNF|Q@ zE_1BvooNdF?mwCsKGr6U?&IF`8nz7l%dp2vC2n4)GQ3zj_FL4;$a~73#5nH{N?hUO z%2Vq?cS^UH2uqa1ysUFUGiY#}YiTp|Z;D`e#|6x?%Bk(-)ub$p#)T zZ=_u@RdYG{Z9soF5yUV^MrrNAo2JDqPjyHbOSJ_&P4&GD$f#s)Fd*a*f7?;DyS0YkYBv?8=;&fFyoyQbfTHqNPX}#-V-X_j5YvCz=~|KHd$+6}yb zE^)!KMAm=AEoH%6T`Y37c1MY}Nb_PWu#Y3DBtSZWcQ$C^@@!`#MKw%O9lD5XojJl? zFK1m`DT9Ui3{0N&V4G}!zwe31^weuIm|xLIYPZu8aL~_)(&EHZ{cJc9&{JK?z@MhW zKz2AoHq62BP=6v|{Z7*DtB0rsDTutcFXQWYqJV$HdpMHbXjmGjL%s+Oz`h}4qr=O6 z&y*jHQGzi~bJ^{wYH~swDlc>`H5kVkBpqs5tl1A?PyqOmj#R8W_3+~4RyJc!18pKL zkgGV2)0}PN0lP(shH22v~jybz9 zCl;>a04T17py(J#QIS0R2a8xOM4z87I&FU;PAKIHI-OA!P9sc6@|73f)yg!L7f zN*}>zdEeyPes1q3gYXwe+1#6TI~wwbGX|{RvxoYJx%^GjhuM|KY5t*9RCOdnyZ=F50oUwQ@f|i6B zy)>qysKXfr27zak{qi=!uf#9|rM_K0ALoW&M^30;=?8&;wL*4oLq7;41T}wtfp4Bl zw1BD*(U8~yk*#G@j*~1>xP?lG_WI&=aQ#F6 zYq}dvn6wc-=``J5NqcRWW>J5Rqbm(5jq>f0N@wXh-&CpKG;^}mHCFM+?8uzs)DZA* zB{AeiHr47sOScYo>;(p@D>?wxW#gV_7scM}A&;ln`QI5PedFU_Rq^4&kYnuzbaS1y z`;=13rJ-YAy?6`VKBb25o;`ub_twYvV|Fl?r62+efe)x8Y0q%YU<`j1^jw-=&G!Lt zv&9b_ot)d2#Qrm_nGGQ|(;^^Veo-N?!UGiVEY=%8dp~U#+7n8x3HLI|CK5ghWZ1tP zZ%zrom^=EyWmyB3I+y#T->9RQVTzYLRL4Ck`WHBBkuG0BG=0@1z0(*ZenETsjA;H5-oZ=b-Ucy+;2zuhWqzI}33vrvPxhQ^wMwLdl zm<(EXU&*H;j00szJ`kv{b;0#YJG}3dw%t$5U zLup%*_TdM;4#4t?=Nx~2!{vp{?!!z%x$S6Wys&>R#{Tb{A{e?({hxOls&hD}c^72* zUW{Q>N&oNLdLDoQ>dQof?h=|YeUX*oVul&LD);q_wsoPc21RLVUl{qdl$^6vg4b^0 zea!m&pJ|Fx52%Z!0agu2m3XeVt!afoQom^`A z-Fio5Cap`!w4250xWj~?zF;p5O-}lLSQb7!7O~K8c#49R$i;Or147r%>twZ4(ocg4 zz3)dvEPQH6jf=ZQ8&JzYyH{_-q{H|ts4stUlQkNuRSW^$`9EfV)&2+!Mj@)a+L}Fy ziOoNwF_}WpGdeH0kD8pMAtM*DT$A(BeB7lUI-q!Y;hH}*CpggoOb%zgpE1ztGIkz6 zKm2M$Me;Nj`CjEsDIZWf6Gd<0)gY;kr3qz!(Q= zClHQ5Kjzq1mp|@a1?6w+=^=gou3&-y^|uT$o?q&YUZZ{7m=S4cr?%aeoxM<4RL|Y^ zyE+g32hY^GOf&w&GJla0hqWJdD6M}@OJmj@cOCHTdWD=|C>YJ((6P2H+PZNi^wsDk#SgZ3w-`PyGD|9tvG2;UDaG16mX*xTtdv!n!Rf0+&X5eHhOI6QU_g{Mgyk38l7O{NH}K6~$>N!OAGL?e zYOaQPsB+pxFePjn`Vie3M`UyQ)h0I%*0O8%iShhr=v_6U)C*JR5e0u~OHP0Y$@H(`mI*8>bW{V5fDdVi}x7 z)?JY}Mp`8l9M6(-W;da+tcO#3Wd!S;q_2fX_E94$Vp5xMNjb~k%q8}g9ZLKkM zaFw|vI@ND;MN&WU1v{_CI`CCukoGqr6UO*I>hvh3#TNJg)FpquR}ko0?z{nHfL!9% za2U?gE&hmqrj(&g<-*7@4J^!~PggkNb&+aMkh3Aee8E_ZR?#sFh{vDg6bhLIgW>2q zQ|-h&HIcw>qA7P3=%#*40V^=cE$imQ&)JwY?aJK`+^)w28$IazlVu6l91nIyZj%M< zC@X~U%XsE-;}U-uL?2N>ht|zW-brg;q`&OpC{Gfn%$(x`)P$Aia^M-@kA^OuD6bVn zvIqr=-%#AuTkY|#DvVtgVO*@?GxK)MKI}k{UmkIkPYf8^Ph zsTvwRGl9AH8yq6%p4TtJ4}&0eQU)&Z4j#8-O_2QJRNjC2gFXSdG$12+6Ifc_B|4qb z*wAEblZ~sWyKxJo$*FIjFI`CRrca$p4A5RYK#co_}5{JD6c-zfN-rq52*447!vZnUa^ek;^B+Uu|Sxqn`eOZMcb+{bMkAap5A za8pR=&{V2)qQH?gG{A`PgUE}5C*P1gvw5d+~fFqu> zcHUzuMt`sawALKmMFui&``Uea4?hK3kB&;9Yya}KX5?kJCCYkvpgy}385rSn7 z5So8r+@K!L`P4pl5W{ZjKYrPf;Bo$cE_V5=)at5iiVvrIq%(#05w>&D2x(B!`XA!(G7!8m>hLSdQ`Iy>W3haZ+*DY<1DQ>`Aeq`gBO!t5Ov>@1$-qmlr6nETWTG zb<+Hd2=VAVss$IWkVXBbP&OP&t={8%Y1ye%KiZ6B=+4WADLt^@P;l7GAUDQ&=u&?P zmp6j&fSZ0rl`U; zI2`mHnQasDSO)KwHBx~G*-p@C0v3N7Zqe(W3$+LEpjSPITwt$Pat`p3stgcwqaY`q z0HHPfnSQGCf1oOWUWzs{odmy9R>~ajtlhB}QmU2F(izwOCiQ<&ZdqwN zVEa4ikUorXO(7Nb69r3xIod5fJyb1mnM6QP_g+1oFyiUc=WBb(HGL)#yilGu?)hze z*2=;?l*Y)uSQ(w_f(OCgnM3ZnTq;@zD!`cAM)vbeUyyQf0q`!?KqF&QMrWzgkI2JN zQJI?0LRQ0bw=s4hUNvk>lLUV>Tm`)JI;MRMF>&%qe+SiCs@O1iFNH0I7GkhWYD}iMEo=f<1#IWn@F&TYF`Rrch&73Hp)@WI5Xf+EtzUZVDFqKn z#+fxNK1Y8F0@;i}<>KiB z#P4u0UM$`O=TDhH{ET^dEI98$ka{3iUis6Tz2%>yrU&0UNCw$v3oy{lV=ISJp+DQZ zpiMd)bfnRW9r*Dzb;WN0)H(sZqaBjBs<}+XXgYL2t-Z3FBfH`jX43cK=64KA!WFJi zEkSgKjQo_qI!mbV=CywnqX847GjCX5MSZLJ@tpZy)pM}tT3fSAkdl`B09Nxa<2 zTkKgUJ{sdh-lMXFAcmEDqT%TW8;8q5&ffR>q`B}lERaT89Fc!q-l(|`^*?-}&e?fj z`sjgVc_fJ5GuAiST1Vb5(AI*%yvlgOy+Okgs^qxfWH;j44>!mdGCnJ5EZXGTBQ>j_ zc}>TVTi#IciTdWSw@CEaXUipo__SGxS{0Ql+ZBYVP9=FNWlo(a(4d-*Fky?>-Dcr! z2h@Bw7_Cd_LA8HNTBYvg;|G;h!l)|hHQwvn4{@#A4+A6xEPsM0=_Dn$Xlb!`Fpl^G za6HY;g??=h!25zp#9oY$Gv*PT%FO2I1!aSeUDQ}9e}xkm1&@G(M#UG@9j43#3)|&8 zBL1Zh_`QUNYpeJ{kvO7AOsX=X`Z0M~gwGl8)GZyFnw@_(%hbwG_BU5p9{EnL)?YLk zXKbXJ=luC?>lLTsB4&}|5mDR?7NCU4_uy-dHu+?-k=t;0oj|HtnOWaWt^irv%e0>^ z^uNEh5KFEW;k(WfO9gd?K+LUZ(bgbOgMo+0QErVKQE7D*ey{KU%NB_-zOwRx~K=zLKILA!iNn~5tCwBsy4|OVGRVr(Kpqdw+<@7x<|G@*j z-v!m;0!&Ct9a&8hi1ZNIUAu18hnesa_=>X6P0oM9C_p&=1J^nY->d~TLe$`?qtk{0 zZNG5MygFT9!Zsp`9VdyO7(xcDFreRYpaM~D(XAGnv<{?W~KEtM``_{ z30gSCD1|6?+2rXgSBh`tFn*0%wBcmq@j#*Eewa3Nn1ZXhB5NZ^tChIpNSyEjcNo8lEcLl(z z04Y!H$43nbLFPxm!aCrGY(BXPe zPwPO&USu_*&WvDlYU7;#ig-C?0TYStzC01efQNCg6Sf;>KrV+rW*@HH+MwuqU4CDr z-F9kyp}g7U1YSiYSUe-e&#vdA9NQqL6qPfqz1yQRQ>IK*E(*iuc9(&iPmzCZ(h-}x zbA5F>jgwV+CK5|A;+)rfx#+9@5le*FQ*X0Pqr&h{17fI-1@ zL35Z*489CW2zk>vVEKEV^po35dFp?UH+7Z6Owbw~G%0Z>f3sNel$HB{;5Non4v8_H z(=~_q4X|RR*gphgU{i60I0S#-yB3k#wZcPD?}Yp5`o16yGACY+K)wL4R%Zb=xx?Mf zBsv&|-(e2BRe~8q03pVw+||a|GZ2-P?_@=NZbjRiNDQfe>N~A>N;BC)YTGWl!DS}E zTab}IdC-be-r9O3%cmcS$3zP(PU}(1prQ6;RXLE$L?xV1gA{mmWzv5alNe)X1)%Pq zAR)sqr5)Na+2Gdb%l;TC0*e~&N=@c?xst&iY=-UzxcIreJqXo>)JQUU3{_U^WJ~$c z1}NwF$Wl78k>K@gvu_K32#{}cRvCO|@Ab&ic?@JWc7k>Gia9uo++iS8Hf`C#!zji|W1n~h!5ZtC`%JB#%OijyxapkBwu<|^ z(yqMzg=WfN?-t*FKP&wAPLyydV<7sgUYvH4$JJ%{nSXu(kBxt9iYgz>o&uz`58>|MyP{8Q>@Nl(nXV>X#9t9bx%kT?-U&Cku=qiLv4?hD9yEs)$!w20{|GrVscS z>TJu@l4zQ&LJ5Cl${2k)@e5$7(yvW*Ng{E>eKq~ap}nZbss}-krCJ&Q?ff?d6MBef zLKGaLN=|qAwX>qt&1Nt1k}=PvQ1o@m_3mCc_`;vKH907~9x=k%aT}2LPfN4V7nXfw z@*R40-bS93>z8NSn71`P+m8)w;g)AWBKf4~M)EiyaQW!n!1H;z(CXldkff7-O zWQ+IZys!*H+fYoTQ=(H}>ES>#Y4v>}{ zqzk&goZyPPPmW#K_nLL>enCs3un>6(66f^O_)vSmgOOIkJQg#*R?#6@h{a0;=eOvc z8aQMT7%+04uMA?%i^@x7?;#SMxm^?DkR^XZDDvz=u%IFL2w}bCF{Tv#miWOhwFeG1 zC}myKutE}|t}-kr9)0z}M8Ogz`wPg_rSsG#=R9bA!@}i!KsV%tCQbYATVp!-M~&CM zD}V7(D@uo11M$R=sMzLL>0>&wLCzC$2{ik9_&)UhMlawYJ6Siu?<&4g&|tdxC47JQ z8Z6()*&ana@Tva_6*q`|>LZRPgrX+T>$q}^LHAxDdjy;DM7%}_#pV4x7Xi#!p&`2C zdFMY)IfD5#%^e0~GLdBza_W1Re)4nlQooeoo+Okk5B??-R_d|w?bvhDIa1!)Fsi19 zX0-u_0>oAdA#0J)Szs`Ue)I`J1_s z^@8*tZPV@(@$@}c#E&$WUKzxov!$q5SaZ7zDuGtca~5aIX=8qJw7b+rq62@ih4tea zoREKKCf>tIP_B|db2!+}V`o8`NE(X^$S4Lmlub`3q*&S^SFIJ>_}_hd%jg$gum}y+q2!ewYhhP53!4T)b$G7vp+pc_K=`;LOlYsj4YNtKPD6Fpp0kNj;~<*X7I^wxvGwgzu}382`w z$E1&Jd9nw-JMDy!@EvF&(24$r{{8p}a=1L0Jptg@8@|x(PLOdA^Wf z5+=Ma)aS$B(Q8S?e-wXb6QkT;!{S>;f^$`&v9|;fV!c9fCDn%fDecNCPGrJ!tRB=aP3>6`?s5;g$BxFP~U>v>PDV#0+LNBb@ml=8dlg&F%2$MGxk6MsCVg*UItmK^^R zb#6p$E>K#XmN9?sTk;rk_QfA`Br7_}$w?H?DN#h`W&A{z&aQpwQg>p#ay2gJ*BV25 zFhS+qXY&H}Jo}CBZSKbdp8Gwr-PoT|fM}(|^EA&n)UgYva-s2vM4iVA?(Lqb_+6;wkxsFw%z$?zepBwRV4_Gx!%NTBYuf!zXFS-K>H9 zUP3iv`g#Xp^OIHsHk>#(RDQARVE_C}WL!*qR)0CfLu`_;c0q2zq)O(|bK||+=~Hh! zT64gB?FjloxtKo5$H>LnL>QvnvYn`9YQw;F(@LR=R$1}ss1@=}CiG>_s3`@u%zat? zm&p@o7pQ-t+MkCT{t}mjEX{=zkWZ%!P4F5UJ8(Dpx0bAB{?GoYt^#fO| z`LhAg}@9pr!BAOE`j4H!OCh$(r; zN?Lz(eyx~B35-RblAw$9qY-nl+2?WFl#&NUiZUC<#*p_GN74D?y;P)KNxGz$7dn*j zS!juEUG&jSG$3k(r;3Z|@1x-zM_t#!I1f#AW_M=SR>TLJfUB%8K2#@2s-pl%-ePsa>70;<|~)|-B#M98RBlJZZo zgoatveiddOSJa3^V9zvhlA|9U*&7yrC4(>|HK}xBc4q!w<~w_paqE_%&P$Ju`#`hr>( z@MD~cS_JAHUu$MON#T1TxKUdzCEWOB??J>-ou_wJL~~{BbRLB|gJ{sNGzzTv$5b9H zq?qYKxbpX%YYA5_{C@!lC-~Td))@@RczI|#E8j4bxqe%iG$EA5br|jlPfLAuxHG6^ z#5^r(E*Za3(%RTVU|H8v8vn)M!DJ2|FPN!M>#D%aD%VRamfJ>7o2-9q9|r!EcbZaC z!kHfwW%s9DCObaeL ziQ<@F>U%z-AW`?F!7Xs&;f#e{by{iVocjb?m3 zKXD^E#a?Kmp0oN=*rwae&gDnHJQ z0U7<)+Po+m5Cea==8n0*IV=jdlbd4<`XPjz(gd?Q0RS+Bz(F#3=DxHrO^J@>B$q> zL8tVX-cq-Z?3fA{om7b z$+0KzI^32jTZ=T{mX`$ja7qN#j%RTtRySbHqTOGdDFvmL&vz@+v+k7!0fkW}uwd*+ zpIce+xdq@mf}?ag;T6sUe%lrm24-fJ2c+jUajB#)qNDI3N$`;`2ED<`r&`s&cAy~T z*J6J|?EQK@-92hzzGXMMRmy{&JSVgLl=TiOn;}p55(}_RNvK1Wrl!^cFJ+kL7Ny2U zsLHi()zVgtnY0JMMo`9WZWRuzLdC_rfQjQw)}NpfCy9*N!#K z?3Iu+eW0X_ZR?_Bp?O8ZLAYP2-y0v0lK;oVQLs!oK1V+Ur!thT|J)8+)Z_}N1QRq$ zOL{MSr#n+D8w#^J?2u%Rla-?(f`^AY{O{ZTj^s0QAyQ|-(csOh`hm?{SL{J$lmQ;7aC)Jq6PuGsMWy79Q%Jcn$8&`K?=KyH%_;`q5~hFka`yr;SlHJsi_cbn9f!baP}#q^p20s;MmdHGXrBZ3 zehY;l%1Gj0Gc?pvb+9nst=*IWxCpR;qY9<)X;R)`yK7FSzBNWTjgRriAwGDivry!M z)FTmG1A8vFSjDj~+KtGsSGiTKtc>r^jtL6NFS;MjHYHUF%nR~I9!G!B*;BcRCrkV+ zC^9QAk)~2tBcQ>jtqL)-4E)NZj4nk3=)8sf$$tq*wD_7#8D8vyK=|RjPne)nHH-B& z6`OP?=Ovs>$A6s5pc$jDdR;%Wlq0Y~TviN~Hp*E$;ZyE)J48Qlb&bgW(Km++7z;Ro zS{shn9nZpOAbY5xEUtg@%mqapio6W^yC_d+6h-pcTVcux83v2+9vxR4wif9zq=upeKkI({ttFmwuBYn!rSovPK`Yn2yyfJ%m`w+jF~}B zMDLe2Lz`4BRA1p33GjvBKY$grvK)G)f?r}!4Sj_^WHe$V)+_H(JBhkOi>Y((^KVen z<}$yuHlh88K|o+)W$MbBdy?a4b3XQBCMTea>(b8gtq2 zKwB1`z6Q_o#S0gAdkH8H($4_al3H9eb4IrCLo;d{O-HKo(^SV}_R{}DlV3dO_#Wa< z(&fQpa+bSD<9+E|(vL0%1)9M(*(o>=#%ABOm-pv#=TF6?;IoQ<+$;-U?G@m^(dbaW zV!Z7&oX0@5*<(m>zy(Y-!l*phK2LI2rCLUC&+4ZwYOdYXqO8qQ- z=uB}BYx`Ec-Ta_`%FSBbH&qhYsNZ~dp8Xr*Q%(y?iAKc`EE?Is7yV!|Ej=?_BlpF3 zf4!b_Vn{emf{l}pVjB%=b+?Y~$IWYjigQWZ_~R}qvoq6s`3To{Gkkak+D_aqY*@*k z?)NUNt4A$tT{AjpFzhXCA`tiTc(d0@>u_aPQDSJGT8r9$Pk0yNJ7ON(6PdOVd(R~{ zEQXwPPo6g;92ly4pO?}9D`|Hq61)QE0XwRj?WBZ?`7Z56m$*?{ucO*q62__Ux+9^y z8@%I%X9pAM*?Mqse6y;=%HvXmLbQ^So{Yytl3wF4jjE>1%3+RgTa)omm9$6Iyjj}jFMY6R;9Ev@B?lf_)--a7Gx)G;Z<{kmIf;f*_zMobSuuSdl40hs!jD?F=^d(NM zEo&btv?G?tx`7n%`$-l|OxE9=D`=`b_#$eYY|Yp(Fiz`eLwjfK{w795O+vRTT6Gxdndsvsrx# zHogo|f3uHSrll*9W5*);KrjNz^a0c$^&4YE$-}a)uwtILLluL6KttnX?o?F(H9Z42e0y$*EbPHD=S<~k_?TKx zZ@4*(;@;d)&Y0BYIlZU=>t$+|E+E3^^WLX&043hqc1FTjCgy*Dy+&|gbN!BIv6gB3 z#v*T#31vnuyFs;ru|U&|oHt*<*qlDJGGjI5d8Ohb>x6X;Hsf#~;fRu+D^?nRH?&)ZkCM=!7t!yh76(=U+){U@qvPwiMVK~>^JygJv< zf;DfZwx-(p+7`T+)A5^l6^OBQ7rGr|S}K291Y`t99sfE(JvAyrtKU)(;Vn1#Xu~)- z?0b(-kKaMcF7Te-5H~dN<1po$QCUhOg3SUUfZG+U!p*?y`^3r595%dvhHg!w81od> zkg>62*JDy3g(k+<|Aj!4zh0br(Lr$(Q-AMFkxVTR!E86Q>QEE@Nyh}+6QDVt%go&) z>1OlmWAtAaeRD*=WJkn}(Td|IS{-Ie%(JQ0xrb&IrUx|;35}`}yb+G+ewrLr5{FaQ z1f?O|d8$$#vhNW57Lc}otG3W>c||1CkQ_e+*_FCJ-Lq%&`$+pAI+q(lR=0Z7v64vU($Dt?p|kdSlHkb zaW{#KToPMeH~?DZKD~aoz*9LdU@ANS?eQ>YIKiFfka)&CxNb55$5zT1OSKgs>?aX7 zt{N=mjHltgb_?tWkI>FJpY!90N_tzFw#Ab1aXwt&RzBn`7QHB}@pkWKy9w5?&5$Se zxCkwhE6Le=VFCqz=Ln~BL9+)T=&uUAmwUvCtr6=QGq=5bzM;y?94u8>{MB|er&~D8 z?k;x}W*R#TWXl(Wheho6UI6vERqBY~|HgTi$%9D_NxY>Sm~=Z1XCc4+zQCsWM$J~o z82(=!WJojl89A-pv!g8?2j`(w)(sDy3LAU1Uh4baPSyK=$`lDb@OttG-PwgEM4sRy zEmv2<`!2V-dHfttsvFf*#MOyeV37@0?7Os2=17Cjauq92)DAVtreQ4AuC7O-HmJ3o zt`;KiMjmGK3wxVSC$plEU`_5yNxJcW@wlA?Rs_9-CF_GS83459>8j)(P`YhDPVgaA zbba7<`4z%{h$;L2oH)|QCui37eyOObcJs?6!C8N>K@`? zugAf8C?B>g)WJZ;NK^oi-IoEgSk52ranXv@Pnl1DaQa;m22B8h-M1kR;T*#IR{&?e zq4DxN3c=7^Q$Lx960L`z8k)^E#+!1Gbp^YAH@^e>DcDn2`;QS09}2OhUH^0mbBHHwpOEKhhJ;EQiWU9 ze_Q!~Pze~;!hMJ ze~Yym9}TzF(>CBor+c68=JR6l(jLNkUtvUl6~~ihmoJ-F03K*NI#&PTWGiqRjQ1^F zsvBPh9D&_sUJ}{s2pNo8dXfOlA(K_`|C8uP`4!52T3zMES&#OFQn6=6?$L2e8f?g}f8WD{-1RWtB|avFv}sZhm# z@C+8+qEbVwZwSL2VovUQLO2y3!}%aX~55)+#x_e-GEa zxFr?|)1`njHuMmFpBG-4f$CTSiH6qmXVNzTMk3;tF_eI!UvaMfr(xD5d+4ke%r@i2 zBfJg|C=r9h+ZV(pso;eZCXDfOZ1|D*>HIlI%sVk+v&*~bz(Jj8fk}ygs*{m_^QiV@ z(?Uler8OKgXFPvuE_#0zESPlZ9}vN1ELavfJ$HJ4??~M&E`Dw9OoeI9Y0?SOpjPXe zxT$vYuGUL{e#pc`UC<@WhW~DxE=o{c*VUqb(yu8&FjPzzexI9L))-u(=~?|QR$-5v z{0rqt>Jhqpxcf98+={TQxqhI3IGP>gQdkxpcv;*Dk~3jvYt_NmyD#7G_{Rd}3Y`4G z&}tZbH0hw5lBu1!?HXU0ydUCsa;Yg`!r>)a?@`!!ox)Yg@26;2qugpf=OY`+`LSEa z39RT$qZJDF3B1^uk$Q)NV&40{}5zn)6q;TeudM z4*SmAM*wD$~R)_feO0XYMfMm3BcyYRvf|-NwGQH zswtL}&S2GHxFC}64nA--IrLY){a0S*(h7w(JM`%~fVS|^{1Pf?^7}(m`P>N;)TZ#= z48bdWV7b@X=om3Vu6=r)>;~)M(kl}8hKxhQv4V$GpFhZf9Hd9>yzlsh;6fZA40@<+ z#`#EN;CY#)@?QRb*=(KlLD=$6d@bl9K-ly0zsZ-@e(@TRzmujTp1gRbM($Z8{P8$^ zEOMDDo6Qi5lDGQd11LKUVl@dy>e7GM2`zt#qQZagEZpfed9u;9zRHDR(rc6Vf*W(7 z=@5U@Y2*M+^N|~cw&wO9j|0#Iu%XNcTFCQBKu3DzIbYL%!2`RIvBpM`I;()K?8K8jYR4>11Bmmc+(~CvKZY zY4i{7qJvEU_TNhORe-Yxq9NiBD|CG$b`a@yO8qw}pu$Lq1d>u7y}p|agSGpfrG#t} zgAzIsSD+hzRRN3K9F=v2SzAR8{lt&S6!4C#o2_o&>T7~YM3L6safLyS0UsCG>64&~ z|G;=y48<*bft^98RJSe^x@Ko=2gxoD)D49{SrJSN|EH`moZBqX5>Q?mZ!{&5fM|)+ zAUI%I>$m0i2|6>&j>^D(Q>ydsb2184f>q!G6wv%?%j09{CoGPxLf?Jv%jy}Bo0TakE@_Bd zkmE$vUez4Vj5XBejY5ZdM|rLg9n8Zd_Ltf~EzMcuTKqwe;U80L^JCE-exD>QFRMkU zp@SBGacD`!go^LL1<-*5#N|^dU;bUu5C;q*2Vul0vxn$H!G*XNwNjZC0v=}t=g&cv zax9p-no)=N3NOhXdWrcL5!I6H)ND@|Ds2 zb_8N0S*xJ>=kFaL;On2S>1`g>I=XToTc`w{h4_I~<{Yg(JHRi(sz%FMi$>P^FC4IUXC@?6%O$0;9wGju} z-iUyt@L=GGFR6O;5_XCoz|G{HWo1rhGgNSij|N@cFORNhP3j}i3DR(eGjtjT&{RaI zm9hpM8f67~>S|BTh~N|jNoD9$+3k*hyzR2E4q-9ycD}16U5bd|i>8AEIJw9LS8`7w zg{Jqz);Nn6t7iRVf+YD8modpVN>)gChJc<01tPNw`%%7DCv{;hjcZSCNg zdy;5a6~heoqLhpd*1ZmnTJv#uho2E79@+j-JqVH8a3NzixN@5mxLl!j9BRE!6x~bqEd>@YZ6ld_TxWyx0IZXg!5Qk1k}0*8@UC@L*=B z?lG98JW-~Hj?k+@%_ppg{W~wYY@XO+V>nDAuoR|T$1f}}$@98@IDggE(Oa_+ z#RytHxYmFfr1+@@h6ww&d#O8O;6*^4o?)Qond}tyT(Mh!%Y+PF%hxDMyI_qICLZpG zRz+B7+x#9cnfPPlUf0HA{5WYBmXZk`kgrUaIcsgQ7P`z6weyY#Hiza=*36m?$28r% zxJzHO+x&I7Jx7~OcuVeo!(Tm&9)$OV`v~;=n#@^>Htvx?j0@+_Ii+_{Qx{gHXz%ZL zk6On-`jSGM=eZJYP<+TKA_i&$qrVz^>3q0X@fWH^A$d=h-j0ud0hkA}6o+W5RH}DGJH9MeCf3#WC21s7F%fAm zM&VQx6tQ7;t#b;0uu2LzNLM!BoU^ZT=e*@r-o$Y{O(DNKxF|2+18_PPTK14H2xDZ* ze{Y0-)|WE?q~<3IOlbJPO$D3q)R(QDgRTSl=@4cFNnONFC9-aiJjwrkG)J)D~;P!5`T2;2h&ks zwzL*~Sd{W?E25w2DkM02{blI)7S7HdNp7ya*A<3Dq~)+7M5NPEFH{E9A|&pXBI%)d zJq>*^C;&k^jg)5lFv3|^M7g5semm1)A6?r#m|rLsR4J_nDteB^PXhCLpOt~Z_p;8y zVq~;Pp_&$dIql4!pBdR>=+mi!;)b{qo7h<<-@y5cdRyBvItUKMZ=*h=T zIg0mxv$RpW@3Ed32zq{$UACKkWfcOnm9}yRGKg)Pk9RlkFT7 z*HXAUiPF0Dspx|5$QwEvz8(P7rfYpIpZSji8@#C(TsCpY!T6NL&zmn)2Ry4=f1z~8 z=d&;jqRj9B2EGg;*CJk4a>_b*3u)E8`w6Ol0Dx}GfLW1uh3*N4PlkuhB73f(MWfC3 z6&K^5;l#Z=P?1j%-c>y^s7Cy>k&Z#lR$^u2n>B1^4jRrOrT;<~2uBzH&0oYKAU$Bi zsT-JNzUF=0f^?w?*o9G&j2FRL@)C(!0xm?|U4|6Widdnz(%&*mm`Za7Szn_{E&oq{ z`#ejAcT7rndaW0YCwr6BteEdQAsieHHE0Co@sfX`pvUOG^0U8?q$Yj57~y2_g~G)p zfuUIrrq++w--)L>y6=q52rS7>Ugx8TFZLd-hBaC4p~H5nQG%ZWvu>$$${hp&b1lpy zhJTBOmRj?zCk|L^7Gfl9Tc`T7VJ_-_d1Ha3>Zn{fK=(AmakqNTcA9qMZX@gvOQS|H zQdZGHnUyTB!z-F`x=uvyB1R_5Syd^_!QJ;NyU;h|h9=0g<@1 zEWzqf_NSL4H4M!l6Iy@n#XY_lx)9<1@eb>#_>rm#2MxVQfA&=-1RYX7r? z9+oauX_<}%UOG`UWCYtxICh36$hI)|M|7nPUUVh(UP@#j_NT_apjmoeaqT%}>FWA) zsw5k`K8g0xH6kuD*@13$?~F)vbg^Z)G~W%nf;c!sdB?nutWra%oF)b zWatDxEU3^d>k%+0WaO%zgAVgJ0KO_3xlU*%5{|_P@HT6Z#4?eh+>`=;$R@UHx2bGz zT-8+MU!cd40t~t6F9e%RE;xUnKCWxzi_JtdIyZUc7K7}FhPkH!3;!j=1~ITVSKdqG zy(k@l4S4xDYOo9OnbZ>w1d}1I0&j?vmFIdi9_Obj3w^IKxn-{*h`Z`9^86$VzCS5OX$;)F765)zN zpO)}O`r5nGTrc3(@e6rrI8t;%xCOm#TBC1&!HKt7gQhP(F5^jmNvuvH8cPDTOdo;uy$4V~jl z`KEMb5N#Uz#0E2@{kY-s<`Bd?3iEUDpO)?BXRT;L zQ|tAyOvy(`wrHGxgu+JW_1!3{zc@W7+dR-NO5f=~*(PmNWm!U(dVg^T$4LEpL9FdB z4QHSrO^3Y_^8p&e<5tfLQgx!WbgB@M_E#Dqfkx1FXwr31h1=s%H8F#-op|60ztr6o zgT{M994P7R73&03-A7$~)tY2W1qQYm6R6wa-WePU@XtJdd>p-Sb-eW#GAVMQbg1Vp zj9{G1@g-XXh-IEu>^5xvQI6~#wFglm4U?|z&4pknRNHa;fo|;cYJRCB50G@TXwr9I z-kRXbL=(nk##;=LRHVMZiZhPPSa0osa5)lZqA=l)aW^F_$!jBHB&;YI5;gfpRQ6fM zx+E+pWsrS;*U3_`$RC~GPM(LHQ z{puGC(Ex~1t1Mz|mclZH{kwnkfWsuqz$O>`GSEboY;G2I1mC=ZAB?*zfu(1kfRj)2 zN>UjZzRp#k5I88~`>-5!E0=KsSV5-kO*jv|rIzY{SVDX~VA8s%z1JLs3-b-FfBUyw z#5M5w&|j6SaT;CIs3dK%FWjf_Lm;t1i)x=HgAXM7(MC9QEMMr(NY~B{hXags4Qv4U zirltz1M^W+tov+MEVvdNX5tRo@!vRN&R?0xmNw^3Kj&rc+S_s{8pWWNzMkCqL1hN2 zvh$RGp2F7%ff^FyG2`Q(*EKUa6k$03a5>q9xlFH%1_4w{xX7K0`YOeM_m_F@JPyMJ zRW3;`haQP|r)C=iV}pFEDT__N6Njr!pIhe(fEJi|h$KqKsu-+}{$fVrdOAic$uZ{2 ztQ<#~L-RMIdZ4^IfP2iD$C2Z-#MX(dcy7{vSds^YvG{UUjd+l^u^neU6Fx~iX0+bK zHWM=B={Girjky^9@1r^%UnlX4BW-~%<`-2njZ)5A9op`pG z^@kEryY8iCjwtWu-SAY_Zm(12jtN0D&)mvdbO!|9fzm=Eo6CQ3mn<}L_Q3u}kmRBp z^yV!Gw`DiuP>l*@Ze(+Ga%Ev{3T19&Z(?c+IWZtGAa7!73OqatFHB`_XLM*WAU85G z3NK7$ZfA68G9WQCH#RhvaZ~{n1T-@?Gne7u0VjWLxdlvRO%^STTjTCr+#MQscXyWy zT-@EQk;a|I-L-LdcXx-zY210=%)FVGKlxM1$(FTKYp>dsRB|XuB^~Tt)x8{ntcqS*bz~H!05npH8UQJvJO>VDAoecKwH#g|mYlKtV!XL{fiAQ5_&5#;h&|FtIlW$V>lIZtv>C`wtpu z=4|(`?ic{B|FdjO{%4u~&-!21+4DaZ69OwMz#L@e3NQs)g6t8P|D~IZy@dnd`+vgb zZjS#={X@v*AASIue>9{8m;){TLA%-7Dw@~<0W@L`c8+eYKxcr0gE`RI9-!)AXJUW< zUzCX*$kyxs7x#Y=GOi~7=pbTm`Hyle{|SLyBtf1)b7he0KT=zm*#0BYzvEiK|D1~g z&>ZAu_n&&;KYILgqUH|vwqE~t%YWMV_lC@3+8Ux#BJ}?ofPbeY?9Cj^LH3paHP?T% zG;ucnU*O+qWfRbUrsuz8{yR+o*8hL!E10-CgFFFxEKL6z50-ze|5^tB4<#z<;OWE2 z%FPL2WM^XmuyXwK;o)HO`~T22b8~hE+PnT+@PB&wumA5s0s=jOW(aG`4rY9z)@jY* z<^B?dvlYC z1<<5ee;Svy_d%m>$FDBj+e^_JP@`w+ej)<*>8nv^t-=bfOog8J)*yc5h3q0;Q{ov} z6_f`#9{$j|WoKxzx^mz;HD-i7?1W?flq@r zW$GC3XZMsJ2`0KADiuprWccNugml2i`E13&*;+`YfEgy;G=NnAwQGZL! zu2e33vkHK-Z7>3g-ZWiR_Mpbjwoxt-ql?Ih@L7?={*3r+HLfa);pFZN;({|n8Atbr zTM`+RR@lboPhK~^Q)ho$*k>(iqxU7Ausshi|5IMr=f{}k20_t;4t*BW3+90NY4JXe6dT$XH%-@Yz2@~N4hLs4)$=T>F${^((}pg4I4S{^eb0UO#7P?9F8b)s($ zy<>OA-B9+nVjua9%^FOh+5sOGFC^B7#}pVX!N=4Yh)+GRy-I(q67PmY@DzfdPYlao zX(gStexfZbk+TWZJ3;=qKyO4`Uk~u4w2AmT$%-D}86~-ys+1cb=mx=;6xB29T;9}x z(>L-dW<5kGiIu@zUfmYt?b`FnE&D0U9Z-^DU90xyfpnU(bk4YbjPiuo6}fl68-T0p z`HjvHh2FZ5FgAZu>YJ}t(au;ao=H&~k7fNg#3>n4;9f7L+or$SIGpLxP;ltD_2#EF zryR`V(+~E|{46fIH1_WaE~dUz_?SduloVgTUhtj6G2GRB3PR)Ti7qTSll%5|bxM7z zZF4PnLd^(^F9WBXt&@z$F{Q+h5Z3Dx^S~7YdvbHnsr!Fd)lmK#3=)FzL0>{fTMSQg zm;2SOT)R*=>*67!dD?pu$+S?i9_m=_^E-4VAuc-KQvGSignHVWn!9LJnmt!%lfiP5 z<|+-1TkFdpDbF6-vpOTrEMPv%t@S8{{Rqe`aGzmCX7Kxl#MoO`Li-mvf|c3&?xxq8 zziv+_biRL1yt6a#reAJBw02F%BYU#T>;3 zrfr+R86u!6ju%UI`LTH<{5Yg-XejHxH=o@b%k+OSO}>AgadA0&@|HoiNb_kzeYI{f z&}t6fquG z%WRhel5BdYLep_IPKXpiFCdHlwNVROk z?V^9=>5}yQ!T)YLgdiFDh3VD998RH7KC8}*XKC*vgkP7C?5{Ubiz@shiM4AWF9 zm-4sRIy-df>2voDAie0ajPV;4l~_rdNc3*;XruA1@8XkCkdyyt|BP?)CCyHRDA}}@ zgT7li$ZV;TFS_CJfw$jkXW~V^tU}`Yg+YJHoGhI_3GzfvOyY6fjL3iNyO&fmx=*!6 z&BE2Fi*|Q;E==#W8#0*XwPvWr7$nNQLUJwL+Le}%;rvQ8sID>AMn>UaL74EIXt?q-V&R{bONp4_byl)@Pstr zCe#+0Z342p>zQpLazUsIx7dm7wb3#Zeq(2BG@76xy+36q|g|$iqRk zc-m6`#*PXzZSM&FQ5{veFEunr8@vz4wT8U=B13c8505c*k0CQ_R zl`di$iqsh4JIf?A5mR9Jlw67TX=||w@}Jp^*M8eM!xn!&47R{EQCV2%2-^x%*k)v+8W_Hz6@&4<-Y@K3=%aIQwMVY+ zh8CVKZ`j^RPs+`=`Y=8H41kv&hq{KlaLp~>$eN#wNPpDybccCd8PkkNmpl}H+gm=m zWU!-mI{G8Nz?0Y#u+t^EM*4y*%0GvU%ACGMPiI&d`%UTXX^?-IYD8L5@tWJVgI+Dw zc@R7fz598TF^?8%T8XDsi6#jgmf1I9$eE-LIG3`Z(AM=!!?bNF_$Hj1Jd#k8p*!}sneo*s2Ni>Y$qptlF)ywpwp3=gq4JsVszy zO$?IR&u8EiXYBq`yGR||pTTJ2(k|@AYa^Spw$zd~fCsxpIanDOp1|`985lv@n${MC z&(fB(4tF?33n16y_<|pXxY#OL*h6_U+o}nXoU$+Np^iU56TKIhHsd|OeZSukY8drD z3S2(od*Od!6qjDCmLu`eWH_wKtHdha~WiA>=K@$)f^_H)tRp7@kqJSUH)k{Q`Wbof>?8lY6vx( zL-}=q_tZiwn_K&qObR)z>3JLC9O5}?I(tZjqq~3C;g&}kaYRN3i;YAx$W5BmwVgMa z`Pn)J3FT>W{ahHE>g~ISvQLc#C4P%{S-;u8YE}?A+%A?id8O38@E{N{Hz7uu%tBY* z{B88nTsOBN;wP|%jA7_Zg(t`D_6@5&=Wy0%B&IYx#GvC_VY<<2-*8~9?)4zcqPvwE zlt+K@j9lr0TD0LjLPpfJf*@$ce`m<#!4OiTg4HJ=5d-#2V$s9vUHXZ>myPx9)FCFi(GLypFk@QxmMS!7>nj(1`Ili7I61T%xq^ zbZLsRhZ1INNTBrq>tP-1Idbhvb=Svg&PIt&YzF@YVPUM6g3_x}!P({h`-ydoPEM-Q zRLsQQ zg@z5n`4PCxF6CG`v7)(M#0J}IHj&)j3%T~h%7!bbs8)R8ynyGB@y??@2abkx5%#3` zoQq%cD${Q6gnX(9a~+xi9!mIYl@Z!EU>=;te61#FRTeMV(3ui~6;H*hsfd3NLBMo6 z1KHHV!8{4+UM(45)?4BryPLgxZlxfvxNF9&ppL4vRdMImtywGe$}L+G1Cv*2QKULnXf{-Y(_>L z3YG@>B`~D31;omVI;HY>mC%11a(sM`6qoXA5sHkQ2e`P|PSwx94_S6hS0wZsJLz8s}g*=0WveAfp@GFr1tv zxse5A2_WpAeZ^XeW`+#JJEU3?LoXAv1k6Nu1xXT0~9#Jxk*`{I1ge?y}9h6kE1G0w{R^^-?d z(O2Jif!A_m{xt1@eu&WaE3Udq54^ATuzpIneNnImA2*COk=X_ zN;g|wi1F7=3II`UBG0gE@C=DE7azy*`$b)(NxBrE;fB*@A({>wN;|quBO+hA@P%EP z6lLbhgycXI^ESFD%Yj=ZC}?qC5||7$8bYkwc_+UuKffq8=cwh3v*U4-c+L-E>Ec?i z9+CWDhZfj2rC5JF-95TGR`C;Nki4QqUW;gBq20lMx|(H&820p-x;0@1qy$IfTzTH+ z7h?SBJ2z}{6e4&=3mZoOLPOx7EjUQCjIvar?3$KVyDXo{_~i$#nK$7pqv(? z(ryiWi6lQoPNAKwLqp$78AewQEpriQ6u2Q-hSmV@BM_R<^Gq78q~(69qpMM>`nk$> zv6<&yw{m~qVW~dtc`en##0o|$g{@eRmN8HEqBYoQl}DxyMF_!d80P}S zmtBsmEV_E6GwIM{zG~LE$y(-wzVc|SKB0&vB{|tvivRr(ubc-yj*9r520an)K{%39 zZ7*k~HOlo~T2;p$f^$i_(Ty}Yz!wGis#NLnjnaR~8`i|tnhGa5HQ!CY#`3UbGw>`B z(yaUU6-iMW4iBnOG7ce}@c>6aQ32KwtS?3mKhVrxWsay#&rJueEis18`A$R}fV9_C zh_z{R?@J&nfI}aBOxcusdknbuSM6aM`T9`EZWUm2-t;Dc zAOL?&&D(gV-Rx#Uc8k7AWH}tuhX(;ZBdN*G*p2sjcm8gDTD-26-fl}_j7v|^ws`0~ z|LOIDmaxn8+mE249DzDuO5mNp@eOmK9C9W*dF)M`wG6 zm`dEqtD6o_GFAl*4dLX_i@*e=wNfLS=`Mc_wYjtNCHn~f$vgD9?jv;Yj!5MSYNOWD zumyTHw!>+yiI_F!0YZQb`VC;*zTdaY_4(QHNx}suP|`(uxEEEaqD`OAL@p%f?Pl3! z{9_4sOuNxN!TT}Ns5*kUoYbMCKAXTOl#Wh6DUu0{>kf5ymY0{niEjrfzOZGVZ)bmS zrUss!Je_bKiA0uPsl7JCiZMuPjT*m7>UB(Bw?*Y1G zY64mFczKctRlY@SVB3u3<$Z_;z(#*6kp)b~8Vj$KjzmCPji`oqxDv=7P7QoU`5v2s z5cFL|Qyf0|Vmt(r3XB;{N4}YeD@7;$r!6c7s zOicuC7L` zcGr!`+$R7{&n$Mls4X-oS|8X*o5uZKP<$2QvX!}`efo8COLo7KW&0^GA44gvrpAKYiX&-&n}+>f6EC$9u>J75QCwj z#c(D1sd$F>5+T`Z;M?~6o$_6JEBmGv{LVZ3e!qgoctUwUjIl# zi$1p!H}m)Fry~J3X$B9#(N1Sq*PBS_=l+iUE;ek34u0{|mXswT%Zz_fA4`WZ^A17D zP37P?T$oDLlK(FPbtXX2ritO}1<3>N=P{6pnT{EcLobU?JWcMow3l>9OW}smC|Jy{ z(;)LFr-IR+WSjl&p=`^rKv?d%{(Ae1DtUe6huQD1SZ7yV+w*()4vCt3xs-u{_>w$k zGppBds@^1+=@9mkwQqkW6~Cc6Wt5%KrFDLvcOMz_$HhFBhX^r5wD`Y;KBm_R z&{dB(_^3eyZS3}Sx@WEzaR;Ob$Bl)U1Y_teMmD%>!y9N^m3e>9p<3c7N_A26g|eqP zCXRAMq*f{8l9qx=$GBh@vEx}ZE{HRA7b`Dfg_q021o88h_teAi!N6Dcti%lrzDPjG z^NrlaDPi?#y!Io)>*?auo7Azz&Q6ih%PRRb;+(Nj*94P$vyK^9Ng`*HH(q=_@S1Il z2IMf6fwjT8i6ejE7XSS*IJNZ5fM+Fx03X}c)%b0~ooR8PQgC^waa(0zPL|}!c9kyV zEGc)4ie9rPzr=2kKvlP>KA9r36k4Sr8CKPECUn1&tXZsQnaQ$c#po;z80{xf=qzSrG?G>uyQM7WK)9*mjYx9zT@>X8E`z zMKSO#pD=%*jy-EL*t=o6Gm7)Yi-&L0Q^daif(1yX*rh(W=g3>GwiX#VlJst75*507V z`n(G*3sGF+htG~O8)$XdRg8zg1VmA~##(>X-LueoL+dz_6`KJVZC%VLRZZLv`N5V< zU}1Ao(;%)%jzjd`?F+d`xpdj{7AJ1-`WgB|M<9oJR7jC>GKWee%)|=ODVSh77f!unydP`tOZ;CVCl)RAnMLo&|j-x1fG}p zyGvAd3Drw1tcrqiwWK$%ZCGoMsoChtmgCz(mxH1wK8hT{Be?7i5 za@E^X8o~JD0bB3DcT*~>(!_r*-@)DJ$xmyHDJQ!GU|xm$wnQ936Jtok^EX6BE(ngH zb>~Tc9_I~1dmqF}51f#@?~J5N@WxKM3MyaQ%+f$=?*2JaLOk95hCf}zlw5yM8Tm=4 zO&lndVU9M_;#^sfghE`$yUAB6kz$OqN~vMmquJ>DPpJBn$#&P9=-lP8A@*wFg@1ZEz28zCAGjJo>E``%4WEqcPyiSPf#mcO0Mn zvghdBmDLYBG~vbG&P{!Ly+D7(54zZH4R5w-5w9CyBfbn84&QZ?Fj+6X2DK=Lf?nH@ zX6Vr~;VY#Kodi4%@kh6gg7P>eGj9ev?6$VVBBmKjIXwS4~}Hj(eCAe-}q z0}Sjt_r2X{9NLHBQ_x^4S-BM&xNZyaV2c*4c+=*afp@)|{&nYX@?(D=Tyvhm9>kbL zzvs{U<%bcS{KFPXBh=|6Xtnwm#%7Oz2aIH!Wm< z(#|1(Jv|rkg0;USm?(hnlg-7+^QRh7#aVny%r|=+Ul4OLenmESu5Yq+uA5{QZUZ#w zfo^xZiU?<73(feGKdJX&O#7Q4lM`yr*WcWF^^lNqt1|;Kba_Q^(>!&88?p1qa3A|^ zwP1SbeQ|%tgMuq-h)7u)8x2RWn%(y&&(j-AqQL4;Ry%D5@8q4MQaK|LfaicrO=Gvi zfp%XrieVfq)iuUjL|!#^$M8EL=%;HQpUv7kgg4$IE=j?9Y-8bbChE2M(j$w>JSV1x z9|#i}gq>4xU_qEhXOamgwr!h}WMbR4ZRf_eor!JRn%K5&YiDcmv{hSmANu|FLwEn* zcTUdr8kGQQtqPyvOjyRMWH;!=$w1hM7;~OF040^F-iK#l*F5_MlD&8L?7!Q(kfz-^ zl>R7APb(I_X?B_s? zAX72X1e3+B`C^!Qs6?0S@p%)3%@pjeG0|h}-|TC&wwl$a3|usPx6*_+{T%}Ap;)0@ zAm#;G= zq&t3Sm$3W3%=Dwm<~YRy*<;U>HY5H&$~F_snN%M^SbKEv7$HpEipA;6dxcx}-Gt%y z;6l~Y=S=rAHe)1eDmeI1&xVj;d7TxEz>DHdVkn0bXIY(kPFgg(-C7|*!43f?noaxpq}q9 z5zm}}NIXN{ABS8}25%5W$F;_svtOfpJEfVsXgE7?mI`4RJYorY8Uv2G%wO9N>GNqw z-8-WhJK6Hc%`Cr1C?9SaIjoB%4ET)@;Lqg@^V|`=J=?Rr&kTX zomL9UeCHE?k8>)L*Yv*&%0wcRomX_fL<}MBBxisL*9Jwx`C>*r7^X;aD4P!#z6o^ zx78=ay?c7C-5f{12iZ~MOHG|kshj|PC#b!;R>$UM{Pv{emFwdgX|MMi{`V&Y3fg}G zL^yD`r#|dCZ(a|-vf8@>KydCtS*Dvl<}Ts5TDy{pOkypGbtID@*0I?Oz|0n1O7Z=R zOez-SxRd)&hoI~)Re^@&8d@P_qTjvVG*lG{doAKB|~(HhT1FpQe_P5VX_ zUG!n1iqwFYel82gF&JD{9Z`Vgciq%-X+#9G=$uF$og?~XhctTT^C-77!BXd-8SJS#O<$Jc*yqC!%P z4t>$O?#iQ~Yqe{b-$NQJOAqMJG&krxZa>jCza1oOF?Cj-@ED2*aiwLXrS4A3Qqt@w zcpXIS>x;JgpKOo;2y5b*Kw00yT{4llD5UZ6HzXx*KrlqP&>Mh6g>jB;^+rRYaYFxf z%h5H&Foz26*#!*jy@abL^I&_MDA+zVl+)84?}R$pKWj*g4vHzK`6>3Ng^LBdKI$O) zo7rvzklsA1iELxrcvzw#yPDq&&FHt~6a6fCRP4g()Qtordu3EYnfBb+$|~R3UKPyJ z0ue$NBsUAtXzbS{V@0|^(JWd*Y07^MV{r4}kIqW|)&cW5+EWvFCSqu>)22PtOp&0d zrz7JQX#+HcWzq68=jdR;XNq$4s=t=C@@iLb2hqZk5Vpy{>o`J_hPsWC6>`E@CqIty zTeAL1uXunHkID;afVp}Sch>sc7B!&P{<;cT@<=qR{V%84`gSMjcX?L$>3#HYUI~?Y zG!i_5?)O>Ky8x4;996#3cK5bi>CQMhl0^DMhP?THzUHBL!pHqRnTK;oy`ieOVc6pp zdw&9nu73%BsJG{Zy;Baxr=zf%=xW=&w>0Ie@j?Kp1lb@AOy3kT0G0Y|>q;jg)rfRNwggE6i$yVeC--vM*%HR#)S=-Cn!3e| zIU-Y&TTvzPrEo4e8woFM$8Wd{mWMTgdgz|9skGq*BmX9-U3Q1&>3{)NY~yEF!g(EC z*eWpJOhIhbX)pw0lAACdQ$l;!F{?2eZr##tdsM?E3rY2c!S+bWo$z>ut$uZqZ)_+? zk4kF(>@|TX2_-#MUOZ2c3;L3+!}dK_LkqMk@Hl;6F5pGJkCz!2ui%4qr)|#AbUqn( zHTj7MW_D)Sxu(Xo$Qa~!=KIp=iI~pOh#x>Nm;O0z!%?}@ZyWkjY{e^xyY6VdterTz zMGZ^Pb>)O{B%w6c`|Oa7RHUiH=#p}mlst_O*SRSh6F3&hsR$Nvk}t27H{tRA@G?Cu zOYKLVhlbr$Be&AS5%zU<&1NLwjO7il*bXM2%4$|%i&-c8qSwcwTBeFu;6lO`j0bQG zPT3bI&iJ^mhh87xmeq`2za<*G0P{rpO&Cnu&)WBlfvuUb_uHHl{7WW@ja|NFyWA;V zAT6$^Kc=?3$k#|eUmQd}C!*Zd=k`cTpZy3AP!JYMLfPk=qiKDzcyrf^$R4Y3mCvqP<+V`T|er{_F%0 zgKJ36b0Kg|ore~+9R6ku&<|VUy++%~%K2@Bkof*(&=VQ-b;>3V$__b^ZdI^wi~U1K zjMK1U_4y06S9_zr4W4m8E_(UM&zrT^yj^10t-IXU!tK$w{KVL`3J&Z|DWx4pCW zUn(6gS8;&(SDrx|>UXeXwc4CuGgfxtx}+Xk!vq7hbuF!qx|1rST&^G%9=%@&>tg0H z`>Oncj30DCn%EW2TN+p<15iD4@!ZY7fyoM=rt3N)Goaw`^tfh(7te{o+Pv>XMIn#I z3i$5B(kkoL`Jvvut^9Oem_mH0T>1Gtv`fdtC(w{k^yl!m>KXpSmaCG_$ z>eKO=y1zWDgKbWHdg>pAPTAGPMI<2^pMe^+*3nvp=MQ+tOezziE)e=1j-@1WA6@R+ zTDb|~eW?{8DIrH;klOW&VCxCnv?VtVJH!zcC1k+nVXFH~+ir3KMZtTrp7cdI#^vf3Ww8vnGp8Wa4bkfYuc>;M2RQbuR-!3Nb+kJWVI5?3X z`X3_TD7Nx?vR;}fVBS^tcD=b{O?*$Hl$>kHo*y2YDb%z(2Y|m6762P%{bjTi_Q}i( zf&62NX=}d=1`%CT6rLvFH#mOAydb_SDnDHQ6v6Q4Jwl5S?OT09<9-EWg+x6pCxvI5 zzy*@W4`iI`t0`hwPP}F$^!iUpWXEdS;F#|9@*7Neuu%GmSPshl`@`pD?zST0#xPHZLk<0 z$!3;@tbYSM#mvx~Z2U>){G0a~t@OvpRkc^wNB%B{T_EM?xAq^OnUZTMbF=i`B*nVa zHV+-m?ZIR5l$rTm^dU&8d>#$dL$yh|CQbj;3)?&Vbk9a7K2k2y3z56_+oj}6DkLjZBxj0&cV6RhAK9Qu^lV7D;F$y1r_ypey?J52?sdfDv&YiLhsB|(3 zK3LNOn+dmhbtxCM>C)NmkJ3}UUsY<(H_a#W@)~7KYYa4}2xk?+9oUNz1}V?snv$Hze%FsB_VdeMwZCO=)y$ z-B{=BIZuP6%qz(6Ip`-FNxXf-o~_&KAJ!M`W16^hSF2i=IzB^PrqV%ut@|5{1dYOX zErEk^lj|{9@@fQ1u;H23U%JWzax{ngOIJ44KJHim@pTIe?xl`EY2T&;4*x;bRl;#sI-kR5T0{;8D$$oQLms`%&|{;Q~82uW%ZsaM9brwR=xRE#)C6aEW=dbP%@qM8EL z<6hL8GIXTYIAKQc#6oD5-l*DR6_kM^zAj4LQpAmWLrb;z$$DnLw{f5NX6P5C0KE{- z`8o(LpLs@1eK{$+9l0%GY^yYX-a)NNm7zHZr zFI{d3idXJ@00Ruys!CYZ^)YqPE-J*#AjmljDM7dL;EBF2j{|O!1%tcW@$#cl^5b+J z6h#h^@XZ<-m-{E0h-JFw(-x>W0Ga;d&sp};`$Gc#@^;lWq%MAfgvoOA?c(S7`-KvQ-y{D|HKl%eXHS;7@g>8#QLntS-@C!D={l$s?2CBK_<{|gJAN>fcyWU&m@ns7Ed(5;$NOOJQb|7JKm1B8ksI0`-{(rra76aucQK+u!t&ISV& zi;Xh9Wkna7L8gFlmV#X^B#ul1q=*T26dv?!yJsF3lg!mkeHy!z;1yn|fcq$O!Fimk zsl_O^dGZ6(eVlbW_odNwxA?~C)`(ifyzsIWzag4`zEmP2b(LU<-e$ajsvuTN@%!?Y zXNMu{p1NPC+7EFS6IrDUfZcaA@j#A(-TE5jiSlG5sQEBIjd^g6nWplptm3)s)y*)I zk|G!K@=zl)3Pyy%K*B;hBssG(k-wn`BzY=~PuWwTXgk>S65%?l@#Y zc}8G=pcpxAsjzqv;3OA$NtCMBL_m>oc_R-+ljzjAny&4cbApTD@MO%vfNo<{;Tjmt zn@+mht@FN!bLF^IxsUM-p@L)sDo63A$`SP{m*3!xf#}q#*a!=Mi85s=si~7{&Df0I zoAUdvk)waE(1JQ;i%r$*duL;A;Pl#3g#02#))&-M@tH^@u&O^u`aNCyNk=?iV4`}q zeaAHg5mpF`%Y&DhnWTud!onj=i8(A<2}12_Zxt>QCo`pO2A6BfuByMsLg1H`Y=PcHX zPSnHdytv7sCGIixR^BQTDp-sq4k0EInafSw-Znomt~TEfiIHFSuo zuBkYUq!B9t8WTL4#ZfMVQl5)V;{7{YhMeCPJTw0O&=h5weuef-?`M#V0zHfo8qagq5^cNnIJE(QBM4<2Iw_ z&F{Sc)fiO7EmE@>)(dtI=jV#^mp7Z=7*T9p)5N6RC#$-nL|gvcp@cj%rV^@`reg

xkr6Kt$Y4#g5ZCeS;2Mu|r}&e6F8(UU?5m? z+g!QD0k_iwb@8o%iNXTD9Vcobj&!&qSYC)Xz|JEjjMQ}*?99S1^~a=re2y5Djho&@ zPxU05Il8duFF~a78$WInC##brbPuObMj_Z!`zLbg@XKha9Er=?{Z_|C-?34w$`-Ln zWfjR+${cFl3%uvH#`dZ3jzdYnepX0vp~;FEKO8=2yl+f@KOmdC_Ch@2d&ObQRj1Ow z`Id01KrQM1%n#K8JVuSTmI!!_4=`sOlu5FL8T@35X4gs~VmBh?2DToCJB<~{Cq(cR zHxJ<&6XrATov-*!_K)~4(OpgnBfS-6=$eTaMc$6lY6O^!QG&Sp5}r|@$h>-dzb8#7 z!i=H>nfYD`mRR5D9NA&i$7mWm?)=fuC8ePG;taG|bjUwbCQ|!9DY%S{_nfewR8?a3#YDf1z zjdVJ`5%)wchgggDvl(naXx9koBxA+unEAHn4Sjm>!dk>3MU(@Q%S&)B{}~@|3p-@s z=c5sHGRV?LxS|L;EqS>CIwtX&=cZ4u)g7M10! ztay{-3iG@3Yf$kpqeTN@00e_F0~h|bjV64ctP5l>5>^tj9K~lB%cy#3M|J&2@C)XI z=pI9kNuKLOCKtLi{r*F27&P_Q-6JqHD|&OR+v=D? z@a`_md6w=3nT=;a3!)dEZx9;SuM^BG8TXgZ`^PWtYyHJy1@c?7h z)FEKL249Y`H7Ht7g>R11zZfO+LiNuW;Y>N-T~i%kY9!B`5fA)Q?GTN(A8zHmv@wkx zMPtiZ(5B*CcbHmwFERO%0;NvD#N=*w9B3_BGrl+3&ZDr(!(!GKY$>r5tRKqkWBVt( z1oq@J-=i0Jkl#i;J}2y`%g8^bsqXfe*q#tJ78n4te0?r0%Yu^iT-4{_IH>J;MABz3 zhX7aU$0%dbH`MFqzx6M|Vr0^Bi)%$GxoDOaXb8I=2-u9}ve4xk4k6V8d#dQ%Wd7WY zA**z)nxkC#dLXX?whlRY;0L2<}X zUndE%0E(#DTqih!SxSO~gM~BCrRK%vY+!Q5G{^aIWok!HKBQlctm{$_@jD{FK4y>F zhM267f)X?WT8HR(Z?6BhwR{4*)G{7u8qicfeqY9ATm(cgp`ai@IF$1nYD+sk$nLp6 zNDHpJPk?V}1`i}i5WzRa7VPz(yT>3S?(XiC9)vt#h}lnI)ftih(gX(};F$zAdcOyI zrUfK*LAMvD0Z21neZ9a=Y`x=?ZE*V^PK42V7)axw9KDFXYdJsc0{ef*0xX1Jz)xRy zKg1GCeHlm&lxanPSzdvCn*IB{QlOO5H%|=6>4grPkla|NC94`@kk=`f_iz6WsS}@D zBRgBiTU32VvLs?OL?FHd(G)%3&td!!e}3#`pp8SpiM{*rXI}!6Oa8G-uiq{$;oZL> zET5!boE#R}!h?aXQ`wcYlS4;-yWb{Y00GD7&3&xtrtzcz1}2`q4n9(HgX+2;`JoQI zE;6t2A^nv?o_+a)5#}2gWFBpn&_0GHdVo)1co=^-fv@|3>W`LBc?6up!?&%tCChg_ ziu>PNLj5E0S6iUZ+A0B@ef$Wi%zBY+kF$8+U(uhn*&0ILTeG_jK6Q`@Zo9Rn@Pd4w zzp3>3e`SUM*L+vD_s0N@v2jaGw{K_x27#Td5Hvz7IT@5#ggD;|p93xrA|wOM!`k(k z_UB98C_lXY5BkRi6pOR3hGK zNlY_#Ym7ujwujBg8hvtht9;dkJcVp2A(FM~{CqIr$m`>94q4QD7aDPzbbv~U(f{;# zSR-jR86D7fGK(VfoUtuDs}1L&nUc9n@RVdX)}cOv?R!}HCnJQazm!{<@+qa$@ckS- z-Y5WopDlI;PsymwsIZo*r1?pw;Bk5iA~^7I=j2WzDF=Pkks(k2!-0`)(!2Tk+B*md z0&IbD<5-xvi~VAIf&6|agRlP#i-aSdzNB>OV2A6NH;UfPLL>dw^sE_D}-v-dVprf0XSgqp#TLDvexx*5KX+gPtE)-LR%t4(gj>&o1}mS6(E=E@>vFdya)I3NzZtyr78`d7d;BFD#km$pqD#$=p5FR_z}0E9l%OpPmhAe*tiMM zUXGE9@bRWlU21$MS@MWaV6P_odl^tffezC+irqdU?D?okywo4%fopx{3 zflUUluxUl=BVE!;)i{&>t{60+u-*I$+IEnmS@=xVngsV&ku^a3`#HP93liolcjMeN zIn^sikm_*Hh?SOdE)Lnil$KbO;AcHLd+^Q1)X zZn!#r>*sp%c`ijMUgSWbiP@L>Gtx(Gf{zRs54bgwOo3I+2%V7q;yoYGR^xoCekY4rig1-s%KT9_CUhHijRm_P6 z_=Nu%-+pPh~R5w(~No=Av)2f$xF3 zW8LF7s3CIqn)g&-;_Wfe{eH?^;p`q3h6}hS(|GmC@c8+HcLoLk-do^Oghnuf3T_is zoF|S&_XLNAf^t13r~y|{Hz;QQ63NFC+687-p}o?Cq$%TvCRK>+1cG<%o>8~jHEdHV z>Ly^>()<_^n|Lbh5&9lz{VJK3?L8!C;da`}c#bW0ahol1P1i8{=Ehget)05&!wDm0 zVUGBRVrzA`E||B##p7JE2V}(f^tgv(e3`@xD)QCD?ql0b`J(Y*S9N^dti?oQsXOVb zKzv5|xVH5>aR8;7Xl7zW4<_{T3>s6ck&G8zxOq9lHczDZ0ZO406ImKEkRmz@D+vy z8i&_G`E`>QgXhb_e3`mtrMT@WYi4l9}D(##C`)YWO+?0Ik zNs>n3lL1dPWM_VUp+jawv(`;^N>^m3HB$9nuEA(@lR5;=srynY*4QHahv+*KD%x3T zl}Vv2BMS#$%_4Y<7Vn@m&c5_cXBq!Qq+>tLynj1{BEPs^vrkimsW4MY7s}W;ueUUN zqRK9PW?c8u`w$oTK6wy3{#^fr%Lfu#6KLR3)=UTmSEMk^e-z{0Z8Wq5DvXi(HFMl;5{DkuA`V(RI{cKRfXzCiHcXqbTa zPys2<10s?U5~pE4v+YMg@gLvw37w5ke}oH}Bk-WO#wN4A-!D?*MYOoH?|mn5Zmn7Y zQ6j5A>V-WH_FK$YPzR`5!k@;Rzu-xz#_EvV_6MW-wC`3X&XpgD8)L8R>qsM}pnHi8LX-B+e%Fr- zFrXAeiVT%Cw$p=fr#vj}l`KKFS!QUML13hSIL=}eI1>E+Y`NXAu=M^SE}K`lj=3#up&KBruk1a|!JM z>rg134q2rjJ!ub9`MY_g$LPP~T7^32Vvf=0y+(-A&#I+%#ql=Ia;!Hc%zUMqFvS!ydUzVR=< zT4Q)t8AorG(iQj~>H5&z^Iuut51t|=2@n{}(nPl&=NV-0lp1Ux;2Z;#2 zVT<3sxI)|vhtb?$JcnN5yh{4j1x8pnz7Z)bWcfUpnif3Hc*5cnRBnpT47oX-&0?Jd zr>8X+h|o;)4}`e0cCu0EmMX9TztkMzy%vw83?3WFpK!6!7za(kxs4Ypx8L!>(+xS_ zd5L2tHkvmRl;9i^l9pn{z+7D>9<8|!OPtp_+-LZ6%G>r`MwJ_Mjd!s+=#|oP3pO#; zaG9!XakQnSN~zrvTjhj@wcS%TT>CNP&rtYqlRtV!c<-FHKR#3YGJ?SXYisQDf!+Q- zap7-IchDzByJOLwIE}mKUc&CD?-EY&gETF!>_QJiy7by|>+pZv!BH*VaJT4{OsB-`!`c|*u%Z7um-3{1$iY@}I^KFA* zbl%RB8ceKOd(8KI5;@O%t(>vk}Lp$Z?~5BXI8Ylc_BRhBh@Y*6ZI@p z=@KLdW{W3;Xq_~g!YVXHWz~I+FZ1XY z>~^+KV>-GrVmd-TNDsk^R}m=`Xll8I~cD}fnywz6%s8JUy|$URDq@%chGf;^v%U3%J#^=BVQ$kMQzI<$u#nY-Swd7N|4=| z+3WWs*c~9f0aE=!2>$HkI~odUjxqW^uIr?(L*RL>lJ9ZH`aH`JNNVn{*8>h23ir|#s#fThrlL5k3|=~T8Y zZ{493aj3KOGl3Mkh=F*OES6m9gI#nmdkmXFNgKf0pfPJgJ(Nh5;+W0xY1m*!BxORW zIxbkvAI0U+n5GKqwajvf5{xw0aHLN9`Dgrqq!_PJ@?n~m`a5$@xYU<%IoJY4Z@~;N zJ|s|lxrUB!TJjpoL}}9dn?)}@kC`6{hLBh3kB|4=<}-C);4e}1c)AA;neN8gu)6jz z*#lrpW-iUiq|C$^yLjuAn~&pwrhqP-Q~lA_s5OOHsO76>yG5GfR!in`IG zSUAbduEHLn&zy&#&#Em}a?>{bi|DtDdFzFPO76`GN&g=4cS(Bm2*aE?QOBRNb@h>* z8S^xV%T52T&N<3<`b2c}yauYNwe1KxGnIg0<1lZblqq8MIiE-1a6-kJ*4*$*0+OrZ zxka{W;;tW|wu~_hZv%lv#PuI3erQ^w!6*5ob{u=&R2&u@ajyB|K1;YKOQ%-dcBkn9 ze3)vP;Le z$i;N;CqHTD{%&(prgPm1P9zOKM}l%vD6@Pe%6LefO;E2uEF$ej!S1$68)Z#Kiu(;> za>RAf*fug2ql9U075{42g|P~9&XO@*n#pNJsw`!DD8D^p z1@k28raIo!LQO@JXj+5g52Q+9KZe)TKzittzH%8qN&d(=H`tuM{8ksTW44bIOpMCx z!A!Q{opm@0&syV5lfj=x+QjZs^$|Lm^{o&p$3YXF8fZJ;Wqv6v!pOTL@52Kwvc{d_ zAk8($3aik3YP}L7WN|Qv2ZggG;i5=T_V(e_apu=IQW+(@SVP3G{>g55gV|1n`KKNE zK!3bIEa87xKh4mTFXP?>CCOBkSM=bhe$=)H_;tMm%3tfc-=Y+*#2yM3T`O zZmM3TV=Nr8g{R2^@fe1}c^w0|ihK@R!+$^e;BI%-EXF`a><(_Y5GTxc$!+oScw;#m z9&9RfzCjBs|BhusLyaahs}iPHY2|-7qWO-Fs5JH%QrRUZmcP}ZW^;IUT>-tA({BEx zQqFxC5Q2iK?SSDQLw14EVXj8)FRF^k^T)vJ3AT8NtXzq{01dgNZ14r>pfAmFxfaI< zzrSn<^Hx%Y8I|D8;!#MLngC9T$oOAS zGOISje{PN@R;?sXy-MXH4-&fSqTA%)U6A|+Z5LlR=Rh;YF z_WkbvEjbldO;SeF`+KU_UsiVPhqwUIzL~+cmA)yp)wWe%Sha~kWVMk&%v4Y4l$h+) zH*tS@Bh#xLGkufGNLd@98(U(atE|zlHYh5HxT`FyF{?Z%j+3{!yqvnbJmF_${!jXg zEfEPavggS|vgabSMY3lBhg&S9I)mqZgF32b1F|NvXz<17Te{#yG?C|7G!e2U88VdT zBA4jr#V`5msB^0*+E3I3BW!=_1@OkjpgWD@P`Z#34{OLu%@FF@M=CGqvZ)%GQt7i6T@!`{T;FvQNnSYH!V z@P=-S)Kuj1T=B(--M;))eP;Vx2H5K-{~99%>#7Yq(QSxmY^?B$g5qtB&5G)bs1GCV zip;7F%ct!Mtnb|#|3n8&^bGYcZoYoL;|~DaAWbGfX}-Q*QK9K)%toL1eBZ`^+GgJi z{Z0}1A`tf4tUa;MS5ItcV6|g#mm?$fS$FHI6Ln!#$@6Kt-aY#6sl-LfNGc8`U-p&U z+r2^5B;qoJ)@1T5F$rL@+Od3A?`+w)gGPMKBk+EFIX~HE?Eqg+n4qSjKV7|OJyro! zsE_WhuOz2W_uch5OX*Yf%at`P zwIu_CzlwGZ(;iH-s4-aOIUHp|#b04U=B!+fmib$i)JN-#Kn(^9`yzKoUx(_@xNE>r z8Wh9+O6Pi93t&sg63Xnyo1Gd-2Dzj@S9g zJyMypBVg)=WZ8Hyq_f5p`bB~kq`m02$~I?`KYVLVE?cBYSl!E+>hklqo9pSbNSW>n zQjK%yUjRm>dtO~qT)Lf{C4<(ePW7Z=?;92Y?AjTW8FR8lpLUkxfzDruj|_QXE7tLU zN`{b{w3V&}Ps1h<&5-mhn4YrO?{e01)F;l&C~*lv1rqrJO4GP}&)?)BTuOR`tec4J zpB0jL(V%(VVq~PyF~TB*r%6mJWOtJwzot16tpJEZ%ur+y%8%Gh)9_f>75^(ogjTtc zKP2VO*6Crj3hv%l45ybm5;q-wSx1)06%668sTRNvieIgZ-F1# zb{TU=IFwp`#gC3LNb1}_H~Lch@I8+{wyv#U*!O8QK$TJl`%Z>_bjHl3-`iNps1>8^ zH3Fjc@=khsf2#fzyH|v)l~f|%zV#DXN%3XBl=4#5UK~ckOcimFWr}X(E+nsiVp`|2 z=y(5FREuMWKMwMirMeO=?XAb5%gzgcXYx%QsS!P<7-`nYG}cDcMN&>Aie;+Aqx%il z=xf(y0Sirl5iIC7w;hI%^2lJ1i^|9J>j7|OP52jJw##5j-IMrL)&dsCc5O;DFkebC z5dXbhyb#tdzy1$Nw1SA|P>xABSqd!{Rj&n7AVr7Dzu!fh$JcbA= zyn;P`WQ-AUR7HMfd+JBF4Hcf8oidVaj2)aCa$sR?c?D{wck=W)hckt4;QU7-Dm9?1 zO}g(F*q6IgDi$#t99RK`v?pP44Eds9f>;J&%%pl}w>37bpC06nImO)_z0TH&k@NW2 zFr0ytlZ31ipO-&#IW4OYYw}%cmu*!&cIB>w=hr3ok28tRA~@sePn1f81BRN9n}P4@ zTZ_5fAxj#64j{74nTbYr@Yg@T|563e|JwHb@!_XAnOJkg;#l`o&$*GZ-CyK|8#7-r zswEZv88cNS`(sMWBOw7Xh<)|wx0eO=jS1Q`HUo$*tx2@H@3Hz|=bL;IHcuMGe44k? zJQ^L8#yypem4`(x1+9Yh+E}Xwmp$ls%1U^TCp+N|jNL^&uO1315&WYwO!z<7S9WF4 zG!nrwAT>*n{G#mHPcNVGuc$zC@emP_MfCV{DTay;Em~QfO#O1ku-=r!=w5kF{%Mv_hjTdcZ~$Vc%DmQy+kkDIGqetBotCgh+$t(;E#bq5j`26_bISZ zaL|IH=c1VUa{Fi-C#w`9(a*M<)ZniuFi7DT58NE}>Hr@vA;y$1w*UyNwGjF8H1W6sz6B5N+^U~qrT6jv8At|#hv$4=7$)$mbmaETGTSkp z{NgvAUX=iB98|A-Hp-9dxh>z?L@T1UB zq~Go8EJ~9$0c>%=78Y>h?3e^K;ojvzez_k}Xb?@|m;F}vm^ugbAY7!yJE`a3(2^D? z(uF6mU{4Z$7D((UXA{w+V{r-nDlA6_cCpne)U^#4)6L6j1x1RvIf>QT@#(&@ezP|M zT{~_OB8kDG=+Eo?J*;7cIq+dXq-$u9L2-=tY$L~eysA$3>k)`gEQU79hD7Q3N$8xL zXvJqxK%2a@%XJKw0*kHgAJvAH(sMXLqKOjZ4mu?)6UZ;5Y)mvLa82aID!YzOl78C$ zW9s0*q>`eQaSE*f?zX=wn}oPN8$&JE1Kbjs?G{|*MrPBV4b;!BV_Yq0H9*o2MbAou1?~V%sVgd5~g;b2txW=aXwT^r#S?)rS3|A!FXBPpjt zfZg_Wg)P}yrdOcug|*YeePd>+AZ}55LFc7BWs6nYpjca_+ z56TdXrAIJbS_VN!L(7(Y7_Apv)AwCI^TSU4 z(A$y6#uE(FvK^yueNa|`A2lBfRYsUYVa|6K!ZyVnI~j}8BAOH5wnKhFwe)EdCPmvZ zrDFV?_i9#rPIBD^BKLjRAzb4(6-;j-%}IN_>zkQSUJf^SSQunPvEoc*D@UC8pl8h0 zogGjprQXXnSs^y_=U0G3FxcmUml_`WRw`QeY~6kB4isg??JLV950Go9QOt+>26Aj_als@dkzIElGa zv`*YBr=_m~%30PoM5|XGPnAj6iFst0)=L1G1=P7U6~E_v8eXGvgQyJzwum&RmV&OW zOU6h{Z_C{#2-H}&~^0!}XW>TC7W07ia+vas)qi$|Zo*sQ-p4@#PUH?{_r<-wAFR3b zn8~=#RG)8(VExauj33rx^_E0bzpzkgj55#DdP7GS?P8AwT_cH-8P)1)7A)}x5nVIQ zS5!X&dTZR)SHx;%^^LC!gfaL_As&HXEmU3f2y~Q>`1MbSfHk3Jd3o1CeI;4HiLGPG zI1dSJQ~Nx0VU)aS+1B|9AEwWnwEL(i-rQZZEs@}oerej^>$)>#T$^r(LC|qDDcx>p zm&!M(zHhe;x5b{-N$-90YI&@*r8O{wS%~b70 z@NktebxD<7WyKVmF(oOI({zlLB2tLt22!LRoON`+vvl40sT#yrmkAbw+TGiyglZ%P zRr>dMqP=lewo|K@?-mZ%M*;vH#@fX3G}&7gQ~HD2)lbs37dG_fJR1bHv$l4NwJ{nf zV^OW~b+wyIsQVCgWU1m@xIU9tOFa6r%ylcCXJgi8HI!|NA@R)@Y#4EF3Gs6JCp>M9 z9#WO0wn^2$h`QOf9azrOp|NFWtnP{?k0(ds-+~u?J~VEG239U*N<0CkRu~3tuxsnR zO2pey>|$2;WY}3w<%MB-^_j#NI%vs}8e7Gg*5 zN;Q^kq}5hlTfsm5x*=_TE8rfi*#6>G$n-4Hv%@USfwnM{V$OXF91gs1l4&>WfW z|J_o8hiuAoc+^sGI_CzEL)GN7&4GzgF8Bw|9(krw!mp2SLWciZ>Wkhy?`^V%!b`r$ zq$|g(H0~3kGWnY;&!|+ph;+*~l{Ex4I@gJh%C#|HE=#)EBX+r|5_vd&@e;bJd-Ot= zXG=}nO2d*p#tg&YXUzt>4Iumov9fZaqa#)432k2bG4H^DR4N7FP@=vJ7YhX6xkTcJ zz|J`M##d8&PhjH<9iiM`9GKbOEsX2t6(j%o2J&Q59?{r<*!RVx>}K%23cD|jGG+ZZjy(+u}qn(FpM!x1a?*8@fA}Ct(iNO zs$J-B^znp!$&G&Ca>1lu+Q9PO=RAY}5H%zB?M%uIFjnd?RgkAKt7N_yqn6u{ROwpq z)7y~>k&Sq|Vx>rr&=W>gMxT@MK`lZG{4rJ2Pg8%M_knu`DWMZxy!pA*KTe}Pw>Fc^ zVHo=~P*qK)x3GIifDxu2J=N)#fUG#<=q6N*j!%DNd%**k2C5Y@qZPnf=LKm@^Ih5S zsMJXYl!)cSj;Rxew)fMZe(zjh9C>w^$q(eABs8?+p7Mu6aAa{n-c+Mc2p!zQm$wS3 z4X&;y7Wxot>9xI@BrraTsIiRs{@`*%5&$_&-0{mcV801X*Xxd9{ke$qvTiegA{R4F zCFcDWx!wohc;uLwl+&7h^Fzaj5BG0cr+mju2$uv8r66^7${aQKc+UuXF>e_b5>EDU zB6G-NmZ=+H4oMs1B^hLfyd%dacIw{LvS8v%=tdr`RIx#payp4P4;wWNwx2&MVM1pN z(fcY^d45LYlzuwU$ZxYTbjojFj`&Lg)WPUL@g4x@bKj9i^x(OcC-@d0pvyaD1(jhq z5C;F|Eu!u5^-X{foDImqaV$IC|4ioIW`t31`2EbJap47}GVQ~yMROIN;$CiG+Mw$~ zk&pxGR-bfPp%dTc9LdE^72+deR7aik#dsAu`10x2S4{=)n;s0hlqZO)Th7H`|h>R0fZBxMRM*T$NNo)*3n5+2tfz zFSOj>LWxhnTnJ-2S041Y4-XMr~=1PO>zdoMpYDo$}t-R#ihA&uC?nfpDZOK-;m`#-lv}t7gu*f(&0v z?YPyilzl)xA6Uv2=CA-{ZI>boCmcXm=P?7Kd8S@$W^6l5+VST>TTo48N|T%O{_p}W z#tqnvj$bFoRVR01Kl{XOQL}V^BQkB*5#c?gu&zE!7@ITn=T63Q6{pHuf3=fyR*%bJ zXr25?)uwbuRIu*!Hk5JG`Dt=3sUuW%05w!2MJ#0Zf-={vufVX=J2u|R}t{3S_hEjI1X9RUr%P^(Qs zvvk>)x@LRdqztm~@OZp`=zIvN)fokn@iBz(>X>556roPBbg&)SQ)`)DaaMopthe}M zIu@J{KJ(be&+@T0A`}PdKPZl=T=cXwU+2h==cy`%5c{VHE3fRww|@+%43&%UH%r&$ zh%Ogq#RC1?CHR8z%C;B9z*~F(4V)oyUW1cVECc?ej<5(tmk#t5%NEgM(?G6S${X8D zE+WTd{?l0R_Y5OTuPaT&93wFYu0c3S>$s_=q|5=r`Zo|`hRu(%^nY`>T?C_7i&_`C z2NgTd!7S?E;*gn)U`=@U7pZ>(Ft>95DIijl__h}V=Qo2TY|!YCY~_pqD#Vj6CXBzn z`?R^k{{byP(!Y`vC_etEU}1EQ0lx@$K9_tNz;~BU$j9CBdDJ$Z;pVKnqPaP#ncthkG3amNY--4Abp zj;a2wo@rlKgTv&+G10{%4#BwSUs2i(^zLp^t^<&RZWiESGf-D22| z(+azL)iXSOONA4kt(aK4?}fbW?)#kj=Ms;{M-90=^(p+24NTN{io06ZD+z*&vx{gQ z4AM@~_p-ywh$IWJeV&NbHKk`{WY5JJ->^}LOg@?Kc?G$I={|fQF@JtV@rb@1fdT0u z7tx$?p)Rxwh6DRYB@-Up$QrlvqojLAPS11Ul8ER6t%k%1$fykb^P-KRp6a}+H^cNj zsL0yV#6Uu|C%NbR)C6o|LeY0vGS2#ffZd~tT|G;3e*~EP2qc7m;svqYzJ-L;sq`GU z+8aq02tBUJakp-(kAHdM1|D9&6k|QU*Zoyhyuqny{6NSdb;M!^ScZ@4t^p25RA2Z^0$$!jHXs*=D#d;vd^^WX= zFQyY0Mol|qex^M%+#B#@C*9rhS5)fYJAkM+G_y@l0W$EWY;3x2e18BNxNI-jC6E(I zy$UUyjqMWJvgduY7=u>AC{$xu$&lm%$ABP8|F*fIU%!*}8`@<$epg1Wy&IG<=HgM% z5~nKaaf0{V=Z`;mcvlnXNE6S1(P%ObYyO7c)MDXx+Kxo`L=P$~&eUY^OmJE;E5Eac&ow?DyE03X2JJMQbngO9gQ7_P%Zc~c26mDF zb8{mAcYkpR{53IB5dU`>HbinkZq3%p9%No)G)&#xq@rE*P?%^93&LwgEnDrxgmw$W zeT&b=Iyy?8agoUScN`xJ+~}29xsS}9Uc`I@-rS6d#RTF?e%@s}!0V^i*FdTG3d zJb#ao6iNToj+i>vp9l#PSlz0$16kzpJ=BMIky*w$S?HhJ3UWst;W{noq5J?$kpw^gVc?W*MHU7JYnNm(E8qR4~XnL$3ueDKeK83ZKx9 z^SC;BU=-@Mf0rr!ihH%x>>ITsZBt6IIbz?6v7rP$?@;(zij`p2r0KGAaE$S8jDMJ7 zHIn@ZFY;+}Dve%WJL#UvSK>|Pa4U0ghtZU%l=Qk3^v7`m%Cm)rQxJs!QLJ+|fC0=q ziGffLjx1toh)Jzi8Sz*6egAvH(0w5qzKeO2oq1{kb#Bw5W$Ys9Rd_E=kv4oxK+)PA zp{<<5t}FM6QBz`Y#Zn&vc~JUDKYvG-BO1iLnbs{X*~d;%95oe(NIQP6L8K`-X~t}b z*q$<0wS=e;;xG(vz96)%+~qAP^Z78g^7F=?b}}nfNuQMb9VuRgYAjA*hGbEPHoxdu z-UkhI&a63N*2n9iGb4=j^F6TEKr#;y5PL^iw0=5Gq%_wJ(PL6>sw%~NK7TX4R$Tz4%+kOOyyq|F(L4VUAMbR)&QPJ~l%~{a88pV*$RLY~P;r6B4e95@_y z+3tZ80xKImP`xg1SBh18HTXqDYb23Uc+f_V9gaxC55kZ0fAa@F6q#$@Zai6~d<{+- zZ+Z=+-r^X6LD%N23xBeG(g1djBWK^%L%w?)3R#;N57jBXzgHr;FN#X2T{*!YJF~y9 z{@KBoOxRoGH+NepRWM-mdF6rI3PMbV-@ww=DV~Yy%lOiw#J=wd6a&e?VC7jmVw~WPfYI;Qmm}TjlnH_aQrO z`V2jDiXp*1t)5<{(V$ETt9UHJ;Blgtl&p=EkD4;0Z^E62=uYzskjPB5E4LLl1IMUO zye5y6-firn(geJs-nD_tXbHQxDYAs47%!?*i6VrOPCrbQ_Ux^s&ti53k_)pfhTt2r zP9gb}=`te^%ztMnbVP9BODdrtgVHF&bhiSF(A!Z-4KEKzgZnL%j^t`PZBa`IXokLo zgy`UZe)L#L;HedjS#J`D9n?`Mf$jtiH{eX7B*`5hrZ!0e;ZSoX3W@-JE|U=I#tZ^D zIg_8gM4cQu;8qGf2rfBGI{T}l^~lgRzj6LkXe($`@qZ~Ygj9SlF|AYe$4ea<_hv99 zi2NdKX|cxBk+%;VwV&*EhSiFI92rKRonzS0hx8y&RfP;#gb(zgl-LKR7BG>(#kcVV zmO-(xP+vxt9{o_R4x4rUy&hIrv6nvnz;;LOu|0TqMr$-|a!i&FF0W`GILJ~%FQ;if zVY0=CEq_k&KKplEI^dKt%v^Q{d6$Tf)>omWxIc%a?kd^!Z6mx-C^5DaJ7$m4#(=5l z2sp0}bTM5jA&kD;&MYcWlX0&-e9N8tM6_)Mui5IEaTrG&>?TE1-W>QAtU{Xq&54jA z4tB+D-u9(Xsu#u9=pDlv%pl=qW!gBoXHj>HC4Xb%HOyprMj#e@VURCg@^(34)wrr zj;Znuq>8*AwREu%1_ygSk_piB z)qw~bo!C5hVFGkB)dit8KZklqgXdI?GF*M?5CEQkkiE{-85)wD{4gP` zg0^>cic)~mV^9@TD5|yE9SaFl#yWFG!G^c~bfZ_1QK$+GErBY{+UPpcvo_v_%zu6t zk?lMokvCUIT^5xMu_hs$*(ReZ91x6S+!EygZi3otK=KG*{hDxmY3vx*SizP954{uC z3PwtiQ@&uc%996gXQA);0}{O_c;*X;*CpS^RCs%0tE+`OIt*qJQ8CF+;n-F z8gD)%{+AIR$e()zWJgS@pV=+|?SE}z5pibw`^aZKiiuwa5iP2}^Ui|@O>b*vU$j4@ zMQ~W*yKMOzpgxg6l1jJ6Ba|SQZ9D+E7l8u1JKj-Hh3Y!I9=jJp>)XMb!*UO`IY zGt)l?M;)pD)mqSIy+80r7Ch=Q%<>P7Hz}Vo!M<;kc{)8%_PiBhjTA#&KB-SWoxv)F zge(9BcD|6+QEJbb0(@u+0U<|R{(=Zi0rfSpd{c=V)ym+EDH^z-u)W<2bR0~^Y}p*| zK+$*YSm_vJzPE6Y(V~w3!+%Iy$QA}-k!a623L0jqRMvw%u!n~h7T;PUgd zi`78KrU?%Tq&5p1vo0x&^Bglv&Xt2k~7sHE*ZplXf>8e)xVMbtN3OqRZum zSY{1|*eJT+RzCp7iKUzCV|-cFy5u32sV1Fw5;|#t*S;%u33|z+6MxAKP(j4Yn^n@; zeIH*(VK94)DvZ7;(l8#(aorSVBBkj*dr`kpG|PsDV+^LBpderaD-SU6oat2oK32oh zQ=FyD_(j3pX2Y{N4J2_=-9~gA9Y~s?7y(n&$dzNHORs~AZL*w$Gj*y&3K=g3xBosv z3o%i$y}%1Gj3Tnmqkldl?Uee}5<3_75t-q7Vz>urcSXOeTEh{&p)oC;v{n%El{jG^ zav$g5qW47uvyATd=zjy=E`qH*ZLnWfHt899 z821S!`ANd&tuCC~xh_!p9ScB4z*8v0BdVr0x!uXQQqcFEDb^aj>26r%3bZ&!HA4 z@WuE?)pX_L=zl~TSf<`(Yy$%LPg{*G@l{2<)qe)_fl`HV85^ZlIk?h z>Q0*5#EJd*j{%9Zry^vFqF|^H3?cR1`3!*SF&i|cBydd=WgB0ALB>Kh^%gPu>n}dL zECP<^DfZ2jT*B2N=;s^`rA6&LE#GACI*GEF5x>e{$bU9*_}XR}UCCW#(5^y< zx=?dC&-FpV+ctrLORGX7I{6&(v&pSY)qR+TZfI6pvp~<~@G^xGZC$85aFnhyw8_?} zcK9WTFE5#00!#VEn#cU9RcCJ^S%0jn3#4s({Ti z6SA}imOJa$!RH7XKf~^?oKa45bg(`n%9Xg_8px;@ln>d!h$W+M(-2Wre8IQp?|>A)wWBTAT|Yqs6pm{I^4gc0M>(w zCjnYCvfUHh2QX5PvDNKhL>6mup1a=`h}>7qjxzWC+d>fHZ@9Xlx_6#%mN3h~%|a}M z2^}o5*Lo@(AA~};Ac1*!T%nS0Wqs2Pufe8b*D;2(D6bHHxidVP;Rh=^%3^hNhPo-0cQ?C*6lQLX+y;f~bd7 z;4H@zp_J&UzzDZ-l5&ydE~A7rS5?+6=uviy)QB$S%$?<{STfi$K1pXiHo+nbz2+Y( zMFG#C2hZEtiD!n5I800lQ8TVsJQ!tTyMI{2vo!MYknfi*!0Dk8oIl?q)oU0l`JnXVb+Qm3z9I9Fad2$8LD;)HVnifl(J8eU?el)1?p*ziZk#`9a{y z9wQkIPRSef?hny5uOY`dcim5`)|y)TsZthILeN#>7a}a0OF3!xhB+!RN`*C_B7bdl zaW^r_u&S*;Sn4eDZDfa?(QN9%C=Jf9j0II`1=lrPF;hMQq{|fHh#S28u&ri_k>F{? zm;c6{#u>#Hj0X|1NuuUhK3^-PJw_XX!##d}e6;+DIV*Zwx_u#kTZsf7CW z_-g>-p9^298V5xZ%p^e>h&tbQB7%vJ47Ckzlc@=n&2?7dQ5+Rhjm_40G=FJB-gqa+ zehB#b8jwR^Fq%nJVcLGH$U#l?C75zN_x*|Zdh^2i(y z9){%eNg`Kj=0|eX8fl%lAAh9)=(40pqlGL-J#sasik^U~_Uu!^%gt4H2QRO?QaGtI zD#=@X&{P<;H~Gc=AwA>sb1N$1YzsZy_#>f%+s-?*g`|O@25}Zg0RY*}F@%_~xP)q~ z4CwuNTar@6FVMZNADb@_1V;~(5p7oB#seEswqH7p3i8atp-MdQ*?<1jZzj+2NQFPr zW@ME!sGbw(I-CI4nA3M-d>4Cd9R%L!>P{_RWL)@{lRL(bE0)?KR@!`&Y@6pnm_MYO z31acC?3Ts~Cg4+o@2EL+v!uJ3p-@9aVcva!ACIfuirP56^DFNbiaR^>&AHDf$aLs)3JwLF3S9J5h8F|XZdTJ`( zM8EYHfbpPKl5n{0AQ!uPuN-Q5^02BtmOt1cw1iLIs$mFi>_=5l17STwaGRqpW|*#X z+jGxfhzy8(qV1aU^F#lV#YmHKTi`9nvy2>Sl6ieQce~;?{>1rh>AXRTqy1<2NRwujQ6I~FWDdC{F4e772R_E?nbFCg2l z5kJ_1$_R^R;(tePy}#&-T85_{Mc)*&!g3yl<7Am1UXPdYHt2azEbQjhrc=b1Pr^wY zhMwT+tdHfau>_O3O!@IVW&M3YcohxW*`La6^A+#gj#_qT$ty@>) z4<_o^ikjFfd;*l4Jc7O%*g#OLzlbC6j(U^YCUY8V?SCBGPd#_SWl2L-?7Tn?U9Q#V zm~WS|dqERDNcrYHBz;hd1%h^#EXz}2BklOOVqL)NkAufv@!~`NR@xwMby$a`gL7mc zWvUo~_rw0E8Ud1bHPy)L0?S)727z1grbU;&gO<>j^TRk^V8z=mP4&Cl9(Vm@Lu#? z4M4ZcT9XWTH&>;pZmQ}d7?FJ;>dUgGhy`g0<0fO#dF{+h3_XD1ut1l2yBi04ai3PuTtN5~TvDX=cdIhBr-hcg^ z#Wu?m2xno?AQdoUqg%=y`r~Ve%b|KmhYLPx zZi>U_jCrx3pTAA2&saq_9@R z+qdY6KX);-d8ht#z5nWs7P&9ERR~57;*@oeJUV6p`~btEiUMtQ`H`E;UH4In5hLz!ZU2tmGjq(sd%G3o$sQhz6BXUqWqZNpcRUAwJ2rzm#|HQjv#rDBvGji}=Lo;Du^ z|Mzqh3#LVTbkia%j@#^d>sIc3I9v8`iN4bZ6|29a`UVCNKNWphN_>M1{RKgPapWZ* zZM5}`5;1GA1udw$HYt+fMUQ%ch6#*XlFKh53!q$-^l}QVM|C7Nn}2oA?IEKClB&zw ziI517MQw3-82-FTW9W$K{uwYUZ{S6HPH-Ih&VT-5MNq$K%8uA24qTe%b|;Hu;|}0b z;qG6>++Ekr;}5;Wmm)$4igUlPIWzB|G~ubr3vf@iWs(KKWb3ovyVsl=fD|`l;nYk= zjx2)SOMRNnXx4|z6o1}%D63*$({M4GRIlQ~vl(ja;BhcR2BRv6tlfJCI|V{q<<}0E z!nW;XY5^ysr@`kxR6D(^b1B1umswWd>ZV-M(svo{D$dJ&3}+K>yw`vIiEB_l0gLVrkWu1T*OVPZWq+ty_d)*@H@5hWk-bc4(Pczw@({5@-oLZf}%)+p=dL5{(D!?PDV4 zm53wXQ1+L26MuOyy>i%CI8Mv4goaq4_8_-h@4Z)e&IAJS7S%Wi{QFbI!-)eXAcUhu zb!C^G4|?M+b$&Dwxs|{Az|a>q_$g5v*8wyjeCH26(?~7^0+YD?=rVjWNcw9_LF@G9 z(FqzDVk6M0p=2z8xg zq2ddLmTFpXL0@d2h{<+a=$jtUto(uJrFzQt*YpZj`Lx&U-w2VVk0CgR60@_f1AAkB zk)$N=`F{`VdP-R!E}fe1I#~_X1QdDd4}CGi3W0R_A5{x%=`|m*S?gQDcr+fM_CW>6 z7%S_gB?gwrs^3ZUUpFSd6cr(wZNE6Fr}+otxqy`n$35w!A{d-WO0c4`S$8|*;k|PX zMzf;0M2tdLHcSF3Il(`{tjn(mHf=ErY;xcb;eRs&!Ri0=l~pikiynVqm(`b?{e}7k zM~m5O77!Ytm)*`a?f`B700S9|&kZTH_tGD`L1>Q=e}i^jU@fVqV`sq&RUB!Y!E1Rx zkD_ua6dRBq+mK=HkUHq87_C5Q8`W^USf_Nc1<`e@q#G`!k4xaT%uvF$B9o1DX*4X! zr++dyX~`Nj!_lQmu4!_|nQ+~c4GWdPF{Sg?D)pX?_h{~vciP-}mhspvOwUti3w!INRB@@GGpa2Wmdo>X01WwK171MuaC ztM9z5!{oa(b@Et8`W3<)4Z|ypAJ0U{8N78{A99shgT6taWl*x+V zO+MrlJ{Ig?g$zG{p!sbKFa_A%9Ao! zCn~4Yxbm$bg)Rd<ze z^7JMZIIS7O7SV7Oo4m|c9LPcilYbh}h=OvYqiSR>v+UFm=p1qIs9LZ`?Wb1yP06?t zP$Ao!=7~FY)1hJl3)Bg!frwZXM^rZi*gDN=c3k_xJAK zF>O&uQv<23LN|yfM|H%&E z!@AmD5o2=CA1z68n;i)H_XeljFysna57oMna>+A8DFj7Yd9GvutY%8p8TJK47#kIC z0kDpZ$veua2%f;Eo^twFd7gt`nEH{sT&?{6gUEd{OS3TU;2AWfm z;5-?-vDk&oXpcr3g?hVc=155h2FG-p2J;EHR8VdJz+$*poXXL9#4w&LpI^fM=50OB zxqbc2Oef8*9sv4#yrvn8)}C*GQ=6x;|a z#xfp{?NZ-LS2*(lHO_XkodY2xq)_W@L?Of0j_sE|BL1RHp!tpX_;D=TO$50-jKUR( z1qZwVdq1Ag=gg;v3d;M!m#U$k#=aa1hRohU*@8Oik-v}BT7R~6z1kA}Dp2`DHRZ7X zDBM@HI36Uoi1j0p1N(0U%{cTW+0qnrD<=V>#Jx#x+TH7I)Js=;6znVL=P#LYb9qV} z^Fz4uiWFU2Y;q{oC|E0$c%NWZF!nV)9`zVo@Vk9GzzC~NAFduQV;o4F-6y4Q9Db98 z2*y;6fokBH!hhvUL1AD;>FR%8E$4MTZYQ*6(E;>V^ zj&tfj881ha1DL~U70Xz;F3uLRn1r6b%(2T|OH=EQY22>GV}R+0$GK%Zk`QX7Q9f(7 z4438vJ`2%Ov-Gac3AFI-Y{K7K71}6NRI?injjoY&a(}YpsnA+5tD&3u>Ov}@X0>jA zH5%%rsHSVitcVfa?A&x)TIRi9vzIFYMDO!(9NtUa8&hP|WVbc87{zvT28agU$rKCs)t3=-60isGSTO&#CRpo^?~Q}SSQk&e z0U_QlgQtzBqM{dB2kSRDG0W(IGhDsvQXnD3R)4jwYZNH8y_g(MI^9{!-fg`PI{2`E zWhppvq%wD34XoMX#m7~)iwld3;n?ci1t>-v4Fc16!fhtKTq%^c4a>^pmqC+7gLjl#X2*RQrs#$z&kukysx(Gz$q<~v4Wqu#=j@6)3F@{S1 zHKkypV22uwA#5I%3eF&k(4yK+@83>sR_aX;!1F-0Zxjso z=OCB_?dG#=Qvj@!V+bC`!p>Ef(8wXp&G)DnbK29xY_+J}F}8bb?nP03COMtEk$=vV z{9&7<^aecH#`*U>o{)u7fLTfK6#!6$!`L84q%r+>ZA>o!08?eM$XKsjQ2?!;zvBzZ z;9iU4r(*|4<&}HkyhF1+w;KWnTnP3VA6wF7Xk1CXQUDR$DxED}8|F`Cbfk#Q0@EIF z0I11vplYZ6g-<{qsJq$@{5H2)nt!IvF-c4Dz*8%i(I{-P2mNut+wmHVAtHu)Ei|jz zpDCQa`&#D7P>mxDvFq$QOsPH$PAhC2=ryQO+G8U5*p_=qwyo}tW1(3e<335w_taB> zC?`2nwTtW5?wj!1@&@h#e4O?DaWgB!5vVo^aH?Bui*f+YA4L@-4 z{1IKTxg{?&E_D_FyluK@6EkUfOWWP@uC#Y*y$=D%D5>$W0~VaFBS-)@^i`$pp!+w%uV@CEDR=l<@$SECyXiRvv-++|MN7B9!r9n zE@s@Xe5=v(9g}N8Po^3U(++m(icC^fA5nv{ELvMc3>k9?%oO{>@!;aOb|JHYe2~db zmBX@CI@EeygZStEEnImdymFO=m4qMKcuPcis5l<|ZX}d=>r|9)pMSv8TOo>~2{K@P z`2eo@JnTG&nCu?s3ASsdE7lW;RL$*~)JD-!YA!*4XHgA|pBWhdT(%)ooNoi684>b) zQKJ<#Ij7z*!j=ngey~!jd6y+`KuMvL!jV~VwWDj zc2Ym@m{>{G^yK~iQ-6or<_13!1`|_RGDI97oWqNq2j~VZ5GLkU>I~(=8_961H6(z> zgNloeH0NDS4VxYDcS?<62hthH04Z1jI$Lnuq)mB`Ng3O>@st{%)k>^*sTSD9;y~+# zB%W~!mI1ysU6D1JO*`{WfLJ<0WJ}KW<K~V|-8(g+Vlz zfAbX=)a9w)61G-U$_|C)Dp+3H7_pm-PzDYi*!_rf!1&~%N~ykF3+R@rnd7E?QsGq% z7bkAf*>^=FW$)ZS?{nN6ds`2z#!un$Q=(x3{H#8nXhEI5JdW7~;nF>|Ym0;8cNrCH zv9^+q2Stkx?|+VacXG9`-q(+5N3z%t6Zm=|f8`dljVm0}pQ-b{E!3j!`>6}rnSPuOkE9V~j} zldSqElBo>9PbEK-Nur}$wOL+0xK2zI^EDQ^)Z(8kpggk8>oY$_KtE8FUGQI~)2t1W zkoAX2#1BCp_JoO3LTrSY11dl0g|Xtv!9@o$bAM?jlp#;1&%@clQ!#(;Y60b(6v>Qd z#Kpvp2i|GaEFZ0}j90zgR(Sy|Wjpf2KdnI(QFw}!_$E(P#%?){dTtC2Rq9mfQE7Fy z4Y6IG0sq5s8N;yd(EgDa9cM$_iBfJWQK_u4f0-YHwPMea%g0RMHwE{2G-gdcb2GRO zaDQQ2ULk2ruRh(DOEAN84umc!xI6Pf{tJt??iTcCdzVf#q5(CeRQ#laBUhS*&9;fC zVdDPf$6zKz|^(DSjJ&#*s@zGT*tF* zGXaMd81e;+EK9wK;p{N92=<4UUj(MhQUs%#Alo~KcVxb3U zt$K1k!3{OIHW!u!i#q_$2q&UTnQxUZy>`?{&Ml3x&u--46l=c6p5Cb&&i$q9?{YURz)`8*LBe`LP`_~8nZpJ| zP^?OXG``jS#DCP>G*dB}-)apWbe?fTB~`O6z@2>aT-cVut&z|}9Tm~$WPmS>Y&yyh z8~pR?oi3+^jWvpeq`pE)BcYc6LNS+3Ve}t3p+5`$ZJ9{{N~Vj!`O~RX4u8)c#*RjD zbW)sBMzKEM`56BXdbh$ZRuJxAK^C3;y6osYOR=QtPaeL>oOeL(++H){4QZ9xdmwtM z-xEhLiL>{|jeAIgI4kF9iRC-MC%xvg>^0HgT+;1o;Hy8m&@ON#GFJ>&?P_T~RD4us zEnbBfUG(@wF!JSqo(0yP%76Q0qvY?gVxXaNx|+O~8vVF-Ye!!7m4b-Qi0%)fKrf1Q zNTB-O<-BMHoPDg)bF~Y?did)Yq+Awlx-6B4{wi`}nJ&QAE}2eyTc&>sUFq7Q9V6k7 zo1vfIvwF)RJO?kYx9^hfWBhxN8#m#^JtJ`L7NSh*k0t4QT`D|?QGc})!%~GCRLT9? zy!R3`;)UnkPQd~%-c@Knww3;#T=T{3RBNm~CyI!)uWx;g(4t^pA zweViv;z6Nq`@gNHu@-h%*#n9Txsp3FdtjG1C!Q@QG#+aSjd9{w(w2Q zPX=*}>8Vx%IQB*Ia(}q{VoF1b2N6YCIcm)0JgwYF4}j78W5&3NkQvpPP34u|XWX~F z&u8Q38{~P3UoGTS60VVtmM;lI9d>$R5$#f^^QaBR`8Hnh8`a(J?$8z53Aqu_Ud*4y zyGc+7Ix?T3^N{vAo(f;wG<*Qr(#qvobaxw}G>p5FYI(|Mc7M^sc;$d6oOyB%!`Ldb zM+IzSg22G+oEq1;_}xA`#7{c>Pg2#UPVD@K;!a?LX$awvhEvx}+PyC4ZzQI0Wsp{0 z<~Nctl9z#q>NLNQG(m+JV$QnWD?{BSM~!$X`~SUK&}pM3TG;%e25u?rq1@2)$oydl z@Oh8dw!gRMbAPqE&;B{MSpk_->UWfseiSv|+K7gsFb@dP4Gxb2z53ASwx*Q5aC7OGu z?8XA{xx}7Ue@@5`457QF{~Qdf+3Rf+#tfl3PoEJt6| zf>)Nf%aF9og=rXUI+77nxxq&BlB<`mRB^Y$iv56C(87fyJ`0?XPZn~m|0O5CxQ(HK^Td|{X=&DrOr76?P+M?`e zS2V{`1%IHUi?23a6uc$9T^1WSsISo#ZFP5@D=XfBK)Q!2u@qh|4Es9I?Q{@jVY3vC zkI_R(R7+rj%MsmxL@%&RQ7{8aXNNshscQD;r*B%I9S%6%MeN3F1g06rNLW2D)i4vn zvYMa}a?3y{@l&m9Rxg4y$&$ewi2XFmt0alb&VNP}ii8>1@U5XaURz$z8VVfR?(_ow z08RFX?=G*&QiHf-n;8OlVziEHo)$)u54TadetFJY3+T893by|MZ zSnDzAw($S2yI7YGPz*TOmLmQ&*rSpVK#HG^(dchT{LU#&#M z)-68Q8pFx9d&WAaQ{VdK?yowUBc2a;1b==f+QucjHI=Cv6Qg0qmgD1NklSAXM25wan-wD9^<1#3%dwV&ixQx!$Hgt zADM3pl*{_0xMvL#C>@BMw`D-+#_% z_DCL1z`I^Snx6j(QJs`X0{<*~q})>L{|W468A*bCc7K8)m`7WchK0GbXjk|S%q@>5 zqNBnR55Y|I2-3Mmhs8J7R{C;(vb`5JEJ>e}8M_J!L8wLf_YF-M8VYnf-&#S@a^M*u zb;@2YpWz%4{Dvnh`q~~8C9*NW)_;#H9C)^@P^q0&TU%~=myY1g3Xa6B{kKO&Z8kSr zP@8(?0+LJ@`F9?7956s1_j`5}Y9V;oA|@PnNWBTo20rVU3Vkmd0iLAb_LcOH;s-RO zR$S|EP>D3Qw3GVn=YJuEBdOX{mIueG_jU?%6$)l-6a8z~8ET)9&|=mo8?+0E`m`9?2nqDJ zz1k_GyQVyG5S792o-y0U00e%sI+>KP?3Ag4V;M=2!Qjm$H=Jg5C$tcVpq^ic`k^!h zBi`Sp^XCqiHT9Ug4Jq|Y&B{w(PSY9_=b@By}m%aov93C*XevZnoh z(9|>Uh-a#|#9(!4?Rq>~9B(|)Fg1_d;KEE`AdF8Qc}o3jMOmoLFBTPfA_8f=Z$!Ar zcXzxa{O?(4x(WSag*B5$0SUvVy0x(kE!gzhvAt z8TFzQsw%C+VdT{SbAR?v3^>_c0V&M}hIH*iJ)weYX{WarXB#(=!2&nT-yR*%IhqvD zt+U}LcT#yMzP@uZ$6e#>fv0VN048w+A4&A>djEf9ixQcAMk8Q;>xwJ>Wb;(-Km?oB z&UCLp^$dFH&;4QlI}I%*bG~9CAU<0DInGDa(~KV?+bcRyOG$x9o=T|#1u+RrS_tGErhM%lQ4q9DYFvG^V-R_?J{_~=vYMRx z!WC4Eh%&ISF@H*gW~JrL%o?Lq(a=$Mtb*i?Tn?qX&yL_uVlF|gQya0Ea>pB1#7nB9on~)T2(}O2hU|B_e@)ux&O8P}2p)4u$A3Cs@bCYSsuIo@i&MEaUJdyC zffyLMT4{Ji9TyGmtx((r8a2QUm5@gP)ed?VtO-q`76eJy1BNad5x=K{&Y1o*=vOiQ z%W3VQ%7Fg2`i8IzBAZVznZUe+J6$F%ecxjaqqqthu(kDq?@^VaBLw0)UNAMfzlQ$ zyt4=}9r=WFbQ|Dlk)mLi;Dn7Q@X!fNr&89TnTfbt3J^(q+$+@Xd`0{XrjDOM0aNOC zjK43M6*MH+HZM_&sBywyHS`|6=sz$}-|^>V5KN%_ z&wpZ;UD=dNAGwVNLc5Z%z=$Lp!3N4YxC7@G>F!L7k)3&ZO3eclSV`)7v+6A!B@WFX zMgjuv!dO4ZSpPP6y@JdA%9z-j?br@QQCV&r9OJBf{->7~8~?BZ>>=?_)UU>zs^>xt z)#d<~HZo407~+SqZ}l3o*o#&-x*+%OQ-4r0V7*~zFN&u3XPpu+24LMK&lA%#r4+0K55|_PaVxK z*pX$imJWwt5@qpT+0KqByoHCoe1UhcnC%KE5CB>U~jH*U_0@4yFaA6 zeniDT@FzU<>EE$}*S?QrRtIt0cy2pIbQS+_%Td{U55>!vC#3r?YkENSs`4oInsSg5 zW)hVCL~@4D!;Du8loD5*JL?Wq*U za}CQ2U8<%wo1hRHeI?RVelMGIZt*UyOK|ZDcs$Wp-VQoI_exUVlGuUBCFA zs*{%kJt;u+{c<>j)OF6{QVR@pkbJC43>zPJ&KQ+q7-`c1WvE`46{x`13qs_Oqt*VU zkZYRq7$~Gp&{xw;>e23m9@zJgZ=L#j880&j*xeVu%SS#9+pF_@{STmawvD1&J$=2w z(bt`GuiS&mTy4b|dMz)gT7Rr;#sf4QFy@47w-Pt0@WT>XC!K3JcYhN>GmU(YyWE7f zT0{0@AaC4fYKR~Wj<2tLROZhIvTPh9I-kFUd{@mM21df_+ULb+ zT4iAGC)qF@!<9-*a<O1;Z%)g_8ij3cE<+bRLGl&G5nH1?pK4#LASSey+7z_oIK|?lI^vmuRYw?C{Dl+1DvR<4WW=*7+{!aq~(gB7= zFOyaUU9tI}D@@7I{`c+ z_QXT0Ig)Zo97HftX4)^KmXfGlg3|)jS%Sob-JR8`n}6&6t{x2&p*zMbHUouf=bjjb z5*o7Tu{_V7YlB=&5d<6)JSdlNNTGBf!D5pc!o0=#BO)li5oKIIOQ=|ry!;JceZ@5N zu0Ph&r6zBuC20mAJo?Ggf88y50_CvkcZ zWE8*i))qrR=mq4xFy`%82Z$+8_5eG3DkwNU?lWz=q4gIY<9Ftkb7s~~@{B(P$<~(P z6Vk@Z%>$GTU}7b&j+K2-ZkH&(1&emSFylv$2Y=#V(9&eb4`?xJm&H;lcx@3k9G$N5AKeD4K9Zmob*7yo~;A7h7x&Nk_gEow%h-`SrqMru8<|> z{=2`XXZ9nY!1gLK)xRael1LoXAcjGaKTO=OI!S>dp2pnBqTqg5j8nTy7lp^+L7Srb z=`r%^ZkR~~MJE9ut>bfpMS-LL73=NA%=VF2jBh$s=>^K-pY}80VN^h1uKa1)W%OlU zehV$)w|P5T`McsZKXnQzp3fFh9>OBsTNUe}Re59X9kXAAsyRzvQr(`fj5`c9_ip`h z@D1!fM7z+OBdKn{aMd|?c|963Oub7iqBA$Pf|pF7YLlIR8L30O&J6V{-UU#nB-)+P z|H+0BSWIZPxTdBT{w{87h7NowSb4dd5q#dU3pQCnvo588p{N~7*V;ABMfl8a&>(gN z#ne&2c`OqvB&rf#0^B?+j{uoT&fC+J$+Bsn<&mC2Q^~D@)4d8DI)s+9A<(_A?BrK| zOt2Qaj_gvINzvA+=xjcdul0i;3&ZJHOnW)jaof0U%yNSbVc@Sn$ndwvUa^wms5~Bxiir(r>;VDCgbCLXP z?J!Vt%7%Wi*94R`hxz_!H2E2{=Zn6~#eQSM`!R9|rmsXmxm1+zN-^OxzYFx>-AW+> zIIf{BELNfu2|>bp4wZ&TuJrb13!LLk>gFH7d{fNM;i8xO!y6wCn>L&qzm6mjSqai{ zO5D_b&fI?&9-Ua&j_f7$r!K3v<&nncOo(^YC>4E_Cc6mDIoElGktsUqslw;oR=5l^*@lv=A+7UWZr82=A3cXb1P3h|0uE z-6U-*+rd~Bt?@y$AviC1uJlVZYm>o6X}A!AMR{P&la0!>H#_yBi-bf}|0fDYTJw?f z{NJ%4n`g)tBlZFN(_bMOdVPFig5+OBGQi$z*!b4+zt|-ChvPZ@bv{Ho-ww3&{tz@z zLPOTjl%|lv=CJS#<<@H4;zpJJq3M~soR~BCnvslRZ_WIGt)K2I+}+I-d=}aif{avo zRZdD{X>rwgmQMk@P98fu9>kiO(jjHsSrZJR+N}cI<@b6zv8HZ6(Cqp!#G~fjGwz9;{X+KhX<>2_xZ4AQxWDwB=<@X5t;|``(jl5s*kKCZ zSN8-8Jf$xvIiuspVGQ(K`y#s_3q}eabpKHFHT^>nep}dXHTB=5AlaIeN{(G!he_~i z;d>1#2i;EvC`dv-19SoaLeVpdg9kR6Fa;)n>9L^l4X`feW}0)J=F0SXtawf!Cfo1} ze3;~*`yhTMLxHRvb?X++qYk!edFe{EMpU7Bh}NqCvVCE**;3^^Dc;UmAIG~8CIf4P zguc})yzw^HE7eMbq)_%`rIYtjY$V1SQUp<}V-2amPlEKwhTzPp%sY1azIO$yur@^d z5QlDt;*I?5LY@KYFRO}^x=&shR;YEdKQV~q`#21ag$E7H6PO;Ai02AsD`ZHqayd2B zyu05Rx#-g(!pg9HIHwAZM*Vui?aGXQg`mrT9EKOg5L%da4U5wP`5A7c0z8pIa&gA? zOH?4qee=j5{as>RCt9DUjfzVun1HDOyY_8j1+tHd24M2hPwi%CZQC49`VizbU}&_HS_hldM~Hkh6g|sFANU5> z$gmdPf(F{Fy~J~WY5FvcGw^c{85%b?m2Ight*UXKl*pd7{z=#+hgJR6SIYMtXf?)3 ze$cv62#qN1|G~7!^WVyJDu5Hh+1lV^A!5Xi>L!vaqHa70&Em2e>1XHWBb%U&+A z?2+1JQw-0R`*uDY@pw!3Uic$^4I=t`6Wa{K_9R0M*%@p9C}R^)S8h>p6_BAkZlOvp zhhQal+43Js*+9fa8C#iCd|=&$1}6<@qNg{P=3rV&v|*4-W6Hvfa2B-av8FX=c_d=0 zn$tQO5h11oJL<*o3D0-(&j@~>g|`FQ3eK*~atfLE>>7GX0`aqjPk=bUoRznMQW)Nf zjHa1b7)Ut>3s@nk1f-UsTo3d2Vo+~uKjfwh7wgSx3^l9=q91=<%8>F0M(+ayBIrTn zzlj2K0WOZ>xt4^e6c>?<)}vV=RD?(tA(*Hw$b?a_->xcc(*CyCBeWu18W^~J0Ji+M zVRjb2NIuStnMhrrOA^w8#H5LN>5de;|8cksq074yqOTq3Rk9_5vOneaaw8Ut%URRdi7XGzG!-2Q(E zd0Sv;Ay&~r{>N&f49b=G2QJEw6;Vh61R}#NX4#APH**oUH+Nx9Q*8vqk)Xwsg9lrv zV6!zN&(e!T^S8ES14EKu<^5Nz7Z4~1zMXtKCn=8n2VRTe-Kmdu?YZ7P(UmV3pV3#z zO-9PwxlYj1rY-=V2T+@g$qGHB?oWz`4mMz&9<$Kg9R3BX#knnq>RnaI!(MjlR%rhl z30ZUk*6!qlWwJnaI8#bJAp@6@aF8dmkGa=iBD`>cz3n^@Trv+HoUc3pjC3$NevZRy zFTpf@HBXzan&Uk{;VJ% z1=Qa`cSj2JqD26GdROp@wsEwy&K$ZA9$Y-q^pHOxR@32eN6drD@!Bs27MI~Io99Lc z1E`C+P!p8XY0t@6#j2%i(=SuhVAG8)Nkdw@F?T6t^`Y6oyb=E>&CqE1KeHcjouxRY(`r)=rh5Bq6K$@4DBzdwV$Juk(>P?`tET8NGRX7g7$*-%bmcXL z|Cv@IqyRU4F2^#1)U5CwpC|2qw9o<;b^KJ}AjB>g@795gVkwq$cA_U%!c_V5v!{V7 z{Vl@mKSXGNNTk|AMR1@-F*NkBo|WnABuBFt0p!3+TJjUrt!AN8_<571rj#?WCTNL4 zq350Ecil(l&dMJjR;vbnCnN#Io33)9^c-jJPv=T!iL3^da7@Nlnw*BSQmf1d_)WtBu@f^}GGFTocE!6|lx znxp1uwtiEI_?fd#X+DDSQR^(5E2NgocN$P7kEldQR0E}o@Td5#!~a5Q1HoPcsKQ6` zb@&-tj(Pg#bbQdajzCl{r>m2*Vj-;;_-flf9{U@;sF;kiX1vrgYwR>W657q2rzUC7 zt@m^I5PNh()`V(4^(((26>VC3tUjET}=OdGVDOu*eu zBTpCHPZ^gxXQxZ2LfGrO3%}M(@5QtKdpM2z^w~=>U5iUgl-(luGAF^8W5A~m_;AN4hBM$|!Iy%riis=Q4 zDdI>okDV0EC@JgVmE_@m9UcnvTi7XEabOvk^k*5g1PQKz<|1;*SDN?-t zEw)T4EqdH&Esas@Y?iPd+LOhT6&rcjBW!Nf3R8^_{;SEF=-8hC2>ta1ANvd$dlj3T z?H!05xAqGhx+8B zFy^GS)wWeEuEIde6eJ$eo|w!}X1i%QZw$R97@x~gwNP6L)z?KB(CXtPkw@D^UMz$$ z#3PX#lrS@<|7smuDl_qvB9rJd^K=$t8K7dIE=Mgp*|gM{wC?~G5q{M`93-7bjTPQWs`0&L8Aua%quhH|@ezE+xlpcK2IsWJtGfvq* zRX35AASlQ99lE=Ywg;2d$!DDPcGl(+J`UoG@;lW@;qi^3_I7jH+|uYYsG0> zA2010FOF8Vb%^7np%l8r3*##aggxyJ;Ow90Q(NSV#_0fp*Cubsc^O$ve+-x{lkU${ zXjXuS*=9)lEcduY^fTA5HJs{_7risbG3fNH`*}bv?4!Rq{C8h|*Q53mTdqqLh1X`nONp6glM|@rR(LtlCWGFqfNPdChW- zkDT`QMr=waAOEuXs)omHG~vw^GX{r$0M2Fc^(VQ05uOqvlKSZI-))hhRi3qm;Fsw<#|AEP-!mEF-f^74Rob8T1GY2Kopv=MJ=8o2?z)r zA`Ji+Sa3rse6$rAjG`;1V1)&D1fgF7l}gn49_Xd+zF zt_^bsxww?|s_{J?ral+g9CTK(@Tt}aO;ju$#p*2_36&+Qh;Iz#U3r0MxGG5-4)yz( ze$hB9VCKOv(w4Se1xyyoA7H0FPd(%sLVag5L%Ji8sJkzVf0kRjVads+aM7;MPr_t# zjrj%e|2Y>%ZJe&r?B>E=nk|h&$539@Gvyxxaw3vSw;K0;Q}~RTTOtlBrO`t7x5M$E zw-SMli65*#N+URUVBNtXsVAOLHGwA~ZN_PtWRf;~}d1zqi^WUa_WBE3A zSa4DQ&&q8=;6_1N;Eq=CGmUv`AA&1C<^%EzDdI}u1?!%RtG63hvV8uYWK40`)WqFw z`9=N0{nI|ox-0a>p>k!^--X2X`4z`!8vtv0IT=~?f&?UtX*BwAZUZg@hzwSk_{q&Q zn?-o!! zV6JpM)rT)Zr;kCGelB6$Djhe=OEpD;&L1 zZ;OPDU-9Ez%0y)d4QtZI+!{gTPW8a)2I-ccB@?EuZXF?>9^SV*u~q#W*ReFe@~bDv zuN?YL?#GTMtoUBsJa~C++T~sd>i1%4((5=C^XU=AUyn5=Aa8%vn7~WN$%q zin$J5)tZ}YTVH=YTYW2WEKsQCT|%5-%qfM99}C6S0=L8N9B$p}wPJCij79gTlm&w6 z*p@q`dwMGNiH~`dI&~UP7pl`NyvC#v5YIGcksCezA;LEHBu^qpxltLipY<$Ccrd$t=7O7(35W5&c;7ut8K$=_cs5S1hNKB@wx=uI zW!n_Y2_QW`JFo~%)svO z%cu?(=$w`L)_x-J>b=K?RQC$0-ElSPJddH?dqC8PGdiwefZmt+Y1i6%);%)60jEwJ z{=VonyWhfOZ>Ghinfb5jfV`&VDln-DvVBU=bw#TmI@KQ(H*Hiwq`*tFNb z;xE@&l@2#QpN`DhSC%SU$Ju#X=)%LA?J|CYKcjc%uusm;>_1tq21H1|rVZvbwJ;_p zA%I*x#PGRT~V%3{%GZRjDSFn2bD30h?g^1%!7H~NUIV@B0_uF$}vs{2} zPG%3W8F4J*f=&OCaA%Nvyi|#m_(H+IKRi@g?5NL$kr*%p@{YP*RR8an#HN#n9d}Vo+vq}jkwJfXjaZao zF{#<(oi3U_>e7ts$))prv0JNfS?V=!g6|{?Pyen^BKf6V7iRaZ!{0s~86e#f#lcd- zG6s+3n9I$N$x#tD!<6w=N7^Ua(uhVB%I-D0K;NJ3S`yZTnP3-aLoKx@Y>LRcR^Gd^ zXHM}R1wWSa`}l@En;Qhr^6HtrSCvt>-8da`zCd0-oaH5u%C?O7-qFwcc+Wm3yq8Ty zOy9NEbVfF9&R}yZPcYmhvX9|WV@T6F2mBUe_R&P`|Q7ks_U0`^+dP)EJC~iH_BeJ{rCow!$vQ< zN~9<7`|f*%QaqM-g)-@Pvi2U?9qAwWG3TG>_)&JLFUqC7k)Chzu$njd(?aRB#UuJZ z?eB`!+avF7JX^a`TK^%v?NB*Bu~}C%gp_yHygvm7Yxes4ZMAiG(d|WbS6ADe=dm>Lu%z$mGDZ1v6oow-L;3Pn_KFq z9T;5F^Z@XGX71QnS^rz=PR-L1Ova+60yYP*NZXr%Jz!+ItYmDgZ2ABeRjcpd|8xN? znq<0cWb9=BnN)Fba3SO2esiJn9}9B_GM@jW0{=4*Bh%#<78dzWV-o>!h;j4qh=_3u z14THw*~Nh(!fX;eKtZzqj|#?{&f79_V0#M}OEMschwQ(ya@6BI3VzDie=odNX*WM` zBailzDFnag&dvx;M%M-C`ym8q^lHr)F*qX3CM)5)8=01@_%d;QF&eFW*nyqNuF9q- zX-_2~2&0%|m_C>#9Cz^9SZh*{II(WmEYTF_3UT!lEKqrE`k0Uz5gA`I*~FTRUQ&8RG0BbRrS+RBv}smygRY|mClx>Tli^b+ zV^VgT`G-fd0TpQasY)POpv{US_ZjRGw;Y)cL7O6~l8Zkwa0@Kz1a!D+QymYlXXd_- z3^OR_u_`0*EbT=+>o<~|pA*j2ksWuk>5=cCg*yI^LTG;=juD?{FnK8Y&J~V6mJ`%| iYssM7`k&!-b}@#yctGCb2?TP0cz^(EYH>vg!2bfd{B5@Y delta 128423 zcmb5VRa9Nux~7f0yEBpC?(XjHZV3c;A2$m!8Y@#IjfJY1lpYE2q|F-8%whXqaI`~}-bp{sIDk;|^K z02*3(Ajz|Y0R8z3*7Flp-zZBsw*yXo=G|_9o&^Tt7J@Av|4|n_1wZT-1T40_>Ozs} zP2`5!{E8oKyL~&s#Ej4E;CI;uoQTON#|C`aIT7+HG+f;(eyyF07HaTD8+_6@vRL(8 z@zW`Qeb#nLPW!^}S>du2(`(vogl9iT-CpaqLY8y)?Hpn@&p}|%Ba0*3)eJu-WxG&8 zt6b#;%r=Ja9Kq7w!o}6u($wycm4lfL0vm`0^vAD&00Ogym!l=_ZBWzHV`*2n<2vQdFS7Q zAnrfsgoOV35bNJQB=!5{AOQgovlJ^Ah~tlqe=NB{oPRAjL0o?>e~&Y(I6IiDTe^bu ze;-Xk3dF2oN#*GZGDP^>tN%E_Uw=Zu(*C{c2M{|eXVP~~T3}93ziOue-Tz0Gfa+1gv!Zt{3aGqCMSD!CsxBb_GN0|6aJ9gH>A`<|JTW{$0|-p5JK;3C!Y#HPgdqTu&MM<-SHtkq)7@~2p}0&F+E9_D+c zto{+UpCvC`cx{9)x^M&e+5;S@RBwm}GTDKQ28QZ~^5DOE<_AZZV zN$b?3{J~Cgd1nQDTtf^GzM3x&7dTSt3f;x$H^?Vx)x)R>8C?Y_)d{6gGuu}hsql;x z>g^HAmYW-c>awXL99(k}Rk2R&xj%&(WJ`3{KH|KP?LgAxqYH(EyDR6abI>P>TKAji z7heF?_9KH#4Ytr)=3!oC>68%T4u>_gWi8ho+1AXVZ_;#BHNoh7oJg6ZAb#wKVtGc4 zuGvKk6kANB{qJX3-@%Ocr_KqbhhmH&`x*Izob>xtmt-UNDgBa2*5AC6H=vwy+ zumB2*+T8~X@}xMpyuyZ6LHkkG522dvmwA9x4wvE!Pf1-kTL%2TE!Wye&2sWFdEa;a zo3Y&hWV}eTwd8DQCR?&OmVHuuB#e0iDS+s7$UL*TBFN!fdg=! z+NA#Kq@MQ))=kCZ3e8jd{!rE7PVgfOR&SoNk}&n8BC&7qMjn*{3_4O{8e%lpFOTQX z#4pO!D~YeO)1ODmj72Gn-j^ds>(+xbV_T;Ami9Egv>giPnIsU3sJzvmgpSHS#Mnd= zgrSo8iMy=c63n*8auCo%9hcd=KQsW`8XMrzUr#gJ1XS=oR6r_x@!gKWAh)-%>NcVK z4DI7i@qWtpgdvkl;y9`rYoVWVGeo;2S7J6pYO|dnc|NP>xTb}=v*ZN@g%FvsX{tNP z8&*<#q?k{EB9v^7PYqH@1r9*9|>SLnv+#jurU2Xje)IGUE0df6FA0T#EH1 z%I#s5(MRM-ddC@uoXVCl0*++fDR2DmsCu&8WF3 z341*3PmHlu> zrUA_iw#R(|*6x2T=Z^~$g}@LBedSQOz_$F6@4HBs1YVaT_u5vg5F~11@pTDGRoDdq zU#hrP=b94S9NbhsspA1)H^tnq_#zi(iy1FPlekM38>$6C4sJeoMYP@u2QX{&&d2v_5+5MG}4CnUG;KM?wBOkE574^ zQob4qj!WcS%j+^WLiewbRjtzgl7%`WfvPlqMsxFtUO~!?9o9F`o>=M0S8_Je#cJ6q{U9Rc1x3WE z8O{&J^|8n{zz-AxM&4eWpm^)gJgDK+lAPxAxF3l$Nb)lcXzG8#N(BoZJ5|P$GdzvJ z>Bw7EGDI6_<2EDQ%)a}mtvj~*vLH{gL?F9(&^VxA_5ihJa@LDJx-!J`-3^wma6&)& zQ;xw{j1dBF!ch=K2D<`}B@;0be-RX4pQj#iL=z=DG4M=aoFZQf*=P(u;k9c2#Y{;N zDco3u_h&%DPipbzyVdM+l?elAeo{+`+lp+bSychc478cW8whjf4n}Sb^1_i`)#0(U zB`+~cKRUzig|_S;gP(-mKb9N@{;=Z_)Q60CQ0J1B^oe?h2E-%h^r%9RPE_<(*^uYN zt)-eZz602J`C>_&0(KG+D#Weuu`@1BX~Z|<+L{^pv3R8``chl{>We6_-!S31{NIQk z3w7=%AIx2oR?k`|FVMn}Fb+Z8ESkd8yDYhxBSr(S5_yY#GA+tv`=MCTh%0DNN3smy zRCNx%M9m^01=)kKKZ-xowRRx9y8yqQ7zFR%ItGG}wvCriuclCp~b+lGjp3hmut>8B-1zZ#_Wd|aaT~5XO zhEM9ALxM(nWt9;a=z}@1lq=jy(x01vldVx>p_*_TI01F&kk(xxFk{Kn-n9T-bYnSB z5@3y0hxX@>?5~|9c^o7`8|RI$>4p@Zw4$5Pf@p1<^e9Fw-&um!p2@_bK$nirzQem* z6TVPdpQYAv*-EeJ3iWlkN{?*ZHdGvmp_>bPnR;Eh(zQB_a90ZOCxqgT=)1ChN3UEp*PvT7lOg5dW6Ir6$f@Hm^SU8mY=c37!m?MJ%=2u<)4?^G&O^F zs%-Kj{dz5f;qXPRPGAyf`o+TF+kwz(4wK53YBIoVAgoVp`Be_`OH}RPtta})_d-`J z5-ppj?n{F<`W`_VOESN#&y%}ky|pYXEu8PUTJdC8-4b@$K}(^9jviXUq>e@|F~LAb z^o9i?_L>rS6drEI58l}?6)zSj*wgG8N__+vR{T|kKM=7+UZ%0wheQWiS+RHIveB*&clF@}nOY50Aq2g=6R(C15wJlbMO$KGKo%^)vbIpU zXRXb~sk`Jt@<*GEy^H5mzN(L#Yh=JvDfpHohSC$K^RLBfyUa(z`tw3z1(7fC=ulEc zkM(Kq;L0)M%{ot?6U1qe1fC%7KF+4? z?rqB%o#kSc3I*Z%+Zes(x*h~u^Af|h%Ga$b&H{<4Kw{lt>4)a)3Rkg_oqY@Wg-VKj ze&$G3XrI~hH`<`1WAc*MRrJ~HPWw=9$7%Mx4s)RPa{-;xJA~EGps!~p=-Nah0_a}8 z1T?%khrX)ik8mcFL>0f z^N$IF{xhuo8>_MXae%*$|6i=e#?76Sk53D%>FGL945IrlRGF+xMJ%2@Ic|pYT=p38 zuwWdMb)CWBB^1t?$i|Ar-d$dCPKW70ybyycPq~K}E@y ztyV=x2y=_zaw}b>Emzc0M-2Z4Opw|@)1HJ5N{CmG7DaB8+xK4UTp|jEQhQiu-n22S zDkf3#aV{c5KcDFdX6~dh^T7yC=Pr*~B+t_5E~BPK7by

j8XaMbUj z0=c#52?&cU6YAE6BT-p_EHP6}3ca#8+N?IQ7eNfi_|yZEMr|SN+dGkXA7KTZNVGFt z`AaPtX)5D6R3Re*A_W-(z>xqXm{%w#x*F=M5O(lHBF2wdphgVRnnjJ9C;r)?m^9{l zSo*V|irx)No%JUh8%7PZ{JmNvJTBvaVkh;wxrWHWl$Cwc+A-pvB2Z{|6Sc}NseYLg zLhTQ%5hVt}s*bW)^~Bw}^ggN-NfN>JanVR$lQ9D+4I;$}yejkGhgaB%_hK%Zj!PXFN;N{;}2)INkzf5jG2WKL;}U{RXy>AU8@x zQ7)tFRT1(!x;cR_fp*x@(=NeE>gPRCXnTGfHjOt27hjE`=T~hDG{slj5k}V+$YgDM zI=Sy}Z~?BN2$tB~5qRJnVjs}-mK71E65y1_Im6egVLp&3i2EeE%ur)GxFY5|JsnPK zFQIeyBf3#_=qUb6GbpV8RLH^>`#It+VV|E5JqF1aV$(bX58eH;_oly-ndM28BNx6K zPEvUu8XfsdBp9S%+iOG%hiv*MYP!uquyY%#hDqi(W`&IxeUbhfM zu(p81Xr|lQpbKmW*O7_Jh5%cqWlL_dh%$yrLm5;khcckCdf4twI+D?JIP0x9$+1Q_ zYqA$|HpqYs>1Yj%?m1dUimpS&{M7-MW5ZhehC2^9E8H#3mA>~sw+e-MzQ>#^Le)n# zES>fA)Z{?a_=1k#sZtbpR7M@k(?`jiR7N7zd)%BMSOV{1DKmnRFsAExrLEfE@6J$C zM3#1Q9zX>6+m|4j~`?7=2?w!Pm^N7@##B2+o&=aK5eOwqFAo^Y|oy| z$@?N2!{!>6t93j&DFszARgtPn!;NZ3$+?*q8)$fHhB4ahBn47w<1*1g5PXKgg@^{4n?5s4}97D@PuMa^%)d zSM5U!1{T=w3x9rYCXKTmlwD&q2x>gmuoK?Bd<-1v=ugcVNX>yA^xT}R>1D^Hp+D(Z zyvEalm?a>kqVl#6Dg%%6>bj%q{EQk{S`NIy*T%s-<+}O~3EO<|ZX3P%*#*w&^HV4% zS5ATJ=Zsfd1O#)i#lqf;U%S`FO$o@$T+d%E?uZW(?48s0aec`Zf!1cf@<&y}_t~gq z72X6Ym&ABos~}k+s54;iPy}7nONjJamYKr@wpL)XI|d0&9@G4Lk|Ao8RR{VwfiU2% zfycVCm5yJ4Y;4Jia>y?EP+Nh6;5Owr*bC{*5bx(>dutw49~_wf{+Q?3okTSeG9~^l zHX{F!K9A>7nFMcwQw*3#%@>zh_Acr9tqec9qs6Lr@a~LiSzt_`B0}yHN3%+FqJ~>; zqMT%x7*+MBK?!EFN@otd0;K(K31Gkqd>UBymPC+#T-MAqPY;Fe;X~79Jny6p#L|^3 zf)j&XaNpFF9~i+}wIUSW-oD?QoA5;xtCaXqP0rB!SRHqJTRt2k><==g*Dw zU=LQ1$%JBUV3)AhSczF@+em2=kl%^3fNu>qgYwAf^`XU^rUH1~W!U*HVWhw`c;hOm zW4I(h$hJ58ogYWwMMj4OHzsZd0(Q}y1HKAIC%C=V6RYh!v1Y@B{Eh8|#C+q?vPfbv zsQRGD=eZX&y-J5{P<0L z-m`zzsHBT}n(jIlR(0jU=^)^1<|;=_HISC%y?~lM{?0^i-$HGxVn?7s@AS6d-H4J% z#R+vi*;o4(r5iK-Z{`NaqZAvagPv*Hb@&vb>DrkjdT~h+75)YxO(?E?xA2@WdAn1U;s0 z^Cqm|es+T-Y`A>X^*_0>Vfq@A`q;^zIj50Mx2MmAFZ1B#n)m>HJNREuzTgkLjLEd6 z<6pXr(d3km)u${c6^8-v6<{Zk#Klgt?H$Kw+`r)2Q*H0olCi==Ds;|TI!w7K?5-GT z`k$L#psww+UGk`!j*82C#%Cm(%VXE%oV(h52fnqG*J+GzEaNe$hITVEdFk})Yx*@Z zrQ%+C!{2FhB_W)g&{O)II;WhEZyVrY4})kA(^%$@ zAc~B13buSq=(M_ag~iQo_=gGO2)vs|A&axzNtQ)Z6fyFU9~2Zc`RzwZ=o)gGof&%< zvBF|^q*Uq2R$#m?6JDE~t6JS#;hXObwY`!*5x0LMS6|5+`*jH@4Xo%e++$Cah~ZzQ~4g+pQaPbUd!4ZOlyl z`e{3%M*i&=``dSWF3B8b6C}|j?lcAJ^B2F?v6peG6@!Tk*{fyYH@W8fYDZ?>tF)Gu zmHXSzSMIvaxl#MdE0@uvaqomVybOCXSEJf)VsvGh4#YBcvHf09eW%7`OxlVKyVoZ}Y1IkLCO!x!PRjT? z30-947H0qEZ26>TqC(1)K7@6*XU-JbaMH&yMO&Wy#GVt{DX#1*z-(sR)N8pbAC0m8 z{Em$)i_GBXmPK_p0A>0TxxC1dtz**RkB0zTqzCer&&oT65td!EhplLF5K&HVNswFF=I&0;dkkeEQtnN)TJ6AH?Y+ zJNA`eHl1i72`s=kMSmJ2e-F`_yfGrKN~OXqsJT92FS96cDgQV?wk~&N=Lsn@n>iVcO8V}YSwrOhbDt!0mU@^Uqt z$AEn1h8?Hhg@i|c10&-@cM>cL2+&krApv6L>DO~>__<6Ueu<72x9!!Enmjb&J4k{_ zmIQ>I=GV~ZVkKY|OTIpHJdzIeq!-^IiGJpt0zUjq`YJ2bQ=r^Px|4KS(J6jr&m%bh zP3Rjl`Cc^&`C!kSqjpr=OmXhLp59@6RzGJF3=S%gxx1w zd@mgZh*=@`Y4GNYnGzIG|Ew?tz*O+&I!|=-sS9AE6f=dZa6Wyzph`kjurk8EOH-rT z1RT~-pR?f)Me*JG_zSGSd6vj-MToN=1AX2jtX6T`X?dCprjamAG=qXjV?;iX2C{tC zg@U*zGO$zh)LAqeF$&iDo-LTz9j1i4VQBd5A2|LK>3$%{3S1mHEZnj5{X%(^cGb)h zgi+8P;xDb*#>!)a>aWu!pphkJ+_$Ft0RS4xg9|s*0o4mqBycIHlN9hGskFm2r;!vJLWdMzN z(IJAA*Ifz{UB1P`Z59%O--gPIaURf1vN(kI(c3n(tDQJZ{X{n5q0Zx?x{P2^Fetu7 z&ANbJF~Sxxpj0M<0s>87!(=e=u2*d8hmXJ;=rYmLBP0V0(T2h~T4)A%m~ul^u6YPK zunF0+;R;C@OuR|lKKn3)gWFlv%L8lpvcfKkzBax)>YiNu*+c7NioIHD^HK>acp_rn!alY>px)Es4#1)}Od=@+Y%drz74#4c~H^&p;4nT7QTQ-lnSN@~no z%6;L>6!iDCazb>&fvR+yv-(Ew5diyMspO~7wp$0D=05|h2 z(@}lxq-}V^YoKC27z6*#YVXLWqKc*GSOww2i}{AMV;M~BV^8r`OJz@F8MmcVRa@ zIOGksD@~2mrqt?!R73oQ07sbi+`(FTDF^H)WkK+@^_qqi1ATyl`@D6(;Bq<9+z=Z( zw=D1=5SJi6!K~HAl=x+92Fob*ofWMh?dn6%@y2{g(l58ewZ7d18xdQp*6GLZAUXMx zHFv3wS|lXGd4^g4)Mvwn<>c2qYC#0VMt1|_Tf^Dp()MLGVZ?~V`*`mDDE8 zLU79H+LfH3a*y{cM@V(Fq&jt~bpk5~*?Uca;(;Y==0F3mZd}pE)Ff#^o$?3YW(y@N zMU)MRtpt41_l*2+t#id+JEigPq}UVtc|7k{X?cW$ji_gJ6y`D`OS%-&_a=|Q zj&%x31cv}#6Mhjb7B~ThiECA!qFcE+gB@~*O7!em9rwop@$!HSwv9rDc`vP}BE@+o zzw$vpI{3pnS}_R}zQ8C*^OOfTJecCKMlXj6uTr?f-p4XU?sOOb^yQ$I37#{P21}!` zZJ%aCg4O&|SBfsbJ<+T)`DM#S%2Mhs&JOTj5jQ~friGDP4*1Agn93IiJaZnwz^x{< zzF*z7wJfWZW-1D(tl7-$?paykGG!+wE*)@=5R-A$6dGKrzEMA&EqztlQwpKhQC9J& zE{ZA&yhX}AJB)ZOu=}@&Sa(3J-zm#z7r}gJjG<&0-Dq6-jG-j3S0PShp1RHoVxW7{ zoj(Ct;!ET=tg>HzLa_?7@_S2_4VlK2aE6~XZO1XsNY4$2Pow3aF#0>#ZX;}bH%~XM z%Oqht+0RvDe_Rk@k**dD;+RJHMC7s}mDTonq-14^gheI4i?|kLIFiYN2i=zrC+D&C z%$Y%`fRl#yW&+XO9p#*d4?B_nvYQN~$yc`H%A=5h0A%4?Na(EjqB33fHe@i#hOx8W6LhLq~ zPf0Zm#w2#nOI0Y&Lp}+g5o`JGj9>KeQW=2>KFZ}W#r+LI?2C3?zytzrf{nY@(T>(w zu~mIsbH^RB?oMm;h0(RZkpMl9epvwk>}2%7lZ`x8l|Y)M`1T1;E6BvoTIsPKTK8X| zouzw;cqqJX5EGgrxFt3dx0;($zePt!XT0R3_q=aTvh69JEfqLXpT=^JD3v~5#amE! z{r&(jJdp`AQPSP<+yf7+%~1Kp%Q znt`8<$vU0r=<#5k-tC1iVyB(fEPN8wEw*V-*_O*jKTV)fpH;ZsC?*7Zmk5c%d$&BC zB=a4fi@?tpnd8^P(r~dc8?Sk?j?L1^iLVu9e$Pa*W{8>)zy8EJmGPdY|Kr(7mU1Un znc}E=K}LqE@(ugmton^NWh6inA;h2KVwc!heWoL4K}R^EtaKpu?#5W@K%sQE%&j=7 zBG!-QYsl9EuQy^}*`Y6s4;x5;hS`C3@has*0aLm5B&DUZ;Viwf`d%xeLGxf}aqBah z(T2eZbL~F1vgTQ23k`QM1N``s)z8u`L*(<{-5U$lSx-Vfz2xJITPk2ZaWd2EoBy>=WpGu-eFNlXiEmV{NGT$CkuHcs_z5fMPw%h%7sk1Ns%HDd< zsMg0&jYyq$36WDPP0GM0hy>??Z#K!A(|B*RzA16mb(Ct2vqo%`d=D#2!w%F)nLne) zd9*{|h1Av1nHFuUg}k0(CsHpivhd&0`ra%jRI1ux8yHOZ3p@-CAACsgqld)5a4k|} zkwr^Lvu0l_5-*F$`x%XRZ;I^0;Pxo_-UT}H>-M-ahMPkq)CWjFA%O~OYyy2A9U3!a zr0_)=8X=Y0#6Pc}Mrca4B=^d-176ReuSqTVEr{1fRZ+4*_>Ui(hUTP@rkQo)YK~sjszJpf#8F7KRkQ7;-VWaSKf>?^&Zb;&8gak5N(*d) zD#+%8iqWusQIy01E_oAcUY%({X|xNL^@iB3^}y9S{~^KJM*Vf*Ce9kS`tlsQBSu9r zg~{?DtBqM#By@FNPVCUY3kl}XUIJ1^G_*KO?(HVu1o=M1KEAhGo{~Mvfh?j12rG;ABYd6~lV;Q-?t>Of0b1o4WJ@cKvyRT)S^QB{T#l9kxJw-PN%bAaxL$PE05;`EL6l>W3 z09fdlvGo6WE=bCz=q}Bbzf`^C-^KvyK@_w^AiIx$;r73v;V z1R<6t8WT~zplR|n?LSX!+7J~<-ZY%XKrDb!3te|pLx)%(pUZi!#(<3qOgN9sP@8yF zq-{bqsCG(yLi0vYH;bkv@IGY)% zL;e{czN}mGp#qM1nJVTkY9PCP?{VOoPCtCqwpPSNKX5@eER`?U0+MImh9Q)FeWzSD zkXMH+E)H3iCXqNTx^#p9xS0^6$`*39oBT1dP3 z^G0erA$9lVXPt_W4iG)@L{k>=6}1bwV56SHNfD~kzeGfh*XVfWxCJ@NfuDjB4N2<6 z@W|7D+DK}J&PDcAX*4Z{mc$vvWyI)6c_DcVIcJNT9YaZARg zrVd4I)$sp(sh2;*GZ5=MOYcrSBsh-n~)UuYYCJG z{@YeassgZ+fjy2`Z?S}6-^(w61ChHEgE)#Ysqq$QdNFb2tL>P(P!Xoj6D;adqSR@U1#+`ubzBlIwn}CcG;npk%e!wVwl1j3)aF`U}_^GfF@}P^m07aFB<#;xRlepG!1ef z%*HdFaW;ek8g=AW@;14;`t89g*Yy-Klh2PU7Cjdkp(DDtn5>rU&=HQoSVXL?r9knX zS92MawhX(-P4qMn=A&era03p|ok<8vgIe6j3SgBiv{pSuD3EJv?|ZTmv$o_gE0(u> zsT2@ImPlX;kcUAS@FG8f1~bfuc!K0Dv!q{Pi_7aQ&^KDj4)ikmT%d~)ZJ==_^BgJ`5*(qf|RUSw*6kcV6Lx0=YWK zE_)Jp&pS)=o5*^_u0eQCoVepTZa~q5-F_N4$|eZ9#&eZ&>QoUUsqQkMJd)>ZHC<^A zhHINd5v$da9NTIhEu`+gGx(X*Ek4c=x4$@kl5^s3>o;kz~`R)tev2mppZA(5B zoq2L|ui8WH(cIx=O@!V<& zeg;o6v1o9)Ti`|x^MtEnxf$*w%>-(d*J?=eU?P<=F_Rgvm$bN^tPJB0gJT$i72^CP z778{+K?K@Py;alY)ZH3m!ZAbLEPTFpx1trr6 zfp%p@^!<>B<$mg?`xe|GgJE3g;r7WL{-b+JISM>EbZeCS5MaX z|CwwS$5Ct+2lHkYLwdfNI@T`qOkkY0DARU&44V(?=6ic{eyxE?vz65&D(`#&CgtAh7ERZ{}al()buEzBTu{f<=bdktSp z2Cjk~5W_hx*q*t;+~*!00w%-xjd9BLgX=wGzB4>efnDKZV6+KU z9NTOFVwVi!STZ~CsE5sW#*hx%m__4B*#ns+jpBhmJ-k!qZlV4aN0Iy_HL>CI#glLM z%?gF^lCt%2malHD?R~w(CK!NFj{HCmppeetm1F#rlx_^%DFc^#rJ(}Lr>xPW1J48= zhzzKos_j|=Q?D7G*QDh1!|gV^2Z+a9nNxt*9J>@|#76w7vr?CMHY+C#?Jv_tYZm7h z5^vG7%#g<;a;}jU7oKWqS^XV0iGFXp^}_CKLnPv^h35l?=-Sp_`EC};)CUYHSEp0k z)%E%gBadRiru0w;WXIWvZmJ(HakiThShl7WTQ4m@^p`RO$dP zo?j_XS;pL7F@Fqf;A}Nkq&AHt2hnm?5x?%f+c@c2GLG#;A89o zH}Dj=;AXoYk_7YZ4s8nJ}foJgH_2XqMWx@SUg>WhDc+1%&LpV{-Y_R=5K6*f~W&0?)tVtlQ zP@*S#;H2j2vd#2dYI49kA{sJ^x8MbJ|Ey3~zKr-#P#T)6!R8t4w`M9FRqOE0pX0W$ zJc>3Sr?4Kngm_wHNyGOAH&jOcI>{5C6!;51|G}Q@|K%zF`vMu;pWVU#IeY#w_P?{| z@8;rv^%a4ClpX)hoBv?Rzn38YZZ7}Ep8t2={B17(SKsn4_T>EMEwz7V&p#CDU&sHe z_{hP|^_Q)5*crg~zpFAy!bND!9($S2Lq(34BmjvLw2B6@)7zuP+UdNM+|yW4TkIf0W8vi}O>*#FoB0l+UEtx(0;h|A*F)F#f4R8krweD)2Vce zPMT6F>npUhf$f+2=!Dv0#+}x$iuw$U4t|eim4SDffN8(V zy+i6lncg68P0P&bi_++Vii^I~TIk1}HOcz1G9Q{?NBjx`_7Qct8Ew@oYz#RfDgU^} z&)L39(jE2*KqtkZnIGkqpN2LJZ5JtipmIIrTs3l85`k*g`yL`RX?!g7+wD^atmJNw zd_HHmvZr^>VIl0Eoe^x%Jvdt7z`TKXy_r#qKJu&_DhyuC^Ne`_wSLMV*f%{>YM3E7 zDidU9nPHZpj2}c31Dsj8koi zi8a@qk*6hk^a1KXg=BUKm>1XXulrT6b$X~+dK#7HJ!kBHuTPA3Wj*JsU&+n7ee2eG zq`R@Ux=UYj*HjMEEW-@`qL`^3)KsH0zS(s(U+K<(%0EIk5}vFnJwmzBFaMFEPgLU6TsgW2Fj}D{@lcr| z1g&X;1j+{$Y>hrkpDpR1+Juy$EpQ80XnYL!%11Z_c*5&i^i~(CQ(ud97(s^4k_NSt z{<@4uKdy=v=Z^aT1$UZ{pL!7MLc!ng&A~VrBqJtl)JQ7rRMC>)1*U_S$6&Ltswa~Z zFNs6t5n>@oDH;9sJ7VnR(YeiJj&`L#GItCmGT$1|4XXs^d#J**OD z)t7LJusAOLiU~E3np3pI+RIgzSHf%lbu5+YdiW}|nGO6kDt%oUN+ zxTJ^iv{1;=#r30}M_N5M5mE6oLT+=oJ9F)e24j>{T_`l}>#kxx3wG;-%!+!45y722 zRE&E#c%EVl$VZ~0B|Eu7k8W!VoLxq^kh;AEiLl=Ey-J3YoSesd4fz!JlR*Xb;%h~K zTdgi^#mnH=HujPQI*()6JNj| z`+dO}L)tk>U6GJjaPa3TW^crs<*%MlOa#3zvQ%(pz&OL8a=Dq7Qn^yr>ENna{nO}3 zP-BTscR0z+-bSH!Uxnd=RP!tvhTeEYTfU{VQ*YhzDiWsS#xRw@(wxB*ow1BW1cbs! zz(?MQ_ss_u5dtBhnRaX)M_q2BeI0NPBA4r$b=H`Y-4!wAt>4b^e`-xlJS#OW#@~u9 zBGG#50$}ew$gkN8yH8tH)@a#TC}at#;fc7h_Q)kZ(soZ36==15jn}g?`H(M`ZY=3& z=QU;iZhLw_!E#q-&EOS+10!w<$wTx}xtc-Zd0c(tG*^Tm3Q}GC$8#^d7NK94oQjgV5YGLC52f*E`)$ zO}4l{JDINdxMNheG)#^QH)}H(dOPZlJwF*~(AKdFKih`9YrW;AKhi&5Sz5-#B*ny8 z)dKQh(OGP}`X*Ria$mi*y{4K(H}n*~cD6DJRbItZ2(9hi#JFqXTs{~pt>)ZjR5}?C zX2CSz3n~p)#ByL=wcrnOon2MVHBLCZ=l5<3G|VlJJRx?kww$ruqHkJ}3_XfjQLSRjhZCEp_BBljsLa!D=x^Wy= zLc)Vm2)@11L)7vtP7jC}N%m5U5DwT0E!kp`PTQvV!D7zILIho3^l6h=u)^M+L;z9v zJP77WdWI(lBW$E>dmj-Mw*BZ?!c&cu-<6JcOCm62_YfMEE)<5VZkP)Uk$skYQA;s2Xe|h5y z{YY12U1QB_hp*!%N}vcS?4>!Xy#t~#iBSa$Z`bFV>{fnI@SNtL5(=}O_Dh7zo#^Hs zQ0X;}IMxnce{aqH;I(dglHGHiOSYMQz$zK$xjx#$;x(099Q%b<9|@@Y&_g($ChAy&gNy_s?wnRDGUkkDFIh^wCJk%_K4|e0R=y8G{ecZWTZeCDihm#eSt}NXf zMU34oGN@2df9&z&o_Tn1Z#;L+M(pV(;M%%+2-nb!O0rIej`6&%k4rfWFr&`3w7lG$ zoo_sYTm^J4qH9&pq+b$U&S1BIoMD8dR#rOmdjZo7)&bP#@i;Rs0?p0g7r9#RhU`!$ z#z!hIt8^ko*MW*(;%~|1F_#K19m@JXTq&|l9>E&9nF!hO1tfKfwyGA;Iw{L$?^y?= zr$7~h9ZJ)&qUkIZ_sJGzb^QlcHl(Jha5MK`32(^i^ZJsAB@0n5b4j;=c7e1T%naNe zXI}Zph9QpqA^ogF+mxqo{uAsxGCI9$H3vutg1?ZAx7KJ8mQ?;NGBTq3@xuPNa* zNGcyYO02-PVTFeDDPH*3XE+>`TYAB$>TugvqL|)h~oU&=I62mn^dQ z{;_s0kqXD`xk;~;nwO~L@ml?;qx5O{+Z&JZ z^mn@(d&8vQv~nNe{@bn8m|lXn()sdX8^Q8<|FK>h)@x<|4(s}o9-`8nAxRkgGSn{$ zasgABv67)V9c~6g(wLA-JnjPV^TL!)RN!2mC;b=Jf#xIW1a;NK9vTU7lu=K6y941(P zU=|m$Te>OY%TL9kBe+VczmSQx2U?q7dK)pAK0p;Y)eOg;Mw)B4e3aEM$HI?^8{gpK zBuw%uGR@?NiLWNE1zOA;IE3H?;7lk4yWstCGK7(t4Hzzpn+MJUYYG^P)3QrO5LWnp zfX}{V>r4cBClquDs%j5EBD4N~oV^D;mGApFZWfWuWUo{rdz>SivO^+!j|fG|2#+lZ z$>ZMk8M0@#_}$Mr-tW9WpU?O6{r>-6uXCUKxt{yJ?)%!;b)Rz{@|7YT z#0yG0luAqTPfr_mb1|zY@zNk`&%8648F7Q0HV*wO<;3b%1g_n?spGn(%GNsO$ic=;#cyJ%7+RVcmTMQrOG29KLY1TL$Bxs_G~IELB4Qcq8bWri>Q3ROqQL%#@vEx(WY?^%yqYFN)W4UeJPW-` zmyDIp|6^4o$D<`yPZRUL%N=|~sevs^&6bwkw~f#_GRxTJX>H4He5i%yqvi|fIk&qB>ocYRKejq6XvGJYHidl@xRUKzfy?JZv1gyRUv7)hPj%(^?zy9duTkAZndDB8O_KDHv;m2Qv#8@R~ z+$ac}cnmoXdZp#Z-0^DZKe7EznzlxIt-HrW+nI%A%o2)!zbeZ44cc%(p8X*-yt(1H zUzvAB%v7xJvsv%D3)xNQ=|*X~h<6M*gS4{CV^8puQtT02wu6sXcW{XMxERU+xg8B0GlBE@$1 zFsLaq&P4Otfo0RZ*DTPpm-}nCAbSbDoVC=Uz5GNW4@cXe-Ym)@R$&wOL?iF|s!pL2 z`GwZ>4JJ#SZ=yoO7Kb0qhLlMYeppHkZ2UZUnMh`|pvNUadY|OS`%;7Odg03-^9=eo zY*&-UsttwZ!+2#>!^czH6-?DHOL)^Fd4=QR8~J9+M`C-v+ZqtQ$A{{+qgo6@VEC) zgwMCzl+ z^lmBdTK|ug`nTzA!>Azhu2Q8pZF(t=ZYCw>k8gctk0!{e;cCIgi#mI&SKiY^xfy4G zoz0gnml%?lvQRjafv51Mc+q8e;S0{w7;gHunUNYsyf0^~Livp(B)0X1W4PyA;{!|8 zJ5zs8<>pA*S`*Ng)+9O_b6#?$Tpg-C*uC!{o5}67LniV)kT8`4s-{nBWVO(0&md^F zn5qr7BO_Y5dK$NyO)IiVd)6b60V~U~?W)>rz4F`MZfTN!p?8~@y1@g3osJjqvD;{{ zb$8|xTQ~a~aDEwUGD($bSQENwHxd8xc$^f)JSWvrD!a^?5`9{l0rd zGQoKEya{o}CCI0YCQZhws&r=;uHQ8>669tz4o%0?x?h`1w8{oy-WT=p3EmaL^<~n2 zKRAgvFdff3+k)*{^4(W9Pbr@ z)lX*lFBF-|SdZMULu%z*QjcSD5N{6qIL|yxHdkv7>ux+Ns!Be7DLnfgC9bf;)n{%> zncNWx<-tB7q|P)~VjZk)xJiHOzGBMk7W-yp?GrAwt;dfX51q3r9*oURci@}8&P8N# zz_y%rJ22Zm-SS)L+#RH^Z&F{2qe#YM>iNZMJRe?k4YFDkP}oC{Y?A$HDylq-)N$Hu zGi&QH*Yk)QuJettuXs~(o9HW*E43^%?QToVj5gDv9QPRcqp(*z?0UlbQ#FB)F&r}= zEaI@^Rps^;zE1PrZMUx#`%n0c!Juik8^VY>LdV6yx`-h;(V z>nAN4GSV;7Q^qGeeas}oT?I5qD@v5CuBK%zGU}T*MMSz&wF;9I3=^LWTw zzxf5js@JjOQaBPCwVz2!-t3$nJuV9I zem=KFIg_PypLECT7~Az&noBRAfi9 zLAQFJ`F7mJ+`#z5PTwcidiHzM;6X^Yiuv?;k(kBtbB}OKAr^I93ywwNSZ|dA&c}mX z>Nh5`@$(t)I8Pl#XMcNjbzVe`r+X)Le|N%$DTuH~ctYg8K%DCyLz2)}j*)M8F%nA? zcdD$-1gLBuWvUEqb$uXA8ID`_i*Ael^_ax5cp5xwPDt z=|TER;!89i^fT~dkZ$9fu{RUfA)c#P?8-EDXUqaM)snlCTbQQVd+oAjv!o=Z`y$Ja za&x8~=QFN}MFu_A=&ZwiUsmm4*!S?lP51J)n?EhGipqs8Ax7&ZhZdEtVOw=}HhuNC zKN>3S$aO#Eyd?~O8(Eepd2sQe_2v`Z&hVzYo>$8B=eN~-bX16@z00rphS3$^U&q+L z-4_+}O^nc@yrr%+@s?q^l-~{o##H<>-K`tn!~C}|VXF|8+g1bx)mkYgk9eI1SUNjQh zowncUZl5h2j;3Ua4fM*D%eLHo{+0NmvqJ69k}xAf)nNlHw$;|m~h>x)_ozv@e;UUw%<-pM89t;Rx8Owrj3uFCjN&2`ta zY}Quat`B8S^}Q{URW-tRdtcPv^g;f7>hu0<1uVhm_b4KIpS*gA#8Dhb&?jM2&FuMT z<8AJ!9y~96qgRL?8n?W69*f&nm^>{vXW6U-b7SGH8z1C`^-LMdO-_=D)`3D#KTVX| z<$mp@q8rj)_b z5Cd30;|-tLWkqz}^cxU}iJwxKJL2Ik2y%>j#rO2FuX9mv;Rqyi*}{9$!90Y0+2e62 zC!TrbvgPj96O$B|tj4>ykrv{ioJ%Ec_GK9DwZVsmzmH@(7o_DeW8|M^E4s$}VknAw zXFbm7QfN`Z>ACb!dDNdw&4gGj9|XM)x{yRWqw{-aPTI3dw_D{%Ta44QY{wzYUmCUD zf4-6!?khm?KYR*=ejMP5#|VPYPyR2zUjyYVJPdrsa{RzT)V%*vGDH8jXI}iHWd6GZ z{^t+U{&V^K*T+34%j6SP@@e#Q75Twe4asnLkpk!^M%unqR>9&S_Fp-8PCr~9HRrT& zmMk!-emqfv=q#ZWR?r;hrAG0UWzFEzD#~LnW3etX+0?;r8cD2t1#g8}D|%BTv)F&Z z_q;Xuk~QJSdA|PpHUrt^G%6Xaq%yu&_Hl^w$}4{ha!o(CCy==85_-MyG2XAzTDO`R zZ+q-lqv_=k+g>Up;x6({$z^Ey<=C5FrcV!@Ew8G!+wzE0Y%Jmyx123q8dvB48h1N3 zg7Xdaxqv(AH?kKlUT_+p{Y<}mUo2tF6^}XLS>nSizY_B`meLBcA0y4mEN9+^L6XYE z3QlD{PwR5i7fO>%u@e$PW40FzXvkG4FbqEjg?*xLQ6^2xn7FUI&owdBQ z*dwCTu~nI0Yu!%a3eL;S^D14h1o`+yNV zvGPAWqVnH$>py?Q$PXS;`PVa4{v6HR{PU=k|3xM2%ph1{`Tu(Ki7tW<$;rbg2!8A+ zgy7}mXG93{a|$vd_>r8jCJOQ%chLYrgb)Dp@$iCH0KxNDPY}LFLyzzA3vwb+NCmh7 zu>iRM4<9EVBOgB>Cj_3YiJAa|k0${zfFj`*4MFn33!x_dJr;eRUjW`2KbV2g|64GB zeV(a{> z$(Dx~-~vyVLB9#`Am9xN@dLU9_)#;!MgZgZ(YyfEa&rSbg52;uAzlH{^79LTMFn_x zKr1N74QBF#bs?}1ZWO6Pf=GAB?uIl4@d`Y|9J=c$1Gk10v0lg%s=e>>s(P+00;~L)Z%|{d3gi@ z%h4@2N&{gtyD5(G{iJ0tnbwpj&<+ z*a*=rA0G-XfU+vEeSj3*B89*h0aPo*2a5sS3IO)Nn?SXH;{^JDaseR$SXzHxfLr{4 z-^Xu4NFG1|x;;5d5O@{9$A4=P-0JW>f5ly0A=v-_4F@XnmwKYuf@aSD*Orf45CT#LZ-2M2sQ{mU0x23I1VS7iqYyAP zB(Ppst%L;N2!sGoLEsq>j6yr`~^@=p!LAskudIKOlZv#f?x#4 zOMs{dmfNQe88Up%Lg_OAYis2NM86s59S#^%#lCh zgEKRfcY%aZrifNRbRSMq{Chvc0QCLyU$q|2` z@M7@m59Gw)KR~pRquW1F9&YIGz48L@fVy+S4*ua>Q1JlmZc#0I9Ew;}ZiKRsf6#$m zP6%iYP*sqH!R}WOjt4?;!i6$K2&ftY)_5eGOCf;$f^dUs1<`B)Ij10q58y$7ydY+P zA-r(p5CWH(7xs0+hYOz(JeUAqjU>_is9%~297~s13*u~(qP-5FDL|<03F{(U7YL- zf)EY(g+wI)sP-5g3Mo3J<3rJKG9&u;K6n; z;O~NlALP&=o&nbe(hWhNXCTah3<7Kf_+3CQ1k?*?2ymh(ehY&72e=TR&wQxif;{ka zSf7Blfn**|K6qdi1yey92DS?H45a=*lYj!lVH-}_`GLFu9G#hgI_fVBe5g<@h=jAi zA^{=53k0AVgbomH0Hq)a zgR^!a*cw3}0Xtg&7XW!5fFnT=0{nv$RA8zAfC?E15GDYtQ85a^2Xh|*%$b)F5(LE| zECV>Jgk1q_v2Y7q5o#GQ1H>;7j)290pIV+&Gj#u-oa5(%Lm0~Mqq1grYe1l25m+p| z0G9v|DHwxt6oNbuENMPLR1g750;mu`<+>o`@Gv5QHh}#A=>s^>ZyY+a>IrW3mC4a0Z$M>{=mzkn2XLTVWt4Np^ymz+Z6<|MI{#} z+CLoPN5viiRHX$w8Q>p))x&WPRo@80@d;Epa4Q6h2_}FK72fzkiU-C)V4xsyjBr(l z5CS4VSp`4X9T*O%0KN<8E|52nAwUj77c49|6Bhuc2jmHl{NwljoCp9u0Bk2p64=M{ zF``>O;Ot=i0`?C~0R;YkeIZZ^c${pZN+|>o5{R|H%b{n0k_a{$a3}<$Lc{+;3sNtj zs37X1mV|MmdnZTngLn-H0*|8rZ}5P)aBOD-JK5N+Y@9n1uui3cd^vGaN-b66F;IQI#M#xq*2A4?&=^ zOjtt!LR24tasX%v0AB}}`(P}3WgZ@M(IyD$U%)&R3x!ZDLsNie-yix<(j_49SE-2> z4|)YSnF5tG%FZ-~|I;;uo^rB9FL|WVQ?k@yd*bVs>5*r76C}qkI%T^WCMME2+ur5j*2TFas3N7zyf0e zp$iE7_yS}nu>XNKiYED=y+2nl9)6Iu!P&)MJzj7~_}4rbiXs;U698%k+Z2e^;EC<1 z87L;gJ@h?35MB`=u%hyB)Wsj6{C)5TJ3;uY9!^*U0h>TT0D^}jDV%}BN0@LV0x=2b zCHg)L0}KSw7(T&3^}#|Qx`C7rI89Jvfvg;b3Ed(EK>h`M7lXp=x{ox%l8uLCTIVqB#`wSQQ8?fLs8=TE>M>7>;lH>4zk|dhs2BRQmPeI|d2TSozXT3>FpwQ5F_H4&=vd*5<}v;tpC4kJT?* zDn7lwEY2YluM{k?!mGy8T>+)Uf1;BZYB*I>k7Z=?(_(Vm!VHI-kJsUMQ}<{f4Wspx zwH4OOw9|6K!?D7jUj+?ZcSdNx*7Y3yaqyEw0zVy#+uq*3`_P@1(d_=b89sjzb~BY1 zhm!3W3s$fV#?>teMfI0WM`g)VB^X|`WmFfwfB!xkY?Cmzl+eDLbq~`Hiee=2EXsPH z6`qrYKc4>zbNyy%<`HKweH3l7wej2mm*4YGRLvdDE##}51%)`Thmh3__Jw>rkFhFc zPrsFG!6K(sS~@i6*yqC5si}^`HcGYJ%ddcv4%@;qM#chyJtdy%o@TjzPVxF9&)AG$ zHVH|+DEcX)RNM=Lu?Ob&%%C4OM;@ciUz>Xxn|DUWSNei6CZ!ZG(zeeW=_m1ZxAb66 zDXrL8ZQKnegg&}FcpsAx`0UfWcUg4JR9pE6GS?E6yjI+|jdr%Db%qBk23>v!v~w&e zwI5#nT;Jd&+0oharQwdkuQ9^1Gmqk2qe=uxR=f_BD+_79ksqQz_LlN6bVRKF#9w_(sIP1IjQ6O^#TJZesZChy$y5xfd{i zNmz8$U7_+3njLv_00nN01Wk(96B?-=28_CAA4un}U>~0QWchCE+@~h>BQE<-O?-O+ zqd%yQq*nwmjudTHgp)sYJY6_q*4}0u~@R8Tb zJM7t+GLk;Ik5KGUqQpQyV?Q zN%qM#p}0@lue6c9MD%I(1vmA?q5D4i@%6MZR}duG3zt1>->6f3-}ZR?OY>a8;Q-bs zt8(Ix*}A~DF#%iS{g)>Uz8RMCQu9{7DK>22#NNIws0>kNoX?_B6;VvQACC-BUdNY_ z#ZV63YooK;+Oj((@N`lr?3WO=R#NYkC@HQb<(b(gWLL=<4U3<4w7j&oHr}Bh-lnOO z8`K5J_h=Cqu-*uxaU;;CHRkbYlXSO##5<3;SoM71mSl#b+uUK1{ynpiLAx5q%QTP2 zeMLMc`PAs3;=9}~fxg;qtaGY?l9#G7#(uD~c`3wSD#KTnJ!iZ<_fdzk#7U1(P)NP6 zw(Qyj9mCKQ%S^8QwjY=M9n#qFwVP%53Lf{EyWqCZ@kHt|@JuuPe7lFmm2f!r@z;%Q zM@@!zQlEk(O3N3%yFXlx*Lwb=tMU0}z#64xzMp>Kd1*-a?AO^37reroPbKIXI$e@% zf55R8OdBm(e7jw%?wRFuY`jko8_kPHv!$Io)(rfYA`_MPRRY)E?BNny8t`53YQ@ov z=u}hD?ox_mxtKQo%c5>ho$i3}Qqw9fFV+)e*ZZ=i(6YF`hx%t^ev~}6QQxFG6-;fR zx&3=aJ3NKP2C~yS{bPoETcW74id=@;s+Pj8=%(Jx+vnY)A?I}!4y}G5V@5RdBGvEI zQo42ugtT7F57!X)kvB9^?yA6lP0C=%RAPQW&I-9dB31eMi88!1$Nkoi+Tr-r=xtH9 z&AUliPkf^yGkIdXOJ8S=`Gemper)BKCV3n)UoP>c_3$?2@M1jd0@(J>l z-o+RugNv6xSU@)SYa)YnkeqiOy}UCT>=~lFd;0s58Y7|KmX|S4=N+pjKV1bX-v_2= zIjgN(wp&>L{4MP}*MgxzmZxo;*5Qpe#Z}uT{3Y$?So5p)`>{g??JtuZ&yl5E2sJ`< z;sr-s{-t)M*TAeWS5;2-ne9k_?6BPM;?4Nd=1LY1m8{f6s6~pkenHta^8R_6Ll2Xs zH_>vA()V)*^w%`qjLwS*8oqO?5G-9jpWo^2L+~>His1XnKtU45;1Z@3WASU3X9bQ5 z7=COz2TA=d^YDmz!G{}gGbgn;s9CQsYFkfo?PLA&^^iQ{cZs)UR2jFKCbx7Hxhl?v z(53O*efG{^KVK0VBJ-bqC8d9j_lX|eYYc(Hhdo|1av$~l)D?UKbzHwhUmMI`;X`7m;(ktH(mkq|M$@(TY5Glq>?(Qsh&<$qGiB(W2Za>g zl6>-33WsWRjsgG3`AoxTV$PRH!d20JDZVmxy1*Rhv!};RZ0MB}%kJ$|GOo`G6`Tkb z=H2vzDTjEc;iT`shFXlzNxq|Xq7Rh~BT(>jNmfnWpIDt9e{|u7b2jabYqFvW1PY{b zPk&HJeG9DVio2$kR~8$bzD)4glHxXH?c6%ggU3_OsrMYs=xpN_OJXUM>pt{ObcW=S ztX70CrYMm*HI6=o2zo-NX*h+w+r)GO6fbUg6-ZyYJy!qL_#URF{=Vz}@4R24jN9k$ zy|^6{gt%Wwe=V*uo0%b8)m2#Cs?4W6=>v0NpsL3WH<=9H>oI3j@id=k+`dRZ`#QxL z{L`o4(R1WW9}S`JIvWf+7Ny&q3CunzX&>*(CSLeZ_Up_zg`X1iwf-#DJ$0@=-FQCH z3NphjUr#&_TRc)q3Tbvpqu%dndF<;!(rknTr@t*4~@$ z7bz7D^4_xgfKvr4BOv!7Hn#jltl1bahg$fZw_{{0x- zQV(+78-8@V6Wzr9ZIYwcU>vA0&hq?_XEfyfz!@(M@4o9R@6w?7QjO1D=NT#d&fkfe z>vJSn39(VLnvkqCeJ7U6tJOks6?Z$?n&)0RH56230r8SQWFS}8#?LpN%)PW(wR}Ti^^vxR*Pk7gp3_Ywr9XR=G0awGL;sK*$#l(#fcTN4o&sL^ zgxS}mBytDNDlg0Z1bL6+WpH6-XSa9 z_4|}i)?*$KN}O{{>{xbUXWMKoInHiu%9oaO@thKxc+=}e5$D11t%=vgd{fve-Dib1 z^FrL+!Y3tDZ*`!q*YT4VjIk5_^d8TBAn)z&NV}-Ea$Yg6n|PLhWjzPt?sU?1VeBkOIKT4s z`NfwORs~Xx!e=A{&$4rvYF#a8x1PGeG1a3LIZvB)hArUY)%1|++NFCPn;-4k;s}Eh zHxY?C4;!_OaQoLM7JRX_KG`3Y=8-9pQ>Lo!hAP{R%HDllG@+tV#9Uz;_=BGnhdrLb zq&s|-L6muRb{&nT5!Ya>Sr3>T#?5S&XV?2nhtg*j14k2+t-59p5JcvpxP9Sd78$M z-5mHxKzQ`dpyJGgDhor&%x)PA0T+jjGf@%esu#(^h_vj*S;a;4-InrOP){&T=p-k7P5W@qRw{p*aOSb<^&92L5Kauqd)z`a( zCy8weSH2N4N{38M$Uw-m#=ow7ELc)wp=-J*ViBc4z0q(VZ_~V5t4`&qtW;uN{v%s5 z!u=~>-Yqr>v#u63Z~ScD>JW8S&R)Hn)1C2g(ip$wz-_5HIw-!H`g4oP`y%Bn<|}ek zftia8q!OIMn|unUXdbDqPf>+#Mx)J|>HyGIJ`l z{s}_FU;HMtxM?4*_*udjW5b&*{_Sd)Wx5cj@@OG*|7hU(so*OEvO5mjGjlu-_!Kwy zBh$|ptS@L@qO>)+T<}!6qu)b#lh!rxBL?9P(_lcW_@kdSd>-KtO#o%a%;Dq{R=I;P zyh}}0+jk*G2dn<&6km>4O$GD3O%(Y9tqohcA53HX^X1$})83u$6d3cGBl?8DOLic} za<+i253HoBExqP$<@Eewlw;EZ|LIuCipe*2A8FRI+mv-w53HJLa+Fd&Pwv!{Z!` znR$hi+8#McUHS4&J7L9;yE|X`>K%rF1YI2`o?x5#EB$q$zfu&nO9^M%;;P$I8DqC! zy=~m?dlpM`>c(!l%3gRNN8bzH4;7fQ?)f>`%6G*07}zsHr`qMA%$9*f1lL*NjBsUE=UViJaMOIyu_gS1Nk2lPFd+0;duElEIx`AO83vN zV=#7QyKmk#e6mTfuWiWVKY(vR`ZgDj{CQL`H-`I7yuB^@e6>B~bT7HyJ(?Ed58bE5 z+gditon1ys6?bxRNufsZyh?3+%`2`ybjOVM3TJ|<6Z{eTs`sl7wIbMxuHO1|N_cj6 zH`8JL3BhvxR(b*djBd#ykEOo{lM2qy$(IaAH)iH&a>jQ zcdMC=|3b|@ulZh_upxrTE1zlxL@w-yErSLQU#g)-+{(_%}F%F?ZDrEbX9D?pMOkdKc z)CjPGF3x;QGOEq!;rRf4VxU0MPm;>Z;+aNRz4o%!oyN(|)*X+~z9SRNWx~66iG6Bw zH{x%;ZAEgaRv3o?Cj|iGm(Kd^lH&$Q&m=N?pu(WqEq`mw$lSf=j*t;Af zQ~fu%7Y%WPwchR-JsPi>MiONp=btfJe276PY|og_i)J-A7YNY@KurZ|gi9?6_+R`Z zaIZA;6pFYOR7F`?Uu?_b(%63%5h6+&9BlU5i7x83S~t-=XQ!dwgY|jdUkQ8pefMXK z-6)Mh-zOoC3R#U;OP7;2cpvPuCywW3F5MaRk8!YISIvGdv=Xnrh4`Px3cigyB!{vRsEir z5&4tK`zH%?sJVK-rm4BI!qN7m0!Pr}mvYqX5NkXqb-erN_nOT)Y$$iJ$~{F(V?!b_ zpIqY;Ay3fEbeZnytF$q>J-_L*zqzZNx%Zvli++U&k*s)HpCjU0M9&7*iyK5%cpXpQ zJ+bU4PVSq?Y^1_gPEz-0n;!HTif5Wg%{Plpo7BR^=(-=6XDSebvH0}s!$>yYS}MKW z<-9DU#GYiUSPTmmXZb#4M`3P9kS9Z3)*&jBCN)4YuoX!9(rwo0P9>(KgYaywY?xk2 z(Yt74clZ9B+gwj4?91&|EjGDdrB-$~KP|*AqqdFpd17+!>PoGGP{6$QCgXs1bjzED zXGv~c=4d2#`R%32`{y8pTu(p~RS4_+#eeiZ<0HP<>*>jWe>0+Cm zNJ)2?^8)g2qxPG$gA(;i6H0|cdAgc*)=fzaJz%G2<^qcDALz$x7_IE~9 zKG&Pt`YBVhmDH?NSFze~7sIi3wMtVFI$XJ70BPglk$iqrco`P1Yl?XTOC9V?Db!hRUAN=@83*IFpX~ z3-7txip=A3sVM8hRBiFMIPj;)rQ}o$#ZrrDue-LFJ+@^LA!hBw-lq)Kt zdLvgZodEBG{E_P28$*!mMz^@$?qNlX$XLGD0;D4`jYs>GZ zV2pn0^mU-KV*SjrnLXEO;MlHOqNH>2l*y(JZ=d?$z0H}QgkF=1OZN|@u-5DB2MYEj z{GS;O>zY-@e@5irQX>E1E76iOr;>PXD7y)KsiZceRoJEf+{|w>s6nmz3lG+t0@4?Z zJ{5AUv?QDNU;KnLoa{Kx)~T*k?o3oB2#+Lj>bu@`cqGJ>Bi-6`hW*!D7iOY&3e-ou zuilbI%H#^Om|ix;Z7CIEyem)RBUDqWn9!zZ9Mo=!5WMiEEj_iH$SvUKHf7+3XNkP; z%uc-d{qyH!)gFkq_fp zm(!GEuLt?PdDhr-w)4UHQUY78C#DNqi);3UsZZW3a*fJHkqmwDP;{MGyv(?1F=s*+ z@YqRNUq%a&d}nKX(EUZrU~(~5!0l)kXW6G8)Z;uXC^V(UJ#1;X#-RanA-;sX5vih zpvPW5I+JEM=p_XnV<`ecIQBs}#A zdR9N;vt>WYB0iE0nRec^y*kt(?0pn+k5iG+DyJagwn3EXi)P$+7vg#Y3BDdEnT_r9 z*`E=#zlXec8*{|LTp~L?luuDxIinsseAhXkk@Go1EU|Lk;`i0MaZ4rPhV#!a<^LcI zQ)ypdzbB_wcF4_K!oKxp0-}|jpmR1B*B=Vt=G$dHf5QFFoZ; ziC;mi92tEsotbaO=C4bOihhb_vOIcOL2Nfkg}z>{G$5?!ESG%7>&zE$QJluW+H&d( z=G-0^!g9%lD#4=cQJ;jY3@$@ugV7j6@LN}Y<(s_E&&L<%T}r(eIgkYnKA>g0V*Gog z6n~%LB9F#4f;p|*?W44K&WpTh1IpcXU{DU8L-Vpo*b+ zcS72amrZ)C-)aliyl|C|uT!pUH7&pL7~jiGW}DpmNtvVzhrfmL>@8)N#_S1#$B9^E zMvjjg4qL0YB8PhC)uX#H2_Oe=i8aa+8Eb|ggh!um?2&{%787Nw0bf2J2`$x5oSG(Q@|vBP=f-0ES;a4xrqXdr`BT;ARJNOof5fHt3fN^*NxhDsGX zMf}!7c8844N9P`OD&UtW%jd*n_s~5+L`@i5DE&TXJZggX1Ejs~9yHYY>E;ITd z+NpHEli25iFAIse8RC7g3XOB$WQT>2cuDRqqC<9z8ka9a>{h|iDmg(LlauOvbWQwu zzc-&!k}>GjuQbxp6}VU-3!^aOFC3*nF-u zW-+1r+T=x1NQ+R{+^IK|P?A{egwFD(?k6`cg}$&gTKMuoMk37ka);5>-E)Ynyq21T z*mB#_?$4)wlZPwnre!`WWbpO-PM?@$j&mhBaTrlZ;*(m@SmuN^zPqjsm1?ep89k$! zu+~v+Oth(|ZtHv1m|w!E$C;hYPFJCgL6($sDjYLmmEmTORlY6QNYv=%_ii0I`sbO=&d2hrdG)zX7g>d z3N4kNRq*vwRSn)K~XQ z!Z1}tN1s&UYTtw8%ykTSUudSX4vsI{@m`rDWn>T-*dU5M6S+`zo5(b@A+>}w{KE2? z?Vw+|^en9rFKvsM`T0<6d^W%DxLt~~?Pb&(KDixoqrFRq&&mPskIo*8J?Kx)s zon*$GsmHMS&E)dWC&e5(!Bd1mxjVNtih1!jf_IW~>bf0?Py1yI7k392;FQk6#>lw9T z65%{!e9KbrUUKC{9@+NfE!@c$zsA9M&i&;Z!Q0&;WGL}>?iE1LV+0SSwQpv1W()eBX zgLU)c?w%ndrB@L(i&K#El9?*E;+Uxry-{ME`r6JX@GAj*Z^Mg*ZXa9)3-8h$xx{PL zE3$fa>>26X^3?Et;wQ9v#x)Tyv!&>Qp@4!stj`?a{?{3ORG5Ur1T4UrvW#;beJ*C$ff@dK9%M|@QpXuHc z{I+X6Xd+tjEC^pPtvWyH?sVr3yO|!LK95=OfIUGmMRiAKE}7{*Rpi5WAOhjoZ9;o7uv*ylDc;vHQYc_G==PJc6b zP<8vs#&Ay9W8=VjR$g;i2!Hhjad_#cVOeo%&NddEFbndh6ITt-l(VNtkvJ(V@rSLI zzKV`JiV~w!PLC30%DQz_VMF-h0r~utqbL{09BUwDox4}#h1f3k=yNe2jKMj=_+`fS z=}Tkc`pt2LF^gV%BKl0%!>0BE(+IRLNLvzs|FKvhYQ)<*DMobuvNNPWEB-+E3G`lG zJ7;>3N;|1H9s5idjaA*HmsJ`8CUaOMeowj!JUf#yU(F9#T%Wb!us4=;c<$PDAao-u z@gsZx>PH*NrRZAeEAaWXB#a)%nEnqN(1(?wQo#c&tE zV7PQO;{^SZ^>5l z1H5rcmo%w>>C{r^2`)8XKCGeXFArF(4XIK`?PlXCD8p;bM4Pu?wvQye&R*&Miu-u= zT*$s*TV77NL?6G>XnQ+^F-fM{g}eYUaKfh2-dNN7TAlsx*$M zM{jn#-C*Y8cez#XWQ=_m8J5^0@WT9_L_!&B7hfV>(oWUX=MYzd)7@WF#>-sl{6()( z_+3gq`Wc@-p2(g0yI|mMJAI(!~7!L+tz~y)2`VY0;jV4Dw$e7+v*IKS{db;^z?9Q6e;rfqC zr#i0M+lz|nm>CmFX%2fA;{C)0sNW*$X@}yvU)-SL%VMUmW&FzUL;9WKdj}c|m1>FE z0ABS^Ee$&(s-i=j`wvN$3M2(uBrUu`bawd?#V#A(i8H$G*vodO5h{41Nu22Ic7~oB zcRs1M=`>;SEgRa6u4ea}%PniC5bUH4fqXTYx`gEUVbnufDW&3TiFR*KIi}5A?^sKT zsGlizSdzc-N{hJG^<2f&y8RdaZ`5&Lq-&{Z-Rdj*zD-ORhr1}=WG&ru4&@i!tv~CK zTu<%D9PyqvL{coMS+p2BrCGqfFW@__^fl+4mCe1HkT1}hSh(by@M{-cu=qFvRk#Mq zgzX(!tE9WdCYW&o7O}WaXu|;jUKK;%AQCdX64boA#mb1=STfz>*MvYV2@yFFpE$oTZ*Rz??x1aWc^ zOAB$T8!sLT7-F}4Eb4!KP9-8C?EZ&XZMp5w51|;&UozAZ?l)eY(aUCu`N%`~Barx0 zQEI)sD<6XWtQ(ELp3ir!Hm{x5?^&nCRCg}r)U5^y%+hG2S;(EX5`jqS-8QETvS(+; zKgkY#;MzKD)_Jz>bz!M9Uq~dKSt-H@E3s8-qp-?=aW?d;*F$-cUVgoR?`bM`N~v@t z1!Fm$kzA89UULqyQTE~}yY(tsYRjem=ChYX=|(+Obx-lB3L6!o%Gs%KGc~~D)618c z^2~JQ-!CJ1Qs4KF3%F50X{5FRN#Te`Js3fajja0l`c$LgJX5x7_f*LVv-;1SNy~8W zS+jJk;;Zu00RP;h+8hga6%Qid6}xG;ozG$-ZSc17;WM*B8@h!dc_qOo{znpTyK`{u z?+)n1Pw8IPQj&h5;QT^WbmGZY&0JsP{6g*f_H8wYNsm6B`P0`KD(JgrB5vqoru%(N z-ovTO=FBhB#GXsaiPd>+#1j0xme;;JY}&n0v=vm%AKU6*E}p~ z&JQGVmfK0IB$9hpTmAu3$|}Xl?RpVhO^p++QYVu;MDiWmyN~U2yXEhtJEwl03oymy z*exO1=EB=0e(+THf?!IL>dVDP)z7lsTKlB_C-!+I7{DD$5vg1=g5}zL2}>S zL_^hVY{cs)H)h7XzXuFEQinv+$Bml5yvjugmy|~@P3jRq_2-49w5YpZAd;4ye`d1tVAP5sy2DQ(H&4L?yQpv_g4-hV#NW#wMHc#C)3{bNc)8N?$(SH+ZpXU@~k zlM_MgdTNX$n6&jvDt1YtS=#H;4&sATMysGL@`zpk zX70**&l)4#wxdaq?s;QHg@K?|hCmn_&>{D5#RuR-@-fg7=2l zRI{}s4{k&0IR8!48J0%PhGCHS&M1uDI2kBRpw20pcNma zF7}FPVtI&9EkN$`${%!sbX5g3Zn26CkM|Z+Ys@Xw%z~b(j#XT8@1fw?@Yjk7g8Ky&59g`dlAO-7^oB|j(c z#o!)>AbyuUx>kgp3SOHR1tLOXp;_ycS%~udTWXZ|B0w(7w@|bDI!8YE<+v}xHA%j{wiEJE-{ZWmL&#Z<;yn$jkoGleb&9BO$MrATf8#UwLI-;r|YnGRbQob(?u zG(I5ncr?iXavZhFg}><@zQUPbWAPfAYaZ!ITfIzI#Z>fmb2P3d(U%`ehz`#0Dnr3CO{So!Az@~o@4yxT2ShUBR=J;2 zxlEZKVR}Hn>baUk!azgdw($?e#`=9k(4{CVi>U7*>Ti^R;1$lGv#;Z8RVwuU2S@4 zq>th4S}NdJX}|qDry_e5R*1ZobrObvsMqVmWD1*IxvcPSxm@wDjO#x0KOEet-{;09 z*R!{&G%<7w{4vzRFse2_6Ic^J?ZJ#ImX+cB zVfny{AsI;9#dL)vO5sG7k?_Oj``^u(1ZH-M8!cDN!E8?!Td)<@d8{Z1QLU_K$;r>N ziHQMDxse;}v0=w~A=Nw?Dl>WE4#otjvmz@`mw#Yl_vs&j!f!2!6G1yar}7H@m{;B# z5ksk5*}P3olD7bg=C1Fl)m)9_cUYDe7HdaZq9@7Gs;vu#J&3k1a}>{UMzq{-icW<+ zTn`tf_>J0$NBGS1Pf&Y;W2XEm-tWyBoQG<>IOzESnJp^;PSKM08(h3n<+~Y2`Ug^X za?8bEobgOhefY~4S?mnH^b?^WsPUt7F7rVvV=<8~)olajlLY~n+d4GD*LF)(>qu43 zgve=MUOLqBA<<{Akx~&|Z*#R0F*#C)X?%B3u@7AFt`ly`hF2Ve*4WQXygSpnB?=`2 z4Xv%%I1+MK91C<8d2+H6JrK+%sB!xhCpoPb{DzV~S}A7pp`@2rz8V!roMlv#g!F#% z^Q2Dgk&Fk-vLHT&LQWb)J^N1gScI_%S6wwNQef$MtyoM7Ba1h%)*}er*Rf5(?ZSnK ziSokv50WoOnWx1U9~YC-qQDg;1Pe`7_a!c3uCe|(IkjH15&z_Rtkz~r$ISFnsBA?$$-9jk9M$P7{1^nH1o9yWE^1)EzCE3H;7p(rS9+4! zT03dd-ITT_9p4RHD}C{Km^3j~kL%ZOmR>H!L{D=gQdLg9{qZ-d2`din?T;D#DOH>> z#|chKDbwTF`pZzoi798pUc+xS)j3Q3bH=s!YGk2*S_DhlV5L(lL~kKxhx8y8ZDv z41)eci9d1EM)lStNwb{?PB9LYzcl&p0RJa0wsR+H;uqd>*18RWL&9w*LE^lK1!;$x zmjxotzaYZC@Mo$AR=(ABvkp=@S?<{i1l0~xkd04B=QU5%fk>iYZKc4Q_JXg5d`B8^ z-ko2E*fr`9tZynsOOwWgBRtQkxPVLWJ#FPe;`uDOZ~QV4syuts2Wo$W1};~w9|3vWh?qKTC% zrS_%Z_KDHA@Z4CtlZeHm=@3DQQ5jfiqhdH>`d|Ihg{%DOLlJ6u@`F^h*k#?ukm%9j z?e`qQ#E0rve6*-oO){(3Kbb|-VphD|srXp~p@kVIz4>Ht7c>a(ieK#g%g|B{LVNbFXx1+zjg359?Ijq=u?6|`-@Kw zv3W3pd`|evvT^+fWNC-ZN_>zXx9Vd=u3{m^#Q&rrtZ<3ncjP@ATuh9r5G%kdoI zjT_+{NOM)7CQ|SBM*Lk2^CEk<;Vshy)gwfa*;XQ+>64fE^5WGw4mIl^!uQlq@s#SN zY^mEK>`0R`^RG+u^@w;7FfpY)&N&bzq;b6Z3EP`IuID*=Z?(&=WeECLqF5n(oG)hf zF+^X2e#1pDCZctKb*%)ifS6~1CK%L`tVcyyk><#Vz-IAu#*Gw+pJ?t4<%0QI_5oe4 zYhWj%z1w5f5CVB!z~Yv$i0%lvMd#GcdB1q4k{9hqbLBRsMMs?nOu-25w4X}CLYGxx zR6a7Dr+zx(SNq*Z#R5GF*!lDSEci)+(wuE?9|=6U_d3yTf-JDt_Shz`L1&rAq?(-R z2sO@yjAu@EnPRu)bSTMKTBGeO?u2T_GM7YxoMw-qaYIT;wGq00*Jl@J`|%S6vz`=s zLB2j(zphyfEGfbOqUM`jQaLBHfS2#BiI`d35Oh8EHnw>mK{n8+?GA;FazjCxrW!Hd z3Cn3ai5>N$xZxFL4NN&tacmQ~*?n=AtvE~o%ox^L# z0kB(rTnr}slk6oz;0Pxyw;^iT-ay)|_~OlVmfgwK^-U3v#VWZ^>R>+RSCCA%8*9>> zN~{ykvZ>|kt%p@m#WkwcVEh>bldW^?*`3ciM(TIw7{=5DWH9~0mxyzIsMh8vSD)TC zJXJo!RiDlyfEp_wJy~T6bP;s;-S?fW&z(Uap zo}@Mx3^C7A)U&vZ!j>BL@J=U^L=IL8J2ejpT})9c3-iM3M{uoq7P5zg?4Q0MbW-R?S3|$C*=b;iS1Tu=UZBm5Ve{Mr9FsXK zd9PfFyEj+X$qN*de3gmdX%2!p19I=cxW%L-va*7O1J4}4$nz>67{3tKLQJC~hcGH_ z+ITW3m2Z1^#fJ zm-~*PD-tdekDr$N?^a?P8<#^aodG+*lMBPW15s44J7+)sj_-?63 z+Z&2D>PZyb|CI3H?`=Gu=MH&zK*C#LTfE@C+_Kmx6%}8q<9;aed+dI)8(M{DUx`OD zc8G$YeM+ZC+GD77n0wZhDOmfS;+zD{fZn8MrA-^0i0V6D?e0Sardm7-M5Is~J|I7~ z@gQsWXbLWd$(M$S@5oSoP_M$IzOvPszmn_%Io zA@*+M^=TXjWGyJ^ia+@~%<9J8ug#VrK~!Z54a||z)Edap6Hm>QOnIjXV6OEF(2H`W zC2%PGYA?oo;d7k}V?3y1-#avZ8=N`%N^!dy{SrmjnTjgWvL44}f#ms?r-0U5U|%_g6gWmw=S&`WPtwE(fEGdLPFt&I0d?@H zRDE8YKAD*HCcI#Dh5EfWG(oWkF0Q6#W&aqBOpkK48jcO5A_AU(WfPlmqi_11IjTz% zwpMt59;nXCf$J+N|Hw+yd=ls9(=9(2zK(@^)r6I_8o8YMvqHx&(E+Y*={1t@VY(Ln z^F_XW2f>ts=if^KEyDr0kHS2U_4r#}3{?p_*=rk3{5BxX0Pk5p@7jA?Z5;8eb0(^L zsk*1Ug%b{i52QMf7g?VMx2Z`-m$I(9_|VziG5qJCK`JIhkv+M>fBm4=mqzqSw=1`v zwP@?sGp#Xqh>)~gH9s}<(Uc3-v$uDP*+g?(0`kQwVfz~(iyC1X|A0N%upp{lMQ7rL zshJ>^Vi8n5OJ>0FPU1x&;!0VNq#O;uW986kD1 zPgQ}KwSk!v3G07P5fZX03)HQsbDQsXb zVPaus{&~pBjsW`4_xxv!p6Ne>lFkO!7Dj@$X4WPopVKQjo7kv+PV_mV{@;s$|5#!^ zCowm0{EsZ18YBo328n<~L1G|D&`*#INERdyQUoc1ltC&WRgeM55M%^0va`0c1sQ`( zK&Bwm&yNMj3}g z=uc@gJJbJ=HK2bwBL26mfrE+t|8_NSe#%Tg%Vjh`BeZg&6%PAPi4td)M8CZ$5>ong z(jSa0jQvPR!fw)V)B%M-WQ0;2VTsP6VXV|MI@fuFH`x#EA6*L%Rc2L(9`_rI8xI=~ zJ~|w*5!K*1yk89v6$HB#yajv(Y5ek&18C&oNT{jDK-APhlRXA-!d$}d_q$GCg=5bd zp|p>IF0^n7I5?LRC5Sv*e@!?}f%QIIFiaS*zlDA~iU9#&q=JIOUH))|m;&&7@Q{#= zkKo5}oc)A3!sy$_fkDeWxweZ>FF4&MgUDb~QsFo6vamyK0?LR<0u8 zkhzZD{6r#$Him2Lh4{G64VOz+0}Hk;`)J1J#zQ`awLfuz;`Gi|&|SmayjqC_OG~D$ zO=6$O^Ir3ws4o$=e%AQ{_sXSB#o3E^{?H5^+|x6qXXN)o8#;1}kpnd>eTI0f3h{$D z=LZxt8WtudCQbsBz#15u9S^L(9^zNv`HzqBAI1cEK#oD%{ey*qd-r_5 zG4mK@WP~_By+M6_Ku0|Kdi?L}(9J9E6TcudbPz{(jGXe*OdvA9zN4rBXvi5d|avuzYaMdAD7@L52PE4i|)fd7-%yrgb0$ru~7oE+nr!b$$>1 z3KYLwB!2KGf0SPX6we>7g*)4)uRIfXI9nfIU|YH~ecnlI(@y+bRs6AcR1q&fg3|@w zy?0KLbQ$~VB{(_N^W9$Wj+@&c<6%_o4FIA)U z!yfFgA)y|(;pS`*wp{;!fnoahf4Jmh2!VmW=~Ztg7m^EfpYvm1CIb!-u^-HKbyL94 zToM7WcfDdb0k9{%Vrqfzx8|oB-!tCWA+7m$)44N7V703T4z3^HFqEGsxYi5p{E@Hy zsZud}Bf`!`!Zg!poIELG(hhrh$3ZYMVN53u_ZiEBENAV(-`Q6*?c{Nr;O6(HsxX_Z zvQfP5Y|%&39n0JFZ-DYO4ZZw)n?vhbMJLi7$vXsf@vUb4HA*;>5r1lRj>~b4mpshn zW@xgVuiR731q&bw%ha6JszIA2`SYD<*UJ*q3|*12C(bH^O|maMYR9O*L$2vihS|ZJ zSvL8HcVFduBrN~dpwhNCe}ib=auWLKIiD|tiM zq%0L5=nQ7ol$jrHiuGF)*{EwAm%@2K1>MbhH=rocQEK2u{j8nUI*>nlIk1jhml94^ zqR?e@MQ-$sx~N`kb&%P|*J6+Rg_LmODr9qlAX?Op{mYK~x1P;%@bI{XWK9k~dB1w5D~t9G zTn;!+hOpS~EMd_c&z9RW8-vkO5YqMcaXo7n6Pl&?VE{SNGB1>@cQZl_GeE#jG5?11 z-*Lfd41%l+Zc#|Nc*H<9nm42xwO`IlOgUD}sR(cVwP(JlqAoL%fs*11v}qDt26=~V z%mMLNE^DR35{wLn9Q{ODw!-=2mmbY;_|b*i`SkNBXL;U9LVpMbl1a794wf8tVi(o= z5-e|LD}WtS0Q#dm{fEPEC*x(qVUY|yrkqjtF+(*kpDfanec_Hv9m7g^j}}NXE5(Os zvMP!7)>*@V1$W|7f4S`$<&3kP^&VM#NmQ}L$MY}i`y2gIHmG};&Bc+S!V0g(N9r{* zQ`WXdq30r%DuQ4#IzL!cydf#8!l_;6fpDP2v%?dFAc z?O>r8Ip+*5nxjL+odluqxp6-I%6N!vVNNr8SVlOclR`nJcu$;;r2$C{2jH<3ai44J zj|DpA*$`7CY#N6I+*cwltX6}lxEcen8yDqedXe_B(#m*-$4R+~?I0WuJCSS$%@Thn zF4qIuAn$>SF4+ho}@4JGbD>JEpMUqCncsuVh}W&R94+BZ8YoId|tJ1~%`ihpy^I zPAmty8&}a+>WM_;GYCFy$pQwBZu@Zj-mz?=t6JR5l5n4G`NvJ zR1DXY){wO4tFP)>I4CtgzsUi0bqK%LTkTWqP55nMf|PLl`%tYaZLAL|N02=@ZGjy% z`DaZT^Yve@UZ~R|8FRX}{vLQQ`t0hKP^RKsNeAv#?qw8>mMkRUbc;VZ6Fp@bH1CQZ z4C^Xg811i0bWoNXlaY0|4OzJmm1i_nAG}1tsz);N6PPtB)9#e7_g0iM*|g&dO~v5# z;6l(DVz|fI7r3fsbu@)6G&aQj_W@Okjw7*pEPuCQY>1W%3B{69(;Ef#&>JK<5rZyF zZYx=5$XfRnDWNV~6RkiOXc1<&%tUXjLP_yMwU11 za^I;#|7^ikRc0?;E8yD5bqDKp%!|$NC_ILA+?Zm>n#0FA9X}}75+qS?X!QlcI&pw| zOzR#j1I19+_nO>wh8b}`8ypvsywyDXNzY;MeDJYtRIck4eE#Tw>pNt9P~s1I31+{X zu78^F#$I^FJ`cWy6uT98h)YC>`z_BTbTJj(ve%xmn$xE@A#FnfV72$;+d1peE+wDMfz8(g@g77B{$7S zAgO}QrQbSFCPp6dWG|;swRa+2WBCQ11Yi2{tk()}T5u3i8MeBPMp(EQMMKq?r((J| zFH!YD@mlVTI@?gQVJS)wM`4o1beit9)S4GP3fVDC1MuPfM3L5wK%p;$&AiL9hCO#5 zR}A)0t6Zon*B9fZYKlhRD^i9_w;Gfi=$*qdYM&)j92k5fC_!}0x7c1Ma|!xk;PlrJ z%WBqLs&cr}YUN{oG5OJ^NuzLm$)a0kh@AuW_dz6#vUu2@w8zjjnV+;*{t9(nKn>WWH)aAZD-gZK zw$hCV^>50L%{-REEZbaTn`h*DiDNE5m>aUf8Q2c)6u?v58(%oUPFfH(K$s`j9B2$z zlfPgPN&H-&ASqp`)NzX){*Cj)*R%DWzFw$WjRPHXL!7xVt$#RFax<9UTHK?V)Ae0h zosDD@Ez32K#fO0dd}Ct4iXtM8F`4CWT3?C+K;=&AuDf43FD*UDSSK{B^W(Q(OlRF^ zoa);cD(nSw;a~f_-{%sgYpM4dEln?rb&sQv@wuuf!L?kWe?E8ZBh9u;ht@BjD11JI z+2Mf>)rn1z)zIW(_rQ*&gF-MR5TjuJa?Ni#%%8I}-5W;|B`$-z%y*JAWL@(d9?9hL z+?UyNn&KR*?n1hyd)ov*k8Gwvfy}S|m;-ac9L^5{9vX+xL6CYtrMtaHJXtms$%X>u zY|Pf`)FE87hF(w!V=3(%GjC8$!DiSnqVLPrlx$uNnMRror|412P?8(SCFada#4uL* zBTg89{olAlz(SPK3yiD*`!>=WYP1LzlI8AYMhjK>Xh*h7-jX9bjADeA;xU@q8*uKw z!WZ9=Ycd>((fB9x9W)aoH@@8gvKo!{#Ae)Swx=1u(Ml=qCGTv|YpkmivKKcVqRjdV z|Mejcaq4m{G3d{!Z-8Tc{*d+fhd#R=G$6L=3Tem{8Rt>o zyCCiBAv2Y-b{Ho|XqBM`ioI3&U1gb#d@1oTmp{}y;A&wK{{}@fJMx1%h59o2T$x#y z8&a@ZU*y@xO0_+cU%b&gSS-&~R1Y~;H3_Qm-~z= zZ=8DKQS)^~NTA#Ge>mEW7hA=CVSqsX^2S`Kzr1KXz4`d%TV-WyEyR%BNsM z-faPAu%`z9f@cBI)ccWaR(>9U^j_IX9pI_lu0$J0g^5Vqi@n4t4HHA#cWulj2Ighi59sa*&9j}$ zGD4|hWyQ)t+bW5ujmQs2?qO@a33`|l^i~t1l{0?ify}-rE}RnqJ)?{v{@3C%3f*-DS1MMst@}HM6~}pT}?kB1h(xz!c`i^#v+l ze6|af(^eT5D)MbjHRhV)t4mB|TBS~uM!I9+0IhZ@0&qJ%b?cPSEHF##q<~y7|C|@YaQw5no-C%|8IDvsn>}(tpV!rc}vHw%KqB*{_&#^+&4J9 zJjqqI>JELink`!SKSeo?Ob8f%4+;sc6tY}IaArf)C71Bl`QO}UJL30{8LI4%#>i$X z*wnr9Rsz#}t>^Y*S_|j~bk=#PHoxB-8}5s@X}G_u?ROvQcUYdee{585=A~qF#b`u6 z-|#kjdS{0eg+jH_GT3j_L~Gicl;Y(f3g&fwHwvE4sy`m=$HE|C$`x9@q zNrAW8k_ZUDz8-kkV4zy{RbKq-))YGM;(4eev1_b4$8s-yBF+iDS^Ei(Jzt9EJHmkbDACt z|84J6X;ikm7r^)RCLnN{eu=o9UXKKN^CuGk z+Lt`=>?G&oqN=e@y}|CYV&P~GO=4G`X2lGzOX6woH*9ozhZSqgxEK%i41b+ChFw^A zi>|ErYG^xrmN{>|G2xQQU8CKK5tr&wqZt^ihjtg$#>yXu+3Lp2vGOD zuyqVZUwU}g+c;T`%TjI~`ukevM9BjwU37R3p&RVG5@kBu{}>A8(!|_(T2}C79GACW zi6@#w&OoG={!WLslVWs#@(mkQtDNipF}$}3B{)uI?0ELgSMv>H@4U33HpqGwii z^9gTfaML!NzIu}-a~90DI=I(y8ZeXJPFO}C(4l87sr@#5K>(Ybz{UUG(s}RSq>jH< zJ29ery}Ft?MH5zLyQTMFOGD10a~B}vhG9h=y^H@d336(~#8zCSQuyakdL>6gR@Pnk z(BJAhgRtJq*u(ELD!-h2zgVaNrm6g0bXHFC^hX9-9>~+)@DXRXqkl@Yv8j>{$stL8 zy^D3_OytTxR?Cj_^W*aK*gG;5K$I&$IbBb{lAk`h{+XMDgc}G3nN~pPG-X}h>D}zZ z&R3CS5Ou6N%B4kQw=vVI)6ySw89g=h#dFK07bVa5dx1^;%K>KtL^MtTUSgV8uDyh( zMe0r49R_eP*B;xY-IIV~%ng}K^TfXf8DDoSj$Qxu|9mlp%({k!XPuXHnqhJ@GL(KW=Y=9Jm7X#nj4I-Rnk$vDX}7YWt8 z6grXCo{4a|UnL3%+zffLc!i^hMX~7U2G^w z{_3C8P?D-$#e33Ii_j;^AS{Ho>^yQ4n6_==#5Dde_e7{|0yOedUVe(zes4>fa&|d``{ib|y zuk4pK3y~w#b@^Sdj1N^tZ;7|iRfN)kb`8Jp)J-u+lU=$6)U@98&or%ldCE1BWPLtb zcPy|IBJ_qsWD)QELK zGYa}YTSuhCY4>Q2wA^57&O~5n$+%H@+eqWZ@l3F~cN!fmVN$chCanfij$FBH54SCxiDB#a-nQND z(WFFxJy~Q-*#KN~&_LqxiegruUmMUS*DWM7GeM zlPwJ&RF=im)c$+ywmYNOKJ3%@Twu}VE&6_%peuFrH*PCK3r1Y4y|i$1{$DC)2hSA!8|ITgUqT+$4b9!4x;{Xo;#+(Xv;o_ zip-u^`*-#?uZ}yzAhH6p{1D)r`o()uyoJPXhfhPD&t`+u*&6o9z!WT8b}s*gPwk+r zosUgJ*J3T_M~!z#w+FQ!jTtXWM(mQQ*!RWs%=oU6N*Q(kJaTm?O~V@nGf@EHXA<*? zYEh{Eh)7O#!0q2_i&t&D(E}rvq!cno+z_190o1u#rtjDGr4LGyG|AE(gxd#(=6~J; z$-Ze}VS@QO?pdzo<5F^|naTTRrFhQvrMO+#Y3^0~U$f6XbVhdRSB&%wdy|;P(xFub z6%ErUZXB6b<=pP`i2W{^ z?6Y`u%v~~|UkKmnEz}7>;n`TZkM=?p5*;Mb5|dm$7#uzxX+Rk_(tlaT3};Q{ioWI3 z>tpSUHjfJ9R6mk7CE5H^&Qib3<-@;qDI1Y@wM#C2N)~Fbihuq-OV0DHA!-k9mp-Pt zY&;ZlPUX~1uvF5)g!$=8V9v|*yWDonPUjxrTbecR9dE%; zL)3woz@&;iP?OSsv1MekTSQujQScR!F%L`S>gP5S*BS`NVgBy6xl(cY)wDAc7xO1o zMAAL}Y52SZc}NNv9zOnltu_Av4yM!oe-!Qi7kKeMbA$h1zzaEL1vw?b|8f`1|1aDH z%YV3w|Ab!uQy^hu1pfbn7mQs03%vM$auD|r zZ!Q>{91fWL=VCH8YauTwnwwrl2kwj~^wf05S};*H$fc_nP-M8mxH# z8{fwhyngdO7}(!_kw3nnkbBxa_F?pJ2vbm`1U=OcJSzd(V9$(Na9_7yVlYqRqv3)w zI6*bd%^avh^MSB1Zm|bj5P-WdS~S>?TG+4W&`pr9mbkglj?f>=c&I3d-QDOrSFlr| z%ir1s?HRW=wjk=Dg@2q2^X9qgb8h*%`E{1V2&^I_z4dAAqQWwC=Y&FnU4wmOoKGI< z{UVv#>><(8O0B?$J4W>920JBX(D!Sqhe7Ry?STdpJoDuW(B{>DxB^H(X#LQ}P8XML z&S(M}vN&L^7nhUoyw=-j96_)#u>JdLG3{M5Ys3v0bF$zE#|R;x5*gq55;*@rn~TZy zl!wVtmyq7}y!Q`{W#L@c`>vJR8|PiNAfdG%J>}uR^IC@edp(yQIv6P*lP|h~0oW2D z*nOSL-rH|~{~G*94gl(%dGi77=mN$Ga%r;}93^Ne@S@B9^@o72J{ZI~Jj(3{&*LEi zEF9F5pfx%eek~+a_>J1V7t7Ln%-!2tA1NQ0Q>WJxIJkEg-^ZJYM-3y-*SWtBpodMh zv5Nd^lS=)OC$rIy;OlEfVn2S4E)u^Cy`QP5V3?Q~P+?)0kO0JI^Z*v>sUfxtx1a9dg6Ah)C-^rrqya*Ad_M^xdk&l#b^@YFt!>;24<*94{76$k8(!c?s*X%8VgKyirZN_I zD={orY2YY;3SjKyAzgv5{u4lJiUz0;P}{a^G@Seedbk-;hiVp~yOH;HUvS!p8MO{y zaQb(3le^F#eSP0siZJG|O&_eL9)p9xNjM4iBAkHn2U=1;{!3r7vu?hwV5F^m|6a5Q zQoomb2=IGG&WRcx=#7ftMHrNN=r+GI^lP+Gy+;mo;1%aFBJ3S`>6ISB9dyn=bYb-& zUjNBb$1ZIS^Uqwtzx!wQgaJ5Im;6VdfyoC{(;GL+{tvm3$B0)Jgzfug?x6RG_Yx-m z4-=pQ>QU}-QW5GM`a^ZJYv)}zlF@JR?0r4t{YAu&3<&t3QMi5Y14%!VX?Eb55j2%gYn zGqZh2X&$}BYm!HPefg6@Eq`Fw)SKhX^{-jor2Ar8^zTm-G06x|scVbKc|BiRrL!KO z@nf{UC>}n9+^d-f3-^X4P(G-^j3EOpm^~W>%$?VILh0LwAfJ&O(Lf4cKz1Nwj1j-d{@t%dN>hmEenK@TrhIa`KsSj7IICL0n4x4L$59ZF0d} z{urUmd8LXWMPEWKR$M^L?^FJ$4{jen_EIZsmByx%EJv-*qq7ZJFMFgE*N9 zWw!3d|s@&6*+bqzst6bN;-R5MG|Lq*lyL%&$UdS$| z=y$|5N=2#tfjy>VejvvDWt0t|2n~_7LFN}7)5>tH_#rh)SBk#aKk1~He(6ee1AjeO zLxmSf#x|R2EixMNJJ2iut;F;ie{vbrL{edL-?C5arS0yT9mA46E@y_xalZo%9AqBf^ij&uu3oo3=5eRz#nnCsiaivt~ zizNS=H5De$BHrlTPBzc|ca7~o?2Ob3-XbruD&K0iqIhK1S4KVXb1eSduxQE!bl)f9 zE!bSe>CoVeO15^G88KcR91I*~DHfGn&Bs1n``j3}P^IPAOWyCc~(sYVsO!}$&({-vb$Vujp-TLyz!~Q z9sPFd&MpVyb=3Nw(Wy@d2K19YCDQiv2~x!;;QTtoGsahE7d1sm%U0bRMShGXujl-@0CvT@lJ0?! zT+G)tXZh=A+Qc7{GEYI^{2ha{VDiSHJe8#->cYpmcJJ7uWj{ks_lZrZI@R_T@2yR*E$emc5_1O73vZmV}ZI6Gi{=>4;^M9CV}k6iujQATK7znAyGJ2GG$6 zw`prxKp3cZM%Q4f^Nc`}{{T(vD$*fEZh%Ga#mxn6Wqlyn3?A42(puGFDeKgO`9vHO zYtGDFw+0Oal8YeVV}c8n#tkr2KObJGmq0V?M$`LnEG{i|Rr2z9_8#QeSM?d(mNAt| zWYfY9nVCvj*(Y(9b<4pd$Hu>r)kD2$&_;d{P_gHhZ0;@+A<$g9W%c2ce65{f_$TmXnNn+3 z+3X0j+~{E`uQ7!{ai`DoVaaRQT5Tn-uHEjDNenlbAy$`GH_|{@2vg0~_9@MM=I!(@LN47b_gxCo|-M~1Ivp(H#30`*u3OHg>AlB1aPDV2ZFv+ehciJ_D& znQS@YZpY=51K)TId0PLT5i6&oS-FBv(J_PT5)xra83VjAo||N?^&C~z`I}^P9>|Qw z_6bBymYg5cgQQM`L}+?;+Sz6TCNYyQ*Q{dDc~0p^+Yc&;SX)@P%c$u;wuT<)s&JEm zUy0#rHB}VsMJjHqc;xN(d)PEb!cC^04F>lGfhedu+SEV(8bAbhrZt9$NBo@? z$IgXt4!4EB{n1oHTX&ySU%@rmZn{vuV>@nZnPvZbPfsf(C64gwu`@Um5Ajyl0P$&% zyxq)Hge)m{Bb&XWsq$w%gRvi2*Na{kP|Xoh8i)b&Do`HIICFSij-`9_e^K_%QIb8` z`ghrOb-B81+qP}nc9yHlwr$(Cx@@znx@^Ba-#asR=B_*I{oVi0b0SVe?j8H&%C+)| zPv{?DgS9h3`j`@BCgbDiZ=5hdshz&3aPCcMBv1*+KcYWsJ;vwkv8c}{IZSnsuqGPB z5~jEY#_sni5-`c=Si&&MpVVR#O_AVdqpRL+&cAIaeOkr@>WKP5WG0%%FD@l_7{I+k zUj!uR)B;p2KYl!m%U(eL?BghnABViFrMGFru+$Z7jMdtwSO^UnZkXCXqY0DRX&w%S zT+~{C_e~)x{2}h)tG-S3n1dZ~=L{D$KR-GzdsE{K5M6q#z!bV5zf5_6_d_QjgQ&AH z{njm~ES2mEFnz5^-AT%@dlf(RHeQ`qi#*o(i+OwN1H&)MfnxuNP# z1A^u8{PFsoHl;96S1V8oQ0b_ax#r{DMl#KXOB$8_&7?N<)}`+1sa&kpTTQT0~+?)h}r3K%^RS`ja~7Ewe0U5gfEa6IO;UZe);l zClpYMXjY$gwOcfq5Dit4#qk50sjSuEiy0dN5O63fZ1&B=;nP!N%)zGN%t@=8a~;e1Xtva|pC*T6itlRShXibjidvF}qnM zH*p<6mP4&^tsl+Q54j>eKpxr_N4x@U3X`N_?c@_{cnnEgWNR8@_qK=O;&2IkZ4VV#9w1{O{9&lOlNlw(=Khd(5XowKAF{YZpQ?d8C(=eV<1{6`QnNRl>_IWkQHeoWZDs1dLT zF(7ZJ(B)_|b z8bYWcrEffv7c+btsD8jaP-L38zuMK%(p~~6cQJt~7)6}@ zB+|Bt&GIlmaSEOfj;#NIj>7*OZ;Y8wkIN%ynm~bymE8Bjs(%plOS*Yh-p4c`RahJB z-e1>E95A?oSS#LNTdqU>)Sl#dvD|2RKxTnW5XqDD%W+_m6$Xxb@^Ey`rGL)OrQT4T z4INL7=(Am?mtJFZAr=v^Ox`EtW&5Jk@ag(3J-X_v6tURpevIdp@tNRvF{**C`8QHf z(E-h_$Q`Z)?>EV2f))QGHR-}R2zjxzA4Ay)Y!2T<9VR=1GodVHRyxIUPd(=ba9T}& z;t*Kq%3w!V#!SBgXX-ukj4#A*;HP(KBUG$+jj7KTia&`I{n{x8Xk~`fmYr%YV4HA2 z{pP*I(3#FO!vU>4-_us73FbO+WK*Y8tfoUo<_527`9agCw#~ad-|s*kE=#25j5Ume zi@3d`M|sn0BJ&(t5b}WMta#yI7i#|YhUl`Gn5^i9p7xSXU#{*;6>F8_hhsjGhlSj} z@WZe$6wh2{LD_p2aNiPZ>MK~&A^Py>(v45G!zykg#_4u1^P>J%WbN~EVO0EcJ2Y0I zo0(+lIYtd^dndb{&rT2}I>DFZMWV#gH*t@JGsJwhwNGi3@mIj|qQwzb+` zYBHN)=V00$0&@Y&`^*(uGMK^pCj9&cB~5F0gl!q`kZ)7~-beJ~Tb*cihWl#bFS(RcnZE7p}T3 z&-q@_@yu&BfG%}r9=K4x!coCs1731U;qrJU(Whyz2h2&!s+Sz24RwpbOU~~R3Hy`& zCF>shs_>a^_yH|f?)}Iu=dGtS&U`7!3-u@#tV>(IWgg;)>+Aw=_6-j{g)rAA)5k;P zsNT9tiCi-|!FocaA3vb5_-+Sk;ZgPSWO_J|4o}?|0d{f=LyJx4IAm69GO#__0~_El zIc&EXI>T(<{$~^~ScpFlsoX0wAmsb6%`5HabrKYgnxPJ0_P`4~jU!!4b^>>MjBa9X zKA5;$Vj5r4;rPFw+B%NO%=M6pSdk+&&we%0l5*-oxsd-x5~3fQX!5vYPV8QCPY57> zIUY`I2CV6-xJBQxw+RphXp+}j^rDWoIcAL8)?XaoXS7YzSjAH+H7bKIFvA^24~531 z$ggivqwnj$OHWkWorEy66=9U!)4e;&YdTxl#rm3ea1Vf_ z=+f3a`vE({yF=}g^;L*@3M{bm%+nfgf?ip#juE&+UqP>hw zPFI*X8&OodE6tgPJfTp0x6u|1@JULO)y}daJ`_efQP%5$mooZ%qZPOsLE?Au%ZyD-Q8{> zFU4I!>hf;rI20)3yp{6{_M<3Q9U$5@LPm$SzA+BQnzHptpRMH3ady$jWK?Ce1v1a> zRy5V*46%mDNo`lsXu)E~z~v3vr{#6fCwsUX{^tL*4KmlPA_x^8E@KN6nfe z3}jt4Sr|?23Sx0dhHG_f1qI|xu(oE zn&bEyj&pRhj($0AC(!?SH#QChJs(ak!E?%`Ta#kg-N(#xJ#!x)Ozswhs@eizcF;SX zypogmyCFcuGav-|%b_8s2MD4h#N1};C|kaXf5kp*drVGCF z=Gi#i)?TabZOY_8f6 zO*(ALvm~L^T!V9)!6UU6c6>3w&WY;}djZ~>O?JG@uXc4i5~1Sy?pJSfIIk8;MX8y; zTqjy)N%0EY7RgpBqAB(;$BhqCVosbZCx4hC;srRTxxT>XI{?NL1elnf#6-D2ML~J> z-=-Aq6Mh(Ej#M8TF2kT-$KMw!h$fTe$Bl}R9aMqh+bdIc@9@9+#j7SQ-#O|AdYNwp zb#ui_iu<*I?m{hy)eV)C_MQ)47T@CvbA8v?NACUfOTcC(z>fip!hCk@37#lcs&Lg2 z0lg;OoUT>R$N^&1UkjPcrD^h+NrtKSrbW`Ja%BV1zdTcp=d_9m=rak$+;v0ToOY6Vz@|_I6 z7ddC2Ob;inO0p8|9+L<+m(le30BR!p3JWZ!N+ zGVbspSGF~k%qNi7u+hOMw1`Y@u_I@y%p(tq;)CMgWvhf!xg|Bqo6tOnksbXoayxOy zS;g5;UGfEmX^ahg7p zCh(}KDuAM$czg4WC~-JO20p>H8!rB4m42_YnaE2lWhhc0O7YrO`eVXqw~lp3sL@a7 zYw{NquCOBYh&LUjKrKsphN`_#H4Kml2~ST;aRd-cONd~WKujvMk?}h~NN2NR$8$#F ztSkf{y)G6$oY;5<&qdr`f7i!1o!YeRoJ`WqBr4BdJrSJh^Jmo+88JJ(n z$?4redK8avT5r7jw$h4QEvtv#^u25GKs}>hnHp@V+~pg_H@t9>LM6O3vTR5WG< zRA+H*ZG%@ek{b|O?s~q_Frn;0o;+rq)A0e0Rzsf(=knZDi=_$Th7Q~i9YlgjZoo8K zt$j*t(d=qnv`fodbFS#N%JqH&*c_>?$yG7LT&7-po0{EPC8f{@;C;+9<`QO{?`Dig zN(N{vF9rFXr?pR>P+9V4OBkW}RvC_Yr%LUVQ;ttH*?P2&luaR)Lz3ON5a~}gks$yP zWh2F=9z*G9?LNu<;7F+75wne*s0W|sP>P4CcLbZLhQM)$acLL z;m~=WQYRdZzs84w#zt7Y2_RNZ*+EtE3(cz{_ zN9541R%GO23m$sz$BcatYeh+kZc-igE8pyyhw~x4v4Ye-q?WJtRI`q5MS9;`>$;4I zEb1(3@d_2xI78CQ<@Xs~U}ZQAmZC**$;Jj^j3xVRHC0+}Bik z_Q4rH)v?i=imLGg*?ny2A0!rp;7{0+jTU7l1EGB#X1+gU3Fy*>98`z(PR540e=IPj zDR+|kwCms!cLR-L&5B;!G!>7;187cE%Y9@XfPdLn53*~meWAyO>cPUeb@v*~Nv?E&GIT|7@F1(K1&SignA+*{Sw2Q&F=v2@;* zo@jJiv`~{);7-RBmGlZc(~kzaqa2hlI+@gNJa?V%CY5@Je!blpV5Uh7w?M|^)ri=h zetLE5R>4UpKV}~)3MWqT#%`k0yH%;;8MU0ZlMR`Lu(9f^$@P^s^-wU;Y^sH4sc)!KJ>~FLA+N;p5&i=wYgswjj%FnIq$rb; z5mujCBJxcZFN>`Wpp)WWsbIM%P2*JDLm^o|)5^gZR!SK&N}Y;-MNJ1E5l`{fV^vu= zl5x+~n2}mYR_vRNaCYN47@qtU7*iadpLsD}N=f(Dv@!Y6&OEOhwBX*{lb%TVVY;;3BWsqD&rb-4QH%!bAb8 ztOk$FpNC6pCn)TtvGb-!l`R&-&3j^rrm*WH0v{;>@EIX-eMfV*R~o^Mi%V~E(Pjf$ zf#2iX+YD&}R_#u(7_Cy9k@p+3zfjvgb30WWv!s?}9eCcv{3aX|s=4v>KELBOFmZF* zhzDJTib+`sKtB<*4D`MRL(!RJ5zQkU6m$}SIWAz@r+Ew}nK+ z70W6TxhwqvY==|z!3r^CH)#9k=)o@gqu8U!h8f6QwNZsUOLq0EwT!wx1FIM`OD!<7 zN)selXWno$l}Uq(LB5Y7TI>-a&7Rb~T<5j`crXwI0Kc8~O?%O;Mp8fb9Sy#OOe+6a zqq0Kv4hVj>hHfCGC~~=jq;lJI(o^__i@l+u1hbnn7}*efxfz4Z>e1%@BX^{qT9#u&PeTI`Z+^4xkUg`nSk=d9xVkQV!_zHf zuY5$8SUeJy<_U3U4nCKq%n&zbVFrBu{s2Lg18&$;yuoc8-Y{GiNUFhPn-JS}ESxfQ zR6gVCK^e#!gfo4Q5QB*-ykF@HZN*#%V-9IT1Jp$&y1wYRX$UV6Z|45rq;VQ1dqK~4|ms|{( z11+ba@KN67G50;R)N4@ZU{?m7J9OD9DkS@mYoTbhRKzE9Su~{YlKQj5H>uf_jD)(d z1aPKpq{?&y2hD`qd*e6OiNk0h5iipv9J}j%2eSUG(snjN=k$J0XqK-XR)PN~ybp$pB&Pa{aB5QjJ8kOq=$#(<6UquC85O-XLF_C2VM*b~b&` z@7jlr4XaynV8Q*lM#3czoGT+e8pQlA0$^+D?X4+*6t;4{{t>kk7#26V(D54L8{OxrHx#9Paky{?BlyXGieqcpjVIE}N8 zyT(xBb30W1*~TeKb{BrVdwKHl;dc@i$-T9vU%SQKVRql`_!dpVrF1^v2qrN z*CYL#_a>;m>D=q0urOuf@c!F}d*>c;5O|qtdd<>sD`14@y5vK24t#ulaWBkUEv+cc zT)YR>UFpK5+@mYun5~ttDk#{}8<_3vyZ0pOpe)<)^CxUQ9C;>aIo+y1^{?Sa$3d!D z)Gx&%%59Uv6ez+&_Z~NwVV`6Zlzq>n1hbLI;^I<7t0IC;Uo98;!rh2^$ctA2^=0X| zC5(}ebnxn0S7`F!DFVbyrz}-&yYwlaV(dB7YEUiYG0prEt3Th2wtp}yY2zMeQb`N$ zD^98o4pjsCLv#3DO&tQa9pDa*0wjkZ8RH(lyiA!CWcRb_3)FJIpY3lZwg15hV);LC zg2bie)P*(w*wsY;BPNK6<&Rwr!1)J1#K^+>2NcB4^xu9pmOt#D|KI1AL{Q9{w4p> z)!NkMUq}6K`Cpy?uK)D@ckS}mq<^&n%v@X?{vrP{)&JE0eEJ`g|BoC09Ph98KjS$V zI+@!2tF5h}i>1AtiKVlHjUk;Uy_>0r%ik8;@^8?ke>3ti|10?DZ`>o+ zzqm(@2i}=n0Ji@_H7Ke`tIGYY8e}E^6EupM>F>}e1{RM0A7~Ww-^u~-pQur^e}hH+ z7dMLik5TgP*eF7lf3FBZdZ9nusJ~I8B>r%tWa;JqNsUsY*Z41Ll>MJX{b5F#nA*4) z{_#1Q)0-Rq?T+$lrv@x;#!+3{w1dztp72mN`Hu2F8>xO``;sNtXaIE1pHq(V^T_5nhHvP#rB7>^}obM z``6dUUz9OMhX1GF0RI6q_AkM)|C#GQ6pYdzpxA#E#y?8pZwqYxCuFO?O2UQypG*F4 zDfn-A7?hof{hybJ{V#YJDk>8j$G_0Sn3&jE8UJRDMF(SHVrTwCivT7EL_LEmWZBL` zz#R0`TGaJ#ZEf+kodX4Rc1k;h?IQGN0}1}Q))pcZaNth#b!T6@`l_5MFE`4md^qdr zyfTN8QbK1HQ*?$@&PxjFrv6Ti3QHiMbHhsw>mL%59Uc+_AD^IvcW4Fs-ij5kgnIfL z#HsG&ZBk$p+hQLkMKTT07I=Y%_Z!&Bt_4WV4Tu_(fSR2E7S=yHB;<)d6k)~(2pZKr zj#D5Wn()K`(M7Nb&E4VN2|`n=J#gXu1X;jX4A$W2=*a9jm0MsD;S`RExgL@tqfHC= zq7Qpo#s=65!Hh7ka^)*H54q0C)%DQW?D6{AfT`Zu(8-|%t-urjNTdX^SS>*JHMWFHqr)qc6#!J%hhYNIk{5SIsBn_@AKk=8)@uQe}>G=48bji>`{-In3f*_P>VBP-Jn@nvKO5{IG+p5_nx?(RuvHbW?`j!A|YcX5T1 z4hREw*PP$h+3cS|u(&!4e9p`T8^gAMuaAkR#Fyt4;b>c$QD`t#2qMiBM&oui8b zn1+8O&}#sV|1P}<0Vb+DVc*gk{OQSE>plRPn3}o|*W?(60bDEaH}aPVWMlxwm%;TO zcMuP-7tQXPF?ikk=ljz*5Rcw5!efgbVCu`YXNrl5s=}$@{!8UuKRYcgh`cW>J_x*T zY-Ak7;DZ-nvbhV{`vqTU1oFxr-Rom|L5mC2^;HMn`innm>x&nN$q7iF z7D?dFeC$D!LvyMRpz*~Y``WAX`6c^&Me$`X{0V@TY+qadl$O1t|M-esA3`uWf3OF= z{@KwUh$%1!+y(LYwW0$1JUdSXGA(H5_N7jJZUq9+15@;t-uP-kJ|qUe16mP8N{a+)e=i zi5=jt`QG~jy^jXC$(8k`@EDvy`V-T!5h$(rld!J&o?r+9f0X|RULVaHq$5z;(I+7T z@C*MB*uJW3$berIpMpFj}SpXseckc$<;oVLNNeou78wAKu(E& zAcEY@JqPtIX8@4WVwVZP;My6Vg1d6*T$yQWK>hT%uq*sd zk6#mCni*eIeZ?6cnDqgu>FFFnkjK4V4!~xF=FIHeu-ey_U*c2HGgik2Z>dD1_QKcM zFJWs}@y2XlsL(oH?LpMfXAt_80PFy4(61rzC$MLJFwM2T#r{IeeWQoc>0aNg%{~C^ z2Lbe({dak0ZPdJ{(H!~cLgaA)iBi&+G>>MP~*3d+$R))8!{ z1pzRV0lJAJuFam>yB|a<2QUN9njW9-N4K!EdgG^D<@}`hWQRS!LVc_JsM@vr44-|$ z0p9wuVkckS1iv>o;_Q=s?PU!L|B?jq12A-Iae{tvIXhtL@Zx?t0gXDm!2$x`PCqfh zTGtM013K>}GaDJ3r59p|=CSb^#y9z#zN< zW0CGfoY*xP%d&c#=~z5wQ)#wl(-ruxl?jx4ikm4|mkaUjEyps<%j5qxvAeOQBR z@-~Qi#}tpb+i&tJ(0aP>u;LzVaI1815cPQ!c&m;Q#JwuAOrw^b^9WSfIMSW>!&#N9J#Fa7$x4-&aDr2&Y1;5~Hs$oH(r z&v41HtBx7CmkIKo2|Q?__pV|tCB`kkwSK-~y)A!wJ>4YREq}bL2vD&0 zue836KcH7@h|QQxtTyLH8*O(iH*Nrh$8^#Tv2oe6c+*xbK&yM2jUNz6pqKin)AvwM>RaghAEvs+*V8`XyRhdt-`PJgC+oC-7haY+C;l zTWw3(Gsi%70L&+leh7cN{t~0H?)0|rQ8)%Q$MN`0Z|Fsp{Y&L+J7-j*;h~QO$`gK1 z$&2+P;SWxcu?M}g=w{R*BhY4iyDV_p!%FoN!r;zFg7j|o!U}*(77jy?5>li)a}-Gw zfr6m<>ocf0Bi`b}fd1Tjo4AB|+A4Y$I!m;o=&h773Uzc^aL|az5VVW^c(jvURn;hT zl^h}CiNBJUcvx)TZLwV#wxDAN^7x^R!dxnHL?C(llJ@?4TEdqCrZai7b+q_`5~j~; z<|(D`twC8*avq?FPE!##i68mLwJxJZ3dOI{T3EFH@D4k86YEo@p27fu&mTR=;x9K2 z@EMzB)CTL|7*^#XtOBZ` z;O0rNIVqB|y-1q*2aF9;+k;oTCRXpG6o`c+zecbnGdugS>v;@C(tnx_ zCB16Podmq%;f3K&;9eGat%LX4YZP(i%tLjosY*8Qos`L34>;AO2 zJ|L|LSnNHA6yQAJj5dj{KY-m9Dm^TlJsV@Lo;>iy$-gk|OU6%rVhl%HK~J2y5F#PF z)hZN>PANsWGFLWBUy!NYOHj?vtMldYd|n($i|VXi33~Fy=U_x}X1_gT z!>q}}Sh7kBa?a?E zg!9;uSd}5SdhNTz^JVXB#rV6ShKxed=gJ_WQc96tHVEXEcLc%HLaT5<66lh?nOGe! zz>Up)6%Lo`trdt>Y<8eQ&Dg?j6x_(oT*;x$XS%BFdeZXv8hubtr?sEAG82fHGU--< z2i#k(SsJkdX5`A*wYhzM+x@6(=Nc@mJn_+TB$wMXw<-xg1H<<*nGv`QyXq&*r5UW- zYF*y(Jbr~C)9`}58z^zL7VO@V$MBLH;JhS>h8nxh1#v`kX9o_A#GaH{Tj%Ly)lIQN zq5=IH**aprBAk+e07hj$%dw{#Z5Ew&y<@umsP+c?T(E%XN@F>+IWt;eLK21>z0vIyFEfkiaIxi|1L;oSc`Z8SYw@;~35q~=kr-^L zuPVo04}-1z874D~ZnTVo{lqhxpc&4s2CWHwLIdyerW@{_(l~56NOg0Ijl%M%J5`+0 zVmi?b%s_ar45V(N?#Y^2zcV_70c!lpk5>xHD!cSL!wz@8gNS1%;OeXGgm6G=kn%T? zcJAqr1p6_Rv_5!30$^3Tb!8Y(>idq20OXCuM*DmR(Y1^LwkoOY0S~IJ5y@#aP5=sw zMmD{8zp+I|hO8a)LML3JGOc916Ak4=Kzp7uu@eG1c%xXlB&R#h(9iKffO4}0uG2aJ zzF9hX8GReA5LxpFA-!v!?n@)RN3qwioosa!M z{zQZ}`z2!8{+8=JjU_b>Jupc-*7`ez3uEkLi}-`w?+}2pu8Yc4t3+Acd9*!J*iGX+ zHf2Xq9n+AmWC6FBVn${vKu8VvUMQKS!$z{s*naW|9GfT%iN1K#hmtVX;ab8g zk$ncf5{$~Elf|`nfa5Dh-|a9RW6PTI!g+@$x-nVUl>g=i0e$z>+(!c@X&40$n`2Y^Eq-~eFY?RYk zSB2|rX_Ar?*Ka0w-lTacVi0rW!1uX03G44s5z&L7jRVU#zv7H?WY6DigGR+xSCmcl z7FG&CnU3bW0Ih|nS|2V-X%IM5#Upyj1S;pq#NtZ#s>*LrMW<9Nf@d6<^`oIu{y5Hs z#G(gr`wpy94`Rg#o|n&B9WUq-*knTq{BLfKv|O53ci6=y+)(yHrz$YFXO}E}QzIS@-8h%+YJ9Fk4Fb5BY)>Vicb8HV(-s#2Rd#L^XfA z$zPl|M6fly^DX7ZX~mIJp`73cQJ=CGhdyk{f&K@WSW|2)8?9qK7oTggJfny*-$5;D z?=cdExAl%LiAcD`;ElFf3z0qddRK$DPPq5>0C_#Su6p#M_twH0Xz{nZ^k^GICDo$4 znqF0LJ%Yi#2YhitKap>gn6G=GCW9ubdRkqPw0T~Vq689B4&)}B0Gr=vlTo6&>K`1` zh}umHFtKeMOZUf-DNs{lFWxSqmz7b!GFWbiF*;_nncV92v#8bO!`!)0RV z<@>GsLPXJD3{F&qVXa1D-3U1AFFWU`VimDG=*=YV^`?d%C*5bo3g1byaeE--h8wif zss|fctL{$O?GO0W3t3UYlK7dlF~e*T0X1lGueRSxvwTzY=855OYc};&mh4LX6W6G? zg>c-HX=^S;ps@4|wC0GqkThFHYnENuJ z!i_D^TFkKHy^6PYX$&39)9ngKUvWv=8sQWuOw?ass*Vm_1Kd?Z zfSsFo_h>nvrb$z$>fh}bugl}%H)>xVbqx>CszrMYJ=Iu4CFbiSVsGW$3~I}{1cz1O zidV~&Tfe46PiE029Ej`mx7}f#npKg^WtZ`R9OSyB#a*OyzBy#jLZfWQrazjYs~27o z(I^>SJds1h2$a{$64tAa7gN^6076UF=XIu7mHSZLfy7l1(=Kq6IgZ+insWl?dYV40 zCo{?Bm@JnzIxd`>aqa5A`RPMI#=HWO2MsNO%p^wVU6kZ|1ve9CgeL}O&vBDxkM<^& z@iUVpmRqt>_|0G=s-q^qA%Ru&*KdQ2)gE&(R4I%;s0^Z4QMqCv27WAM0rb0MIDjLl zxaQGe7v6`u80v!|7|@y9xR5v)4T-Y?ByqHvS+0<-_{d<0j_$*nVkE{i#L)__+6}mk zA-!u#iSU^opsVHRmzObQ){0iD))B6ii9+ zMHWrU=E3v~xf5p${4XDo06g|VPDO#x4^J%T)N7EnG8Lkd-CbNy&veJ9^-j|gkvxEb z67Wnp${rfA3kL1ydi!Ei00A}L`uD^diNP|yf))jrbWdjag6iU%-%l25VYcCBUn;z9A=QJ zO%JU{q!%8!_?E3le)qH}T#B%c;4L<^yvzb`JQP97%7d>sQ~4H_@==C3Bs6261SZCi zjfP4HPO9xB+vY_(1GHuvo^Y@5<0?HjyOt@l=oi>(l(vv)->0%(e{p(uzf0z_!(lk# zLtT2wDY9Z!5OwO_St1JhFr~h1O&Ee&v#^Q@9Oa=BQ%+xEmRfS)=F8iSZh%J3`^0l& zf^HMF8?G^R{PDqkvo=IJpye-H^A&5lz3 zQRUoCv8};t;XZG(sziM;Vo8$yaa`jW(tM9Ro%}M$Ge7C}`}tCS$Tp_TYuV~eqEH-~ zh+mxJRX9>g8lXoFQxJA5C;=MpJnVg7I=JR$`GVs&L)B&!n}3yS_-LA)JtI1~Mk^B3 z>cSvkmkaX7_V`BMX*MHo&ghyoC;x+_#{PNVSbaKtr;9#d8;B&b!-x=IUL|ADSFm-# zP)>vYt8P7ee<_pR**ip?d*C2hegJV8OChzEVXkEL2~dYCX{U%Vw-It1Mda`ehVnKr zzF5-xqDkyTg`zU)g3^T?ssemckvpbI!SZ^yK8GoH!U#Jch2I%48`$qg~?r+GRG!cB)IB?e@+&n8*0ltZz z1_XO3sr^RsVP`>F*3?znd%oz2ToKsc7u|;Lf`;N14MVNkPLW@Awl$y(HdW--%(K)y zT5e2-ij~?1eShDn3xAYSbddZWHeZ^{b|O`dWB|N2&s0gtn7adSOln`LJ&$=we%^;+GZX{pl(Muf5&n1ZCZbeNXC;G-)D>W=5}ThW#kV zO$mhejnB;Dz3o=KhgMQ5;~0ah_(RJlnbJ5n4t7aVk9I=VZT~y+r=EZM^n<3O!|6)* zq#(d@w-COz>amvO4|y_{`DbUX@@(wAy}DF0sr=;p&#?5Ki?~Obr^LDO>T<`z$Eq`= zl>t=z!5r<{d?dx`njiR+L<{P8Vt$riaIx(Xlpfh7Dh>kuN85Ria=MV;BYfa%#fUzV zjT?Udmf*lKig-P~Z~5XAfLYN|)-sF__=EzCg1;r+OW(8*IctX~EAvl{!51xs2{y?; zJ#`G_b_tVG>4?Uy*$1R)u6d3|OcDz%H-TuWjl4x<#|za;hkUR7LYY)5b(yUh#O z`8Go?jM^O}wm&O!dh_v!Pnge-6h(Z%Hv3S)^~{qkm|Zx*XESjnxs4${;3rzZHluE7 z8*yVC-7u|6cLU$}(<0#Zd`+C#e0n;M&qqF}!>vt@XnpIhYuhYHU?a=hLN3hCrMocD zlG4uwg0#ZvtTivf;=_w{NpDR${Uscrzd*t}aOT4=l2Sb57@MRQzg=eeWLLKc>r?Py z(_GyQg}FFvI7df1XNBH7(zIEIAZlF(!96H}Yj(BwH06(0Ub#pX&P$8%Qu&A>2}$|L zOH;SjY5#dl?tN0lXEfPx9-E4pjVE{Dp+gBMw3*#rMY4$2*}<~9C_2vnpW{DPc zq0=PsO_=&w_<)m7-h(V#C|-t~AEKnkrHR3x)o$j?lxu49?Cch;dR2@0-R@0^fHrSb zJz}s%wPixwk`$HL^Jic#ixeN9$Is>WCLbK$&j#=)gAHxSZxh- z=G=~g-OBfOh1V{+l96#7Kg{_JC~WO?>E&LI>-xD{jgKN{!{B2W&{bHujjg~o$~6Pw8eCaTTuw&o#z zm&ax?ESw@S22ym?RJexF;R3fi3I-xLx>X8rl?_Dq55)XxIQJhR~=p z(s;aPLg9o0hG9=DDCbgUrM1F6Kk`5giaGM0b=*%fCo6{J#E4-*CU z$#@aD%}MQ4=~KOzD!r&gyjoKH7_2_(LEa>>Dvfm86Y{@0_WpKe~xV8qKm_N=po zH1K5nj^{Nsu!ROa83Y2k=7VsYiX zttP#`Q`e*fdU(DxDU0WMrIx}u2U3u1p%iVzxHO0RLPRS8uIUoe-frBN1L1t{$W(~u zm~hg*iW~Y0)%k{{Y`#)?xeq~4AIl|*^E_b``RhTX_mKlpW8TKPI#q^N^tffykTSDVWQ&tTr_4Cgs%OlK! zk~%1d?je`!>u84EZsCOl3v-!`Ie8zb6>UZ36yb~(2s)@4qb>7YMVIx$?8Kt5(IBQE zNpZzpIoJxsZ)`Cg=#TLUve+c~_sCUGtSi_r`t*N=+)TdmePZ$>zaXATE_yu_nI+QyrGpCPgp>GMx%!Pzb&_ZeIUcbnmb;c2G*ui^~9!}x;0Iu<|+K;|A>rCz(> zY16>4LaL!QE;4biyws;j!Mwkugwfj2NYTG#FGf1$LlUw84?h~BWv7wF zq3ey$T>VJ=T(R`_SE`B`ysk|R?KjZxI^?P|E*S^mo=_Rx}&RSjJC-UisEd+X>bJoAPc63Q*x3j_L|^$kDH&O@Nxs_oBBR6FGG`HYwM-jj+9zz`@>X=$3F!z^@Fz4(SSBOv`M#*oUyW_2Q4 zXOmcFhao=7iO_@Btjx_ZegCZP%@5?2JA!f@yERG7(G)T!6?`gv_wegg6t>WI7etPW z`lVbXkXJ>Is5!icSMYnUI&}3x)9SlhL1N!04M7x_zgG1&Mue@*@As;lN|i7xz$%7o z0FP&y6+bDJUAa9O+A0<`t)&VohGyAq2^UZ;*}S|XB1J^gLT`X3nj!(HGNC6#U8Psx_i9K7rTs@JNex@dDqTud7&HVi#$2T8rsv z+6=YE>%9%~M~|Xnpona~*WBXRxK@I=VdwR*JREw`WleNK1d3RzM>aktK*qbG-tH$8 z=;-qssQzM!QljQgRRZ%B4_SC3zICkBJ^lsulF&(?2VV+_E4t-MD)-NCMy(B>EV7nL zK@K|KRkM7;@rG1na=C2KAz~I&KIbv!*U(_F_yg=HRqfZtdU6jsSQfdIEYry7t4!vh zi}~GdqU9$Q(mobnL^($y04gC0&O!T;0uSk5VJgn9gzGEG3+g3SXP3{ih@ev}eHce-Q2)`q zcs~&jQ-bhCXHs0^q{aYA5s^4ue*f8du8WcITH*dC$HMq=l{$9NVQ3MFRJc?$c+z9w zjRS`zk)?7XalYz76LL%hbxR!#XU0;528SEdObZyU4f#GAmR^6}lw_Gct$@WDJ?)_e zkYFvxgAr%ScUphL-?yVv9(7n(kE=D%GEKgQ1A4V=QcE<_qGeMgZ%SCm?Ty9#+swPsr%!chHpMh~b z{|H^Se~lt6FSaV}lC(v>F*pPZt$x37ux>IdgwywdfcXW!$S9v9xottlPr&4)QyrtV{um#4uqc-lXUNSnL2+@5&i!tyUWjjncZ2f=Eq95C0o`x(y^uU=lkBrBR41Scf;o#inm6%M(vS^4W{iy zlFOfQt)$<9v*WB3x9lRK9CXv$^|qBy`0jZ&y7*n^xKAg3k%%1tec!*_?o0;6M}t5$EGW~L6Khu;F)ltWbr3O_Tt#cT?0T)|M6EaF$t0<6S9pNGHtEY zQTm#?tsnlR5(Ie_h96z@^fTD^a1)zc1=4AHo$=tn0gUQ*cae6@62C}+{;BLtvRE$@ zvm-G18bmlm#X%0h7(%obED6ON7xM)%Or+;WVPy6aiD5hLC)3LnTvDp}77~mBG~7p+ zD8I?bexqh}nCd23K&Z|#tAhP7?B-xNnQe!J-ZPe~{B_QqeZiaQPjqv`NY~QFYN_d` zIt%~>n{eu;%79)+sB`I+9*0!Qe5`Hr7SA!@W8Y1zsreotWLvf zieTHSe8rR;(bsMDErRz&%{~&eLz?9p?}&Z|pDW}&Yl9!XLzR%63w<>5V^Bn!0?MC* zsO{g5U@qW5JA7m$Dep8*N*#5hS(DQco;~M>B~7gy&s;ye_~jcoth5fQX_XCQR_DpW zMt2!L>zK)-+BX#>X|kltowwmP`0BSsgEk%}%WR}_^STD%B5e%vU*8!%#@pA^))Dc& z&Ky&T#nJ@mpxo=*!CdPy!emu(y;%`ij_x>;k*g5_D||fZS$<5oAT_xbza#wjFrLB~ zgqMy^}NdHb}ow=2W(-mRJMLkPeX+6yGQG;r{6A7lA&UA2uUcOjD|3u=!mMl z3zzGbT(gwt?W9kQ$Ej}1beH*l@(UI04>1*Z(E0-qve~D=EbEKH(p+00ruFdf?1nT`m3n*L6ezs zDxMlA=s^+Eoc3Hl!!zCr=XJ+UhnSJ?WGrk7eERX&m2cJ%3QN)P_ zAR}SBg)wb=c#2jQL%NcX@%U}(49FFU#z|CZ5FldZ-E60mX2(PioM7w4VJUs>u3vBn zq4P_!@sZ~J?iVA^bF_&pJ1)jU#LlXn(Hw^LAjub*=i8mx?z}(IRZMQQctKYD)#i!3 z`NJGtdJr!llXBek^w9IEqk2y@B&Zt?;I6Ek=%g0=lnrwCl3>$wB(O>Bk+4UOxo?36mG+sZdADrd(C5RbDL>pY^>$U*wjp9K9_oh-$E-C?c1VW-Y^nqf>huNJq5a zgdObx6uqFx2(~_gqP2=-+Vp2xOBn9k?#7F(-Kv(=MH}5N{7WXZB>owYDJ|)I_;V}t z1`}hViThsI3u(ZFz%I8!8Rq@`#uV;sL$1>H-G%z5XFA-}&hf|dEL|kVtgJZ$$ZMGp531%2a3lomH5H~GNJgM!Hau$eFr0zN2`VeHxooXDWQkhEDuJR^>@nyCU6m~y0=~8S@ zRuJRS-^t`9i+F|M*Pw zA6MRXC7ZS5Vcm5OahUMmewK3P_G8|HD!NvG&^wc91&{a`gWYSw=KIF@M7{L2#z)c8 zap~8T+fQ%%jyn7*xvc_B+dw_ZG=zfyNJRJ?hK7`%G zNq8oelfO9Y8d#DN6*m)4gWr$QOyJB2v$`M(ZEahnr~PJ>IH)Kld_HVy=An`sHdlqf z_)WmwdV{n6nw{P`hT{wLJUIu|uz_b^Kj#=9fyVd)# zluo4$cZ7sAbTAk)0^0&({kD?c4lOG3K;Bszf_Zy|>jwJ3j_Tw|Nw%Z|WV+~JY8eBk zk9>Ha%Vau8I(VG*_X_RRgNCN2*`a>2> zS&Ub?%JVLO%A;4cJBt|?PfYmJA!MK^FDW)jFgFO@I_jb8$Hp|Ygz{JPU!rTB1t+~l zt>V~8pP1+Sf=wJ-oIKZtj8!%@MwqlQJKf^=c(jWW5R9U)Ujvv%ykI2z4_+cn!c(f3 zKE!l)vhl7sJaY2Mf1CaHJ_#OVb?c^PD1MTz*Hc>ng~x`(@EJqi8W$OelKg^da3quG zeg7%xR8t%?m8_Rf~ae<}s6* z_ZEB&b&LS|8=Fr)6a=~ZG?8g?_`DUQe)ycXE;|w}^n*2EF7> zuaq{IjJjCb2Q%!~hLW_yDIan8H?DFlCamHIx*GFXr&nT6zAK4(uRjEjU1Y4H@GPii zp_`3e`VuNewf;C5@dkxuTnm%Y$4XZZK2ek=w37-AF(%=9(e?)cmtV)mI6pnWBd7)f zX2q^FFWaqx<-0wM4<<`Su<oL><1gdE;Sac{48NJY1^vL`xG~C*?eoTK?(k zf36LClxXJ-{%UUh0PuCNn2&e%{`JOQ7x>(kKuw!nGrb^L)luG=JXaan%N(yxfAwpA zq6G~5_|4hzOX=a~V9GyCWGd2GCrpg%Ue+I&NpaLsYCE|d`}zyxcqeEc`%@CUefnfA zx+Fs}(JasKam$5={biuMK~>#2k5MXU^E7L+w%T|6hlcgLg@z*2U5EZXOUVWP(5l2) zBBOtsz5-H%zc)_VkgC_DtEe`7;Trp=oaUN8%mg z&YUL!;!7?g~M-~1?aiB(^08uFR&BrcZ@BTP;`o#TI2>EFdS zO63(WWH3ue7IHX#!#XRH4k2z?egGx;axMHQisfwZB$`iqWhE32NkIL<*hsV1)UYUh z&%J%_C>t8*;V2;QiCc;ajOI9)Hh99(n~0cGe)@uO2$2J7VkVuD&kM2LJ6=dq~mv`Z=bh!KcSTi8g5JuNk5qdHX&43j=R6Td<)x9 z;I12n2-~z3ep|5+Pk4I7OG=VITyziX=(SP()7AJFL;t0s_$TeiBCkhiTPAVG78aRm zOeEP6LL$busI!SI3_|sT%;m9h{y#6X$1(P*Ze}dVx@;|)ypVv^H-=DvFS6aphGr}g#`zs|a3rBEYTBw8*)Cxb&uSBEX# za~$kl*->-@Jq?bVG}7Eq?4A+#NSTP~N>o@JcbmRw-SGicy&z;^ z&m!_%x97?*0G?nNc^D#%WH^K6L7mAdKyB?n0cXtUkM)rsWVMIuC2{$s?MEGq4L4=o z)G*%o{`c4h$%W`n`H}rkM1e7W`^h$OSE(h}dBes*g!xp-+}8`VYjlEd%bq^pHBFTM zU?2?wc%dbV3jXtey9akvA$85pF@vNbp(bK~q|{O*&@n12ZcsNR_9adH!vN}pq1da4 zAd2EWCsBiyQV= zcUqk1!8@J|_~{?h{AKQ25y;jd+AA2;_(V;s!uT2sdJi68Q}{NADo)1R#VE1NL$wUG zjk$yjczaf>V@<5d;i#3Z43;#sR4}H?L3C`L&99@Ije2S2wclP7U_d;agxzn})Rv3c zo5cuvhcNP~H!N$mABJjln||1UCU0x$hzSn7kc+ppf~%#7nAd~a`AAf!tA~_u68Yku zOdbW`N(ng+pRx^VBv`<3gr zGzz^S@wT0Z5jdzuBy0Umf?|uzyC|ts`la(pB@Hfpk0@|VRKCW0XF1VL@NX-!7G(q~ zAQCHPyNo=zgcpucbgOO6L(J|d6oYT=DoZ9P(=}QHVbwv)gcOK|C zmvFe!_bRgAUthCicv`0lU{853=Egpq<8Jiz54ur0DCNyd86D4gD6OAmp^fbIX{GE4 zt~rI}W)UQkS5lee8{7frhGy8t?5$J)o`<>_N7GB8ATckLZyf#+yB)<#(P$cJ0pcgU zQi*h#!hExWYYx?PHLvNABvoms{k`dHGrthivR0IFaEP}ZzD%C9kO@z>^cce)Zp36X zrOm}Ws@vFEMftX4C@Crb+|W?!t!rklB2t4z1-!F*n288HOl+KaQ?hn3saHb-FQJe( z1b0zIif$JWh?isyL_t$sdxV-@u{^=}>l=!NhQk;zUV^a~5w7Bs=lmDXblliZ9^B!tOt0~_eS;TsFu_d0thWU%Gy6kEjHhL| zvnBdaKa}HgRd=b=A%h}_F{WJ~cs^Vplepr3gKSZjQOGn`ECAF%eUf#~1ayD}aT6#av^6k)x#0d7We~yCU!YQ$~NwQ+D1*@xhU^%5d z@D9|(TJO%kO4)6jcOTP`T03;<`!B`(sS{AOm9Cd7LYthO9r3G9k9WN)z$GS?Exr*0 z{a?+$`By?I9)k5f>62+yVX(ZzP|cLk8a;127Gz&-wyVh$#svc;wHT+oz^mfc%8(ZI z%r748f;UG10prQJ(!L8lAaRapO&s;hU86QtPvPBxT<@QQbzT=IL#o4G;5h*L;l!=v z5ixodu43uYfTTP6U8lWh+GA6q1LUFkxUm68WgN*+roqr*lOb;7jxhxSbXHpKT!~Nm z032x`_FtErW$ifK$C1~IhB6sm80RZE6RGJ)x>!XA=Rph$Si+Jzkl#m_VZ~Dc+DUG+ zHTF|Nfy`up`WDnwC1-8{QfGW246L!d)n&cjE+9cySn(wb65q`42rh{xh)ieZp|(={ zXK6|N`<&)v!BsS2+-vR1jDYt*q=eIOVSdaH*5pmR9BLboD;CtfOn$^M+4^;oWhGwt zXtzeZml)D|;=>=QKz+KF6Ila=8X=6(d};(I0Sv^Gk{i$%m=BOC*bpp_^4gQI?VN-$;8m42i_9 zsgOf?C5EIP_ePLTkz9MoMwsZ+aZL0J@O7Y&I1t!+&5POgfO1YpSZkySwBL%^p1dk_ zH+%Y*9;ZEP#NRQABl*DP+Xe zueHNQ+e_TE=;<934HLdtThfMTKCgekf)WGeS2W|I-^4(sWwB*(nLNvyf!xKO`MKx*kWQ`;?FeXP2#LYARiK`Qb|#IGgv zXN!hGCvB*^C-PV|NQkovZ%O2~yOI1kh_#r@;vP$b5AZEVBDJg9lqSuKmU21YmVq zM+W^-jyi2GP5~bRZt`?QArq<_>QmWNDu^336_&yI)CF zjIJiJbh$R+`3Jg8?YUOA`aq61VngxoAep5y5o^<##h-z)>6Au^#qpXfCFP*C=`FXW zpunBRAAtdfcb2TaRfo5lUbi!jc-MgFj0BEgF-D^C%#-#7)1RWvvSrdm5w``Ezlzxy zX{bW(wkoaoU54SutD*TFV&OZ%6LlK;7Rmh7O(tVcX5tF#z*}jDt{50+6%<7WKWVzW zk5GP0hmY!Xdu9g6dNNGxS6IozmVmM2r32c1FXClcAaL!Wr+xY!j0UH;hQ=2j8$JSu z+f#uLKWpgPE~G6?9m@QIol#@9gwrr%j9asxrokQ3%653E!D(-KSXGbHV!m&`J<6g> zSJrJYaM{U7?gjGYt8eCAvwh3bbxJL;z|wn&CzFtkX71Vu`!0wI^-&3?3h$EAA6wyqR*pjqN3T&M1 zjj^ZA5RFYC(4D{$)~c-~UF8h~2;qy^&i>$fAAN0!C1exJV)1W=&vnk246F2v^dUqf zj~6&DqWE$*9DCB#yzObN(EK}+%roCpCh{P zkBj(UssyahO|ZAqZ8yV)c{o6~l4oj{rLsz88qj8pQPe4gA*J~Z=b|(Khd4dd$jAJf zNj`b)M%QoabnTvaW32>ZduHc_nQ>x8%|%`axDuZ(ACH8#tS2E|Vk^o7O(i~%l~0&r|5$;wajbCXjL7bV)!9KG(Z=4K~(TJE|1;g+Jc$C0$b zV`6>ZNPp+j&o#;SpRqn35G!ZzPZi}$9}h4?l4w{39izqHm&YYn<4gUFQgfMesX3ly9_W4h$U02-{o-cxZy8e~TBTYSAT@ zzAv-zambM~yaOq!l2YxHalj!mjA#=0r546JY%fDvXS%`pQ zYT-kQ+ZFG9<`=2?auLb~qAJ@<6Kpw(vbrq3k3b_$qq^=VbpFffC@c1_1=nR|LT5$? zK0S+i=(BXFPv)Y;1Tm=wP$WyF0T93K&#>EN9nV++Sm3^{b!hq-M6rrU= zyAIcIT3=TxLpcfx9tejZlV&3(4+RvU_rY?PHtLlE^`=*L6ix^d*3;gi44h3IO_{U0 zeIZ!jRwW_2>P%87W;0gIf}tj((fdEdX@$##gKIURkMO}s9B3Q|@=qo;x}&;bBM2*} z!|Ubt159zq4CZ~lLpKY2VuLd3?Jmj}X7EGSoDdT@5Qnr&sE)>2J9G)_d1eQ!6!9^H zc+7Rqdl&nM0(Q({w9mw3M%z`e)`Un;n z05OiRPbv_i1&v)otfc5|sqGB6tpF`LetjUL%CjdJyX-#kk+l9vdX8N0I|>ysvUT)? zDFg2G8C<5MN}ytyh@RoLnnD&H;Pccd_3`N^-?oi^5nG((94GkvU+wmZU2=+r0mTD0&xKM5DV?G=Mv^4 zId86Q{gqVVV=$)9rC$yucuf-lw6%-`xkJ1d9Yaf3x^L_g`I;(EoxQ`+1a0rEAzyT1 z_wC(h8o8Ry@Q}P&?gtV+?y+?{5J9MsJR-Y*_&4~g#~IIDHv7`WUg-(F! zaRZN{xc(fmw#pSng9&(|*E4K)Vlx4uIRgxuu}%96efpneUEX3V^6L1)`m5D8wmnfo zNf6D?P#8$Z8Z0Yl@*;gJ4;j^HD%ibKXdj^Njxzf%{L3P^6wd=?52ttG{_uq;eH8gD zkE${}(d?^DMQQ`Mk?41KGMM84EnN(B=$k1b!#H8AvWt_iS}jNF>~A5wwlemzN*72+ z>I{tYpf^ltB2Hsl>!Q?DFf4-jqPp@_?>2e2lK%GFh5mhB2uu3AxH+b(Z^|2>%|Dlw z!$ITM8J-BfBKF>@TQ#T9s*bi)qks4K5_LY=Z_q;xYulc*k)fRsFNRG3YsK3NoDg=d z7fN$0#>J#lzrb6X9jL>TNPZ^B2uoe-amWQH4OFhgGcZs}sCIezH`}`s$MWl(x*lZK z=Hr!tWntyAn{7w=&3u^FSk# zzKtQ?w7lQGxe3|1wcmIHtMpgV&GjM7vRF^99X4697yP{pN{Y(V4Y%gt@7$w%3&dUt zjQd#9cXUUz&q-q!&4GW;WOR(@xY!Q&@k&B&k>EB4U@T!OO48R#o;8a^fkvYt%>`hzKLgvl0dizhts z+AUJQ&cZV?a~JS64v-AU6l95qSm~`Jj)mfpG3!M$Yjz7X`w`Q3GJu;ws%Hy4(H@KF zXOPi7M}uz%M1CPKu>^nJwCMN_bQCjW@67)`}!T7>PTtsF_22I*9dFN_Wsc7QFjRIF56O&)M(& zGbLso=aTt?L%SZqc8wWj4y?RBqeYUcnlDw%m;4L609qOe)GpL=)&Jpajj);me4{Ob zvr5du1|1$)g3#{hng3WZ0&48NCOKk+#yOv`1e>+uX*$B!EYMaD)iU|W}{W7y?%{#s;w>LAiLur zqNiORxElGK+X=o|VW^Gh5aJZeI}f)*gi!QOxFL)kOpow8a|h2Iu9F0M!Ol^ZYk*nY zoQbT_pdq@Mu$WW&F~lnnS`Ki2CvH7j_%W_+^e@ndI0?HmDj4Kfq=kF?Y+ZocGHG>5QXSV30n_kUlyRG&Y?V@nM!C!HCZ2^A(T37IfWD>9m6$u& z;LcXeY+8LFVv{QLAOnRL=^%@v}Pj3>GDiuv9Af^XGhtvXuM|iI_v!LsXg}jNB*heF_ z%x9^Q1u>zN`A0l56-_mJuz@5pMgL)DAuWaZL=8k%HJC* znj^w0fy?29J<1l&Rq_7}rXcUpv% z-~gd6yOmTUV#8Nm$Ay*l0IwwaHLK@|mcQtrCZxVv+`1AZBbk57x?a9q)t1!ECyC#= z(QfL<#@}UW(OrL*E+XnvURqhfaRpI>yxn|<^M#7(+&U!)PgBeluTis7rjx-WL(uZ| z_AJGB5GXqPepJ;hQU+%ajHM_gR`RLCn8qC_J{o?W3*g1u%d%YId>d<9d}(NDbt+qpdvm+?=d6%9HJUcE&ofVUXfJ;z|+?`n`=7r=DEz< z=KX6Mg%^(fW+?3!-mJO6lK;%y7AF`nz(DiVkxp8?0YP)_Xcb|N!;jO=j&Yrl zs$alV_B7oo6f0}V+Y=VC(@?ObR45?EA021b>>e}arBxR)a>8~r`bSOKaK}#BT=)e{ zOzd8v?axCOgNH{pfP@WqNg;_5O$-Ga1mbt}_|o*Ks_|lhI5;!3w$PsKhXj_(K0>Fb z$(w~$nF^7q@1jMWV!e`dGDDDK7z=@P+RfZ_2AK_zWhtjb7QmR!UsWNk2Cn^6ChCV( zSFDr|>GA*Vo+#QZ-#uF20*neoAWi=6acRvoH6SmEqxaVX4%#pXa|8>`J|Q24J1P{l zf;hieQOZ~FHU*KLDv2Ci0~4HUjB7R%YEfTUudLZp1~eR97i2*PPQ;E=h; zo`a1B{Cbc6gD+V8ijsMKN~bJYTFMh(=JDOMaxsM9_81`t>>U;-@ICY7UyjURED#3nI8zR()$!^XAY7UP}j5Z@r({*Er_pyq3>%$%|RH2 z7XEzm9Tv4#LUzdE&m(lWAIvvT_cJS8+WJ{fUD&1e5uj+-@Kcmgpj1*^D0nMqk3;UD z0Q9#)AGheY;KDapwbhk7q4fS3S^Eq9tPKgMW`n2?03(UGL~L@5l^^rR!TEbc4qjLW zsD~Y%pPHJ!)%w5@a=b+-<&yShf~P!#*4rELW6G{`BTY*8Cv>EPdKC^?YtP9LRxXN^h=jZPRI3M#pMojfEXlNF{ ze`f_RXBI3c{QQ&0%nALpLHwO`+eA)LG+apa6b%%2kXC!cch zeR(pc5T_;#ppAF=ee20fF0)GO?mS1Vhp3BFDh6ZUmW5Q>HMrS+FV8c(ugtA#pj;mvq~@V z%ILiT;+%48(eFvnCPMo1fk3vbM|c%1c&}I?V<<+mSmh(I>Sj(FHR|K4NEQCI+U8n* zCES^(65NiN~>*r z@cG7E(mlS8D|$3=tGB2~I)@+brnx&Pu^XxsZw?iJVOyyu`Lg`s)4PLdo}G701at&~ zaV6gLneGH=ke3IcNGkK3k~*WBD>0t5Ur7WIF&xfBnn~=6|4_$?B3_RZZqvc?Ie}Q* z2t{nU!5#LWS?rllT?iWFz=<{MMEFK_;DJTz_6i+*N3eLg)#{2ji9KYjGuvgCu`rQ8 zFqOs!Ub(~;Nct$%(zC7Ug;V{*8?ae*F@G|w6}VF!dj~n!IAjjoiGs@NO4(}blCpoM zDIs}uV*Qub!Ly@g0|R0VsZ#R2T^o)1V)WMftwADEHyz+(vlbi7)tYvu>HQ8?dIs=> zY5u(J1HIHGGvJ-f`m$Q1#!ILpK}E@dfiNC}Pa+GA)=@kfc!wR6+n|v42c)F<^y?AZ zaMO@A9m%iVCiBUo-uT{eJC&WV~p5fHIymd014#^f@HNG%wbyRmW<-hWW; zK%_F#7Jk$mK{tatq(6_4)x}zpliz_iVIRvg5AAQ*q%r<$r68&v*q z_PFifYyJzJL<;8wejW}bZ5l1_L24~Zp!0Ur%F7E|IGQDLIFXgBV5PQ{mOZ_O75n+u zT#;7CPj?KHCEG8lA1J$EYazOchCh~cKSnjFyFYx}y>#^;Dc>bD#HZV1)S{$*$ZY}p z202D!7I6np8+=dw4op;$7`kax9VCf66o6wUp;vEokQIAG)ED! zWpy+9w0R;eVw6BDH*!0a%BWy3qB;6lnQU@gZZZ8=A_`q>1n68vVr2RGm|ptS$vnXQ zaGDUQFiSpr!S{GO(5Yi6QNZ720c_dFpMtdz;p}{d&-`oIbb&})(O9>5c)exAf_$;G zX3D9qixM@#1B}1J!D2;J@r-T=5Dg%whR3f}(*4v?0*{J!ka#S|<8Syxl4mweYu#fG ze_Fp!7*N4p{`pY_;ohuuUCpj)cwn^ixpTAY!poYef6pO6+g?UM$6@yKG-i8vJ)WsR zy(8j<0C9|ZJmjYmv1ERHtqo80{^Pi(--hl(gn*B)H$c{KpiDxL7N=LbEwS3xO@ar# z!lEu3VG#csKf=XiOEO$_GUGV3ck#5H$TC;4G=xEO6w?~THCJIt#Vb#+v&)J+P!{xW zn`sJg2J=h^e!}^URgM=>Mc~amCBuhb(-ec&ClTSvwP;qel@exu=oYr)MGq^Bb@2ch zl1#jg1;m$uAW*b9i9-S?ob%Y71vl6@4~@jI>d305gHGbdMEvpNd3IsJ?PnoofFzY_ zP;|-9=5e5E0Yz+v?%9m#n)E7FF+Q=^M{DU8nuk_!0+$k(V!vl~xxKPT7hJVf(z-=- zabg6cD3Wx2cz-^Xjo-M(K^AlQ3>t*G3}S8^Ao`o4HSyz;!9T3p@Q;xnR?V2_O$G0d zw5AKAj{Nut`P|moXB7cOnv8J<4&r&tbY*R%;wYEaV0XpG*=1k(&35z=^);}p+p7=V zO!JnWMI=-SlAFtL*X0@PZGo~G&#%e4z;T!xp=U3!W+OpUrI%Ay1$4ElV%-OZp#}YT z;Mc#xnl`a%PYO#%br6d!{b5Yi`m@8+pJaUDSv&Fe8A})46d64rLL4$)&ItsW7;-}v zF2?Qo9U(YP6-Y*P zagQk=N(*Yb)-utECW((_N?6p)-3TY!bhg@SL7&>-P zL^58}Xht*>fmI5}Y*D3NU{u`)XgGed7-hf@RF@?Dy>eb00ouIyLCU+1YPlg|_g&Y* z*;$c_1-nf6tVLBK8Wb1I?yj^P*TS(3!4wM|`>lph+c7rm0BPD5r0ap*f7P9Tgke?}8QV<BMn%yzDxMqi3tsa|63kkS0Q^s4xnA#xbIb{r6g-Qe#>cZ`3T0#^bt$8aQ7C0zclF&I* z2ZZ6-rHe^NRQFwgiOpl8`jlyol%Ek)+UlRX1q_G}J#+=tiZCJK>zoxso7HP;)A>UM zKIf^PA*Y@f5X>ZQhydxHNf?DFE#}k95XMS>U0afLa!~{Z;Z(wteIpEM zCZ8aF2lgZ+eARFFiIAVES?)0LJvWE~Jl@?zhP!Z0^>+He`|QGie&0x``EXA5EE3?E^iQ?6bcHcunxq;$vp0;+y0fPjxv*B*jN<+&QhDQBbM&$hn!-Q;&SgPxW;+-F z_ialxH~$5I1Smprkicl1Z2kSQsbg222v2;$X?>h5Pxx_P*Z`}KipE?5b>U!psK)Zo zUW_nL6w!<_I4Z%GZt`lkysikg0ojIseeVCpY~QIol%o-r)mm6QB}2M3-|=f(w4qM& zh}G33LzJ6&jE$K>Ox;6mreVBeTb%1$`;cE1_e2=zj||VSqK*n(8gI{C&ViO@_v4nc zE`x9qY=Ce8mHQY>S*9g%(VQ8xs)R;?VGC4G2?;h_(m+dyqx~jT$C(}3Xa_f-z$&lF zr~FePg}KSOaezX~4Pyy&Qv<8f>k;_^(Jd4V-|K-{P432&!u(9|G52g`mhBgZYM(#i&}}>1gWM0bE$$VP`XAe&Z%6Skf&x6?I8~?2V2m z^gd!^dIlCV2$Q!_ThHn94V4Uo=)=Vy=@d%95kKxdGw%Bf%`E2}hn~*O+RCn#+MnWl zc9{ZXgxjFqE2yVD_+K&#=F?`Pih8YiX4+b7cpkr>iz)0+(yMKSoA}6n7Ur!rj^%NK z4LOQFOZjGeUf~W#VqSE|Mtj!@%_v--N4{&;59+ml1NpE-m&)qT9>aXvNjN=T+q|p* z9;jgIRSLRkQ6A`nKj-uwe^H7y@)Rpg=u6{UVKkQ3sgm0Ipdb4)E>_%`G%-8x0^(`e zMd!uL`MD^<{&pUb9uT#`51*tQNMXoZVwE*}1lRT7Op-cNX_zRXr#n)#E#t%mlkc~3 zaCMVeHabH#~kK%I^ru&K<$1~DwSGo^kW@4YNj{w0H)^2 z;GHBT{Y|eoY`67suS(qtN^VmVYp(ta`_t46AqGAY9W8D8g+DUpH%~a;x5os^75wVTdN z8fx(!xzzH&U?NBZP;WiC>lyAyh2fali84aq>nh=A;gxVanD_5v!9EZbh;)ZuW%{Z! zsMy$N;2w2l{|tXaKlp43a0rsO24=2z$v~FIx8kKwCu;`rhCfUs60?93g5=^!7VzJj zV56(VRqFVH6Z10cA8H>ntJfaqX1xv+mK26w(TpY%RaD$W_A`u<@4|{>_!IAqpa_aY z1VA@HjK`bPS@Ha6LOAf?`zeh&( zlRQ8kU51jYK}#zW#G?RdbI*CU_h9FU(qxn#!vC*`!o~XkLu-(dQc{)?{wEr!{GSL6 zcIN*@U@(9Gk7xk=KOPF__kXCx{{y0Ma{t%B_&*UC|AdtP0bp=`|37*L!vFXSvH#K* z|3NS$|I1*=Fv&8>{lhR6{>xz~0an&bs!XcZmjBcXH70c?4JOTh1cJ_gb&UTYD*ux= z`G098Or}hx#x9NyOs3W@rtbC@cIIA8rjB<1dGNnH4M#U))BjKmOy*4H|B+Uh{^29W zu2xLu&hEx`Oy*vucE)Wd1y%d_g6mnevU9q-49HReB&@T zkncNrR;G}k$9;CaB*iO0iBX!15ZNCzKR+TOqE3zJnofW@vJy$73|aa@*oAuMzy}dz`r0}9H2G412>%prX{ZnSK2V)+U{ucEi-Z6Q+LT*K));h#@vnSMCv{5?(121Z59svBc*Ae$-M6w^9#n+14=ltrmg2p6^vYn^U3sS@9oYaC!ZO)e8%wK6wS?VTcOqX*)t$;9?swu zv>%u*j{P4a7RVxCp+Q3V)h8L3P9}@B=pCh{V)6OtKJ!Cq!94)%Pf$W zpbMcV!8U;!jY|>`v_DX{cQ37fdr%n#1$(jVLLjt4&ij-$frgzdVGm&MZ9+1TA9N<@ zY5gxW2mpKru=b>-F(AO*yi&c#za6ltDRD6?@4q(w?eT|$V^$1Aj?YI4loU!QCSm*r z1)yL;fxUn7#t(&rb%C-20U{NFF#S#&O#ePpgT;?J-6jd5Irn^(GBgGPr@-w)f~ z%T|!ro&t${K~D{EGk6czPs3W;`O^SoV87rop=Sif!yoJsV$CKbkrN4sK2YrFyP^yU zEFiH@r+a?Vh3p+bhWL!X3TU*;zT6?Gd5V4?fNVF+{t{5ZwE=JZ=rRWDCj+5_=pTp2 z_F|#{H8u`J{`#O@59a%tWe$wTh7;XZ1$nx70X;W@+1%lxC4<^keYJlDj{*Y){1iVW zOoBlKx_T1Zr~_wCiQQ%zKk;E!-Oo!1&X*`L6E^^6HoHyJ(MO&C{>@cwLCzi1!hH0BaunQStU| zyi+(*5b=w{2A>OJ@6-Hlgmn|x833+{9XU}((al0SxRDzZ5uB@#PdY1qmObpQPi#$WJDJ#=*tTuk$-ya~jRn=R!aokB6Q6(YxbZ%7s`NgaWzt z*w@UgTw&VBPFp~`|Lf0gQ1Ym=jShIu#n!wR#AWp{pzCd)E1%md|B#npr>h$@@-M&0 z*E|x0=yDa+zRInnl}lOA$_6QUwa`R$M7`rM)0J;MobS|*ZdWi+7;YfzoA7&$a=9>? zBC>Q!trGGo+*R5mVEze7OxpplFc`&D3?Ve$^)^sn&;0Cn{pS1+_ zpZE~FQqlfTL*y}jK=~;T9>@#iYOMSBd*UvA^O6#A?@~|)C17GPLXAItBod>z@rT_x z)fa`rZDkhP+|wG`dTty~&Zop*MR$Rh4wffemq+9jS=OIv4C1+>@J5)`K5! zp`UMgzq9l$-`(Qpb&IbW7~}q6XS|pvvbedx=WMs%zx#WJG?w~0^q~%bcq%djuXn)%(WU-Q`xF#5^6Y9@=GwHIxQ%gju-`|X`tHeZJ% zMGtLzELf6B4F>8e86Uj z4HRmGQo0`C?7;eDRT_w$uqGWj7c(DcAkyP&178ukIkL?8RqmBQIhC@wv?j$rR{c)? z(uto|3o)cim}P;pvpD>YhE!3g^ro$~VK3q^SCT;({2P!kvlwMn#hB1UdkFVNvp)w> z*BAasp{hF}emn4>gsDY;kgV>2wVR03+wrz-T(y1NY?+$P_KeyI$&*7FEA#H`Ms*R| zJfOGey)1qyj9^O*>cAPBSm{Nn<2UBIz+SBK-aBF_S-wk}Qt=FJJ7D6umduq+W9)nq z2$fa{gw#x7`KZXST$w?<<-%VW{y73TMj(AF0vUP|3;@x)a{apbY!@b& zpEo_F2DuT=tr;mIkqxDHG^Xe(u*jsdg~~Tayc}aNfSdZDcjKwt$j@sFKf=)hILQrN z;Y8uU2fyzcViFEfgN6r*e!OXmn=FhTrJsK0vwaz+u_NRlq!spi(gA3zR+^B-{d~-v zESCB)hIw*Y8yI^wFI}f>6uQAu;3*A*w%+}OOy)&NEE9D{Jx;am*cO?$8eH1LmIP{= z>+p{r?-(*rP0Qjv2~~D>kMqXHHgFG6sI-<6+-KjCH2u=@VI+!4KvTwQRf2J8OL5Su zY29t5ISk(xQ2W~NEK{xiC5o#@w2}Lc{o8-=d`3BVo>M`5;fi(HUwH?d%;H-aD?eW4 zFqxgS`t{Z9zDV%({-r#17fdY`-|2pm*asB0SF7ex9Z~C~c+6=CgKqBpcB-Se3! z8&Ice5I?}bO6Yxl#q+e02Kh^@+iJGVb+3o7m%d?9MD{!G!Y;dk@xK(5a3PtP+hrc9 zxg6HDbRF7M6HLVenlX9^Kz5Gu8jXKMfA1XB`$v4=DSh{y7BgKC?E{{DIb za>=rpug??b3nqsvA0ni^ZScS;ua%?Wg0-CEpu9JG*KC0d2a2K2BDD^<(9Vko=SFqEje6A_W|XIM(_9qC6e0u|_$Pa_hk z2$s*S@?c?0YEZZp2Gla7DTvC@#GA3F!;xC_E%L_|PKHTcZh0HhGzA0s9l{fvNdq>y z=UJZh!%UU!>smWz&D}-@HVKI)-(^nyd~U$fDWHKzwJp2#BPy@CDN3i!y|fze zLB^8KDd$-Gt-ZP5&9Ush96HH*Bop)10`(8k(k6B`LTHi}u~N`Gevlw+g&Z5%kMD97 z%8@ONnl+-!i;<-ql#;|RhzJI0EhKIR>6&_k49s4ddD~HzCuaOi>xZBdeLDkXD@$gd zGn0;xIh9d!-Mx>Sgmv-FL%%vJIPaZ4iA2fl7IKOQu^p_ifs(a16^2Ja3O4Wiu#I@) zUEa4FT$|)VwQN7BHO37Z-t5-;TYj4^q~ho%xx<64^yR9WPy%vvQdkn>EN^)w_z3YqiVEzX6q!y1yM*fYU8#?L7xPk=-6ZH`qba? zW&c+{OXeLZG>=EYrjLFY-$n!=l6N|8-4bB7KwiVd-TFKv2_7Wro2W7IfW;p3#2AEm zviZsj7^&E?tjkKNtJFvr=5}q&;d+8#yjS9(<2fJvNNR$d+tH7*NseLc8;947FzL z02SQW0?WRRpg?srk@2>zp*N8HxlX2kF%_D??R8>cg;F^XDb_BUL? zDQAI8!~n_|UlwP=eBEtAHUs1|^{cA9mU9kME7hL~ zs@$9y7;%R90x>KG_~l|!@z*l*$~xgA<-{-Rw&F?M_n_bBm1K1}7g?zgL|zS+O;Wm( zsO*@d<_Qw>Oi(WFxc|2{x~P@<%-Vp z;!++{2o)ed&4;O7H2uBcuJ-&~R+apUJOSRYeS)03_XNf~JN6x$>b&yJnY z#Sge(N{D}&Y(a59Z$6Q6Ee^A!4l9|DweA|9$Y|&u!5Y6sYgF~Ir20ZfC_(|{&Eha~ zssc3lGdiS0RwnYiYM9#a*c2fO^o(SK0q`4HM{az9^?1^k>&>s@OZyvE&!7%h(t=E4 zE((kP$vrG#_r&Gkj$BVBb%j`g5*$l%0hD4}yp7}uaO{2XkEiUKcP7JI7YMNVEQH*_ zuZF0F(&T%8^q}i|oJfzq8;EcEoco(gX9$vw{5P_UFkbh(+Q3u$2OOy0EY7H8p82N7 zP1x<5@Vp)VM%G6HCcIz22dQgl4PZ}rAIn>In#(Q4ufuK|4)fR|P;^i|=gvoAzCc_i7oqi(1YN6w*wgfu^C^Oq{MHEB|TqP&UdP_VVcZv<^E z+4JCDKy?+*>y*2q**KGM9=A9;hir$4n!p?~`EnOyij#+U7lniGoug^BA%-z8!t)nf z)bvnyvNK6^FW@G5pEPSr%}Y6&(4wKT3Ek-@+S47R`}K5v(6dwi?BB*b)V&A%42>-G zmkb@y^4xYP1BWZmP=*gq537m<>dv;(Y*U}&U+9S~EnwW-YIRAD| z`y=CiKhSvG8< z3h%5Klm@udPs>aZ@p`)lL%*(luZV2nnoH6eQ|G?`u3xPU$JP55TNjp4O{!Iakg8Vj zZ-4K?fHO4XOv&Oe#@Px=dqSf5)kp)I&G;b@^TDzE@I0NF3C{~jMf>1p<#EoyvZSGw zvfi|s`8hT#_8#KOy{yM+?Gn&ynR?20!-c5ojpM=v%^hDm_D*53`S-tB=FxIV5rk8^ zj*PIS2I715anF0<#00X6GBw#lO4RFeWk~K}K6el6XNF^=RZN_@_t71>mA58z)eQe8 zWJykO4_)1N30)3jYSvcUhwrfN44`)}AyUzPDyv6`TZ#UBBOPsCi80}kv zhka|q1X3Ry>aXs&Wp+Xh6{i7ovD@`19?6?CeBH||TO#he;)DwJCgi(aCGoG6!SAWm zRcW=$JWWsvK2j;|yXgyzKKpQ_HfMyIN3FyUd4&=a@hgZAtV; z@OrQGKT7eWC|a8|V^9~z^zEC2PfMA0CZy!`@()i*2?llaO+}LFO#H$E-5Fv{J(w#J z^Sp+nwS#H4t4^ml9nVXAxD*q+rmfht9S)6)6tBR`6ccM_Qmv(V?r8)*A`DLMJGTOF9#iWtzXr#_Nuxze;Hn z_RWc~Y`py?b2^$5s@t?R3@d^DA;T@z#7u0zvb_jDb$khp=({B#{|ID%pup>k#aQ#* z_qT3w+`&bRgYnC-wgYH+J;aKU*#2i5Zy`zo!2Q0h%u_26b9oWxk@u=#<$0KqZuv*w zt;TtpQ#**n7RT-P=iMZrGGM@?B95#{P~`kye?1x2qDp(yXFsyo!nVn8m(M1qs2-VO z1!fW_9+9L#{&{Gq)jbx$``A4{L%JjYoz!9qjBCb#l|j1o((GMXE;y z9$LT~>oMTtB9^1;-%?OntK-dvYjv@?s-^7|$q3N7`T8@`;r&`S5b@den>{T^7n;i? z)P-TwU;=7&u248J90?e&sp)kj-105|W9O(z8gcN)EhmK$2h{DmHAV-!rxiFNt2{=J zD>>Ei-cSWw&1GF}iF(GnZaIr`EbEF)3Mn$}60M4dX&^OIJu+`6W9p*At?IvzcRRmb z6=6a7#U3~7+FNe=qll@OowkK2Ma{H2csW77P(`9Td9c~8qaBm)Y(MV6Sn>Kgu>eeN z1H^hvU*uLjWxuCZ&kdcbH+5VN-X?h(FoE|#f?1W>dOGEzwiQM*{>&N&jUsaZc?Aesb|k;ZEZB~XKo3jLu#!Bn_EC(hMJKn$ zb!My}gqJb~DI(3JH5{Xvd2Y~5(ZEb|faqP@_v0>~#(EFzPDhT>c;5bv6 zp}6o5*sAJn(c-pa-;`XzEE;2SX@=pmO0r`Y|3lQPwa|QPwH`m8&JEH6TXqRi6&5I3 zWu{_TKIe?oA1{c3;S#p4hh-`2=0>$r7}+l6Vb*df<7i_?bIGi!qtRFs3}P37i=x8; zHEt?##ncDgTA{m6{LdLLg^f6BYfi6&$rW{XeE%Vi?Vns5T9tYYV`hRe-ad)>oFl&G ziw?h%!BqJn8Wo+P617N`G^wXPgXUf{m&D3Iy=ey1TsCU%qS`*%%tn*WSwJNOJWgwYa&nr=b(4> zbt%-$euLToeqH^w=B;ivDzR6*Jv~u&)U&wpl@9x$;7cIF=8YobXWoMbx3ZC^0=WX9ALt-vpvGa7xqry&ON67ayY)!9I+t#`{6D2#y|=gH#(? zcP&L&4|WAO{EM~Kd)q`EtM@qX6oWeC3zMe%N({5Uf+AQbU-d56Omkf3Ia$GV6kyf& zxnnum)ue+0!^B)yo&!SG^ zW9ky&o9CrLn#n^6;#Z-Fc6uDKvakfz*}B4Fus%G+x~1@abx??|F8jJasyv$Kb9F9U z6M}0D@xAV(__RqZYt?SSQ*o}M_5jnMa1u_AlU&TQ*chf#Z%MlqHe;ndiY>{MDw>1> z{Ng2`r&ovsf%Sph-w9@}aFr%&HI83<29~qG9GTWY;JPNE1Y5yVZ`2xfh=qA0HkkhX zB2IPKt4PlG?MmM?DINIDZH+4>se`99Exas$3J)R& z$k1arVGpxCFEH=OHr_{dG`=T@@xi3~eJ@6vM$ z4}pRe?%d8w^(2o;PfPwi&w>`I&BggHwc2SuK8eIOf9jTx+_(j$$9r=MWm*xJW##1x zSAFKYCM#m_*!^Zjx_lPiasr81IHa zk#Y@v0SVvg2Mz)m*cs-w;8i+0nV2-z4H#_+A2Q+HA;d1iwP??CR209YB4TqiVMpDci(`?5TSUFc%p2K0USSK^km+>2>JeCqfx&BGC2y zoRGBqN&2V~9Mm0R-wwCU7FD6r%4&=R@|%bPj6c|xjdfQhdSGb&6oKbxgWU(;yi4YZ zF98D-oKvm;!6Qy-Q*M*3fy#r`p>OA&n3gGN5ux~qn_eAeJy#J}l)!?H0tqyQQ~Xty z##a>9G#{)(y|pMAskD@LbC_j2&I;_!aCsAMV(E=$LCP=8hDuAhn{>m7dM%993Dt!RfEGzXHa(J$eVD`gZp%A&^oOreXSnQ0U_S=7Fs98> zIPTV(Dd5;{83oVa}~PHOo5&|M0s+9+Km@wv>{E0l%?IkmFp{FA$B z#2$XjO>LCVQ>?iFIjwSHnWR}26eJkMF>;7&IR#D7oz;SZ=)@}!Zn+%J(wZ+vk}Y`n z+cGhWo`t{0>kymJxFO9MOoQ%tCSyscDur2dVGLNU|Ic8Zz zwUA0D-8h7S1HfHJ0JOJXt~U@sDtjx%P;C&eY{AncKxehzQ;*$bx{=@pdCs%9aQu8m z@p=fo*o3oHme=N6>5oj$4-zYjSCTXL>-#KCZd7U<;4VDu2p;{A&VVFXY?&7omLHvc z+Q)$`GA|a%S6mO->=+)r8XR|z<`37Kx1jtLsHn8>`r>V-kF%>Ne#ut>Q0dX*p8}1H zsof#LLpA0_wJkWXoxj0=`iWFQ&R(b;y!sB6MZc*@QY+^Icr8axP|cogT9iGmL%b(n zmo+<4+|kaA$T{(m=PkBmi^M&qdnFdeZh^9p{yUyMZxxVbs_;SRZ_QIZHER*!Ob?Hf zl(-aarQ{grt(k+`CAviiA=V+Gl6vD~W)Fko|9VRuND6Cj>78GobHQOb{9yKvK%v2v z5WslIr3d{?U>h)3hEu>bU|DUp5-Ba`{{2nfbM)V%5C*5Cv_k4tz7;zxXq9PKGa`U* zFSFVp6k`uT7lz1^mCTb2#j-}TdavUwif=3@Wj892sFoLBpI+-Wo)r4~MLBNrcDD`0 zr2fEjJAhDp4G{*pTB<76TAFv!f3GP`+|Dz5w4V6<=bjN= z_moxwsErLGmFmJ7A(psyJ+*pmXU^G%a5SYyGTMnCPjNeaRJpKfF3NIcXRA+OoOh$? zH_5DI+^y4(tuseqJRcu%)Hbs+zgFMED1H60-Q-@s%lQwM(xc8sPO}YDoy%AAx#!8k?-k~VN z=c~5ZIq@S{^&qSdD#*F(q+i!)sN|&Q$|C^_^REFkZFZ-vt*~{n&Ez%Lc~J;15#X~M z58@#99;kM96^)ka$ah(JlBPvKOzNSo(I48*DKf{6sx4}imp_weR$E2sr$y^Xl!&s6JWo%=`P6(EV5bIJHBSnH z*Def(O|^WI@bJ!g8Jm31ijtkI$f1rjU!Osurj=Vfe+S`MqoNopy}HRtM{BjsYY!RS z=xnnTL@ScKiSJ&AzXDj3qDg#TB%x?~rRPZ#IhL;{3Xdd=%0F>tzO@Q%8e$Z?A*#hX zC9XQW2Iiuve4l*co+ySy0;CUkneD<}H>!4v?gAc@#}e*C$X-)IlA=lsC6oBjpIbo9 z7cjBUh@!9(FPTT)9hCpplJochGGj__(hRF4o9Xbn^!Q-FB9;4k)l?5Er?K$~PRjUi zv2NjOxV`)CU6s6idJoEnvLzWS`cZk}oiU!%v#mJDVeAa1H9oBho+p|^KFm}Y8|7`} zgu;~{;d1aCjDA7zoH8~(>N|I;-3fsvUe6i!EFSh8SLHo_3E$4M>CtF7XBY$*ZA^bE zB}*$jF>WdvAr)QB-(?^Eh|S+Ga`R-21!}Dn7GTgO(HzV?3h4-FG7~Y9msK&YBSBN| zxk6LMAC%YE?k#up%9v%KL{7HdOMaeeZOtc{DyqpX69OwsB_A1|c*;Wt#3n(IutJ#Q z5$)NCC(?EkOoRgJT)G^k!(H?p>MZf+4rc^DomL0)v={^#)IB9oB^yz+XzowMrdQ?P zAIe7O;Z^Jb$eHn8o6@l^gSUg6Y&@ z4C^%%kKhNa?wr1r0Q^<$u0BD0iU*ti8iqxk19oOBce#sE(PlaEz6vSDp4}@WKVCb0 zWpcX}I<&Hk zlG6^zQhROrgJ2)M{MFG-xX1CG60e3#rFRnwveZ1!X=7cdh4Xv6p@Ey-HP_?WZ#L1y zzKHEn1}rOM&=IdP({hD`rb@4f)**ZolzBU*&gYWJt1(qywdh^0jpVt2`|LqmY#?@4 zWv}xa*h7En3hBbB3KhtVHdzt*Lgc!cp?8zS=uF;};JyOq`4yE$p4`9O3?@p>3UI4Qxz^8C8X3R5XPDi;uGWJ8o@Y=0yC@ zg#PCQAt5_=Vl8?A>wowtGcgw@=YRC*{}&zwS(_05FFnfk|J0)*|IDb;e?idy$vRCK ztr-7ziun&>+B5z$l>g}DKQ#G|Oa3<^3HU#WB-?-PMhZ|09OVZaGaRFgiLIHlISVl- z3m5Z$DM<(}05e-ctqKjO2~ru|8jW2h&{>kErqEf+&5c8X0iKSo-Px_#&$)zn0}(Yq z!p*I$a2EA8kMHUZc=h&m>A-DoF*9DUO^bo%*Ph1FsxQ&EMzMHT4WqmC->Z>wb z9?BB`Edc)p6_7g_i&7;o9f!7kWAB$7z#=dK4)GzZ`YEgr{vRJng?IGNM@D=m!61AP zSR+C7o)e7cW$Tx+{e}DIBj=5iRR^ZRV|pS^VF1uM^XB>lJ_2*IJNbLnIzBON z9yk-o`nvit(_dB}8q18`jA>sj^1OQ%D60WwNdsBm3@xaWIRjdtLUjEGPBe5m@_A%> zk;~*(`lR>o5{(V73qeH{-`kPU&yV30<31yA&4s>(Oc5QyukG#auVJsj1Y*GApr=DV z)I4qEph44iR7Z?=M$lcGNKDXv3r1+fdNmlwH}D&4E9;05_70AaFP>j(H(M}S326GT zP;Fpz0*m_8uly@S6T}t#&o{SOe+j|JV#F^TzH$2ce14j|Q!`3qqwl^Te>{EENe^Qm zTS>8eojlv+6q1jB-<}wqK-53j-2sE?*ayGvL0$m}#}4W_T-$>Yec6BV(|))Of93oInY?scyo2E5 zU4jLC+i`r~zW8mOyqNm$7<&s$b#w?Hs=s-ye>?tCd=LP+szMsWx;B34RR=`A>=8-` z`~i`GVo}cN;2*&>$^&)$*g^fbLsfTHBgFdD5(I|`|5mersdI60ehxjgXb7|qrS!ch z{O;Dt9U6GKA~VSqNIj@V+}quOOy%K9^U8Mu!i7hMLT^vJv_vEm$8O<5)zk|bFvODh z4Ly2;t1?mD>v4<@f$OJyn7jtIfS<#C5rg=^+DEs-z9{^3-iZ3Y>o2|F!2($(z68I4 zxo&TT-6=Gl=Yo2Mfb3ralSAKfzXD>7m%F#gR!;Qdu>M}&GCsSepdYreL(!lLoVl#5bm0nSS zZZlQ1yr+&fXT&+Ck!mqMJ4to23uyV9Ji&V!-=Mi-Uq9;(e%G|>M0Z;1Qbe`a(JZQG zrK zPF!vYv+=m`ab&vNu`;t>(!P=kz~RpDH{0Q^MFrmuDb`39{4hI9uq=s>X2@nut8eg=?_pyR!$5vk?k}51 zo{J9>4t3;#FxDu3Y`rs$i?|q1^E636vIOOqm`dn2QwA11k4RV^)Dc6OiwQ1XH0m*zJI~J;<%U@z^ER z^mqojH&OT1rgP;ZGR0qyAr07MUCh0x7s3%w+fu@*k4OP`Byl(81K3`q_}optai}}h z^$)mUxJP2I#m!SPt0Y}p>UV7J`l|g^O-uRA6Y2UvS2Q5bTF=%*0`kQ!|300}3I1{M$Et#-4k{)EXxyM%LY3wAhB>V{6sgr% zE`(JBXdd5+2h-F*0D0E8=(G9TI}=dy8a2Rabu|WhaI2gLLBbF$c`fG9a4#UA7)LQAM{6%rlGRF7_q7VrCxwsj# z4a=|vT2@Ll$+F-ttq|YtQ+RGZLAqTxd%$^A#z!JBkS=7~gYMvQq$?7xk4wLq#h+`O zu(5tycTlyHOE8XR?=7@>JK{_Pzr1l=X8FWR4am}~oADWjX#b^}tvl?Q_Os;(kzO4# zZ0phn;#qBT2DYSYu_F0`6-lWShyM!n7>H%Z;yJ#OWeJqbhR}{~CBfQt6rH^H?iWA$>CZg}{zG@4xiHtp+$d-P!e?v_m zeRlP>`&4#nyMa?G!krVfg=KZx7qZBs+p|enMn>t+cZGD|e&8cL5`AHsTOv}^>Fkg# zmB-?itZjCLaQfg06hqpZ$WGXE=)_R$POv?kd}p}a1CbI%$gn?n_YR~^SBZ-QsY0hB z)^?I2?wN5PTM&w70(E}KYS35gq<;7(0!y9&8f*#(QGg4q!N!RpC48DbY3b;1=}r)- zTE%y~GqClJs97mP%bc*m139Y+(i_tE2n}9KPyx-~V{}SoeM|?fq0$u6)G4p9AnfmL zfF7eCApdpe0e5yB@u|gUYmIqeabE_b>TH7!nPzfZ;wvj_ypLYy3GFd@U#IIe8N&da zM5gqmhZ{fB0+dy^vpNo_xQ^&J*%_W*3n!I#9v->*+@9Q0z%(noOr3PI*Wm%-B~@dG z|J{_@FPN0ISUE4`y`@cUQ5NP-Dk0O%Rqq)?It0=D2(0WIY*65c@W=T2VS9FZu14A~bHsqY66k{NqVWs`zXN>q=#k5zEIJ zR9LV$J7!jpCKj9eiq-ufQ|7hocJL2dp7U=+9TJ%>5zSKij4qYokd9nRg`N2RnZj^C zDB&o?(}6dKXK$_h4Rw{ne%}FYqF@Q1gzH1If1aPZkt~0#_>*#a`(4*5vH{b0rpn8o z6Zm~`9cY37e4@q)tP8{@yB4_H#Tl&t#UHwHElXn~8NFe^MgV~aY}AXoVcs|Xi;lNR zD0_+s{tl6I&C-Z@)|D@}y?BM@1%;fy-!En(tRh1&;U7L70fhaQ_ZLH9f_XWwh)_+U z?AK72hZK*sKn1Prz+{(S#usX&qHwXo)ZguFs}u~SSkA?k8RTr;indtn6XPpEUFb_# zu&Mh{*-iYFw@Zi|=lLrNPr6!TlLw98VPV%hxiz#1-QJ3q%$ zf}SCg(6CIfstZJYF`IM`TbfQmvEk;ulcwWR^8D2%YA2tm6twIG6#7^XmUY`&S=13b0&!CDh1?}p(>)>+P7gy@6Y5DmTMMG*pXc&SK4qAcd zX}&^UBTS*cg{&3E<@u2KQw&|8NWMr|$YvDP9B&v(9PAKe*TJ~5*gXLBR#oZ#R*rT^ zWl~}6)Nq=znaqaKZ6J5fM9x#;Yg^3yqg$QKUl}EA$a@%vSRu?O_JoRg8xvt@lfNo{ z^_v70GrIvanZlU@rf)qjtzam{2^~F*(&RTcq)1%Qae|v;9lV~KC+o%TF~5Y#ep4xa z=ozh@l3Qe#wAO^UaS9|T7J)slyyY$xR|bj;lfp&u6RbCEX)||)O{@fUzb;8x9_eVK>8yQq4Kj#*`d3^kIWABRzu7P2l^o1 zG;oqJsUzA$wgW{F$_!bt+HJ{0S}Le#m9I_Rl@2bYNCVz!XUOXoQO4xVZ@gpfJsYv? zR||Vdq|6?ekAJ}vP)Mmz&LE&db?dBj z8nKPc^$D0f`EivylL>kBpoJ7A|!-Xx%wZ`=U$sTseZ~`f00*2JYL6)lkt9C39eI`AN5& z4?|hOUHg1MXapuB-8Kik;PU-v4A*Xi5Mm`;zvElz&w?u8cc2OW{3!W+4&NDRS_|~! zF%m7-;*<`Vt?SVUh{48Iu90Y#{9Tc<{louiV#m*xOPV%Ykbr7Zy3IOI!Qo`O+1HW9BwLx7m)U+F!%$RtDLnL}vQ@XR%}3Zv;tq0tc^;oi@O1Tx ze%(U86PF&UzZ7!eJVU%a88s8TEuT(9AZLp>qmf-L+d68!{_TvV|}D6%J~zq zf;6rZ^v=l?vKLf_sr_Znq;3m;g88&oE+E){GLow;?q2J!gw)bhu{wEAx-m%k1doRW zmhnSjo5W&6{-&{2a_q+{u;;ZDia(j`X#Th+U9L7of~LNaNH6Qf{l++eRf2`43Le>?ch+6iRCS%# zx&_7icD+gYpsmkoPj*tImTx9%2zlKvTw;2-2ei@U{JNLSD!$pqvDAScd9~Tq-y)~YnVn^*r7T0)J06p9E zEJkOk3_buENLOGL551v8@XPm3iLm0oGiM8*sxY74Ahb9r4Gt zQ39obm{IG)h*n`r{(UmRV|@Bx-cK`0xwaynj=5l=b<{$EzpTUX*Z=mo2zr)pCI6yxxj*V}dumgW>Jh8w<^~C2nVfcH$~9@h z7f5XI*&(oX%Lo;nJLbBo7zzZhxK-WHWYi++b|s&*2sSGvxziM7

Z+qu6@DiEkYER~-aivG+1* zK`TixP-yqcHofEr&@|9UL8C6|&2b}*>LbbIt=H`{X~Lw*b+-^xgqQ7I1t6`7qlq=M z0en24+dAa}ZM(&!9BK^{{Hz^PJ~w60{OFyAq`@!!b;yhUy?@q6D$0ftc!GDcIjS=` zc3u#aPxt#gIeuH%&4S(CdH$xI81z#1+KpL9TyLuvnJo2?HwhM1xo)ttMQzYwKW_}U z`^Y~2Z6!(%ri(L!%U#J)!XVmEe%h3+1L1HJl!8vK5DcQXg_aCXM(FBQx{c5x@CCbOOuH?d8miD(vcjaZ1haaVbNcEsIOpg#FycKz9j7$)i&jd|&lOA`KwGh(*Qd$f` z;%Fsd-{X2TW&!?meowZwFKVs{F}Bh%G#_<*Gr>~yMai&PDNiSj-*AW$%hTy9>}K@8 zgmnY?!#*sIF-Sx|rGpi%JaX8&i@kn}&IQfG^fIo?>7`Z#s(?_Nwh)dq(rzrFaDhJ} z=4nm5SP-OEOFRwto3kq-nPSJRT{k-K2qGeQ#u!ye^p8YD?tJza{<0=3WmgU|7QRsO zUg##P1P`SRLGF4PI%?vCIsQ-0?HCi~G;=dq4#US4%`92JMFew3DQ-P`LfSd7s2#X; z0Er~3iA!b5-0uRe6(!-EkwD`5%~Hme z6f&KXaxSaKC>D0 z#G&vD+jhk>@4{~{F}tq4Y3_4kqvZy~7EDlA9v76}>G-t?ITY5mkh1AwZ#34yo`n|4 z_n29>HA(F6T#BVZx#JT^x@em-z3LY6M6-z#NdJIFnTkyAFjN+Msu*H`HO*-l?&-`( z5DHOmbTr$$>gq-_H$B~zz}{owgn~D~zlSp1Ny_BL?10tUh$Phf@XZENL!cb>`3WTP zvc)-ic%sPrj22cmM~y#uiKdx_GB4vQ}-dy#N&Ia}9nL5YRxiyPuuh9;GmM-qH+ ziG}?)-(*=5{($iy{m7ax@TJ2Hn4!xH0xV`{I$=S`IH+_&o zRrz*Td@^G1O1y|qyQ}0}$Wx=^{SFju^@*H@vjiV384=uCRFWuVz&|6`8#9PH#@xFa z9wO`+`4^}jel$wPFs5{FDT0Ow^=yxf!NDxkc{s?tE_^oO zE*e>rOX}pgx0HB3qNrlq&8}JbXv9l}FYHv*YPo&KHBshlV;TY)V^~lea1(07b|Gh) zy*3S6Rr>7%$q`@4+&5hvoS*>;kf4gV`SWHJaW^8Y3{T`t`JHnZ(_$;y{bR%R)k#KK z>#6OC@AC1F3>Df;=R06USqP+*E$w98g9=7@<734~T70g!L2NCCkg6jB#cvR_& zFJ|L!X5a&wkcuR=(c=ZJ+H*#3_;sh19M4z6S!~IDtCR^~>w8v1jS)!KH*8J_&#o0) z8-uw_<%rOw5-HJ#z2hENPi6l#l%Q4asKQr@wnzB!Atad9=rA&3gzJif43$StIo?4% zBwX?#zPP>2VtYPhhCu^%xgt6xP>A}a{(MooTz&>qCkIKmYj2F^F@RMr+W$ zo*`i@CvlVg&e}wRp#?I(BrZDeyD(^B&d;#QHYXl_l3$qVZ#4+o99 zL-W|BBGyag)dp%SK=U?9v)#hTC>yV=jBNqEL%r2isS@ZMoq22{F_bqBZ?f@Y8pWup zxH%`dTkV96ejO$wHXRXu!#&s#Tn~u)Y*2Cv^XW@ReP)7)X%zQ&YE@@1=lJ26)Xs80&~$s8!#9X(NY zLe$fP#RI7~#q{6v0ypZyW3#tj`>E(Nku3iRG?ELKjX@$wde;k9-P1RsM|MWluNRu> z5;Rj)7_e?_84~Yp$iZ6^tIG_Bh85r6z_cD-|m2 zyz+f2*uw@3vTItnTD^YVCJ*}C*?-e8fwzL$*(gd_mH+ff>kyQu`%mh5wUeU$;ZwgQ$kdYy7Wv+ixL~? zPizuq&Q-mAP6O!tH1ihd9)C~i(-6KDhjIUp%Dy@vs;zsQQfv?j0SS>tUF)0C z?rx5>gp>$~gc3@ZbhmVhbVzr1euG}Gg7^Nu_s&0hmiz4UthLu(d(XI^=OkBQM6$iI zOm4}*uG7SAL;a8@O3$JZpqIX03aqL0B2%5*<9NR+XAHjKk~lSeBw1`KPFLTC z_l9x3(n+IZ@tsfH^GMihUl*e88<8BcZ|X9rh@{#0Q+bS`@EJap!6&W?DgxduZn5Nd zMTch#@|R2sl2+dyK%LR84ILuOT-kTjKqUkM^(jm| zmFbVPGS5DmkAwPdrUw#h97^3bj(r{n|7licW~%WT-7Df(8_hH`=oKe`2<8k)E(*JM z!W8?aq`zvj< z9-(U*>MamUA?b{e2`8YC0?!u0i?7G1xj$S)LCiMK@aE|Mh*rw(7CC5-d6T3@%fG^j zwuhGJt6=}6chk)C?z^KEVF~%>s|qXQhc^pk?d?{89^y*8QgbKHe0)}3FUs>EwY{5f z6W@0^B9Kmsq~G2hFU%B|RP*G#X}TejwEE>;<>VJ>LtcGbls^1Mie$jV!Cv`WZEyFB zm-;Ovvb!@#o4s}Bub2v+u-?ZvYb-Ft-s+?5eUpfF&LtKytDpJ6gN!^wbO2JB7Y6z) zm9+j@i@UXJsIcVKCx5JcQR!%5tTgh@tjE|2Nq6B)V~Vi`_Qlj9u48z#589Uc-E1$i zwNO~+uZW=JRbT67aZK+4fSY!johlCZAH>|er#R-c>RsHfBFqgm1qVC%&t(#tG+|co zAMSpgV?L8zejD~p`BUF@N2ztUPI}S8*THS=1?XWhCdjU#{4PhDxEX~2zLMTe2^?z9 zNtSw24E#;5V*KQ{B_(`caik_9x$Nf3^gTmQ#ay8Bd2k;Ok|*9W02tm~PHqle)}9P9 zFY37v3Ik#}P+d9(8y=oy$XNS5b*W{bg525CLOHN z+}23nM(5Lv2DkD8os#g^9Uo4^Q5=eI6ddz7n?Iq-ZwYVNbPT#Jn_ezU)Km9zh#jf^ z{uFW(kE10I!V-P%vmGGB<%k^~x~GI=7`Ttbfiy?MX|`oL-a?6)HA$2bMY5knSku)c z602LJZST-V#%}RptCx&-g~Wp}v*b>xluM8gZ|?hGo83t)+YXuF3?RT&$j77LfLRVR ziY`{Wy+Ip6AQgN)Xkxu--&JQG_xQH=c-5h*a<$hs8lL&mNdVA}Mm3Bk{_%~j* zkLQF9-QSN%t>eg_^wU`Ugp@xHNV6$X(DDf;Yb{t$J`)J<5+FXv_?jis!a;xppkPBNk*HKD!_}Cn1jvi5{c0 zm~u3K9at1fq;)T)CvNN(qh`#u$)cx+OIQ+Lguo}%Y~kizAhXCSRhIHAGH%rKt*`su z&G0z$nU5cSjp4q@=;3*cfhZxeU9s|Y9E{y#EN!Di-|8|Z%h&L>av+mOJ}bMZg%OM3{=ulJQbaC>n ziqZ06*9Wia3knl@O9iG9hAj`=1KTo|HOzU^C~cn!H54Y5X1q~X>W_^SiH{YOwtJq` zb7u=u)q(Y;jgrEb9xPlI?D@V?`(=RB!$^H$wFzzh6hRUIG4DmFvDoR3Tb?E5G(WqX z_2%OEfrz$fdC#kx#Bs?I8{C?(( z{)c2BGXzS=2x0!8&wRm7b_v;PnHuSEnH&6mSZ6;u@bF3U#z{}#WC;(CIBUc5~M z&x;E%{RjUAxOt=%r7!$v_|5&_yr=sqmC;xy8 zUB&;)KSo$2|HZ!_Vvv$B&Bq@?j2B{xmRi<&=HJy3zyIwo4aE!b#9u;)zsKdS5iFS) znSTZbFBKLT3=?==SYZB(RHl#+zmT{vY~W>-{!J^Bj+u~}nE^xy27?(085yC!G9PyI z@lUBt0CuMGpF=|phULN!wM+=?#(xQpG_97UrL~3QkI-mYTU$8%2*!mDrr!4megE4J zBg|lSA#iDCWDX0JnVqTa6C+Dgr{8A@(^ZK`rXLcK#UX+4QICLsI2!t|WkN<+QjzE4 zWT=eNzvU5Zo-jk9uwXI4$^_$YW#S)$rDtRGKLqRFGs(zY-^kp^*6BC@|8W23@z1E$ z3V6H+U}aU;j}HdHWkI%%TtYz=v=e8#N(+J z(8Zu6GDt7gaScJz-T}dK8=>SHZ^<>jk`g#pRn@w4qOuZyI9+PC8U{G1`1AbRNJx#E z5mr{a)`%lR_3`_M186nc9k(ViF)?Qj=pPZT-mykhQQ?L&js&@cZf^&FjTDE&!!iNg znA_E$P;6My0x8@l?C$G()z^#Nx;Ujz2Gq8~Zy?pLzz-9WH+LZFA|52^Juge4Us(Uj z1bzr#wx_wEaSsnmCHi9u?u`voO9T}!!tQxghZlF7?`~AEa0&=vy!&>`^Mp_SG_VH# z;MfvwGf4f7h!n0NB>PLuB9Iw-uuM>=W3OC~;MoFDSu zBzTK=x0j;wBV>h@g90^CaiSnhpuWI9G;EUSit9$#?OAf zJ9#v{zy5mhQ=O?Qp}6|_`*Wv8PPc1HW_R!IRjZs8Z}(G06~iS&Rh&GJVm(oXGY8D^ z*`H5t*R5A?8!CIAXHOI438SiDJ>SrnWl!j<7T!BhL3|3J+@OMKW2Tj}Qeh!!9)@&_ zl^m32CUA_NcUhm)&zwul0=kFQw@v}7a0dtLqrR>!tZ(Pj#kSX3oK8C&<+E8Ybs+L9U)=0{@o)2Hna-O4bQy(~Fz1xdgZopSPGdDd0Q~A8-+v+vpX$q+YnH*Qk zZbzxDhd9|F@NmY^NNy0&w%ed%4V)ju`?U{m9%6W~i)>3^Ejam}xo9xIC=Bc%sBfyL zh0C?I`Lt8#ShZ}>fU@z;Jzf~MdxWF$4xBZ&s%F>Y=kxfda78rc4*}IoI1T`g{M2tz zf|wi$F8v($=52)Mk>^}p>>1~TT5#P*6AK}&9t`KtN8tz;2ttwJ3Qmz{uEDLI!6%5o zog=av*q@=e%0p1MP!3{;W(h)3;B1eP(c$2<&V9QKu6sM3y*eEYJ?5CS5x_t9VC_n) zJiB`sA2&`|T%CBn+?+KwHX091Bybo^AF`kMoV%`YzAGj)2|6U8`I`9t9`wE0fLt$n zJS`BsxuLb6z@LzWZQ2s%WNLD)?ZsH^=G^CYAqTPZfKsI=gYy*b#|s2FXx+RZs&W?r-@+w-A} zOru=s>3vF@dU!I-Iz`nxlxd-;w3yt6<+l7TjTy#^X^Zzrt}mp08C)l(JREylP^E=` z_VUa}`kv#4Gfv|;eo;oNQ&W7y=QwkCYmC5~HR#jw#g7)pTp}m8i@FIhsTN)Y6IU93 z=>6J|Hnk`p8(yULYN`fD8_=LkY#(+hn}*sht`y6+e z>D}_4+FFRNv{~4Ch5Q~GJ9I!-2wQNoSK7gFFZj^ zQA~C-_XeBpn4a;6-Wc`EU?;|1$SduzI;?g3I$;8Oq?3(0bc~q9LYXm)*2eR?vmZ@r zey_f5il~>heAV{`$Dq-2Sp*8UjBty0&lkQAd=Y5;FV?m3(E&75mfh|OA?8O~N9f8_ zzNkV=FormsyYTsBgcD#IdW6oOqQIv87WJjl9Ao@3X=i)P6VWA+014gIT+ZV2o^;)U zd~pLYBa5uh*LbW~nM)#rza{fO!F;m*K&L z4o@71^OG2clDkV=9VaMtSaBRK>5BsW4S`Z-%vm?YKUTdq3r8*hw5cQ|w4iHIk4&%4 ziua{;&&Z%Y9o3Ke0RQxLujm((p=b8Nh1QtBr^jgidz2etNt5^QhgxBO0tKyhK6DQK zgx$bBy$21$pMQ+8u;&}%oH*kX>lO*|^hKOFyzhD<)!$oDjByNRu^X_Gp?SpqQSf@z zLS>Tjxwp12ILTN;9oRe+zsW!4CvYu>cZ^tjX>cy|t7%D7e-#tEP+8wK?kD~+W}9q|)~n8Hu%3^knIbbU|DKaIcBjQ`f=(WOo5AQhA$ z6l#SSiAv<|KoTzZVV#QMPI%X;JkwOK{wD3P&4EDaVpewK4`}+$yTx5pwykxryIm*q%Hs=^p2Nidc*HS(y40yF#13I|bioOSc5<@5dvkiIOB8U}x$6|_dNapgZ7gB=^eC0qJRrqy zo4Xm%H8o)i25#g!I(J}k`8{f`rWUs2?;U!&1S(E@wAJj+Hn0*dg!@TNxnb#bvk@u( z3x?9DQ;3=V$F*cy>wK*A7p1ms(ww#;^oun$hi9Z7lKPvC?;7?^aEqx=Xp&Ud&Bte? zl&tBW;Y60tO6N47we+?&su*IcGRZPTpv%_^bV&H8a|2FpY;NaGWuP3v>J6Rgs)<(4 zoVlr7wC$v#*i-2?xG6lSo(UnV_t#y}1j^_z_VNyYSSg_t5st_F9>P2inR16`K~ss0 zG`R%!yZqc36di8DINALPo+{U7oX`;#P}kj$hLrP>AtG`4J%EqT z-mo=lHRn)ykr4RJa-7Q?rj_QdxA=6T$kXm-gx5pCuM-SYZ50}lDF^WxN63f7-p4Vd z4BaMFWt;x0gJKa^Dr2BzF|Veax5UkG7RE){D|-W=Ul%Fbv-cV;opT!V_i$6A9UV0+ zFHU2{&+An+|G2Nc+DY3F)_8_pN-0sTP)&C_b5vMjrEQNkx4 z-4Ca1&uD=f)yaHgFFt8%6Xx7XPa{#umLNf&dn0o2-3d^Qkk6l~gibUD?>OA|Eg-Qi zcgOSt?g%9|=f`T2nEH#@URx1=CUC8;%Vj=&dqN=bK`55yH&>47hx(K7y{EqQB+owG zC2z%SPSMis*MF3+j2YuV-g5Ikr&zKTJCS$};KlItl+DYl zHzWhE>DqS7p14UXcRM0!>s4fy9$IeO4d>{*h;LYxk{m~ymh3}p(~Zj3MNkqP zCMUaJL{dzNW)Npke`Ao2)s!!9iTbc>~(;;bM?@>{RBgB??W$NYm^0KYj~?Hvwl06sXsOSZV|DBFM7Cwzr( z4==T50Xv@~i{gp*BMRmmlsI<<`{|=+hf~vJnyp+D>Jb*u_J->$v}kD(tef8 z8*A%{cV=~9uPyC2rA5WxL<9D3d>PgvidgqtDU&}wc9(U6lLUy49ZQfDB2yY3%uBxw$mV8vc#Jdw6e~Y~_0wg+nn*$(8 zS$M0j{L$-;v+crW{Jp9cvo&`VYgKyjg2cJfn@r~R^0qIg_FT5RmG!e*c&5rtDQqQ~ z76_PGrxcS)-CO3Zw})H-7KHWZ);y{wWb9Utj+B(&3mn;UHz++CR~njJno8|1#6Mrw z-=>IVYtMO=Sw2sQZZ-dYcjUch*hfErbZwD|HG?0?bf~Kih4#dEmYN6^u#L1)Q?g(* z=h`ZW;x3Dzd7`#lQS&VP$@qx{r%>TD1`F{7&iTm&GSe(kJvWboT~EkOtU)%82VE^K z?)X9~NqMzQ^*SG8B45lojtEAzXbnWq&$r1>zVVCTd37+@7gK5+AnW)|F3lhWINB$T zkmNWd!R3)EnDc(Wz|$4&p&_6XL>+0|_?3+r{PCbC=AaXIYksqNPOK zk5xC*PL!}tWeRn#v@AE{Uis$}U`Mds?_+o6y%R(j) z!{fTB3&%sNZmSZ#^-{_`;CQ_geMrGt%lL%LQ)}tY?e}F|b`I(C?6%V1;H~di>1iVVl=W8}ufJhis}4^(+ox-&RCvR90 z>2@6US7&=>2&Omn=A{1<+V?1AXRm?M0 zTCJP!-HaYTj$%_?`?ib_o8D_7B~|*22WKKTnT?o4NBWhGyov!T!`lZtc<-mg@#U$e z4>xXbdsRUvoJEH_u-$^Iu?B=eU?&;M_h<&Hvfmz#E)_42dhRAq2k&eHLs8#8pkY_F z9Fb@js*$UXuIqX>n8~?W9mB6wD-Eb_Xw!AfJf*=E!F7m=U`4xGM1JpD2!h$B+_3S` z`>fLZac0);SL`!WpMBZb_j1bN@$jTL_=uAq!)F(l)evlpiTX-x_IdfVl?Ik=K9Vkb ztd$tA7agKN(x*G*Czmol0Stc#_$t`6U%^GMVECdf*#GO)IO1olNEOBaOnS^awCt)| zyHgWW+CiT)?~`{@MeD)6(K5U)aUJCq&;E$cTEvN|yxWV^T{<6MR&0;H`s>7M1@XOU$mqcn*WcLnHzeBvq+UGJl*4#X zAJdlB7!u+(`_9&SemD-hZ;l9Z&v%zc;wa-t2hlQQt?s1tZF}{6vZ>CHv-^^FSU%gR zpqO-Iv}oWn$yMcLlO)t<-%mk4w}in_fEsgyHj=m5CXhZbls+6&Y$ti0Wjf5PA-P@S zPCvE6Bc04;zku}F%%DvdpdSDJm)H>YFJ8w4Bd?zr%%_X(v(62_h8-^W$F-04WL?yO#8FweWco_ z;)X9@FlH{7tV}n}8h~?}ijNsM*6nbgSSyXQbB@6+-4iQkSl%3HZ~IFAsp>v`iLcTp zGovII!k0OpY6+e-kjyd;81~I0feQ$3e``M(Fei{g8Cm00R!;Xk7VzHA`j`Wk9cWql z;ek)dO@EGO*%&VO))0~bYzLH>1I;|wuLl|=cV|5ZGFVmb^*YB6ez0yjn%*l^vrkO* zF`uGbf4xz|$Z9usn=AvWB_oA!wiW4LHd5e3-m5V|jzT0yV`{~jO+GcUWdpo=ePnL2 zYk{iqaECnX;gs0T;N`>OD2-@3ZnZ8v(F7bY&S{{eQreGlejLzM3f`2y>zksl0 zWyH*C$8y^+PjkW!Y`;j#=OME(y{o@~ts(d#?Tq-NOL^kjDQ}EE!;u);5P5Gfmv+lt z3|d9!^CP+FV(}-ejusTq_GKa@B?-i_5=H?ox;|{Ht-z(4Z+&|!Hv?XMu+c+xM{MoU zPRl^|uBUqUHhdkq1t2fD;VziGp5^T9HWxUCioqj-f24A!z>(J>noOkr^bw&LC^01W zgSkzzrGY)7Kw=^AICdk3$Nif1oSt!p;h83Bdhm2gYSfE6svkb;q{KUULf=2KioAmy zY1;>`;+Y z4bjKspP4*(^OS0{+|wU=a!5kDk{pD2SS&r*LRRiWz!0O4`>N#nvT@iWpJdCmBueDG zI+_e7%W>CG{1tIPnLBhW#CUvG29R3{wjVBByjCB#!C-gVdy+-|CL45y_)&LXa7uR; zV%cJ}SlCA=)5LI}nJc2`oCUE&j&;7AIiMzxT89tP{lo)#{wla?p$oylI zyd~Xaji}I@F(HTIef6KCh9ae$X&c;v=uvi%#!GWE=z?j0Kn__o#QbPw6SnI-8)K)f zZT3 zs#+|ja9%UCa;PfxQS(nO;<#onYN9DJHv|kWJk4V7#Y`=8uNn$E&}7wtq?M&wZIw>8 ziW~;YqfzMrQKYOyD383Nzj3~0`*f%5x*bL@61I5L;|>{Wf5;59RkuV?p^k;CM#@7c z0Ppb(*38{qcS>trY~NEVk0fP!zqzq%t;KmVX!7B;P+<);Xx)Kou6!pWBqA^*=N63# zLGkpc^v937_mg<*kiAp!-V!(wKM}O+3%$o|UdWDX1|(5ICsuvGR)vr7$**Zzo6r|= zlVPX#b}wSZ?Ez0{O;2B*9of7ow4+pN3n{pV+wXxum3@X%A9nywkY70tG6*p#;CT@d zcpVPSwC`3*^w#=Z3xgZ4UNo1u@K@hXIM?8y(it&OyXuf9Ur9@ zEhWW_$bnH#janLs82Hz;z5#~DP~#TjcL*v7o2$oVEW@}{6$kK7O+^c(76S{6dRj9| zJq$S>WqcGhhGc^3G5BfeXfvQGa~3*)8f>faSY}E1&7)u}vmE`& zUF5~VFJ8A_e#Aw-F0&d=r7-w(iFh4rB1s?9*jJ!Uv(>vuKQ2Bmy|cN6X3~ziEG@|VtZ;kc0CQM3^lF9dh7$n!>!fiWhaoJss^LO zW5ht<&gv*-MP~oNZAfdFEqZBq@yzzUpz61zFWvX;2+|(15?d#H_?+cB*m(_yxi0yc zHIonGfrJHXqjLeAWi)M;9V((LL7(TTW9}s7*lzp8OGT{xy@*#m^!bUD?raZEiSiwY zr!%AZze;vdjU17LB#tmI-ZY4vz2~I-^`pc47~tuPFQ#bbR8(*p2m)5d5>@qO4qR%H zigS*$$OzH;STPW%3hd!fZsiC5Aax^ALSpLB*i7wAeTmIlr8VK&evrwtd29O5ss*oI z+v1k4q3U;j@gI_x(aOh;jd?{8w)urCCVt0IWl2a&kMf(zrme)Gk**|uS(ar#VL2#n z@e?r17RJ*{I(KC5%RR&N{Jb$aun@b{#FV8&x_y?PEzj%OS0A5#U#k8G($ze+%{Oyu zb7)qv1Rc=kL#&yZ

JyhtN4}JC;$qI2eK?IxxD;*$#_9uw4{d-r6gM6P&Z46+Hq3GloIr{Q}LyzRWM3 z(ZM(9M6k5n4GJQI&sWIApB9j#aS)^6`%DfQ7 z)z7P?T^bir23@Jm#Pw=Le(!2=aA+iO0d%*O51+q^hI*58n5ie=kqg8 z?yg&M5tDO@2TKt;Djy=M^R+!|w{ zL{L|hj7x9Db-+#W2Xvvj9;J)+eRi>}J?#~2^V%qmUU5nuWT`wkn6XheNb6z>53ZP3 zjp(yIZ3YFU#!&bSIC(wQ;x>*yB*8Cjb*L-suqea`EhUi(%a4bvh@7s+-`ubcv=ZS< z9gSEeI>DF3)MmQ=S&d#q-3$&`Rk&8oOfPhr)Bd)obKqq}X5L0qS@7yC`KKIcHT7Hq zM5ob2pxfl#KC7)Zsaq9Q!|=p{rW2<->s=bd;GH+kA1uGzc1%8fW5)IIQ?>Ql_!{0m z#Y%=o+4JN8gN#7=IN#nIO*zlUiSHfD_wHpk(^COcDW8yWWsa-h)O$jGffgyNQ@s|? znFJ`0Z9t4Y<>Fpp%I32FHY-!S$30!i%rCd0^iu)v6;&Xd8+^V83{}weWv^M~&c%{3 zHa42m>~E7^c(oK|WjI*TidP#;?f{>nu{zB|pGfR1oT7$u;E)Ze4Iw(~Ecr@C_;uDPH$G{2 zv!dQv_`(|Bko{?guysDtNh0dvgj{uchlMK5d2pa|@Ho}VY*Y!p%45n!9+eXxbLh5= z&wXm@7=ip?lWisp^+{t_bI-m}gFN@#B;Dh7)Yvbb4n+kPs6eoM`3=1jKN_@Bc2Y6&%(z)Cohw+zrqeA(#5HrIY8KBWoa8ySQP0`}KR()uxsNV2oUpr;jWLD}c;+ z0NeEFeO$|$H!Hkb9WTy<6t&k%?lG1)D$EgM^-5er(ew(-U(hl1BVIN|D%?$-vq2Vq zfN(ol3=<(ayN@PJ(Xsg{!K=!r`&Gdi`)PRyt=?{_Ar0Oi?cFTk)Rj)Fvs(C8h3;S~ z7h-_Oa{~vY)y)@`U4e5o$8di^VH4kL6f3D`+Hx$}i+D#gsSH?|*!rVA_iok_?C8vb zM;eE1Xg1`v`_^XaQSNJoA;gEMb(UatoI+mpsl6LAL|gfC+ksn{V>4ozHFaW0m-x0w zc;T+%D!EzEUE2MILIYQBXj=NMudD7T8rM;gmYBqbqrqF&&~(67yL6d5qEm9&<)wGk zB#mq;rphO*k9R?L;L9b=>Ov!8(y>NcWZZKAqO>>N()ZP#!TEv02A{1md4H0|pvV2h z=qj`;${pk1asDpy)fm%PUw@B@0dejVAEz;K;gJSby5LpsQ__UIl6!lPdt1ekM4F%b zm4$wB(P%!jk;c*h-a74P^rWWK9)3ay^$SBM!k;wv!Q8qZ`(zWriFuE6T7rv&cm0J%YH>(6d`uP>@P>EVjmsywoB)2VUnzqBPzU0 zBW_HKJDGL`9~N^>xFtcIvQpYzYx?JWS*Dui5w8!N&^uLc0%E~ROZ9oGug&^!+A)+D z-D6<9wdFxHt~XT{J15HRMG_TGTt#25+v+%%w^g2*_sJE5r@tw``Y>pU)VHIN$sj?S z>&i}4@Zv?*>;qi|RC|5{tv!kwf0oR=p*@j&Y0@5|C5x!Vm(-e67zd3j;JvIz6{%`w z*%Da9xGE8mAmHfXg6S4Ulxdf?pCHDZRLXROg#*P51If9$J*!0Jli;(hy?9?|b)^X?}GJV^3Ky35jI+nU@S+`IFa#g(zv`ithmT3?4TJ4r`dbsKI zQ4fPCMh;+!ZJiLgI*SfpZ3szr-Bs_PFMR2~bkC4So?~-(n|j&gC0Czh;C*G!1Z4Z7 zYDOMjyP_xc0XS2YiP54hOln>Xp*Q3#^1Ctx)655VjJj1L)uKI*Rl4el5ol@c3js*jr$$F#?WG%PmZ zUQ-qVUKaRgLHKJJT8fVj6nFMcqeHoj zGMhV8CI(BS*f1yYH5tW-dIS|LB9(Kk{_!-qG#)?X3UXP~)+pfx7S@iRE)2`a7fds)lK96U%Is^9J zb~M0Q4PtmXh1-FBzIG*oFA*t^1Y=W?sne|;Y7A^LkMv2TyfZcYUJ4=Ed)M!#g+g25?69XBT>IEw5Y_DxUmjaUiG^23J( zr-DUSgO{#aBxll&PQo6=ka7z?}S9Xz<6E&GneWn}Iz_d$`KHmM59dl{XNWShIHtQXl zCRK!-QQ>{0k_Z&yhr{G(*Cu2K5S@I`(P#L1^;B_m`R}H`!c}E+0&t4o%a(C?ACdv4 zfn(R6%2<+$WC0>en5pkdjytk4gbVc4ADwe{@7A|yMpc=+qHM}#D`d)jom!yTgGmWa zC?3d5bIQ2xQai3bW)i41bfyhxZCZW)Ewh&FX5JziiAMEOCOVZ21^Y^a0vC@;bSBw5 znfPzWI7CT7@90rq59-ey7hAfQ%O`39@0ITQ)7~VdZ3@N7<>qO0F3W8lbkPogj5&hrR5we8}b-AvFg-=6vtunQ*JJj1i6*c7UPi#N*utF z*!$hOxiM_vZ{{X$ZL4F#wi}-JfJ9s1 z=%upaq71gg$$O8(46(9QiIMlarkk-Pz9|)tk?8E^J8zx=ED|BZh7uU0wE^_g zLC^vIg+U3o7A+Sy?#BS77HUCGBw($Cs<5j!wJpbUyIFR7j{RL#<4ykDS^8MiPWePc zYNC~gLAf*vdTh?FLdGo8P5PM2&bwUIkk@0jRc*EYelJa-uDM1&i6lq8oSnK~%NLww zhg22ayX6k19E)>68eNKS!J`B_w;PzVcG&BR+t#0CwR!t(m@a0mqg%apH3~Wixr~BB1Ml*+37K&;i zM7H~x5A=lG=hCmFPO@-imQex%bdkbrRES$uV;=c_u#&Fv2ts@m9cj{DP3(|RGHxo+ za0d@@r$>ghPp(SizBs$+i+fQN-BK?I+<>&lhMhu>!_1$xW~10il(!QjP>hdfliCE8 zh<78~f4ELeP$FlSOk|N|ua|;+!;;KiX>&`Pauk`eFnGVULO0>=rc`M?aEy97oGs}_ zV|dJ8lIw40_nEGc^&In4tlLv&y3^;K z`=Eu9k&wU_nU}j#uDoQTivT@xl(pb-hw`u~o*zg?Fk9wrik>aSQWb&F_H>~%>$C2) zt#`W&52YHIAIbw=j!_}=yv|!})KP=xJ=E_OwM*@Ho{4JU;)4^skrE!{_Wjk<+) zNb&cbGFDI&`1ufc7wjKOa}4~U2%0D((jr?X%63t~V&fxou z?PThfE7N~ z224tqK77O|O6j}*^_dc!Uci9Ktkrt|DqmjVhmZI-1#jE|JvwndJMGyGHj=;@9=Uc*}&$t?$~1_4{RebuZ*Q>H#P( zLsH>b<3^9ZibL-ZpAN;riq8oJsl`&_3)I%O_GEgfh_0HqW#|0|e7*G7;t&0evKdac z7AwY-k2m;kK)^SiE|uYm+{&3^DZo*Kda>?py%N(hdTV^N6{S}@j*z`8#m93R4Ia?% z&k#C*+orZ|Ep5HqwK5_@S9av3-k!E*7SJOoHfQ@KKeE>O39}TW zd`R0SHrp_%aBR_zOR*9L;d!36Mc8X<)Kd4O^ajsZBlokcU!ghXRxxNA?$NQAq zlRm$fH$9i2U7u-0ZbMk2IL*uTb1LdX^3JHQv^b{MKPX6X6t2nE7~LiDY*TdlYBCP# zdz*|pF?Jui@AhSl6OgoH0)1&Yt?VL{`qJw3@J<21T;;Q4zW#tuDz8zW=&_25IdXo% z*SL+i7?P=*_^BntW+l@fn4iA%E2UA2v9P3kkkdOViDtE9h;560Gk#blKZwFX_X#Kyb?;yB-|1tf9H&>6 zmsQrY8jU{QAe+A1sI21j!5wASs4wO$RU+>bTAx38lj?V_pxnCkd_@lz+v!^v*~n{wY22q=4l~>Sp+(Jvha_6!5hBR=`2ps= zc{+LWVNbcc{Gcn3-LY$k0V{h|Dz^am+L9ns1h2XV31 z5yWSc-`*>HQf(3Uk}HowzkbLQi)Rtv>K)j|8C(_Ly-ogLyJUg-6_om=VyDXOwYkF@ zH=6gI{thV{57q!JR{3`1L|KW$ya+xbqX0jWLOhSAjkB8Zq-aGG(qt7%@s~rx*HiEx z%=_17DcasMY;jp}uIN6@mtw)|+?R8XVJR_hsBHaYFl^#{YKBd(Ug}hO*G9q5$mtxp zYyUC*pJXAX-^oINtdk{72Ks{i@-G6>0=&`^5-=KotkA!aCg`Dm@kzjRkpGEK@*52R z_?<8F8)Md1;#Pa`guVIyHYUHwKcRMgazSp!a@F-t#pePxD4laG!n8>5;9yr&|E0AUqN%x z<0UjqutvYofMH4U7aG_=Tt)-_MVf>8|L?*19gTp9xB`z73=Q8u#^!=wbQ#ShFuy_r zxp?+3HXmSo3;b`f`S;LB$%@E{Uw{$&QJSuV=Az790t1F6&TpZCRhXXx^_>{?3y$$E zx{IOv|L4u`p%GP37MGFxj^=__cm>Q4e}BuGOXCE<=w^STf&7T#FQy~-V&wiC7-4B; zCCLkpqnOYIdFwJ580+s!WPl5{+ON>i!6x3%&|J-$-xrVnEoTG;C8dNfGFbW_rW51$ z1cv3`Z}aIA6xf*kgz{rRf5qj$kI|L49sC^@;NrCiuo`_eE|5!M`E86~W&QX3HNJIm z>wg=f-)XoP{{Ic;2bMpwm+^wi_IH^9!^-B*xLlq~u;l&EU;x_7q}VH1{zzU3EUEs+ za&hq&6c}Cja#+Cs8XW;QuRIfL}|&?^F6J zVe|@?KWgu#5d!^|xmQ`4u$A#rx&VJ|!LF`Lzk|8L$Gn2&kJSAg3*=X_K(0iFymA|qlyn^MA)V-80;NMrsAC-t5_?y)YzF5Kk8=9+Iu`6i)NZ#+S0r@qNE>=k3 z$AS&HI;+7KhX07>%I4@Yn(zCpOZoeK9RPm9xw!f{m#*$*{=_1wWuRvR+YDLQ!S*e% z1w`_KS8Yqk{3G3HMT~T92vxpkDdG3d2bmwVvRf@uv{7+he1 z#o?#hzotBlz5nYLNoxyTI~_f1LUJ)95m`M&LQ7qJ*dNqj8VHCc3QHN0ln%@cVg@mQ z8KI2yU@8zD83;rM+gyrS=<;gW>JgIjKBEI&X%c0jj0ggLbV&W9Lqa+lW*SBij7U!Y zy=yuU1;uZXb+p#gzXc+MDFuN3{tz-ip|I~z`h-7i^h~hneDNVP|Jz1)QTndfKo>;~ z1pL+zCP4tXi1qIcVK(}Ua(Kl?cTt-!+n@}fiwN_Uij5KU+r1ahzxY5d z*3XO2&zoWL3G|GAfT3r+7?;cKAfP|*g)lO}lHf`^=Bog~%uoQ#^hbwK2*VXmU|<-a zf3~B)SS&9;1PZ!X#(uYfKnxc=_p3Ihi(TyZ`2X}61fpkVhGp>YH^aiua52*^+vu5L z?^U{F1A##dper83Y*5gZ2!cS2U?^;!{oUX9_=6!Z_kJ^8{3{qj2mP}{#;X89U`8j|MGaLAsvYMLYU!_4a`V?^=8=EF7hfMT;JcJH(QK~MtqoZTE8U;E!*lVKxXvaWz zDUUAV4{LWdt3h=146s>!{YN9`eUS7?>}#Auiv{$nZzbz{(86ACX~#6@e@FLLf|ZfAt6ajRpdX{?!D5($oKe z8cNS_@#XUp7zTPe=Bpkvz@B^6#>m7(cNrio{*27vKjtSB1JfTJGQslgDnMpNn0r^i zFvE)8l?a0A=pa}71JluiAYkC~&0u_60Q_YGer7+Ei3xILjKNUm3ni1wU>F!-8a#j4U`61H4W{C8@jd5~BaBcO>dQ7* z{bhu?eAx)I!5)3Z23uV(cD|Q7WCk()@sNvGvRwrYs}+BQpBZ{_?~nE8XA;7S3arat z53#k@f~m(?!+roFq?Ivp*1K4GX{9YJVA~{EYF+$5AY`s@LHK>IaB;y)sKN^6hw#z! zgSq*5z}$3nuzJe_<>qAuGckeb7@2s%4D5uzH=+CIHfn^horsOCmbLBoH6P5(0EQ_a Lk&y67@Zb7>8vw#+ From da220dca2f1f272df3d77ca869797fab2d642984 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sat, 18 Sep 2021 09:36:03 -0400 Subject: [PATCH 0009/1686] Add the Preintegrated IMU jacobians tech report and mention it in the docs --- doc/PreintegratedIMUJacobians.pdf | Bin 0 -> 322728 bytes gtsam/navigation/CombinedImuFactor.h | 2 ++ gtsam/navigation/ImuFactor.h | 2 ++ 3 files changed, 4 insertions(+) create mode 100644 doc/PreintegratedIMUJacobians.pdf diff --git a/doc/PreintegratedIMUJacobians.pdf b/doc/PreintegratedIMUJacobians.pdf new file mode 100644 index 0000000000000000000000000000000000000000..02616ee072a30a63e88c2bee32de0387d4e7d14a GIT binary patch literal 322728 zcmb5#Ly$1A)+XS#ZQHhO+qUiQuWj45ZQHhO+nhU7vzxp4C#$TIO;Ybu=Om;GB4V_R zbgWRM^UEXaP|O4j1olQ&1Ux)Y^fIP)<}MZljO;9|1pjA1(TiEyxR^Q-(2Lm^x|oWX z8rz$gLhB~cRZQAs((&@Lupk0gC~aGF9E3_t zIkpUMntjZHKo{&U6;DTre$M|fKS(}3&(X{^ne=*N{PvO@yi6V5Ft(3aYPKY*9EUII ztkp6MYoN;plc}*f`AS7S@<`X~g}*#a~B=zM&!Y}ch)=D%pG@N-f>cHg6@ZyfUQc*%y)q^%TFm|J3wFS)0g zcIp_FrQI~X%EF1!*om@LzDqz%hDi9|zKmYxe|c(F(*;Gz`TEGBqP`o(1unE2GrNbY z2aP0hP!1ZMFM5=9g*X(O@_Ch8eSc&+bQhZ+@rCR(ZVDFup zK`eo-u8_cI=97=Mmp45R$&$K28nz>4xiy5!xk1n}Lc~bsDb?HN6yyh5e7br#SJ(K| zSwoy>csVnBQBg_UGJEeTD6XGJ*9S;BLNXEMz^I(GIweYs7Qw~D-ElFIER27|qPuZT zMMLo3(QMon%I6tk;@eRL*-l_!dY?*zsDnDlw0st<-t}|+_!2I zv#C707m{*ptWFo&hYyK0U?GoOrz%#9i#4>1qWF1fUWhbq_LU8T2Pm~buWO0-qvvDC zCQea0^2F=u7Mt#9*y40H+H%*#OkIB)?WEd*gMauH7`m1FSS=eEEx4@GOblgtI&D;2 zuDWTJkKw9}Om&j8XVWD;oysZsu{y5Oc%M}C{(GulD^#_XM7x*s=U&39FVOF+X^|Sr zt759EZ1zl|!H2z09Im++MIK+8{HLuQfM@&dQ4R(G1i-wg_xWa3H0Sq~fQegf;=m)^ zT#(P|2D_pGA>?&;qP*8avShT;X&$7^3tD~i^)D-q2n>0^)~TDk?rgRXd?zNbPZ1>6 zmxK57Y@ELo(M=6QMGy@#2*ZIcb2d(|r(gkw9y`RC zsDQxK)yQW$0+-vwKIP@h&0>&qFQvYxTHh>6H=`7?=rdEMiyNAcbSXGL7+5`KoF&Hh z;FTm(0cOTUr*NkM`IRgaLyBd72s)2@;h7eB=2@#UY4)k;KWj%`UW^8-&v32`=3wnQ zfCKtYA0h$UHhJ#RLlGo1v3##E@oJv{;wM|~;(;8*jPdgU)-<;Yhb;;9H_i7K_Xj>TA#|;0NE!K7ya~NiGU5zfn08cnC2fWb|=!o zpg&ZTEkS#GhA7n5t0CCzh)bF5Zbrd^9oEo4r;uLeC9G2CZ}NihZ10n-Ntf03;>oPX zrc%gl^wF17bm~Y9lSn;Rs;L?$|MAu197DKxp5NXI4vFhydp=&r;bO-|xSaihdbssQ+`lioZ__RUn@1bY}># zuCNmI($S=<1RUFc}Zc(uURM zBQ0CIS<`EA$79;t!Ns;;z8|{8kN6&K8Z-fcB>bBw0PbXU94G$Q-5XIU@a;4HYsA8j zvUMJ>XRAaK(^nmH9GPi@)-+rHVQCLv=k69PvK^InEB%b@}|&(65JN5RtfIJ$mJP9pG&P*3>T5Txb4WNTs zrv~f(M_Ni2%Q55ngliU2&*ps=R;g!iR^_F*Dj586WZaYKr0iXbCl}|xWdTxIF8I3Q zdkzK0FxIfo5$}OpJG%zk=J09P)tyyPugAmRPoU=!i!caHAVLhFSB}m0^yTo|npxLp z4K{rU=qzkfRjeK`EW_d`rculwBF&c&%(yXY>;ZFwFhfx=Dr1&O@qTXtUm>n|<6qME zC;No6l@JO^l$`EB)B>ThM{Z)4Oi{XZW)hW+lt_+8ACcHeEer?l8y?gi2z=#)@DGmb zkN_En<$&ez9(TQ$?LfHAybg(Zg3?jP6_XzaOUo;CW&-lG0`hheKxMTY5}1jUNNC`HR}0Dfj3j){<};W z34HFHstRv56DWr2`wmO@hdqVFvnZHzsT=XqHn4yMhnSgok=3Y2=7AZD%v>HAN)`|> zQDIU$#7?O|h!dO9Shz;oKS6j%#VU+!_MZNN6lQ&DTF8#6^CS1!!Sd;(Y+C(9v(9IC zbqZdyF2=>R->ale@0Ytx&$svG6*x?2==ze6o+*+hEe922Bi)iY${0E<`+yo)w73tD z%I$NiKY(;P{J|mL$-#hrSa29Nz<|guLI^wxEbC&lU_C5w902LNEF!Af5HTmWFW2sA zaPZtTB!*^H!RJXupFBu88mH*!IeF29ZoK_nXhkFVa6oAYkmO2n2zyRywsA1a%Shua zl--f2J0tpd8b%aDcbM*Qd!#BL7e&ForYUR zg3fF2kRg#Bj)8p-2eGjW_LZCpO?yTyAU%95 zFnIsTyjAe!E&Yv^9`?}q*e zlpyPJGeO`98nSHdz$g&w+Bc7IBrK9dHa)*iR1tJ*iup8UJld(8zaf;{mj=NjLus9K z+jYBM3~1YFY!_?7$*N7MHgeHO&y$L;)V2MhwuhJ=UTq#K&*Icr=tZ~E@fDU|xLVIc zTX5l1F+v1~f%1zW`r3N-9Y^V5Q7F`S0h#VqOCA$nr0|2H-@^NN=)*(wN!^)A0@Vmx|O%Vs2ah$P#9c8asNw?4TVir$>r z;?ja9IVe?|Nv;-W$mrsbh_oBAS$$;)X!@NQuBuLWTjRU{r$L>TW2%Z!O@$ij9^a)O z6cw9SsfeCZ^5UJMy^^Ic^}c>~#+*?o)>{ZQlB1rM*95nYs$k7R-=djqK~JN*mydS7er-MQy2TzP-@(VGKi0917fC*`n1ABcN6~WO$ z&tP9*@qX$lQ{3?8NJub{s%_Dbf4>F8c3MS-#VbF9%wtXS%Fy5urFz{w*9WHOEWs;= zdRg{<=|>af{4CvpOCiNGkbI!>ZR^C>Sy|`@Vm(%6OoYx`(li;g3dOl1O+>bX6c3(`%hPRwnDgXsh~Qd(&SKBmrk2l1&rivBC!m1G##;53V2Xbyn;aPu)={lKskUA25++^SM-%b)1v zjP^~od%v!f=x;OirwYu~)7BHbn>2Q>R~yWB{mp#*aKJ3=A_CqwX?+(+7+3IDpQuZy z^M;b=!x?;``EZJ#J6zy^x2vUo144Le=|`yPY!x*Wdd%(;)xO0y6QWo+Mlq$u_9drs zcRec#CTBu<9sWF_ISm3|j(Ps=%Fxa6-;SQUcX-7n{?~C+6hGz4ux=<$%ejwE{`;fA zfzyD2-cAJLi~;+ja-`xwfmeV5A2ZjOw*(tt5d4A)wLY8XKXC~LtLQ*jIPdk@(}=WW zJbXO^T~Vs3-zh$67LwOAk zk_~S0eFuR!#S05rPxQavpCf+&+!Zox|AmFD|AmEYtZe^t7S1?tbt3kC)fw1577qf~ zzw?-s`Y_KBhRrrVH0MY@nxSZW7K|n8NX~w7Jlo&V2~H9~PSuM{JWA7-$^;zW8ojmk z>H2>@9A1aD38CkD63aS1lpp|1W2s}so+3O`;iFrYFhNt30B?PR1n5p&&9S7f}tvy7nx8~(|bk6~I6 z+(cKmd}YV$Fj~qoqRD({^{M*|u*`;#J~W5M=oHeY8LQ>%2r<-NnfDebx>N`biKPBs zsE`l8kc%*xTJ@Cm?UJ3&Fr0}Hq8wfBo|p&;k6B1Lco^sM=f$;1T1Lp_XH)rO7C0{- z&)O<4y|?C?`}J^q&1Li_bt8Z}Om(A$0LG$!96GtZ9w5`#-cPw7i|?ZLsR)~c?r&p7 z;M+&Onfvj7HAHS}h$5Wl>_ZcSGHZ=km43@RWJ{zu^{{ z3+6(YL;uWlt6BHkdqWy)Unac2F%F>rK_=42r+yS<1P?g~cOiI%_6}(k+FsRTn!8a3 z(l-a~#b&sFkqg)>q<|aJJ=iIn_*32|@AJ-~E0ZJ_pH%AL#8O@-E(7SAfd}~vV6U79 zOCLJoizPro1l6>tsgz-m0jr0Z@4yKPUFnhZrva^Dh$+P9JgWc)!UT4dWWBIlbq`|9 zwRI zoXXfyGbcm-Sb8!`I+%Gy$<{RCV!l3}rWFSjQN{k}d|dT#MAJDsIt)*_Q#olSuaLQ( zfJqg&Rbi5PFF$QQ4}T!gEvuH0dD80ReC%&NWlM`ZSzNi^s!fC{2yidsgpsMd&Y`oJ zEhstHKZ!F-P*J5QbnmOq#9ikZT=V`lY;n^&}L^Yaj>V*@}R~kVlHclu*r)FczsY5FceX8o> z(VGSqU)Ih(Ez0>qtS_}`qElyj=wbw&D{|rUiY2>US8j?kMqA!bPi}Ro%Hb0`r*gQT zI3gfyZ?L54!o;;Ld$#nTQT3<$6a!BG_B8Ft3dLL=ylLt~A z^h^e_r(swejw(}LshvH~l~cJ^2}5c?;5%I-dh+ec-bbdAYJR;+bn&eRbw<`{pqZ3W zh1Dpqy~Q7NrEv%qyx1d3UiXa@+^ow+%B6EqM-|WxI|1xEQtz!rm}^3I#1){kexsBM z?c-{l(Rc5Qp&~lMpoR^OL2|q#VK+nL{R$*KD-tuNND)4t(`Qqms2gm**dA0hL28xgI2^&hkCb&A~zU` zm{;kk#g`h^7Akkz)Vd+=Txnv1Z)0+s)xsVEh zcFtBhb@o&_`Hm|*%bG6`y(CaATqexEL@-`V8*Gpyl}TkQ;y={T(H(b^=dsIM*|7s3 z_K(fma7f(Yv&0!|D$!!X$RJ;p@uZ^JpHd(P!oT@8^(gNWE{pdxRd$ls0ss)mweww8 z>545}|HXCfjUJnbGmg7qdCuRk7#m&#BNf7>O8hw@w_`8_3>iS`yiddM89=qoB@Dt( zXt~4hXTR@+?EKc)gT^^+pm*cWGF8Bnt>vnKzPfw5@J#<}{)UZojNkBt&W-DQ&8Tvj z{*?7n;OWp4`T8u+`;7jVUaPE{!}`y*eKJAyn$FsqAC-|kt1Sm=11bGB+C|Gd+iSG> zkn~BtTL$kZnzyp&kd&1V(NLQ!T713pkkmrFWV7**6xMvPLr80c2j3zMMm8PGA**;c zKu8=qURI&c3pIP5=)A(H`oZn>JqL39Ql|eQJmxo+3)%DjwsBwgRypOK+*XJa%H(gL z3%z%96$AFup+#pq^!Km%wtnhEb-P$YKCNk`Oyy|Pq8ok_P-mroR;wupnKmLXhW=U! zek}bOZ_LC4Cdn3#EUL)Z=^yod?ugl%&Oc=Po{(48^lIYWHf{p*k>GdW5s|pGOc*^Y zC(jCRAo`WAR#EP*cT4opk$Hvjv3a|%dnJHbmbDO&AoSCoz9amtQF&yrx%#L)kBV@x z1uwo7ClTo#e*_N|t;wH=|I`Q|PL*JPG-kuWM5mkEFhw3K8>>ejW^x%}K-X>3W!hU! z465Aa*`grG`>Ev;m)!_l-ZSnLENHSomza>cxeNRx-yG*5E%cLc>*wn5N%qF=ZOb$N0vUX)GchwRxG zf!SWR7mzHps%MYRRb8VIC{=w~o7~fM9a(Bep@OYX<45k4XDGVEiqjT&M*RbKsxn@$ zh<35HIDl&4LgBC(j=2k1}q=n!kX-`r{VGpX$f#I)q}_;Zo10DEA7hCQCXjVueJegOIDO(YD=e>x<4iUt`?lU zJlk|c%TR8{ZFk9aLIhXvbU!OMi=^@C(4SU1J$LG`grO~cuq9Z!QEdIZAmsAyM0;NC z`wT%G_Wp5)HT$x6=y=nSKdJtN63f*jEzgM>ueFAb%Km|uer1;Z7q4>s7q7B#GW^fI zD(#HTj?{al9&N8O5(Hqug9WZ$qJ)a?w5fYluPWIZnR=d{AVEpevavbz`)WHKgfndr zn$J;8vW1?M2^b(&)OTBl?eEv!`TpC3kYPM4k)-Q02?Edr##}_3l;2d9b)7Z=pVp`Q z^ZoPBrg;el)uh||kNT|82I)BjroDRWyUWIac_12_?5<7Adko=FUV&i5Z&9({}n1FE} z!GgM!Y$TX8N2;_LYSe0$0^F<{C|y{c?bE!NUT>N^El^UC^{a@Q-SwpP>YI+Ny>Jix zPm4l(Bw1!KT!=(B?j$5=c zR!n8y9|3Frtj(>`K9g`GcH2l*WM4E%Jf;Y68g5V;nc^P7+YqRi09Kz2RG$b{p98Cx z08-z<*ZYFddqTvcWyO`H(}ljXyH#Y>;wi`e=mZ6+F_blD=ak5B29a*Zd25@<$T?OM z#gdJD*4k-;j(6kKAa7swUS?lTlu@_?#4)g4r{*9Y8y<;L75M-$ilm!T1rJ21EWP-6J)Ztq zX`j0Y5xG0L{y1dWKM!ayi>M~{vdpPbtC3SGpu{wFi`XZ{II_#$@)7eVNAlkNG^_9H z^iJtJNAk(tu73|RlYFDC=tTWi!p|Jje-_2+w3u&rujN%r%T8vIAvgUXexxTmn8u$c zK`+QyIa@uabArA!7|rnI#EJY+_g{^WZTOJK+QoOMw#_*Dp|0g3@5nGnx3rwk6<{~D ztWW&2_z~|uJ5m7T)kjPrWSd)GAd3Qnbi+79m7atzPHKYIMICS`Nd;5l=n&yZ5V;*g zzQ+V8a`=c5mx?@jYC%!S`YqgJlU*<_-$yWRFCV}4Qbh`PxK>OrdV85&^{gJdn(=DP zj)ki+Yito~Ns%itGPRv9{cgY_3%>)c-`1x4fee>P=@2N0)38WdE7D)O#N0e3JImjxM) zUSANhbXrMkTEtRXWs)nA=axu3Ap&(+$ktt~+}^Ghy!QLrF3{ zCZR5Klpv@^`StD9vVZ(qnXz$|e4dsog@>>Dl8#9Fn?_f@G`qk*I{sDu@Otu8^Yzr2 zIhEeCWB&4C-I=zl9D5GXi~KBeYfP72(<>cYv0#fFNPo(-fpb3L zRxO^mczHQGRN9<4(k%h{TaLToXLoH{)rk_n+Bll=xh>mHzt#Rv3w@sbbISVY>3g&9 zONYPkuIa{IN%CV#XqAWTS`E0*Ng;;y8TqFAV5{-M8@B+dB<4&h$)5Sb?y3NqR@Nd_ zvdjREk9^PBNE1F+<29PZ)LQ4-lyn#WJTQeq_28E6v=vp|R&OyD-xob|dzUULnQ;v0 z_qgKTqRm(|aXCn`jdAzT!-2uFd+^lO=2a+toRMMx1W^L2cOOgHa)jqG9?3+kJ5Hqr z?1@Rs2{E+06lE(HhSoZzadJEx*3+oY5row%<&VwnS5+D4rh*qHbsV)R8x0S$&Def* zM~tXLpLs{Q1O1?Z(Y&?cew>#>yz?BxB%RC?9f5*y!_Ich20JOKVcK+WQI(=ltP9u~ zA!5FRCAMHL5Ct$vJ%*oWdxkyhcg+Bt6yhi@Pp2#C7W$#3k&0?f9KvtI|MA zq3khXW5w+E;Ni%Nd5;IprZ)1fiK*K?(K8&?q*6*^?GPt%`}CXJqD}FWv?ThmZkI?- zMx*boLl(o!mi1#e5@?IQk?Op)_+#qVdN(oIrt;rzXw;fOD+#?qdzg)<5y=T)8YDxE z^#Q?JU=JuV4Kx{1i&5a5^BZ3Vtt&g~Aj5+b+o(M;O>82OUHC5+#V{V1je(>Uw@W*O zYlDsuavm_onM&FjvfTUV@8K*2q4*v40$RYwNsW^gEL-CwK%ho7mT3y0gy1S}!{pL? zY4&M5#8tbhnW@G#77V&fiA(cf zvAlRHWvt}nWh{sC%dSc^3nD_K#&NpHmy(i~zB%(W zhJ9zCrJ3w;s~}zU4PpYB;m1U5(%YG({)y~7Tq1LlDI7I4}kH-BsC_XS5gRcfMD zNIU6>pVn#tw(NknH| z`(x=ubp4?IH|FAFUqbSqvY%w~w87<^W4O%%({bT`%JfaAHOi5H%*=>)&@+9xdPgK@ zde-MyoPn>bSgJzz7?-gC$NivO2F`fVXRpOL4pCa1XkZ*;R9wN(7zM0p&BT$hsQyuXOj4F7djuDz zfVoR!tPi8k#3CIz0G9GqW;r{<1!jZ8rRf?T!hHBcpu4~Ho$Xz(R;Stc9oaeiTKdVX zjS-jAKXJT0d2@C5IO0>2RWD{vEK=LgTQ&z%qpkxt4E0hcCsR!@%nalB2OZ4Vp_B?7 zoeZf1#mfda??xFof++~UfPQ7J#*WmW@MKT9#bjby)jSzzq4Cs>Xo)he4JL`V#{!1J z92-n`8O@ZD35g^mPIq&Bd!ngniy;GYO|n;sR94uA44NQWn~Y0Lv35fsC@W}5Hw5)o z4GGCc*3uXvHe%J*GsWUG>Z;6tYa81`yMsv7_6h`9tlStx-JC1rHX3kus_Fm$M z2NI0>KtszP17-<3?M!Jg)Jc*$8Qa|IWXw*cbja$hFY%;Z^%Qo~EqWA6nIxpu`Jb%a zY_#f=8rcNKu3A}sSf!8TF{{P}mGW5lFk@LuJ&CjOb#lkx=^R-ENE5*chuwl?1c~oB z3qWiKFD^`3vbFray}uX-Fu`REH}s49V`Q)nVGC8b7rlZ|XcG>bwO*ZLuh*Hu^S#cB z%SwuVGc;j@OG8GaF2|dnG-5QN7$U-ju){Bw=k&+ft4gE=a5L;@uehxT$3itC>dP*vK!1r5j%CrW0sRco$Z|dQDSlr zvJq)R6X&{uM+38Rw+ECn7Cw&xxr=5;lwEW$l8Y1Vv)VqmHDCitqzc(>J6;Hinsp@J z{PXNEnc#ga4VGxZFgpsfTlVn+7ZEBj+jKM40Q*Ml$QRzS0w!|B zI?V$jErrUFd<4#Q>X`i!#=<_hocm*%D$(VQ;~c$T+m8y+9y2``VYU%IJvtH}n{qrY zKG%!q$I|ooZf)~sHyE6l62PS@=nK;*u7H8#l!F#eF&9;Rf1n;M6 z)V&rJeJmcQy7(7`|LXJDF1@c9!tM2HMf{_}{=&UwdNE(WH?`1fRxi$O8t{%CZzX8a znzzrs{tYmm)C-t;MN&*CY!~+n|0#<^O#9mc4XgFZm<$;L9@jzFv^_Rn!A=9zu2Yfu zJi>wPtw??JyQ|;9{uk!3{1@i1vHgD(yr%4M*wJ>bsHwOiGt9=P-T=S?0g^)8 zGaw}VNq{LD10kWqc{{HLs2V#fwP`o7r!Gq+R!@4)w$ZP$uA=ICT|>-w z<0)(XsDqRLcXO69omg9^kJ`8MJHy%WW$I0!%!)iG$VS+8&F-9?6d4%NSa`nM|F zPH33Z!5kmTp1!yHgX|uM8#5x<=jZe!FmxOxZK#y&%2-2CfZhS+eH~gY*2`RaFE(jC zGU4(21qf_&`XoaPzHLRz+E5#qIS6FZIwc0a6gt#-PytkV%N8t41Npv8`HthRh+8Qp z=F+Zj6a5Oe9EO55N;7#QS)xE`^^o9Lff_e2%ki6hxy*eK7cT#Ktkvj80MkVQeT_{}L{pGdqp&(^@Hwu&f`Zld zG!!Bc6vVc=oUtykODq_brMRQ)rU4Sy*sBOaa9%&_#r|=S&FOw-+<}(*C(yj$unDtq zHk+zzvzNIHq?kd=9l5&*i zCUNKLCa6|=!L06Ci}=#ydt&L26-$k?h1S`^vr71Cy|q?r2hUF8^^>Rt+i6D^WvU*6 zc)RilqOE|7H9(=sLRpbHq#ESGw)0t;LE7q<;B8^wMnFb2VskW4 zb2fPBLl|4{*RpODm}K(eT!Y1IwKB3rMR3T{Ih^>EhQg8b9ZXP<+&Keoyv{pO=@4K$ zA1iBpc0&ABc|cGT@eB^DgXCf`GEf-1IBe>1y2}`L5KT244e(l-Z!CUoc6WEzri66b z-7TKq-&3T{OINpdch}F+L&ejAJ$&5O{S`jGU2Y}+Ao+?q{-3VA^OwWl^TR10%$J6r z>sx!w@f_qKN@0<_al98(4HkiwcrZ|6X!zE^=1cLoF0_2d{Z@eX8FhqKRvSZXM>DKt-Fd#C9j65`fkWCWyJBt;pF{7R;1TZyL$ccS>M`i_dO ztMir04qT+r*rc76=f=#4Q-d89>K1)hOqm`jJS7b1DwtF_X~o)(3|d}CLb{yUh|8}= z#acooc1dHU(@1sY#6)GLJaJVfI`!Oa<*4zA$ifVVn1c=bB;eHyh*n@gV2kLyQmlvg z*ON7WKHz1hnFI(>5CZP?n@YHL$Bkz=wK-9(cSv{@yy$kkB5gho2Vw_=LsbMyHssZ( z$5rFK+A#oK4xWQ~a>MyGKpGqcy?3C$wWwy_CIyY9`$!TjqU=!wfC6?7IE7cP^NzF` zR@Me5E3?{O_e|Q--yHN&si3Eh{w}u;~lXM9aT`>k2Qomqa~+85*8Lm=MV~AWDdd>MDBEsoF`K zjS};7&`by}?{@8iCL2aX7Z&Cg(tpwUL2!4VSk2dw->JH9A5vq~U5g9$o30r^1WO~qcG#> z%3&boK(-i;3XhK?!(m$xk)gdxl~feF?G;JM13&S~D58X%fDKy!ZcZft4NkdnPG!zK zs%?uoa+;k+n2oY(C6^hSiM(mtIa?6IsvD0sp^tN`KFQ;&zPEf_6xv(5qe76ehwE7YcNq4i9^(B*hy;KjDOwS(GMI^N8s@{~`7(I|r|lrrVl~n_KtY~7rg*Z0 zr1czTwdT07`YWUy)oA}{(f}OUlr^>TDrZ)aTTZ;pY^ms{3Ey>keOBNCh^9c)rWtyQ zh4T%($yA`zlxD+)^UJO_kr=BIdTXthrn;AxtE{W;DfS~Abj4}Ad@!w!u>@prre&_S zdy5@#<=c=;DzruF-bm5SADO5$B13!3Eo8Xb;QpNwYK*U?tN$iKQ^-2ZGFLOEw3nM( zNxoL=I~AnBr=ML|s8{dQpZ-$_dSUL(mJbyw(P=WUoU75Jl-I7~!7W`RDYZIpr3!YH zIRH%S;eZeyEZ80urd2OI$d`N#Nu|c^2aQf8+#)Gm{m<$9y6~@@1y~W*fBUkbrwV+k zvuQi?DIr?k_;6}4sR=E)z*&+Y%PtNWF3ADqw$ztPO{0rFoRTHaPCbeR+Q5`>;Jm#y z;}YM->}hzQv8Tbl&~nF|MFoJ9sF)0FUZhL7D@!{4S~>XeMYJn=2heN1hSp8KgJ=DR zeY>C~a$?b-S>LGuss=u44{$Ac0{i>`7Yc5VQoIn zmhxzCW+mO~x0NI3yTuFcZ&|`;>WTw!+xrqN!34FN9xRY$H8RB3T`eQ^oucx_jz36$ z`S@zs)l;RX^ZNXD8JY`OmkGskmSMfiW{=hK&i{1IKlESB%Kl%>%E9(O{%f+MwG+41 zj_9}7H~2G<7HDHL=~{NPua~))B#Fs(DuUhO ztC3pK*oi~GFN4spv*%-JPGuH`5p&9{&7GNwgi&aQsRH82$*n8%Cslz-f1E|O6@J8f zAViYQxio19>(4ixe&2p!A3SH-J=Q??_@i94DZIKAQr@ypt5pE`V(yw|Mn!%B zy2dk8I^$UNN(~caT67WR14$o$yKEseXvK08a_-o|6IY@CsD1^V0o__fTmxiVNmv8)7&NOX`riGh5(KgiJNPhJiqA6g&>Ob6K z7ADBe+kMKoFzi&45*QD{!DsH+>*zo=X6C2zUhovBjABOSrFwo|Bc6J^cqZgtVO*N= zegtLTiQQbdH?nZE)2lbKxLerk&0;D~_1Y<_uz8B+$7x0DIh>ubuuiQGdUsdxxKdl$ zXeZEt0T;J~4%AdvV7diP*6Ee8j5kVY{72gFA_iF13H+|@5h#sX3rTiTVDsey=Eqq~ z?$Rp18CH3{!Rkz|(srZ%Wp6>-;D9v!N7J8zX?9%2o`xeH&+)C;PPae9Hro!WP|nW1 zIB&GD>Uf6;Z@HvNS@1qRjaKkl-an3$<;eMg5GTeS1kBD~Tda0+LU+XW(!y z;B%Ma3Usqpyc==9vV1Gr<6GH5E+gX|B& zr~MSEYy?zZs>(Hi^oC(Z1V9i6+?)q#1VfY|()}2C$T@3dWHv7h0LBcXKjg~3Mv-bF zPEcGY)X}Uzc5p=zE7n9L}Bo`|#)ulF?$3()b|CXuMpIX=~?k z-JMSMX$;Fok!A;ApW0}CTYMb2je->Ht1ucyq72gQnl(@5U+z><<^e)*1o9-0{QWPW z(|n0W>E)qB-BTDd3n6N68>^`As+~p$OX1tZP&9VP!D^_tT@+LlLV1mN7vgpbBv0rr z%zCXsZy~`113^>+-N7tsEvmNt#_dDvJZy3k9Z){D_x(MhC81%4W$6QwV)?(}9HU+! z*5OhyPG2Ybt?ue-!Z%fjHdP7Zs6*WpZs8{Vt6TI~sNnQAT%U~uZ!d~4t(vU4%UytO z6XG3wE!d#H*6dO6zHBjNv+Ho7>$D$*8!!e{>QruP=2c#Y`idQx7qq>V-c*|bFpO7V zfdrpH49VesZCN%BF-*iBl1qXc_|yJ**hYi`8a}a7BogKAr9uETd;G{!fD@GQI>ewm z<``Edr@P#m$a_K}6O5Uzzpvqz8!{c%m!l$BqXCwx!HCNB>d2W!;PgbK7eZ9|BZ&x!uTjXc{;2dv?TzWrn2ZnRh{_nW0&-GefnL~}_mz=MJy z4LggqDeK8TZ%WUOkU}y$ZhLo8vI_>>!1^|JFPQV_UoP+4sXh|UH9#qR zy}1}pBkY5TtR+`I7b}Cv#Z>PIz-C}jS+)_jU+)Pc?`>j)$lQl?l_Q8*@GT{@XcHJ8+^He4Wnt~#_){?v0N)<-m3s5h zUw-JQm-fk9lGV4p`|TLSNS(8Q8772S&gpz$*U|fN^XAeTXs_TIaCfyqF5TfK6jWyQ zdV6}u&VN9dKj+Gixcnsp!|Gk_9KHZe#Bv94&sWIj1C&o%Hq&ZlN7Eh_f3l}yZ zD1`vGH{!6xeZ`fC>)fAGVDLfLNGo7uS!8h^ksy=z@>2-Inb=_}L;6%SOoKEgj4x~g@XXtLb;>Zh*+kAf2OP5t=)|sHM z?zD_)=!kA?2-|o|Sit!3AZ6_upTh_pFe)sRAf-;uQbNJxrq=2N+CnL38)74;+7O{V zM55O4WY@k{yMr~oO{(9RaB~F3m(?Xi_y_vp1xm2CSq=~(V6oWd;0x85|0ol(eB1=i zQk2TO*n7n{DDD2aAxs{Y^I?(_uIL035=JBliTxy4k2R$F)eC-dpuqa*ovt?169ZO1 znIkNE{wD0vxCtoJvziX=dSGqL3X`ybCK{489&C4u7_4a&f1hkRg|rbHvbf`1?n(F# zEukEK=R49=(c;0@279te{TL}(_14@i;%0;^qJlJvE_3|xRv`(*VX#lxX%=*jFAEJ) z2Qtjr)jzOg2c`jcE{<>7JS5>Kw%`F zC{NK}0uRg(AbIi{z|)Et{IYZ)zM)Rsr_9njY+(uVD|m^wSNkwq8M!*kLt`29EWfgi z|8*c@c}`((`?9`014Cccr=U&KQQ@OgVWP@1ut({)_1pt%S4ULDJMlpI&JFKTPNBrL znK_WM*~RPL!PW}ZO4T>zF$Wv|CX->JtIe;6>cNZwajARS?kL`mB#(N<*!`tumnxgk za{Y=lQ*!ZStm<k1cLg8?0?MXZ3MY)Y5^Vbk6vvYLq zw;YrSY*!$o5F-K88C{t|GRd}BGL-L8wWM9t2lUgm9i7yK#9X_%J1H>UyXls;VNu=Y za809vt^L*dk^knzuB!i20@dJOl*ugkmV4s5g{=gc5)!7h7CDnx?;4P-ldJBjet zTe9PhAmr(oj@9un>En~ZN5YIqCYw_a$>XsN<^9hqN*-)p=Lz7|;}7ZYh1GYuu-e2w zkv6m_7Kj5Er*yZR0N>vXI!gCGzM>FIAb<01an+FqeWD>@%p$J46rZ}De}K|5E=K;Z z{AOYLFY=p-^M7WcTxm=HW1%4Yi+bNm5YD>o#G!P7Sp+h_QQaX+ix>G8~DnFWxY5g|u$zEaS_Hy&O-;$R>{ZHE3(Myq`EF!6Rb{v6D#qqt{ zLszO^gGy?GzlI&gZenKTPZ2_a&VasJ_05X8`V#*%`^wGU)$x0^*H0K#yNCBXNKW7S zKL--U5ww=%&tE+u7}+euWqQRBMRmvmKsDNz4y{ut$uyHJyc0Y13S}1iN_U{;$$vm%?>& z71rMnDa*2^r)F&u=ff0xuya?W1=t56R_w?QQv2g&kQ^hr+MKm4$18n;%wjAUw~2j3 zTK=CO{ZUR!7)9|d?k`K38%u9%su*-vO$kXzMYeNVkDzWr zVHm^M^c{j-(fvW+bw{3)G3!l!_KMXT~W)r z@sxB;%IUC{80{Gia((EQP$Ps?S`vg{dFa%#2&1%#N+mL-H`rEI3ArV3Y&RzR&X99J zD*-SiT!%3SB*6KR99zUdy$icAjV<1&naIH?rI86s?YD(V`111KTz5M~zo#%5dziKhbofv<#XN|x3{&3B{>5YBF-amV3b2J z@#Cug)hRSk#zf>cr-FkQn=}GSSWer4o!M+)ia=u0#5VSXtO~!5L7pHEtfUaWL%wkW`=XuY%s(SKN1DhN3RCNG$RP{pWgbU(c^fC_^alh?K+_ait2($@rlXR{|8 zb3^1nP9qAHOWX4{49dJ|;u7g}R-Ty42!L-WfyU;mmfb{7xYTl4c=|Wyb@Fr`Z@`2} z7j^@s0aFAdd*&v@^e(_xWOVrJIV>;~WNu6uL3MunEZt^5xenTxcs6zGWp7pga6Vji zzuP#^X*xSL8yvNrNC*V&n&wFt&dZ8LVkng)N(w_XCq8CjubWgws`s#{_zv9vCS(yMUcd$Vd;m z#wY@~Yo%Za)47SFt#c?=1qg?H@`~o|n3-m9|H zK!o!mr^@WfG{iFx@_WYmx;96_4O7g%XWZ6;)ul&bFL>yynR#m6VZ|hJ7%&V^PV;>` z5_ZUldWu5=;wvgzernel zhk-Nzqh9N4C45SjTX_Zw6}ApSzrq2p2)GmL8(~34()JiMMqq<7E{FWVptgGA^Vis_ zW_WQj7>!Q`;{n5QQ&CP4WR2cuTmp)3q|{#sohdDb^)DN`f$l4FTRX6H#YF!;y{Ft4 z5co)5@`aC*A6I;d8MfJtb%>6-6rC> zSP-#j;^q;B=v*(+HGYlo%_z)Ptun5Saz*Zx?3EA#3BLax*;Ci0Oo zd<9pX>bW2f2FGOY^A?DQZ$Rm>X;^J~J^rC#Lje2n=PP7vQRtem0h>2X26Gvdl*d+G8KSMf0>ddfHB zp2EwfQIbL@@&TL-CaN`}1JPEghAr+EIaLe?TUwlR=u4-szqy?0+xM?gncDdEZMt!j z$EuCbx4>bRJ{Ld0VZ=jW67lwR?w#5Bza43f?fny@Vk56bbSPckDa0TfJNrKN0eoiIMbbj%hNhZ&4o#D1wGXpD@BW!ixL?JY3L8cK?#fSBbI$^7q5ej6G zEv1uS*=bPgzN_EJHhw){arK^_44L5=_MM(CYn`QQpA%DE_@P?0NZ1NN_RhM$Db|kB zsUjUkQ<$quheuEW`09&voHZ8xods^3pnr@k3=~gbY3?@zML8#W3r2A@8aXlFJY1i8 zdke;KG-QH`kpC^}@7zZm{#)ndfA-mwze7OYG3{=ZH#i7Nn%9i41{9y=YAmw;zMhQI_a`&Khb=_J8~*~G14Wk05@+`S@T{l=oEyW9_${^Y6$LzS+n_4FDRxR z9}VwC^D9m3Z&ms>J?#rAjAD<(Ylr8*O{62XE@jQH^(~C@ zPIahYmQ1sM*)n51(bpQwJN_3L_1|tWSr{1qSA*e{)<*0W_Ls!-JT*cMj-TR^A z1~87}m~nCWOlUlhG~iL3La0-E`ON2?&EG{|ZuEToEDqTad%KBbWx|G@Au%3&85e^y z^&j{QeM!VVg0V=u*uhS4@)aMZRMr%ikbn9VV3EvU_HLLlX{Bay-__#J!JtCs-0gxr zL8SgNJr;d%iKA%aag|4fg4>m2h|{vvr;H`_qA$hr71J=JYIVwi%PWht0d;2)35?N? zlxGrh@t6LP&0*1KT9^ezg2=ttX$isMZFYkUn7{OI*<=p$AO*lIi?~MN=y8U_`l*); zZGs>a@*uRY29fol2#U$z?`7qxcRFTVMxL0=5Uzha6tegxIfdLN)U9eKYM5$`F!N@@Wb%`{ zF!di1-h9CcC*Q9?EoBjbUn_sJbF~b_a~T1kHnhbYV;=j2C_R=FxK2gH?vk}E-$vwyF4SbT{u)x#|RaBT7@oE04PNLut?uaF^&G=TToWp?SKLzkeyW2-9^@Z9gJ zu8Jii$1WP_9Qm*Hs-*6qOLtW1PBQf z)KzM4P%fL_)q?kaw{G}q*uET@bydKa3i#0uN$JzM)wkLKtxA6`>%?$qVY? zjxdIHhDBIXRLAu<^wpCP9kkl)*+-1S8VVj7sl;w_qy<4@u%A%4sWm5HKP^-Yo(J5H z%a$roH8pqV($r9^XqQZc(5a|v@a&VL=uaE-Pqn>?bP$s+)PtFZ-onn zC+6r_EZ4U0K)lKa<4}Dw1iYI#k$KE@Cd@nhjnTA}8KD6JE2hK+xPdJoR5)%df^B4M za#>qMk|+X2(l0N3Yb!I8AiEumOX|_ zvj6t+e#ph{$+Q5sXrZ7)0)CKdTH885e!|Y!I`Ho$ap2A5T}q_hX|Hc@(KY*NecPCF zf6Agfr^_Z8Hbhr)>7ym_hgr{iXeo0Ngc4@F#(Jd!Mu^5xv4iAZA{qWc+72j_T71f8 zfBLdTN^Dg$mS^E}B^RBG5l_%3jxu72>Td}feWeyrlu*&VO>i!-AO=Mrqj)EKuo7G> zgAl7?dRJjF$5VX;rVs&v#U;4}qKwVoBUHg(uvyBm&d-NvO_)QmD6iwiz@Mt~?T7Hd zl9m-+Dhn|mph*@o%=Z#PTZW5FVz3(57Tv-*j4XOHc^;gD_N@PND;o6%nY9tOW(ZH1 zXSumoaB@r6g(||i&=f&F60nIR^#$5jQN}IXXv1>ynogp%F3JpWEN~4aSy@Qj%>FmO zi?lhS`gq71{xtCNoOF4nMxf=5v1nTmnE)>+8jeV{*j;doOsy4QG%~H(75bn3ru5WoxbTsapzeV2hmJ2lNp)puugUyfUTG)@ z<>z1PjJ|S#e7M1~WkZ~rVh-hiX#jCF0dyFp(*u>7} z(;`T%{GCGXz;&}OmosF$?Nv~IQ5PG(2xu0BVX$m?m9?0(VLFm`XVkDs!6bwhUi~V z%(AnZo20#A#kzz95xqWRt&y^frg6}BbSEwZaI}>ooRF>5VHR|6N9)S~?lP^XUf)>F zKIeA~P?Zy{ZAN#j&Wo2xg}=>62K)B&^Wx%)@5 z@9m3w+|<}zjlVBT5V~vKgX^M=Us^)1xB9By%Km})Z7ah1e+3)se?uIy{eLAw;x;&t zx?gH$H*LU<<5g++&>(9u3_wWIC+x7i$4r3b*BcJRdWtuaWS(n#eE%eF(n>83G=HAT z5KHW*uBnu1JT0jY75H)Re|*PGbl!r?xP4m}BZR7vF`I;{Cui%M;FJAi`tkU`d|?++ zfffk_*?{*4(2IR3#U=s}w+mqYHUe4K1CZ7)j27L8O3!(-2?{Hjj$JX5C@GT#bNan$ zs(-k9=mvD>PVLql;%yemv90^c%57?pUSM+LkH#TBX;Lhw|Av~ms*waX3ihoj4QTV(P+gxYML(2AgK!BnT8(0Fy)kc2^%%QOjPxu1^ZEf zzZrnU_Kc5M3|Nz`k;yPx0Maeh;Fv)Qsl#-OP1HdUJrygPtk;SzACB1O3Sa(#Dk;zN~CBkGjfULhktdp;k$t=*Ud!t41>xR0S+9S+yL;PMj1?MmS!Mak8>VSP;;U zgM#3ZafTu)ri4~ zp@~gBXeZ>X<{iUv4{^-_qf5Fd9OF$>YAY?gDL1=Y`MdcbFQ1f>Tw zbVP%w?8owqB;9t-nshP@+_UA zij(Ilgr&SkjtI@~N1|Jpt=+=!a(z*PJlKKL;0(E9AcNH>y1C+_hvQF(1oJ`)UU~lH zuaH7}Ytqw`sSkbZA|(*oXsTAsDPgs_yd$Z-`v_|jkCrR?2y?TUsJ(-C@3}!!Q#I?$ zyXNufm~n}f{f?BK3X2Y233{y6%EUhe`EG4$E{53!LJvUH6=>-Q*so;1R7R@1%G-(2 zltjqmOj_zgeT+aQ+4TN(R!GH28}Rd4>5I`IR0U&p6vjmD&R|y5k%%LTbW1AmNI<%`C9c@9||z)PHKNaXI)@Nq*_avAA6I=hyi6ogX%VvMv zdDa%pdDh(4NVbv8@m7;V1ChmJi!0kS?9}fIT#$Q5bN`R<0p+tT>p@?PngS5xC$;8e zx(jXsv%k0qJPv6)%t|)eW#d_5^?eir$d)G_O@{13q?qz++D%8VC&x=PEh|Qi@Q1?zT!-M@Mtcx_D5Y~BAm)g!{QQT4$iM@&P;)K z4MT4&cYEfGPh842;Dy#UT`dzgx=NB@$&;)``9d8QA}QmE%ehb$dom+Xei4}FX>zGv zU-dd)sZO;_Yk~&OmuSi*gD#F@CYV@M!FuxMQMBIogoZx^Ye_l_z|X62z8dEz&O22E zqEdBY7U=hw9m78z`@8590-h=BUX|oAstEwPx5iPfSZ1+b$;n9P@3CGOuYT`{c00|j zm@~&d=Gh_Q@o!L#%tO{Bwa*j_i6adK z9Uih2Fp4oNDx^Y|Yx}GctpG*q90k;wqrPUUZJw(&&MOg)SH*BXk)UQ|#9 z*m}7*W1z4GjIdDJ-vo1iKm%>Un$6|Ouh!F`<}h1dFQ6?Z&R~<-k>42K5b|}2cX;}B zrp9(JtrTw}5kp=j)Od$SEa>ATQyF83sockY)2MHhTR=%9x^xCN9kr#scNVHRZO@EJ z{yyK9Oh|tfHl7EyPb(x@s1%zOPrc+;tFctY`4F^XU6&aVQ`Rp|<*@O)w%{7`bOj2$ zqCH_May!y>9gm9y5ZsVM7nZuLJ&?p4>#(zA6rjutUE#vIq6_3G*o{2s^gS35%vkTZ z?qvp)*LU78!G2;aM^81ut*TmsyDVkUYy)J}6*IhRKP;czb+f-~l%5LqOA%%yN(31C zIk6_#g2CU|Ey;s`!S8cmVa=UKWBM3`Tw{dt6+yGN|Clywsr%+l5~`RkQd~qO0(^59t<2V3VCglHSC zo@a%N`uk63rFEq;9{g2P%z5cH&t8T4odi@#omkItP*H;jT*elyb+yzY8 z66Rp5d$V%~C+{A=)g$4%MtA>B2+_5%E8(|K{bE7eB04nv>$D2d1vzs9UBAp)Y|63A zE7m3Ynr}bPr29y;3%| z0d*_c%KC6*vvP*6i)5&8rsxa1>>< zr1&e*Kz;pz>F*-PJlC|JiFDyGDIxqkoXV;n-(|91x|bNJdJej;QC(#)T|1oi%LQTe zh*D_L*-$K$_{@;%#qgeqf(Z|QCYP>>JnLUH!@`VskW6mdy%~V>K$vofo=UIXf50~S z3cS|5om+DScos2U1mL2L;GAcj+;^(D&*s>B5X&GzuuWr zsn1R1K?UTuCg7YWlmQ`O3v10}DMb9pB$j$YYD3tEjQ^hxD0tcoVn!c4dk>OpphV1E zKrApl8LVW|5G_CQQ=P^sTccOhLnPphPTGP1Ia|cSjw@f5DC|3c)XvF$9MkCA6g)Yd-IQoB|*`)X83HMqL0Vj}3tP5%szKnkjn@F+QqlTdZNq1U{oXEvAKe&Q1XUbd6E zp=H)7aNtNz=@;;R1$iD0vf4N>3tNo#Et-c(5^`t9$D$k@h_oNE@XP;MW*oJOdDaT% zkUFQOMND?20G^Iu?OyoswQ7 zn_Ojo{}mdPx_*zS86AboDsHSkXZ0g_(I3EQC3(&tGL?tzstA%9n9R(8pIJ5}W4p>s znIc@Kd*7)phZU^3Ws#Y#yaCU<*fIRHN!O%+3&-bOerObw(jl+;2}qwbf&{v z&wv66hgoiXSKM_;Q(4dg$;!-FrrdpOD`iq&XeZ!c{)^DmKRyakU<15D*W;O*Zxh8r z%a5Ug)skb5T~Pd+k|_2U;F}0!LIO32f#j|SiE9e!hDdxUn_yhsTK}1;S8{>v?V(7{ zF%|L&oIdlYX-ySsev0Z>e}d$nSOP+8G4N(}MWu+BCPar-BJTky2b;iS``9lO9$LKB z_I%wA_uS$;5L!*7;ju*N2T-1V_*vyg&^o7dVT$0V0OmTrJV!JqurE(EqboP1T?m*U9_Tl1}3joSr0vNVfGk-R_^Wn%xPJPvF zjuRhpJ^=$Kw7GYhrgKp(zZ8gt3EDWWC*?_$goM6v+02sFsdhOG1v#ycOgj3)5u6Po z3fKTpKGbalgyWfsnbT`~Tu7X#dL2QU`JfTPhbkSs65c(o6+l31_nvhIj=C}Zbmuzy zu+h#+I*(9jnN91KDSWN}^R<@-&pX-s6eHeq*9AJDV|;1+j7p9cO*(RIM2Ks*b2uAl zWDUFle9+3}kkrI#yRoQ2fWP+ZDyP6!ctq+j8y%2MEO}zgt8!tZ48LXWldWu}L5}+v z#Cm^R*mn??r+H<^x|n+$!jv@v%U=Q`DS_)Jhfei6Ep$`}I>8Z|Q-zH75PriiwTNaD zp0hy=f^ThYV|u_V0io^XW;XEW>h6uJz%q_r{11Wd`YU6j!%(j!1Hw#RlSUU9cx8&K zX+s<^MtESf2g+XWqF6w;b|mkUZLGrVid^AORMYL)w26HK!5#r*#2dpN*TMmgPn6Q80)5)xjN zAxx!J;cz+-r<>-^Q8QF9ubV2m$13sN?+=-R47GHn@@J%VHawAwr}=W#0My?a{A9ERK1aaPL87OOVZZVvJb;|iYWvYmuxn*0jxHsmkbjL_QTF~7B z8}L)DV|2y^gq2ZP!OU9HeSMF>=hXWEzTZbW0HD16GF6#GGq2bb@{X9T*3H1~fb2@p ztn1}|cxD=OT}56My^ETaipql_I@WrCEfM}N05y#yiKS0okU$UhW*C&jO81gX5mP4o z(B!2{fAmL|cmuD4w@~jMEJ+DEM%--jkJbn+54O!55j5#bVuC zh0<97A1VlITHy(YCaz!cz8a^Q}*K; zI+vEd8oYV^wmAeG`eO#$O=DB)6qx3hgKcL{h2k(rm>35wIcV@@OI*LzLm zm(#w#c8=%S=Nx^7rW>j>sM2vzXe-R0x~ZQIksS;89R+Sfeb9Q702=`>-l8`)N|vd} zc}xQ7=i1Wm@bPXp3?RcE0Pqk8mN z0;4tglbbz9Li_j;Z63WQegh5m_Vh?%A@E#1t8dnfw&9H9qP-m z?$mVZU>5>G5oe};DFd@XuA7;r`{+=dO@JK*QcB!=2hiUSClPjb9<#;<7&Vh_x-jAn)r3QL0Q|iZaLYIQl>EqeUugU}ZT} zrJ8W!BXIskYH$;^^h&aKdHUo)gZ1=EwK*+U0zv#Lkzx!1%@LLw<3Y?4F0l;4uQ7ce zD{Bep0#ecB)X>Sp3tdg|F5C=F7)*@eBDzDrgD7zqw`grZ3=T35bf5ok@zTFh!6xJ7 zGEBcQR&*TH7d|gb9vb+k2@W3dO@yS88USdqk}1BOydO`XGjwNL9ns8ZHqWGKoljQQ zv5y`}UHl(!m#%hFu0_6za_BRNv^qO{T^L{%1IG-N0S1^a8wLTQLOu0V!x|8-JYYTyzYp>{siZ2N8>PHYVR zCk9$k{M_iAb{m6@oo@U>YkD{N~MbA_2@c_Ju<@kuH0bCuE z@nO=CQFk6hUQKD^(5Ig&))&r9r&vGl>DkZS_4RShr~8}J{m9AZ-~A?fR6Hpfl!EXA z#kK&IKS#cIS3ZuMnw8_fGgV@2bx+<>?D70hiSQFBU4I`pjM+%|-;^9=3LU!nsPp&~ z7IcFABOY;mbiH00ap}pWMt>@g_r)dgKRjn%ZOujirSJ}G6XAGVY zi#kalR{x-~vRw{A)8}l2PWnUCQz5DNBS-=T;E@#G!+~7?WBqt ziMp4sPxRbT8)u?pAY~MD@j^diGNI_N?T*;REEWjC4XfiKed_VDFwiH=Hh>xmsr8B= zMS~vwh&ThGbw+toKq7K6;-(N-o7Ko9Jc1~aRZ?)D3s}eSAskhsfK=fH=i;hH8L%ew z;r7Vu7zmaS0~wh$#M4KVLGp0RZ6Vubk`}~)Y<`^XgF#TyW2p=*xdN{B>1Rmu+g%sg;t!9Qd(39-B2SP zsx8y*M%~TlQ43BrIdPz#g$I@B8TnoEP)J#>cqOoeFJVji!}jc@vZcu4 zW$>cdbFXW*xD7CWEzD;C5uG7O=ZIPmR6lwm?@2^|PT|2g$_OicY{#_Y)nC64-zGL! zFTZw6uk*nc8+)IL$AmnktIe7#oRWO)>*-TV;Pu6rWJ!+qklpZ}`S_|G=^;u9t$~KzQOu>d0>%`^gz6omw zhxH#}(Bw0w@X;vqWDFIL!mxAg4EVFul&TL)f3kV;x&P$3%VJ8i-sun%q^c#&s#is< zY6K+?u_05l57jJSFif4``ZxtQX=kXFHXbvM~@d&SOfBf6KN&o-YnQHk$>lJa^Z32C8M1k$dUAD@%4yHy3Mw= z<$*)mwnaZJIi*CG3s^yAfudghG_yF`ec1oz;%_88+O79=5h}kw1?z&1m7Bd;nuGG{ z#{0O5iZh0wP$O4^bBNx@MC?dI&50eH{<(@=f$|qi;~zlH37+Lj5x7_+w8)kU^s#bp zoW5q<$bAJK&7;I7AHTD$0+4m217CD5f<93P1s@UhL%I+u8mAOrj?0qfoz|7A%Ve(mo1Tqd&T zeG!sozEm~?)Xz52UaR+7`8dOqz+|#x}Yz7vfz3Va)K4Rwqcl@1_RrUE2fws7B#u#NOtKajVhJ&i^|Ck z+ViwsXa5CEB*|O9Orjlb-Yv+&jsLVHYomPz%id+RYI;KtFq;#@!AHQ7HX^r zxGk8rs=G4h@)N66d7Ij?9Rkg*(d`~5U^9tUCeto1OCLp>*7F7#xw)DQj&Tnr;=;T~ z^4EU65Yc1M-sfWW);`fO@_<9pr28Cgu@w5rm$kM`4cfzoQ|9{9t7*NyqtL zBpoXg`~T`U{ZDLX^IwO?3-wucI3&0CuT_IUT~MgnVY=Ee=+V9lAmhlykp!0U$<_Pg ze=QnoG7lqU*}}76Y0qlWrLj_?hP-@L^;`6FbHC1NqD}u3-f{CwVKj_X1fXSMST{UO zT-tt{-CckFKC~!~WbXIk6h%qX?2B-zPki?#HQg9z@w076oo)FOBzb<{(zr~iy|08| z>LNxxr%!1cqQw-uJHz}R`)I;JxHrc>xB; zQB{eStFD=rkp~ugjJoEy>ZWIA;T-+?zYNfs4g#5Jm=0?(Qh@}6xo*xRy(r5?Nm`7L zefCO88}}s)CQlD~2NrZ3iOz%ZUu5ro0={W~L%L@lm6m7>Tf?>kV%3U*@~ubTfLlRV z>0|YBi~R%%1(&EUZccd~1*DkKM*LSVMTxYZT8ikgo*z;~B@T4IKln3=H$qJVGmUcJ zH)x^9G4|_FBNU8TeL7MbP$$aq&>oI}UU zAv66Y*M~{%li#P~Kt^}ST%4nh5Ac-BmOXPLxS*4lpo;dd=hP^=`l%vS#Lol@K-6it zMQ=_Dm1qx3m0Y}XHFb;1+EqHYGQTqw#DvY7v==^1G@V#JnhhtCO{4O2AIzICQ8z1+ zVwDAm(_n`iC*RVc!KFkS7MM;Xy8aEu<5!hA)m8v^DA`^y+u2W+iqPo`aKvJY5`+X7_fX^&c6QL*(2bWTE~|f6 z{QD2{2Ut?@M_i3xOgX9Rsp0RWPF$79dJyk0e%)MX>8yxqTgShBEIDbbP1Rw0?K5bj zf#^z(Sj$DPHZ$+q0h>*l;JnX#;__oCxps(P!DdW@%7pcK-@oc_G)> zE+n8@b02~;UJ8a^K%wVU+=Fs>`FQDZZ9txq`z#jgLUqA5x zrz}1x=UlGf4Aa^FV2%BQQgWWPvr`ZR(8<1%lrR`+y6QZX6q~mys3Nz(m5Ra@v&McJ zoRMr?zFktZ;Kj)vv+(s0gr2*zu!YZKg_pie@ZdFR2f);XBUJ>itk<>OX3Us+X-JRU zX~_@f2LnZIKCU`~=)E9Pdn%wbNbI2$(Rx7h6k<;S@vIJrBUYgtLA~C>AJhNhi!B44 zY!(z$s3|)0;{03h* zmu-Jtk~=dhvB8bT)#9#wA|Z=o=QK>Y4*-h2{7{x=H%1rpafCU<6-at-c(kEpGJYeo6Q@SmRF`n8^zrp*UDbyG%I@1u~WEu-GGg4}d$sxfAw8zVJKou&=bcuZ6@G1D+n z$Ex7h3>Z}oA--x}4}5X6x0LWTS5&MMX(|rFS5O_r2errLpquKzMmXH=#l}ALxoi z_fdI{&Sr?#TmHhDf9$vX_0i*T$Dr$4C7gyRJYy$_6$+L9qs@K~lrLbN1H5>X6EWAt z7mS=UOp*ioH=gZMH7?IKlsS`0SG%<569+NacDfK<=c?1jkIK845B0LcyH{S)Xgi+h z&&d8#%hhu;sK4N91*EvhV%Ylna$$(FM%@(WqofmlHNA=9hek^PO^64szm18_E7aZR zj7K6mY0B4GtDMDWLDB*Y1L~87k=aCkWSJZ)?CSDiC04Po4&@0+y(B|&>E$mOD0(3? z?q4F4?%f=GY7gjaYMGkT@cNfuNk7(^z5r*}$veiX0V(Rc)Z(^s-D@hn>jk#r>+y(c z7HW-9^cKclVgi#NK=5u#lcu(=42*f8G)dYCKo9Lvbb+}LU69D68>4yF31{$?~ zeL92y%ka+V%JmZi`Tb0e2X6lB_ej4|BRlStz#l zl2}bc5Q6_l**nFG5^dX})3$A|Y1_8VHEr9rZQHhO+qUhu-c3$&le0heP1Q$@r2a?m zjhh_xOr<8`T)UW0OsCup23Z=KnvK{Dap$-+6@~s?;aytz$E9l605qe1DUke?%z4HD zPbT1V9!PWfBO|PVIWYEFrBdJhY=z|R6DWdAf9iEQl7tXhVEmlIq>)F-`-WxO2dOl` za7K<<)>gwP?WF_GY^Z8KMeZ+0D_3pZ?qhx)Rr)1_tnZt#KI-E#l3>n9ebM=Jz8^0_`^SO6%oQ5) zd>LU&yt@_8FI(e5k#Y*iYv>BVHYkdeBK?za3xzHzNP)MzHh+nXIkxMFf-*2#)*ENYBf30j_mWG|yd~$(kI%np_#oIQWs8XcISL z1fdV-5;m|7ANZv#E=m6Bz3fIwkhk7mtr06?YWhp&-vz{7{IpBPsYDWw+cnHZHo!S! zlU4ak>!@T|gl5u^59j17|B zo6#c+jRg_fN+*UmjP~6GS2?5#4goQ>XNNP@V6jPxw#cZ-(zlDvQD1s1?}5DHW!%AS zEU6cFQtM~T93z>LCE7gTT>_Rg66r^<7B&`yNr@F$NDy%b>cZ96@TevT*R(KFV80PO z`DM2vXZ!OF<3Vcjl($B_kMR>SwixOPyJ#^LYabJD9>?dqdP?0PWy7-+=vqLWXJV}Fe>sqac-b&O183p7W-ZDG_mX+Yt#|kl&A6Ju;q2NMTa{?j% zD-lJ-1@Rxc3iI-ZJ3g8B9cqr1wqE|c& zClRAOv%1r_FD^Q!tc@U`RGyT=CuLwbA$U?KW)6b2_N((O3Klj0J#|^~u^BfxO4-7( zp={ya$8|;*7q(Jd@KS3GVvnvHKpB7%gZ#rLseWD8G))L% zjm#7OXOl^5?yr85p!*C=cmH26I-)0JSJS*V@L}RPPgASiZ@l~~E0YPhS0xu6gLV9m zLrUQvMFG?W3K@7(H9H9kisWippW-n&)W4DxVG=>v?DPhqkU_X5LGNx*UbuEf8AF`l zP5k;28^7;!H$+#eA}(}#u2f?&e`qKg4&%hk1vpBmY1KA#oU(OtYX(6&Xn{BW)H{oN z&KTo0#m~q_o3!KI{=K~Vu);ObzbtyLXJxj^o*Z7GBuM2ihq1~|c;Z4pZ=vQghyTEQdSKukzhKTvUFj2U}n1_F9x zCJ|R9OGLTl56yS10L8azi2X_cebzd2%#Rkw98tCCW%Rl@23~olLTQ}qWkVNa?X404{0P#7uB{!IpKI_jg%e7SRRWx zsDybKJ>^E&A{W0lvj~`7p7(^w)WVo6E=^#CycxI+=uym&uZG2hxLsOrUAm&;9YUI6 z(N(&!3g`|xJFgVIm5Qe)$sCKD%to`!k!P)0aZ1d!phyEJopC}j&y8Db%~jDzu<4{s zr@A2(Zqm}pc>uf2F=vBaf&S;AJ=rW`Da7J|2XP^xjdtAEVbnVF+#aJ_-01j=itI>@ zYiJfh;r6hC$f~>j>5Tefex5l7h`)}cYLc-sq$=3?2n;A%`F*=r9Y|J()5*pCWnj^c z7P#&xhoOkwg13%|c1Z#J@#lm@A19g~*b_;r7iNho!55HtJd2#4DZyubW)ak+`bkRh zyQjNI53NLR38dpY!Kb}QFK5&mdn_LFyz-UC+^FS}mB4>Q)ttFSQrt+rRg>z_A^o!W z&8z$1v5K+&Pbwjj(ZLm~jScJJ7Id)M!Ni7Bi0$81oW>%iv0D9Vaj!(Sp&VsaV(q_fcqFSdcDmm5ZlvSnPNwzS3(78(oTjcY& z`EAD+4U;&*{X<3;i9qB;=0-+5rbOmaNAg7BfV3A}c2lq^Mjl}`$Y`ghxtEzJA-2Bq z<%Z9Ltq0o~u6#!5CLcI9NcGOTUm4uried!hQ!q4R6BiF~eE-9Be6ED=`6nkrMFjlG zUuGuIu-n<+KGI*NgkOPF8o(k|Ie=)Ly&%eJB@0O~@!7sxJ4}KsL8j|5fb?-p0?0#SvlFDTv=;Q5UpL>^JGL4jY!Yy+b zjk4v#)+Qn@dz00w4`^usWy1b>4g&NYeL=HD4I+O&>#yTQ=g~h+k2oE68g-ycD$?}$ zo5b4&2{bJ8)lE#{$u8A6Ljg3W+dCw7BLUUd(zs@{smHvPlMam|n(uUz%S?Nn+9{q@ zlMbG)1MxC>&sy>ZTS}JxMWr1*I!y+lQ0463SGUCc`L6h}C1_tTaw9cimgsWG>jrIK$YoeBD5wAWov!96(1GVtr(?HD=a=4DMhZ zo2sQ4oG1b8BOpD^p_XlvJo9)--7cx&DiUIKQ)jMv6m?`$P#su3bP@UL3T3(|i#iBq zied|%fIY-l<&(;htUeH^B5QW;uJ(&M{eTZd0HKHgPe(y%|9N;Qn z#F~YKbn)e}m}D9Dj8gw~zx(v`UTKl%SiA(Z6M!&Q#W zbKVG4k~3W{BIfDO4L`%K+F>6+cn>@AFurtzd4KGC7mPHZ+e5J0!U?_*Pn9RVbhm>* zm{w2%%paa#eZT#27${^I^?bhm>hRlR(xsH`-ZAaRbaQMM?tFJGYV_a-4z z5u%wL1K+N0Zl23rZpLDavG*eQtNj^`=)TIE0g651kX0jDnuumE?NIM>;r$mf!+uCi zLfXAqvwwEG(}Roz6*gZjTuOjakYF#ugY-F8bAmMpg$aUaN1g}OO!GWtLFSY~bZcd% zUM8FF=l$g%6?#DLApj~L@iPpw(AxOj6`!`}I|rTZ?f5c)>0IajSMo`S5JCg#=B?*n zW8L#Gx(Xf(3zF!b3Dhdl33IiY8dk?wer2xVkrfJeu9J);&Pu|YAmnzK8HN8_vdQx{ zK4h+->la~BlzMO9ru+a{cH_Is^nuzq%MnGS9_j1c=JoaJrE-OODcq$h za{F_KmNbeZgTMbqTRpPmw;v$bvR_TH^XVVU+?4T@(>^?}$3<3@GNER+YZK5XY7N8<1xiekwf2A)aWUA#m)_?0SKr$D_m)THz zYJV3XmZ#f(GL^TRH*7agnyS@&q(@7nTO<{$b=P60L((}_C0{?qD{UfvlHkDcuEdI7 zAiz<#XE90ghKjX40c&QbiTph(uxmkgisE!BLNjCXl_FEiz_8Qh7HB}LDV3cS}`ZvGh4GZqmH+pM=1Ong=P}_IaNG&q5_pC z-@Kmx;aTs+` zHU+ok3kXNM9F+%`Wnw{|riCsx`!f}96IfU$*s)3r91#_kn2>_}c?h*AA;b?@AqFcn zJrbpi55Cib~P3;Lx)Mw%)a8L_L!@zfBi-VT(=y z>Ik7kk|`{{BoT zh$)XR?p7j7XQ`0K04_>iyzBk9pq_cNrfr)J{W3nWQ3?mBs9~~6IZT0&A8L%N1g|)_ zv0f#!i(lQY_k{P&UaVgxnQ~AKpP9=|vtGfrs}91_+o7#m%(iWhH}WRa)OUkCEgG~B zuu1xknwW`dqQJ7v#ElSbn(>jv9zV_N-q#hTl?qn^ls!Lj+h9{S9Ugjc$pC~gJo-{n zQ^Od+Issgk2~dQU1B4tJwiq7WJnFd;S^q=c@2iPb0 zKl!IdLP@hm?4pE4aCL>7M?KPUL`N8}N#+*KTtkmGTyl>aK53xxjr9QFb*GG*vO78V zTcbc$ht}pO;QZ|pe%)~V9WOCDlWmthh%C8fwqEHK$@$iI6bD-5G}t&YF(=LUcX}v7 zlj9TNNr^hGW-O0nPsy;&ILPhvMj{$*^`4nFB(3%6FxUI6OXkxOLY|p;3{hsKc0e9j z&HK)6Y;|sVUC*?A8rItzFu?S<767cCxxhRIqam;mxHA!QuT{z|2N16JRdTok($+3B zXX|(thwa5xPjlcEM|V|XmPjrhGcO9*HX{bFA|>^TXBV`gwFZ|L0PjCNH>9j*V?8+z z4S>jT24H11Cag}hCPK!BtXsRO>lm(e{aNAB!0>^kGFE44YkmTPCqWTPkvrU5+q-nO zz7_Cl+_XE}+dE0F@NAKxAAZA&2m6DD6RT6f;F>P%>WF-a0v31qQJ7~broLwfLuV<# zYmSWDM6trH+?7n|IvvOK;6-}$;q-2TMBG_>P>|h8Ic|cQp|b|Ic=N7wipyqqPV z(aN*?8+Nd8O)b5av)qC!#7JgVV-eIfELo5M_2U|wq)5^u`-)%Q$Qu188%O2yP}7N? zJUsEa*vb4_a1t1hW2#9J^iq@dZ|BEdwT25y2!<{RX0_QxOJOy|cXe`t5n~7Hlm-At^E)xy zhhA5JI9$gFxE#9A36F#w8s#U{@ag3Wp=VENuJ}vZjWZK0o%Py{T=)f>4*=5$t5+Vg zbMx=^?T?2Jr=!QZyv~`|$7tjt+fWP3lZX!TtpV7go!wgp%w?NabY1L}7p$R{t4r5E zH9U;Ynfr(s3x3vJC9dL^sUPAFW}Ui0Y(8;3;ZVVE09T?#%DlPCd1ERoB$t@zKCyvO zcv%P(G&Kc_fiVj1Sce*S`65 z4uOLHUz7Wq5-F6jpPeqyHK?OQ&EMpChP7`ODpm>#nBCZHLlSY$X~BMJ!BrHwOuOG+ zcv!pPw>iI7&*`^0!M8TuOEF9_Xz~`+Ca4%itIzLpqtB57{{hndPYM8LM%Mot($$u- z#UB6v6#!ATBryL*y=`a=aU7C9EYI-j%vHcM)YTGwDL9eMNSuew$LB6)9_oa_d2t5> z9coRg73I~($_paBoPYHHtx+UJfl>|oZ#MyQ5V;EbW$;1^doRV#jBag8=JdnG;K#+F zSAKJjHDApFG}C4cYp!j@u6J%Fy_QOC?XGR=Wo7Qk?Tns3pYt2tSeTh~{hY3uTK#W# zNn$Ya{AJu(6a=rIW||pQg)K|+co8aXM}g3D<&rY8%Q-ikNVs;!90HXJVhEf;!D4Y7 z%|2hdl6by1wGpj`n$I5!x39{=+AyE;Fd|tr;2ebo3{&LVH3S{TEHqUR(DW{XUE)dQ z{Gf&&`2jZNUP($-pr^)FfOXz>KteVePozB|SsnY$kPlpJ)8c*KwEyEC&t&Z2IW)MfJVL9W3{ zQ0pV8z23Z@pR#D^Z=01sHh4n!-9=y86wufut=?2SS>K0O#_5=yNaYZNMN{Hf9;GKv z(3d8+nD6>B1>Au=hBzrfjvW9})ykuWgrh{^+MoTt7_b6fmB`6T&2rtQ%SBy0WWk|) zmA?#=MBxH_%;DzE_e2Cbv251~EHuGyc_lhGWXVNS0g68g){^tmA<=nvTpS{d1I239 z-@JFr0wp*SMzXV+IH09r)kMDw%ER~NHH~ry3G8O}Dol)B6 ztt-7WrTDN%3lDB1XQPmohkhM@Lzj{pJUY-Mt1)#2%Jf6eH6zP335?BSJCu?|aA%%n z(tA)DL4o););zL}mNi5@LhbMgAeH>8x%T6`6s43*uIDK5z^PS&PlcfYkc6&Awb*fN zW@Cpp{=6KiVxp0qO7soRG9^jZ1VQ^QEp4Oe=NFl$9 zFPSyp#zGC$E{1l=_XBIoc^NU$OcTjmUp8SfiwT(tONMv(91RkY#*{cS8ME7g&tYuP z9-Uft79%-(XZzgm#8AcvWhRVxB5+p<%eL`~tuP7)5(7$L-riv%+ww5?Rvl3cJz;u&jB);ODwu%9G*G@JGO-K$u-Dknrglo1N{Okm;|J7>#$%-~5Czp%rG@tZa?l zPrlE0@)}xveMj5FTju^;u-Nsq`qSMLx+)%)8KhfKdpW(N7-Un}nhMa&(nXmQFP&9F z**c0Rt0y!k1_irR9W=?(X$-Z`IzRY)Bsk(GHV}?Jww*@(^&GNy$Z20Ge-TL( zvrbJ!!t;--Gqmn^M2jqa@)I&!Le)FGJYEKMjZqg}L1eD#l*@vGJxyDnkSwb|U)NJc z1=#_8l_;i$p>i`|oI4El&xwma_hJ{EcP^c^brJZBfJ7&GhYt7LW$fEFc21VDy)oFh zY18616WzSv2Oo@(a2`taaMO3T64Kz5xfhi5AuFQGfiWAP5<$c#5-mpzFhr^-%~UxX z;(21%qC$Mpm(xxI%V>$Aulh(}vWyf>4^cv2nNp8a6VrT|0F4qWj%mK4aGagJ4iraZ zxH0l~+NoR(*TpfstV}vb*%+apG`G^@Gy!Q85o;{ADyzF^hqm?dl4H8&jS%IdTG?Na z{dnMo1(~G`&fVCn{|1}=*& zo$!$?b2bxfSNTayrsuYN3DP&)^d*fk#;L_tGnZ1jd_^w(7=oNaC*8FTCMtRqQ}k$n z-0Wms!b?sg`7JQ%_+w&Yeg)`Sjc%HuK7p2G3(~NC5*WhS^^@3$63>laG0q5~(!*Zev+H>v2Ufny9QNdKeu#ur5e7b?5mL8m^j1Vev zY=cUtjv`%0!ZCmtK$?Dgr-sfQTNr2QMOU3bqOCHl2+n|U?7E1jiEKZRUcLY>yfoKD zW&nDPy}j-EwFM#mv}56O&Tpy2>m@4ljr$=d?#e1GD%609vtwfqZx>eP%|fWNri*wf3n~tT(7vB{05A(q*x(*OHU#(* z0lR)@Bs_UPU}#{Vv^&zqS!X|BYDC!|a=V81VQwJsgZuVWdvMmv8v{wliMwcx3~BVz z6A&1-0W(Ue;4(6Xj1bHPq8Un2=&YU(M0jq5iR@a+nyMRm;cG)4Jp&#r_!pOymY7`- z5Hp%&F3XY$CE$2}{1BJ{9|{eDKr7sTg*b+|*aG9bFs5tLrIzeIXXAyiOf(y50C1lI zc5T~4AHIWweu}&T*nWhFQ}t_Qfq^03am3Ou0x_cy@T*#Gr-y^NX!zuX_gg^cnurt) z{_ODjehTOqW2Cx^!6`mK9uUlxm+E@ zaVAepR)+3_)?7u^QC99pZ#;83&ZtTOH#*s0+Y z6xz!bUpR3EB;VU}R27hb_W5)Ja$G(KZQ#`*;M#RqOzB5+6+jyl>Dd9QhxAP!%5nHr z1h0UWRO7%1mS2eAZ6-v0SYSY^Of3>)0F|%*(N zcb*wKU&_}Wnn((j4_tVEfk`S3()s&*0Y6yg{zDWM+kc8+XJY$*nB+EXwAj$RU)8d@ z#vz6tTH40}p`?|h{lOj?k%1rQoB&7_l-#|rHwEb6AFmtTXjk?TNfjpQFWLkFPSs1s zr@b{iX%rtS8xw1L9#s(f&DFBMl_^~U0&B8V2F#SQy~}*kzCNEu8&~zbOO3UvQc1sm0r$Rhky`r7qa5L^`ka8+4uGyXo8=oI$Cl6R@y6~>ihUsg9U z8af~>Tv}iSrF3Avtu9iwSM5(gT$VEqP)=yo6yIw2JhV0@{^pcP9^_Uu86(!2!BoI0 zclUC??~7@8_rdF_DW>gJ>Rsfg&fAbf#-cB0Ci-S|MZCwWS68E7F{CQg)!4pvW^E(& zyhs3bsXtRgPufR{Ug`!JfE<`>ckcfhYeQ^~4=KpDD$HUU1d9S0Tggi}t@lIFjg>jc zGg3hq9{MEQS!C-h506z9{k)bcos6^Ds&41e;K^tLDoy)1*nitE>&pmgdL#)qev)NC z0P8KmVM*?EkfA$=#;)$=#--uk$(A!Fkhq{5rR>f3A1;`XgcCrQkchUm>Wd3C*;Z z&w9sa+F-owNkhVGKoQ8K8r~wAL5Yk zN6@V_#>8c#sFN@w#nLt5LBx9sy;)^rMb#kx#?#Akbz_~UmI*C^AY0R|(;^eN-p11x;DUxOb&5zdh# zPmBH&_?lj(5058q#g$jdh6PMjeL)3YRSZyX1Jp~eYYYH2qq5dis(|+RA}arUT~gd* zt$YT+FLbkl60JomLJw8Bw~@1>=J9$rQvk3Qv{t%N;Zl35WbS!J#H57MVKbwslCB}V znm!V3Y76>g>CMYxR2M5joLcoege+=kSe@u`ueIhwI)Ee%ls0|_?y#@hU=3(VC=!vX z5t1Bb0UQxxuq%0-S=fMjcLd4L7Pi^Eb4>aq7;LwK+;QB9*FL3Cd?G;igP>Jx2|KUU zdBA(-9A&}gIqus#RVac1z*VmF6?p@L#F7LI0MmBzLI}5mUt7aJXp{nh%fx@Krd|>l zVGMfY+UTp`Ip)RJWPTyC>SX50)NM-%ml?7LA`r1)4uIQ)f98dI728&=qAKyVmfGp z%+iKr$>oyFd{zbx(V{b2ep6A<8cVQxguQJ|xXjy{r5wWUg$dG`e{xh?5!!YDnRLnH z$*|EWN@loL5X9AR(Ez7KeyMV4kqlaU0CkJlF_Apf)M#p^0{_ z=i=~U_^O8MqNh8%w>Q_<%*Tf#ciX!oTW=;4_>Lt?GN1L52`Bom8gasIvev}4D|6_z zDR!;)G8M;kst6WOtS!)hRnnPF=FEZd&=nv2D}-xmV`Susz033c-yIN37e_}=+{35K zgNB~Sf9k+iv`jeKfWNmX{doYLO_sHoexJ{gxZMVcBp#PQZtfho0VwjL-3n6XCOW;(zmyakQj-j{=#cOiA|T;XY;BaX8kR6wXTwg}u=gEI%%_f|5S9eA6|s zqcq$7H~5QEr4Gi06^%&X?d2zpa263DkT(HYX-ilqMoK$KS+sx|4u=tF1WJ`?!;j56 zcdDpTQGM4HeTRXc;z}gJ$;StRpkRek(}z$Q2efQUwnXFcC?=iSoj;pEKc|jGD&`W7 zn}zWiEL$!Yt}ha(P1KcIIk%fj%beQ&Ob+Qvn>NQBFrEK43j<$@#i*A&Bf&l_sEq)H zeO2%WBEkc~j<9D#H7&KCL4YJisZgjcvwiA}Se0=kHe{k}h+*g>tp0V(n@xbo$*`6rbHD8q$}UeRM> zl@OzFTae#tQS-w`hH68Bn%a?%`}pH-ymD{7*H*{!W4 z)KndEW^Z}MttBLo;miWU*Gb`SxSB^w`0){$;^>0TaVi?`*dagDuE-%K;xNOPG4-y^ zQQBJ0!P}P6=vl_`EmpzNC_23^$U zP52@^k7(|(G|m@0ypNxrwDGT9fnBS_Li7E{->E+SzIN_oSk6gW}7>oGJ=6EhUsUO%uO>Y?_pX{~KXr{|}-`1~&Hpo=nx0`DdF(=)P35vO$V4 zPQh^y#{+7D!y*u%lku7a-y6zQ7qDt?*g9I;-5LF^OZijN+(1n(;;68)V8;IV?}?q5 zzdyQXs%9eRZk&nXGf5Cvcfm|VlI*y8WA^0vX7}{`I=E*N`IiQ&2^XSiCZ(YZacgb; z+|aU6atWt*M|P>+O)1VAvc=LQs7RKqU#uxqj5TQEM_sk3vC~Z5tMjkimu~v1vEbPx zB8UwMY$xI;qFY+xf?}~yqh|Z*oZ2*Yb!b6VeSLCcZ0JE$+#UIV6ZWRq;1*&kQkYc~ zWkqzI8W~exq1F@fDi9wRhHtrMhip=zAx9Y^ukBum*}ROXp)o{Dj4@tlCZKrAfjEn4 zuny4cScfdQ{>HD36rEO(bQ`k%Ru8ZI#e;XUI{W8^s=kXVNHn^%@z|$@*khCk3!hb^ z++^1$`*@@!32hkK70WixF1XhEw4cgIo<109UUe1U3l3k}hcD-gC7wTj%t$mQXb3%> zKX1eoe}=qv7j2!A*ULW$!oaIqdX_2Nj@@b{^=kQOc6=U84O}lDM}uK3vD3d-4&(;3 zzYM6O-a9EM03crkb4$7IXb8_tp)VR~D7w)XX(lcXs0O!ES)ZiqMFEss@`e;pO~Opr zw=q45-7(9~?1Ovfg-9g_Pb_PF1@=a_(;x4pt{%AhmkO{BmD3xjRScR}lUR>L&>uX> z(8m6bb@Q7RP>43zm8wmtTBBlCK7c}PFF#Y{w=9}_=Mip7{TAK>0uFUjmhNSo%c$mJ zhB;m%sTa8)4?w=O&*(v!0W|mxy0jJVPm62S(^^_KtRKg9!9?tVsgb!T!Ttz=0Bsl6 zu7lbDIuuo3^ZB0*E9QcEw`P}ZBSr}d403E3Rme3+oc#}HF-WnRjWk`oz)S}Rq3s}= z;xvtuaR?H(mRagcih}9T^!<+@Wrx#zB0>65!Vn3-V&OMc1JLV%J>FC z5r_EoS}beQR3J9?XT!wT(k@Es17c#yaoBZAI5p%Q!QkS;1)z&Fn}Xve+?;Y zG9lQR#>gO`f`#&|!^vBv?6IoZ&-07fZ@F>rS<3-lZjGyvH*13rbyt9mja+I9p4eL+ zX{``lxJ{Cd@vR%dZe`%;zAU$EThDy7&V4-jw``WbUHPr}FSeAt=Wrjl$iB{Nw!aW2 zc47Yb#umM4?@(tB*2&+DY#HhMUN>Rr@iCdVt@)GNi(h|Di5gA-?VZ z$#gOg&G0>|iXV3=k3q*O|8^(8wiSztJ=rh0o?p<5P5$9l{P;v%*uCNtO-w8-;=3mJ zK4v|){T9EL+idE+V0+OCHr4x>OnPDyde~K|Rvh8=9@TRdf6K^U@IFPGr_CM%wRldq7QB_d;kd;NoNe{K zdafq!#qyK@?vGSXQjddqk z?#;zAvSh)<8=k4Fy*-AKeG{jF(-6M`RbGyr(djaGBs9}UIa6c9ZuOj%SdR{>)KfLobaCQJsV@sjlJ&V7r|ap9 z-U0qN@BeU_{s(0e69WVNe@$2EOxoadB5q&)(PYDh9GN4j93w&pLjq^eC(az&;DFmB zrzY%?b&6)M{Jf@o5n8-5k#jWZI3;`?crXh&C{%Z@xIoE#{5m-}haMV$w535~%Y_Cd z80#1aKs?g1f2?xhk?{k*cJHD5*DzX?GZ1hNwTW&j-Bx4r#sHux{)m>{a3B>Rpkw5<5u zaA+;M?assjvF}?1ItX_(zVTvh@WJ_7oyISfuHM)6fjc}IAj{+`x~gXj`ex4C=g?3$ zKwWa)WlO4r0zhP(IxHTu`uY%FUffnRn*QaCkDSv8^aAy&YUR=pzgx(73z#<9E0TH* z)EdI~pot)mbGDt;Q>ELcu_O=hO9q3bU7{xNl^HBo04Z$Rk7`VbJW%-r zy~x17+jTYwLsinPRLHf%Jf(q2RX|lO1$-s&r`h7@od;jKYynhd*NOc?wd_!p)65DN)StsC{zUBYlzt!$MxqTz!Vj7+ z+P3b`Jo+DH1hw8;v&MA<*ax|S=J;}wJUbG#$vscOt3HhV4iE6~80~fj+)fiKO@HhL zvK_^+_+wTM;9>Sn5wssuDt+)tEXx2u_I&P`48QFO5VJK9>fQy!zomVBFa7-Yxo7sI zBif`lBcizaaFS6~5E$UoGHKkvHgoy*z~lqb+ah?-Qw`#QxLiEpeN);%ol?h!itN#Z zE_N=TTNE!{Gpz@cSs2XN^jBnO(0=n4%s4&`l5Vnsdv{#%-@G6jRE;yW{Sw|yt_ zQg7=fCvXkvTx(-n=`aT~N5@KWGFt*@OoomQ3S6X2hOILq*BG$HU;AmD+y^maBsU8V zo8nv71oeP5e~G^Ra924-wggp1lw3`cI+$XT!yPv$%eaI{U@~aRxHwfVW@M$e z`;C^i8_-I2A77N{er%1h-|xw*^?8!9Pt7xD;FoRss72w}&OCpj(~A zdXxS_yIEUCb8*|6%EsOB8E@Etxm!%^NYm7+>k$yvhC;ZKyDRV&8LF`Cr4|hSl{vMRF;#XLLkP}PbT(7Sj;?qVhlVTR zR?uMm5~|qnqu^jFxf5j8s#C^Ju^5zH2Ais2ol~?{uYkp_gyoDgb;+;@{JVQ&a1l7r z^nZSt0uRRbzKPeey2Bg>b4+LkdsbS;YKVor)w8i&#xlFq1U_=uH91iP&i3|agl2k* zdf1^mZ3^W@OH;GToBA7=lh)w&6U*{Ikw`{kMjgXoY*3Jbn$mC}$Ltxv9+Tdw zT7R~ge!huVfyyplZKuQsS1hOq$q2_<_dGJ8|XDP@QD=0%~H?jUYF zL7Mywrij^f!hJze^pKP)M_u)RSJl9Ehxrn$qN{!!UB#GyG88D+PgQtKnXg%stNwqz zX-^;Fy6onHu(8DuvUv)b&s%E{-=a10k=6NzSs}w~GmyR#8UIR6TV^$;aMD{uBgU|q z#CP@>;4)}qm1kZ3`$@K7j~&?PIb07-%M^_5*bp|)6Op@p40Dw9$QC4T*Hhmp1Z;H> zFhRL;UU{LoOa*q>vyQG9G%s&X2bFE8;N8o=G;-b8KX?+-oMVrQUTtMFCQf&V-Hl4f zZ}B8D-D8jZk=$|Qj{FDtWREy(mb$t>Ngu|LP5zA@fZiOqtdr+;jU_zhVMCiUi#YER zwMsn*lhR1?vPt8gjnhYzk3ng?TY&XXi|iToJVU=5bN)c%sHZ2#LO6e91mATf3K9v+ zF5ae_>}h5C>C@USx&Q-0VqC6f;i%=h`A!neV&9EMU9S9grr^>TT>7$H-tj~yUvcIG zql53Opca9x{qk#SHS|ZC`Tm##QSCdzY?lYfWyF((amOM>Y+KDtS*=VtIhdd{b|ciY zw4cJzGx+`i6201IGYk`oNhuk>pbSDuVdCVwIuIN|hZ>-On107A^$QNvU{A~S3&iA; z7O1l9s@7Kz!Lhg+?zgjxnL+m>0oW28peC6*Br(8SrGancDLS2fA?!vj(g&MWbQAq? zpHaLTa!T`WMDZ{@k9C_)@(0aaM>xg5oz6$*No)Na&WFZrm?IP`5_&R{V}h9{l+#m| zdso+?OiZaF%t)jLh^fOK>-v33MhCHbKAgM`wUklQyU?p`?)*^h{(1TN?A+8FwCwu$ zDfW3hEZw!a<@2ukmwJ3N*!tRf>+@ZWr``-^Lh#Sx4<4a4yc+nP&d}KF~O$7a3 za?V4P1?6-y7pr=9oPc}#9GddMYRXNjJ zV$NWn+d_^vihtD@TzX`liZH9ohf+9?+9WuUC(H2uO1B8FW~F}Fe|}3Lfk~F_>+C0i zjmSrnm)C__(B^6SJ#bT$7*K>HphJ;6AKca`VEkdM4)1bKTGBC246i{h1@9?S z*17fY_wZzlS)G96C^JTJaT!KOiTY)tGHD<_2SrD2Q@5gMFDalejxyOeUwyiL|Vv zsmvNgE1PNKhZjzDCWD%%#YFaJgWwNq(?ge;xcWwDxR7EoNprlbc!U|z**AAny?R2K z)(lIEfw-IZn_T-$$*>DH6bIFpPOUuhbPsD!ive74X8mEC9He4GjKErvAZrVdq~Bks5qt}xY^<-)Nw6t|~(-crszE z`jLLD=YI>=(PXHK+L&7~eYlz`sXb4&VCOhW#skWR^%GgMU}igt2is_6gHdzvX)*Wg zWk?|pm|RXN?H~BlL-10Uf0R0yOb9l!QinieH8yjh4T9KK9?b?&I-kC4BIwoT{>Zg~ z-Czv6VA&VJ%`JE%0^urr43Z1en}Fndf6NYoiZkHQ^RYCS$prJ*Z#}w*;pW#aYtM=Z z)-iXMBO~HYf7{oJkb)W-r=UV;%YMzPG}#pOc#teP^8A?s<2_Zq63_7_5FV#iv7qqA z!pbL!9#Qfk2XEFZ)KOFTtmp7RGiqdo zpSRwjc|~|>nknfzh&IZ&_KUG-vC@JlztFk1ZV80SC@wHK?8*bRWj^ID_1mu;#YNr! z-Z~fdq8|8x3>`2Ei(0XyS=ADJHQ1ge~5xynkouuVi? zk{o4H6 zQ|ozq`A@^Pa+p*ftQm-sj{rhWhaOA8FDtZ?mI~fCI5;~zI2bxSR0J=|9{BTO$bcE3 zZ%2M`{U(B$ z2k8X(oj(#h3^L~mF!&2~CUA|A!;b-BcWVc>=|^z)iQ*bY0|C}{3pb~v0B+VEK;Y}Y z{0n3U@S_dqmm2w+>)_kqiwY#=j*-ZifG_80DJbKu|@bS=Od0l+ej2P5D)_u|ziZd>o=`^!L|&X02T`{N$S&FA~a zovC-1UW;OA{gdx*m-s|AK2?Q@-sD&4JvXn4dI@@O@?9CBZ~Qe0yl?Uk1pq>a@BOc9 zwy({e?MrX>2LD~|;&*KX6~e!a!6Q1P*Vb1y#8|$}{s%GEDnDP>xuBg}CWyX=+-J5! z_X$JC-@Wf&wEo+q-_4ufiicnA-(TMNg3iXrTlPskzh7cFCqORGUxBULMy>;0Y^*uY zVE!L$3y=?~xdwUD&EJ@E0>4+Nc>gu7U&m`R}g*A*o{ zy4!AXYXRL}SM0uNP=BHuC4kqXFF+T0jFsB(2cWiNffyHDo((NnhN+?h8h*?V*R>GsYZ@F@_WZ?~Bz6%v(b%yWwLwD$J8C4I% zy0Y)o$>)##T$GrUG8APBa^WGP>E6b!y5$M8Z)n|-y76h_ND)!kY4GO~S&B?WMeuVa ze!(b?l3kFBw*)3vQ!h>Kz>cgJW^?@~sTg8}6WEW&L%}D~0dCzqO#F8z4}`9icG?oSG{bP_=?1z=kyZzZ zx;4E4Hw4@zw7aWKucoxCosP0%%ANwXLAI_i%wF z&nhIPMg4{#Dc3}Z*oF{2Tt7u%`L={OR9;67ZhBHo!Qje^s%|CX+Iz9E@=+sBHCEB^ zXLzx%lKV0{CM~`+@tSiSB%BCuPz%wDG5xH$UgOC(SY{kA=k>}Xk23p%)Cy-cW`+I4 zuU_vY$V#bB&^Lhk-$w^7drkaQqTP?-ef$R~>u7>H+#VDN&94YPHPg|X%6m@CIx6^)m~WuN?yc1HF+6o zj^CP57S35xO!~d-V|EP_utGY?+YUH`_6;_;(DtuWLe{jgFFa#YxWqc&>i-{O=MXGd z&}Q3f+qP}nsB7D{ZQE8|+qP}nwyjq^=ocN)|Db0lCufqAFLSTGa+Fqei$OuulCRcH8kC@-er-yD%In$iS+Zvife=MKA`X4(>mmQ~YspIYj} zDB2;=&?Lhn|HXn*@?)W@HRC8eNG&MW(E3mdaYnA5yABoA!6b&Q)?N77{Orb4;o*Jl z0=^8-_s3Wim6pa5XZPW&vr+Jz_^AXTr3;x-X;v{={Bn>jeTq!43W{$>Rg)H{Th(Nok1XN}yG3NA0_xc5}+Qrq0cX^H@S znqnlmgYf!EVBQO8-c|0mVa_SMRjKT71&#I9X{JetYph{?iz3YZ%+pmMc=6Kq3&o~G zPg-fPb=qW@o)YC~eFW!|Gu!>!PVlUU6PAoPtnY}(g!rsuIIWXL+@X691} z{BP2L+msPy;H^;XyCOP%&y~KAk(nf?$2E$viZEfX2u8d8S`jY=FQ2VRe#W^edr z)9K4v#jRMZK8C_Dgf~fqJTVFGW1vRZW6)(3y&O@7UWpaMD#S7(8*-0OdX+XmLy!Xa z2d~ULg|(-Y-e+KSH&SoVhrX{|7nLW8C?8u#YN5(^SPrq5<3PXs=Vxr(nAzug&_7cn z&-N)COj$AYP07OJj}^Dm(_+7RPzx0#lyy1|z-X+^dPHNJjRRIien5ebJ|E+7a<( zb4c9!GHkY;z(FKPhICctKUb!2wiT6c2SzH9!2xj2#Y3m>{^ZRhXVGF}Z}q8alV(b0 zckwx3pC0rS&Vym$^Ku@GX)RekrxW#qXViuwcIPyiQbe5?jc@|byyPi_?QoN3@*Cy& z0%UQEBKtZn5w$l^6=mlvT83;PN9~}!6_p00AcQVA>@Xl|WmU6q=tL;Shgl-siQPz3 zsU`!i0&9m*w6C!KShM_EfFm5K$nAFkIS65HA3L>UE7k7H>7vHla3&HwoBs%|mnvYu?PyB7D`M#ViJOD)x zA7illKs9@NSDj(CsHYSpf^uA6)!l;U&_jq7TEqD2#**H-P=1Cvs8An=^Y7* zZ{^F93wsq;nvL=is?uYVl8&A_A%3rb_Aj3zFf?2Ld3M=aQoq0sFrT)|_n)4rglI68 z9EXFHcO~qVUBEcKBR;GG?Xp@F=6puk^O5QSRZg9Vo0^RveZPe;=d}xASc&% zig+Ehy1L0|TRl543~0egK}!k*)pE_i*~qCO7WExPm9^;@pcQ&1XGzq*3J*hsT_*4s z6_>CPD>)I_F*;wN0x!tkfE5VIkIqfwqGrr@P}4#6&x07@3Jjb6P}CwTXD);c9R{)3!%li^wowYMuZQ&t z9k1Q5H@l~@$^_`&y%V-H97iG=eMVlsrr2FZy1eZ>40mFp;KqdACC(EqKJ~ZIvZdgf znT1GXwp$+bQP-u5(60kn(Up_K_SE&Xc8F~73&*h+Wc30BE0w8m>gQCv);96+?>hQe zIa*Hxk^+vpz-71rw?GbvmWof+yN%&Ky<~I;L`6ZqLNMD$w=@9Q7Ig()WcsQ^or)|6R#26Kxey4?m7I_ zT{{AzvhN$UQz(7|sKpfwS1gN*2NZgi^v*d})G1;qMoXMAup5~O-1#11lu!#8lWC|myOz6_uS)6=FE)F z%x{$vr*mCFKD-3-@`>RRaVN|)%t79W)?0+M5Z^YHjzAO!A1io)-;F_RjzNEagse`M z4td>l+`^X(&tOvB^>2?UrjB>pbrcQ74qTUEZcGQ{@^g`??Sx5e4v9)5iNuxKZm#yP z60}`Ey)3)PNRPxGhG{Tpp*<%DO?0w5_9e_35UFYLQhH-P53XiLy*A#NFK4wru=)n> z%Qfll&&2Fc69b@~iM|nxV(Ib6!AO_$SSg$iqvRGUD2h1@p5N!sg~AU=X-(mpKHJ#S z|8iJ4iA&<{dP(@{o^`ej49tJ%lxh_z_-pIz6i+fw;3Me?U~9MhQRCR;N#x&+s77!b zVr65p^=-ru98WlMPwf}2cJEHlj{D-ug5=aV2ljxDFyaPhULec>d<@ssfQ0|i~!JO7kEgkQrAZXb|51B1RSLh^-rE3AKogU>xG!Cjw#l{<~hxn87r zZc^)pow&VZHHa^lE*hh);msrfXs2Y6J}7iPt4P!DX@geGN-=%PN@Ayyi_7HMUsnr}?RfWYJ$0?GO<49rY8G-)8_e|$ygyI5W1n>WROIBy)9ywH(==uKQBFk} zk+>YAu$pm|3hrZ?LERyu2XXsOgr1Ai9 z*`HD9__KLizlf>vw@+)hGl-#$KkNQFOrzN?HsqY&T6-E8cp+q%yO{l;bKwnphl|bb z-XyeFUrG=SaRG9M^MK}_-KpUv9~3P=?VZC5+K{aheOKBevoRG z^w|Q-LbHgraY0t#HM;hQ!gZ^y-2(%CFew0RS8+8AYS4HsXW7PP8QosgJJc<*|F$mQ zt?uC@itU^#|4ZJkU{zSvAbLCqFPfy}eCejz9oOl8b}rYTv%bvVqLUrT7V{QcQrSyt z^62~z+D7TpQ8^g7b;r!BddtvbH03|9SR0d@`Dn6Rmcx6>IMGLfP?XA{Y^OqV2py6V z2H(Qac?0`8MpcU9Nvde;B?_$(};wA04=?k(W^lP?aM{%}~ zQ_66gB?f0r#wMTF=@k><*@#&Q5?Wg()^EG{Wm6%Qvh?TP zBUY{a{YsN&4t!Q1#_+`P966K_H3f2ZsJpycWJW~vR%aAX!O$9o%AkGCgkH_tBI$K$ zT*eD7_ps{}4zOwCqBy_m@N}COTp-#-^rOUNF$i*gVHo~OGRb6c)3KFbO46b5Fia6 ze5epQFxQ(if$FIVqXR})8D=(Hc8^x-9)CRo2G?kh1#a(%D-~Z;X2n`GA<>D(5cI1MjVraI}A7d)bWj z#}o%6lu3ihLPsvaz11E((kJb*HBG=nl#X1*e$f!xfMu7(>W=lx*0?yY=%bK{mnQ&@ z14Bglp+JMoY;{7ICLq~ypHO>Ry#qdQBovD>1r&G7qjiG4C2Xg}vZ;=9yiQyRaoaN? zG=a+~s(Ral|BpU^?M$|2d!23W{?nmVt8UIm!fSuSan9lJD9d&R*nJ^v-|PMfB@Bj} zkp=oYw%1dQsNF@3NpmYs(fzi3VyWju8;s@p+fm6B2eS#vCOKO-2WPVR?(op=8rvcg z&zpQ>!wxy~t8v*_3DyCSDqe>V&^!h& zn|Q8>)W`+r=S=bCP`-#8Zpf~0!G^N1`w2hUXuYrHfgSnoH(e@$**+i>5-PY0Pa*l& z#n_+nravgAJ1^{3?1{X_kE3SSVvE+Hnhq>j$Kmf5aNR~;(lFAGA2_*lX{cV=Qoa81s(ifjp-+-My1|aFXO&^#Q>osuZaR`YTrL#{ z`nJn3H=heRw;k(2i`f+w1(xAMKi;g|cF?$?kNL5$cRN6;dRi(N_oH?+u%qsxgs>mC zlNFjJm*>03Mje9I8fXsbjonNA?0AAE{2CVM6;h(S>fVGox5Uxg+!y#It9_K5K3&N& z^iAm<$13TCWjmhfxFiQ%M7CJyLd}#b&d`?VLk$ah-H=A{G^?yKPn`{Rxiv8!lY&{? zvw1MX(KZD24noZoY%mz4A4vu5lo!5zzsksY5>4kf_GNj;4? zOZ6dm#~tgX2TW^%;O<{)P@_U^gKo)$q99wh%B}2mI#LBP3kAp4&nXtV3;{IOFM$_? z{g6|)W{;FNhQ4yf5?vFrFjPs&>2g50W!smAOf18emR9R} zsv#uk7sZ@X>tsZ=kL=8@{5NN^gv@L&^(;9k8Apv5h$E#+boD4Jyx02MyqI;9w2B+B z18>}V`NOa`;TdLZowOs7Otw91;B8wVU@F^$&;Pn6yUo#VxO?ep-s=Ucsq7nvq=C6> z^zyD$!i-U<$hQBkjJTi0Rj;h@T67fsaoN?ipJNz`#Bgb*fGKe-X!$)Q%x>(CX}r4^ zP4pDkBJ&z0lJW+L-Hgv8t|E#yI}v5czDnr>@6l%jB{3Byfi>ADhCl1L#u)+>7QjfU zP)88uj}Kx6Q|gy$Y&65)!3d)E#b(oNOB99rIs1mI>a!t>X2QnF;e=ChCZ4Zwq%>#Z zBBd^VzEkmHD!~~f`73%|G+Rosi`P`Hbzv*6eGA0f#%N%uUJ_$o6!EZX4a4!E!HO=vL?r+fVX zd;^mBJofB}k*4u984u1?a1|B7DePcV=oprOEWJ~S$NB1Z|kkd>bH3l2Yu;&fr4=M9^{sxr)3H(@>QcQ zO;L48|6wz#jpJFOm&%tJ&;rbEtC`$3{>9D%qM0`px? z8-D3*7knMlDx5d0xRFXOj5JyclsF8IlrCJ`vDq{tJs2*$RNw~NfchdX27 z@X(j+_o8#}F81CNE^0$$0cx(6Kho_7avjf*T{j1x)+?$gE}G^F|v z8z(})alG%7oayNi33rYlG@PhR;^Mk#X=YgEkXEHvGD5ZispCya#TI}6q2qUIgU%#ve4VI?;dSDHreD;MTGJJ2A-8c#w((22Ps&uID2jsCFogFO&baPLvF>$W+~*tXGuB&yNUKi;pz+9lcKn_<~I*z(CcR~)af)gdf&)%4`?AU6va zFq0Ap?kUu0-WJvh2{~s{VBLl(9H-IGkgV*=e%1# zhhCakwXPn$Fo$Fp0Czxo(djDY96WA!kmdg#FQLyH7OY^D4wHH$JhG1t*hiU99d9FT++xqAX4f7S@ z88s*3Z*b5HW5D0|%1y*V^~iNqPLNEq!)SM6Snq!S{{Ga1S<^qV>Mb%CXIE$ymMXu= z06JoIsPZ?|-KTt}8%ziY{3iWyrDJ#A3@bAp)a!lJlxo>N ziy9K7u%1I$qKLX(g%q=7W-ex}-8klmBO(E7eNP)VWl2WVq&rTWdZr7p?beHH4t5bi z=9eO+zR~BDMbXwYo-O9;?bppD2}r!S)0`pAeov@$yR=f-(M9i&dE=dKz?19|F10(@ zGp2>nWj$ojt*|A&{QbD<$@WzULSA5L5REM_`ZG2zvUV!e@FI|E>-Efe2%~bw9N{j; zmuVGK$U^5IRNPoK!&C2W%UH$GSNRD3h(NnxRD3s? z_qZ&B#gD<^zA8P5j~Z35I;SJ9ypC`D0}tl2{BO3kHFk1#G%>LGudjdJbtp#0|II)D z0}+@x+5ek2U?N~+(AC|3QH?gg=R~VmnvS%=9Ud1 zAt4fy`d6c6D$(l=uSyNgCR5brD8I5FiME0Y$&ABKal&75eZTAb+Vr=7b3I zF&ybolPlS=ZXgB^Ccbk$fIkEdNBa$hc|=? z*YEsF^;3fn8tRz%3&_dI5!OMAL4>#_pCSXe57aaG1EK(ndI=Ev=lKJ^_S4Pnjs=gk z1BfwjoV4yB9Q!|m6y^hD0|B;%5izzwxRHQFg6%~D!?3ylz-#A^?apxZ;(`G9c>*J# zA^nhV=bhz6?2YO5>w9@6M^R&(!-{hO;p{;-hhBCJ4D0{{>c^5gbHz(AqHzW@v( z>T_og)@B6(UPyfaFu?8MyJL8Q5Pb_|F&2d z_O~6&3vm(sSPl5&1^}zcVN%rnc7XMa*^D71@mvFI6ft>&*#a;RRh*-{sGJ< z{O&aRa}gqK#7DK6?b=7X(y$5QQO7q;PfoXTE-oyZzr1C zKk@)2MHg?o-YhLtO~-A0G~jN0_M>tcX#?fdq%g34gfX>$_)xpub(SpMEQe9@aTR#cvd?k0ixvaGQk*7w;VWUH)_rbVR0 zRs%BawM;(pjrT=T$dwD%RDVy5#o-8T>lSy}u;AMma8f-eNT*==R=zSniS}54L5+1H z&XJqa(lIh1YGNUYJ;@xcIV+SVu7h;+I;>crfs`bm#9LGD=px(+WRxAuq-qCt7ht3) z!|-nm=e##M4MplG)nGZXu2FpAmkt6Jueb7}oXJnvM9mH_3OW%lEs8v-{1z_VhR?&C zdruMXY7Kxx$@Xl4fko(>oE%~vCs|Xg(VW`Sc~bVuE;M%%9_*CjyF3(&OxfkRMUX$f zYN&>cREv{|vpMs&;@fe$j~;du4mQ8Gg!J%hY_(-4=f(37pkS5|l!~nP?`1|h5-7U5 zOP8%`TM`F2=5A^8o0LrF6h7Eh?=n5y&6QcN!ujdXEkN83x~!yeFD$T*Mwf{7*L7>) z-^%B63{d%%c516Or)z^{A_{f>sLyDv3ouucI&d3Js}rv{=2mmBHWF7zx0B4q4yC_lr88Czv1WF0pIgBMO)+@_GD9mGq)-cU z3gp;|Yr*>Qt`R7wP!ShM<`!Rk~`%Y&cneqm9m4wW|=%!+K>{t2s4={0H-EGBVXY*HZn9jf*6jrKGb zlq-%edL5!p`38e0peQ%w$PJK>-U>Q~Et}^^7LU4vB%h#7%C)6wu<5>Bh^EH7Xp?e| zJUtWVcR8iPkICnZl#fL55mv2WnndZpaj3+w`K;)}=sjETkUcd%vOSyHey9LQTERYo z$A0*<8TX2TEwV zX*cClniXFf?Zr`Z=8Lwia3 z`R0<+RQ2NDj4qYPm@^}duaiYbbP1~;y!6ip!fxbrkRBzl4jwmZ&hTMA{iLGND6kB} z_{wQ0m_f68eh5!5vk_v})lQG`a{O`Yw~PbK)HlvAWh+wC`yt{ofcaXaP%4-%L-jLx z#=g(ntTW8TS7@nq{B8tZLv~{^_IUtd_3?u2)wN!3CC*@y0U)VERSRgQ!^*Y~P(8S$ zf}ZrY!B<9g{;Fmq=J?G@z*sTCpw)7(-<{j^jLjwSud8=TW%lgdI7TC2KD?wwxjF?^ zUglX2Vdw%YtbaBD0%jvcTIG6M^Od_1?)f1t3oN0B{4ka8-2D0DQb5#ddT7f5SgDCgoYvG_S1Z*BzJIP&7*5ZJ2|Tu~Qmg2l7btn@^Cdd@U01nZOw&>*=nRCC6|@JEttA2~05Nnyq-Z}j$v zwGmnS47@0{0ly;tkN8AYtT0&7@mU5urpjOiwx+-;8gA~(o8 zLL(bvryQ2oj)WEL`w%m&mO=$Zv!H;4`EX_v2lsvf4vq%@+{gsinxAy@g(Q?3^S9t2 z_CW!jyEdT>Tf$#E8em~fz?I9`SE^K1S;?7r6^0|`Plnq}nX>P0c37_E?VLgtA~}6I z5$Z=`|9RF(eD(-9jgwmVR4LKybP3$RJ8)S6opd>mH_8X57RLVa6V=I$bGHz-4>6M% z&k4=6(sjHN+Qd1$wyu)?OMAoU^zXM!AjwCABhmJ^=_F&@{9xDTHGeuDUh2yd3Q3pb zAHkxqGx7`s#6YQz7*6L4-a&IJNw8RuL7EnY`x~<9s_6bK+Be!zJS>9sPMAeFK?hI) zZnL3S7UR%!jj3f`657^@AOR#MO_BAzYVJ8pQIar`Jiou~O1u-iVa#K8Ik#cL>$qYs zEtmyDfUH&(x3D^U&xe;ZT|kq`kP#}3T=kPE9*9!ybwyElS&yWtJq>N1z`?}6zX_Ot zG;BGLJS)g~LTZ~o7o^!yvC-#W;q<>DQ8p$0bM+S^>LA;|jO#5BnPJ7r4zLO=k=uq( z(k?GKP7Eov>!L!!hSV1?zLu1M*TMX;X~WVreDWRrW(bs6PdTjg?|jnj^c5AGsV8J> zQyA6J5z~k$WGJIkBmM2US-tFseht=CpZh>%E|cHKbGD&Z{ijwLz`=#v6|tGhD7p*9 zt?F~RcAXjeM~KH@>_!zIg&2>SC%{bx4(|zI*elLiqK|$mwGY zucuF@bmBa9rQy8;Qpj`OJX@dDZkqWHPn^QUiaUn1~l~$$z$E z*=rh-`CORN+0gGMtgo=d;LD}YhsW+K!f@7nJ#hs#tTuYUf~{G~3CO*a>dJ*ZfyHUq zxw(J`FLXI!uD3PYb!UQ>A`}8%63io{oxH?-U_zL3G|jra>Ky0$n0!|%))$}~rfhS2 z4XV`^7TnZl%DNHU7;6*&-c?H}7W5KRnLTo)UujF&4iF1G^!rdG*5cUUi6f#W@mgU7 z>R1JnDcw0O6n=tUrxG(7x12I4ORF zR;+#qUaYZFh}NlzFIQu#RZaTX7$nM6>I*_Qg_wf}CFW(!LHO_z7}siz)g zLAG@C2R?9t(mLRnZjpe{Y;cF{e6qf)jLmQMiQUY?m3q;+q|!~-acSzxq=cgD{3kql z@&Z9aHS20SKSl5X#~hiYGCK3mitO?I@5?#J5+N#t1$(;7V|mGyhG&hBC~%{%u- zR~1AmB9JPop(yvB4XZ3QB5sB|<=V|(1mpd0Qey{yn>|o(KZVBou=HjmhDyF#${*!( z3*k%y6fw+k9;3fW`;w|hoqQQRm9oMw`juwi?46dV8}Fjr@yRGhf383&5%-sZ;)BFj zr{dzKHq0TWnm*g3W&Z8+G`cpyQ>wLO4`u88AF3v81H@1$CBswd*4@obE?(%Le9LA9 zrVf`ba&Y^DtpaWao@;wPg{J(JJw9&O%Z}q!X^(+;8A2K=-;8!_>|Bv%Ooq;*;IuA1 z!rZk(5Z5E}IVDaeP0Snd`%8CGOES`1%G|B4J|mkS2}>LwE|$1R4ucso2zDDZqUl(G zYbV=T>FiS9qp`MWw0>)5Po`zHY(5v$P9I`-M4uf$+C_Fe<{PUNDcP1?R<(FHYJTbS zF_S73DHQ!>2s4f8@iA>m9GKsk2$-bgLGpb4~TKr@bI4sv9I}n)OpKWMcQKah1(O09o4WSEV>8})!DPLU?M4^H(RM2r3brpP2o{*4pZ#Kv@*$BzPugjy;0Kn zoJ`(=Hy1Y8MS`;c3(9(Rw?l6;f({VfUWYQPHK0KC>N!&%q=V)P8fG}IyvYb;h=npOyBl8aT{e=1;SZ_Kv9ASC$h93sAW?t5c$^R+JwWMsfOZdkbMbz zN1gPWPLPc&?2PFLl9Od;lzn!@Rpk%HCsb4YEN+}Zp0Pl~%8R8b?eUrDzuzonPBhN% zC=IW|&l@d9*p+gL$M+Yq30i+Ydv)k&J)^ybrkY8D;tp|a-_M?;1&|dBzB+Z&a#D9o z(30qOQKEVA&an{o4W++oLVRgDDax~Y-Pw}el8rwQlP1f{lXU)Ell6nLH!zvjzmo6H zGsK$q*GAbBHDJbxg}HD&J(uIu6inI)TsGHHGaq@EUe!dq5%6GEu+imN9XAzRHd|u+ zlNPNF_w2pD0cjsFt<*a>JSN%HWa!?_{IwP=G*1hZ6zPe-4Y0U)bZb&P9{B7Cgxh{M z)e6g_*~MV8xEXbt7~i34ul<{WS7zd2I*j!)xRGa0(R!YO%!;7r*(h5Qe)IeyUT6fz zYBM6WF-KK8WX|7+^Rr!$pBXVcy4yUps%Qcq_Z{7O4^^$Pt$|-b&UMe!yP|PD__&_n zd709OUHD^8F>~+g#xZ{?$eywezCR&1N*&E!B^(WTPMNw}B`11>S2C%C?2+FP69?ga z*S3i9DtEwjnc(&hL#|jPI%J38E* z;C&-lh!||PJO3E_)-qptL;6qR7M%LdHB|$axX2t5!*_wP^Inl`7Hn3s{HE!}F%~%j zrSr<$j)jF9^)O4qIE6vZSJEf#*KlvJYN>Rrp861cZe@u=*+9Iw;J?tFHQ&(b8hmqj zqi5t60sdjEZL)$j1o~OzXcERR37U`fxgOB}^u}xhDvYiSB2S42XcMqDG zu@rA=)iOtJCUD&U@qvJ4-4fl)J@zFocRt@(79fKS+`Z7-kAF_C!nt zXaj4YP6QoYS>VnFR=LIyeg3m}o#rPf*Q7X7#6rgFFbbO+2ld_TC&CDOoSkirsxeWA zwYGbyO~p!|hpn!+eT;qiZ?XEb#lb?i3CGuD66&UP0Y&4h38|WL4|5x`rH_wc*9}pM zt2h-6A-S+_MmWwTP4<#{8Atk}`*buz*jrN!ib2PNufS9J@PKM#SBQv{68|gBGnzu{ zC1vM?zpJ32t(@<+b$l}x98+Z&6s(vBO^t%5+B8_4A&~F}NLL=auTJIoWHdhH z5pp3@4R)gysj<2%QFn9JjXazZbBHsiL8Hx!R1wh_o#w#kH_hv;@I}z#^ucYMwvcer zC^dQ7`EY9>Ri;?Mxe1`5p=m(C95+=qjb>a{Uvv^fVN7|H<_}rienJ?(H!bNK*Sluy zh4{P|oF(J#EKH%r=6dB0>}r%a4Z@%$WBe%V2%4#N6ZN*{wwtCi0Bo}_#i-peZ|8zb zNSICT1I`1L;UpBDb)O6&d&`e*Mfv-fTEd3!bdw@D*Z@x0gN}7+f45I_5YyXMCFEw2 zag59cx#$dP9-3}PLe5~rC&$O2XKwkDG0W07>B=n)`}4=VkQwRFwFTfC&Idz^*O2zg z++QVh$r3b%mk_<3oJJHf0072-|5x0JfFr;x>BkS^ObjGx4ic zQWY`n(sGC4FTtwpz5wi5$5-;0EXUYWI-T~8A)M)kUU&3!%M&0)?KC%qROQEV_=;jf z<$tjX%SwZ@klv^_?N~u?jP=I3>H%e(r6`c&B#iX zW*Os2aKi)sV{!UNkk0}FmlLba%R4f{m`Wz5$=gkhc(uW_%)Hh*pSy~y?@6`#v4u^O zyM6a_@NW8QZy&fznNIqG(xfk3?u|N}xyF&&=q6i+Mng>z7xksFJsphuRA0=zdB>;9 zo6(m{%GZvIl3J=Nl{1kRrYpOzyA5c^yRw>pB@W{hTIOpquhv<6whNn*=4~q)bhr$7 z0|M>RiVT%|vVF=VexAMM=3=S`yjBQEMB4k*I0R2Pdm{v`Lvqv2eqf4Qb-mOLJ~Z2@ zX@C?z&){!?-9FT8vF~h)!(onu00poddZ|rJMuS;zYab_A=;Ve^J@rd)iXr#I73FrVEvTSt8#_NUdxzg8}-AH_| z3^3c-r&(@qujqs}%mG6Z|B_1`Nh-yG)<(k*{40)T+5eO$a{Q-aGY7~2?=LeEaIi4{ z$2^gfm6_@Ps$Gh4{jXv(I-L&C0wIwwqy*gdw$1`;AAm3{jIgvDvEl+HK@8Bs0#u-X zle1gtlBk@=jNfX9+q5S0ZfBm(Z0swxr=<(6Dx`E7r#jjNgc)dq0|Zc!vhkBY4gee+ z9UB~+ERCn9&A&wID-9<~7aYbZKmZriZ!tbFK=95hg9XC3whYJxgrZ{u*k2ofpq3zB zEls47NgoIR6y#0a zHv^air;i~VbPVw?P~fIN?hUb~{}rI7JTwHx%{x7M^Z=WETM_|xXJ;oj_E>)iEL0w+ZUj@VD;V&0S1OWeO;KkKd#P= zj5aQ9KSQ67vwvzJlfX3O)mvD@13nauKYtW3Km*{f>uc$=oH)X$-UtCSbXgGc*gW!q zIc#0vS`eUR!-TaxJO?zuk@>q4qVX+IcPn^%0Kp5vqgRMtc@RJY5*EN5?;!tsyLumi ztUWp#dib|o>=pm^R+`4hydu=a9)N3br~dbp92O9;*4FBF()aAi2B*+AZuc*jh9C}Y zweLcmvx}kM4TOU$D7D0IxfA`shqx(hD6l&R2*@CgcT3T}LV4OMrU7tzTW2j)1K`0L}^2%l!}T+bbkA1cF3WN0Um&G?B_i&5Qnetk1tbC9)omQVfQKjMX%;mO(}IXQRV0t`EjqHq+}U* zUsg&IcHabL-y|S_>VF8{|*HuXF`m;8(_u9UUr8^Z+a>^clg-VKrO*-Twmxa{y{fsA_MaqKes|c z+Qx)<`qC~CTLUL?oFA3&uQ%6(vHC7$&_|~^!1|z$_Fv$gdfd>RpI*bqJzBj4ci*bt z+(prapi2*@9}W+9KmrUHW5}01@2})|{_Jnzhcx~E%0Gj*m``8>bEm-|m`7OlZ8~zC%>}c;D`)m2g5A%oqC5x2afBXE0&+#kI zKKmE!N07r8c*?I4;Nchh4SfIj2RGoC_Vi~P=;kSoyodkzcQWLXf6Q**Py8n(tTL=+wXrNivW7&NS5oLvFaV+_tL~d#5mrwP(S+!_&d$L($2-8Pduzyy(=b zzh$V?R%&XrYU99)-ZoqB3}lUvouGws;gqBE;jrQqQMb))+@tH#_n*t;?5$!%leBgr z=(3f#igC6u1}IYO+-aJ5bj*BiuPPa176Oh3FE%&Vhj{GAQ@r>s5p&XvJhXCdQ$K+D z#c|52k|RG!JC12mLBt(n?FeXr8O1pBZ<`Mk@{cYph2y+YPiuL z()$wLkq}UA4VG7Bu3&!@CG4(%bUjjfd`HyEPA^V!S3;0=SWrC;zMXk0uHK*V5F4G_ zYeWoQ2fofa$vcy&yNxa~@Pyu%P?39}`=U!fvz+&sT$Vv<-B{R~NOu<+v<~%cTyNIcfP#QngNyQZil@6$)QcEp zZSx2io>!&caW>!$`s$P=eK$ZJ-t-{chkNZ6)ZN5n?!e%gGDalz`eG4aTysZw+1?Hn zyiprRB_n}>9_()q;oE?C~}1_kr3qb1W=X!E>(o zaHe0jc1u~ZwpPh&4gS`?a6c#4drKP$<`KcCY2`s-U&EEXKf>j6l-k?pTwR?*{~g^R zDY#DFIrHwYta$I{6bCu~$SkF%otOF+S(+6Xv`O?bVkGCP3oi_MdAS>AgF4m~NfqWz zzrp%%3YPrwbP7e@u}UBKu~!ju5;$ATKQWD#C!&*qr#EsN=O%?>q`UxBAhg0RSz)y1 zlpo|P@h=pET)q^&E;EuIGE=AR#HV|-LLVx7@QN=9W6SP5T>z>xKa9tI;$QwMwA*4|cH3esWvV!5Z zj7hVg{kAxNO}clohdU3Y*Ur0QH={#izw{3%Suqn-G#N7_RVe%^ATcd|OLKK3tXAtL z#YeX(d$*G*Uf*5O2q*Q%Qygt-Q3tfA0(9qOZZffsX7x_IZpSlss@1KAm9(Z@hB_-) zB_irsDlbI8)v;n`v#uYw1Mgb8Hz-;$N2jt4L`0rM2LXkbu*;1$O!kuDCH|~YtkuaI z%079QyRNbJ>o9Gl;TGWbo_8(7DYL65>2iuhR84Hm&tPe0>(22~w(qW4CObxpia}R$ zUghDGk>eHApP;c4>CiMrwn|&c21))@9xU}O(>Dq{S-2}g-J^=<5ng$P%$Qep-cF{R zi$vgQ%T`H(EaDeYIC~5fY0p}eqXYHW+Lpf#RJo*TRpGjTZ!EnAA}~}b_oDO#MY2P~ zMlf=TEmnt+J{22llxA#4v1vTMp?4hRu!9+!YT@*!+uy&mM+iEMB-M{4rO4Wn!-Gy? zp%ayzX~kyXWH3APs~3N`^maZ^q#BBVIbotHn`;e6iZ~+rgoqAy-%fD+lphSc31<0l zy_g1xg7D*&K8fSoYa@Cd)=<=t%<2;263zwBRKmgQk!~-CtWINPW3qsSJ~advpr+XK zrnB9|d0z?FM@uZ3(Rp(I)S zl`9m0mMVq5;D<_2^`JleXuUdyu|_Fyhx!%##Ic)14m6+-HK%{aB8N}>UJ zXN@IL8zGr|~&Ap@Z#0^d}dIYBwIRJ?j~CzeHE%gKPe^wWZ z9Bp*cZuWpiuf7#w!ITl6P`O%@Zk$MYeLo&@cFhKc?O*|1ytw6N!2rxZ=dVtAE|4g( zhYPRz`~v+hvYTOoBTVM2YE0HbR@JcmWk=g*zT6eZMXW9b-Nd+_3Dt^q(MlHELhg(j z;&kjmrp(8mF`do90AyO6)B;_2!_cD@(LjZ&FXMmB)~SN#Y3-nF`6-~pK^9LzCf4Umanqu^-zH;`y)+9Rb*-r`^G$dicHgZ*t1VPh|;o! zyM%a zg2j8`RW&Ap1nS0(qC4@Fj}zk1DPBDO(3c0K?0S#u3w9|da?jQuvX#mdK}K(T!sPbJU4OQmt9twssAr8o-6!W*L{Zf3IMU6zuPAwY%;1ZBl z^(s6Jc`f13O&hVns8=*~8)33k*KUT6xYmiPGQH|(r? zy+k>~*^NQSn8 z^{7S4qKWD?&3Mz;X^`qeXENmB%Lhl(#DkWf_i(~kz8+uHmjqn~iFiq$j}!8i2gxhk zyfr%Ep!O<&Ahbotf@*lBxN;1B4ez$N&ZqEP)3q=wYlk2ywS!T6Q~iQ0rs(GYwo_0E z8}S$FuZNSoTgY_gAuaByV?|wh;7AgEJpA*hwQbU9n0r-g1_l$Pz3~{{8ONWvT|5^K zK11CBovT?%sOUls!c<6aek@%&1b#84+JQ!#&yfD`P~Ld5MlE-<@tq#bZi4K7spK5~ z=JRdGMm*e8R@iix{JjTHJKIf1H(WGCo3tva!HLJ zYHNIKhSmoeI3#&-B#jD|v6=(-3p-P;m<8$^C&CC-7CX{e<&RJh^;cL{IM%*eC>g#s z;RYMnKQ6x+OXfXrj^sGx`Ul=HD)ya~Wvw!*tvPkqzZ7bt=o$K???lI5)SmuN&IR7h zA=Q`UiuTubmd3rK-Pg0=Y0=y}^>mYrV&mzq`@`abRB|DOoC)UuVuM@GX2fVpIOM>_ zKOb!~Jz-An(B8_K;@rur`1~**lZ5k1I&v|7)poc4er~Dckr`J`i9ON~x#6G}IzSaJ zt)_gS!(8)wd7H&_8dMNH9`3Ubi_K*(SOZ>b4_Ook7y)bkc+W6Z~2c{)2NFYC{3!!ve5 ztnW|_!$yJ_QnwQXw0Q;BJ5(#)z5f8Np4Rw$EBfyoCPn9BkluZiVIO%a&qg}tB8DD+ zp*227he(uljhr2>>~`91u8E{6lcAPT^9o#F7p4d-1mza5BHfZ$SL1xRUyV*ch8Q#? zk;ksCWdd}`oPE!6-Vbo_dat8Lz`{1%TRoCXZbdBRy!DPWR+FD*X)44^ec{pi_MHKizV3F8+{V<#(kfQf=^LqL& z1@z-n{m8s!YFz)tdbZTz*^D!9YwVJxsl0eoIA=(>i*EKm{lSvSpYy6OlOlcjV|I)5 z51v1u#=R0*xpO)(kXp84n?W5s+>=b5kx?=5d zZMfY}^uAU{PpFAu?m(L-g(%;{O*zM9C6w^o2FwEX*|-%IHmsu8>Ues@RClDw8lc{gcHq_x#~XXx_ajgDma1q6R7G@DusNJa zu}fEN(;F)6k6w**L%e93iZ4bc@Z`xXPG0ST{%fcwl*qb>YqYKAnv5x_@-IYLQ$Nvy zxMn<@V)Ur>`_E8Oz@E$K*t;P$yp@|&lj3%~$*9;Yqg7HzHanTL^5%HVUr|^103IFX zHakN-a<)X`_%Sw6wo7DcqE#h|w^2w~xzeZEIRtg%op*L0MQeQz>Tx06e22#z3X!Or z^_JK|9RYA&BKN5tH?M_fYgSDT}G(h21n_3{yOya$fK-KW`}?10K)9FU&YPvuD> zp?1-&T*!H0KM1`~mw2__d{aX8*{xi;OK)tn+xDw%+ypMF<7==$nYyNh7noS}hIr^S zTWmHg76f=?AKARn(iUo*1`2gM3Y8#qC4T8e?P?B4R@S5fskIx{71lD)t z!iFeXqf_r&54o&LXjP&7gL<)Ff8|M>7S&X`6j#&6WkS+dnMw)Nuw)3WK25~r!LpF04jCt zF(tIpdlNqyZr&pd$jFrw>)RZj0evGe&RN%?GhWE)?7wVK;L zi5oEnZ~X;R3D%W~M=|V^8e=S)CdXdWJfzL%Jd?bLUhipBU-4!A z3A6cDs_bLEjeD@J{-UmnTbYxBpsZG~RH*VPS6(BNqFq00U<*HfYx<!55y~T!}tgN_?sZ-h+7``qq__cePw5eis~*KJ9Y}dVL1RG?c}2 zn4P(AC>BUUpqg+f`l}{WoCix*xdNiZq_u6wp4W7(-Et({*Sz_@5TsCDibTQy z5^7IqhEa3qvf)*6ecu6fuG9Ay7=$;Pdxf{r4cdttXiL;}XLZ`|%S^>xzjFW!;z=`~ zPv@jALl%zp+3hl-(bDn?2X9F+6p;v}o>Xl@s{~Rz+>SDiHuW-LfbJknJjQmW9Q}0v zk?un0RH3;jJG|%JS;sM=rrKWHfo@09u|?)3bo$02t}KkF6NlAD58(P~;8mHD3S<6!5={liiZ)uG82>1qD zP+dqe*V%E-xOJIiMyQ@e{Ne@NOip%Xo`;|QKT@GfQeQ=dP`vWy+YkW9xB_9`s zXe`kigqvNFuwqfEFG<`M5lIVul&zf){b^E1Jj=X{D3!QcpFt9J==+l*?Cw?Kw?$cX z2`!)0BmL@%$F-=A3sW> zT@mbDNnj6}n4V`PkcF2LflumVnk)sb?_IQkxoU?roh`cN;0)*sO?@0!Ao?)~uc{re z7RdI&+2ord~PiY;8zm*qeC3IvoL5e^oCo0mMEd#jrD%2ms!L6TnRVv zQ;~11rqsK^af8*;W>%#M+3i65i>b%pWxoRFu%ryMi}L)~#JVS%i!4RF!fCc*VriPy zdZ-Qg8jUF%8&U)Y2sQonD)s2&L@2Q%);zz%2?AKXTghMUcw{j1q=dakHhEEubv^&d#K6xcLWskN^5FPj$JvaAY^|$_0`C3bJd0S#|Fkk+|+U#8DISq zVBRzzso4khRWFeaz81zmW(B)<&ommGC!Td`I6SKOE^SXE zsUoJZ+M#kp;|C39@>1EYz2W{jH0rgS;HpUc?+7Y1MrWN zWZQd!8F68(hS-^TYeuRW{KbOv{964tO?~>@xpt$KFCNgwwEA@ zqG_F)qJhP4ROC>z8IwT`U=t?v+i7i+l*!{nT5dV^fhb4y)ws?0WHyaT7~&KLizPp@ zjv_S*QiNW?A;M)cq05^a6GhNmSa7270ki}Z$n=WsyYcZUxGmm$OXayP=i9{AF<*i}GjJ~MY3^h6k>V##8E~`d8W@xe@a`!O3z+9s5&X7^|P#rxF~cTfux@ZM?Zz>FU~E+lTP}gsx*~Q4ame&QCga zhfmdY1WD)fX{Rw5n6FDUsLj`3J4yMY{rw6%R@&HU3~|4 zuk_&~qQJrN6F0^CTNq~Pg6c#wzBmC|IK6An}>zRwj&J1IeZ17YSQrq7|F9W5=cj;m7}Fiuus)&0;=TE%N}qhVIX zUo)}l6;=_Z7W(J@$*heJ8xo**rv4(*!KVBt8P!dc}1nk(Tag zo2#odZrM5CH4c%b-8bKdsjF{i94i5NTE0L6ff9G9TPivwQHsrs+?+RDR_%&A&XHlq zNn*oxO-NVnd0g}-qll)h_wbHejvu%fc@rW3?Pfy*J6RKdI>lGj1x`^u;68oiPb$Ok2Y_wwH7Vthz z#YGW-jl42q!yb{xG~H$FOeq1Ht46J*g$aRKmU3y2f$a?7>XS(|uWqy&q`$u->B=VVC7VGuJ4BO^i9co@dh}mx*f3X zqw*~f&7>8%Da&9VM0iUYl7sJVuz7J{Cb8Q$6NzuK`g(QCqek0cXgY`DZAF^*sQ)Rqy0?gB&L1KVx!V06caG{5JxxOk}7pGd&r28O~T4PhHY); zQFLgih|sdI;fNCoT)>q|@%66Ic}q=<{pTt1P9GvW!vP;M zLqR{P9JekW%AhJdRogMrzkdTVmC+4No?wZc(rL$ZJ9UTFp~(%H17RMaf9!gXfTYV_ zL7>U6=1Mrz3kRTnz3i~^+v%ezfEh`c@$ODcQz)?{nTdT+!d63J9!}fR%?z zM`FadU20g1=qklMd>=~rVNb5I-~BLr7R>x$f9*u_T6&DeA- z2>9|FoGC&{P|h2eSY;x@x)k;o@Y@&5Op)~j&)C)M8@{X?M2w?B>|4-uBsNG?6`de* zW)mY8gf%pmr|*h!n+1J+uU?d}=mq}u{^Kw#!5kY`oId&7sX1pSimpf=eIgDkImEy0 z&qlgm7G@cvb$GdFC6+@?RRo%l2RO_{gpf{ZO4?p#A$r;wiUKrn<+-dx=NFees0p0Uu6#lbVs07Y)?yu5jw5 zZU&J_0(NnDBMyR87oDe^vhZ_JD~Wp-sMS*|4o``7T5fjrdOymKhG_yeB0A0gidI9+ zT^h}7GHp)BTj{Phlg6G(Jf>tAK&UgV@5|KBy?R3q40%@Mp|!)qATqe~)%chTAT*{< zgoM$Un2}A6maUta2a!f?IC2DWoJs+U)_3p{=ma)d|_*qH|UQ8o^FFQRS?HJ()n{6=ftClrv7cmp28}H zUOEiS(%WtH!M`P28iP;4zz0wP)Wo-r>a&Njhoq@Z9~fe)KdzDw(7(~0e?=f~nUulY z!xIJX{$;3<)_lQV17hk^jM9+jUqDNXs=)uy*UTd3Ia++^1yXybkwuOJU)dA-7fEWU+iuKR?1bqom1_Y%g zMUntOpqzjMg+{Ee!x~zUpV>1rehO0{feQDR{s=1w2nn81XA?pAjw}lG176t4{hQwh z6lA0nbf6$WAOHc8{*n+oB_bg>xVxW%a~8iL zN_2m2^#HhIY~U5ZiwY*j7b5h}1^{jln4jq<-Xk{y!(1Cy^j(2LXt!`fK!WOE<`@`I z;J6;|gM|wu22@W2f>~t&;G$D}(KnswgXs0&ZUKP2gZ?IdUVke?fc+lB00kq?&=GKe zfwcp#4dxU8;F`+%wSZ@#0|W{CAqmP+45#v+F+!YxG<6bvadAQv(A0wi=z_j+^Ppfr zItv!RDKeDj6GDBZbpCBZ!YK-Ha0?rpr#Q$zRSqF6+^cRe2KlL~A;#H>;+zk4U7ovBeKztzp%L44h;j{kUENWu`0RRwiF(8`)H%88z{xdc6 z(o6lb>U|;ud;sTN)hh^KfBr1Letg{qbWi}d;ZNyrReeBRVq0(G%XS~p54iUoz(2Fd z0WuQk9i(KG6aa`Qi74Q~fe=7Gzw6IL|L**6(?yU$pFH@Nx)Q8iG=Rhp>agm|58ToH zZSUR(FY{Iazx$k+4l6TC|FiwAHh^g0UN!!}?r) z@4;VwhH=c3kayXR3sd%|WgQE`x-#IOJ{99L{pK3b(EhEQUvyRB;JOoGJiF5;c`QQ; z(+qHwB52{@>tCy)zG?^3TaaL3S44`n*-fy1atM$gcsEu@gRyFCP*>GzeS{~gf}brV zNH{S8Ke@bw3Jib{ksyZQ{%SB}BveojNWEAJkc<23c0iyn2au1ypbn^c@cn3kBtM#p zhKK<_PmKdQ(-_(%M5Nxz{#^Pj}^2JAST^%V2`dW+Bs9qtdR9OOn)KhtYg z!xKcuWeWSIxy6vQbMsCE+@wNLZe3-VyDMgytKJbxCoagP=VUEa^DAa%v@qdo^EWG( z?%nu*W1SZ7yKemPqoYNk|Qyq(s zX)WIrz#W0L9cHGm%PDbvhKTV0$)`LS38O7#@Ou|JDRRvCIre+->c$8Tdqyxw@h#Pj zjPPg_nZ_#Q(tdMDJt_U#0`;X3rmpCcf_Jf8vE8Rv;vw*Fc37hK<8dligF|RWIGJo>Q4P&+rc?{(Xb%g$RiE zsjNPGHO(_AN95Hoak?#&O1~F$oo~+i2Z_xDo8BB=~!$VXP)p*o`{qayN8*@ z*xTKT2mJYjtB2&cd7snBnQyVm@VMB7@S~Ihh;=Z@S z4=0=O4#YE6zM~kIpNyc_m@$BmNV0c*HG2Y$V{x|(Arb4hJUKt^D3gP0uI*%nwNj&B zu}>6om?~j_${EJwC_(c*cxl7{ufumeqfe1pY2nM2*p0h9I3K|B#R$Tcp87t3koCSCz0=D zSu+yQ{cj(PA+p-(4hKpb>lUQv15kchT%TfSk*g}X?aBdSstwFkY(ob z?{is-<>x~JLmhUP1(FnAq6_3ZkC*c%S`$~F2n<6OZzVPk{3>0g*cspu zMfw&fi3rFXZfnNt{bg&t_?WTQE4148=83#`u(S4_#E{yzo{RbLTFqS(e2uy5g_aA= zYgW=m6|b#JrvSpo=9ijo7DiZ}+*(a?hb&n@%qIt-g?(E^lcL4`af|+0w)yh@T<_4~ zP9v0p#pe*7jZ>Ka5t`diDf%Y$1+U&&2{Yz6s?5PP1wQATqQ(y_fHjNn)*EZ_X=pY^ z;KQ;#VApZxkfjjdoDZIzKTe!eLgIe^=TuT}HLOQ+e^V5Yd%k{g6M|(A*RrHaj_!%0 zl6lwL&yEjM>4jlz?!lF=m*_lhE5^@v>2b0ndfUQA#3{V*!Ql3E^KalsZd)KK0aWnh z+x&gW$$Wb0Ep4Oyppbi5DuS`Mwu>?ZH?G3h$5~?sQi9RqT z&Nm$qmK)9-KScMLX7#IH<$5obZE;IGDsh^&*G;ud#|8Qz!Ehi<1OB(df1O>qF6QUqV=xRL7~C#}bpc7U7ED$-*T%Jp~q( zfjF(52lW8D>A&eS5Tm;*?B-GZyb^Xou01qVzI#?!itUjl0 z+hVR>f{7UgpwNZ+^m$S&8lE|_2^)Fwe zJ_wFz17i+B%B68;&tn?J(@yP>dR_Jg=IPz_{?)V2IDEOY(!>5K-#+U{7Zol3s-)v1 zB;M38B$Xr2Utbu*--Xu@PLBw7uXQcev9sprIL^(Dza>EKF~?0RsnF_EQ+^XAFW+7t z;msE}sf$v?$it@Ofr_QGj@C7~~x?#8vgR~2tu3k09FCq7u$jGr5WAX~x z3g*jlb3D!()!NoJIqE0je!m=NxjV2(OjL&wRppJyj1E*Fy@969Hzf?LKP}c|`j)9` z*M4JTP^n7aI+4E7u)ts3n|XXg_)}ZFuawF5p$uFQ!>2Jl>L!no^R6ffi77vF$X7gk z8m22ZGxZ<6^73MxEl)ot;~r_n4gL;PL<;1s;%uco4^s4OcNK~e{KnIaL@i5G0##;I7IXki=`zE3c?E95#TPdYUf2alW zSTNJ2=NA|+4c0y#(9_q`*^V`#)h&6E!WYki4igyFT$wha-E3QqdM`DIhz)iB&TIAb z4%Rkrvujz?^vZWB%=Hj_y+gTjj->z0dU`{S$2Mxv4KRRDTU~@D~>yP~yQ4v&h zmD?o_Vp&R40~52S_N_OL73^Q9x$DhUIA&qJ^Dx)bi02&-WGGL@^Im>k2Z_mt`?kGW zk1FfQt}`&P`#FlEcGI4wyd4B;HOk7PG!Tc?#GPAqoc)_YxCMJgJ8%8o5x!+ zxS_UdCD!6v&oIKtq|f&|#ORpBPaoJbw_1u!*$}JF{eX>J3bt*w_VD7?f(k zF2UIMR+oi%HMOHl&5NIsnoBjUVk~}n(f;HvpI#FOPM#UY`zB(whQ1;?E)4o^5!p?I zctYBveZ{r5GbmG#k@6s0e|JT4I)i$zEZ+MT8BK70-%S8$jW%%z_x#ku5RMh`(mhBQ zQARHajw?-Sb$D(~wbzHp9o6PLyq)#sHN0)p);>IkE7;kWsW@NtA#TkJ;b+ zQJ57hRNCBuAPjxc&0jP_qO%o+jN4uyH-fy*m5zX@AMEceySr3i+WLzGvNdMz?hN@5 z_MIOl6XxC^4o+KTMY=j;9Otf@waU_Z;aK#7KmCXIIFtBur3G2o;6wDV_fA|c?tONF z1a*5nW^YdJkb6Re3(_GJJ0o`18cuSS?-;phxU76hxPgDjq&_x5MG+v3gvs@kU)>bb zU~&`{EGr8``_SbSF6Rv&T2=+V)l189#RaOSBAUI|8o?Zr*kIgC59lk=Tsh~+*O57A12_<_`{wNFTu@h`V1W;8O^&Ku1lE`URkGT~*UTQ-%=UoTt?cFt z+82>M~6xu8P{ZBm+8T}k^kHcmM97y)W|+ol`9x%S;R z&DG{q+}oz?X9}M3-<*BD&jrj*tcXig;>Wd49Le2sw}Cw_4qEj5SHsx1)n<|0^@kr} z^KK4xWex$oFcB=3+X#4qj1 ze@oTzkc1@Msu1|?j6P8|22swaUcBwyJx%+Qx?38^dgvl=4}TrXmgEp)Jq1KW?A~dd zkQlaKx3-z4-3b{F_S}p>XQld;@zPhNveO6y=r}{88=<5eAC~sn^D%BvL3Nq>^=9Cn zyuphS3qE7IabnqbI+tSFJMv(pb~OkNs!1c3F*s7}NlV-QtQ&=5%4jPNr|`At3yO=C zoKH?=P=oEdv?nw7|YR~Hs`_UFo{7-P34!>*q?s8_enu3EO57*U)uS!}*21#a5&7J;RG zvvHf~7B+dUSn7LdW~P37@Z~a*bS1FUDu8*gcDFP?b-A#*l|0^y?!=5}zn{6^*w9Lm z)UxTe_#}^hq6x@Vx%_m>f3!ACqUR7yR#e#KdWj1bb$yZdLmYje)#dqTrlvDDqAXV+ zR6Dlr0QD*ypUN0O&>qq7E`~fF$F!D!&*;}x6K7r= zZU_lrT?|~^#x^mJtaN4Dn2lzhgo$8?x;C*x&Ph>4vUjA?v&l8+qaV1m?NdzJaQNjk zD(bqr-)MPlOlkJ_kCFosehOsPwkaOQc+cQWiuhoJD<1@lKC@u2T3m9T!%!R)jUYBa zE07Z~5aJ$^wq>;dvh-s2f5gp(p&}F;^|sp<7ejwoNL=P&nJ0o0c3G?ah+?xL{tCC0 z9Ak5ao+RJF*M!`=%JNgNWb%xhZi!ic+S4*03x$(!U`_`KdP3V@xvpcQwr4 zUVgsy_WK%d$zY!Vd{_R4zPlPjXg(Z67+NoXPv5Qzb5_jVquDRrcmwavz*q*bhkWVG z@N%<<2c?vOxOU8Ur%Ls)#GgCObFNUgYx+aTF=ZBj*xP9qN{~jUH1I7qGWmBAg9GsF zVl<;pAW3RSG$xNkDqF{r8F7)*6E~qrkk$Msv1aOb>9y~dshySqr}6IGo6|09X|AB4 zr)9=Gqo+Eo{V+CtiVsU{lr|Vw-i(KOxt@fXg`OgCL##s}W#?Bv5{V8oZ_RsD zWxTz(=mcTl4;&IgB&j;OR)MU?j_n--d$ITeY$nIzQCRdz3_SfE9>ANiwQLa^xhJ1O z`u=rK1|-8p_o}YB2{#vpwo3Qf4-~MeBtQT4*mmAJy1gYGrEZl`G=vQ9=Q6E*=VAtH zvy31S;n{#o=b9xppI-TmWA+hju$^~vd zNm+C184>Fc+_X{uq5UyB97_<23c5ZEI?ZX>Y3KYBkib%(rZAOJA|>*hiMKdWL>VCE z$0mQ_;}7;A+oDDYlUiaY)Hi0g|Xk=CT_{?R<99%Ky8hNfM#VgVqxy~Mv5RM!^L=O;r{ z{Wxmb=(9VM-rZ#8WfEC%^%N*2(X902bxo1l3+rhGmLz9+ZUw)$E*=r;<_gV(vulRF ztuMaJ!RkW8X73NJaoy0 zg)N!}42=MP)1;T8v^QqYoqvrPU$JOx|MQSX$-1E%q{ag*&oj}ibl?DJMIv|I{~hXTe@^~ z#)r~azNY5Ue4t z+YlDD^(GF4qDp@9>K-)lU)@aUqJO)4v{7qVK7$1`tVqs@W7TQdJRX@(K_zqcX^mHa zQ%$S#x8l&9K)SE%{a}g^_)s9}B?#w_7E*(KFj5F>cvtmG-`|5BIe+_Jr=pClmd2I~ zXlbkXrLejL%)uz_m~FC{l7(T6dW^?Z##+Cx_P5 z`KvX@RhC1hNAL1+%W2fjcJtTij*<PR;~r%6Xe=e!u{Rs#_4NwXEsnIAm!!tvo5chT`Fv|oxy`ABiEY2_aZ zo2>72`Pk`B^WD^HJQEN%kIRp+`)$Y%Gw_L=B1Of8k*Zy8DD@<)KI0on*a?`^MWzV( z@fGuz3%hl4*MX$|y7gkh7;mK?P8p%=WyKl3tlha10mxw1%+{o(w?DRZhSn&(9Ll-$ zm>7@OH|)GUAozBBrmu$F?%f(GH6IU_!d@R?zTdrDDJYLhiUn~$7Em8iu6eZ{u4qDRNG-<9V)rS?y?j|a9P&+c>FVhhR!wD6%r-~M z%wLE1=Xw1=Yf=HSV=8~>3pL4fBCwkb{>?Ya;5AJ_{IG+JVN`80(2hp%`nDb(b%?VrHcnQIUpqV0YAC}Lg0yq41Zq8x zx;W4q0#T~j%Uel5?Rb}E_SX9RNLeQ$*Eu5W;%dH~*fGWI<4^Z&rH=kxsje^rlQidS zsdk*sA;y(4c$Mk!Vv+ee3+}f%xQaYC+kr=qv)BZ&?YnnVuKdZX>#3z(bYsrEelte< z`TLgXlRzJRB=*9bZ2qkMHfF8AsONC` z+md5iIbXGACoc`=!&5ipvutNk(W?qOiILa#xa5hZ6Hcl-oSHZwu(y6j-MRLZB$6LU zR+1b@!5ysHfeF3-xC z2>CWyX9V=no_b2!eblFSMkn~gkF%|2!BObS@R4B&ZDZK($7OCZ#{5gOok7DMwg%?4S3houYL(Y|%UGtVF@zUr*D z$SYRP488vG)6Nh;J+Ic$V^51aWUM{p(tXl9?Q$ea49D&)&D z98r+vOVvv%iu_>-Gy`N+VrvWAW zJeS<`8>$4;oW;c3WxEE~mD5*PZ$H#PKcm|c)w_6lgEgdq+m3xdrQwV0(ZM+9&d|}m z^!MAR{!uzUkH*9eT*n_VAFM2%jpp12p}*c^==9uGi=3fXPz;yRq3|ZxxmQ}Aitdc$ zviyGG!n5DqeQ3a5QN~LL=N4Pm8(&>9NzHkCcZ_cEe!#Dw_z^A^sdKkg+$~+d6QFE>Ta?*}=GzV@BZ7Sn-^R|hTuWEKL?%Ia+$ACul9~slp zM-SS2Gw}G!Nv)###M;XknC5J{14C3a;i%CG^Y!!>Scz(`>_0{OO#dm`=U`#^Z=nMd z0VCr--NSz$|97^}$i&RR`G3QGD0(qV8y8b20(vnULl;vKQ)7D*Qz$+@sQ)LE@YslL z2UW;fN28SqKp+8uB;<$%v)|g@rWM4tC}gewFb_nX`1_T0eCznV7arZSbyP4Yh z{8hbGRiEG8XnWx^zplrkVlrhFLqx7X)IhQVHa0OdIsuKKq!@2t0M5u<&&bHsRIIF6 zB4nVx^S`Q4$ujT;hgb@G)kidXF+jMQAcG6y1*H;Xrp^UV0K zj$j-ID*y<}46e<`h!s==V69*TfpLDXM`HOpVaTARM>sn=8U|@{GYHzqhFo9*$RS{G z4xm~Cw7G>~1N_3nEP!YN`(?#Kra~3i#yPkv7lyThat2xt29yV*j$m9H-KRV*j)h#q zyBmg6NKOQ&SP!!Ofl2#i4gkDc-3QRf(Du+~n9g&rP-F@S0W z0!|@0&NP@|00S5wJ#r@){|oq$0`CMOSR)`N59r?l2P6?y0U#ic{KJ|b+{inOcG70^kG!Z193VfM@sX_Qft_Y6zGi5Mu~H+<-X@_MCqqZ`N?0 z|91X!O*jL9dqV!+2$13L|Kqpdt&{<|H2U{A|Bk;7gMyy8kf>7hcXiyKTU4}g27q0R zO$~sU8k{*GG&2{w|M_X}e%JMfFYs69H(V7H{OyN1@=$-F z;N9BZ0`OP15W*LU1w-I5{>L?wGb1+tr{Rm=egL2H*Z<&G_xQK!_xD=jp*VFJ-!F?F z_=n#wfpz%raeV~2pnnK2Z8*@ArKrshy9)HzsTg&DECGJ)?F6`0t!I; z4U(VM_=e_lHU5V8*-#~TvLAmL25tq*{;pccYkyg+$@_o=#Xf&b-8-6b3IA1L3+{Rym*hney3 z|6K^U7x(@oPyA}^kq3H*|2ZUu1>+8mRXjB>81?xSutK_T0lSIlb(5PlDN=zp@`bhHLaV<>#|)*Sm|oeXGoH|$wzRg%B5;h_Y4n5WB82Z z9{N7c^FO zQOlI}UyPkYmnKTrD9h|pmu=hilx^F#ZQJOwZQHhO+qSg~06GVvP&*w~>L>(*65HAeKo zyXjPFILb|bIy;Sld}&%`DWcMyTo`xz?(6P%)sXMn!A-wXIN3Cxyfw2$p<==xgU6eq z-MR#Si0v`5hQ+7S+CD+#CMFGtW%i*`nx<}Lz3=&62DJ>-=X0XH2k%~W?%WQRf}kka zSn1^Ysrn9<0_F`y)^i`h;dJeD_V3l}021R`DchRC9&ftI)xISW@MeA0*}Rag9>|%H zRy;rt4pz#9zDg1pgIhuO&qOjL9rUpi{=2r;%I=k88yZTg7}v(A`%AT{)gmCgW76Ei zd<(C$Yg16rvWwul2^US+@w`|(f^a)H5q~XCs&}5=;k(QD=84F^LlAm3auZg%Avo7V zeB+(vBlDl*W(zr440tRYVbrWCGn3G`(O)_E1a+sv-yeAQRW55csL-Mij(trJF|8^aj`DtnYD)SRjdXb+O^a3dt}*0)vTb#@_lcP18hF~ zIO@$f3lV^}XE5@737ZVvmbZAe>lJu(E(zGefne2^=K4E3$VW)b1=6tGLoJ9ul@^3S zmxuE+0ft4VTOZTZR$w?G{)GgGKO&AaOE!BT!(s>1@l7_!?u|BC?8_Y??Y% z@|al~N*4wtch(FqA0~F)&0ymQ9!NAg3gD&mg%Wo5dd|Xg1-FexEtI{*aK8BEwdd%JTXG1%9ai!INjzpD} zvX^A-J))*_Z{#N}6Y`37J8o8^C6?crB#8?F`qMJ@R3K?OnhG?ga5~$Dc==S%Z^oT( zD@S3O0J=_n3fD7OAM*P^VuQMg^zlmFU>?Mwqwlt#412L`#D;4rC~SO%=D4#|G9<&h zYg&ol^>?XYhX*FW;kFH^@)C1@XRX`CoI?ONXTfTWUYM=+L)R&#wH~oTiFq_)08Ce9 zH#3K_I$z!Wfe8yD{9SJcG9 zbQSr6_v?24ij?dVJ`=lUQ_IuEPKrsnIJOvVKW2WRO*^cj9HZ~e`d#Zv`+()eOf%1h zdQZPLNtUoyt2Co(m4Zhre75jsnk-P6S52jG4&`eP`=MM}V3pt*y^(d}oovc&nHXXe zbf-9FDIZ#Bx*fJHwucT8t3RqP4E8&DYs1=J74HtjYCsuU!^-53Zy`nH*&*xWgNbx7 zDML$EN8sVt@oGfDWyd)HC6{VM<^44SpBMYvcy(q8)AWbKI)Ivj(M01~N2cVvSc$iz z`{zQ*FIrUbSY!i&pK$C#R42o{&-9?5v>Lr?e)ZM;6pPM;XpVU-wM`K;L5 z7P*7%orXF^i5ziAO2(=VY89Lb*kkYgW7H()I!3Z%LULYHoi}6jjCKquG1IaAJ z{>^rb&k8G~**K91$5Pk`|7%O&e2BgtEhlfVJ4SVMKSDRjJaBeZk;zC~JnI~0v@B_- zd3(eQ{GTWhq1cMcbm#2|n5^`_Hz{>JJ?y*Kh)^)f!6biR&Gp#e_+=OTA?Ui!dTCX%y<}SA>-@4}d*G2d8yz*zjb>R8v z?0cO&3X2#;-u5bQ?up_Fl<mgPNXR;#tO2_3CbgY|WZ|Dj|qdV(@on_0qbq~Ctzc=Jl9{KqD zEl+`8#BETbjLS`vzM~tj6>*TSt+g0O)*?z@;beQg^>PUmHZKgNnt$Tam`~1xZA%7t zgXN+34=&)U%WkF)>TXP6`8rf0>bjc)r;AJixFE9D4p7J8nIK51&jlF*HC=oIYJK->)&ZVbMLxhFnN5VKo~|#N>biYNl7vF z!TFjVopB>CT^KEu?Z6@p1tukc*1zqj;ycgBs~-jo1MB;`rzCvzpZm%tY#(vSJhk2- zZ`-()2BK={zyTW;OefN-yx*4zjf(_IGDJ)xe7SQbhG(I*0FmKPlGqQ$OAJm>(zCfZ zewX@(k$#pQHg-GN)s4-yf8d%Tz1JZ)EM47^XWOLp=*G?%BLu3pZW}_l?zP{ZdSvX? zc2t=2Ju+_fJ)5tWhp$>H3`=v2uHEZ9N7dDHv-9N-kQ$E^ODO70yH+6k2BGI-2K+bu*ir;h(SuT52 zsJdnyN>^hZcb7Kvu$lv4mG5(WcTkhsC-uHf)&`3=EuzeU5O*>fLab4AcAu7TOpt)H?@HCm zkvGSc!iNuOe0U{;m>P-!7@K(~1y{K~8*Av_i2ghsXkPQ={?Mn!Rzd*}+{}5(x^WCg zwiitiW&W$}{rh039R+hIpVP~6vpZTSU1+rz4d}&WXdUGse-t7FPkp%l^WUe^+{b{j z@qq{Bb01AY7jGa)YAexHgGMg?{-5$c%U{;7Or~x11tdLxoJL;4G;$7@$$#<$ihXK z_kuKJs~Jj6uIiDMP|;TSQfWGPrThInn!hSD_Amp(713lo@&?rwsi-oFwKkFNMJyau zFHXm!Tk_2v!*Y@dMX}ASjY059WmQ}c6XPvjhTq>UX{fv)v29gPOt(lDXE%(P!RhSmWuinbq9ROd!>*MNplCM5;;_kb_KLLDljrL$ zXx)k^0->3YTo2N%!u?=SW!D-=bnyz$#Yl3y20VgH%C5>^#Hk2czbHr?x@pDIQbcux z{ILF6)k=*=3YIft!#n5Hn^=Wy{{HA5DwSvNK5}xp4_bTi-xot^YGgsU>HVUcvt(Bf zN)=c+M|{CjPYMznV55F48t^Ws*=J6zA*%kjtOcX}`|gSGF9o-K8vu}T;fwrh8~A)T z1*QeP<67DuJ>{ScZDiflR+Y1W2b})69WS`>VW`}&)|5UCR}lkmy}uC>-@d1HSWj!4eD;D5Ox zLVrAiHyz`_{xt>-**Ry&=PW<{aUq7KPs<6G1LA>Gu$-TqOvX->n%+s_tjk~;dhmYC zyn}Gm5pcv1@8@dcx~GL7)@NP&W_zD1JK&Ol*^o-}MtpTgbz0D``#d|+?feUUU9r7} zR$>hDhg5+QmRGH>owN6S^05y5sU0NfnjR$1A?@`^0u@=3TPuJFZ_qv0d45Ibi4g-V z3vQrOk|n2A*rmqzKv@vJ0a0gd4-E$K;kTajr;8MXE>xWSVM>JCx92dVSv3Gyq)Gwf zjB$QD0!?bf9BB&qv*ttSTp@@W^@o`oO$?IsmW=P&j5R7{5l4b-1D-u%Awk8LEJd?L zTg#QM0{QEks(dX<+AWHR4g4L$K9yo;X(`@I~FwIxx#Rc?u1E^ zZfj7)p=o1Tm=Kx8hSh~$v8};OK;nHF} zSA{bw1J~!MC^8A$^((6e$#c^(A0;_WA5vO{?N>HJ0%~ju@G&Aoh4W~*HU3;QS@Heu zM6sBku#GB%1}4|+kiOHVj$;b##HcUp&W58L3>Qn7|v|aU|m$YY%&S@H_kgP8w9sb^s#o6^g61u!ep%h`!_m(8siL{pJMA1Cd#F6;*P$NTX8~`K@ zY`JRtq*lBdUt$(ovc>50ZjZrD2+z*~tH$a-u4E6Ix?z&V#_5DoO|+*n_cVo$4ogr` zeLr`yxY5(CA9CFNwS0p8R{ipEKvAX6>mM4!QFIO!+*Kw;jhtKc?7}Yzn`R?=wdRsR zSKYTk#M|2de5f->OFm{8`i?)}7+sDPcCc*ZFGaepD7`@S4kF+kZILc+=n3IQ^dz_| z?UFA#k9iE+Qy1=tV4~bJ9QtP&|(~YYM^H%v_Pm1N46TbgS0&nb7If6vbz3jfiox2oq%dFzi6i6A8 zOC}j^r~gy4J&ij!1gIF_r5L2x$p*7+W)ETDNt{UF;8#t=UB;5c_>s;Frwe@B|7`Q= zdwzv$sGZY`Y2$kwYy4`uB_;R7sFgKuM527&?bWPx3=;-cj`|cv1mJ6}Yyi1j06c}USem3T`m*vQ4~mY+`mZB=5Ll3$bUtc?*DcBD@ph%x*d}p!C$w* zW_VPZsIi~LCkbbP&ax~ugKm2meO}XQw)VuNU2cc;+O~lxcHNcH^YBq3PygFlOHag4 zDg0dxF~^z^djvzD7s-C#S}Sm)Y`uP6vfob0p#rKI)~2s;RN)jzoB27C8rWL7R*}!A zvn=Ax!QOVAsG7tYO08=e-`+76CIkA#eVvdR<%e;%4eQ^xFquh?FrcFc8VUe4CM3dI zPcc&I{%-hPRmUFlP!)N?ysq%ma)#lfuA$@T-n-7gbW1Ka(&G*9EHq4+=FF_he7XoZ zua$)8i*S`$oMsp~o@@bMOEb>D&Nm~!kY*VGlkfULqx%hKU6Q0`-5cItsP!oU!Td(M ziW8tiE}3v**kPjoZw~KFqv*eQd&$m!xfH@_IYF)98X(L>C(~H4hu!8n8%oE*VNVb8 z1!V*bUzm0`yfk`t+)xz~LZ8xYuj!4u`4qQifk=xb5TGQ+Seyhe8@}TqgcLw+IsEnc zIa@5MxAcV2i?$QnjZ7R=unh~>D)@WgpgJL$`uLE*;qi$)D=Q1v*QlD%e6$ejeR89z zX_ZQ=@1s66G(n_H)SlnLMS^zRHD&Kl^`fL0??w>u)I@y< zS5LGL@7d|6WcWG9tx}U^6zsjHW`H}T!y>1U8)MaXzYiK`+n)%=rep8~I-Y}36h{u3 zo1E4-vfkUPt2mka$0_JnBJV(R47ZbOrh=WMKjz&wN5DEyFKMf|NsOqf}<$+iZr z!24WnPqVY<>uXb)>c@5MXO*OCByj3(I?Zs90r}>90ol5!+7g5m*@nMMRh8z0pDChR zp-=#&6zKCQ#gFOI@@y^JMn;<3hyodn_BUm0Y8MpBY6_)tK4<1G5>30-h}2JuEKmiFe2pEbwsn?0>p!%Diz*BB*8O&3;G8@*IgXFrY*cx44S0#_zJ!AS}b>`#Q zaj^{x)RY?Hu2OtW1C?#cFXH#_DCDpZmJQW%%}W10+;w|RgD3jJF>G&pr0Z|dL@xT- znlX*H;Z~6rVWF!5=vIxt>C)frk~OImxDI}HPk{}5Re^nP@c4>|lfq?e@A$Btry+>I z!DFhvB0^?m+Rrvp^hL}usP3E~?5Bcu_}p20-H=#tz+6p3FnDZTy^ z@^tm^Y}Jjd__;H8Jbxk^fYRE7A|=0a9t$Z{`Ha~CWQ`HXfG?(0wMgu9jis8yf=W+&0UOf}c-fIw)I|}enbQd) z>mX>@rQ5gr8L$ew@Dj=3f9(hx@iM*&QhC;Aj_v-e=0gkM;NQ;lb7;6uCkeTfJ4jMp zjYo&kH1}&_=ZZaZ6g<}7I3x{$myZ<62IZ`!5!!P0v_j7B`oeQUdue-pls}kXj#@#> zqHqEX13chh1}r9ls-uXX9~Jwajw40lpX4U~x}P(0nuVbeS^e=X-*d1Zl_Ul`4pOu` zc?p?^vHBZg?8|2ufQ$*bChZoszKe@PW$2hlH_VRH74IK28JS?MTEp90UISu9)FinE zn>Mi$!X3`e^QW{qnzp(10|rsJ&t!$f3oY$Ciz?l2PVTE~%s1Zm2k@u}*@)}Xejl3v z3W)%c<#v)~2!etg$eNpuq6OFzw<0sJ+Jx{c)_Wr9G=>d^kYnm@vqu5d+(PezUaP5N z8CDl9ky;aP3o5{`=^r9p`!zv3`#S8%Kzg~AKjQna#Hs0AI}N%?b|8FDoYpMn4Xl8k zi3L($+}5u6>QoO~8?`V2BSLvAa^3aCAU@mhnnHK=E~l?$!|lye>DV$r3951e&)*_ zIM53`<$dHwqU}rtJ=0Id;jhbB^XGJ`UbmwRG@w{T56fbd7xCR&Z}aCA8;j`#LX6fB z-z3M~;?1;^Fmwi}Z%OXJ)8<5M^9avN+BO6f<8&rFJv@1SE(bO_*R?|$Q`8fyQUysm z6Qg-@jh#2d?xT$3I5tYWs1K?~yc(q~?Uk;tGy>(!#^7MJq7rhGkC6-XHl2#PI)*V5 zRhO2W92tHM`#u!Kmd%6boA#aUEsF1oWRNb}03ZNTAfHe?;*sILNEBNrh#*bQ9J`^* zIJL6}*7=g&kFkDmBnXgL{rg_ce*wE%6R1Us^;K1ZkG=-HJgiSj2IO+AwB|@?AbcY75u+A3k+8Iw)*ZjR2{y*3bP3Ijk zTrcVL@YgZsR6IctBF_;FHLarP2FH^B%3S z+X|Ull#Dxk57nw6D$-1a3npobl_s^_lbiSZ7{kBl9yi0@AdXcqg-LkqTZJHR9Z~Mbfk4Yb?bcaTZDkCxK{76pV@Qa$ zmZJIi3=5Sl%qS<{G4q||gG|tcMlJ53YVNU2NUcEuS7hQL4?k}Z^~h0p_L|HiQDupv zLJ;0NU!nuQv>;un1i9j%KTfhy-MQij(rds8+oN=3ZTqzkT3obunjj~Z-&Y8iwli(H zgmgBZfAbNM{S^yz>yb@_-*TDNQC)n7jK zD~vIor78)-j3AWjk#40Vt!<|BoghSnd?*A9hX@74)nwD_$Fy73 zSZ8HcszlKr;EE#lQORPi_oM!|@_q3j9N`4tumgeD4QIctW+-%Q6KK^6@Z1eH6DG~!dxnncd?YU z)9XJggAR-tv&vdKnL%Y|A$|D3B9y@(UEr|K%I>UL4jp=hZMW){{ zUgx|9sfL{%SKzF43AVk=qf9>7g*8Q`>A=4?nFIWCS+7yMeEa>Uu3$8Z{vcp?0Tvh; zf0sHgLrH_cXJ=rqQu5N~4V$vja1=q`(q_v_L9lKtTL?V<47@E}v4+N)8Q`~uJY+w} z=y_H(MSj2^PXoYcD#h~u<9QQ;upXeK$48Nh*2?&pSX|`f!`0J{Xez)I(j(F{Vy?LL;oveZtSHFcyGN^h%dM-nx(r+{>fhbt`iys;tAlCm2E$*! zo5}+pE=51mY8L%xES_m|AqFZ=X;ij_SUC?G$pXmf|0|G~4D-<}^(96}fp!NpS5k>) zaIdY~3;qigf|^>&^J%B=upcCDT`@wby{lTB|FsGmN$<>Gt05m-(y~0O`C%( zxVPGW=(u=5|0n4qLwl9!q#%ArTy$ZDQIWY@zo&Npz7c<>LN-n@=EhQ0D_!)Y-|JMr zpez*lXQ&R#6t9NBsl_ecq&{PS^GGe8g(Zm%9q)c)@OvzxkP8V+Qu$iL_P28I^^^}S z&i8?Os9<_^r%3Od(}wJ5s2Uf&L%Egl3WhP`8Mjfvr2_T9eArxZKCCHl7gypTJ&24xy?Ir|XR{45laUQ0%xyjNZU9t8m`r<~ zxTwg+_7!hs-;7m~#`9bjG<`?x*Z!#!b_eeW_V~~!fM^v$usS7uPr%sl0tg!JO=o< z{pDEFijK+KUIl++AA$-BRy+hSS0}h^@s=fMYd4YYW&v!n$2Bwmg=Cj}{^}f3oEROk zC$#1gd)9}X8&iDFx_0jvsPte8@myw^R#yJkKz46`6dYpx7JmQvnAmdy%AHHLsJ!N` z#l=MP>5^K=H!9L}SwTssfk9cORqMyKev0KSIyKC|9&iqu_@}X~(b}30uvu5;;BG9$ zp$s?mxUEht{yO0WCx)~e-5dZfIjuGQB%qIHTJA}kyy9NpnK@%mL@m!O+WKT|vD!9p z0aNJhr&%U%`-0*U(UKMNJ}7+~1)}b*9G!CAvFpO8J#OkLw1`1V*97)(YVYL@Jv|Gz z6o0wf_4J zi}FTAnaM=vINB{}ctVQhdyhbfa<7z7{aOI7LYgof zX%>TtuWIF)Q624vK?_8BQJb!y9e(>3>(xRIc|C-Izk=Dm+`>H7${Tt#ETvYYKQgE^ zbU0qzl_USLw&NIYG-AADjwU(0bKYr#0D7fQ37*TVdV|gsOdjISq*+I}D@()0G$v0+?gMfHaAp!aE6Lad#Yyj}kmH zi^W_kiai`x6DScvr6y`eh~jc6D?vBs%~5kl+`Hl*(Ld@=n?ekOGAet^qUMIyHcVdL zvelV%#fZ02f7&U6GO3X<9^1q^Jn7uTIy^Mn6FTG-kXmrA^$MP2hZUkPAJu;y6>G(D{$1$l_5OpH1X((hr4}a9#ireB5|ql? zeIu?O!R~v)4?@XgmIOk2cxr#{x91rR_q{_ke?c>ho+8u04g!cJ1Xar<2}il|_5@~F z*14d+pIUf;;gH-IgA4(Qgd`{}ah(s2f++Yc>x@MzHsrc1HVU<-N9>ZN^m>{sO{`&G z73l07{~qfe*(41~*ScRKzTc$~PbP)}RD__1++fKsMC$<-+3=xOYu+K$f22_VrDa#5 zlnZ(_+YhmGBXFQj=KOer|6EnH1FFMVkM6p`VtTlke{rl%@Y z1;JWmVrARJi$+T#Nh^;l6>uo5M6%;YjgZ{0L$bQ%$A;9dauF;B3HQhlY_UqXlrx#& z5-I(y3vdj}2TJ~i@m!_LCF9o8ws@{~7gGHh(PAbH7cJ9rf@XL^hw#S326(oXC0b z2H=u4VV6IKiT(Yg1kRNa zqU$gc`$fv!zG_Z)2ZB2oD%^|rsIUEb+* zOk83yIp$F{Uu9BMY{=!L0b?P$INjWo!DL)iPuhj+gJo_wUY7I+442{UJcvVlUrk^A zSuxl%HR@NLxX{ffT26M6`SN7pX%C{nl{*kECxQ)hPnMFZ9I@UOmp>Ttm}8WeoDEE; zRN|=3x!&+R>>$FNlc*ZkDH5J}C^`ylqy^G7rW(N77NQJJrx=Ty3#;(vnOmK@1Atdu z>!FS(x-`PWyZq#h`ZXfwpsLBLsqmzJ>O#S*mJJ8$J6KhG=INDFh{$1TU3@~fY7w`X ztey}y%mhLJwyuNsKG|4j5gT7m&u z3J@?5cYprdjG2lGd#z6o5oL{Pb8dJzHt_XVv4|jL_KpY)_0bR>q znkyg#s4e(BP*?EIwxDWYK4?%D{@A_UDUNzfAWv7s)m>kmG`KC$BM=Az9C$=(h9%U5 zeTZg=P9VfEQ0L@jpbT04GrPJCJ0PyT*-l`4C&yo%o7t<}5P~_qaRO@Uv_fR43+R9i z5NiT>egBd`Eb=e#EL@;K&0nxU9BqSe?|3e#1E27pO8+&-zz!z1CSO$?N0L5+i~8o0q(pVKP)!HvgT>I zzbm$~+8^@ajo9iMH*!z|A>VPcXn!E@KtsShLi~a1n1Q|qCSotmJb3=A!`2eK%CQFq z)V3l|LF)$*0KbH+`6KzQ?bHysF#z2hK)gKv%=Y!tTHD(Cvkt+)*MV&c=B@oIi?#K$ z_1X;G=@8HZk?{w=wEgE9?Css1LVRcl6~O(kKl+`9%!d4 z5C|U6mq4(_djLpaDC)Mi@@x8+{-(D}lVB{j8~B&9>`!w5a9cnxfPn6n9`D9)BJh1S z*#P+K6ABJPa8e)Wk#B(=`~kEY5#i?d5#&qq{rCLGEcsXF<99ngFf(Ydmf^AX?H3sW zAc({L3r0|M1tC@y!uh8jXYMx?E6}gDfpZP(;N)#r!Gr^<9&bTjD|iUd_RbOD-TRHG z20jK`*Ng^cYx1fk?l%qM5DE$gvl7@Y=o%TFybF_~RpEH3BfU=tmli&Lb}eXx&4OEVhqIv&lfCOb1V znW;>nntHaUPTO=dALGz7rJweG)U7S9emvqj%~M%xDQ=F=?BNs3k$&oNe{#>rL!w+| z&}RhZP!`s~{E!^!)i-jVh{%!9 zb=F4=;EkpV3gQ0R%rboKehS-3i5yb&TIn{Kq!~|T#VU2ZEcG&VuA1RlheP2>`wX#+ zgr;9~GJ-%Z5AtY+|&mLo0RBWroDULl=LbQLYsU4H2MXb(e!8#+ij69=T_0 zhG>i~k_t(dK~VVqhwM9~z%3+J%!hB|=@FFdhc!JOuC$^9w^J&9je0@$4odv%mFPt% z{vKxQj#-@@ehaIdRC4U5o%A;SQhkVfNjW^2P)fGOB?;ebE6f{NQPG_y0*!x=dupAa zm!Hn?w*V)WlNsc-h!?{r6~9_l7;vo?y_Cfp;m4;;JdE9S!a$XSZY*6BFIu1ZOl8GF z(82b7oX26*N5R9sm>leN+AY|`sElDNp(A#w3^cyymS>${d-tKJ)O4x3MXg9ln&rOc z{ItKmxt8G6tzccDnjW221^_|wZjgI`gikVJRsn6UPqg%2TQhZq_dG2)O_KuCWwV&E zO3gtzW)Jx*=nlRmZ0A`ht&XKNUa@?J!(d)<+G|FmB!PVP8(#shnwgdJX-vmC=Q?;9 zLDntfPmgbily^4sL{MmXv|sjhH@Y-^6yI;MS*Xn)!wYZIq>>F;LUoPFkkuA9YIgvC z_|u~|21^@hxmm9NHh2i}P8(Uf**c~Eks_7yU~!acg>3|pfRbTU&8=)~VEh6t7leWV z-@EHj@h-1EIuB@xq2%4NE^kDa;d1eWlo`b03eEQ5q@C6^9?recjfAQ zMc#?#sML&$F++bm{?4AF-2rO-7f)IJx7;CpnC)cQtIEMSVv;QjX{8A&nT_*w@!6}u zyPE1(JL(l(i!0(ppsitIjNM)Dv{Q7%yOo0ftGLPh3Wpp{il<=!BG(R6gh|py;MzqM>h$#qS(1-$wShI~9duT7j7^P)~(i3n* zQ!y+aB+hHEkk5dClR8VOtytb+L~`$&G7Oy#*VPyaWlJ#mQr*RiXdu?&;ifb4N=$Ib zC^4o*xK*K{?4+3KQzRR`{`|!$v|4nfmH|!txv|b8;?mj8U(^VZ$P1xiG=F!vU642; zkMIlGe`Pm>Gyh1XzQth818VI2dH>IJF(FH7PWWXUfohRuvRBRu)=Bedh`9=0f=Tp^ zxukkR&WFiO%~Ak$sfmTnvqzXweUO=?#)buFkio0qa;Qc?ey#K0`M$@Mk|Uw?TQtuk z-H;nq>Q7gaZ{HpN-NTn{w@*`s2yEcR=Ww}*(>O)Tdi~SyaD5s10}Mhu+xab(WSo_!2<&t*ox;xAbg>j6rm*g zScKWtz{mJT%-$j8N7nm{G8i5%m@dzY`VB>gHZ_Ew}Ou>6@Nld7+Q0kGhGkoo?*ys@eZS+E!DaaBKcf zbf@@qA!RCihyR%44gy0Y{P)BL+0KZrB9Kns?s@BIe3QyFA@i|v*SRB3yD5lrtROOg z(BMn4mscqKS6dRlSkO}XCB9XnXeJemYc6#0VmU&hq5^yQ{U5r_6_qHRx>Qiil0X}a zY=>d}h{o4dYfGT&^{&;$VS5@=u-G?uQ(zfh2lNs4f!En5@V#p5DE!>o#bOrAyLcG6 zdYLu8*H;6!-o=dC@LYM%isy#CSl9w z>pYA5b_djm6Od?>Ra2Ry83ag176|Bxu#6Y}eoZ(k*z5E}$G#8%g8I($LL|Nk_{397 z-+MKm0g7%>0ncB3G$bQ2IA-BO)=)uYB5hJ z*ieh7;Hf=%X;8w2viG#lDO|pxtf$&_&OMjRX{L0UI{C3_Ks}b?wu)P|Rt0jG=uco@DMCg~w|7d1 zumtuE)ph7E{t90+C0sCu5 z$=(DvL$)t=_cMr8CS7*-Y@=f#hAkj-#%aAAaknh7(D|-cGLDNo3h5x zwcfzTwJDEqdYF>vhhdX{jOcq z|A5oSDMi@&BrZJ9pU@&qVX_2_mrqxZ)~FnProiSNyMs)LarBGDhWKuZ&Lue_tL!`d z9QXhQl*^iRX+T`}&3tze+Biy*wDM~x+`i&9{hEUIL0K7`^*IyidC99^?ZnUlGl5MH zScV+<$2cy{5sJQU2o0*{MB`bfHAwY#blnshl*kL({0J}4Fg{k?0m>I>(AlU0Dm0mn{i5q$^9F6T)LQ9f2zl9<_957f) zALByt*H&9`aq>k~9dLI$5INJ`;W$;0iXhn=`mZT{ z+S}iXxn~qP2@ICd-28cKqWO+LE_!fwTUCorZ*le&wcJ+uo1xzU+>PEX_Y#$0EIavd zFC9_e6+M}+C=ek#b8Sr=oM^h2JvZJy(f zRZaW0JgZ7QLWPLR;^M!W!s{JVefAmh!U*5yj#rPm3UkQNiZu1cT5`9XZV#TY-9kxt z8=ZKIGbh(DL6+Qjr@o1%ACJ(ZV*`J)6VMS832m+Xa$o?&0L$v>Y23U z=ReALAuRsKp0g9FYNk29(2Ty$UM}dYF3UQJXeN1xT*D3?=JToMG(Tx24Z9jbDB@RJ zy>BI&N6?r)G?|8v!n*Vmg$$#OVu**8z_o}fr1KkGIKGddJl(IDf9y=1u*1mybg)#P z?qnvq91dXQr2TpjcXs8e_Kz zp@(ajqPoQL%yx^wN@=me`3!sPqrIYKQS%1NUXv(upPia9)w_M2aFknhLWZ>jq!?BZ z^75bZ|H*RIpTRqnQcr4eV^*)$Zl4-xd%SXhcVwbn78Cnex92~2czpOP+#7XRv%SRP zQF?Znh0hj{^oP8#|EC$geG?b?))DBsJe{akdK6i}le?ey`Ul?~7MkmVSfK{J=L$d$ z^OwP>B}+0BLa@?Ejdm`AgDUx}Ja+uZah=d>%#@isMt-}EoaY;~Qib9cX5KT=QwG0M zVze)>dLY=iitpgiBgAt;^QW;fCv)3R8$~28UB|I!bpI@ooe8 z)VP*D_{>ctn%XAYr-D)Cd%;|TygE@oFvS=1F6yD z>B}-#LdEQ2?39x^J%Jj!A;mw!447qo0zsE-Q*SltoMcE;?y(fyV9wPG^?VDgLf@u| zG*Y`ZQ2cJ+r-NnTZ#``*6YeJX3LML=DWsIJhnZ$)CF&=F9l5KmoPnC-l9Ns5JRU0D z27XR!(PDmqNf;v>UM?@+0S`MxWFb4(RU!V0Y%jdJp-u?vaTh^ax=BBE-*}xo;II4a zLy(}TyA=%X6T}QRUg5W{UO!Z(qg%uNla5A`#Ma@A)e`HtdU-VYeNqgr(cG=wss!e+ z?olvby!{Vi+-gY0fARHQd#OfrP5|d44}KF8^oO{IR*GGu=ktG|;L*CwsXKWIshC}7 zu6tSOT*w{r?_x-a#VHb&##jA=B(|a1d-dD=#A`(;5%^dITjYN4%LhVnQ6MX}tGm%x zZD6w$W6lBIYe2CWq+WqE<`(QCLX}%i_ZNwh#`yDt3ZODWNN1uJSe}-@o=fA5K zYiHoJ$U+e`TEt%-##abPCn7^OlgtBz9a@9s=X;ty{OcR z>6j(@PQ%WezMoCp;pyOLOL4K~5v_St64Qje7k^!%Oz^`x;aH3r=M1T4wZMNno*_HOyaS$?PPW;Z24hs?=Ws1Gov!)BJg#E6B$uPx%d4a0e&8mhD%BpDcmcPOxNlkBUyBE30C0tA4zYd#SYc39g z$zQPwiD#`s3UKg)-S;!2*dr7iD9h$+E1e##Wef#HVs?B|ly{VzH8f*2=9=~hOH-}Q zZ&8d|VkPK{R(SGlq~WI|%C-L-TG66ZisoU5#ltw8DQEw!Q(O-`sXfh8qi9E*$ddwh&$DD=2FG z3Pz+KZ2ZG9ef>7DEnkZ%vrpN|^)Pyz9W>hslM?(&dS*v2Q$nP)Smv5b=Z6PinC^2< z!rVDZ&;9S%#=gSGpz9J=>Tba*nv1?*bFiGGo@TfFA7$qdBMK9?*|u%lylva&ZQHhO z+qQMvwr$(C-P6fr{$!GGF|({%)T&a8dY<>3YB(>Gko^soqn)?Sp6A3fF&F0B-H1>r zI9BtiPwUtIAcreb7S3NA=RpqTUc0^UEzBC>kBkTGJ$&wMM05m*p@aD-_byoD!EOe1 zM^+V>TZVUq;GgEVP`bA>mTki$_=e2!El1Rs!OkrA3w$vUlOqzanDldeT+&BW7CY$_ zHu%KqhNQ#XY?B0g=-me`7atT%4=;(;(@`Kw6(acnbsZ`Zyywa~rJOL$M?_q2U+y7Jq1C7o6&ytDM8d?AZx}XJLC7{xhWT z-^bCv|3fyO)|&w6&K8&NEjt~^cTs1yM`Nt<_Gb?ne|Ne(xKlJQQLK5Mzi>Lgj})qv z@gqg*BRFvCP`z9xmh@mzvL_K%HzKh)#6Oc)zi93I6%36!cpK|BpNAd&02M0Iq{enbd`!66h{pTc{M|`;Cd<+#Za%Def0``y%o6-#brcl5g;o3I4mjbAM7K>pk}p=HE)&eDb?rD+>8Yqr&p5Qm!JG$5f;VrZ_&BKtUWUC^J8y;Yp`NqRF zQy!3~k;DJXfQ2YW!c8!Tf@w1&RS;3P@QMbfsPOI$rY3ILs7UU`e&J8V8ltZ6^pwa! zvB3s; zulzm=1KsapYoNRr3x_2zqwfJ!gvQH6by5Guh!k9c$6-Z}K3M1-d?@|x){4tkkek!8 zyAzxe6vl4yW)tI3XOhy3a3yD5cmMH);)=3+`By?mKFH^pA6u=!8zd-$*-Xe|&5ZF>!xb-@$Gj@)(2?Wgyu$Lw=F!A&|FHjz+NAxT z(5qNS+ijiG_0%xaL+rI693z-7iL#rdY67ml)hsfP6&lR2q4tP-Hs?d<5*QA%4Nlha zWvaJ`x$jO*!mJIpnpbJ35X#d#(HAsRx4CQ7*Il(IHR=@!!5H!v)}e#`JbnRslqDY- zFWt&iMm4`Z{Svb3!DTM_A<$)Pj>RxkreW!*o3_F|fzPw%GnRHuR*#91;aGAp6e`ro z)4U9?05DsalhmiA+$CY~Qn}#KX=&ZC;+_^u0Dn&AgT+0g1ir7;{%TYZUCMSNXv5yi zzE$p!ZV2R`y!eDwByKfGVpf%+isSzLn8!mK-Dcx^OL8k7K7w5invK5SSqtxu@s4{H z2l12??8E_qcqH7NyvaPh%sRkFxae6_3}fM4v|| zpyz|i$A+TL_4h)vQMR=>{ z;6P@=LI%(LoZjxz6lzkhdh#84!w6j-en}I+p+*lIc|6_vkvSA@dv~OX#p0@b0H#rx zMff|4npS+_qc1p}3OY`tv_e8BMz^w*XL&IJ03WL8H6Pjp-w=Hc(rV;**unh?lD+#J zGRrOo<1!F~8AQ=iOix1WF;pkivCA~WkJLYxoOMxM4~3EDO=@s?!Kv05r2;X_+gRTS zFD`wi%RfSl%HR9(c5Kdu&)a6tz-*K7P$PyVgq^ZMJ2PB4r7KLcG7MHn37#0HV7j9q z!Y$#ZHiLn2lhFzz&B>| zsn&c-S*>#<`T3)g*1VH(J)Diz?`qK{ni;_QW)yfL0-?$-V{6YUDS}l}975KRHo!UL zb4oq?fs}sSs*}Hv9q2k-?Bt#T-xE7J!p_Q0Il9|{aM%|HjX{Uxk(cGpQt#on!2&~N zD#)Cdy<}d+vU{wP0>Jw_!>gzC<*HpepX`4?4fPJia}}(U71$E{eq=GKTcrM=9_51b zeYUJpI&n}iFcGTK=35U6<0tG70u7Ayw7QJigUZ`voahNrt}I!zBqUT-Y@4%(Jc&x@ z=~TLDmM3!-+E(<-6y>G^g6aiu4!78&b-r}GXU!YEmM8C4?#|?{7nz(67NUSFk|P&x z&z!>wF`sfR#Wn2dAGG9E60$$Q9o3MR|CLR%{#Q25!ty`bJ4OO_CYJxqra73{ng4&X z=|$TG)?xz6ty*y@SK>D2c>;o38fcn2DH_;$an}|CNf@f@?h7ax$|1H!d843kZAv z0D(V#U=aGy_QEP4fj9u|c7IR;Zr@{3tP+|bf)d%`V?#s1*+%D*v9Aq?r=}rq{fMjp zIT2LDBDn^kZl(V4BOgM%6-HraV&<7bJAWCj1Zxs=^V1;!%3jc`axg^^nC*B9hrKOYyZ8Yqyhat;DNn*t-s;)F=+4_Kvg~*La$OD zCtE*qA0$9ul@Fo-T#cO(_b4uiGk`h~WRDyi5P)$LAVE=Y&tY4DcAhMRs*P&d0DU-j z&pbg#6+}ZqC>N)o9)#+p?un9LJAdzJv*+Dso4O~)Ch+kCdTmI5Rh4get%KwKT&O_y z76BEMuRO>T)vs{P@i5|yRrb5MG#^5 zi&z1lp;re`4xs=DbT$Zlxj$F0azRrg;I#n(hyYSyuqYv4wk}1O24CRB^gE#Ekbm|> zrt$FoURHMabZ6oZj6p*=+`goKynDFY>u3DN+i`qRehv~713iJf;#k^VgWUkVJ_Eb} z5D!Cld`;fOes6?R;rwh=1^^JQ2%(t-;@H#i3fSoM@wt>yBb-Cl%?A+m zHv58|-E{CT+xhhqXxOQq{zC`H9GdvhXzl#4CL47~`-O67xiYolsy{U^4pjH3F z9ZCcP)AHUF{VCWF5EltO3XRQyAWjmL1%J4%A;9fB!{rx>4JJk)1Ry@;17O(-{rt}o z4Grja^qcWZpdSFQ%{LyxPwX3?ga}|);SHTI{rrbO!3Q9Ax(8xx@eBO!j!26C2VGcn z{R&i|0Y_O2>AAZRg8;e<@~b;B+0_e2=va?y zj%=x4#M81YOn8Btr;mDV6V=VsCwxaCpGrk`cC0^H8uxeX^5SRekd@&$iQF8T8R6Zz zIKAisnQ1-s&t!c}xnpuQEmM-GU1hw3bFx0xWXfzkjFgYe> z8H7XxE8SFOY27nia-Kph6+eq0)ze~LAsM(bEOOOrbrIn z8?|Ho!*HUg1wVvN(1fFq{)fpBeOXUzm00Ua0kICv$QEI>2WXxOB)HXAVD7FItFtcr zt|s9FdJf{$=;gz~EaAiJYHNPl0X+S2r_yXCs=E;}PyB<9Z|q!nIbYd3thM<&Z;H9E z+9e#z)7!~@LM!QIo{-b#{V#T&OK|APT3zPme*8>R+$pcI@xe}N^VJ-=S-Us>#2Cng z%R_Itksqr+&$@QA#}Eu!*-0oIf8S+M+Egx-PKZuH-OI>_CN9GBCt}f^27biI3wdfF zsBGgWb3(QQ$kR^!a@Mes_NuUMnO+TAIwBP1Lqs=H(hw*^)P064n98_zqM^HJK-s=8 zB~pFM#FnfsVRs!nJ?-qNuS$r_tHNRC0)J{~fd?ifSkx@3kekc|8M1bS7Q%5S`os+b_#{ZaB}Lz^|G`N~@S`ccm6dCSM0M>NeXh?Q4jM(?oGj(WJLF(=7*lE$ zjmJw9LJJajTuqt>Ie3Efm*|{Z-!c*d&eeP8NGMqT^f&75yWQ1;%>H2kSS9LHe~og! z8%zs0oKhL)hbLA1o=YrE}Q^kt$;MOrLDG;Pw7)GZ1 zM8_`=2?)eDTh8ZQuJmM5gT&{5(L30tS|NGC@fFyV-bO;p6z{9)12}2T7fBik%!7SE zOz8Z_BRdbnQ!(6$H(|AGmH*I)rdom@Pyhb8C1NiRB_Rszz9A_i%|BY!rCIyXOPs_$ zS>`J~nf_^Dnu51ejo$vn3PUTck3p_a#R?Ba7EaM`a!D|f0)=AgAQqeuJ(Isasct8* z-i_MmZ)^v9TDX_>+;2z0U9?{rOX7RCdv`^V8KMocNNIIN?oHatd)fzcgjPcwqr~0}eaHrcE?jyeBnOGx0iGt`TydHyDM zNWq#uE|c9oP)ZI$logU}Fa}YmDsGVssi(9a05=u9sw@p~9?-YOVenZ7epmzPA0Ufj$_hcKP<9A1PGE-H0AJ=Ss+Lux&jFKJPM6K-xxEB0m6?x`NJ zE^D|RT2GboH8r3hEe&R1>4Sl5*}W2t8=-^=))3-i=RQ_Ua~w=+g; z&66fr_=_2b4Iup}F^z|YIBLv#njmA!kdcpjz1UyoM13{KB7GdQkHj_=i4p?!FVI+| zAHC+DB`)lItqLU>wlqUJTRsM0(wrgZ^%$~T<;XYvX`zP8RQF%wdHC0Fj%NoxXsN%S zig{bxBLq2A3stPlPBOmWr|j#2>ceyzrVhexgrOBBhTiKvh;uqaLI+!%c11 zW_C0An{p}oF?Y9jW60MiLJFVku3e7LAzK#3rZ@P2VND5dd)wk`p=r>jU-mu6Kep{@ z2t>K(q5nty#ilaoZ0y9C%nhBmyf3G7Dw)oBbHS+?S<_lqvLY7}gOlZ-@TT}P+h&1% zB@*g;mTMb#A!)gDY|SH%ZYyI}bqK*QxH^5AyR;5ynW#6!wZOi65U@jtz->h0rseOXSksqj2i{ z@3=ZbICn+(v&UL@TEdeyj=-;c(<$v;?HPnuqzzWq(KLc!87-V{oAF+>bD;Aaf-A$M25BKrF>-&D9i;7&QZoot7M8tFq?u*lnNl0**^l;GTTs)jZiCAjO z8&7>E^5Bqq$N)C9qds5`o( z2U2A;xW)$KwIHHlL<+liDq7mpgH5oC)GSfE_HgL%3-3{`?4fAANm&7=wrJf$40e*b z8T~fBm>I{Ds17~J1p6vn+tf1vl!Cj&*Wa7Bf?03MiD<|@E9M!672pS5V_a^rr9*3_ zDBszRHA;KV)d(*hjpoORAzGwm%^~n@%&D=D6fO>cL!egIa?KR4Ya->EMRTT7so>NF zWq_mAc(*;HnbSs9v}t;U!i)1WbD90zYal}Mi1o zg8Sw!$iTQ+4=xn!iH;su8JfvZ6+FJ9Rfp%5np47JfsC=0%BUu)#g3lP+kr?pzf*ED z{fXpU!-Jkyh2j3wc+#X$N*VS%%3X#1qzMy0tmjjkWmtiVCLc7@d}jD` zbLOGQ58zec&1;@ES`5b20aMD1#dpP1>>NO8jvUijO%z4njWb-4h|zaEfGI(Di!Wfr zPM!C==EoQ<`bKueqWdqR4dBAMoPtf*Qn>F22jueZciL$j~=AbtC7tj zFg2UWq222w8yeSLA3(!`lf=RnzNkQhB5IDv>P{m_x{`LUmfADK5OxJxmHVB%2HF*O z$$CgLk1}sU@D)gGAAHlvBh6j7Jr;)9wVBA!q8OlKLc;b$P_9~sKXVVrTf=l<_RhPs znKKk?Z{Jzb%gsvPW;ILj=Fjje`H;D_j}6*}=QRorYtLjzuy1+s(VNIQN2yC?8}Nn! zzx`Jw|fq^T$EI>y7u4kFJFS$V>zW`b(hT{x)MD>Ke(b8{HNL7X>)AV)KPB%fZuD zwk^z2QBjc;%YIY5Tx9pUS1TVIMiP_>?vnd;iMG*|Q4G;|6rK)4u-rf1eIJ;A8zuF* zx8uoTTpZR;d1OsqS@Y&)JX)8@8NfvEoaqyuV~LX|CFV@Hx%cs0+|gAIcL7cd zx-7bv2Jxo5XHZ?Tr8kI5*WF}4hf9TiF-4LvF6uAUIsu(iRPe?*N2LspMf{m^*`o?s z%s)>oKQWW8a5(?a$3fHim@JkyZ?O+xw#JzIG^F_{eXXo}OIGThOe-z^jc`#Q@jw zu~+A-&P^(>W}ZnQ4?(qc`ZN4^detJgPz6eH&z7HY>rccknN8}f*L97Fp`^Sg?%_`w zN@_Abto>I7B(pwBj;pnefpsayE-od5I6UPhR>q}SKM>GJQ^HN!Z3pk`ye1C2xgiYg z9Z4?AO^2a;W0FN@LJIQSWCohs_!gnqyih-)pBrVTK?-I2nk3;)hG=KY za#{W%Q1~;s1#QuGdZ!uTYIYbL?2^u5tTdoh-y0DGNE7$7fHBO#@)GVNAW|R-N+{g9 zP-PkGis!?me^5Bk&(1d+u7bQU(Zb#Wi%no6Ubs7NG@M94UJ0+4zN3EiBi^w>M{AR7 zqnD|dcfHU!&t~dSZoL=73fW0B8B^Z94wurt-RI-qovMT+ZUHYD**-{ZzbCD#EwmwK zvAhgxp=BoZU4HiBBJ1vKM?qh3b695Pu{5uYSZE9C#*AY8{&!1EKQM4);8wJXVh$quMR&d~#Of+FqqyV>C>F)$7H!^LA!V*&uQD zjTrA(d~!vNZrh5>_K*0@xZ3oSVB$h@3j{v3IAWetFoITg_N<$*8gfl*OCjbtePMj2~~k)s>TpJ8%z;s2S0@r}$@fXk5pd4VV%{kt%Uj z>#;KzwR_5s{4mgViE_f8)IN3b71h40Br?no5CL{q(|jrg-rW)bbuw8nkUUi%aBm0_ zOtN#*UBZCIe6q>M3yo{(2j2CY;7Y%+3EAf{L>Fw}Tzm&jr^uwr&C`(u?1UQ=eibxk zS}&I=uYC>xs)|z!F(?EwqW`TO)xhApx(z5y({jf-z|_TghN$(NXO^))OE{EYy%rRj zaywBVDAe%T%u6bu>8smZ=yd>0EyZ`4gW?Q{F805E3xJ*|#INS@AdME>h|bfY+oae2 z^Q?6k!o^hR65*AaBhSWhj{WyS;9l)>64Ouxm58;Z_{i#57yZ~~Z2ZL10;>7#t}C&( z{%=ArhQ%O8b*eL&N3_o27N_+CQN{?$?Ws;#2MOb?nd$ej|EGdYm-a{56czn=T{ioF(kCHzMB(NIaAI$Nk zQafk~%VU|`br8<(*z#*|)cle?M7|ehq;6v4tlUO7i7Uw(yT$N)z4^;M>r~vtShOTJr%kv%)jgkg0;Fgq zfI<<7gQ!8+AI=x9#WI4Tr>XvW<&;yki-$hj7t|>CgFoam!53aR+MVP)`x^L02^F`* z+ZE@xWlK_qySfkB*E|s~Gy%YphsPf8VwborZPO!5pJ7zPoh^ zFGdq46lb-8irS{&fqMSZfaw;y=PF*fOqceQXT2!9BWPNsfgJOV4*5?puvnie>9?1I#Yo`UX=5`GVC+@Z7w#G$XuF}w?4VF4cRnQK?GmS4s)wLV z2zn$F4SlDy-H~OH^#{-pohg?ZOdpargg@*1A5Kq@+m{=;cZo`*CMq|Q(;=SQ%3wTS z6wZcDKh_sQ@u{Z?gn+s&hQr1ft?LcxuBRX%xhdAUB3~F2FH=gs(-`z-i+byW$tTiY zdyh`I&-Fke{a|;2N94hIP8Jj1%ugLT;IZV0RXN#Dr`E5K_@Sxzu5LmHnKBSHVfa!- z%_@Xx!6K(Rmg=?IN=j0h_+c%)@6*|{27UgzqlQ@jwBuj%x9xeGZgG_=*d3oGRkQ;{ z$k?xVdBQ3~aH|ofjjft8uXgH~AW0zgJZZhqYS13xrhI&N)G6$ja|FW7lGBSiaF9Wn z8uH@2ST?%tHaKjH%F}G);{OZC*Y+9eZ6`>FEF@Y&(YTnXKf60VL z*}BeGISd5$UYjhGq~=04URj7GF5*C|aU9jaDnyEJXqkWk-?7=)zb=Kyt1rJG9zse0 zFm4h3>R9+6+|JH(=OXJ$#>NUE4`DX&>MT*RxbGXQUuN=Z*ojPM9HvCod&;;}Xc{86 zN<)UTXn;k82~rgkYR$a%iUS4B^Ec5A92YNk(#4bZ`DQi|j1Vv=ymmBgi2F}l(VuS# zw)oy$0)3|*S)5Tgul-n~`e{RnbB>^W>%nf3waoz5ku|4H_tzcPx;gi$Kgtp{ytSy6 zFL@>Lr8n$~!-9T`)zOvBx^H1)0a1BWZLY5>rUqQf4{v1D@l{sRfd`?*3G?7{1iLW0 z%eSo+>u*nRAKh-6VNK@w6Xa;x4Hg7l_4k#*8$%@`K48=VsD^QFD7l<}{OwaFfqs^u zW$jbe5V|G4gq&VtRQU|K+K1CfTYuIYrRW(^#GGj!*Oj5M=VnAbnbPV5136MK*+{!v zkg3iYGW6^H?Ya=rDPUg`AoUt%=S69BYTwbN1zkJT_p=}Q9PE96Osd2{kqW(iy!S+S z&6mp!xJ^?x4OSit4;3b0&sPVwAK!naK+8^zbK$%AED~$lzHaQimK1Izwd<#d{?|hn zD+l^&c7onY-$u9cMo~NgN*Q@d`q!P4H@udT#@6u%^1&L_-9=PG06YMEP;u{8VFq79 zYK1)d`EB5#M=ua_lTZm(+P-{K;aJh&12sj#Qh%*EQe6KW*R<1Aav?*Z+?YLG!$?&w zm;Kvxicw2;L)I#w!J1Sm*`klivBtK;XSy$z%=606H3gvHnA5gUNP1RqfwD#&-E|1k z;*rOoP-+&!Aj#4E7so^4b031r^&+B$FOi}EYm?W`_7c5PQkDeIV$`(ehk1!v+%zW| zkorYI#PZKTehW?S)sc?o1?s^dnV$C+J8KXwBGdTGE_~92%bwI$DNL|O<9XGt4+?mP z2DU+_v$Gy!)5!QCZ{;K*PefI=3v;AAZN!Zq9lldh zlzwEJC`qXq#318^(>7{~D&wX;VNlE}B(WlY@pNi$(L6&N3Znk3{ zHC=p{tDMD8msK6u0O|s0VgAK&k^0wC{r7RpC!A2wta!mD+~r-C*ITwW6Uk zJMEnQr#!;by&gl?N^lKYrpr*$QlvAjmCT|#RE@u=s)S*biNWdN+@g}bRo7YpDXy4P z&AkxO@@whzQv0($Xvi|f`3&LpYUU|N;GUa(#EHq zW$5DzeD;*gyhTb)@z|i(F|Eygkw%P?Ikp8t>{}gcHzH--)-Kj44{T1CPKU&KB%6pC z=3>4JDg05*-W2qO@~2onj%Cwglrn^`U&pvrE%Iie||jEiqI{aFgzYj-LYd@&>p> z@_6BHLH`e7g5ehnhwiBW72C#{GCOVd+AG(_-~5mFjou&6NK-Q zt?pWLWTfsB2%HIXeCSS^YGU?N1r(kRnp&T3Q2%&66TNma)anI;L>H^Js7*z(F>dY1 zqz9WX~Ah4pVyjGc_1(PSB-G zQQ>R%Jyu5X67F?%Jvm(}DQgr8J*RN zJ@nAI$p0benL<17D;0}-q591_ki2hznQ!~;cEQftn<9BbuTe8Omxqo*@2AAzsq4YK zO-Vw8be)w44^ssUR?^-=;ZjC>VvU_+U?UEQvnB$gX-+{6%F8ZcZ3Qo?uXy4}*9;B~fl=KmUzRQ;{asRZ^n+H#5 zUtpS00t;;1g~l4M2uMuL(Q^xzrbt{Ti?cQlb@kW*FtKHA)2j_HOc3u<8#c-e4AgHY6-dI#{JOX zj4E>MCy__j;xjOv_N0^1=_aT}v<*T5vcmCT;Y?Ue;N7!bai|5cV>UAxWX+p(tE4+u zI+w&WFCR0nrhNoC-pEs155L!R8P|BKoYiBwY*ZW5Op9*&^vpej>?@~QQ8OCC#jJ>! zx(UK7Ss-~iW-q|CYT%*^imKo{!!G@DI%M8bbt%jlD!ys`2%di%su;G{V4YT>PN9LF#I1{$FE8B56hqbS^i%pQ3lpO z?EkMO(Z>I65{=TF-Q8}LIzYn--~ti1!!k4Lw0DKRmbHU~>kI5a#sLZ<=wnff6EiuU zp6vS3ebRAWS~0cOHNEjZEn8$>BbmIC5vYH5k!K~~Dn;OzR9DZz?;RVPnjRYq78NT6 z4H4w`4WB!8;+LJ)^W@6+#T4i8m(H7EG)F#d$gc0g1xW8~uR+lD)g`i0}%?CyayHwN&QzRe)^nhk>hKtbI%eDA@<)q-;P zPf1?_jFZVz$6Yy!G9g3oFKolW1bBR^LWm+#Q!EOE1rAJ2MQ;r*r*CbKDJF%Z?t+DA z05bDW6OgOMaqP0``$dG)p30eAnmGZ`QrAA@I>>lJmt}?{L)_B%`AzY=OwZuaxf~Oa z_c}WGm2@KUF9908l-AAXf>rtTT!R4^fq&y()8Fj)_qzD9XZ~tbH#pN)-Tkg;0MYay zAo8dx2jQGU>w%;%Cw;Lq__MBZzhtyzdJ&KpOau9-*Z@Z*%YdbGAiqUs)+Qk@0h~=- z!GwI24qtJP-%^Y(CyOtwtp!}w9 zwQ<-RuXNv)Vh%Y-UDj-<^0TcX31y?0F)&{kB(gIMEr=F@e}moSb>421<>@lnEeR*q6N}? z56(=v0(AgyJMhlnA@sg|yu6I^H`sR|=k!?7Ezx{Cs{I+}h$^6(+__i(l=>Z*U=O^$j!~B{3 z@m(Zq)(aca1)C|n1oGB_HvTv{s{PPiV9VoERmU`fbE*5%t>#`lbmt+tq{$V_f*l>0 z9(yRoxuk)10Z*^=&o@!=g`4;FxXS_tY6dP};|lccVV}{-%K9nv+~#D;JW(BbYcuq% zkj~0gMR*r;^fjD)NceKaWppulKJICWk4%Nv+dnkg_kZR_ms+cT~j>6Cjr=% zf5Ya1#|j<(-H?009|Yc=eaD96HU0Aj&LhU~g$>A&D+T-m&1>5Djqc^r^oEWCVz>GY z+m`FNz7at46AlZ)i+*$q-*m!=Bb}9}haASS+P|-BG6PlWyXz=2^8oebnq?Y)fq&cc zu6MkD__$fdw|vqj@zdwa9ZwL)H40;GzP&BYzS>UL`c)ztuo!LaDF|{$awVD?X?!4o_iewpC7a=9bvdY`53+S8i>$&v8hU@?#)jp4sO649bOd z?jj?~1FsVEcpwu+0xBP=)CYs*p5l^DnZa?wM~0KeHl%%fNSMu|Q&HU~IL;+`Mw_Kr zT@u77fHO1`YZh&Ru-bZCiYR1LW@9z)=4MBvsKQ8|I>M`4M9QvmcpC!;Q)B3i_$CHQ z-VSz?w-`2fe-r{fUgCj3^`h$7aQh^s70;;ik76|GZKrb;$Wazc|bKvl{dpfz=!#+|D`VS3F&^ z`}~H(PMOZc;6E0o7LoY!6!7<0jpHB#Sl&rt#Do`CUCGc>;jhwS(J8^<)qc|ZdW6I7UB<(qZ z126Ps6IjF;RJt|;T*qd6h0|1DNl~THQT$^R&afUIu~U6M$M_RF#o#P8o)T3gphq*0GXkchjPz9I0J51@_cSSDUD?JERc>A%1Jt|_~L2`odFRe^x zk}i%j`bndpCr^=4o@+gqW{;Li!W3{^LjUXoy7*VwMQ0UG7P!db8*J%`yC&LZiV=g{ zSe<>A9^2|2PRsw{%v@j=XFO-pVQ~qJ`-&6kiT(7n1R52=~Ss$jlAn6&O z-WR68=|XD(v-z5lG60HUSL`3t*(V+ZJs_q2_FzXieZW}LEz-f8{k{zwPvA)Fq)}c& zyiEN;lY=?NBcJeGRZ%n2PB(Plo+tUf1sT|;f~M6zjlNJDxTShp7~!NLyJ&=GI=}Lq zdogaX`6Wx1@zWwI^goS8)?2uFIXI7x&Ncsga?S-=(%zfI#dm!x-cGrLF+S>K$eU)9 z0TDGxFW(d!=d+uw!##p%YLW7&;OBUEzgmqLn}+#OlpK9oV`N zYImgbAn}gH2K|v&E&Am_{PHMQ@fNLXqqA{A;!_Ar58;M&vKtN)(j2;PVS@mdu-fQPR1ive7Hs>UJ`$*J|?Q(bg2;apKiDF;EnMg@PJiBYfs4~N-}(n}1; zYk+?Ek7F1o?6s&>r9Z?)Io!>AYGh7<;k96iEbVK^u~i0QZTIM+XwO@-7l7(KRF)lI zXJbc`6kp&9E=_GrFJdJ_qSo6hE&Y}01tj+zWo(2djKT+-4+VUtXF^2*8<#|EfELx3 z8z+9plXDmjM*ipCV<5%gecHGESar!O3AfQQSCZ;EETz)-$6{}RU&q7k9cZ_cYOYkL z0Uq6$oq}}h_k4OC^hm6eY4?r@74_DLdz2W-r6)Nre+5?}3)~N_ zg*sI7kdkKYGou-HebHp^Uv*TBo+{W>M&)O-kRXXQF3=`H=*%U%od<~qrMGdYf@Zo6 z+fa;B$>us-WP+9qc41z+4qB-}^3PQ_mSL}#`5$1qCkt`a2$q0AG`5t4`^AtlU~fhF z6xV{-7-fSFOJY0Ps)g8|B4;BBZy=f7kY;`B=on z71OB?UR)@s=z4wgEN0Vsyi;SRTu9yc<0z%^6v4R4VnU9VkuYk6O|@z7r+|Eh(Iopb znhB&`s4&Z(Es9>BR%v2EPOxM_S~`8&S?NAEqgVGX{yGY(z8VkHF)pZ={`qO|02?sd z6z|J4kp~hOxF5e2wWtV0=yq62C!(98lp3 zKv2`^cz>PaJ<;PxbnfzJXLgQ9gR7V;3m;M!CuEQt@zs6R@pcIoH8&nZzA z^KMR}lFCRP6`Zm~5b-b#CaMd%yg~942a10fH+S#pg-PIR<9f}r#xLl`uw~xb_!Eg~ zkS_mglxu{#R$ZWEXpuZ&DoCs{Q+8IxlRlFb1SB5)6N z0mbFy&IOIGhCk@)px{i*UZU_ILUUm^y)<_O`fH_H5R5dv$QzGwg2kifEhp4D`&ViI zmcrk<;*Qxdk*80Tv>g&naFBE!+$d3S33#hylqZk)W;_x>j_*ZcYdSyu!I*S+UrrVe z&5j+l2?|@4uasZdJcv&QwfrwbkgOiP*v_g{Vv1?xa8cfbZ!H59^+JoU%$E-u1#BQC zuv+aSt2ST#iu!^`14!EQfD*NKNp-rw9XWhUwYb~FNI?@k>pe7**}CLR!4uIKfWvB`eP|ZE$6dYRg)mn?Wo}Sj>|w`20q(W7w!ACv z^U3i>-dsf9CDZ`GXF>49a?*LvG{=9>5znti*HjBu>1z=ax}Frf{}gHNRFT#(=!y-0 z7{q##y=W%U!~1SMglV9_j7D1o3Z?!yTsYAw_kx&ubi^fC2llHrNg-xEpxoJAQO<4_ zlE5zS#FzTCHK5Rj-uKgPrz|l5p>on#Zywzf`qU&SzpC@+_-9w!vTm@B68l2gCo&;4cUT2_t3*_PoaPS=V(VzGx}H3+4#dbF*jYYJM{JC> zb*Q5of+j{*!7mP}mlMkdn>-7AbLpvf_wto-(e$GiTi1?{$mu3~hVj}8kos7a!rSwi z+mxk>bkjzwLK?&@kBXQj245DTltBsz+PqGGB_Z&3pXF~uiSpgU%g_NeS0UDhcni1P zXqTT@{THg?C}o#`bbLsC1mHI>)FqqJ{vk1Uj@rdU?~KGwahv&`RhT+3yIka52NU*@ z%rPheuQGzzwn}3BP$*}a_g`0wq;o)DX?%@F2D_xk;v#yee&~N5qY@q~MI}$i+3-Tt z^vAutta^6pR4YteXe18(tM{lq(D9RNWIeZ`UziSo1b=U*3NUg!Z=KFdqzx5`U5++n zSGT8vvMNnL72aXbA;x-{l!;^-qJl@I3?dNm`E<_wtToNAl3Xf($yj`OjEPgdXGBnm z>!?t;*x(=|*dBhXSX#2|K#YeUpVA!ij!sa_1`?^J1Ctd1A=Cat0AA zQa2{UEd$tX*rV(FW)a=u3Nx^>Vb(GxNXi}7yCCTKEbfr34~l8bU}2W-QYaup6SI`i zTRvpwHUt7K)JhOH=_WPW7_EX*AO_<~ocMcm1R(4}tCX3L?>;f$X(|j>vJ2%Jp81&5 zsUo+`JJUMS+lNVuL`;-k^X1^S;V6Q2z=Ut5wwD?^U>=Gs@ouMm(|N7|U$lm!94cZ^ zqA4WU{az$TnZN^EzF=91ZUYO8NMN7WG70I4LWa)$C=)2oZJa#MeVRb$xj>_+2kV(l17FEl<*3u=b;6@5y1iNEw73^R`}_0%@;=d{W#i{}IM3qaGN9s&v&2 zA+glq-cPZg?F#w`IYF6GQ>_~7R1{Hu{t=%EbwBLWEp zCr zSumWLu`nJp6GKgFHdZDu)?_|ToEpcE!(z4d+X*d}Sz1=^5RU&PY_aXPoRVnwSf5=T zDN`Zj#U~eYU@}}bN2RLOn}5`cXkf_E4P|gt*YHq8E(uqYFCjg_g0ESy$huBfXNI@1 zHd4}sWMcFwui2`&7aBbVRZJT#(+qP}nx@+6EZQHhYbMx|5Qk9qdh^aa=)2BOHfouQo z4LWL7Nz51-`iG|`<<~YmC9Xb>SrFM^6rt84th5-31?>3HeJY%K8#1Mv#amUIjHi&d z#Pzd1B(`-?F)=mkMl+xTX zgh^U=6Gy5ZtPOoW1|s2;B+P2Gf|;s*nN9|)m-`+s4@lrraXxFr9NHTC#osd_8_#Gg zM5%4shWM`+&$F2#S7K3?Yt5F2e3xr237L*2bUl?rYq*X4?#&mIgT zRq`M|w&6cJ53!IOz0Ckt(V$wS=3`HxeQ+D- zO-C7@FAW!+|G1{$u%KW3WH_cxyF5A-#th-8@NYk--xf(X*w&UZ%7wV8hs&&cJ4O$F zl~+uR!o2+Cw@<<~Zh9J)qV}R$gZvZT)L!{k5~XXfqt)VX?4rhdF?)NC*3!aRRdo8A zY@xrJHQD3pzlw!UbjOup*HRHKl0Ly@htRBtM%zV>*x+c?S;^m*xa?sLC81N}bdgh` z^t?xakq|G5l{&7iU4HL{M&3e)0*eS`CS4oF5ZVL^^llKyf`mBfHJ?>+3IR=_S(4taJc8Ui##MvUs`42+Wf94vRkrU7>a90X zlEim!AFGi|qSdr?toBmAiRLc&)Yo{=X*5P`do!K|97c*SgDL8x0}QUW$tomBz6XCd zx%aQ&jmcx#TWVhwAw~2%h`@3>)DL_=1QD_*#_J^A&7@GLND`57#7OyuXdv3CwGCxO z2MrIqkp*jBpkACWq;^<|piGPK8v>u*u)&EUy&IF&dGV@nbP>&&7xv}8Bp84UcS_rN zI#sz{%2-U2q**-i_k8&_?%omQ2pGPSQ^+2--!CibMG5FN*Iq8DvDl`zEBbWFYKm8V z!o8+3Zm;|o1VL91iNvULN%l=;XR_)I#xdh$mev=Cn+FEoHr3i9cDCYO+YLPIm!b!6k9 zo4uL2yDi834knBi9TlXT4jw{ZPHapjq_;)rE%xwGewAhFC!PW2xi6m6d*`@}x>Hkr z+QRU~c&CI2!fMbtK8OPM$jqvV+_Dyp|qcEP#n*boU$p^+Zc9#eFctZ>+y{ zZDU3*)iHN1XvU$N?=7*QBav6ghtpI(mrFF~(Is?*bS}NV80!?EqiZ|YUnVh=-D+Gm^jWXs08N5JW%B~ss=t?XpPCUA5C*A9h1LMu2?-) z6kN%=THqJc>qyq`+EY}4&t)K->26|MlwmHVv}tShv$7Z2_VL_Hn!}jGj-zl!a2)U! z@n1dbk8qefcgp^!I(bqjv+4V|TL1AOUX~X-lUP?(OUkoG029mViG*?6>?J||iLafv zyet_dqM$oy2@=_A>D>W+YAHcy209z9(XwgBrSr{f{VZG()3Fr;RV)3L|E_uLj#vpV z2e@i+bSe&v18xu6C2-vYgof5YBy^W^s#IG1_@iyl_r0wq-39%Vq8xJ9i9GKy0HdJT zChrriS4g(tU_l<$9Mi~nkQ)V&5!RPM zhbK#K-AqWo77b?5ZHa^4y~LXAZ)Ik4W~^J@P5eigd;UWGfQU`@HQq>;bFFc}rftcT zrKSy|_Us~PCFr&*OfCI0!#$X#wKyAX^|~Pkrv_){s5oE}+|mzWUi)!;yqO2u?%ZMxuQ1-vcz&_n?O(G+YbsKavoUr3zWb>`GL6 z9A>d5_(ZScZrW7&N02yTh7WQkk9w#Ms4S)4^Cmkx8xg zxGjYb-ZP>MMl3`#bB3ow^@OcBn(wuO7#ctkJwdqF?$d%&I#xbw-DLMc;(SQby(l;3 z%B#g9iJV7`^enZEu&P8h>`cTEPhjvS6Wr2c7G|35;ASGT%SklwP_-7VQS#fEU~Nt7 zMg2f(O};k8ybB-xH-nRXXC!6#H?=e1_c^e9EvKhxx#Hh1(!6S6-{=p;DRcZB2^j zXUfhEqUMo?mg3YJ)_mKq|CB?XJwRLM)##x9jadEpK>Jwc-BhT9 zOktvYa^CAlhGn$PkOD=?9HT4X2Ie<+*^>bxLqlRqc_~MIbp|bZn<87}sJfE~(JCChle`Do?lIo7sKh@63l4hj>%0_;j@P zQ5>rx*nqM1%xJ=giVvcpS$FPE(kgEw-YSnPz>BJ7(#H&?G53|F(9VZ?NA!FNN*|R^oiwuVRO`dgnrI=2KQ57-b~lGO`C29b3CS zebfB-eiiew2MAknvlkb@o9dDm!-VU;j?a+w3gpam6>^49?dLE|dV?Wmc z9$%Xu-H}hhbaW?9sElkydx8>5n6I(F(1MAKBS6wlK!nMFtRWgSIe(({u?iR5!fo_` z?}4WVGPK4uq`lH=$!f}FLrd(MFW6YrNjfS9XkENurLCVl@mM2$Oa}PdM_t^n6cisG zDaX!vrCP$xm4FYI6;w72f(Aaf@T|A+9rnvmb)(tnnOQ=TaO^>&v`@(f$WkD)dbniP zoLP0<_Vp8)?NEwNV&v}DB>x1IGh?1;BxNxpGmzhv6-8n>gExO1w_g_t2pn4}NKJAO zR6Q$6zGy7jZe_lpyPQa$aLE7U$=<`MOg=HX`tXJ9ej{S%)HL4T87`AjjNSw`Go-y4 z#N;dwYP_!__HraSRgpt?4_tpApN}Sr@I5^bj>`Manma6%y+6|j24~@VKLGl%Gi$EWKy5@I0PW~C&d_U4R6lJiTqibj z2wgmb15Rx4{sk3Bf&$gRIw!?Cb}pjqX^*9N8a`WJ9nsSJZXcG-WR|aYpaxBCZtFFG zj#_L-ZkP%0Z4qNVz;k+>{%t(pxsogg7M68X5gEjHp|q{RCJ2W2X4sDzm~V^Hg3?41N^pVcZ&$O1k}L*)}m zg?=XbL7d=NnoUs{;e?~7w{4G-B?ZBjI_VnfHOPE~G$vD~uU4mkj-ZM+?K>MES{*w0 zBzb3t()lvgYYRFpp|`Oo6ue!bn9Zi_pP(G%lU15KMABz|?)VptCHVWXDcMq#1q!sH zYLoz8Ibpz&X^r7i+~aqVj=wNqQj7Cg^w=b13~nee@nB-8BfaO5Ed1Z@j)G*c{W)GoY;Gc2|_SDVWfidzEx1ZlQCW{;^v8fO(}#@8C=Ri>4N|4 z$ZbK-hB5`b&f8h1_e$leC?Lv=;2QO6VUaXC9931YR%}!~t$3dJl3?gM;qn95b8tvC0X!R>rC| z_Q)0?;*BqAyx}d^j6mRWm|D}KMB7yFigh+ix2h7rpcOn>QXyEO zBDbXz`=R85-@n!|<}k}a%hO+phOO9S*M>!h^~O@>wh89!;iszG{8P~9F^F-GGYVwd z_UH=h0k+5iAgR(ly{mCoOM#)094mL6>Kw8GXHLiFGW1}~L^AOP;m_jUoYnM>y{v-) zfT z`-9qh1#Ashx*%&i|bLNDFo?%oD zV)sK1hR!8S9evtWirog{HSaMHZcvv?655>z=0P@1Uzh}KKRRDfZUhinUa*f+Z7T4m zxjg`B&-MP@CP1|xQ`?Wdy_@S$`K9e2x*x;Oc%D^u>6Mk`$1uYkFMcW{?6mysW+-i= zGYb+c?ER&0D}njL(+@U$NOpQpMY53e4rYXyrE-^b{s>*;*&FGF?Udn_ge6=Q5q31R zSh+L?W=WqzSr}AJlQ`p}V`g?O;sKEs1)lbR&E+DLr!=-|?8+#vmLAUMa=Hb>N&bO% zBCBtfCVaGGo?@|dPcu99>#CtZ1F+sHZPB zxC)ol*TJ4A5PeedW_rDiRAESlB;KxK>RD%f@|i~+?;}slclBHht-bXPU8Y6{b56*K;Fsu2Y(zJH9$XcDIF4IRqyJ`ky_Ttn zDz>l9A#~&5)o}?cPz*`gGK+ulkl~*^jgR6G`|dDi;3*xXp?HQjBPi}dMWM01p4Jy^ zs_2358ZGO~!6t=O#_yOUr|2u&h)9t)iQ~yqurxbk-joc9`Et6&yRh4iP;mPSV_WhY z`G;dyS7bo1bh$|VA}UNO>^afjyvDn0AJ%Xej_J_*Rgjf}m3ecN^x$MPIb_n?9$b z>393~Tr~VN`S^I63xW}yn~ii#_C6fN0I`+;8e)ZjjXO8b`$P4aw!ItGrzFo>N^$kWxok0LN2v}a>2GL7{A=C>S#jP3+ z=daRPXX(4dc2Nuzaq1vXhcEerU7}p^^H}fXHYF7s>Cm8G)YrhwvRwaZ4sC^}J(vo8 zZ9_3ThM{r#>9CQq(~%LM9*88%)2ahBeH$ zJ2;2myr~#exuZ`mQO#{x2MlRpZfW!-eCqX$f**$PJ#*%GOxa+3_vHr%P{Yy}8uMU#VAZ8|QqmS1=`#y(x zneQ$nI=t4;$jwpL>Csr+o|?bWC|JS^MMb5@bwpI> zQLi^#rpG``(|6-1h3f5FG}7QkH%j-L5WlvcJs+bY(_e`#zL3a8+Ur(zp7@s-jwcF-X8xokNJ8%gl2lP6b=p=tP zqxoc+dQVxEVPg~It0-7Y5iKo~L@z>YKIrhK)wSO*{pdnKli9@r?q?r$aeQ^24)q|3 zV!I8E`%6?~{A^{raA?_Y;2pC(J!NO+3^_O;G+_1c@BYEColel~Lq2sF>0EY@MAu7< z5KH}0?1nQ=h$M_flEZ!nIC#bv1KCAntwn3GwH*j+l+^vF@wWK_d5(=fhytuOu7A8e zAx!peofB-VIuoCFt9q_G)sN5^ke)usa=Z$;A{0RvKE>XqiWHLSkJ`2iF)3}u-|t9L z{4Dka_$svefc`n`FHYr+DsE-~v4L~!QiMPy&Eq?>BhzM10)J+J2$7p+5}9mr_G0$| z6e~wI8>p03L8HatHJE&lKldAz$eOwlI)0j5Wg$=U8`c_fDynSL(mGrmUQ_i$CVi;^ z@`{0hT{rJ%(@Hog^$2!cVf;+SjQq3nh>YoLcqmw_pqlvIF&V-@eO#k;TRJAl_{BK7 z(xj0#MP}=XT8b%o2CKFd*n@!{(dCgiVTSUeHx4ST1;)G%RY8#6vqF8xgAK#9RR3CT z8ZdbQ#>Pb)K`+HHovxDQup|`z%~TVU&OFsI08|&(%rhfA)P;P&HC;2P#K=ag^sRU%DT=Cih;1boN8%C6?m zA>h4bIxupP;`H54mz(HGw00=4qg=URuOsLzV8ZJ*v&HdtYPKCaN4j4$a_{EP3U07m z5-PEp{6{7^jU5u@5sOf*h2%m0>WA(+OpcoBvKx%!_TqNDX&pyl4C8xZxh9k9R57K_ zMML9R3DvR-)3vG!DJ5!Je-pu$P)yBPAv7YhOQ? zyUZGykCLo+3D|$ey_~ycXkU(WaxF)q@AyY?iPd*YrP~_gzhF1Kx<9!$RNl4u2*x|&T5%HZhtqHUTdNl`ms*^kf>I}8oQ-w7iMd(K z$%ZuId8p&T?aw9d^VMXtyn8z(sI9L|F3Ndp{V0dP#LF47o!9=T zf{Tu=@?d%lh6-#|A5%YWL8{~PFLWM%(<0NvW>XtdFtVF)}i zV1b<=Zf+1*3oNiK3o+96(h#=&yzzTCHwatXq#$ms|C8rFZ*1}L^6|R<7ZNKOC$fcN z2Au56kEOw>x(Wo4G%@i21mNaIr{?A+2gA)l8=A-ZO2Z8L18#i_5FiNpi%MVt55~o} zUgRGu=PC~VqpANnBO|K6YkeT^SW^iFVSpplf#u;#2`~&5|WbkFg49*SYzV`m! z_SO!l&keAKYTWyZsK?qxi3 zk^y||R&GWKjr;TWEq4XZ`1wi0!98;=k1l_35svGJacdXjtI6bdJB$Sdg!#KWHk+pl zAitY;4)#zIK`tD8Z|1(KwM2iF9|T_CC}aR9PZ2;an-|cO!7F;#=;RQrj`EA`JK&8I z&>G8+7?2MD`wo8yUZ43L+kxjeBd{9x_uh#|G6VLD{!MxEN-rL|&-90W3|K$t3z`qL z^#>gVpl>J&i3*v?S$dd}D5iskw5;?ZC(B?O^ORjnY=o*($z)C56y;t*N zy8lP-uADT?Pf!;i>yZDhyr2B|CyV}6Nv+1O?>7@-Y<%a(!q|^yVX^He==V)Cu)jth zVdM%0=83GYfhYgILOFXX#KcJg;+Iml z4HdGpvZ?r7=`|)YEyZ>Vord1TH=~y&BHOdeKQG*&m!vdzpgLsI8=G8^@@=~Z`cDiI zNG+<)(o&an65Q&cipQu-G&HY44NRVpexa0;m4$625@Ngm%uZ&gQI2Ho3fU~?edQBt z7R2wf{NU_8mE=;S(DW+CJRPY!HLp)M^ji*!4Pg(|jBl2B6F%;J@$OTiv_oO)8IAG& zRdv4*N4#`y?l@~BJo48Pa8_a>zfPf`v73M2R9O{ z55*be)f(I10W=+_9nz@aLt7_VVX+KM_>WvSc!*n;6imzvW}&Z<;CWX1#jj;|v?%hl zmXx{0J^3+VqU9kshAvsCX?d~-U5UZ++-&Qi-Wjd(+?P(#6H_J^h>c&t0vV9bro2~3 zUWeP?_70z!8O-Z>72jDE#Yjb1*Vj3PWCWYl%fK>{D9_5K11{RWPesSp0DBy&9oPJ` zsRXeeBRw&MW~3gxB|?l>)!pDBwNIt~8!!Tl-Z9KO6)Ty)LONi=ds>Cz2XrSWBMt5B zAP*M2AEyLk?~j4~kB;;v4Z#|JuDF@yIhL)gtJ59f$(f5f`AGLt#P-DKg8cHaN+jLI z!FU5l*>LSKbjQYA{sHDS&q#4nXdQ44u$$qK%hj1~lhBGZg848%4Me&UEwnF{hw=Gi zu&>K5%}_067TI+lhPP7TF?#4Tc1?S}YmJJ6nX@93sXq}HCumXe1+(JK^T<60Ac zdnI`KJilvG)w>^Dg%-;M#q;^VfbhNbCEgF0bfF5E8FGmFV3}MKdt*-UsLUAj3l4;( z!3qALGS2?sd39s&4P0V$2~nTS})b9Lm;6$o~vjlfnsw1@`U5h z`nUpp9e+hP-Gc7VjuzGU?nQZ}LAyGIuEqHT?E_nuu%i*nELq(N&Xy_j)%v#^p;=8< zz7CfNv4T(hNhEGN2#F!js0^K0$qKGPXl=9uFK)^~E!`l5*H8 zVN(Mk;d%$Y&K>lc?Z&Kh;wnW`%*Psb7)`BS`GPhA*_~+bh`1c=+e#3 z_lTAtm^T2g_^@`A?cQ|X}C>mF9?Y#m^XdCWT63K1g}7`pBE2u(TCSON%AdMz zKOz}le2H1q35AztZP;v=nc)jsBGS?{f8PeG$)7*3?1C*n-ONRWU=CIhW5s&&#!!`v zU#wu#7-2*8>V{G7+*r4vMJOa8D{9Y2*MXqo|7Z`nQ*nF%A8`g&1j{*dXqb9DT?c+v zORCuac-|!sga0!>2p`Y7Sa(YwuD`v9fuj*QK*08+-~KnlQgFMoT0iy1zS?5ucF9K4 z!b88Oj)GUenItjwoaBTA3lG!|L-7r;CAM#&V(nWV)fX;@#$Yn-Jb5)5dtpF`D;+flCxD%(iUefHy&YO>#3u5H$z;We_$s12)%T`|fZ zBPho=6Tuz3QrytW)cCkN4f5qP>WKomantwI zW3*tSf~oh9Z;{Bai*{|v-_kr#p-rt0OJKScQH4rM0~k)r6y#He6ka{E5)4fO?@sq~ zug<-iz~W|(cKz3IzYYge8q?u&Mtq-`h)$Kk+M*)aewxA^|Eyuw3~Cao@QRt z@YzqNdAlx|%XJ{7)pM>jHCGYuFSp&1;{hdHN<_Sl3#_cp;%n$TuahrB9c<}e_w%5# z8HDgzsTOj9I0x&rSY2W%e?I8b+g6)gDWf{EI?6S7W3g7Cp}daQxX9d8oJB#n0ULW& zK@mT}fur77J-$z)mm6(Zxl$UD z%M6%NQdVe$_`**&nh39IK6$3QPkkArkIxTKTlZhJ7yb75ZT)2_U>Q@*(j7IdCv>#M zN4oGG*(pic;?_+OB1klC=~y%uCn9O!kGM17XTEvaf$8x7{Jx!t^K^v(aa0CLJXXf> zv+oy<6$F!I&yCa#P3I+vPD|R+ebV(G=-EIu5I;XJeYue!{YPnUBAUKU6rB^TpSNA- zN|`)MbVwE8H8t@fV+j%?H+*lQgLBomu~lx-o;LL}LpY-?AS@sm(HUG4#ES}`YTLM| zA&>ZEE5ecUpXa-knA4DwNRl?U_Nk!km|6WwYPi({1*B~)2BfA;f{yDeBHg5e=)-F3 zD=|4txVx1%3HOymJPaxm=$K1B1k%~YMpYVH`)7`|_ya*;RoYkg9);Q5tWgU5`a|!ekR$r#LQdIe zdX)Yx64(^8pTVYEZ=92lUSZJQB{*!!cp=$!n@p;It1;Y)u9CG}ZH=WO;Ufdfw1#9s zYnf;eojv_Xb5KlVt|7r|(x2hnwFVcHpy%n-TUihqtZ=dw2C$bzmXO)^v znuO`+b{DzmTPY}H;Glnxq~p+1r1A?q{Bz{}Zv0`q3PlicG*69I@<Dl#BtIPO=waO{@O7>F) zy`&Cwk?x4|;dpoMArv;G-z9tuvNWeM+> zh(8$(&1Aq)UM?B2#A7jao4m6SSZ%{2_hMSEu_A?5VKLb@lT5g}*ypu1@pp3eB_CN` z%6E*iQh;6w4x6Y^W!eP$ zy?vbTp9YrRx756{2}!cG0JnlnG)rj~u z&4gcY|3)U+w|kCe6+y{Xwz@g|^@e?uT3~yQr3el*gBwl4&K0D>p9^w6@;{#p?parj zPI6mtW99dmDaJCYbZQ%Vu6^i1O@A4~q42vyWf-;~p9Dhxfb6OI(`5-vsZ2^_#lP6Q zCJ{N!1!XU@oBTI;4;&ewP$}yiFO6xRE#}8a~9%2f9^( zQ$m4$Gji)YC`n2&_Q%N$DZFpgP=F%lwNaDicKh+w`tkrf66#@H zxBIUhKc5{LJ)&9zIgfCsLtF@sn0&Ag;Ep;^8tr62{98MWHd^f(0OT`~b@uXLSOINT z8e93odR}zqwKHwn4pCb*91SrjxolikhQt6YaoO1gq^OLrv#t`Zo)-}O8;BTKT*t=) zP`k!K`3QaZ{dFLVZ3me_9w6Hqak{FGw+ankwa?X<;|9OsBVJoaX%;wfsvV@oAi;Y* z9PXH=HO)~8oGiP9r2}ozZleCYO%&_8dQD42*sk55yknIcSxCp4Qc1J}L*l1(rB)LK zW6PKwXKiehr(jb6VIheR<6ECbNGzj`+tLvb#Y1T-_n{ZK5TKmn)q@ZQ-9h)6_%SHs zuljzC(c!n`# zYVYU)RMIeBL>I)2bdupIE6{_ur4Z^eWnpvWqHs;ZqW1t^=2XU+5PA_nfQS6phz81o0g2O`Q zF08=3e)}4vx-jB;m_RP}>Du27^K}1+{v}i1S&WZjcPsQfli73MM;ig3boY$4poaJs zq;fkPCbFM%4l3;B*EcWd2f7JGt8>8GW3|Q}a~bmY8c2?*)!nwzgZb~&s(WyO3`igz zwFiJdw@Fp___Dn5`RZF#)1<8;8ug1WQw_O+5yh6R7XRqQ#3t*qTylIZmYAPlfo*Et z^lgj8Z^P(YDP+hd!(07I-8v?BHU5K5_;1uH2cZN^yW#sjloQKHfvZ*QwH6iI)E9$n z!=3JPw)8B*NX<<_h^qOmm*5G-=&m_xHIm|t8-t_w%>*O2<`@$HCuW^4NDY+2nSY6E z@J8YN^x)PniP2QfG2T2ex2}vZV$6p~zbZ-iMfUJ?+U|pnTdyRn-2~wf%0f-z-f-fE zpl3sw@t4C5mZ#jn`Sb4DmrY`V=%`OLBZP#DSn<8RB+*aSmyHfCFh?St^s(po%XA2*;b!$81+PK?yNJM!k~!zbz6nX6buo znPQu}NO?k|Qm3cMrI7u^lt?bRdbsW3k?S+rbgLo!lTIIvZA=Qu;;T zo(Z?+XgSjajl4Gc*t~cP5^4J1$jR*rA=h`-9I<+ckoQ)afRovh4GC?0zoyfVGoI-85*x2{MG{fg!(4tn1eO40PFBcOqT$K_w~Xxs`LQgwaHhFNlWnZcDpr zC*}m`Eq7Nf%EK*a836%|dhN4u;De*LZb=Durjv~Nc#;`jCwjb9b;iF{N*J-Kr_O_3 z!wW#kwq!ssM^$-8Zdxp0y~Sh(Z2EbYoWA%*d{)wpIRu}2UQU=!Ocpzw&Pa4?mnIF+2~HyrIaD*(DW(Ut$N8iy zm*QcByli5Kto`tFf#u|axMf`NFyF}ZN zBvBJ)A<#}k3?JX(ANQbE^8{)(CrZW`)i!91@V}w>JTat*%tPOZY1597PXZSl=ZuU- zy}u?$MpQG^E`Q95R=G(2EumNCv|IB^a#hjxVFhBvowG*~ko$o>u!C&#RqUdec@|l_ z^Sj4CZVf!i3Nup~^q>(6_uAS5ocW8d#V2yM`A>doo19t$-6saGDJ!R0dG5QD z-(@}Ev$giS>^`%Y5KztX$-8H^t2JapiT*mV^b!q5nkPA+iQbli0=SZQjKt*fJ}~pO5|YBKL$6|S!Tiajba>3G`u%s9OkOGJ zu4(A5xdJcE6*ZZ+kU~nRwf)O9}I)tUS2{ z&1M))((YtUJ6>TpyP?}Tiq#u3)jr-XXX9j2Zrvb0*!Wb0NY!=aRHCBS0iN|t1)^6; z<5G^A^NXuxWrxU#-%#hL!&24|)9$@X(d}NH4<}vDh`qhbb%`Ffk*2NYOzI%cjSGJJ zkPk_@$?fYYT$sp%v~D6p47--^DzfNg&u&6Cj<=v7GXGPw-o_*R&eJ+;`x))ix~Ms| z&oSY5fvj;@>wsp$H)NDARTf^jhNO!y`tFe zz&02QHU%++zUOW%);4~TzoJ}|Bw1NOTVj8IIBJO=@0LKMOH1=|Pm!d{AphrAdYhM> ztHp^!-mQ&s*X!5iQ8_j0(@`_8bCDamFEVt+lq*~~adlM}f?6`l4c22~0Efbyt$>Jz zv5R3~GfV^>*BBW1vQg01m#pA7ytfzK7KaY7*p_JF3TK>df`>R(L6?B9NFiMm%S&j$ zRogagHut3)b#0TYh(~E?F@yCD@%va$#bf={D6i)}dOsdQlMtW&Ye$CQE{odf z@M22x#-e+9iL?jl9s=K0jy5RTC1Z$n?V_Bsm)G5dQwcKNv!OJo@6o9%CIq?F!v;ed zFb*zC&)NNlO0p2wyl=0f(>~ZRc>I;8Gk6l7n2o8XsNMa?2u7-j_DOy+IJrTL_PC)Q zg<5*3xPVs$-36M;o{~Qv7A*1QC6s2oCZkp`4Xioa&s0Zt7x~4*_p{F)Sh{WJ*7rh`NoG`Blrux0g z-k6MIebWGO<4%3eeb%VVTS(&9q+aPY9Hn2$4OCDLylhSV*u}16QO0@ zG}BG(ma8!2WR=sjwYDM`Y*lP)+vbai{TTezz1lo7H=xKe5)bv-#R%N9Mr=bnO@s_b z5j_-&m?>M%Tt8drA$yADKM9PL$eo3So7;M;-(PC=19>To-IQ!W=f zngTw0EPc!H)a4jXCl!{zIr6{+r!FwWLf19{_ESO>c1jIg@U`wWSlZcG6>9?oK);8b zvxUzI)A+EIM{tW%8=RsXE<<8ckN5IQS?CVqCNinPn~x*g33=?zF>xu-zWQVy!`ZpI zJ<%73)_-p+Y|>snfNn&Ujyh%oS7_p59~I^cF1%H&CHPmPSiq-r ziLkrp!VM^hlLtRMsE5AE7&U!^500Nb^3r%6ZrU9>k!lC=?v3IV`c~Db-9>@G&wps3 zir<>rXN05I?5xLq5Ye~h>U`@qOEO+Lz5XF|L>|l0w2>iQ6?cm+3B~_lpjkgRw>>R5 zQcK5vL7f8Gw(U9C-G0-}z}j-Zk}f`3xfP2e^qaK16C}Nqm_TAjm9&!A5AN^FO1lR! zV<6rneuRXzk7u#=<5e*>Dz%|BG;=yrSLlr6qZnwec*b~Lv<7&~8MmeE17$GOn5qcq1L`ycYIOhEf7*g;(dBw=XRW4%6@IC;%?d6!s0VQ#Dgul56!(>9;lg zCZrULc~x4;zlUgr)n^biq9Wg6JbDxK&4d@Zjn!qdJzVv5DNwyo($y;k&MYxsWQdCf z=iSjNwSK(6UF_5iM!5xnPpAwXqwUJ!5KS~c?FK_9UM{S+&?Vz@pCPBhA?zr(bPrpD zsrvjVLC%!1(HBUy*S#R=Ym<5*F7D4Vlo-zr|@qilArLP0SyWNe8BP}&?X^D?0 zbQoZ~GP1IYnX^=W%Oj}m=cesv)#6M^y5Oap?W#)KIx3xS3uw#{2}T%^Abo%hZelrp z6jOAT9g7Y5$xp0W3Bc@MQ?}Hqv6*J5Kyuz#`=}!e3z560y;KE9{KZ`JX-t!?8r9L5 zhgo^+ja31D-{*f@9@onm5qU!e9V8Mw28{i1776#LT%8LL$F=0rVRvSYcyQ^r`@a*2 zZg68I7f0b0Q!PE=REivWIK3nxaS3bm_QlXSn@FhMEaPq@n}GgsP~ z;~ge3{@jA-c*N1Gbn6QF1hwFAW+!%Itc9LX)bC)*?jeXel5@@0>r@XGBKPSQvdK=T zU@u#}A0zUvy)dg&kyP!9ZQ&J-HyiC9B-I+=JN zg@ne8&A622D{^X^=vlW7vNin?wXD?QiQJ5$-<7CcH_I&a@kWUUz3p^9xx zt#8e8srXV7n38XMToUy?9Ti>8kVgb(DQtaBH2)1I8c=>?vhL{w$LVz_Jg)D>RB;1R zg};@N0%Z27)X-WP;Aqc0IwpN9jtKmfr`;{=wei7^^+c*Kwa#p5Oy{pCOxUAQOT6@{=f{R8UaxXnlz$o5Q3WVP@nW>t1#0`$&<+~#2>4( zX1Bbo2j|xc4FG@4$#w*HG=Z?XY6gz`;I)R>*0q-I^=g-jfXDhK_tZO-5M#V#=e^_i<3jufp-{?WHSa2AbZ0eVw z+B0>Bm*_F0QX(jpP-q*;N=-Q8Rp!EW$c)SVuP7wae4j?jV)>Q;PYhHxC(Z|fzG99u z--Xch5*Zcl&x~(-h=I;v0S?uY*4m>hr61x<`>*^WDThJYVrzu8F|((bUpTiQm%i~} zCP9>plL`2x5q0Wks4_Usf$|NDmA{**aT1tHAP3C}_cDSp-%rKDxXC+h@iLz?%RvlQ zwTS>2#Es?_ige7jy6^zP^`{)`Jmp9_9gz&S9!SQ3ay1gD2JTx>V4WLNXwkE*6toQU zZX*s7f0G9Jo??t7TCT9D!9$=b|^MpW!2Y}su zn}c7tJV=sk^WzT zSYOv8fEc!WiOR=k6~xN036g2d?woQ`x0%T|^P$2Y5#`&ef&y~YT zLtPhz6?4`8)D>{_UhS&~oYNpEuJ+(B5W4;^Uf|}ho3=V}KWAsuNp!W40fR=z>8%|X zAW3l()`iyHqFs+F2+yZ*7Gf$#yDDO8p^4`w%}1hPFSMJyJ*dp{EMPzj{ElyzNHO9(ohrjtJW^$Ote$cV>7E-9H^m3 zAKDD&bP!O7sO2LBjkk2mQe1(8a>w_gS6$bdKZ0;xeOCk{+w^9;({6}Dd&YdkN#`S^YqZw;@5ik}eb*HGxsA*f~NP#SG3IWc!0_`()@wY zTam!*Jq+A@N>R*(F$QQ54B%+}4Z`0NuLI5Kw4wc-`hywx1}?aa_(Cv?%^rOmk5zaJ zJ@RTC9F#=(c`-PBpzl=k+&$8~5MLR*f@uX-10TU&PkIb($u}& z^qYgW#@}k8Hmh2E@6f8Z)K(oji^Ozo>e_AA?Yz+AV;@P4R$5-iQP(RHY)B9lwU6Ny zj{M%kF@D(GveWQ4lV~G56pg!K%8_5H ztQxy#L-qT*6b;7gxcHg!>a5U1o8Lu|`vrdI{D2he!n21#7mg-35Vk&kPU_mB!FX@k z{NRIa#@Ch9vkA1_qS=eDMJ7+ZRc8Bo;oXM&O%puFqLQm)`yD~y-J;F0nL|+6kqj{# z>fOcl9y26)iP(rGe;Wj+P)$AiDbAR5`#6pS-Ak7i&Lst4R;vDT(Vzpq2OcOC6x0<_?<;y)(Sra*$P3c9`lgrfc1Rn zWM4BniT z^C`a@eLt%VAgm!}!CvMe?PtR|7Tx0Dtx@tFJ(-oYZ{ac&D;<4 z84Y66dYKnWowuL_E<@bDwdIrY6BV)jmr-!gqHhMrn~tB_p`5&zE+u^53qlmak5FHS z1z#gA@0llgypSOzo_#f@pquh8NX;XuLUyn&Pw}sJA+2gZ94!kKBWAr4H(OIHZ@&{0 zm|ju_ug(aOXb_!|1>$lfo2 zjK!kmf1`n!{wod4`G4@=e>5;7GY7-})Smwz8kmXoA58q814S=pY2#w*L_jZQW9VWk zVrpz}VhY8_2j%SIWNK&&<*^al{x9!*jzkyZE#weBxUC!1%{_=|5J1SVwpT~k5xO_1 z8w3h_^A88k0SGh@q+8!^?mqqUU+!g9W!87+-~Q&Kwf7a4uB;oSGCVhcOL7em(Bxd_ z2mw%{%F4k3fP=GRgM*`E(bBSISb}>>$BI=$Ke_^P3xN2BCOC!x63Ta75IAF&8wCVX zaA^g0a02Fd58-$Z<=_C&!NCdo1?1v@1}q7*Gms8|!WNhZ1acBAPIYp4askuc6v$uv zIz=2X7=+kEK{+yiAI2pxgm(hd1|S4LC0GJ8`OTRJvH+iRY5)i>$ooYN5*z`8az!yR zcXxL;2j1vz;N;MbW@-Z18dSgzAo~k?bOqJ~@@D$Jh5RG53ARC<=JfFbZ0S4R!@63Dg$-sb3NLT=S z%!B=Bof;g$xP^2!bOznKDC_>=o^?$yBT5s4J9r?0T?OBK`7CRgCigmS@-O_{pJ)er zaQ8pb4M4&)wSLJBF0Ll4fdRQXf=~cxtRQ{KC~= zpF?~M|9#i~o*G!)oF7Cqc$NV=f^Gxi{Vnk92G|w=sA#7CyZX5s_M0}x!3mgV08KG~ zV*(pi@QwVf3ET9c>}S`}hD9C%=2bP{myi`V397QXKn_v9AnKRB?KE5Td+@Hcf4(8vTJ!5ew_ z>A`n+_~yU3^WDF=GtduraMkdC;?6L?F@1>O^x>nA=%>GrKwtY0zwEF5#b3K(zy9zf zmsaMl;hFpJpTA=;E#RA;KcF6Xrs`*pS`{2T^x#MSgw3W1gNFqy;pzG1)~tz(`=zHEJ%N22ddzxNcT5ybP0VGqoJIR^Zv<$V4Q zRD+W<@8_O^JU|EA6b$5V{i^~2v=)dqi~6Qb{1(IL4yM%u%B!EPHs}Ae<$w8W^ROFs zih%Yj!841rwm!7HGja1yqm%#n3%|$N_uMa{2f+QNUjz{Fjn9CN z9ryp^)dho~oo-=rOmuU78Gr#`AKQo`0ej_`LhBm9y6+W+y` zldqyUw|cTah&TUPp9md402ivQ`HOtpnR~tP2JSbAhx&&SZkCyoKH)L{<@cgJwEEH6 z?+hRNod@PO@wdZOkN`dbbmJf=IMgA+R#xJ2+8h$eeZ}6mzTC3^yp*BIi=NBhwbwiH zE3lD@*kb!#>R{MlwK~-nGc5l=8U=nwT-NpPZ5A@Cmf!nU_8)6GKWjnljDcJ1S^lJo zYf@oS(`B^XXHSQRc~~FlU69Q>iR|kmsyiiK^wU4R;xol`?QOK79Yp z$y?-76bpolj1eSzgNT$)QF)%vg30EpCA9gJJ73HZ|*) zoowmS;fSz^fQ6Xe^4ExyU3QW_$D=?VcSb>}eWCGWi9k{E^%{J141Gu2W>fV*S7Jg~ zT-3W`Y1$lbO#A^t=8~WGuSnF=S@yEHlq>gDTQkHC1gblCgZ{p3){v-c*Sm1n+VCgQ zLCP)j0h;NZZQ_8kxOx3nIcwqKTp0JleXjX1uQ9Z2pI57stWb+tUC)e@7#m|WHqoTW zy&yKCa6zpWf-4R9jy4^=2=3t_Vo)96y3l!wPj#lw4jK{!tif^%edMxlp7Q)@FZz*b zwKWE_-kHJOpH%GnMPYPzt-uNQqyxn90=5y_+D4mcL8A8>wpLHwFQqH%K z?o!-fA2GVH?C;yeyQb)IH>XrhC@ZDcP&rrSLhw9ow&)?yos)gy6u|lYo(%)2%c{3x zhhf0LtXDI(V0KI2uaxbFV>`>^N0Lsmu-rXT^0pmtnU#;VQ-+hbTlCme#X!A(VgU;A zELPgTJ~*d1Z3kYUThV705#`YmWvM&wkY1uqR4bo-3S5Z?7egSaOzd}Z-iwOEodkZ6 zK4V@rSsSgzUsL4l<8wp}WOmu{w`MXURl{B87}ecfM7 z3D=1OE9s9Rp$)PC*AeATPZ8zhk1U%46;`m#NDXuC)ZLqvz%)huAcGh+!ly<8HPbdp z!*eenV|&*@7SGit3ug*Zt-y-Lvp#ebIw&PFL&ZKYl8;R}z=$DgK?$qd%*LmTtH+Av zQgAQwE;_Vulk-a>xhG2MH90H2>S^UprLkA4`Rr8Vh?QSfE(i|$ySB3??(!tb+)q!G zd6a`g%12QtPecp;Qtk@d4vlFY%w}%API!q54oLC*oX=k#4U3c+se4C`zh9gkXF`nS zXVHytr+~h{pF`U10gKz87_K?wLpYVbv2=D>b2Q;O@J%f%4h4po6Q)lNUt5ux^V0i3 zLXz+O)J#y$s^!iF%V1@+J;IxG%WZ>4h^W2kksCwBPFmz zXGNXGiD}j}EFDqm$#7f83TLqkpZXnT$jZ#qB>oY?*&QZXV$ z?Bu+|qBeP|x@Sk1Iu4<)R+#bh_KR9uMMHx78cc2@Fc1f*xt8QQ=e%2iGXmQ^cVLJ_(J2Ct(6hLy-{gG(O;=XQ z^{WCFXrNIYSf`3`-efUXoT3ZpcJfXaOSaH5sHyLeoqECHs=^+h59Ma{_Y|7`Bq}!D z3!6+;bfWW82tz@2CN+5^mA83x#yCS!D+5d!5u~Rq4z*`0$k_de{d?BYHZJ@==jzWg zZQu115Xpde>=29V;rw1~lwGeL|k;kjcfp*DyB3#8DW%>NE2QQc@j!Dd^H&5cm z>Z4T*ui4ySA&}nnX>kQ$Y8DQMx0e@C^hYgmVeQ$U~q$RUrx+Skv>*NovBXz`CeE*S~o174%a4# z2O}RmMdTOA+)GQg6EvQe03;Y3J-U{xi#CM#iLr-*sS<$Ry z_7V}avuwz&a?vh{!s#c74Ptsrq*F8+%rZeX8asvjltW}yQ>*<6k3hO;Cw`vyX~lqq z93pIQ5czGT?AGb({lNaVe{_9{HfHdWM&1oN=W^l%N(G1)@vyuyP`Nuup|0{ob4*9c z67Y{t5AhkiBDd3Ek#EBfTgQ{tu2ztPT#Z_gff0{%WE0NgsRgBTekC!3252Gq?WT&z zma12p*NH@Q^HjCen<49adP>beOLVg~cmT)UOhXdaMK2vZ9pp)ujPozE^wRmMK{HT?99^EsL8iS|@Y8B;jYPecU&eAny-dRHe%ac!*R$6s*b=?Rt>M*t4fTLNHY4rT zE>tB6ItEO)$p4v)MKO|C6U4|Q^Y=+j_`Jhot5N!@XU^Tytm8?}(P~Rw_%m)9WIF$$ zPq7l!ZwM1>`O++Dlugf+p5>7ycA-KH7GH*G;cZToXi}vMXyp%o{0_S!sE%gVNo5A; zX}IOQ)oK+R_5GMyA%k_<3@$boddV*Q+3(dT=e#@6dz%`4f)R>{9{pLra(}l7c5>)) z;y7=gM+{fC8q`h3Xi9uheIl_09u!_c3z{1Hj52?8e1{(9j>s;%$`DTnD6Ju2* z+|#*vTA;3eOZV*gF30C=O?i{B3?cp=YO3?yydp-@=)BcSQ#kp;9My&Dcu%Uyy*pG-HFAWU*H z(x7I%k^cAeZku0ou{)zUQoF3pCAZ=WE?y;oz@^;ISoT>K2}i5ZFAU-ZQ17U<6+ghu zHqjp?rw7moJxr%Z>SgI;38@2gDd@IVubT>xsv>H~=m|%EpL_Np@>E8zN zXk%(bMdA$?o|G-XqY5-^sr@1@71gk5h6f1QNqAOb+H3Yf(3KbRpVYGZ&S@@F9nvIn zkReSB$5;`p%4tS3-^#!TxTU@jrz!pV#w@D{6l}(&@7vg!^T zV^{8NZ?D%c`)I_5mH}my;K(oiIru_4OLGEM1v2M<)p))mB_iE+iv-H5?lZpBKdi?` z5kZZU0BA{OtO1@!U6|9RClQ5X8BDX4d{^uR{j_G{^91w)qPqHY#;-ycItheWDj9{w zNdoy`{7fo1>;;A{K1hHWH)O?nD7?(v9fk{9dak>-)HmroW;_J(sK+h3ZFGyIk)2gl zIS=jm)#%orAr?v16{D|cOMQO;ql{a!wi2JE*sag(5hl0Q8Uheklgg#hJcVpz-{JtA zf(Ib>K+Gn<60vMA)zY0_^#G_zD0q3b+e2r{GaZ|0C?0uc5R!wZ##Hf6ckG+A-<|5o z%kg2+U+k5~Q%Q_fujaKYJ7kDv6?*0uJ@0z^tL!b7{(Y3O3BqS&mbcHB-W(gdkTCrq_9w|+kdQoCG3hbyPBG3+jH>D-- z&*q*UM52adR#*-^bOESssX+QiM>GI)gY&L&p@!i%O3X08iY`r>Jt8Cc+HaaN+u?I_ zus2CHn|XnDUxEL|T20uyzH;)HFL#H<^(H$dnp7#t>Bn;dy~@r3quazS?F?m`viZpG zy7hDpS0Fe%>l8ZvB=&gS528*_tPWLXXSOdc#y=P?d$2vm9hDuvmBLAb+F-L}JEGH& z{1SJ|(zcjq7A~Napm_+8Rd2qWu>^+DYu$A9&ks|Pqx5<19HQo+X3^Ojh+tPcAGFN@ z3jY`lS#O3o7;7+XB(n*qdRN~=zgiDXu#00G)xLB@L9)NqEN&65n(SSBdfumY2vpzi zg}29M*@&O><8Pe-e_XFOoQt=%b(d(1p(VRq7wne1$@q#%BroZ$;p(a|v(mdFoGV0z$HXlhR&XMvU}Wt6I@o2n)NZZ$Vqr z_*FSsw;3=kla#xVPHBgw-0t`<1vM1!UAa&xPT7(ow$#Ogy3xX)X>FhX+`B$Jc|d9J zzApo2KFv}WuAPxeJDE%ay{QTmfuKMiMzpfTfu=iFV`^mauh}%S(phjQAAN)rwTe?z zqzIq{Ef?3S0Qm?vAKLL|you7TIY7@4Cyi9{bIc+O1`@tkF2A7GJ1JHQg^Tvq$HRJp z%l4!{p~cO3sONY``>{N(hC2ZlHZJz&-GA-C%)H<~yZuBLz$N)auYjW(`iR?~<2Rtsx;MC(b z$e$8O2(s4KCY=8YHtK&Y>hpO0{5r73yZjjxk@ErjFhfcf3Ow|*@M)Twn;{svDtZ)7 zcqK9ahc^%zN?h$&vMaDh|E^rhtO%gF%V>kH`Dp95`Z}1d)M(mnnAVp}?DaMi>FxxN zC5$avb-Gq4GhKUgMW_jf-9%ZsT_M~j~SAzLG$3Y2GJm!~U z{gMgcgQmT#XljzTO1PfVVHVM~&H{L<-tY8wx?Lz>zg|=o59dsSRP`iA$o^-RpSx&G z^TxZ_DM!VJYQVN(*@?JFJ1VkKQ`(<&T|&i1M~c`oCvoXrwQwj2V+|!<*S! z3JvKE`oA)2)9+%#r)tHbHMQ~2d0v?fO7Dlrvl{cSyp1jyjvv*Bmp9t}nn2RJoX4DK zC%iuBJx-ltU$Dq8e~`+%>_P^qHL@%8rXDu6fghae5zdh+IKW<6A-HM37yBlHIx1+3 zBl2R`AjC{H5*gZQoiBLjV1sE5EiQhGv2 zT=fk{Aga#QN~X?1x zv3lW=DW5X2wt!ED@Rnj3QMS-gw1|aD+fFpdCtG3_MmZ*fWM`JM*XaW`SA-4RE>7xFK!Mu%gV9t?pp1mCzqG2LuoQqR^n5{2F8 zn1!&>*j7SkRjJ(#*(T(E%tJG2>Eh@$utky=P!3MskJ%}!zFElh1aH#zeu6Q)?H?Z? zV;yC$7V~JAhaxKypctrfS?_8skq-J|al4m=&MZG>QTWX?tTY)C-s>?ATa=>Z_XItG z_l@2o84i5YmccJDv`nWtH__`F&Au}N)i)V8JtSI)%-2SXMh=0aJ&Ws}y@7AHc67kB zqCU6a>vLfcrunUzy2ue>Hp-ri`U@upYSJ6@@Y4rpdvJd9AHq4i5s%$&+Vz#b) zZh+TTbCaErdi7FBOv13rumn)Jmpo+qiuFWPj9e=q>!?bdM%nq+10@DAZ~>jh4hBmH(m!$dN0pHB~ls=L)C4 zl%F$->PSzTUkJZr5%Iu7`tWSEMd=QFO3{a}Zs{4fsWR<>;qtJkMx!JLN0jFTd_3D~ zDE>pmGv3{(-)h*^a9N{}>W-W_63JfUdc`iqvm*_fg3rr=7H2ip;v82ARPm$-$Nb!B}Wxp8n_O+27Pupm=^stdJ-imhz4M0x&ux1eaXgF4Pd>3&YC zdiU6W{1H)IF=nVD$H<#GJ0+#hp#Oez{@PmR)q~#8iPzRkmp?Q%_@YFiG!8h?D{1Vj z+xSmipdg`hhtSy0^5XDG*p-135(dI9h!?g4BDh0H{yMD3V@Q<1Z_~f)Sj^H%yeJ0c zETz4UR%S%niOu5Co3qts$NAOSRSM2{qEOF;;95J1o@+e>8N6-^10i^-B4XWw(=|^* zB!1vKsD~_~Gjt4mdve&k2`A^z0HbBcj!zNp2%(|qit$BM;o{6a)JQ%IHUhi>|L=Fh?RMd z6~N_Q{zS;tfrHcf93(EAXRqtU{w#Z zH4{xgWfo%7i#U=EDPTb-@Tauq)U1;&=a1zzbJ1zBiNYCp=DWF{d<)C zG~)Xgb*;NrlYMv5@*A(P(<%Wl277zUlOkWhtAW*OlZF*z*1k8ZzI(mm+w9Gz)r~U3 zNXtdu5EXUn&VrpoE-H})C6WYW{x5HrL(#mNaifuxna1FW_Doh_Xj$jz zx@oLIdDbOOUvM}>Z+#-{l1WO`CYB0b;!L#BIu&~%)#4@OZF8D48Ep#3a!9|&#Z~U( zCNi_ntoIbnvkS>}!>^z4-z4^4bn`-P5w7XfRY+oe%llY$?H#A8Kd&XI%E1>xHIu=T zFwi6oYj~2NyieDs5>#s#>|7SF*=ED>V}}i@5X~P=tQIi+M-Y@xt0^$8iMU^Gtd$Hg zWpht32fj@{l_tayO)^`S$|86kCIt|uVWVUv($>#L`J22(pJHX;OYby&_v{Qptlwjt zJBTcX(yRQg#v_B{Q*~DXZDXR*$ehtK6V7zHX-;q728TT~YNF_Ed#>q>{U*b#}1Eh0#rsH<1a)R-%Voe?DYU4KQCIWQKn$97`>-U`FS0q@%`#_-~3 z--|&(wPfCwddiTF__-sj!Aml$*(;PNqyCiDQz@;c3k;q-ai zLeUhC&)wV#{d&!QrxaEJ(2-e=JJKRr56YYB7GGbqt>sDfYIrt{Q>7y|pLuDTBxVpk zd$I*b27R)|gv@+GEO&NIv;|uM)l4<8?%T_)47L{=D6uMjYi$Q$(usfMDejb`cmM(V zRk>yYWGGd5YxhKtc6FDq7+O_1j=F>;2|ocxuBLm<;PqbyfF4}(`nZfe+rMCTic~sK zDuX;C!8RHaQ6GEefRy=y+$mwphNk36$O%f6+VI|fI=SA;TC)MsDS%5oj{I@foI|n2 zzY}7Mp4^{xEu$1Cb5Eoo6HQO-0&_^fGWxE#1EtY^LE1IkI zIfow8W>BQz2G3ytkSIG;m0+w|%PbNJJ{sO9p*CcVL=*iOzHKNEpK(}fidZp*?F)l7 z7Nd12RVw6PDCmOxAhOlkfT)aDhYE*ZAowXdSf0FD%gZQvLCZFVK|$jaq=l;rn!tQy zowSntbvl=v3YVPvn28g6^laWIu9{#H6pigw#+LCsBdDL~)cZ6rU z_X^25NW-+XHrL?N6tU*^dyMd-iS5|Ow7#J920HAXmP^RmeLEc)aaV)I5z~?R;)DDrIn_L&km)$ZqJ#L+~JiUw2}%<5j(Zwb~R^$MB5e%u^?Nfv-dari3H2} zj`Mo>5N4Z<#Rco$+2Qj|d5kX_L9Q31Y)DwFF9+|(YI@*|1;^hwhiRhnOoIEgVDrgz zOi59oXTe;SBt^>F6RQ=mmz!m4$zYFB^cYi%a&f4Yg^Nu(be@#{6FqODy$Akx@6oml zJ`UBlqKN0%>oJxK>$V&jITTXJU6AZUt`gN;M?`1gL!t+n+tzRkm6vn)bzYwxw0t!1 z0IB5kSmWX(U1gn+5{st{S|+0OQ-2ul+Tuxe_I^ls1_CdT!Tg%LQ6bIoBx}++4&HHi zu;MSKwNSNZat{7Dcd(m%jOhKK9cQVj{j0=*yc+LH{UEJx3;pD71w?j;x=fzTIpA)? z$a8unH)Br^`tmFGHiY`W069vx5`iVS7%Adg=}MJ?FH-rgM1L2kYrRJfys_miRB}%_ zie5iEX(=~Eg^t=sPEVQr%!nJVzImW8ugsE1&0oQhw!WQXJZUuHI|@>J(gU^EScu)s zg+;@lS$=KHaC=2yj%563tIRH!25RypUt>C4ic)DFU3wa0Mn395`MGul8>3%Ik Y zsUg${4Nw$2jw2#XhqUc*@bv|;J7|B-=7_UT%C*qXQPu69@zt-Ib~DeX*(%UIsAl{9MQHBpDB8=fmA?#GNp~~S z$kq6N_;1@cUqkTOs5y5A%qMi7S@>i`aO3FChQuz$reV-^yC_+TrS$2gSO2#0JH#z1 zb}GsVGw(}ZGLWtR(S|*D#d^IZfUA&dQK=^152UBr%00ZMOqS@s+NVK-)pIv3_b1A* zNldb%kYrQngy~Fvc#`n>R9Uh!VbEO5MM_m-O<>w^<%&1#wR{4sTSE|4gypWkHWNqT zj3N7ZSbohv_LAtqF14zd2pREx?D<0lmUJMO|7l{a_^n*SBcI>%3L|M7+iEOjv;&Vv z%cAbSb65xxDx%$X0B%}Lqc?;;JTOB}z8dPTHd2CNgOs;*`oWN!dEm{Wfto<~xztcc z7cu19eRt(|dn_WezI`6dMUJc`O>rwX#{yGL+2@NRvN;1yw6e{^hq8f?R*2HGm2HBQ z3^jq$**Qao!c*&LAE}W-ItDf{;j==Cog2!UNFbd*-DBDacXTV<3mNL(mVz&7;B|DV#V3Wy)mIURGXIuMl%BBr|$;X}JfW{Dx zpsU&5Xp!a{l8*RvX1V@Vt=sfQ(b@}EWgEEYUn((8TW_u7_>H0nwR9N0ajRbiv4 zQ&_ZF`OeqBXKzHZ&t~Zr9*rtoiZFpaVp$(FT|U1g-t+pn^=_btu8ZEbG>#c}87BJ}asC%N$Bwdgbk-8D$m2 zvfv1*Wr{=_iUhj=)Y9gN-^!yT9wf!m00}s;PQzrA4K@8NSe%vhG zBUkr=Ub#5y=?+ENSl2=Q;)a_bgD7k#xaoDP5sxL zeI+_Pfgd*vINPm@`;NA?wn8Rfow`^JbFo08tVw6xlz@oX_eVrTpj7Vx(|!OtuqXi~ zMorU3F=el&;D^c-gtMHY++XC5Y-roq4?BST0@;VoFAZz%r&cT&rM}`X*rzX`9a|f7 z6Pf#G{2d*g?xb*O_1^yO?0A(dH+VhFiIBM=L|?3lQIfIkjS@+h7Qb#X8^O&Y6hn2? zn!VvnVvTED5%<29?)ItZeaorpCM9K(5Wm31#vJ>+Z#wPu{d-xx9zy5&1!gzlh=UyG zCAWWk8*IfR^er$FNguu+=beCLF<00=6mh>O(`MB$8mj zS^a^*Trj8&>dX$Tb>X`_ed*?4-uV3~j=9pkyOb0SvS2J$X`{lFS;<9!FY{GGN~cQy zPA&<0E_Crm<;tWUx<5qCG}>_A?cg`9A$MYFzh6X{nvp}Th=l!tAUo*kjAl*B+E9J? zWJzeN5wkA*y11t`y@~cS;|0tq=q5+E@m)QXN(u~bMSrtC zB{^^gzB~ZE`+};tox+-u@TY1%e&URsr;pJ-R22R9x^veUg>_XsRPaXBeLA^ghJ^xu z4h!>|5-D1-eSlL&6J41iF-v_QPtSH>MJ=n~RSFe>?wKI(u^zjvA-QcSHWQ$e;`Pvr zh|i|UMuQ_~<=0XuY2!Fu*;&x326)8m&hU3au`8OG0kn0VM#1Zut!#vFG`Xl!X-~+= z=pG{nKKFgsX1Vo5Bg)+QNf@MzOq*Y!vX<;J^p?uHa+U~H&S~23E-54I#>S{eBQ=x@ zw{mFpc;X=Y( z2-m0RgZbq1F=GS1bP6CxDxi83IBwa$*(IS8M{NtfUn(5a^%Mz>LLO|}Gwk=Hp23iH zUwuc2>;FT1&BL2B!yeDcz9)=AUc{CMH3e@e;j>IV@)_!tbOMv**eo0nRz>`w7is(I zV$)A3*<@vNHxI4wnTnZsN}CHVK#Q?)X0;uccb%?hN0YVZCC*0$LV*rZrTh!BR$kIg zA;<>K9_jg^f)zetSK^yVTIq~M|7sy97j>+u)d!mCmE_w4s$%HY>O0me6|@b0p3RRL zb$6icQ6hGZ)IQjT$5e@#)pC|FeOkizB@nMa17#IKLQqHALM&@~>s1uUEwf_V>@f9;yNOJ{s$^2D}WC$yM?&_PFp!Or=HzKx8fiM=6dI zIwm*9L!VHOuBLH;$r?l|L!nOI#ZgWmdDbvGwQ3=S|*vmY1c!V2M773p&lw zuP>v(b)JtWN7zY*ekfV z`&OlA3)y;*8zNm5hrSsg&1C>}zi)El1yV|Fo!JClouN4G>VxZLp0J(2Zqz;RO>Eic z!{9cEL&;uWI$knQ!a7l*^!7d0_DE66avxXMgei1zr5T_`EnkGc+h~E%66Ehnv|fPM zd`mwgo^MC62){WS_Z{YWohNxjBX$RnZj-GXo25)^Mpk|O%5q=)Gs{X;x43#23}~FW zIjFI$twD3k4k;(IS@X+fJdYK`KaDpAJ#f3KK%ww<%LpJM%BJO>!3wZfe0#TiM%rm@M@mwXG45VO-bxoRnvL7n9{IkNk{>y-h-sbupp{^iKz%kO}%l!pCIQjEdMeiNV(dhs|Yy{yLuJPg$z zYi=VE?vIPOl~2cv5!hzhzHI#nV_P0R?SqcRbQJ5_kHT<#?8~Ev07Ey_>L^dtAGx^{ zN=B@bH=;mLMfz9MA*>IUL;?}iQwL==kZDHG=w<7avSS_Q?t-( zwteZ6ch$xAaey!xdYOmNX@;Xa{%@S$HKT>ldT%E!^&(aN3@Y)f1i7DL4AJ&z{Dsz? z=3lov2c7@^L#Z5mRHF$KMf*x+r%#Nh+0Irz`>hayz)7p-RJ3=~hcqTi^@2YZH*EM8 zBW&$8vbkq9M#8rHmT4ET!6e}?xpWR^uHIa^?A!)i8EDHO7_~mqFP;Z4)KXZqCxacD zJT%Y}h@laD=MS*>t3UnUR122>rds@8ZUqwoD<=#4e={xEI5?U9w`lSIV_K+zswCg` zlb3LVfCVAr6poywCBU60)D4Q+G{k~QiXxNl!{nl0J(oue}3+I z&-9-1n%_S9Jihbn&YtoDZ!fU!DLV+P392ACu;df)Ye0GEYwM#xfI&Y74+@nKBoM+} zL%k16K{169C^CTPT=c)+5)-yr)X0vb#lkL%4FqE4)d>h178GQp6m+0qz@PvHlm0@9 z5R?W;wdpZ{7qIaw00V{>NC>_n-t*m&XNSOvCHi*dBgH^6itlyR58O3&4J7W_|M9QEHFN+U(?`JJ*#?c-V}O^B z=vv4})IdJxXCsHeqJRPm9wj9SK!7J08N;KxtL`YQ=RRszzDvjS{t@tZ58<9ega$-{ za1JrhFZrR+riVa?eF_2j_;nxacP|MF5&+NO#j*f*3>uXDt&C$8#`#?{CXWw!2bdnz zIDiBi?9c00Pt&mDB-pF#`wjWUs|(oiHD-0a?(PTty;f2Yc?0-<2N@LLBUEHat2RI^ z;BZ5HyQT6!{DuCsudbuLnr#mJt*n4^7Xcvs4G8G%?l6oRF|_bL!w31W23vcm zW8e@$4-ESLm;z`t2L26)uV(c|zbXd_&0Vrb2ca(YZ&wN1B*yWxl#@__v4|Gg_((DW zkKc|2`UY)0a0z((I$>1^z>gC!Ru0hc2ow+pNqSo45hV!#@{FLx}ISKuB8|E&G_#@I=_85@Aa{p0$DO<9LkLe}$(1u#ottn}D zhdJR7*>MNK0OvSpKVZ8EVCwB5rEqaFm+R$T`Jv*TJ_XB{sk8d2L{}#H(rgk#|A%6O zsKf#1X@kx=C^8pedQ8eE{3RTI`ECB5d_$dBot^dIHVN!z1mg5Fn--dvKl@Ibf)z!m z71$1VDnsKw-U3{l^Ba|2i3OwlEBfKoyUZ8Map2a`4oF__m||)$FC9XDiqRG{1-0w=)8wNRn|C?iXAA{C(^q(> z^?;?7|4zU zfPSnP>?>l#k9TWMvl6 z>xk69s?R37#I!#4=mGm%cw0Jrx%gF^Cr3yYC7cuu5axL0WHtTZK-V5K>HZ7m>nOZN zY(@XBta6R7<9%HNC85k?$XhC;01=ub!t38U4*mS!L4$(C3v6^x@y%qwz`Np*0A2WOsxY@z&2@HID6grpaQH*86dB_in*2DUs&0FUW+2)m@l3L4)1%-@9iC1uoDOxSGei5xwsvS^&*86rAFPZ&r?jpwE-I+g zUxj>-LL991y};#)SzQ?MX5&=0`Ue_PureI_*a>I|QVm%IS<0L(E7K5t4wXr~DnB2@ zt250ma^DRnedz26k6f{>)n#HYAm+(6^&ui6{{Ho)CPHK{rYS5#o2Dgq(NR1en%U+B z=bovlu?!XAge>DTCxGKj0}MU2x?7oYtVb?F@|*iTYAz67jxPDP%J7w#yWp5BYs9fI zhi{b^A$`Ec$|CbSJT<_#l_JE7ubM`*YSqIb;>8s$VR1Kf$g;b~L--bo zr3jQA?@9H0Ol>8#oytUETh})+J6@lTvqsPa?Ppf6(giN3OAAETMIXHnq>FJf zQI^#Mo33d|`m}Fug}A}3dioFUpZ)W&@G@fdK;5oa$Sd8ErrSvzatvA@?U=21EJ-%! zF5fgoS$WFPSr+70qW*&g{#}?|~{=jO-EK zL5}ehiVCt|$jh6)FE)+vD1_L{jM>oXV>FoOcC;X#B4JASZO-2O9k^2Is2Y@^_W&hY z*pXTLeX{byTYo!gm)lv_#p)P^2-=v1_Q9uQ+nVeHc{}lHemSQ zu8-kZ+oBJejl4R?GV2O6ag~ints5tkve$n3D8J0*JaO5q=p&d9tF$86BpDIYZLAfJ4;3oAe{3Zl&Kg`k6^6msoMbgET;aR z&z8LM24CY>mt=O6ZXwX z{oCNuSjT~_NgqyXidV}Ktqgvm~AIJ82KA8bwzAhfGG>_Df@aa#xZtgZ9E z7(0h9QGhPXrfu8yOWU?>+qP}nwr$&ZY1?*Yz16*{y9VE&hVcg?V%>euK3acW?aHB# zTXpmyA_vIXn*{Ezt#WQg%6F5Q)?tnAEx4!IsaCqJ>|?!{TaMY&>On_rf@5PBfhyq)EH^`LtPSKKQva+IFH^=W#D^N75;RemS<{jDJ3!lbqEknfhn07xBQR zG*2H`P(6o2Y_=EOfr;T{Y@&yc<)~N+;=;0}?fi^q_Lq6sED&N!>7W?< zRE9%^yK)k&wkmx&QFy#icqnr#rh4BCjbJ#u`3SykfJs|?LJ_Zrz?+1>;N=SPH<(Hk zG?x+Re3(*}#}X>pZx*q2sx)U*K&M|{xg4&68ljG0(x*So?8MS>NxS3AYs~xc^H8ER zgBm}9C&r8qZhISzq_@yI_TEn_%FYEo{$+B2KldxpC{jbc8o*?$D%748Q5$}j6hxiz z1Ff_zhboueAaj~Zmj*NxUXG>?rCwQ@cNg3Yr6{#H_6sMiPw3v zV90p?RqO>m^6))s?RdBnT=L5+Dnr_;xl{g2?lErW2{&YV)oY)Y!3g~In*KRn>Iy7q z#&UD*bZ>?$Ra&2fx=<>%F>lAng>uu$OK&gr6{6B6(a(=b=Ryq)EQTbPYn=jR~Q0Vcof1mYnDI5u4=i>V_Ii%akVJ9ZaV&_ zjMKVZBbQEAcS)B@u1`;MO{zHZlSWwlJAwMa8pY^#yKITxqTg$If}u+hsZ-ven|FQp>#A-m$1fn2zMZjQH(^(Q zkx5_#BHMBM@wcU7$qM-G%0BH(n2SG|34zN=>fpDQ+uSwVk@p5{30^3em@UN1)X{~J zX`rMV<)@U>R%8@%34^HAsDyLPM5jz~sHt098!f1^S)D!YWlOter%wbk4&xUPjw6dUL6(km>lb)HIW*-5J48 zVi=vuOlXTxjS8Ra4V)e$`&micr3+Z}h=fOuRsxl!Nh_**Vc~L+IY=ySdOqCZctgBc z-C=d!LAFA7fgdw(Y^=UXlZyLXA|iul z$Upc>$PFf1WtOqdzI>T2f!!)XD|3;xqWaN5!8xFzc==6p_Mo{yYTps+UyaaJDO4r% zkBlD=4Xr;y0UTk395T+zBqv>pKTd>kv$|%a-5uSja9?;8x5~E@E>Z@usw>cvAiXKL zV5%zLXe~Q`y05+VlRIXp-(^v3KCO+?qKaR1syy4S^5ExKksX)Ni&td*dM~WZYrE*E z(?*+4(gayAy^21;e1b}x0z)Y??IO&hTHr`M?Wr3s)Wbcg?ppGAM0}RA^S>sFdLuwb zrQejO!}3jZqk@gV1meGPX#9jkgH;+gu#66aD`ab9ya$NeJonK7`Lek;g&Jpzu;y>X zVoYBNyz9i)ga)2Oi$QdlhjpsXsc%auPFrM6+Z>H+sQ(qlMSKC4O-2SAw+L^cF9AV(1981bQHX+@ z9Hof$-mbxuqddSo9CawKHKmsmj00{`F^XzU7+uuKS)9wSW;?%Tr|eeA6?I~^nOsC7 zgrAvSV@fx5|IAf-IijZl_$r(scZdaVtK=b(s?5BiW?&_8>b*+(PblKo~TZksZKKtqrFi zF?87il<71ShTsO zRAs_EXI+rr8|`^W?plGp-oRx-wR7u4a9WDZ zpM$wt)&dEv)wF5nZB&kTI!4KD$(38m3k$u4?ls@m&##74RQCu&uO48{vNl&bU8)Xk z_~WVxRc(_Np5`GUvRs(EED!wq6W(ZSVOlNss%tnyR|mKEb*M-ifd>H;y6r{=Ma9q?+CGBf3Ur2>7fRGT+(?&7L? zYJqw&;*C19=zTOs?)oW}Er1w_HD=?+kMsvI1z3TJ$qI~i!6zx_FneKkSV75?4Gy~? zvbDArXU`#pvN@#Vm|{jYBy7w=YG+161@ze5;HyQp#v$m3s8?({17F=X_7BFLDssQm0_IYaZ(qMMXyV2oQGdY+ z^9i$$ZsP9^(b)^dr=_?Dw8MA2A!#6N-f3p3T?;ayS3&8y_Bf=%xa{50<43vxJ+aXB zzKfr?qv2Rw*QVvd8&qAal_J+ApQB`|cNA=$jUVPZxsBZL1Ku5Nw!Wpl9sh~R(COee zYxH(4p2b&=bbi1u%X0Agb)p4#TyJuL?>Xd)4@U&veyPV++r?}__Cb$6-O;f15$U~r zj9ZD@s%DYbU!F+k_4yo>h1YVkBFL+w<+u>3cW#~bMx~+5BpH&lFr7#t(571|!@b~w z(pyN=P(F0hVmiIbUkZ3B>AAK50NxJV08BD7z6-LuC$RlL!96_uBNkB9nfTWV)oMOU zi;J_m=N-p@SI*BnL1myZlDstKiSO}A|&H1D*qZG#wxA@I9zAzU+hy5Z;) z%9we3=^t*AH_~q6$i8_q^F`qp(xx~!eAX&vX+26M>~@hElx8cm5#wGLWi8q5!TL0-8e?KXEu>#kOd9pWZWjIp!GKw9l z?Z)~78#;Us3u?`xsUh<^Jec}>wOvZjSVMYA55dxqBP>-%O`tXO8_k#2vIh<{Dr>*l zt{d{ud6{i?Kq;7}PlKxG$yGS`qtK?ekv`0_UhmDSA6t!AV{R{s+Zp<;K*EVUj9SY64 ziT?XQJ*2&oKVfY)3PkkCb?YjMvQu^|$jQ0o_c^t=B3JkM7Jep&gM6$v+(wYN@y+gp zG<8bn`?mD4HZ)sz;}hTgN$DKhnqtXM{k+lV$a45jOBaV|m`j{L4_mDX+D`>~rK}9R z!0I^AuoeH>s-hiqTC=Wlr5iT6aW0%#gr@Y#DA&bs(#W8X-YQ{*cXJM8XoS%1T-uLC zIlS~rPvRrmOW@L&3Zbx5!CYh8n#8(E1i3j@^%DCmZc%IPWw2hU;nz*+uTgTz#g9{ z1$jiy%l#_HqE1YP+*%4nnZUl!cXgofN{abJLrR*$EM6#D0b=}-}A&j z_`JKqz0y@<_SbgOkT|vCoGqpIxR~p|cC#ZRb5|0wW?w&iE#0OlsD7E_CVb;oJT_A0Z!%+yiNx*Gy#++n2#< z8rqw!eU!Mx->GMgRdje^Zj8d;JbLB89v;E#W7aaZ;w!PJUq$Bda2WcP)gz4ZVdT|2 zWq+&MT6)GE)8Xi@@E=g?n7M~kRzC7dlHn-(OFdBX3kT{l13L0?WdM%&YdD`YEihyEtAn%d}+= zOZ+`>^w|PVwR=3NSM2X!YB=7v1;Bl6lo|;5Li^5Sl~}QCH0zo)2VIBt1v3r(>zw!~ zG=O*a7cp9A`0X9YCtJ&QsReHCJ{TD`cHS;>Y-%&Q^FR^i6rU$0?WxkbCI<9m#@6GH zuXwN;O)g1cagFWLgR=Fuo*AN8ua77+CJ&?I_p}erwwAPaT8E;K_v3x~U18+?=>S}A z+2aViDU$|GImyCZ1zRwOQFP5Ld{S`1h-fA&X+q?+2?poOx(4TSPVIwYQxTAz>WAG* z8*5yQ=^xTS5S`r1!*W8KcUtjLo5a1c8V)+KkbH+NbddXluKSU(Es3e)V~fqxe|AWt zO^vVQSFOgOSd=06IuYxVkfwQYn8`_Wu-NTzs3O4(vnpY%i&KXJs_GO8vfB}!UV#my zR^CYQ08R?rhggK%phPo9tU+RYE?va^n!ougD4G=F=3!@Y7#~1Hjw>&q;5<199j!@WKv zPhC7r?sD11_OQU`rIj8to;Kx%XrBWM4KwHN!{AB2)Bic?S7lbDg+q#&Su2z5ciSGc z7Wo|YSIP#LQ$btqztD^0Y(f4LV`Ke~jE#-szp2{)VQeh_efpm^Ggfx?KmTjSrUt5v zeAQK^#9ypnFnsp+OtiBr8DSKIApmyNKgL!-kY6zVA9YJWf($}9Ph~zsljlE>?d#nA z-Eq3%;WG2uE%Tdu^xAO(J7Qo(R&@~M9Ar*_Xl76cApw_XVn_k<=RY7Kh{pg$FozTC z8v2P>1fVsbuwzFeeBFJrq`&})NvaTJz-9Y%g5Mbu29O_4Oq}fVV>=nG}i8gV+NX>jIKC*kMSf zpN71Hrt3#I0Q`iN4hDi?a0~JJC1e%iEczy(zyKh(4-+zgu*(jDAA}4A+H(Y+c76gB z&1D$IAN}ydfB^ilh6SMcXWiP$+vx)uKn@;ZC*RN-#=iN1E;y@WXeYBG z$X<@e!(#y1$U0E-xv)opiM-@geR@^jMiA!{?#DMXV;`J&M+YItms5ZS*_r|`E&3?~ zl@-2^n+6R96A$Dku)x#+n1%)z;@1)J17#cY9Q36g=o@bT2m<0x$OSON0Z~WT!VLW^ zfVc~N8w4;!behDFO%rl(nb8+JkTkAg1_%JLwCfwk$EKtSzN~!@k?4Qc)oRLm;351A>T>2n5ituV&}Ra)bDA zOYXb>4f$?c#sK=40~xM zkU&6r1^w|$`fZ!~9evkR_<`T}HRH+Ty}9XY@$Osx6@tF^?=t#bK2*O78np=qL~271 z|7C6o{B9TqV<2yj8}qYtnMc?%Eho_4`n4t6(n5|6;J_SOkYD42cv^$8-{0PcNdL2l z{d1WC2oWTZ|2x0$3VRXiCE4we^idPIuX?^q$$}tXyi}KioRkd2FHZrH3dH8VC4+B+a_Kub6%=XIZ&Ee(H3-O5uEtxoTx{{hvc4ZxeoJNH zQ&%_Zv#`h2`JC|0t>07<@Z@_*oRr1~Ja?5OBbKVCC=Ji#3Xf`2$?fNs^c7nFUX#-A zRL4KXz&42X1*fCmn-&Mt;y}3Fu&YHo{pfbwgkMOWCZlRu{6sM~DHeiEb6_(hITipK z%Yi(dO=7;EWel|T!oYkewmVjP46D<4Nd~P5VnZ5^4z5lgL7FT5Hm8;u<>A(7-=xm8 zOTyjxVh~Ku??S7SWj}wk=?_wEfPJ;c8(@yM_7dNR+7-=%%gCu4mlP{{2hZk+LaYWO$-|} zh>az=d{AQULA&T4V&d`Y)4_H$HX>?jp$5&D0f|A`mtZr6ubKVcoa~_PMSIJh>vI%( zH{x@UXF@XO3s4Q+1e4qQiu+{TBuZ71=2}BuE?)7=>oUhUk{Q3YIC>S7s*F`vykYM7 zAPKK&<-&FTT0<*pJE-~c*qS%|b3iy#(iXL+XJYoXGoNU>1l4M;s z#+c44F78ZBy}tdAm${nu!c!)To3GtWk88Uc3syQu+ak>i;Nefh##!$iO6k8=S}Pf5 zggjx}s4)b@#<7~sGK0p(C>|}H@c4Fa3^l69;Rjz6WIr4S4|raBMlaUU4JF5{ay{0! zfwTcYF@%yi$=IT9(+-%th7;Vteo9XlCVeQ?d!h}{0Rtq{9ACdT2V0vC#D6QyPp>JJ zW)d5M3sndfVMR~Ds9shfKAdUUK9{kNGXVisu*Y!*BvBq7goMZ*`??l?3I|AD-EElr zACJ~PzqErrpDP9bfvN<&BuOwv*oT&K#(v)cQ^2RCQ$j(D$-|VbU*5CAYjtb}Qx_c+|VwP!U~}Q!;-o zzGG|$A+1hhO{Ii&X3A8ijbrmvx>d>LS7@#_!d`-HB!b;xJCoo2$%jdG3I0*ein}2GO$T<&v%o_NG=8+W_M$*w!_RmS?Pbjf}<6fl@ z++7N1pdgS`p?OldQ^64MxX{yDloQSIE3lX*14=w(?c{$oQ^T}If4>tb1r(=F6WnC= z7u~{oH}`S-Oi{Vb;h@i@6@WxA46o$Ti6=`Uf+c-IUV%G-`N($^hIPWes?ecE-NTFa zPE=-`+V@iT>;`8@Su5L6UU4H{`BWzm-dCiXA*tNpebl^WQLj=tSym+L>3Oa7ZGLKH;&gKVPo2OyUSB+aa1{ z;H#O07iP0p4UMIpmWpxH=1^CC!fy1mG4>*$vR1t3D3^v#Cqk-{(N)Qp&EF@YCpsbA zvP6mChqteOE$^VDymSQiuaTr(?=ka|ir5y4_k0-;YXYPiBAj-#3kcVn+RFA2Ff&QX zTxzz)rYtrlE0js_#O~C7*|Xx<1zHO2bgTW=KUz8s+Ye7Ke8oAEuws4tTBF(YDkiT4uHz zt=A*%V9n?LbZKUjsB8LBMd^0XKD#yNAj{n-I5{JkVxoaUZ>)Z9)QarkhM~$jx@B7W zyt_tZQV8rr82^bJU$F6`_`O9~^!QWjXzOzZ{v6`_PW~ENWSJV4Of+Y7A0f#~yktLR z`Odbt|G();J+TU6vgU$M&8MKNi$^Q5MHr#*)ff*boPt|JWEo~%pRKcaqiflUOQ*Kx zLD^G06D@T7620-%+0g~8fDL?8TlC*KN6DhG#K6GmB{pA%>EGg{nT`V9$+jJMQjDZ+ zTK6m1EW?P&`%Ts!dSaeA1wQpC=@(fG16ScPT}V}0W*SCQzMGAu-s?p!{>hRL9QN`4 zR2nBFon)}z?6i%v?(CVhz*+S*+2~CfJCF~WYJ=aRt)*fml zY+tDflJJ>7l1=@g=0P|4)4%>}OnGBhsJZ?kz-*h3=gzHV?h*S4;7f?OBN5tVHoMAR zFBV#@8dcei_?1#MV*hp|>PWDqb_uN+U(r2!HLSDQc0$#zePmg^HGrQnulTRub(bdU zo0dIV)p2dCTAPL{lGJ4y52SDtPi15i4_wBWvW&<7-Y7EOB{CqGJpDoAL&1mAQ3L&h zLvp48CVOlrD)prfP$6*R;Y+vvbd#iTuIrVN)FAn7qJKDIGJp#NxnI*D^BsD;LOlm= zxpRZqPw95*#!Pz&ucW@6qpEHRQM8*sd%=;Gzh(@>A9aMQX)6cbMrbdeJ?2^|;sQ1UP8D4R@@*%?{d z$ujJMxT4(R7E#NhkmgUw(qt?$bXXLXM?$QpXB(F0tydq&!ew(?z4T05ize+`7Mb{ionkz}Gs zzhIST*W8q{?#iCu416bqSK0xYv?pu0@K?n+NWn&0K%j$sf@3OqgzD5g zc?^J_X@lpCOuiKe!Ca`JKj6{t57SM#(M0m{nd#z2nJco4FiM?8bP2A;BAr8d7eYe#+tKqrU@h;D&PE;*_?uU{)DhTd! zn0IC|F}=QV#H_c)OivHNWU&0BRtJ%EV;#)0(;G44>FO5{)&E%oxQpzk;=#9R%Z95B zo_=C$Z))l8O%x(s4vHS0rBrMT;JWp#Hz}e{hr_^&Qr`3)h>cRotg>4x%)dq0B4yD> zqEc`Ekf1|4KWs0Lu=zg3X0?@;OCDFfI~XlJ|2V>!9d-$gjUf#nxwci1YpN-3_-%R9 zXwh2L-dS?rek1q54wfnOcr-?{astN1$fXde6O&ZP_~dhYa~((Tj`2Gk_i{8pf4+M> zcmZA>oMIH_r@inexDt(Vr>p$H*?1ISOv5yl#NyKpy)++iI#N4bEA?MZ%|4g5ToEuP z!tn*ir`+rE`n3Ea2R^-7ze@-#VK^rr_g{b0M*=6e7V(nSR9Y0@w!+iAEqixCekZq- zjo%i~|BJCaMyCHcyIyJtUtI#n8l`0I!NBT{{Id}JF%HyFYX5VAI8YK=DxJxFk?`u` zlU@#wBq75$S)Nqv+^l1nfR)t!3SEZy980~nyV0rUGcV^5f@Gb`5viDV3EE+!ZmL65 zp7eR7B;^1(Tgx;>BoRUFrVHPn$E17cG$7fTHFCXc_k%gVBP40@Z5h8!l1kMJnfy3- zKF%~dDWc9d(ZD|UI3|ZyeO=85nHObIfwGQd-DXzbq)5L%5`v}_QCJ=F*ZX|34C3EL znq|u=sWrF+@+#ZFS3aHeUNPoOed-N(midmOeGnAW*Eg_icQ*?5@C9dw|? z5ZF@G;PK!1i?JTGy2^AGDp}^N262!1v8eehuSw{pq9(l2A<63OZ*3ln?Xni-r-+lp zP8^`>F~TWna#QIxNm$k54r6z+wqPkqxrYXW@TIm!IW#yqyckK=6-$xT40`G4R}sz7 zcs$*rH-&@-TJsP!Gt(i<=6%B1cOzofy@W=~#BM!J8S4I4Jxe_ppY1Ivw2zlJKWe!y{Fh2lQOv_rP|E^^{K4p5j(H+ zTD%cDr|D&rl3R@CUviq&yQtDooW7q+Na-yk8z6Sm-L5OX6#e!Jc_I=#c7*B9uV)lA zz*%Vz#;MJ=MpcbbfQKbwdnXR-S4iHKEGh2_Yf4?N<8esvETC)!-|G%*S<^`y~| zKiziLq)PAtbu_k!ZRn#+C`KZq5gAi1dMYpg$X0y2l)kHX-Tl3_? z|5OcANKeN(>IhWwBLmKWJJD1%zv;E%u=e;)-l>v59*;WrpFmv`Rg;<7uk z;S+uucKcOH?`+Q!*(i`XJxeC2nl}~sKEh@-H7)QJWF(%nf!sUru{Gqh*=cffu_S3O zT*IQnI!uhH9nM2_l>vc5{h(^S0;>@-YpNPaHZwEAExwV*hGwqA;U)17);vol1YHCt zAkDAXOHn0m@>vmuBS%$ateBzVqRy8hcV6fI)p`-sHOfF$VrWR}i0=lUTZkZYCiu?%&kOtndSu(Us-zIP$k=omGf6hnQQqK#q0j8@iL&(Q^ zkuq-SMuv)ad7NlHZ`=rxOEn4L1)n)sd6h97lCwbCRZ|QT`ds9=EAcUjmn;vY;`;~L zlbYl%5ghBi)`$)8OQ|evFH}LEy7#CI7q8MD4m3I7yJ*A5ttBCYyo$M?+GiL>DU?~8 zlt&_Bj1RJ}RKOdHe0Ib@KaDVuo(ydUY>7 z%&|aWfZDzn<@F6*4`sW%l8`0Eizr7wvu=F}y4&&LD+$^a>B>tmOHrB^a z^oH4-o6{9GG7>5)IPutW8_0wd{XM!iCYrj@<;eQkPS_Hqw`ORR_0_vY)8tAltYce3 zM8#tWOHLYvs`9mRbi+9zwbNF+lV@FuE5!I1792b`kiCY5;zRs=Q|k8~*7v)2OlpQa zQ2=N8JibZI*4XlxOF!r~-(+7a-&1f8dc8D^hOR`!>lY%sksCosp(ZWhl%B^g3Z zH$B28-Jy1Ee;>;PvyokwV@esNRL?BiY3?BL#n)Fvc{J5$yvy%7lmyze)w`-7Y!^N> z{2r&7j|{t_e$yS;DtHiKUulL@{394*)pd84Z%Av>{1%k((&nvJlcp)J%+#P=-RdvK zvAt0wl9LNW$jyei2XNxNa?5q~)VO!OwY52_UY+WRXzMfZN3yM~Z(gl-rv;fO;fnF4 zEAFF8(zPNwe2x;eSvaBP?3YRoabc>kJOeMVV+2)YnTK~cn7BkspI;wrkJFi6weig^mBfnGTz|6U`D{z5rR_P#;Luy=h%+v1 zJaoN4xMG!1Jet(PL~_X>W|D``FO|wwwDKCfLSAoBPHD?Icg?n+JLN0raiP#|#B&(+ z;{#eg&l@BDu2gf~wx?^E4KAWA`!wJje>T|b%l;s%>UCr;5unv765gKMpJFs)NHL$f~#K>hbNF0x6 zT`&wChfkNYCpo43xms0w(UVM(OtTMQ$xdg4m#WE7#PHW(@?~0~cbLd{*KsSK^t958 zxh^W&0;iT14j6hRgiZRM*vjvQmiF+1o!X7`2B*&KISjUQyxoFT!I>KZ9umTjcrd{N z{Zna=-p#>($f_#Iy3G^lUMD3QV_MQBbQZ;vum$t|19b(LpM#|wb9+|R3$DX~#xugv zWu(pDy9>|F82sYtrM>I33f2GE)|MOGOxS!g&^_O0t1JCvs+M`OTu*FLL7})*FN!5R zQ-f={d1adZwfjL&UE=HePhgGxKY=x7j{gDH{sFZA*BbOc!5SMo$Ny~!`d^0EkZ-y~ z`3;@hqy;l=n8n@LkQ9xq84QE|I40*O`xDTLLm>rH00Au$5GW!cNlH>sLLvSC{F>RR z_3mr;eb3x0@2%UY-^#L}^bG1X(3)sby&-}_J&^p+xHcLDm{erY01|+&uN28D^ba`H zULWAt8{q;)$gk;Ie}92GcPZq^!FKdKMSgD|Isy@7@Hhp(F>1elJ_rWQZyGUH5x{aV z7=cc}zvc}eW~dwRy*2(%5Tkh88}%{x-pe2RQTluNkR z(L9JCPe9sv1`-_XuR4^#$Q$+QI3NfV3=9gm=NDu#qpjo+;eY_~YOZ;l8}KoZew~26 zGoYA)ox9!PVZbkbDYxQX{CZHV0N7x|J$~-Jkl+CY-!}liWNIAX;XK&pc_xs|w|)gb zcI=;h0;sP?OMe81@!j*E=${mbh!0$tkb(IfUU_8(q+>8)f}TBoWE&v|YXnsk2$7B- z$6(L*g8Tb<0E$KEi$J$G9d?xR8dI>~gZJ-=S@=+a5B=}q?|9ulj6mO#0lh}FNfqGh zYgjRZZ-BmwC1JxohOZj%Am6qXA#WnoeviCA@JfN?j zj)4Y#3kD1tYIv|gpMX1pbgnZs$0>dMH#_1Z^yoT1nA4yaK%zU8Jp*wNoL}JncLCr% zewtByywK0vP`_IM1c-T5$RQw|JzH^Z=QKCM`UmHa=F>pW!L!?IjKads-2tWz(0Fwvk2EVfpY`=Z& zzoIe)<9t@Yzex)4A^gC{zxn=sU47;tUlou8d}AUIZ@0+N3+}i>0fE2cJ9sp(q5FLV zzjpV(aPPa!ztmH|grC3FVw<~Dmu)I{Y43jO1v}z(dwkdKsGmmn$OgfqbD$S|IyL)# zFb#-XsOPued8#}#D14Zf6l`_>f@|kxF))E$nM4f?uY4d+YVddGJ@FLnlpFBx|KM7r zK>yxv{k|FONra!|*ImwsP2i!}`L38{fxh{g9uqksEpV_Q!@NE~@BLd2GXnSkd>J+O zSzB!YfddLw6g=R;c?ck)In16KA0dA{*%mbPcgPQz@g2n08vbr*AA$uW0Yt#dKX0k{ z1hBvx_)T693Bu9g@$IV|2ru|5F7WRds2(o_cK8puFdPI_fYA@Yj|jv`+`wMgSKHp5 z_3y^7ufpCP0Xqx>Q%I;z-}U|1OI493ODuoGib09PkIJPr;h!y-(v{!fOlF}o3*BX) z6M0&r{HT|q$ke@n3z}C<+op3+3u~uLjVX&WxiaO)h848_CyK|*1hFhjmmck-Y{S$_ zs{*s$0ybL@Bo-aZwNv`1=d>bLT2pqYs|Co)%bIL2Y^D~=))(bb{{ypQt_G4S;ZLnN z^0z2$JlV#Fc>R&~@!<2NEJ}zuzn5ziKz!yAie8}Ai2>5|q!`VhwCHC%f$bHU64T#covK=5CtHVHOm>C%OkxvWs>d_;ep6mXR zJu^URU-%esi;DN2d(1T7$V`$np51&5VE>Dn%bYxEuzpwUqMa%4t9f#yV;c(hVnA2O z_&_puGu;vlb9znEbus#6JOAp1_N0uGF(^cZ`AmXXFTW^vUbWg|d)B&~v)m-{!p1VE z!y_PG;tkZN=bNKxNH>apJoS#FPy2k^H+n`ELZmYPQbIY*ZJjd&erGA zR)W@Ug^CGjFxlq2qFs;Jet~Ut`zFWQJ>!ORKchotamN+za)jM0lMTy?e_tuJ(R8zM zBj&n6DrZ&>DA8ZNNJrv6?sBV!Y7Yy8={NQJZURKcnS0xganlJVp?|gW^lcIud55Q> zf89a!HT7**7*7SuiLxW);{4tQ-R^rU@a%HZ5q&nsM`H-)3@&Q(cW77M)sUS$U|gX; z7;h4~R;HRHZ!DWypoi=vP|P3$LYgM0&LMnge2{z!{dx zE(qIoUkpJ476%oAs7dyx#B#ua+HJ=_;Z)WPX72Q{rL{s$Vm-0@Sd$*CG$=VD@*k*esQ! z7mKpr&3uRq5HJ2DNgU^E#MDl{$ejNxVXM znG%GT4yvFuJ{;s_U-kNQGQT~Nd6mc}K`G&@fQ5QZJttD=-Z$S98Ro%pJk-65%M|0* zEOBJ!Y!(x->dEuO^4eHF1hwq!S&8MjVF75&n6n9 zvPSXIEY1}Fxh89w6${Hx^tE_Dg~u9<=Z!1am5_su8}!&|1~$Xg_L?})#(5aq!)!O4 zf+=g~7-k^vTDsG<%$RP0!~XN4GcEbmv>#1;ET_V}rMNck?5V;~@>0OqalFj&9V&R& zU(2|<48Og8L6i>pjPmzG+qd8-XBL3pcJ*KdT@Iz6-H%nMKjr2?p@q8G3D1CCPr^#f zB@ikg3?Fn3L)}IS@?%?JkMa`lF~$o`iVEcCX$+)^C)q4mOT)Eis|6O*;WfUZ9GyDJ zF4~stbTI< ze_|bdev^4}%wMW~>{Pz2x-14Q3^ymmKP!_%VJdIGTG~M)X=n^wv$(&}EmJS1Q;I{Cn$f|wxUneia}g9P zsyk-}^P~-Q%(yzqTkt%jG*9=lfRD||tr{JZwQSvXMwfjaLu7tzLftT%AIhIHS{SB{ zgzXco-StPH)P}9SF3yR06?`8Q!Jm7vu?vM7Z^4R<=X5+*$@CP`xd35R5737eY+%MkzUoYB}5|4$dw9vTS95 z3wNPQ_`L_31^g%<*W#%q(=Nr4GJ#WC6=!j~L-l-n@3^PJ)xpS3=rN(h@pm&;7NNDS zLI%5}hShz?ixGB`JhHK9yA}>d_(*iP$CXBS%h{0IElL%ey|i9j>sbG;q)f$hNu>p6 zP{y-;dz?OT#KPTC`{aMq)T1dMliIrI%qvi;Qd#t_zY5L^^K3!E(I`V8fa)fL0>tP8 z1KjW6vmt*6yLPIh(MTqva}42;%RGdXk|^uMVCZ+5!w_m_(ROF-f8fg1R7BWdiek4o zUUehno_5kd%4r!fC?@V22riT2J78hy*QOc|4c`^}5Gv|e@44qZbW$yVB48Ze83Hk` z#Sblk0!iT+1Gd&8LQEl%EB=-W%^E?*zNR*n-{Ib0SDNo#zX-%e&r6o=P{VjtLsQbv z@rZ#`wa|A1mZNg)f8}Mjf+UV{AJ~HI=aJGbm*r{WPHx~oWTknD&@pyD{0XIE0?zn$ zJZUPmUIJ)3nM*y)wCk>tgFoS%*DMn)-E*jy1Fd|x)}j5>;$dPbBU;jK%&^O*(46*- z4-w9K9af5|Ct_K+czsM3goak|7Dl3zX6tm?tnTQ$U1iF=eZS?g-?DUcC!`+0R@%nv zdIdosnQGrKFBsV(($PvZNaW+`w0ag50M)sc(h#$j|wW(%Az6g@@3|_U{G!ZrSl92|J3N9qhBRC2u+5G$5WOkJd2RW=w#^{s{Ul;;6r8Cx%S^!fpdQ)2>4PY1c$XZ5dVK<8?S1<2>=@)n<}q~s0ISw)lBAS^rZ;_v zv4_!9kTZHhn?}DJ)jag7s2+m%_>ngx#mY;UXbVA&w&a=g6zUMKtqmE~SA}8lT8Jq4 zee|gi8e}cB3T1gXt1+s{)q+$b{k2a<^95Ds#PVlj{Jmu7pzMSmL@UmIm$qM1c@>nY0(ylwzioe&r-})Vw$LsE0*Rp6*VOPaPsO+t`RS8a; z(J^P!{e+ne#aDnF$Jq@+((mtKN=TNlQ9XwEX%z$aFF(+qKZx2}4)j&Q6vhR^51GC1 zwV}T(4@~id`nIY z38^NEb=CxqQISf*UN>3npnU^j*9TFrt4++yO?js^*K|szZ$s=e=23FwGf9|JimSBv z0uPt?fP7T9|1=ixPE2jcNOe|mx(gYeUn+amF;e>;b|MkfOK43pR}fVHS|9?3CJOc1<^j6*5Nfwr%w-(FyCj(6c#3r0j9a)H4CbGI^49$=U?{|X{UP1zKaUuz@sER z(|3hkG*ThQTVURdxuF0)Ot`@iw-Rp^h!nVpQ^~Us(iiO;fDj~k?>$~r1u#y& zM-x|<3{wMxOY7#}8Cdzr>o)A%?BhDybSyu3lT88)NIu4cONq!|+p?G}iQ(qmZoih=ODQk}}C z+uSUZNM?;~uD7>#tekQIX(VOAoN-8X<3>$v9qL0LkF1HveW&|R*uvCZc(zj;`(`Nv zz|xp2=IPjhdaZn82W2P5uwC-IZk%55Gu+bDn;epG0Hf?^VMCKc|qq zi&j%K1F^ocr#pZ6o*X3|XvFoS_RmotIF~UAEn1=2HAs!@2sLTx23`KB9y8Dw3ASOB zyUFWp#04rTGCRFxz*&3R1Ok6oVoyz@Ig!<{iuQZZ2dfmT8bel&2(RaXos(;FZ>cQE zZ#q?&5y3Yi`uFcn(xi#TPGw=%qU*c_W?FJtk#P+tgdQ`|ZhnjV&^;aHX3HtB&!}JY z&(VhkgI2j~+Uiz4(5qq~ka>oC?DY||3g`Y8W9JYg3b16+wqLtn+qP}nwr$(CZQHhO z+qSKFn?Df~@fWkKbyZYk)yX_JFG*WxHgH}}^u1l$0c&Sx64L>b7lWU>wrmM1UD?T< zM+>z0?JpJsQs)%Dz%SM>?kR!M(f$yYm?j0au_38Qx%dg>hx$8G%J-pY;u5n~SU7%Z z6Y}P?OkK1MXs=Rr*nAcZ0*hTH3R}jSyK90J-PIc9gXZiNrCFQDc)B4xl`>*568Wfc zXO!0@fNLsmng7VvqM@JH1DR&MX-P4ugDpWT#v>l>ayQeOqCKtlEZv0Fg{eY(=f8Hp z`#ZaLtVfAre+JMt9L1W^rCRj$1E9UxmaA-dIaa#XH9gk$}(; z{HNR^0~Am_r4LB>w~9B^sRSfQ0+!5Mvlk+7!7Q3y+M~^Gfgd(RteqJ@97w&$?FUSe?@b_UtV4d1 zXW44WpcBhcV1Cr8=;0QkO!apNs_9=Bx5x z?$8gke{7u@h*lsNRoGc0iTTM0g>w*`Z%mJG8dlt%VtTR{w|`Bdn`OW1A3dCOO9go` z_J>=VH(JV58e`vLPrQ-=hAqS4_-wr)s~8 zT`o+#pY?|i-8GZbs*^np&StPt@W*8HjsFV*WPf3Kr?mLKZbwjPpRvWxu`vxP0UfFm znw8+&2)>a&%H1ZnvrfkUo4RcCvZMw~jmTH>T&(T5s;GNFQ@nOHwELn-%Pl-o+;^C_LN50+5pbdh)5uNG<)* ziSw%*sImS@HF=!7!ZUnD^DH}+Ord-DEpC--b>w_hqIoiwn@3f&mCv1s`@`0$8}0Yn zAv{q$+K>h#v?aKd(Cp75G!d3yQ8wGvR^d#)_@B>`Cqk+#eG z^1AXnMYI-X%i9qM>-WMa#|x ze^K}_5ZZ7_U_QKjyQ(ri!jzJ zYU;DaV%FOF6yFVc>-YT5jFkux(3Owe8w^^xnj`+Gno}qRo5u$;ACJx4PxAS|eTs=x zqMdiWwylncNvc4?P`7|I7KUnTmwj%UaI3*gig3}ODDMJG|cYo)v%}f^^ z_d(Hs=+{XpcBN?-&VCmY1)e59C_!lXIH-9~BHVpfAZNB5PdXu*rD%Ar+RNHXY!K#2 z#u|<20(9ejPLRfWzK=yes-lMF_jCyF4m3muB)1 z5E0bE;5UA-3SKU zt!~5f6uA7W)GMYhyuzNr#tf(CwOvX7L3^b$jz4!ccj71D65fEU7J$g&v}>bYZ$fW6 z{gjG=<5cq3xCdY$)-MOUEJaW4QqMhG)#7c26|KBeQdN4~FUlGvan~EAwVQClIP^nY zu+=eW@=p-=E236I9j4y(Vd6EOqmGG>J#w>ai*aS~`NGh$?&W~B%wsBTi2fUErCT)s zO0aMXkj(s@>DBN`TO%)DZ$A1l;$HS!oO_J@Au~T@28iWO3l|J2bEb|Fqci4Ape!>z zuaY?@k-FBo%g1gzZFLf<^ws6Sj_mlX3{VJBu|4AE@K7)#W~$&DzGyFL)=X89&u0ck z=f)RGI7zpDS5*(Vjp_}N%)0J`&?6U*7EI0h0*ub2_!-Z?QO_rI9+8VIbuIHrdnljI(t{7}_y_5>IET7`C%xeYn+c-Q>~RxI4rJAqPaR^pGU zm0_>U;8jSpleMWL8w^)g;-lOd(TMb8kJ2vj`t9O)iayKfBA(?c@FnthKpq7f?#4{= zldkwDD}{UA-=dv_k!72YymH6r8Z(iIsB)n-@+EY(Mv`mRJ)Zd@?42}9Yle{V(4FLe>Q-i zHwR&7T-DB>Mj6hAHB6rJnO5PWUrDeQIl3^9+l)h-dz3E2Zd8CUkdu($4Pvgm1WmMo z3gkkCQ9?F#9O=bfg<+E9Nezn0y8o4EIWXBhB`)ly*kWMXgmy!i2`kBT1n~gX#wWtE+W-<#-i<_nK9n*lED~pp7Ds(oKCH}J4eFzu!=nF{T1OKtt5448{^OFXh_Jg{2S+-S<*&!^B13aA&OTpk z`M!(^X0Fn~AyHH6MiP2*yOdpV_NOhL_7aeuS6+*k6D(6ea5wF|jcB9qs)!ZDEE(s} zC7+k^ciwg$FM@lc-=us(?yL{h6QuP{C?!lmX9V2(&q-UBpYRPg?F<6ZVlRUruU6{_ zaM;?f=zaZyFt?1tE(yOtcPfpP^I+JQijq#{aDT4@qZcX8C`Q zs49UfEp4|Z!=8&+0Ql#do+ZGZ+k^vxp&5XMpku_t7lVQ(!OLr4{L{o16?H1fDZq>H zUqt&n_xyTVcDI^T?{0O83(BdndV^r)1-=0J4Fl?tv)46YL4d#m z`y2f_2;m(AT)_LLLG$T?409lSZg11Ast;>I2fDGbP)C!}JU3wzx7!bIY8uoE2Z93<*a@hmuOsJ| zUy=hs0Z$C#*Qf2nF3|M_zvdRk3vvQ#Kfv)tg9S9FL=VPS_w{3RdKwkHV#SRJLFtp_sdvev}-VXzC8^g6!McW#FMg>J}iY;Tu zI*AOisQf+m4;K6F-^wHNBZ2@)NI?PS^9G#bGj*NU9iI;H%Il5Z)1__OFw`%*#Pzf~jj!YL zqlTd5q62uke0`mOt)xZ;*`hqdechc#X;x~b@2aMJ%e>nqQC1eh!xK`|`inEAo`I|y|j;tu+4K3ahm zJs=ar1H_4X_v_Rg^g}=NA%}{#@yT1gK?dQ%ptNVBZRuAAf#p9C0#Nrf08j%#bYANd09bG#M~i%f`hgjj3=qaK z7&l{Pt4eEirdx-+f^ZQz;&MtW1Ox*A+|NT|M_WdDfs6b_`XRdd8!}v9hq`fV3qVBz z3NPH>rIpv4?`!WMLRb$e*UKDA{I&Y?S_l*jCXg+DY6?H|FptALUrnk^K?OK~S=dVA z&O(*@03A9-xH-p59=7mC*+{4wzpK0e)>)pyV*x-v0gZ)<&nfLJ1ebw}*_suc!&#IT zW!n@t({1X;nbKRRusQng{byCuh3>JBX@RgGz8bWcKlnI+N-e1Wl<-27r%GAZQtM>T zW@0kv)~F!y`r&>aWLMxmkR4V)p2Jm|WllmPkVJ=B4=~M-cZ_`UNhE!V!SA9(NE>-0J8r4F!tTek6b{ zIiN(KJJdj-PjY`3l4J3^|L$^EifZm>#*@<8l#8R9$~4E0*A8<|sfl%9F28(`BiBNE zT~jexy-VGp#m%6GYD8*L3$VD56#>r8(}L5Po`matY#vJ-#dHUQs={SMPH& zVdXyKmhWw-I<%;3ZML?cuin5>KW06@0G6o#zJ2#~lYm`Hqq@f@`>S=uhS*)ns2rD9 z#NL3{>{yXFc!udIjX?V=xBRo*MhTi5pynB&I8mykvgk0N7lP#_JWn#aEG@Pf+V4{6 zKodK76ShQ5vZRqlJq^U_9a24OG7$n?Jm_4|J($`wp}8XD`RKIE4xTylwWAp8katTn zeGti$G#~0v77iIwGzG#Szk^)1`G=ZKGvfYe*1SyNw|$dWjHHGI;gx8Ht2;U+S&m!p z>`Cvk{;V*k>Ar2LL3P3HjI_i+b@YdNvJj!u$Q9QHEWZctyu+@0)9$!w9KExas6l&o zSGSHgivH2(QQ>*O^6|y~B@+LS=;0xr&uFs!NHG#CDp_NRiwNL?)?4+= zHf72iU({xfP*lyb54*dA*s7PC`gQDRy7|$3=7J_G?IjCrE(XPAZgP)8M&DHRlix^EkqKZ@I~P&N@IGYMyB#vKjA zF=q?x%6n}rl>f5NSe#MWse0|0+edDt)5ai`(vYyJyBKI)P*kfeN8_r zTGj6hcZW^QKKwLyJ?H>S=N2-J=Sj~3!Bq6I);*lmEC88~qg~+p(`Jpjccoj1QfIAz z8^J~jZb^+Nk<}c@Nw9id;yKwwcpp=A#+NuWar4{BaO4=z zD{M*8&8Fl|(@?N5ReN<^naXBW#=1oMJXk#Rj8Y4$ z*g3x;S=+AXX2qDYbh)3nFFlp4td9snkUfv^{Ta6!MP-On$tTz=;E)uzQ9ZJIMA4h< zJGRcz=I|a3cdsxyzFg4!e0M;4TO1&!npEt+!cs^gXP0`jk!0!`!L77vvfd?AD`BTt z-o0`UZ%i339r)Jy@ZGwlcfJ?p5o!Xpy zr0JWt`D-~mSu1mA^L`AabRxN34(Zz-jimgZm3%k$Z1t?}aT!T-+s`bL$O*{tLu5$8 zvs($v>gQ_M1H^S)bIL8nRJ!E?#H6(B6{m@=E;~JG_n^L*hPqVlJjcCKy}Oy)DYk&ne=i{gvv~`9pmA4ocI33DLk8uP@wQKBuIEXvhj^5Fe{>R) zm3XF8&CvIeKEb)2`__bCGyGWTn)@#Z+2IS1omfY8>g1LJaAqGSk$xWiHGartL$aRP zygX+4v68;sr1v@E+R3u(`Db~hIVf^t=dK~ZWWfj5Mk5;a)ivQFGjS1ti*C(WBQqU_ z(!RC#pKv2=2`iN)6+vTuE7Ga}J_qIH`Ca8E^e48swk6zTesf5d3*sRqAV+bhr8U+o z=UMC=N3|eI!dVtZMnT{+;)Xc7Q&2nkcq!rbMC=uDuE7X1C4A9MkRY{>c3r=i`;=KV z{p=+#ac=aUI7DF}RyTk#_twg)MN`P7v-`oraiELra84*s`D&m3Z&``C%F5?NLM6)8 zY{p>b{aS!LyOi=txUu~F~l>-W8>QFtC%5pY{b2wzor|yL4+k$7Em|>0+ko*fm_eeF}hG3y~31O z};T=CRSHavHqS~DtF*@HaQbzq{1uTqF}8{ff+;C&uH^O_6MvcnISW%8g%x# zl-Z|8M1lyz-h(@^Q_$g!P_+zV%OGX2JHtCLC4< zzMoLP&#_-DyI&$r_F6YW16&GAg0@$6%=~J_7R6fP>>f;uuE>hc2JJF9!3jC#q0|XzCckaK)-1rAr8R$3uPxbnW-*luMxQj5sV5J|$Y2*50>YM9T zH>Yq(Z3v}rmBFGT6PIq!suHD4KO%XYt%NEX`!KGLFZ^j+oy>?{nMjk_8qwJ`MXOM0 zL^OI0wUbp_2(_CGwo&3}(kmdc>wdeln%BNq+yGnP+m+}rWf!;fVoDy=Gy$AU$4kzg zU9#}1V|t7J2B$o1NhO>&J-X7)M+9O+R(8d{+883XODR%>%6D@G&4 zhgDoVm+qp>o*4*he$XS0iCSuFbY%THT$${vcndiB^K-)PDh5)qH z?z{6$zdo>$p>PL0#JWo;wTX+oKU@#W3)wafh`+6Z+)#_Vhe!1uC+n5(kpeP0MTO5D>_2PK@uLpQ{T~-y-n7j%-C~P_Ikhq_K@8W5~ zo>?P$@pEK|NZ?B%+X+6T%T9t1&xrvqlITPxR6+-nxG-mF#}6E&UZrmuSEnQFcRv3e zH=PVd*#Sfn){w{hpdklCy0mJj-t20ysh=03MUg%2AEbNXpPY!ou`X^!pZ9JC4mO~o z-!=zddEifsw}A**d@ne;X#A@ctH!Z*D$*I?Fv)lraf25MOK!4_y4MOj@zg4a1x(1J zNDPjn9M93V+_rtbXu~&r<7lKzI?S8&baOl&-0%YddhOhB5E&Ag*&hJxa$m@Ejqn!I zElEq)XO;6;yJlJEfXj4Q#oyu^uXi}rs5nHDPKKUBF{>_6tWGh52aZ{^G54Pa&#cw`DQBt=zO#i@8 zW%FjDKN?G%R_GAQKN(sbp~wqQS>+}2n~K4Osg*Gh48#QMixF!CuW_>(;W-TzOGO@g z5xAVk{1AEci7FG)bB*g1oc9hl)>`<2*#hZvotK|lkh-HUnI)f|FqZH(eLE?Aw75$u z+b=my@Df4j^@6pE4+LEr>3rq4K6lOutam}0ls{O_X7qelB2Tl!qPU*j+9h}|Za$Jc zca{Ujw(s^Uoi_Fpe|!eqWvU64q$jf~W3V5+@#s&o)y5EcVIXCa5TsqlTW&Dxz$)9w z({g8c&|P*JdSN(!!mO%B8&OwYk)trRdrqF}S59kI4J7=EAcRGmse&e|qS@5lLwJ9k z;W($EXIv=2QF+u8&N0kMAl|d>&M9v+9Wd&3jdAQ!RCUQ;K3TS71U{9gLLS2>U0-jx zCB(5kY#Pk{fCg~M6BHbh72>)HyYGmc%t|xN7+S zAet8ozjg{{We4etab_;` zwp+uZ1rZeF{pPUpk5cZWMQ|mYB!#iyQHI}HUz%d_RB)r78lJWkVAs1F2tV*2>@`x| zfrjTT7nhSK`Y$2)^7A*clbG=!HitWmrEd}?-BB5(Ayi5j+IHvTJ;~aS%SCLDqnkC4 zleDIq%w%M{;5td3s7+5zqf}DtT#@)>3bU;KS9LQvRRigrBA_L<*?R{*Wly@&nkb!O z+t>)Y){W6#A&Ax^NUb#*!6b#;1PK5Mg|eU+0yw5v1wfc!WZ7q?9VA_LxQ`lB z$N+4gQP8c3uz{8_XvpmExu6>+y&CE%N8fAi<1V3^=|BocFA%q1B+*A_(yj$%^zZ1f zx1J~d#9#TdA1qQ(-df@yRm`CaHj4``AM#u9F$Bl(VP9K2u99ct(vSgr*?*vB%}8f~ zReXy>IZQD6^OPyUSruzg8joS4U&==bYbLKwon@;TYZ@~ct~e)56pg8tPCoY$hZ8@w zve_t~x+!xM6>wwII9e*XzH{378|M4t+>1AAi-+V02bD)rbfPlimf7fy4{-C+&lJCr z$wK|AYs>XEOKu3hW?>Qb)9m(TgtcnIEM%{AM|(?p7#^jP3)xm<};|pDAkO zvA5KZ6`_YZD^2GHc;{c24HEI(k0DE5C_C}Z(l4thXdl^J64XKMNULj){209QSn(bm zj3^A`+k))R;-4MzG_l?}Fec%%#skc6gm5Ly39L z|MnM*eF|$oY_AX|-%pbNbSKJP%kr;-?*B=rnusc*#nmpqBQgot!;w1xe})o2xS(=L zDn_QdZ(VbOE0M4scvIHL+~ViWx_5SSK3z1^#pISje#Bmq^_h8=3++DzpR}NsrnF*f*R*Ak za{-6xx^*27GS z;sA!8Sb@M!0UurkoWgtzYCo*uhL)$`H#CDrdtICVTRD{sVq4sy6&Q(6D^pq$K)=?1 z>TjxhtqHmeZtK3f^jF~t+niPxTGXF~g(5M1`v_YWv3pl56qXn2yR3`?LSm&t$y=ZaM6+sBbGg}n4qef1zGvL1Kcr1Dg-W&0DhBtV}3 zo~>Lt_!SOC@I(!kZ3+6!Y54x%#B!kd`_c{Xh9_Cl!O*ydfc@sOhOF_|O|b3KDZ0qq zPC=NZNdg+yVHA8st(|5{l@P4MD3cG|cEn2!h)=a`tFe87<*OkF%4_FYbEN0BJ4u}4h z;HE1MAIVO}B36ZoZO5z6L&R4< zaq>#PuJ-P(rH#tAtccu#(W}2FQ_ky{;)3y-US6?z5X5iH!3&eVcr(top@?MN(=jyjX%RQ?ryGx(|k%PQc;Pv|>&iFL?>5 zY?4|}oTE;BBqwO^%woSP$NZI({Wkwz@~7}p*w1K5EZD$ba^Wo(fA@~ZmL<~M@8kY! zqkZlclU075s|zN@rO?1Vtki(a>ZV?JWtq}TmkAQP>rfoCEpf_g|0t*KGllxrC%!x; zod00x|1Fd-M?`8YoAdh=^19`WJ(FYs7#v|CzlgErZ?mQOG1#E5V$~8!a&XD3JOuKm zK+C0#=S_DpiD163Xu}63e+o0ZiJmS@$yEPy?K^!iJDg`OKYuE z@|xZcTJzif!$zW+?jIKzyP?`xM6f7OZqe9DY@zyzZ>*bVvgVyw+mwBDS9-}PW z`8s%U2T7|3G3}rxi8%8T()fi}SWg-LF>GbbS{ZAJOLY02ZTE*0^)d8z=swmYE0r4z z1O65Hj>U=NpNBsqWs)he>@6tvES1GfOE|WSmjc!IQN(OuEX&Ae)_I1GpHX45n7qrk z^}EPZ64WzAiuhHFS7zDx)FVqxq;@kZz^h_oE{D7!Pudd@C}d2J>LE!I%!Xv^I6NI@ zSDTX$F-Zf^8-T7YW?J+XP zsJouU0|wWNP6tlQMHjF;LrD&l9wdnTs}NB7Z`TPF1PyGQJ^~I%-Dt4qQZ@fwSe}Q_zC|A8-K;`hoI31M&C0>|DCw=?< z$hbXU4$-lA0OYw$kq6>FNyjo}0A)UHvYM&nN>owY0ReD>To*#w*Av#z1pNqq?` zA8Wf@Bvr>J$K?DO_RClS*Gh@Ci;N&A?N5q!@+ly|v_tXmw0I5U+oOpH@j?TAd~iaM z^|4OkaKFz-55l%km_<1zOP;f!CAG2t+9Hr}KMx7G>U9E5bOUmQ`K}iMJ0xDZB7qt4 zM0w1Ny>c$$feANTdJV&;SY(t%;tg(hA)+P*R(^v3-$^k6;=(9Pxpjx&V?me8uCI&U zCm(sf6cfwYGVa-_4=`KBMn2~THH}A{F)nEuLd&u#R|TsP zSjHn%vEV8aiEm2p*0}Tg;&h1SQhv_;$r~Mne$Q4yI*OTK_G%a#Ln=PGoE%p_&pHfVvviW#88VM6_Rv7K!oOK zJ-A+X9DjYQZ#C5^-Cw5|89&z_r({&t)Ssf?P_PhS;gvzKhT#waBmk3~qNw=z0N}}} z06?G+8X7SL<>|(DT?AYd!%z_;{3O4@1;(KbVg)vnuI0`0V1Z!goxwmkkT*27* z_2K<;Dp~+0;D*8LLOFkcHU{G$oVvPWxsgq7{lLC`S3yG zlW9TZgcHH;cUP zLSKN_0TmpB0|EGU|2!K-tE3SE!9M=7ez``1qA)opF-yDu%KfA&$|LN9LmZ(dfZRz& z00QE{i^1U0&_F@_nCAFq_w8Q!YCd1*`?|d1qBHNwK=>W$63vyqvLfX2PV9X!vTXVJ zs>})JJ;MOneQW-}`4#Zdef)Xy#R>SwfO)TfCmwnye*aPGi$8(iFOJ`!Z@ynIH*#se zxF8y{J7iB*XLxf+K)<$S=ts5wEBC; z5+qn?7~n-m=jA8J3^Y%*z>g2!Lj@b(r>O zG&c^k97r){cKQ(QPTZB9B6)WWP29dbv(x4d(Sdzz=lWdb2K%*6SN!+3j@kd?q0zMwfXXm<7F0_GK&mM*RKEg0Kt zKjL(clHNV912k=X*0cidjw`MdIcO88ZStgXzna9(=dm3I-M_FkDL6?g{e$3cMdXk~Eq6kFBh3a!-HZ|1#X#z;2=uGZ(l_e87cw-!fgx6_o8 zND!fKG^BcUSDVpeyHN48DwMqq5)Gv^9P9@Qlm^{~>$c8h#6nG@U>H*A*PnAQ;$ybV z?l3s3!;&zV^k!_`ULH)XJt*4taE$VlIHAcWVi-hI1uM4_g}ab>qZP$4*JCuT-f&qC zzFv4=E;+nJLl`;ZQ#YWW=r?Xxc^=(&PbkWx^YKrx|B5NN6{?UX2{OQEl8rD4rN32z zfYyH-IkwGVX#orlmj~M+k(4&OmAcJFT-$46xgREHjNZHB9)eHAfQj%==L6hlCzE!-H3q)sr|{hN7NiDkJ9 zVZ8>`yjx>kD^z9*f*4@-RdQYy;>zyH(S07ELl8zgTRY`+%Yc4TQIwm6ebhuct(W6{ zDz-ZovaS5>e##%l!d{XOea7Bs;Xjz#uo14eV}@40P|TcH)A%z_(KS&d5{e!uk6jhQi4PulPXB zY$ko>r62E{cIiy*S}`A5QEmc?=!2gK9@B!8#`$9S+$8lL{uUAy)IW?pD2yVmrvbG(e`t{L zg0t9?WxiEcF0DgzX1P*Z!5AfrnETF$x!DQNcy<>e+W*=wCg!uh$y4*10*O_th1`43 ziI#Ecs69q5Qsi!4fPVXW!4ri(IwL=lp87(zB4 zOO5c}lVl&kd~0SG|AUlW6L0%1NKl&yZ0Bl$S7J3YA%HWR6cp@Nfv#k_xJ<7c| zD2XY}h-(U58RkqmNFSrM7Qb8J5(5o@c740*BzY5L>r+9my@iDvaaLbD)y%V*l6g!x zz{O_Ihtj{$pglIE;Bztj_Oy|5h;h?pog~Eqw5E5CTZiVR1>YrO(q{IG*m>qft-WEE z-oDM)cFs6UbuMxwo8wlh&b_=Vn4#nT_6>$NoqPk3#7pjMg=Vh(h(C+ZCoLY6%>9oZ z=P#uicj7xrQRz1=$@ykpJ6d)w&DOYX4Qhu|yq>g5VzXO*@I2GqwYI`{BMiVBp#jwS zio?X{oau+<>XzU;;Cd^Wx=ZisR!I}k-(Oha19Ew6aQWwH^i_pVE~?OaujV&#xeuamOKT0IY58FYO z7jA`uIa*jr)IdariGHKnbeK&4t%X%Oy|twTV>P*HW2SlDug1W!qn?pjgP3ki1f)l) zv3=Pl)HN82O}yy~*dm1gXFjDAK7-+LmRlA1`_7vWBO$5r)Gld1^hwuV6xYtHU5uXf zb~6m5QZci)l@rZA9N^%s$(oMD(McOIj8`ZlZ{xw7~{Ow{_S|<3!RKzLm{K z7%_=izu}fF>(3a|FJV=A$E*_Uh9ExzrdAR+BF+xYuVp8F|Dt3D-5wM+(4?~Q+1|-6jDEE~Z`dG{WxhUN|mXY`foQL$31s9D# z+e$i?S+?Rw`(I}W_`CfW?FSCOi&Gsh{ENl0Kypi5bTtFWQ0=C($3XOn4e#+6_{l~m1jO872P`^g-XjI=-Y|5uWCX=GvR+lHn-X=iu~40L7Lgt%#-R*k@kQSLW6G=o>3B zn@$|=@21U^L*UGCZDy8nhr5Nes3qHa15p|A*=thA^N5^aOZ5Lq}?? zjWc^+cse2ww>cJ7n~^#yky{I{D_m^5@*A`+!O9^GeF|WHY5fIe_mKER&*gRM3UR)W zHq7{vXN)YcvO>A2#3#;Y2=!d`aU67=d}fVx`&{9}Eb!La*4A2;@XJM6eQdvswXmwQ z5p8naG{dp1h-@!3FZ=968#H6tKM&mW~ zL94FKaJ(L^;y6xh*Z#AhMRm_@{*euj`{G~jnrIHrm*GANum*<|8Q>Eyemro8<=XEl zbIJOQR+E*>`}m2AcoYkZd3D)H`u;uiO_WV&bc&DI{oBW57wqHU{w<@G0p+K3qRz&s zMzkv~j{b`%?L{HccyQZaREwXAK#Fb&Q`4%CT z4~$Ds@RBWl7Z<4|-3wH%lVe{6O?9IOwo3lz%JE{JOUdf{GP0eE8S_Y+Ft%c>x(v!g zEZmE+zPQS5qU);=()WyjNr6CKb{vz}ugm zP@qjO!Vnm1suG8Du{Vg^hH{mzNhMVsHu~b!N4EaQ+zE@)1zmmBWOwu(PNp)nXwM!y zouU%v+S`RUxz_QDKbnR^F03RjZx;ZNK8+s zH^5ms^#p;m7VNr)^f20 zO>r-`hCCkKg({|!+_z#kS<4HgYYzmv1)Sv?ei)qPxiIx%CDgXztiw9x{{0E*{1K*` zNtyI-h`LoLaQb6s6ILFvI*FfCHY99Cg-5cAuQu5ZzqNQ)gJ+Gu9$WY52(^U zDB#e-&Xujys$nX72#Zz*xK9l?cuNiBy0pIp1fFU&X^MS1Q9Lu;5(hcRC0@ZnLep?w zlrkZ7y6xQgjQR~^^s4MdQj%nseURXIqdC7X1n0n)?Q_&pc#JCoYkw4#$4p9LCz#Tp zpP64v2Hqs@PSz|+dbocdVLta$m-%#5dEu|d;{>kWiygLQk?BeBw= z0<}4r(6wQo`y>l+7gX|aI}QsGo-|<7OE5jT{%A4~!zFqNT*qqa5m6o}ltZ8mNz8wz54mJZm473V~I}6Ygs3OMoWr>UjsP-aq*o zzEm9Z#N!l8O;>0~%`oe`^(^crmvenocU1Ot$%~+xEI23g)OnF8QIosWaMJA}qZs9h z$jeig=bPq6Qf+1!SEQOw@>Lxwdf#Ga7{vNT{8#g`VgzseW>!FxTWbui(>2Joab2f+ zBN+TqQUMdYsHQQK`(xYOyikoagG;cr%Z&%+XO6qMV0#wI4gn03!ryr-r$JRZg@;N z#WRH5(?B%ZhH)n35IE=Y@~Qf*D+8LWFVW z5|Z}vZq(CtV|J7>;7Gk$HN>b)Ov8p(#>dIkyCCA)UJ=6>@pV7Nqu~(bmk!>n^dEP+ zN~R9f76j3}*Xzj~>|qF>c2Nr#y-kbY5VUB8l9g!0lswySBv*>Ai(`aBSF71SJ&dyC z=D8@jB~9D+lP|{^$Fb`U05l^Q9K-IfCu%r-^7Tl5p7wki{w^LWQGt;N06%g~0RD@_%quw9z9&jnSd z`p!PM?89ENEJIVeWbw~rmh_kV^W8Bn6Ne5dugxwLjMM1X%^QE*+fd;YzFP*Z1S{~a z6b0#;YEn-bwMW+ooF+rV==LrW?KdZu$?W!llLxyWyEIkY0e_In8?Dyh<)#xhtISdg z^9OpcSNjOx`;5@Bd>Pks4%4L9E0a3@hq80*(FE$&^i#I0x~j{zZQHilW!u$d+qP}n zwr$&(J|~%zO!8(j^Kt)ywX@f?@9U=VeVYN{+mKnVzV-bnnk}K_0fnFB?!Kux#n**0 z+PjrHXCIEMiS%(z^q;v=5A0ez>T3G{6u81ZFj=~cf|b1Ni6gQ^T*m(^@lgVn(K}(v zSUWju+-%_Z^sn-exO(z%R1-7~M(dI(^s#MzxxE?2fZfe`qvVt;u5{hT*y^MnHS*R2 zn{Z_3MToVr9bLZ7@y@-+J$X8{sSHsI%79m>;I8(f3p`j-+KaSO-w~%CKizla<5F4$ zdTGuL*_%BY@2{X#)yy-s?YBY`FFz%*{SoA;-@Fe@z|ASo>-w~O9-#@r_>2B%Hu5A& zA1=7!@5s-H;|<70zyV*AJbf2(0g|lpgJ@S4v5(VQ!9sUccDZ|H#V;0IIAr8xhLp6S z{HB+=jXfJdE;IK?0Lv?5T{DoM{9rS$EaU+<#gQX=wCR>D3cWoA^SVIM!ZMCyps!Y0h`u z2(g>|fgw85Y{t2n4oJfW-caCdeCIHN5d#{|um~c<^meg1giA5A^VRF&ZXXEsmz~T0 z4y^zE?W#mCS?TdZ##dhxN*hIPcS_xJRY;q%O5>Yz?s=$z(y4rYAi8#DL;ZGK#Gs(= zv+Q1JC(2i0qx7p%f<+8@#0}|E-hvH&ZrYPAMIOdz(mTH0){tt0Q39??(Udf9MK7>r zTG-3LMNJK|jieSk(b!*(bhMm(qnEyVWO}zSRtx>bdao~{(||{~Lh^y_`FDWs?Jy1I zkB)i24&NVA+@~QSk}St1p%(N(ac`au7DB<|doV-ll$k__gVlH4OUt>zx4@-nYkcU+ z&~W6bQcTVE>sa3PBO+1-v=qEB$c?}rQ2U+*m~B790n2(gk5zQ#YU-p*A1D_ zxx0r~O?;D_P{sYe>x)8`XFU9hH~1GUte*#v|+9<>YIyWE@ykb>ylldu)b)Dpxu%rN zOS9GyDp-O}m_YNUp=f26Ef!zAS+Y+7%ZX44g@9n)%otIZ325aB?0ca>A~cXhD1+LJEFC2!S&d4?18%$rQpa$}VwRNu{$~CsYdGMaS#6 z8E@Oj7tvwy?yhBR%d57R%pFL!knXrzLR4!AC6R*KetmrLU%7=w#sp9R|3N?eSn}U& zEezNZeqU&$2dqJD2D^U}FMoi^+xqa;wWWUt4DC71lKT~N0Rw)4_>q|ODc0j7@}q*r zzhQ;CB!H0%aqr6e!6W8|iT2SOZ%Y0_w`FTBK>5XX{EtcI@bCesiHJxZJFs&@1Kawp z2*~~5K`%gs_DR=;5CKGuJpWpgzSUrO-N~qzMO1|c7Zy+;1q}WEu#Ied3IgQVm!b3_ z2YNTT_2ql%`T;tS$j>3aV!?5yjYO@j9FaYTMy;lb0u+{xIU_os_b^}17 znCk!@bc}NZ^$!Go$lH}QKrjET@A{X@R|OLGQwN5jZH#C;zx=jcB2h0;v>(u;a+AM0 zT_qwQAmAHV5D|m98h0Pap9tTDz4s=)@nx*hZF7ZYW27(>>{5Aq~aZ6+n6wK8*#GL#G ztS@NvJB*{h7626+Sy^_ ze7wIOobbr#$T5R%zahRqd_)#+%u7qLAioVhb2hs?|Iqo>)Uxxdi)v$%sVV&SOKc?W z{n^p^9{91n?kRXjeAV*=`C5<%Ir0M^{mk>@>gX|d`z(U)?!g{FczprYVU``I2kh{T zw}4CdUE1sI{@8x~(7yGIeXFJXq}=~_3YA|&4&E^D+^5Q-t++2Nji+|t7ioc zI{n}O0m;jl1ZREuR<8S=226FxX`FC!vCRIUzJ31K*Bo~20_c|jfu}un&k{b)_YX=t zCPX__X}l=^ACJA=a{k<(@jYp?n@GHI5Me)Z=3i>Sz4ng~?73T`J~~v8_yK_hn+!eq#y{s)H`m9( z4O_NAyTjjI-&gh+lQ5=otXx6ODKI|jXq%s1ig80qZYH6B?Aurfr}L?_fhU;0CRZdf z*oCYopR#EhFW>pgzb7kZ=P3S#_iJ`Sx+=Nqap?+6PYmyr+j)03(55dw>}U5NJD@~% z?7ZlbFz?cywK{>YnyS$9&}{S97BxbZOI9`C&L19BC)0~2e*vJ}?4<|d`U9dACe63{ zW9oNXnTUIY6LzCSmV1(w#B5vptbVBx~Xi*wbL*^0;9@N6Vq;sV=HkT_^F0b3>o@ z{0O-}B?B_vnSwGl5GK&lj}9Q>l;{w=yaWJk!(-qg{ZG)V0gT57S1$q_GzlEYqGkY_kuf9C-4j z%vq`3o5Me=n===up(p>I%9DyMvAjR2(;?o**`x-XkY)MBRR6*u7elDPyU-4lmP9h! zs!No2OR}meN+`Be(R>0XdULSf(oW{|Dm*F@9&I3qGI{f~O}|uhr%=HdcwEO^(98f^ z%@9dyJ`!KPvHNIi0(0M?UYA%w)c+8M#AOMOqL6aA&L1CC<=F~nbSPo>APJ>QU=!?4 zq%QOKG89Q7yOaj?G8DxYNob|x`ZUkoM{`75TA_vy5$d!Y+hFAEk`_#*Kizw3Mh=C# zr~-4wy}B~Vc&2!}*z-o5%kkH7a**cw6q^@B*{nyd>G^f;lea3UktRF0ycH4pB{=Iq zCY~t}*)^=8QJPp}om7QV*LD+(eYuIfzN2TI{FXMX1%GLBHIUt%H+9b!K4b^a}cH z?`W?{84=EGQ~p?mq9UwpVyiqopWLejArs++I&V_K-1UggC&E+900-9yXd(uRDNwVa`!;$_-O-3z8HrCjnRhy|}Wx!ONKR@6{$pMTKN zzxcC!OWi+|5^a>yFPxy@z7=46{;ueGgDHIt z+xi?@m~LuMVdvRymm9*pAXMZ+v*DB zwum=zXsWQ}%-@sDZQA-p>+h_nTjA&N^=R!6TI-NkyCmm>+E1gx zLfIi!rWn<1C~yp+X}k|fJqOhziaFzQ%kKqVDCWpmjjkf{$A241INV!MuGB?KZ$rO?JV`OsF&Mzm**t0FWj}gq`T5g6hlnb`|m|xxnGasXY z#FQkVE-*F_uW+DsE>9$7bH0n+((1G+%G-~ejy|Y}dJMmXzDN@J{4F(eC&;1jDnGCG zHpKWcNRP>@7`v_&8~YlZu-h;PbEKB=fT&h}r0 zLmOVv&{vJ)_BKuT%fA|E_^)oyJ%mQcEeb(YK%WANrsQtyO?U>(hg!h7MuX}g448iT zvA;x13AQ1~&|6l~Si;Cme9hVLc74+O8!5{bkh3B|R`Y<#_G6iqqH?)4L;fk|TL&4q ze9#3p&lCqMZ8hEkVHfRf4AyzQxLK7({&Jaxy2&4JJ%{rsiP!N*YRMFz5|r^5Y{fkT z*6w@YuJxk4JN&pmX)$p}#zKGn_a9WT&$_D0OP$>7Er9$#8Dq&K5gOP znK`(g#YlMUV5zZHL zq8O>On8NC!6oh=oRoz!)ZR$=dY&;*II*r;O3)4w*-Q|hgpN+8i@;$ZngH;eZDpzL- zzz4wTA1&wBg$*w-ZL&7ub#bh{5rTi(F)`MXQ6dvmF3H9w0?!4ns+F5lJxUHc*kd4# zp#=*ipR~%GYsi@$(xP{D$T*;tjCV~jG;61?a*d);Of)cFIVL>t5hy!v{{FJs=H$pI zw=9FeiK*&%(HYm&Nj%assj7)uQJ;TvDEExX?c8@J+}dEHc(4G^`ohwC2&hQ!rzyra zZQ85$(NwZ6jAm1okmQ&aK%f=ut{rPaxU+jp(S?Uk_=BqP%u}*cau#YZUWEOp12=uv zyoSXncV5w9R-|8Z8C9ITL46iawMATPY6!(~U&6qfe)k|Id2S=+d(Cz%SfMMc;GI?U zyJBY~^Es4C)bSW^sD+kPac1&e-S)#9FV!AT;=`)Fr%{61I+)ffE0I;oz8W_)m{n{- z;udwyLxv1HKaId$F(b^qa%; z$_EPXD|YS68}>0ads9^Eg>0g8BsP4pNmH>y5;r=a_jZsDF`fmiw&NKsM`ay!nzgT> z5m>=CAX;z(8_XtmWg&R(CR7P$FNopzi`*+#fV@Fo1ajYk%I%+WO7=$e13)=K zB3C7A+S8gGz_e>prWe0DgX~M#E$9qfaXB0EZ(-o_#^17rSJA|FyLvL&4n@tfM7(;L z;EJ<(bgtbh?1062R-&rQIj*o%3j^o8zat63eksqqI!}gG_;H9X@`Ej0Rn&pDJ&_EM~$_TIkoHu^UB4!-!R z{$mxSN{eHR;47OG-4K>+zeV^*gJLuFM&&jRdurixRMmGTa(dz0c;<}Y;a0%1k64{V z;jU`k!i1z@-Y>i&Q!;5dB*)XW?tWja(|Tc0;tP^|JIkM^J}qCo*x5uO+C$(GlO^c$ zDs?!ltFxgsD{R-2w{cZ$e7(#u_#m-yQ8DkZIulf9-_k9gwyqdKhW`+eFFfH$>+M0? zO;8FgHs5UPy1cR7Y{LW;3z=8vEvgX@76wGcQDm)E7{V-ROtXg9YqzM9+okyKi$`(g z#YrfeygssGWZEJX!%2X*7stIbkKwnHbJ<9H>LO9f&!b1p5%Guic?t@_p&(9xn-?DY zSf4y{ABt>{*zcZxW)pXe99<$SV$E{RYZcbl_O-lvc$9Rz-!T>dfbKpD>&a8*FASAs z;^Rb`FzjS)z#TC0iRPn&zuUo#^lgDysWu2|_J^|o+woFs=7FUDiFNbx@=`&bf7)L+ z+>8h~o+gxE)n;Vh_$xHAQ7=&|bm_9OWUDPHqDcKa7DniBxSbYaH)yKIXwN1I7=0e( z(%xae0gDB=0lao{6#7vnZB_yL%w3L3E~+)cO8ou%-nMChR>fjeu9LkE77adW5@dvP zpe57Crpr!7h)T-VO|6xS^R+;4@S0K6uEK~*%Fomw>5+-)Z0TL{Wo2o5ZgnHjgKkmqA?p&qrQ()Z`>zltRFl^|g5R<=oVQXAu3!m! zl7Tnf);M?P*zkJZR^)-g>7`YNIJ3H)Muf?Nu6Ssiz%ZNC;3ib`(V^BSr@O!bR~aqClx4{WQc_6mjhagqcFN0 zjyFm|!7xzF{VFE#a152=8Qgf1$%Y~K)(XtJW>nV#d?5XDN%dMf2f~@kDp;xVyWd27 zyY~kEMqXG|?vk=u(fnf3R0zZ9`Csn{s3N72Y&N8?RJ&G0=p zQ9GKXG0{2K=xWleIpeXf;<;;^rVhVH~fkgmrY3M>qRvz;m=U3~&7C zWQv@3oRwYT9h>4yXEru;_v=o$T^ zw{A{S<$mH|g?2MPMg4{WRyo#JzY>1Nv9<}u+4{=?c_R@YvwN4>i2aa6eM5};7EAxa zpCyo+{B-d%P3M!6Qi!qhoHR_bsV8XW8eSh7Zbug9z3nI+x@9GmYYQAMevLq9N&&8H ziTOUb;uv*m<72g0Bt$nhm-l8(A0pY&pZzM`o*?VPj0ot5Jc{z;>j~ z*3C(;$bq9-gDiDJp7%WaOQ#?E)q`d>YjPR+-Ki4(#mceM61340H-_E>8;xs1St$5$ z$GjV|7+;}r0IM-u!SdmRlZ+x|CrE%ZQ^InwbmvXn6H})5$vSb8g!e5_pHISQQ*jtW zq){`!Y44P)czKZ-&$1}d!5EmI2JtsUqj0$K@E_w`CV-VD6zid=>@FF!P`b93xb_=x z)cp9t-P)#q&cK~{4yK-zulCV>zWxXD*dG_^*x4+y)jT3IKc9IF+jI;k-vRIJkxCgK z)3dDFBawh9@!!tO$jZgM-vPo3n$6jK9B`j5Ml-I3^vnW(cnlM<{X3B{v( z&nj~Vxs9`J21Ty!82*(Lw8_aRA!?x{*kP$UXeOStkXlL+V|(`BjU-Ru3W~Pke&sV91jhIu@3=C%oy%* z1u$l{Ul=QMW<8#gcWeHX;i{$G0tZD+N3r)p*2t6^ugaM_S8h37wFl1iOV-W&OO#gH z^O_tT2j;*7(FQqN<3fMx*q-`F85oC;Pn4pIowq|P`QM>{{O-6MB>=GgMf)rM%NUE{Zh;FzSRX5l|FbxM4DFzdS(brR@e z&#FM{G>YJQz6_Yk95)gl{s`Zw$NmvSkh!r3iQOYOK6-o1B6Igeh0Uu>%ReHv&s(-Q zo{?0+svthJ{rY-4hL-F8mcI0~uviij!}Ff19X}{3@??l;#G@_Tl=+Bo{G$sxJZ;YO z7Hvl%X>1t6goUS3>NwKfUBXlR@QxWA7+WrwVuZL*qv8SbkO{ce;F^Qvmo%kFLopoS zDp+zzdCg@OaIu$S=!*I@N|60>h6-tX)$cS&$Ie5W?kyiTWzg8vLuULv#SPWCh^U5W znOnE^&n9G-{I4I_(PjxIHQ-0hgG@z9X4qmpF#nP^*3OY{j8j4RJ4WiOMP0hVQjG11XpT8rZ6O5@Pa0V|MWp=c6i#-(gIhNy z^cd2?(pQ__QEN67%D&RH)7S>z(ubyBRvqTj30^Md=_MCO(gQ<*w@SmnZP)QDZDZc( z>dE$WpK4CsM!<1&9>uysbaQ3BTY&G=DvI-&S6ppe=~NYdcGRT-Z94V{%uH@QGEU{m zYC1E5@$(pMWd7E15y-b1%1#nBr)1LNiXYD6ZsJ+#6 zo}qdwN75ca;)Bjhu?!O;xmaAiCUNnK3LmrNy+e@~chw6CCzmQWH9MAO{NW$=@zb^l zg%8zC$_E?!DFNFHXrYHwueoZ8rRgGN^M-U9B_`&T+Ef)~6LXf8+1DtQ5pTXuV}FJA zB8ae<;Md=0$zd&4p6uE=~zc1tc9_3M4O?bJW$^ zo+aUQClW+410(FZmlmLst1C|L#F(Xa_aU5vRTV?=0%4p;(WMkjrXMe+4^(|ptH`#p z={5n*I9d2rONq8_K^-;JwqN>Z1JsIR^|cXOJGayKFi1$d+T88G1(0rV&JVE6+;Y&k zQhC;kbsZG3R;M1EV{Ud=le&&MNS73z5xcRL5w}-8aUqvgr50WLJ1k9;k=!@ZCMySw z8|rOll7oCVhAt8m!gLat9o4@EBU@X9&9M#Cd25{RaqNaU6XZXpTWkDc^KXB5|DB}Y zmc0(NNosij={Ikf?+g+HYYKCSj(L2d_mD01-cD5+wi2l`u;U*!ZdqMQxZhMOIA9@= zb$73I>&|ArzGiVo_?%kd!r{t)aW*wMrV=u845&)LI(tIBhUmmqqfvO5zH;o)$x9Oj zgPo$A#U{l1DFh*z)P%ozouk8E{ZmcyjJ;6^0;VVkt0UHor^GsrjA5Zib ztfQ!l#4cf&Qz^D$hD+esz8a(ii(BKC{ty(>?74=c&6Z-CEwZC^IHy*duk zFGkKUB_<{(G)e{`*dg%Sgw${$giyx-vUT+bI#xumkGxR^K2mU`jA$2t#wG?32LOd2%xb{Mmtlzv!2T;}QJp zk`BC}ZoTp@0Gv`P)HC=d@K0daSpb*75B>p(A;{@kpZ3qHGZHH~0zEP`KNhwDBKam- z)*g6EFd@+CF+j(J#jltN^_xunO0HL^SFZuc&rRTm;zjMbMv(sX#+V*7z|H}DpiAFQ z%MWf633^sp{y@Y%9~ZdS?n2LBUrY^@6Yml}m?NNS7O2M-9-Lg<5~TN!pKqUI5Wc}Q zxtgw8>H%G7ub#=QQgVpa1Yu@ou3aM4T+PQ=-#-_w$E9vBUxu?E5%(^yFOHSIon?j| ze&trCzuX=@I$LS|rXIl`lsP_DEpll5!549Lb$L{PGY~%yflII6(Nkw;UQbr8o+&dh zAD&qtQ!h9i@Hs?-fBsLXmv-OvKdI{(_|wDNPPA`MC_la*3v2+ex`4HTUA}L5!IXRk zpV{Mm9KD<$6kfU~K47P2$9H>j_OV{H7pLnR>ZeODH#sjdKOXZ1Z}8`CY!sgxh?g6m z05C&DfCw0j@d*vR2l@QgIpza-#rm|Z_=WMja`gILRtno90Kom~^TXZVVc-182OH6g z-vj;Z_zMm^WkT+EfOnp84|OLni!l4s0`MvM+;RJ<82^cQ|M4aOV-p+Mv5DUK{uzLC z3E=SfLh~!G$AYGTaR$}IzWsq`@%xUe=Ul`*K7QQMH9^IoK`?KnN#Ezj7trPH<8w)^ z0G>p#r~(rbxco*uyHUyYWbfaVrwOFGTtSD(8X9@g<83_0hd-?er}8l9(UET~{oYc; zg%?o&QN-(sr3XX`2XuwL&JrJ>BLlzs%`!Fxdwd_W0Y+iOa%U+3%%XgLaKI9emQ`MW zTol;r4$C`0OHe%$ejvY|`mamUbtwZ@zGE_lkrXW9V_@)|Y>vvs(solN?-pH2L z&3o$YQZ7ZvA>Oa`5m~sOr2W>2$RcNoEB)~0la@UrrEXYlh#fI*nGL3ZU-3!x3K;iW z6^vrs9AD^q8`gP~%a9%$3UP^M6~-Y@>(Z{&GIr9qo%E^ize(o_YBieUT$lFS%|HL3 z?}C!QijK!m`h_P=TdWO*vl<%ch{9o{#Sh03$tZ3;Cgw!z8i)++Pn)D0p3-)z%IwdB zAD?_MdbBHn%5ImsB*UZxE6pl+RMZ;7kv`8WkQkRPwi(t=Kzb*5XQ2AV(C$!VdIN2g zSs)LNj$*EejGTay8#m%528$Sy60+QsMlLh6M#0@Ryo5D;K0fz*PLVQrbwHJ+6haLH zzl8Nla^P?127y4)V9|`spjs}Ymn3Y80lW5zR;DSmcZoIr{lLMlUxNvrqZN~EVPU2# zNM_ww*w4Zu(I+x>ZJG!?9F8<|K3Oae^==9}$zyQOx$L${9iQhRBP&VjI&rgVW%!c3 zb8|&u`Xf1v!vBn%W50rr)A9)v{8>C!-#%0n|1NQ;UvjHu136T`ROz^!U#C*_DOSJi zC%ri!;5dlh*OY!0=f5(@5RTR^<)tTGGv%+>?Zd60pX*zYycYx558*pD^Ye<0MBUq3 zO{ue(3+pR?)KK?DCy&u^mP)CQXgNlLlLfr>a?}6XDfkW~P_&oM{PwwW`88`yD0Ay* zl-K3j&@wTP@gQVj(pmVq-nYA^ZE=(3Fmq%nC|#kPjfW{YGiI(UkANNj7p7>`xb40` z;sk`=M;5KG)}lBbSC?aCPd5utdDHMmMt+P|tZ2WYX^9D-bQZy_D3& zU%R3t^9ZXpih;oRGPox~Q^s7yczTkvwWoYu^X+pCENdv9WHE5<#x3Kz+4~Q4uQQbF2S3~=RJr*{X6ciqB4D+bSxYQ)#grNEjO=YP}%4hF`NobP<~}d z+GVq&K2mML;cNJM&(K_by;MyQVFRav?ca`SVuw#t0Qe0gv`}G0uM@E0UHVR&Q_G69`}d%mm@l4Wy)2<`&YMd>~1Yl@l z=IH_0Ys6g}a(wK2!)#vr?KFbB`Oudh=pV1kNV30vivc5;w3hl|6xX)0(>GF84V>C6 z52-Y$qru5ORbzij1ChAkx#D+zCEs~IS=8f{q7X-Ep7Sni-l;bM;+DeTDPCZub(=}+Gn#U@T{|2>4K{SD zggmL0f@1=Y@Iq~w$gZ5&k!l@r2g@2`;V(SoVd^0x7cZ|;s1bbisddN8ar=H_R>8x_ z&DpLhNa(t{V<5jYF19i`Z4>JpDK#`x;uuK(O3@7e^CqeOBuu-7(!Cmf$XkxL(%{(q z+U<=7os{e`aRDD9fjX1$ro=R|fK_7TNf<48BesQOIDNVE+<4v$%K+^msJ@v4CiZG9 zBP;(>=|8jOi_yPNHGr+o^f5}M|JsWDieRiq`_nrYzvJ4KFeZ!d?t75*9-C)Z_K66i z5innd*vHxd8~DLRS3q?ddmu#UZBjT*WJq&BxFvFw%5XNS#U3T89FmE|tBWwQT&_Fk z)7GW)LEco!5Xa!1e|q)0e6hP&MHCs<%HQQ~5w5sml_}-|i9S4u{=WM`#n+oiKYymX z{CYu*X~jxdDz)KFTTJom`@+4?5O%Ba$&&;%yZxLDEd1{>Y+Fg+)n?p+OpD&K*22T^ zJ;B1#levlMRbv-lvp&x+j*Zn3dhEQ70Uz6<*Ge`-%FxzFZY~ES7OmbecX{Y64@^qo zOWjO3A|Ggk179@rbqSR@N&+uq3`XGw?3&t{U-XvVu2fy^!u}?YWBUX=-8p&+i4ojS zSq8y{$aEE*cC~%TFqiWiO(IWPF|f6nN)gBHadmXDoPR;qE8a~Ty-q2eQz_OEhYm_+ z+DYU~j+59dwQkM(>0f|5+yf--d@NAQS`CnSJX_zFc6QzL<5O{!dNn%}8mR?o(MA6< zHbK^m_S_+ugLO|uOJY!la5{gUL^&KV??L& zY27&L^;tpz#Ujk0YyFZWPA2FWzf@2XgyjBJb)df4v8vFNpFhrWSfEv=$_ z-OmR;h5*zm)pK#XADu357R}_{9A9aL83t2brI!bRso*+0K5m!l3w4|z+ zPv%c6Qu*^4z`=9T;>ao4ysq4fIX+)#b!eY|j1o;0phW~MplSt*+Yc3CO}msNMX+T4 z`h+W2{kxMIJWJ?&%^-1-sAHQNC!dn~9XP{wFEpmUD)-(zO5|#pQ|HYbG{&L}<`cz> z`Egu7Y8>64bGRlK$&y@E8q`isL0?qjvncGxN!?Al~Hz8E~w=Qxy+lOKl8*b1rV zqP2TU%{#$jI8Z)^c&->GLj1J*))RdKC zqhJZr(Um(*kPx?t0yv<%6Rh(Zc9!ZZA(X0ycLP&S<;|tcD;r%CHjDr@i_A{9x$%IN!P9`MNW8$+0R)GGMa+OULbS zw;*!3EoP;{%o0ScC#GBJCvX6J^>KZ6KfF=Wy^>OI;Z3DmUJJf8lvvv|rRwCNARn*I zlxvt8Mmfg}4`j0jSl29WPZ_jK6lUI>V^1r}$h*)qgX;9T@4%SQsY*h_-dx^8!y_0c z>w$gnyXXVMx@V^EZ99Kv^Osy8NJ~8F8G+5veo~)ZpUh&|acn9f-&3Aiq;Z-Q6vXvs z{~VEr0QaUnDSXH;?X;Q{g=1&PtUKEe7$H*rA4$>L)H!FnT(|RmPPOIig z>>ZVgxyam!OMojb+k)syl7e$WtapZ(XzZSsh_6W)+% zc?nz#DDcmf@h?tS5i$z2N)(-+EGtCbKivYaKklEw>xGso<%sM!X+OUSa=yH03n7~O2Aj>hd4?0Eb1cJV8guB}{IA$W> zA@!3tn6|}(Wbr&j+#NxRPF)EFu-%(|?#>UG5*FXNRgScG=qh!{#VBQ5@;Rr(BnV50 zBv#Vt{g`x_nRTFu9T6UpsSMEeMMdm#->Cl{+0hhepKj<}cSj4E%!E$NRL~*kG!5GQ z!KJM?9FYjYDu+C`#w_aT7@3~H=r=xmm;(E4v!l&R%H@eSwk_G?&_RFs7t>I!Eig|) zmgfLfyyV(oTuCml%?@1YHd@VEj}hW8LCH=ZsVOZv%T#RY>PRBKXh2pYBNT(KVzHyk zlMwqai+YyFHD>NYabn75l6SJ3w=7^&Sy&6(h)4Q$ysLPTsU<_cF65l)>RL}cV2v6 ze+kC}9&33J7<-rFkmu$}5zIBwJ0(49{$k0L`Ve4eu5b@NM-LDzb>Hj$ zl?4;sL-KiT;I_ej)pb3vvY!HHOV~9|Z!C@c6Eo>cw09}MT6CkR6CXUw6E5Vt&kNwg zQQ7}MDay5@tWJx_TxxX&#;@bM9WEEk2T|v@MTmba8BA!vIl%A|>Tsi4$P{8W(tutMw2&8%eKyCX&}rW5cl(8!>4- zO1m_9b`EL(8}&@YIS)?7$Ko>9sjuCWI)Fce=r~z?j$Z+7r~PAgS;ySX<1Ir{cgp#I z;hB{AOuny*6v7Y_cxd;vt0Tz~Ru<9UL7aMmGyeC+t3yn%L;T{sM98Gwi!Pdo_w#gk z(pTa=pzxtFmm93T;NGOcKZDdUMV6R#m0_D*%=^>w+o~zFQNLpwrV92XJd*k;u0_sy zoie`T7R36Q@b07)D*;*4kpDuWs!KZxmuRT(uWm~SPqFp&0jg?Lpd&5H$624!M7{bF zteR&NFuhi!uD)5=Hr$>g4OG|&lv&Cjvsomlwh?8#QlBz+~j+yPMkO=Ve`g0rFhf3Zl%X4F*b#HJZ4a<(n zCFr>qNrvJ=;*DYFtbB1Nq6H0`i2DxC&eXkJeZe8$+zpCY$>=~0D{r6$m6Q+Bpycg$ zV>PLNpEsB`*lGm5NsJ7e8IfBwp7{#ZEMB~2$UWC zBg*v3a#!oq*D@E|U3F4XhtP64Uka$$`WsgaqFM}p{!QC4hM8JT^!oFNP9GaXQO-<{ zTcHe|eByMIU!TP@wXiDb_RC&Y0bWJpr6`N~1nOK1RZKn;WG`S7TQOF^hYyRL%mh9W z!VBDtAe(tYSuo~o6?DFjy{0t*sUVzRd_l~i6%m~XnNT;5UTbxH9F$bM?ZJDLtcNK_ zE1M+rgJ)nPp4Bh1%C&L89mZ37xmt3mjit4>(FZM&VH=;J>)^>&*ADr(Few-=_0ya( ziW`r6*UxpLMHcdlU=BES`kiAac5qf~G$}5^K*)+YDsn3LLn#RYnJ=En_=Q5W;s4~HF zCHaqF&s@JUYYX5*KKRaawiySSsZGRYaqVF_Aep81{mF1L4DFQCUbxM5U>%t-D-vdS9lnQ;UOb2*%;yC{`zRvC^P_Rig63=c7!Xo1yn>@hG( zTEzXTqwZpN1}#G@6UqOSK=|YjNRxTE$9kbofLWf!uT~F0zvbh%kEkRGwGEQy>5lIP zqHUWhvS%6vlPH#;VgqkxpAJx&26j_}kuC`!>yFkC)=7gY+{Z5{kAFtxKP-6=v*wg^ ziu}E6V3!3#g$lC9fG0Q?7M!M}-+_&vrv;#ASN6fDV_{*@+kNSb-MG?fCYnt<+Kfi7fLivM7IgTojQ6@Sookae#d$w{8mRGh zSgsE~I1^@p-r|zn9gJCNn$i33V|{KCE%o042$aUA0gRX0-#xIQBm2!sDM^8Caw{p~Ud z#9@g&exsh5CJyz2jHp2$aH3*HY(9|TwJ4SD_NiLpN>UkkKcMr`66kYN+A49-G#-6* z^zR0RDTg8J!CGGEqW#^7rlL~V$i7=)3Y9LH>4A55+G(4^y& zJ(%r~A^Ai@n*UbA$;Y(L$O>z3-fH=~l!0+#)o={8z1WGrWSd0T4fMdl+fbdEs##@@ zj2BIm%m=uS?JzzCqCeyzW3a_TSt+{lY8pEXhR=1UlU#qAnc`p7M~P>1(v+nQ{9S?J zp)(Ejw3#Mj&bWMHXB=luCocxG{BKPjroilNOex%vu)96ZwV)R_#VAia)V3Cq1?6a~ zPNd6+bShDEkQ7-PZW;tl9MBwF!ztsZj*e2zO58Tq?lqzgdUDh>J!% zjs@rF)W5&}`318JwgUtyAt7=5B?&>^COAh=4+%62W{{Oz-5RZrh^-$8I*_Y=F-~_rBVvuiyKm~qKQ!P?gzo*lOHYsL-)GWFgfGtwSi#mWECZPp6F}+A#ZPllNZ$1l!*%6If_ z{6h^Y^eGAM-zTny3b_X-#14$DZ%59rCnE;92s#4sLyXPw$7cr*n}Bfl)3=M|q1|1X z767o22mv4=ZV|X)G2ny@7=SS_KFNgpa!l+>ybypC1lrpLkb$XXWXySG&M` z<(9$xABA7PHQ0L*5kqqD@vq4RP(UZAaLUWx$w18rKSqurhkytD6!-TH`2mY?fG1!s zsBdc9%cy{F2k0;61H{*l{8(~75O~lGJ_0!)!X@PW=ZA(k!b1SKJ$cCKfnfI#h=pu@;oIvurYbF~Hq9^o zUa|cL&M2sex&Ymu{fYn|3I++k*w|8benCOt-JcuA9}d5szMpzbKYd?Th|iLI(taSQ z*!L(PS2y2-+gBl&ZNB(6kXKg-9^&W;dB6?dVheaUP+x1xf0MJK{~~7%|4q)i2v}U% zKT|SZQht8y{%RZ8-S7diQ~ryd)z6CT5Bk5}$TOYVQd|fU(7UeuJX;tFu)C8JVB4df zpd+IJ!oQmb=q>2!$Oi$zU|e6M^E(B-PksZ4@*u?E&kw_WCP4l_M+0T>mjN9r^nQE| z0sF#FH{CCY`oxDN?}0;uK={m)BajIpIz zUez&KpZj8tuAj$hQ=TeH1QsYT*VH>byI{sUKHI)ZK5DS@E)j_v4nl=327#YsI|;Cg zve4p|u7n#9(DRUW2&q&iz*4SK(WJ`Y{HStIL&KSZz_1Dum%0TIP5Q=oLU3wpi^Gcq zw2IoWEYl;kk%jvVW0JHA(qy~PD-9PQx_!JK9-VE=M|HDZT$|iXFlZLw@Mxwh`vQ4M z+h0pGr!YFT#tp?Ni^lBP(x7z)Y-CW@C8TrY4!eAQ?~v_ppO%&&3s>XaHjj1T;-*p1 z?#3uj8XO+|A-zm5?WxLEPTogaZxCCtsz)jr*83{ZGjZwVl*jZIXiL>k9v*zKj^)xJ z<2r`d^NIA?9jONRhYn~!&!xuiX4c}w6^6mvy(g3=V6 ztNHyAkM*&cV-ma7mRrsz11q33OqO6pU@6FBs=vu;4UMZ@%L|3ZTXpjG-Zp7G*8P2R zW}YY7J*EdC9{$!KT=J@UK+=b>659FSwwql?@#Xqz)o7^T<`07A06^?;v!#K1bRiZbspJP$=bV(||41|Z9$i)Y^dq59EybUd9#f9^}8MDzkf}47x z-e3P0TjvlfTF|A@YumPM`(4|%ZQHhO+qP}neAjlrzmx9tpp%nSawavX8dUb$`&*%f zee`kpxRf&~ktfM9?doG0HPD1vR7o+Zny)NUxDYkF#T`XapS%5B*PF(Wk z-?6)3kr40JpOUba4zEyDRhE;s>+r3! zrF}at{ltdH2k=g6K980HH?qp1ABr7zyNx!cMD$Ge|8j!jQ<L7vw+BWL*{hy)$xug zj`OK-XwyRe{dudu4yn}xWqX(yD|z>p>G&4m<9CIQy%QMxytmLQh^AeIneKL-q~&Rn zodNUa%F+%VIUdwbI%-zQcHGtQnJdQiod$e=Ghf;)8o_J!CWaputy~$5qN&)X`glWx z;X5EzT*-CD^uK~Qy#-}Sb#R~b*%fizt15-BJ0EGD+5B|2`18ckXLgx6&cpWe;s5MR z!@Us_F(;H>mVoH&Vu%^-{slDA)5JIIKuYg@v6Q&wXyYlXd|;6Hd~@$Kn+gQrl%HK^ z;Dqgy6iL)AP&h;*$<#g1a%0>4gEq=)W$W578AkY7@amB0cfe5*-Nx0dv?xL=unXLP zp7c3-ROQYyDO0+z2>;j~wv|d-!lqG}^}V>D>KNqUcRmo^M;=XL^t$uif?k(F3$*%A zW}J!gNaGa}fQPn(E@-&dJytFCVru%$))iktv^tv;^>@@TE*B31qVg1en;uhe&c?H? zttSGLBt4_!-Ic@qBf5G)*sOUpu%k^xjWv+DZJtWarhnzJv*w>qQCM6&-3b6?09k#CoUJg1v_1bcfod%ictz4b!ne#KH0JQx+^0hk>(xa`lty-yoyuN zvA%BA&<^97aP%T6Le_85d0b>uq9PMz*)HUwX@Hqc0|ZLdyRMHNm4)2-8r;Sb+_8S~ z1Mj8Dk&QH?@vzEu_GD`5Cn0S98C5_VCVZc;HaOi(yGJEGZUobAz=*-)#BcOjd32@qO106af%;Iq3{=phQBi zTPCAoWQ;NxIZYkXZJGtA>t_4DmC?)PxUDS)ct8KOi7^h(kK^gMcbD!eHAPaU7Ct|H zagoN=qh#taZulrkR=7TyM@D+8v?TftFBRLgPA7V2D~8i#!I>nr<`WL{c z;h;MA0{nb!Gp?N1@pgtJm&r(d{^l?N7YV=qDMRh+AC89k0anyn>?rm;;g6TTksDh} zuFa%;;-tE>Iz+I@lFm65Z6k`7!W5Yz3nxrPLKVh}+ z5_XoiOPT2``eSm$xSu6@7?_Q_utoFpP6^2bXNV<}?ng8|6!0_*r93jc8(T$qFLUmQ z9eM%|Nb09E*rBBK%~)2r52y6R&JWQfF8G8m-drOmkGb?X+}hT(e$!6se2WrRnMsyR z*w>A^g{hFg^N3G2k!|CxBQmX5z2SXvmPLilHC~D{l3zk3Ta;~|Q9%)#{&vbZfEi!> z>$l529_^THJjO?)v*(MSG1Ew(e))}(Sn=7dyi_-on;UeABl5)YA z-gPrBA=qX?{zagmZ}MYh4m4a*@}=VBanR9m5puGP2S)><^zlyC`P&i9t;5a*1}0P}~pQy^d00n-r|QG=EE+9DF;q zUeKu0@go^uWuR}PrQutJ(N;Th$S*Y5OJ#pJa_~?Gnr~;bxuw3MPetccZGqBc_dFIML7IX1{)e>;VF=O6XvC9=QkYSKA7nz4h0uSTvVd@Nh@uh zUkNjOte&$}v3ud|&=UB$Uyh!tmZ4K{ihq~U5+Vk+WCLgAI#5nV^|R}0_smF*e#!*m z#QM0b!WJ|)BM&4kVNV>gJ@a%`Xf^XS?HCg{M=Jtxdc7e;M&3)CD^bOKeH4LPGAoJ* zmhkf*t#0kGb;aFSus)2(w>mQ^eic77&`(acIMhiwT$)5JLY?%J=2M7ydWAf2l0W8 zG`N%g(#rkopqrwB=vzw)96XyC%RJMpz`q|kqRC5pjUsk%A)5Qp)k(dc0TspE%m$ycKH&HRsNew^di9ucxL5!)nQa-6#H=|)h zU_Z*^6x(#c86r2^VqR4=sIx8=B_pjkrW2C$g2vBGE7AnInl0yX65^qJ*+A8m4C)LL z!ApiyeVP6JfOp(zwcPtshi$w0d{wQ@emui{;#$gcxrX?(*`@c$P~0zjs~{kNf}R#0 zcF^#LVYlSRe8u={XDBK%A=%)TPBAI%LEV)v0e#%!d$c{k9HzOx{7PY;^{&uor`uT| zPD|kfGmlQ*k(J^Q@{bI^#6EinWX;+JH~pXW-XM4-J8kE-cKJCVcm~}Eqo&;N!55}$ zSD1)B(kedp&Lqu}NA%A`EnA|bN@|Hx$es%#r^xi#4nzlh2+`y9p`Lx4EyQU0I&^Q+ zo<3$<<*lP}ju!MV34zSw30Vc`3b}@h@y)qbIVmJtu*O?4-hOPj)9OGDGb7Z2sstCH zuG7b~tE5OfJ}&ZddB*l?nPp9oPp8w_l(^W~LA9%}xhyE-9n6v8TXW+1W?)_>wM4nS z99WB9yLTb($x}nuqkzj-x#c1(DYG!SUTDh%U5#Av8L`k{BjfnB&UY^gW1qB2-cg7^ z_C|S%!QQ}zaaA{mh)hv(!J)U~fSq|v&_P=fcO8`vbRw{w#QPbzHjb1#q0B1;Zer-k z3nnMl4JjM^07U|0XEJtd6N6mG>A@jVM|Z9vO_{eL5fj+BX&gF9#MvftpN)-O^6q1f zE`ODUMf|ze4?=cB;8si+sBCUx2QPNg%3EzQex|5n&vPdb%SHxTZ`q({ZQ4%Xz>jkx2yKdZmaNr8+#xhvI(qs+2$S_` zps`%znA=nt>pF}f1r>w~0%V&hU$l9*AAqhRz`C}EL)t@TRkelYAw70fN zcy=4_lAMyG>4zrl?9O5nHdS)ERP^1IvblBiq&p zNyfoj_x(?tF8*+fi?s_^?<+Z?GmHy6T+qN4GMSKNXDf~HG!{iV%U`bidvYin6@qwk zdGWaf6VVwzV}04geb1-zj2mz?RyXIaMqdT*R_8`$Gx3NN7}gDC=Vgl8iH6_gZaLmm zTcO|5x^-au5T~SW4zDi!G&NRte)H^MxNQhGz1Kd78Slg#`y$!!qJ>%zWp za(n@AUOmemMPF280JVuXwiKJkGeUDPhi_HsU z?4pWLoVxQaXb<(s9fsaLUM1*J#p1B1n3lQe+La*gn@h1mN=~;Ti%of^BL<&N(BIIK3h#&gw zU@z~9&*O5+*7I4ZSCrJ5GZ%5|=*{GKo51@IX;m|8+`&Ft52PzYbDD9XMtLqnO-gHy zMkd9UgSWoA;C`Zm*WZB0zqkfsAuZ47=Q$G>y$}-sjpS{)tZtC^u|09bo)Wu7u$v^h z#C}%^`IK&RWuyZS>av%oyP;z-M*!GOT(2$R2Y6941P?Rj7+ch-AQDOX4*zC+7M^F< zIvUZ{L8}mzuc8i8$4C>EJA6#W5)!Jol|&$hRgq$$6hvM zdiqH^=(}r+Wy#v7XE^QEb<@%7>-U8}g4AwXs0)G_vD6>%*g{Q^;eaJ*ZI zk#_k^&*{e@jVwWTxamc z$rM~{L1w+ktY71+y50s0u@5Z~{jsh_a?R@VlQj&_OK}m#SpEARI9)T3a-!AtI@R;Z z*n3YLfqCs>=`2b;US(b?etSVLKjQUMji~u2Ed;;xP*-(JkJG3dGWT&6A;37>Ri3VV z)myw&+pLJ`S@s&SA6nnZV8x6}?h4g2*{}%n&M{nl_rO&!c+v-yKH8OrRuTNhByMh| z=b<=@t3DfpQj*+&(5HFOi#M};S+xiaBY@-t6H09#^r7!xH*u-Z@Kp%|VWU=uWsK_; zebE~F(q;^c#u!x4``(TxrNBkL)Yl(6zO~0}b~3#_wP2AJGb#6y@IrOIV9O!UbZw;~ zA)jvF>#rDNv-vfLi2dLMRq^K0v!dG?9a(>*8Fr^#a_tN>XX0 zJz!5g4Lc(=FNi+}+Mi@p_Cv*s9A-@U$%f}z`s&A{sW2^l zuEq~o*!Cl%vm=-yS1;#kh<_MayOY>gOMlbhS!N#}0ToOMkvOI)Xoq zjnm-k$w|ht?{ZU=lO_A(rl?ZGQntUpA${YGqRhx*L!N%l+A!-nC&QcCWwz4UFLZfzwt??#-T2VC25Pal@S6oRBD11j^)#O5OgcVx&r+cA zBP&BKe7P_?v#st}w(Sy^Cy;T45nU{9$bGs*+LfZE;xj)1?OXM-5zU2kckj;`W}O)T zUQ`LQ3|eqD;&|c`P6kxyN)1Uw*m~iuGEV5lew-*;A-7#X9+eN7hGlilRuM{tNnW|kll?=AbeKkEGufeB`{><#cbCrf4sIn5ehH>kj50y9GKckLYE#Yg&E?ep78rjPKSOh>WI@E6xX!^9QLn9&;s z^W*N2$tp&=k>5{HZ42@tlACY&=r@;M_DUOxwppJK><5{rGv1&)6*ggW9LEQTJ>y=f zG4E40)H4ih-Q+DQ&DDnWPiGQsaZ>Nh_!ycN^)UMp*ze9ptKogC+5=GQd>BwS1*cKp>!KSQAe9W3SQpmq^~b0Nbo7^YjFX(rP^u5P&ECm4Nyjf-Ai7n z+H)ovdzyTM>w2#;s&zUkmkQLPrw{ucTJKv^+l1RS@9r!hgJWXtx>M(WH=JqO>*GzP zjc10m7g_=%S6O=BR$n@ZaE`2*{b%{@o;(Oq)8<4U=y^6LQRJzGz9UQM!Ol)@sZw>T zQTu0J`*c$3L|r55cfWl@x>XRMEi-OO$)hMK3#YW+jSC0oj!SFT=DR3{TDn_gRjypu zH~JVxX*e{5Jq7kkf!X98$Cer+64B>$Q%RK?o0WUsfRs$18@`SadWQ120nNID@s)pi zVe$9>frqRN{|`K5XZl}S$V9-%#=^+>KPd74!b3(jPIl)1riW1Uq88T9CXNL3qSgk^ zCc-90cEv&C3=9nH9}tTfnykD&u{=Mr zxGOt6KavccZ)*u8&*lQazyz3%fq`Kl4mkJ%mn)lkibe+jWi;uB4QR<0N|xH1Dht5s zh3&;IWdscnmz9;}pVdU2lSGZb!!I#eS_*&;t>m9k5<@AVt}CddD2pRNNLL1hz}~{_ z!qf~%(f$vTU;!J`#K>G{%TNNEzQ_V({ZarJd2u68`58EtezF5_vn!FO`T1vXZfpS= zi>QE%9G@ry6b?R74Fde(M)r>$=D%>Io7Mgm&ced>_^RT@@}K$@XAAu$#{7iw8mNG*3PpIf9!G-zmb5Ck!ZUV3W9V7}{D20A=8%1+Ip!MDAbR6H$?bD=@x03PNysU}$M(X!)>b{zpp+d+yin>o+Fe znei(OUXc6I55xE^ZememdU0r3cwq4ae{u%K=BMCt&(&q=H+!xR>YMyCPto6Rc4c^X zcJ%QV?W-)qFRch&aY0@wzT_v5@vTj3d3JqwcySgd|L+5QQK&50uhGAs1M?63%ujk0 zzd4iuN54xZusYc^ya1ap&c9elp?8JV8xSVPv;o7hfa>LqQVDsK^JGirfKb8}ebigipt zbu&-9mc&|cTIuKbdPh9v`^Q~F2Q#2p_cwai5`4`Fn4?*PIkGZi2%_h;hutX%YMGxa zH{KLz-R#2WJN^|0TUb*8JEFT?#Uy4y z$Ysl|>IeQj=FPt~PnOJnI3jD%A-)jl)8ynb}oR^lWk8xdtq2aM+mk2|yq zBm&iRYVuNrXI>b)zDq0XMB&xE&eZ;7Y8R7$B;F*g^;?D{{IqmiwY53w6r|fhJjqHaBDiHk2I1;6(E`_W@A#Ag)?r|o}7E%R@#E>oNp!!)!&!hZ>e2hVzOFj zK^CV{tlf+$NsE4~gyeM!-WLWY4eEcKkKP_Rf$g;8MQcCZ{rypf?tGY_Oc&SAa;Mb7 z!}R}lHMs)59+?{VD&lcInSZ3vR9864h#4GnEg3T3ZCozaaFLIl>x}m%22<@(6EjzX z?e3y{C3)t*A#@IN=eW7SVE=;#iKb}wVQ|?ppF|IT30650QcMFEdK;c* zU#vszU$p`tez@TzR;&@QT~TX^dQOFJ9-J)X2lCm_qA=+%YZC^M9bfzp4kQh_ZmV;w z=ooxzc^1q9OXAiZlvbi-t1B$p4_|(;Y)r)|2vMLv_$0T##2XQW5$PaT^{M2fi`0Q8 z9BC7I)V4aOz&0XgUV z`;51Ta0noYX^j~2q)bt6#!0hKPacThAS?NA*;Ykmj-gwgi`uEf-MmkJ)%+Ot>8`D> zJ`PVYiUpbk;#(Ary-g1qhm+7m2AEvz(oh-w1sYblXC9owv_J?|h}$=@IupX~0~CMX z#}rgY^P7DPafw){vheD}5$;2NW{JHsPRuJF=ewyao=T#~fa}9m40=%{R;_qU5y61R z`Qg(!&bwt?<2g#mCinXB2b2igefyv(4iTw;^U0<7=h2Zp;o3Ag-sLDb0TVavxLO64 z-B~&RzQOUc4fG~`CW06Tz2Umdr65cnbw(MI>>rLr9WCh`8Fj4h<+s8LEeA`X=RAJQ z*|vmvmvvw5?3k&_VtzX=b_5FZNMTrle}6P`xNPwPYv#C%^}6S|v|2NB$urXBFcMqgG2RldJ#Cj#?`4Kz48aAY#B1J8ZxmLi0An8W zL;UB)r74{;^Qy?M0DXAeQ^4FanSm|LUTeol6uzg{J<>)3xRIhJQZn?YQ!!rqJ{gUZ z4FBW@UjDObS^{G*N&O}+V0ZXoi2qQ>sX@pSnz#N3$r_axS17oxwAt20x8+j7I6~p>C{OjT!Hl*#BR}aL`z|`? zY~CQM4uX9atUnYp)5DC+9YGll$HA$T0`XL5@try0VUBu^q~@5;#b`HDD6U7v8f1^i zpD=DVo}k)N!2L2)WX6TP4m&RmYx?pc#<#!ig)gt&98K>rcj|G(E6QbBilXA_(kh)h zAW@OIHdMFiD(G@ilK=xN_%= z`DI!I&gE46%+%un?*rwy34+1pj>FDzp<4K{lSa-eRN8Lc$4Nt08Y~EA`=Dt?~ zPb$W~t?7Etw8WbTGJ5zt@#{N2YZ28F6=YNaeJ^5eXf8F1R0MH2b5}KU2|jHyWHZ|5 zM#ZUHnS*R&0juCzT)Hq{8<+(kCdxZ1Ld1+>n~!?#q$Dn}#?imt10_^h$%?r!g3{-8 zwp|$&OLTNB8&u}|TmH^4%jX|uTP+Pss_M0Xm8)L&%7L1hec$$x?SsJU8H*kW5v&)5 zV6cq`7&t{Ez_aK^t|ezG5LuzD4_w^|WWEDIi|`>+@1RC*L;;;6%m5kMXV?f@ig);Y z?;0s@u?AY37}O_cU9ZhS2m=NZ#gm3Kn~USQ()hhI5y~ufg)t^_mf>VOo?uKwz}z7s z0NfE-Oe^Gwr6?az(Z>;C0`KzwKYMRtr!o~E4>$MX4z$|+$+If z4{s49q{eu0)yI7^BEiI?L)8AT#=|e#V8YE>t?Vi&RbDq% ztOz0Jvu=7x-bQ^?MX%$e9e*RrMt+&=L`dCBK_`@FfUFwaUk*3z?$GF~Qy ztotG`K2meIIZ(X7oU%A*s!Su4t+1}?R~fOk)v2F z3~3rwDr%(l(1dAtmAk5XXl0kc`#q3U7q40$%iPc=61`BE^Y`mLIBPZjSFJTKoV`r~ z;cj!&ckih1Fvi8HNpuO}#3$Qy^fX#D6phFVxcjd9Rt;RQ^H;6XkGYA(varV~Ny7=x z<~?FIz*hRnt*LxYo8&lF)_HVo2z<^s9j9T3F4TV$WfUq^0SqM@x6L^DV=-qF`ZApc z8+8NW=}emWo(6#lcEy;+aijPLNr;9{)p@;Db`rgbZCidAWv6mn^eGm*2}TgOcDPGQ zCPirpVt#YLfCGXFoVsw4`#Wk+m>_Zud|SZ&qol?er|k0^q7c!${SS(M^X;Q-b-R$W z8AMEb{7wPUk+m~X(=(0;7e-~WXHhtyI7wecf@o%9i1N`sjRr50>vZ|T%l#mCh}a)A zAFlX2(PAk&x2hB5Apx*BIkr4vrn?`$mD9+B1@1Ago|EGkguB&kR4_K)~ z0j&XpQ`3@&F-t{r%X2@4TwO@)Ud-lC3m$|O-LoymF*h`L`|IQtxW@@#Ap7ACSWlN0 z>LZ>?@<2^Byo?-cB$%5@jhpqQmOt*cKVV44uvtY#XkmWbk>4ndAve}=4{fvhx8b%?hJwv)@`{;DIqGgyB=k{!yQ3deN*~u= zmB3QC5Ez*t%`BZg#s!cvn?dHn7{m=!7?1~3^Aa>)rjSW<-HZ~kiF2o;_32(3moY!_ zxg<3=&x042-)?2%wjJQ#!(7&}ot(;#_U-9%nu3(=H5&s>U4wL$+Xyb64pLq8yVnBj ze>ZcP`P*L!C$AuBZZo^WTGVnI0lPFU^KL$@ZVoscTc#J27aqzI0BzpRng8_IyVKme6ENu_&*_Fl(!v z0Ab3I{!w#vShD2TYWjOM*}QTpAa;=YjnqQ*$;9L2Ad`a$QGwOXdcso-o@B8&zP)NO zZ;};|ENetOZg$+x%EP(gn+1R|b-0_stfTpN>%ln8Rm-`>cKU`H2x@9+ITjT4Ov~*G zvwKNw{KUN_fn4pef}%qSI1dQby-)8<_0s;rupv2&QMXpCRgu>>l1+tqt|a1tnxN&C zp5AZL$>MvcvzNn=;86kE4MN2#98h`sSol~|(5?mSEg<*Qa*jf?u=>5PPvHqiV`qBX zyoXQC5IxBZdHdcIKZ<=o(nGXHO7%6^AMjP*Jk@he=#ypa`frcS!!q5Xb9c(aTw|MW zfo({SP+ZlVIa6k++mY#| z7Q_K(1s2Vb!v)0yqmMZ0u6G(i+dcm`Fk~o=jkD7@+3I1%7$&V_Bl19J)y2HmGy@iS z0=)1Dm1^e71bk@r0Dd$I?xzSyfHH|Dq0xyo>4N-2u#mgwJ51Gc6k4BN3G*sPpc%NK z7ERWP@joI7h6!uH)y>0}O;(p9jYvHAf}L#SOgJrnWCtNM_N`l^5_#(UdRrFHqky>&`S&qll3)~%d+ieD^n0i zlsu$eB}VX}BzjN~p~8wDQ#o(G1<$v7VU6Dk?}E8~g(l%pmacy#bCA(WxJ6pPcUv zREuFve7j4F>+@7ZS6JjAdp0quZ(-X`_zaDIldtV4G*GRF_1@%WI1UD&$@I-X(GTXz zj-w8=1W>!RVN|qBZj!PDaU4b)@bZ3lWA)B}S<(Ai2zBCZdz~KYjnuzt+J6gai z2`3}il}3`P8QbAJf;p`p)hBK+DN4;uHIH_~Q=6mHz#9@7owQT=&olCL6bdD_g6|(= zv0zTV;9HGm*0$kXaWg-=?|`GXI4DY1ORMY&y25NbrjzUAltE+D`B29g$u&Sh0g+`X zLgd5JFM)@~wd;-fp(6W8Ms=u%VG~<7n~M# zvmK=reaU0*-A(pSiMZu?w7jIlz&#mq-B`fwfUIDN!6%Y?k|SBxG>S;)_6NM&1Rn1} z3g0tmsK+Xq7{Dbn6I86o6pbMFy+(%1e|i08paTo9<+9X>&oLA8=2kGc6H&Q8ugaEb zmdV`(GL3_7+HrC#XLD4Bm$gyt(w+{Y={ zr@-cFIsL7Hyk=|AZ{xEK4kS1<^J;9Cd2cTb+S_kZ=OdtW^cyoJTS0545 zk!a|GFy6@Xc15xsoX+aZ5VJVwx2URbPOfJ|Bt~miGlrRhsuFnACBqC~#B6ElWlsEP z7EF{^f;)B0cXJ;RzBPt@b(6d>6|D4rvk=B_<(gzJ1IQT+#uHfyM)T<>W7{X>(_ODH za{vmmwXw%=`tId#aw3W8Q@amk)Q#lPb=3u>dL+b62(&;4`B1XZ0EGhgJ3gkT7Xa!d$bP%%KR zML;#7_L$slhaNH;aDE%dU%JjPf=7R;5Z!y$JrrpN+a#Ccph&eYA}|VG-PWouxJSSr z46dZ;eAJLPH?Wl0fW;&X#f;f`Oln~=PFiz{JNq_I$d3h4A0WefPxdL~OVK4}dHf(^ z-%R5&%>cS?Uq-y7Mg3a7O%UL?g~LuTJN76yhwt)aL5J&FBz*Lb7YQ!R+@P0&OgQbf z%$>~R$u%%Ry?X>BHITJZjOe#0NVp9jeMDDDhg`i z7{iH$LQ>HCKsO~BFh{^p=*;hi@_3i@D-R*1p|qSSQH|o!v>Pj!>G2zJm2|@;K`4Ui zK^d0Q(bBi^jQ26_6a5d?Tk^ksN_B`pKEK4!1}CcK;^_15~Q#K z^o1Io1ex->6Z@xaXcm()@n+}r5{bbOl;9WeraCaH;HugYpY!+U_w*FKLlkew~FzK8tM#L1@3 z8&;9Zw&!}idB6z#Oh!rQ??`HFxB4O`f53>$8`lxRktircuWP|N6QJvim6olayUxYJ zuVrB}D~!C^wkuA#{K(8y1jUIfR&23Je+uosV)hn`py4&y2f^jBJQEgb7J>Zzny2uA z1^FqHh~hXfP7n@TX(XZ|hd}&l6KJ&rnqZEYBvJIUYzWdCd%+gFSWOwme(?&dFB_vH z<0SdGIDK1(@N`$-*1H*>EF(;foxii!AE2^&gBJ^D`l+~e-g6N(M&A8ffdjLt_2)|O zl?*9FY**#ju$|2?&eA7@uR06Tp%4Y(!<7P9Y|um5fBW-Vc81*~kHX;npanG2Pd^WL9DL;F0V^Ta{4lf$U!`VZm9mfr% zMCac@OrYI!UA<(5>&VLbh^#8vFK#29qXitQNC;NCcJwM1#gK8DdiiyDOGzvth7GO% zS;TKqK{{lw@$XuO0%Lnk0}tf%JQ*C0XN3G@(0;i6R8c;U^+NNFwK=SOPeOuwAbWx} z_(Lx#r88|rJ`(Z-!F9gF@8wM+5_Rp9N^Ub;-=*J04lm)ow`oHR>rDWoJ>PrnhJZDO zo+m6)O%%>oSSy7fp(hzN^Qs_&3yCh{ zwb=*aHi&17a_E*@ zQw2aDfWrm)nQj|DIQAVzFg5e4BUhf$R4bAt$WJuJx=90CAgtwpi;-Zlt7-(1C5@=& ztpyul^vK`Ho8}XK&M&4-Qo5cjWtb2QDbE2&<-!3MBFhjq`bSmPM`XcE|)+vN>m!ZY{6}o9< zyf|`A4Ql5htLm2Zgblvc0t;1~N084z)Zp_b=P=G|E?%pEC)G^}0m;Uo1Y8Y#=ecuL z(8|%eOvaStQw!phevjj$e3yl#VH5i^iW$8mg|bg1Bb^%FEfMRYx8GmTzb_gUeR2B1 zg<>6C*`+9E3`%f~v~M8m%g7#Z2;@MyA-Vxpg*IcIBV>XY7T2N1jXjVV!15tF4dzD` zB%3a|qz6hsGYKt8KyBAA-WwyvtiB)J=i4o#)irL$p<8zo1A!4v$X zYmL4-dGwWe-R~Qz2+Jc(e$*cmSrYU9HT>4i*OUA7T~o=*y_cz1NkleF_N_9bcwDFEtSyi-hZPek*e7_cMCUfDZcb6T)`>oQ)SjIy^<2U}YG%oUa=H?`Y zB9OYjQyG3em9_of@02#GKAgpi_yRKl$(r>SJAz~P2K{rSYVfirhy9NfRE4)R>sIVK zEC@e0U#?1Qmt5#mR``5WtO8ZWK|byjIu^%%iQzE6WaLDS zWdEAq$xHDGjlc*!zl4hUqEBSykB)*ASQBsVC+(US<+@rSF-8B#OZjAM3!QIULkmsG| z=;;D*8o3Mj>85N7+-F^^^`s6Z_tHc*eR52jU-8A?l;m&s1bcDjXI)#T6nRB3*yMiV z14w!S&*67fRh@p`r686L?y#x;qYmCRGP2O;wE)^3th?_0$VF_{F?J#pVqNT5f*r|9 zH-waOm7;fm%3Y^`?vp3SobZ{L0Pvwq?0V%}_S=?R&W@$0(z>_T7dpA#{Mt1cg%LId zf4-selPMly8G*=evxA=%_K_{Sk1Kiq*g4A%o^Q6g6zI1n+~n)R3GN~v!CpuaeRnB; z+PP<=J&-EGZO+u3(gBGLV#q{Cn?&el-EDq-X3w{%GDLkGHShe&PD% zzz({eKbK5y0_r$ddA+r>ASkPq-mk|c7l_TraltiZ{lJAjZnEM(e;4j>I!3TXZa<$+ zK&uCn{%*$^)r~g&_GlO(ZrECK`y{c4EET}EFkLgGeN><;j~z`z_r25%FQV1l49PMo_a{+t|e!Zb$BWvP9KZqDJ)@5`UAWT~LG! zwaJDcL)%)61=7Esox}(~I`;t)9=w!cu*rtXuyDymkC8j4z&p47M5q|;XGVU5YKj+D zZdf^IHg68mxK`b!H5zifj}o_EhxNMrfdEFpykDbW)2&+eN=ZgnhHW}!RC6&1*c`(a z%la_Q*UbF|q>4Xg+_VlPodWx(V#4q?Gpm(vqS`5?ABszX2_|l?!*7o@X&3h1amCZx zK2(*ip*61~!vk;ZtKrN&;MgMmxuI=%k+`!zzi_1LoNF>X0g18*`25}V#c~pv_cX=C zD)yWcNRSSTNh;q#r?p;MEWwqQ#gjo$!P;^fct0?TJbF}{aR4oh?GB0gxZB)YR!=D5 z;$AXBo-N5jqXvPkCIx;Lk#j(%Anu8M)jL4$gy04Dc0V-2^VaU)Ss|`}x+j(o>#3jA zIcoSiJ8Lp`5T0YaUW;K#&CVaL=N(_i8HaCml{*Ey{vaC*6J0bY2^|9(V ztg6)I_|%C7w{*;aEPh6n6M2K*(?zX%0w=%y^{$LeQdElv+BG{gNzbrCoUS znS)8TMwa01rRp9?a(hUdA*y1n1OvL1Y3cw6a6U)8TdmQ&TJycN0Mtn(q}#2rpp9T=%3GKfF;JBNT2$MKsi>-bRsc+xu7MZ>g?N z3V7neV|;+ZzX%Ax@?qkL@+;`RXPmrbkTQiSr_lxWO}vKNw@QTzMxqj&ek za|?0KfIE}+Db=W%l6u#oeK>bKQs$T6PI?j6eu@^1A2VG+K0LV~OPb$W% zc?OwffpXRI!P^b`tUa{mxN zM=-M7YKnBe;b;wkE0z*-8sf#8Cnu+_I2F-D#)9@3irzH~bSrhJ#z!xm6+rGdN=sy$ z<@}+yRB#xRB(|M5V&AtJOZlSo7A-dCA?auZfBEE@1XZ|-N75of{80-IE* zq8tlV*!_?D;eGq>@-?^AifR>cc--Mr_rvdt{9kWoZX9nP770xj+6QEZ+RVRTviAYz zz74S_w)`36>M&fFmHfp+%^RBQv3yWFBDlns#-c5A(Z>3a)&)FVF4u5_j9c|}DG2UQRP zkL{5+F89U#c&%V0+bV>#Gqw9optm;u(4A-KWLXZ;NI>4odi}N~7blhSHpt3cbYy#5`baCXO@~&3` zzfec+SUrIty&>EjhQsqZybUR5{B=Z^Y0vsJ46%mzGiHd&(Z=f; zCpa2eK%%098+uGR?{{B~k|%s`4-;*6>Ni^>5Aj&PeLkFxv3ZAzqD`cnk`s)LF8aC2 z#<~Qt?AmikNRC4k=w^dMXy55d?BjFN@Gyp${`SM$VTlSnkq#5>NcgX3oamM}A%k*20 znxcHg!UBZQNprmI`|6FLF7~+Cyyd1u0MiUmc`jBIS-?N;KvO|c$M|DhZ2(jGx^jSq zth0L^-n^J*y`L62_v!ZboigTPBVq329s%9Q?0? z*r~EYeC37rflv%ab7qbLivEOHQQY=%VPalYg3MzjEa4biI9%cB%e#`Uj}t{T_#`C1 zNZ*YP?k-888b(>wA4|hlURu!NnSK}m%XJH)LShrPkZdmY$&dil7ii3_53n{PSgp+) zT64d5&z$fg6Fv#SfqmN9+9C?TeoHqycHfjK9*KR}r4qrZI7xti@IugI}jHi{jastnnETOSQkPJoxMY44t{;~yFnZ(z5XI4$j$Zrnh z9o9-do5gx4v?(n^2)ec?WUA>wn-uYC!Jo@ z;$Z@fHZJZi{=2krzo^dVY|Lk~JA-NFEyg7MNabK~UQP?%s}`e=89rb#1dYs;8cfm^ zGbL#nEB^11w~dXTGLNcq%&Ea<-)}JkQOXD%Ws*hVs%2+*JX`gn_VyhAtrt^dd_T+z zh9Ih`jg->9&8;k6Ks;8kU_sz`lRQ6u5I=2(m?2XFZ&_>#AuTmpwR+JM)$Y4|3y?++ z;*OHA6}-YmSWMN3WwEN)dDx4+UG;zQt-%2q2TumFPkFRKZz3PMty1xq>P^A)sZs%8 z!F=MinbV1o|7KBf%3ri3Fktpvn>FH%u1)apfZ`_EAxVegviD8IuhsWIlO+YHTm_s3 zH^=nEPgc`caXG{!dlsw^$kv57$Li`}+VR*WKVy{{65NM2GG&+1NqJs`e z;sOChhrBLL+EToe)Y5dvz4rsh{>cO<39969okPK-l&4Sw@y?5w`OMpM84$;}{nsp| z@Zk0~{8o>eMaFREu{IH%gTBW3l9B?C#YS5rE_6_sS<+}n-Ald6#4HEOGfr(%vHE8#amlr{zfp zt!;@8_TemgyV!<*utpzDTA!eF-|UXcR}ruD{mHrYGXA80XjZ*bp`YQcp`uuObV&_K z5@!R4P(cRQT+?0)OtQ70zi|v-4}wekMDFl`@VWK%oR37e!u4MlUPV=>%i4h|S`hgF zDE^e{2i)IP8poUv_{UekNl}g>)nD9n%yUg}h983MOYL)=T-e;Le|O!`Ffr+&^=0 zcY2R7P{wJZl9or+s+ax;@P9%gusu(>W)7Q#Tq8B;`SVO= zVdz3>cG~ify#^5h)aj#r@iS@_(2g0LPJh}6y>^=GQ9BhWs!MTC&dD$jl54(ze`EaV zJQ!&L!0clP%;Mnp?y~hb8yD7fc1HhtaYNYKY{qp^VS=7$c<4!Tc~zuXpDqpLou87f zYZIENw3XIJb0Zx(2U2SR?LMNvUD!?2CV$hj^bJcm_dN2}Gx&um4Wv_XMr=#O6UvE& zF1e^brE!DWTw-`IJ5-V-9c{OgO%8J$IrjVSO%Pjm>htKjlt$BGF(~qC#RVt`Veaqk z?bX<5(et_lqo&oAn*uqp-yzZSrJNPY)fZLE zFvez%VNG$V`PvIZu;O)jeR@MO*P&ZKuBh*)EMcNw5g^w^Pie}??EYq}Vilzr)9vd& z7 zB4&3_c8`juoZ~srus^Twk^mUMnF~NsbES`XwoS3NjM$*&6KD!{F~u|!;CAD5H%1wP z;at6qF0)zU3Z)41pQLo0jhNYO1j3goV1#S>taS{9F}m!g1fQTYS8SnD0S!r>+-wu8 zK&=-UY9>%Hv-)+!_Hv+qyvWOqqpgwqR5uA-Vb*9>Pf_4J}qFPU%v-rX>o4;r;~Anu^YDO+-foS<<~5SRPqgVBaLg zRLu$C{ii{rWq?PG=i0|IafhR(jw##uRZjVuUkFLL?-DCyW*+zv*>Hlu5;4I3&}a!f z_KF%$Q3>gq-la7Xko)}at1_N0NN!0B)SpjKD1tcpp!+mSBcN9=)g|)*BoYZ_I0Dpr zb{O|3EELHJ?z18YbuI4n`n1|Fcy;yv{jYY^)kExkRGxZ9I0U^spF6>4dUe)(S^D0i zC}YjAUo&7S{uB0V&}<%E%s>Y5TtL0)$R!2QuUO;P zZ56lL^|%*{betVatHf*ax2}%s%9PPES-Fkbb75<=j@P~?^+)A zyn2^3`H%a9@cFk`8Vi5*4JRKm-i;G;-Gqp_k&_e`!JVpd5a?jP~F`GT#CVNja{aaXv> zm;T1G!_igKLct6BDMypkeG}!TjOhZ&KWB%+SAHjoCW;OG+YstwaBpgYHBM{*9ACf7o2vy zutNI;qRXF;xe_7u?Tf*b7aGD$8E_p~y|epWZ|ubK^A4mFYzbd&A8OXGn~lsC@>wSO zFaFWFmI}}_=2?hG_zVUy&eFR?CQuS$Qg7h6YDha|%ZKSY(Wi`0#>6zJ@39h@F2Xu} zw@2nOx|gbn0NW98q&!scDnhl6{yGA1tVwU71Mt8_pZ~4^Ry!CE>!}$HVNda1)IV?F zxLlsKAbP&03k5(BkYHl{`p>uQ?WH}jFSS#gsFq?_eV5npV<3U5hG-Cq265bm$F_fNs! zbvml~6|rh3kf>5x<`Dr*2(Br5zD^WiGN9eC+KKPLa~}U%*UIlWsShgtCY*43RlapG8QYR}C4`{{UuhBRE#m}F8Xl1aDzF=hlNNQP{ z#N`w>1qJ4aOr6sPWov`lLegM&p|kQkNk}}|dTZGhLdfoKW6dUxME4D1`8sX8D{o$7~)%nD{;`yPHuFJ>~X2!sH$cu*yLU(csdgRT42p{n2@^r%+H1( zM2EA39LMv#`jp0TOhFlQ#Y;-__V431l*{~cHJNf}2*b3pJgdn{2#MSK0YoL_KMaZu zeQD8rUKvY+f(n+`7l&mKX${(orc)kX`2KppTW!rf)W1estPitxp(EOdx4Hc|R~H-u zXD{Hd;_(Fv<~06MdnXiYPHkz&w{E55pGCf{F#t=pCMSjjq09ngqtO`Gjm8iQCtg%s zhZO-aXFZ<7WY;dd2zp(1#TD>5km%Se`eI4N5jEB%BAhxQj?p!qTz%p2v3#Gru@Pjw zd#2`pCA>ohV%pDf?q)QXXdH8|V;RLcx`)7{ii@OdWa&}dA`$g{xGJ}BIKPH0rD@$C z8naf84W%h{Sg#d%`&mh!^kdzkorHEV?~qP&9oW@&zY6e8wAa5Sd*w#jxoFm+ID+cQq1Fd zCxs9gR;FGvG~B?1Kp3_Vg0}kGZAe=}3AY&UKoq)cLBABW)@oW-30KY{s(I!@(>bi+ z+`cfpKn3FupJG@S>|#*qv}e})$n}Rcr}NgrpC~}EcjfE;>|d)0E;Tj?&uy#NV)^Su zJYHbVw&YY^$#{015I?twFPV!zBI<&pA6{qUtRK{b!(kP>ljT)ib(pmcj9Sf3&d%@sp6rRM&tG;;ilZnq%L zjs^7HqbbzEyzbSd^RedSi3pDVqfm4zHlk}NpHJy}mOH`!UA{}jKtKISPSmRC1K}w| zS0u^HG`>1_odOiKH6JNq(C5n=*8`3Ns?+38cV{bsyQt<=%9GApKKwnEj~mq>Cojkk zr%ARl*rlz3h;j<-T-}af{J*WtSX~wSAv!CQuN{fUi-H`kr z5tsN8E2GhnV!|OyIJM*ZFq^h*t})LQ2IOwU@sr66M7hldckxb)$&$S>Bg;*s$a3-NnJ5Co;%b|3kp%l^ZfX)055N@5oN^Wnq3%7_LWf)6BHc-xjdA@53_<+?WBwd)?~f zFt_im!(2Ov@@Ya=x0X~h}C$}0%EJ|rzXp0yIR=c?F`E#4^pmI>e^&cW4e zd7bf|W%6|j2whO&(FE&yCThy%7S6$-v|OSr3Z!gC%0UpcUDv8`6X6%tz-Q5O8b|tp z`&kKPs#6(yk0iYU7$?T3gH3k;HcKJrslh75Frww$!_ly&-9#*P;!`T;B(ipdWIsJ@ z5M(TLbXk3l=HEjRB%d#AJ*6XnmNzJqE8ukVtcd5V?FPL132>aB%kZ&l9fd%2LlUBN zFAPO8-=>PZItBfIqH)H<-4I zwLc|~o|rT(P%G6~wwM4>BYz&_PgdigHMR(?;#d`>5&l+abDhBfm&7 zfnuB;h$wwYgy~IMW_3LDjj3IXxOMAGIXjMxx0l#+OVGaeB}Xj})@vJ)SkAl!;%&Oa zh%poa1GWwtQb%lG&kZ60QDK>51qSH6&)^;gofFTHdZ;yP$)mOF-!?`a^!`cxDfozP z49jjH+&THoXjOLMk*tMrQkwqXK`rGhEV4R(UPy-0+X_V6LxrQPsso!pk@SF4F;yv` z7#UXwoZ!-#0tE}2A~d+pLkSEb?BHF}H%{y&rU>((rSns;|2M>f>Hm#bu(AH{H0l2X zv0!In{9gqA{|92xW$aM4vr3DzB{?p+*Z7}ak;{F#e!kvzQ)2v|WZ`ae#p8X~yr+Dp zuCMD)Hde!Vs?od}uZoVD*pXY?Touln5E&Plmxx_JL{~F8GBW{TP+}fPOpNRZg2k!5 zxeJtwSYG;0`m?&1R@TG(AfOu(8AL00H%r?D#bXN>t5|H7{+{`RNw z>>wippe&7S9>BP;y@VEbpx-6Ak+lK1{)f!w+W2RGi7zDgcMq)aTTF;LfMW3qzd5?8 zwL1X@QGn9e-01EI#szeIEfW~m24Ki-tsIci&AhORV)3cpk{DasI{ruh`$trg6Z^X; zJhA$X4~qGR+~k7P?gE}grN#9}+?kp9!msqhT?hC*|M6YD=wJ0`3HpAfBYR_0%lm6T z>>u{w&J9NDi3m&SnDwU_>|Z`=BYQ1FYdZ@_HTOqhb!_p;ALw6>8cXxnEc{pcxR(pW z@WZb^H?gs}gj+By@mEi3_`UX~FMan{7!rE3-Fu#qsR`ghBXbQv=0>LmfXFIaK3o-rY;6TZh)USAJNp(NjAcABFq&7JaCD8(R(nb!IySY$I^OUJV=rEsBG zU~1t{2=HcErC>%I1YH*cs`t7&AoK*}j#xM807C;c^>YI+-1_v2AG66g&z2EvVIv@R zO{CGXxz$uA^-et^&_C>E;=ab_T=5}bgDK?-+rrI?eN(0FT%yK(q5ie`t;>P zUb1!Bl)?FT>}txX`{sx)*=D-qtXZ#wJ2s4}Jv#%iGJ>``nUiD;##M>-=>^y6d;Mg? zcto5(PH^!QZ;xxaMokkGG6pr(x$|LDdNx@`n-wpomepN!mB?y0(rtq{Q(;O`zZmhJ zL7GMlyDae7p|m{Ie&&Qqi4{@Rb!9-Ww_?Dj1FoR)bHe^$csSX%s}j5(ldr-8Ms`)Q z$0=aRQrfr%wJpgAN?4nNE1zUWW+4D{PnXul$NcYDXp$XJKM`2&WH9k5tOn)_?^Zm} zv;_;w^&v<>J)%mXgy5f(8C3FB7oUsvk?y7wL<{KP=Yhb%0@tZ1!%T*c zW_1=*!>^3RvGb8e9Fv+;-1&-%QzN6b%xfHHuT4rqg=$ZP9U%cZ_cI-+^M{;-C4zlN z8J=%&g{RuWLw|^>(B&Ae8SUFy-#vA)GxmlBy{(x`f3?IBv`*(7ojY^_ZZh6m`$((l zOCsD?!?CND8=m(-27c4yZ3%edmD`G0%b<&?LEM$`_NVfZeOB-~n#g1(7lO=h$&mP= zS+0yqFy<>NWTu-d<8Gz8pX4@MPecqKDLTBDvvdyWuZ?bZtYR_nzadt+;i~X3DbeVg z3|h9s?KAVX$J|FZoYLZVNn#J`NF|HPKy>LZGQ43}iK+0@v6vJlV8mIDApPxhZo$EP~; zauT+d2Lz#Ak|Lmazl=A0w^B$r1D)#?4QIjswp$!hbp3mzl?PBi zTF}$n+ED&WPVG$V3;^7?F?h5J6eN5(9&51tO^@J4Bz3#52GYwxdnUGT+gt8NG zSpx+ZFf{OmN$cDh`^~`{*|gdi!d0cau2CQ&aSKrD#PK*T_xN*)DpvXkvE*_IDaPSV z;NeU|2wrdJXo89jkVje%w|gm(##41Y!7rh3J4!a)ajHBo;rwbv)#z?ksS(95KHT6J z^BuE*$}8$y9e}q$7^53es}Hgns43mCOwK8(64oeq1^^4yF{0sPKS^_-Ti&J0nmqN?O~( z{|wH_cHS*xpVhxa+v?GBs)KdOIp-#;#BE1>qQkp1jb#4&y|UgI6@0wrHqVMQxz6T| zNgJ{r{_7N>m_x8z?f7e2_ITf=M-gG38ul0`o`V0hEi!)E1lQNgxG!LUTvi09C!jr3 z{AU@VJkb^msSnB|KJHeP$lMZLVEx?`3hbmNu;64-==C{meSB~5*o8_-V<=$D_KZ7y zyKib|Hlir630of)Pq92?P-0zL`s1=`4$PMSFT4_g8r2(q5i;kqSX$aJRf!o>n>0)e z;Zo~LIFtp~sS)1B+(1mcP|aq{RKceyxfe@{K*X>_7y22LE^uiV8(9^PHzH)Jtd<+^ zdWDFwqEX}IxV~oRB>DG59$c*wY-r;eNOp!_EE)L5XS(zJ357SExKZ04Z(^onZ1c_w zIrkhU7H3^(>!Kn z<>aLdrL64$$zz718WV-JI6eYS>(pWu@7t?txh7MMvuYGxKbPnS~N@X(j34P9(_#YE& z8e{$(dB4k%@Q3fzDQH9hZsW#&pSrc_5%B0C49{Het zs4wgj;Ibh$3C+(@OWFe$*UqlD_mOd6C}t^d|Btqz>@7i3%P##eFSi-Au-iq1Ox_s- z1+dm8p696A><8eYRzw;0~`;{qQKpz3d)(^^#fQiY~ov|HC(dM@UYQ^G) z1jl%e{?|jPKyo0sJZZ85*O9aT?j8-nGvbY;>Ss9av2-NoW?HT_%z0^+PnYxA)HTkS zzKO?F=jUVwdiB(Ykn;yd4j$GOd!@tqhP#creB-7MM-zu~Swl~%!P;C#T7?_~wh-eg zW!!G9W(7JQg@*G#5dz$u>K)`29>d92th@)^g7QY|tMrs1xqCM)?L5~8R_YP-mWO~n z21)|x+gt53OK@A7yU2Z3Qq!$9k*wu1R3oL|{E3AeM;KEe!d~GLQRGGy^lfXP6J(!J z`}FGy7Xyw9G#islo-7-Df3w=ZHA6` z|H>Z1WI-Q1c9b$qt>?D*cfQPN@3FTTrH-s_=zkDG_Nq2B%Sry%kU=g)2MlH7o2FBPOg2pNY%vi98g#iwOFIlLcGDUnPVh;~p;X zK^1)CbAt6jV2WpFrcu|57hP1f%s({i^(Pd^O{_;cnem96nGjD7KOW~;;-MhOnLG;TfpZ*;z`CWdABPfY;Wl$jYP&QlTDc5q;)0;17ufwOHz z3uH@4TsGbd09<+sKIfiG_5=o54gyNVFzS@#`DZQ>(r{d~5$I{~hZ)DI+?CCyE(1Ah zH?U!l59H)SHh)pI`I>g=9V4NyE9Z4Yi;Z0B$Dk3iJZj6Ek=?CA>D<)d#HiXszz?V^ z_fy=pL$|^Fvh(lH(8E<8mEdhHvnuAne23xe-|H2_$SZwuUrT)ygs-ZLlGSTXo+4j< z9KGQ7fa!48z!iCY*sWmt$cpYa$jG57fU}htzZ!sER(x>CsX2svv7Hw6DC6k>Ws~$z z+51o9>M(Ad!#gfiFB2q!fLvfdv8gSSj__kAY6y`W_y&yL-{jlB>UP&W1sSv&D>Et@ z{Xy?223Z1_hW{v>mh^Q_L^1UiPH|Aw%~nehQddg%x?heLpqK7e#T2=g>bEvNF?NSW zqIV_ESvW6Ja^xwp&Z}8_wvw)Y1?kFWthy4jP5RU3wlJaal!}&qo20zZ}iQ=Z79 zb58v*V*+|h0F{7*|7yGuNy0Ml=GH%Nwd)|Uj$p*GG|C6QPXiWn+&@!}*`k~mkW`0b zA0NW+B9mr{+Tq))<0V$UhjrB0}F0eLHqDy>{KJ5~b*u~j~hRgLo72hNGB&5--jJXi{OF7#-_KDIvkuo3pU6k5Uu{B`6X2&|=hw9xO` zPQv7PyLY0A!K#+HL^GA_)n$GY_MXeP@5;`MASYk1ynHb0!b{2rW!}LCb!azrbG+Yn zN0)#8Z^p^4L;P?SP$~&Pa?(4>MyiFds85?XAuoTcdURLtSa8W`W#@70tQc+`0-JlRGDg|=_^OoT*Np5Y^M~0s zsA1!TUaQaM+0j)^RpsH@RjvCzyG_?!Mv9$u$_A+?KYagmz?TQgw)l!2>mbY;P{APS zLdlFX{<+!((Elzp#wE#Ro2=S^-d0dpwB#02d-M;qY;#oy8I>SHiXr&wnwqQM6>qw^cGZvnjzCVaz(7I#Pm-FQKf^#h%hfee!tDC#_-u<^yA7`8; z)kPuH_Oq$xzh$r4v5~Vz)0Bsg^aKf*n9&KW?YRSyP#j_HbV`5q0R`CR{%B7zBh$^N z6K5YKFuWqWh!hj?t?JZ|?{ysu^~~lGoFTvh-whVfEoiBq?O&VFf{dqOv7lF--Fm_u zgPdz}=J3p}|Am%fLQon~E$yD_P*||oD`e0>2lHfVay9u&^O*4_IyG9{=2ocwyM2D- z!0&^&)taiIQYFi|W1rJ$ljAaJer*LPH|L!}*7935%o+g$zT*ONUN}CLDTU4Ypx(ad z6aj}x_U&Aeybe#Z^VUD)AGP1-j$|~4qG17*G}B!4vNoQ)CMfk$?TDY*AGHXUcb(ty zg*A0O)iLfk&*c0FX=a$oXycw`c@V>K@spyh81jA1<(-Y00RdAQ;YNep8CUxhO4{^j z3DEQADMsas=A)t(nU`Q>_|Z4bTczG(A&E{7Mo--AhpeOkJXk{A%kdYZ-Z!9j zmZtV{XeO9ZMR+*l{!7Q^^>qHo-}U3_!YyXemb3a_LDL!v;ivpq0;{r7iyX6iHH@xg z&cc)mgRM$N`!|)To1=SrQ3e_f*&Q$rbtQ{yUv;r#*KB7@><74yjfu z??O22DTH`pQyh=R4W=|mTm+A4bC0QF<*QuQGvHV_Q>@VQw?yhix z?9!urWc<$NYp^k3FM+j3cr#XR6z#rTg{Dv3g3LpGfwpz#zGuHJ8eB(QA-DSXH4R`=KrHdz%2Rz1V>9Zv!zXrSwMeov9Z zOM=73Qce{3@UKn1zdkcR-(T-OnH1P2!}cj-4zw|PgUAdsGwhUIwDfn5Wzr8AvEIiM zq*RQNx}>^~1eW<&m}k(pza}Hf4?E!FvO8=!^z|r7kmXW#q^p&P7(MOw3S26|Cbvm# zmQhb2q@&7@A7upe>tM$O0H`RvG)Bu?Z`9;asUhI7pgb zY3&`LccV_lDmw9*jR+eDt)OVlepgzEe&&@tFiQAnaB`2jna(iG=p7I*hn&|{Gdebp?hR?Sp$%D(6l?{#BJwXB zyrn6{@b4o-!3jZXtWPeq%S)k|)EK*G&pQ(%LP1XEw_7h1(lGpri%=y-tlci7m!QcU z$Br*~Pd%wFdRAC0!)@Z39aA}O8OB2egb}W@8M)9boY8Qm@7v5acSkDpB-hO9KO^rm zelIqYCs#_5I|(P`eKgEM;-ggN7@A+_u^U|o`<_6O(YE7Yv4%(CA)Qz3s>sJ(ncO$+ z>br=vX(K>kaZeY&l2gi-uiJ0IY$f1uB-pw5VaTN<* zV-`d%rMy~ikA<%ipU+T^o{kwk=lD;oTl^Z4Ge0TM<4D3=%^>I7EJvyUgtMF{L+;m8 z(L%<3B_LJ+X?0p+&tLsy=^vE64z#*Y1pwyol~RA zfe|yEC{}@hpfPbj!@L7PCa$SAAVH@-e~e2q`C7#0|B7bEMO2|n|KI^gb)U!P$`XW@ zME!uxhi`1`uNU5WyWUwxDuHVmtr^vlvl1|C(87V+AjajP&Bdz$Dbx2>9|R&D$hPrw zFA%}rOnaG2&hsNOC}1$ZQwZ?w!-u);nUzB)osgZY1YFUytGIYkq~BxPZJy`^YAp=d z8%fIjD3=|P>6;ZeV}vM;?+90L9o1*)`!%7E%d4Dxq0+(!B^twd16|%}UeHdw;ZU}n~R3WIRFZECL{&{Pomyn*du23D# z53DH)(P49Xe_=@A4P_$|)y1_ZrLJ3$QS;tgGG*`jj_FS{zZlA0xRD*pz=#0#B5I^3 zDgl}1d|BSGi26bn?=&3C7TOwp(T5#0bj_AFNP(mfD?F(jZ@!pP!(lB?b|1weRIw89 z1^3pMuX>FwUiX&r!4+d~(tk>~Ct_<&QfD;@GL zi*V<|3HG3XXZ#m@(y@PDCOL#XX@MDQoM_79R+;`}y?`eH=Dr-=@a}fbNo4aKVS(@> z49>~tzBbu0-&V**-v(CPC1H63iVmMZtzZJSgpfTTX?dxUCq=buDKB7jfdNB>u@(=k z9y3T$S`vR~nwNAh%e<waOvywWcZGBpeHNn|!9_!iGFV=iHr$+?lW+UN~iEhwvLf=`oLg zfzMQ}OItO641+-c5`8@~@o(h&u?T01Lq?B_1`RP$p>opnXZM4ewEzK_-pVz3k{;B9 z0VDB5A9dm_=B36O+COp)RkbG&mC1=)R$Vp{A0?E)_}nW8e*x}V*-JLbWm*Y%NqXFaOVJo z3W6X%%{?6nF?8BU(EGq#6#`Z(ybzjeQ~I|x`m8w%sii0$xv8LB70pF)MAkscKyEUM zdE1`QVPAAo98Q_>F|46Rfk564OIOLbuIB!nT3MQIqkuUtW?P_7)=hMDcje!>3ON+9 zz@>`3dVzt>9$}&18ALV5VzAooVTR9pt=8(CQOeU>iM~LxJ;~?MCEy(F9pRE?IZIVn z=IIM*>^TV>ZdifVK{c{zb3t|Wk^84<7eC`K;E-9n#_6+Zi@u<~NyDAEgb@wefrLkQ z?ft@Q_aJFsx~Ex91*&wd;dJ5~zB_*uLHWcD5+2|KYdB95yCT{*c2N@FsK};z8u46D z{?AM%W!d5U2_Olc2+mYn98EdU*7E3MX4V4}y#z)Axbh?7kG#0$U6384 zC8o5Q?ENS^gh!XmouG0E*aQR8HytUaGRnNqkZ8gng zbCoU*wl9()!ol&7LrMJ$@{4x3f6LBoVfp@y$ZD0dYADQWCUBI(xGS(jIB!ef|AZ

Lx#b%}{a+(;NBZ&ACygQBRD>EcAm9)zwuu|>p% zRCXGN2Nd8#k2kdiz$KppH?2J;qu!1N4oTKE)-UG6ObXS|-N6g*61bP52Vp``(c|Fx zY`M9nf1NoI61qDjK0Eb&m9{`Sat*j3{<^$v5w9d2cD_0r*qNBM`T7a|Y%>(j|8Yms7MmV-Y zhn5?0pan@~znp^Or$qs}4(Twlxf+XMThIKB0@GcIyD>dsD_#gN;2J)g((1q3lCMYE zw_$?8-*%;Zx06wAb2pR+MZ*yUzUXQg*!9#m&QAx)v}tSHW_8lHs!X{lMKPqP;zN7< z&8PY2>+W4goW{m=+;ne_B&M)zP-6ZPLwMsz(S8(X!2@-_2k5*E9IG^KYtyak<(nUk z!_mf>g5lK!%n%$9mG5>uG#+CD6!MjL0c6!YJ|iaF3?G7JXQ&Zb)6JG&XO*}+6C=xo zBoSl!&TsS#>ZTi$w6zM>Cf(GC(UZoQte3U1i>9!4)Eyi!o0`1>NeS^PTiC}Jkn<0H zY6$zmIl@!w+#_`k#U>^Z*PR+zLFHzQAw`L=LJGKErpw{4U*67x97WxHEJv4b=q>Am z$zy9GzSzi|p5RD|RSgxW-R&HA$+W_{9js0yfVmdqO$5al{~=8&e*Ky?wZSXnPGQ_E zj|fyHTDnhWS~S=z2uqHNek`fytv^HmdrqM!)_w@{sF@>X#Bg7KWoEP{b=<0{jN+{} z{&|cU4H50Xu3bjtYn>8U*-%!EiV1F)LAk+p$;u}`*^BfaP5W<_-!*c!ms}bi2DC?u ze-ex`aUhBkduaE9jfhB>FNW&OjkF5F5`_iFbF$NY_?n&IW}Q*u%Eeza>Z+m5ZlJiJ zN5$-dS(Y8gOMW8!KmU)q;F6KTXURg>Kl)R4>fwvsA)nHx}D^2KivJ38=#VUA&Klg zF^i7#`M((>wX^96o06(_sE<3jO$O1LvKK7S3ai%63i_$L6u~T`p_R%~J^uFOb~|0p zH;_#&Po|>bwcr&S>Gss(=%{C{TKec&)RW}9wJji)DO>I}2@gBjJ~YybS>nsr+@1Yr zP-$40*>X_-*-wq@$1VcXQ67jK}*u>qoDTjaJSUYjdqqmef1d6S*}`o{#Hy?jW3CS z8*%VC^~Bsp%>8EM9Ld>L)~|28gb_ctd>Fh<^HMK(9{&F!>>hYT0op79w{6?DZQHhO z+qUh#ZQHipw{6?T-fw0%n@u*E`U#cFn^daKbNJG5=R65IpP_qIi^=p1b;Y5^^HyV+ znjQ({?tCp%@(5oWh4N`CyK1iofo$dirADD8ANVeLqrt~<2GP!Lpc|r6`%?bA`rmaS zO{4XnvUvXWYK~IF3!*# zcYDgL%iMzBPdthL^ooyMVE!;f5f9j)_S5BBDgT`-T<=Okej^ZN?IM$qa<>sRVoOVk zAV+^^&MQS2GENGbJqU^!CD8_mH`^l%YYUgpENjPPNCb)c2bxck>v=}S*~}F z9lQEyeYwSLm!15091mYPW4d304^hkN>!v2Qo@5X4hfqfNHeYr)x5_i2lUUSO9rA7f z{hT<-$7B9c$n&e`{PVb5_|u|+`+COXZ0K@M#)JE+L2}IrX_J#-Q`s4?eAkyd6CS*> z;e}K7`s4_UIlcR3hwFi)x`_4JtO777h4&nV3kM@<1od(;+{0`GrVqJc;;{!#LM}v_ zLNsz8BnkI*YTsT|vvPzjP#o@1UU{7B4?IC+_o;sAHD{3Ab30=6x)@559uAmF5Gl{4 z*fCuLGGK}zNeHjB{l`JH43O`cZ@AiK7%#InESlk~L1*4}q?|=zJ4)^|s2A2%K{Iz$ zX7gMas)-+?rfBua9Bj~nQ{|9uf`^$yXj|Rnk_ptPX`8&Sc{zu9ssA9Dmpir0ZdJPJ z$+_Hed1NDLk+LohMXd5rXx{K)jVMGSMzA6dHs;eGy?6gqU$eb>Nt?er@e8%_JE^`P z4J5Dh?Al+djX`GX+$f3mRpq4UIVhHhqBFY+KgyEgZ?#l6|?EKDU@#yR8mb4mc1 zcI(VB9cdFKB;u|%pMEsGH~W|Lv`Af!DT5IW82lYV!hW|q?+9r-5xpM}J9Qn%R4@EW zLr+1PpJ?7`WIP`e8*KHyzrr<|D8A=&s$+9A&_zM-w&mpHZs?q6-L7`(c?h%2&SoXE zv`7)eh6p4lf4033dM1c<6gV6`hm8=|uh$h>1d9H3Fx@WyikoKZo;S|5mY1&WItaa4 zX}I6#lP!VU@byjWSsiDY_3GKtQ*&A|X5Ku?P3Zc|dUIGJc#5cr>n9EiiQwnUH0d4B zxt)XPR<*Gv8Di{kB%P642PM8why5T-ibMxt)_65;=JR#o+s(#_;Owk}N* zx@2xvH9I@1WZZBfxgi*-NJoHU2z2n1+-5*F;!&y=35_P#ptenJJ^#4! zG8VhXK~@Bfa6p|?iHUw72=%73H@6U0hXnqr*kk8nlhFEJjG2fS-W@WioNP~2`9Gtq zW&C~f%tmUtl20mO{M0GTs=3Z%J7CI6r)NaEhOWE=V;hs7v%AyLP(bxnf0Ft%9a3MM z-oRmU;ryhT#A%^6KK1ZodK2eiKL%UV_9uieJGy&ErDhAl?_l;N90m4`=>uBj&Y=lk zb;f)9*=feTb&pGnmVqpHVl_kSv z-CO$YrAC#FeKg!}c|dZ!>xTR#4)G_i$zdv5jk98o#X1RbHxp&8w{CU17kGO9d@uPl z&X*<<{;D0u6W%rA*olkPY7UNetk^7qlZe)82W#WyB;99jG=b%=UX|~I?h87++8qkv zeaY~I?Nj9}4}+`AN=1;2U!e{0rfb=8Wt_xUF_c&PX!eM4e1=BA=tFYDs|e4EdnEbC zodkZEJEQ=$$igo&HFdU0gNu^fKI=O>nMQ*P`>EkaFB7Zm!s2|LhRIl<@%~HI5X`E<)qH zp9|O7+Lw1YzYB@$5b#iXzdPkcM+_-F%TWEQJO z_P0};sLn0a80yiDlrw&lrnk#T?iaW(W8DB^O!P3)dxxK-Unamp!=WQ7&J$W<-z5y- z5a_xKFu6Zk=ln*=2i5A`sJ~{T*a?{4k>Ie-N4oa|O)D>yEX_Ws6RsZU-=>msm)joe z8O1M|hPWA#VzF54+D6rOcM+^t=^3m-q@bF5=#P=m|k~D9qN{>8-!mS$AiVipw z@Go9fkN1ee+fm*1*Jj+&2Bfe`zWQz0D$#nmJD?;7SH)-we%e_&dp+iKjCY1T3Y?dB zZ^kmQd=kQ4aCvM^vqxNHm96|Z6J1E>H;j+rSIV}0*aB96k9{URd!u*|$%~tIp4Q-N z7e<=}$<_i>G9|w`T9d)BFLvnyms6}A3EX2&GlY)DGgCl#B!+FufCUZ}5<}Q3#=e1I z3HpS81v9(A6w^EErqvl*GV#CEzaGFL$3NlFz)*blob1h<#ZI%WrI z86sZ&uS2KrPsB0tNma66f%h?Gcdg3^D!#`#Ud~$qD+D3Cz8!GaNqGc*OWVF zt=sMN->>Be!I>k%ns3SVu6LlDQ6$R&97N119C_y{zv*BtiWDXTwORg4p38&d?4gi_Q@@}`#N6+>f!8lxRc9e4#NdGoNBJXE}xkX!Jst* z$4%iPyD%=lle+>jQ-7tT?-qKY$|8}IdNQ&*nO0|&ab8;DQRrzUy}t3(``P5qu%HFq zVrO*KM{Wd`D>3$0zflEbTQeg^+_ht<-EH>o&R2DjXeF#`egP1#qxq{bj6?2Um&XWY z>)8-6h(1s0H^H*i`?k*Ds@5((aO}oBOfO!wjPn>dgn#!1QLs3OX*8( z9k)O!kFuwQpq;hDL1f{q!wTvbgK2Wjdc`VAt2Ru@UNe>o-SL3V9V#8N!k1zEG#YoV zoDqK8+>2>=KWUE2b(u&hQ^pdUPc4z$Q4i0+q9dREjuR~3NcYH7^QJPmB4`V6ZS7F!BW}@PcGL;{*XfhNICuj(o&9N|h zj@w)WE3Dz8&=Pd`bTVsi=6i4VJ+CM>6WDi=2Xi&F^2w#}KV=$(t#BXNbIni#J{*!5 zuS@0@2?2ji=Mht?_h*FU_B;r(CPuKYANJr?17G^d`YmO`OlxITpyv7psApChD^w(< z&RyCvAk%L3@c-g(-|!K8E1M9Al~KPNvW3O8==#t<6{`8nAa*hy{WGY*xXZ$&Z|yZ# z9D68iUNhyWI;e!!oIGR5197*Gs-G7KiziYTUh?#oU)pLUVL58EWVJ@J_w|-0@d$3g zA#3pd1=>q^=WFnzDr^!KQs8aI!Z|~_lt|Hb4D@Y_#N;7$x{=7R-BD6*X0?exSm1gF z;EoecFR$$e`fNaI3TZ>UpFmR64fx50^i`N-wXHT;4)^AP_^fcHErkCgU0GY3+Z)VXa$5$-pKK_EJ7qhNA6YqLG2>0 znxF1Uug!BfH`$Z=8C6{NRw64_%!K5X#w!Nx5e3(l@~iX}(q+a?Vqf_2!bgJ6f!n}o zAWS%-z7P|{ih}8c_PDu=XbKCgHz8?nf&6|@^H}gq!!xsTIB7ld6doxb>3R~TNg}!Y zEQE>$DMAH+6ZWXVzIF(ZAInTK=4GDndw00N(EJ&TG4-xI%?|k?#-UzUMGCzOnA2gxYHVUcE##SXfz(Q_!$p`Vgtsg zwNE@CHGvQ+*F%0FuX$M0lb2s-MyYoj;^p(Yf02WQ&>ey-iWz*I@0gcszOVA6cXb)( zzb^+FWZ}wkpj?BT$Tt=4#BDEcA0KUuB!}T}0zc^B`-?YtxP^WjwDQ+Aty}dE&=|lNwHmEEBGQgOGOtr6>q2CSxI4xJOtM7?H$xc}&&99}K z;j(2dRNsp7r{-ZB#6MvgMjllvVk0k@-f6m}UckQ!pq4S7#n5q`|305$EEA;^TsJZC zxK+=c2~7PA&hrGn5mz=(_WUY=)SPKo#oz1Y=wdFAh#b!Xh=r;VNI&U3$xTlgn`tWj zeV*eDac{%fQD_C}<=#K)#q>`wJ&Xl$H7pnPzA>g9epr0A`BhxIK&4O z8|741t<2XO&{M6V%|R)ukC+b>+l#Hrrfa=$HzxG=-=L?%(L?x-grna@S8*cH_V!z* z)7T$wtF#FWJq<(^H9J6HE7_BXaLfpGC^K_QUeTSxW(1}Tp;RTs`T4`aYpXI&o)Ssa zIfzPmDsJY&HI8nTm?DUb;18XxZ&xnKY2o;j%O)%miU+WmuDJSw?4SLy?Ux&!Ul>^BgPZ!wSh$V-Y?sJ}PPU3#I3Pn-`+Bo1gI&?| zWQ%@M7k~VNkYgY9S^Mj-^QewDaWxEe(i-K?DA)tXPNdR^eunehw;gOpxVW;Uvk9Sd za;@Bm8u_Wzk@q6`r%%qFa5}*M=db@0pO~{e4{+SH%3*brR3_iwL5WLwhO!Z@lY9U@E9ZhsklMs)!xTyf%!rL8e zL^X_~FIY1g>ER2}nr!MJH@!>Lfk~h)&8UJYxTG&(VJ=Vrx-UasW5@AwrvvfACOX-g z)PIbJE;hJapppTWw1Hx7*KjOU#diKwnu*LX9nwKS*M>~82Hv2Mj?PFKuopCK_KmZ45|GsU@z zA3r!fR!T0EMv!@Lui9(LG^{AT#0@W5?3BcOu;~Gymy0QTgHsfN@>opxDi&;C3FY3T zLKjB_`wEBLz@Q3mV~hoVjkE=bG$}O&yr^YiOw#HQfym`kf`6ga-QiI4lBz~r-^-0f zzG(%&WJHj9DFA~m?Y7Gg{@te39;m@cbhSH=Y5~1^J3S_l=WPJm$CFny|G>q)EADkP zkXq-t;qY+tqz_Dd$7mqIZIXoqoLc8}Tx0Wa62>QZ!VhENs)FTY2`=e|{RR?YLP-aA z%y|Kwxg8w(*9zG_S$zrhUc@t~@K+**L8_rQ3f79%RCC9m!X7ervkcx4R)~PnZk~RH z1pjQIFhXdKY5zDbn0aK1Is{jGUd5V|fD?yoNHpr$g8cY%o!_eq-x=_Ur{4;ZPYP!W zRH@bxD5$MU%YjbRsvciH*!}CdoITCA4%1h4wVEK0n~#hT7Pr}(hzz)tLO{zlXc=sL z}9elJvbM zM^lVhVC2rz90c2wS;&sy#xxiHzPY}GpuT7F%n~f(3!63YyHR4=eePA?Zvqnj(;-d6 zF?#cZzH&loy~!LEPY}$3eke{?17UG~JIAgFp8T5}6+7G)3EsTbjdIyt@2%6c;-2eat_R!SJTKRsG~gP!KIyI1%3OoA>kYtR~y^ zy3jUFKjl|Ak=sISZa;Py(u3|d53Tiy;SbFEMU?hbDCqur5%s0hlICEpr*vWHxUf=d z7n}7M-jDvS)aeJ;;J~G>Do?T6dAWQ9euAmf;*;A7Y=s6iB&UNjmsa=2&%z6Op^na! zmg(?k0<1;*e-}Q3CWtCalNNi8e+YR~WqsP%cd!peR@B~uQv+1WVmGQyiAY6UsQH%e z^ThVT+Tc*BRQ-{cc&@-ZE}#Tttms64>qXb~yTx-B-=}UN*)Jk8f}N z&jfM|c7`zNDX&ZUjs5RwI(KiJf{3c(#~~iVlij<1-1jnATagQcO%{OIK4o>TYfIib zj}vSt4NRXwzR&V>meC;|y0AyT0n(*<{g*$JtB7-G@|O@5qrj`8fCPee)sy=j%)54z zIaHG~Zwe=y(Fx3=YYV}~##zh9R&-*WHiR{|7H{*)#~dkSH=K)-G43eESsHMfEzKA> zNc0*7EMrMmo&qHOrG~56K5gqpMHolwzx-+*ecVGpkg#XvDsSf=(n$)eSBD7W2l{T_ z?Y4Dt12>>+W&GL;obV>rG!DP_#xua z$UO!Zzcr&Evp+-5Tq~AehkFluO7iYa>QCqZQ((Jf44EfN6Wqe(mW}pJ;UJ9{xIMAz zVMF)+X)Trel5eXo_2+w<2i0w!vuMN`<5Bt@sS8f$m0J;cd-1AbO#eV6AKi*jH#Wui^cy#cQ7+Eu@U@d z{m*oVZL6^ZnGV`Ny2CBc#ReO9vo(LM^&jA|&|vG5<6={FxaDqkGhI`6QT1qUe7#{^ z*Hkr2NRHUn=B)Va0>HGy%*=2PpfViFnz_D~0U!fY?QnENBqu`fjpm2#-2OG!$oP?O`o(|guSp*Ns{!LMJ^dfI1O30; z4!F4c|F|8Q>%bg8|J)AOxBs{uv;T2BzKaQ2|J&_Y85P?ZM}sIpYG`wHa0TQ7Ji3w% zlyd_x^v3?@c7#LE&;GaDQBx9o`rmGcPRxJYj@f^1N9NBzw*#&13E-dG(fRcsw`1o2 zxE1`8R(`eSJ?jJ1;addO%)kCUF1s zz%0<7nc3_2?>wucs}s;h$Cvhtzu9};@2x8k5N`mP!zJ|#SvR5DxvgQUpV7#pYC`j4 zQjfMa}PULdD;+KDOk9=$7`hr=nX`ObKvM#SGxb78*P7#5n#l)vQlFSq9?UG zJt@hm>F=s0iVq+6pv_yqJKyE^ zW4Rh;*)@eMYz0TJ_+tF<)*Zw+4_GYBpm89ptd<#vdYl!*u^m%StZRXVJ#ZTnP|>VZ zhg`XSV}jGGGD}Em^FcAq56T(_#>W=$HhKiu_UVT4EN)Fk+*;MU_A_2uP~XoXkn5-M zD$5dUm_-|!6@0qS^+f6;ogQn_Mo+(f7S6j*lbUt6d!gqne9!7Cc7HnFXT1J;k<{Yc zoJC^>6g?)S0DD`?IOKx4Qno-vf(K<)`wOW)Q7*9iMkn~xWJO%@F`&K_8za%GZ|QW~ z*9l5xVWf8gLx&j3vv(LbLJs(Um!ynD%A8KOTPh?gzP^3)iTm~k#; zvr&Sf4IaZ3$Cb$wUPov4(kYn^-YQH3!xVq%(@X=Ymdd(@q74M6;Uj30e67oS|NBD_ z7B4Nuav*o131^#lyuw0YK*y`YKyQRev`6CgcS!g z!d;d0qEi@D@(g1)1zLwK2<~(Wl)=!T9=j_&D6JvFw=+N5Cj~dWW=x3A%dGT8g4LwS zd4l0w-NvT3VxamyK=Z}d)&(N{>y`{AP0UG7yG`m4s4c&-<}8LU0;7cl<#_n?t;0Qo zBd>85g()9*!^TX^5Z7z8u|=C!*MHFb%WLzUHEGT6WQ>+CduQw5$D4qh1~L=PGof5v6CV!s}kKl<=Ykc<#wU@o?FBFgP^#fNqng{gC;coxmc2T9&a8i!WAUk7OZzFtaz z+?zA#LN}0pkdS$R`2@ejG-2;V`#c+@rFo9h_SU%~^GB;e!TE`~t=LTy^N~`b6HbU| z5kLZR2fS%`27>nkHSp|uKfIqAAMpT8!kM7c^5{uI@N~+~F#Uj=?m!|XdnC!5-NfH& zILz>fVyYX5=e3{&bfz|NcF@Dt;@tc66=%~AX&95D5T{a-?S~zCP#c`y{zS>=VpzR( z>CQ0ohosA1hsYD2E~59@s^TKnySIg;xloMlF}FIODe)l-Ia_VfdSEi!QkEX0fi?y%K#>n4P@TZ`Tad+XleERDp8LG5qBzV60qa>W52hjx#y#`k|=mYag0y zf&JyjV?=S}zLRhvnZwvwMZ9!!m%s3($w^MnAUg4m$|*isMmYYqZ4a%K-sfF~xjvcd zD^?6zg$^v%*N1z)XQDuwL-=Q$Y)mF&bLyV9d8+Pec|Lhjh@l0zEoVwzcd-lC@vhOG zGW9P)cI2h=$&$O25uGrgaD1n{_W>cZ)2&y+(F=qO>t{uOj@XpWq8-nvEoR~7Zfg)A zuaFcM-${Kln+}vCqDrffL`Fz*^o>A3$f=a)pq1T-^qaOuC_8nUmQ4EDLXwEYpSIg) z_?TL-z}8~3NZacxQ^+I-^q=ty6+dxFHES&1(3incbQ`CK7ZTXyau5544Z=y}h=f+8 z!y{g*%MT*?UroA)g3{Qx{`zG+HkDf1D)Z-Y#=MnKP5uz_vR(DXmL^EV-imV~0 z%ozgLE1lXE&&9o5@u#*PJe$pw%-+a&Cm8X%hKWvk{g7+EdSh!DrR!fagp4X+XVDh` zqZpfG0T)rUp(YGdX2hw87{S4h@gQSiJ&Dh)od1@GyCWaG-Cepl3wl($bnY_)bBM(W zVGb&nvp~MYyWHXbwfGuO{nm%vtSoYss?1KMAA%!~6^@N=RFR5Q=EYkXte3n47iu{e zB6DRf3WWFXqrZwi25r_H3->N~z1EZE4y}?n9614f6=ByGqktl`Sg3UMII8zcA%cdn z{y6;DyWeYGY}esB==OR6TFQcjmikKA5BcKJQ-|8;XcqddMSt-oQDJU}Pvt4eOy2Pl z7P%i6vU%_*RZWQscO`B!X0|_7*q)`cBfbI|&Fz_tor)$%vk237b>f8l1FLu8uRJ0~ zGm*M1I&D;bAGYvpDGco`P6U|3kj}#!=AOw`74kXNWQxtd+y%t|85&xc1Il=mj3&$_ z?^*PiFS*U{k~dST1m$}u?iVCOUaZ%xBj&!T#)}a!Ip;Aj)^3JD!7@$4Eze!_;=`&# z1>L>NY2?@23N#dBV=&j=pYk1ah#;Hb#}y1gUH+8`tY!4xkjEkhM27RUng@GJl;GHx zP)mLExSVJMeyCk6@FeN_KsUVAB?1C2sE?aCF`$v#rwcl!hU`)Q(c-P2eN{RuRG6~> z)SW6L`a4gZ?5);G>7&afOMax$E`#}wx9a$gJc+cBH>fGGAh}!RHYjWrNTZmF?c2x+ z!a32JwlH2D_cYF5hjxBi{YjWw(n-nrjfZYvIO)g?b!rrKoHr_TS0c)Vyh&3f#p7bg z2cxbqoBZ?Q$&+5d zg}N*4B%1>nSEWy-AZ()!5jXJW>MvbD=I)BN{-{$g$_N=3r;+8vS|=S^SCeSAp@*=% z{}HT#!dZIy^H-7Cb|<~h&iez}VA9B~!4^8@5otT2v`$5#PH5Xa)44`H7M>3^Pk4 zE@zZ30f-`)8+k42bn0o~86F=f^RJZ%Lr>taQl~|<>f9z~XVCRNQ-jVF$H(@q zlJ4$c-WjVxTO`7PqTSZUa}p%yw9hGLb?nW14COkjULjP~xXDzqvDE9%&WkF(Ktdg* zGnM%y)Lqke<_=S>qbXUnE%G6E5z*n|O~k}IVHh3Zjp4xP*#!ly$;h`4ke;~)GAKp( zHup^!&^;RNk55-b+jRyY2}^6Z4G`+i{*s@VC@^jdKNl;>d zUOk7atYH1!40jwt({fqyAlh}71A`Mcg*tUo?tQ~6QcH-9Z?k4nDMp{vkJ$)jwQFZ@ z;=~DCj_5$Ev0yz`5YDdm(6~ zhoEGuxxo`pyQ!$pKidgEXMF|@udCWhb}$g3LPZ*Zm#7G;OAa;Ah|=$TdKz?|=-*xm4)@s<4FXydV*1eZ{| zu&JEYu}alAVXlTwSmPcMo83$;CCv3te*(&){VV5J8!21-!w^)s6LJZCsfsfECC8>S@Ms)TCTkafo_B2sW_G%G3o2DYI`3S zaa9H+nXr^NcG7KQlUQWEGlcg%1+HopkB$YCly3HS(dWf7Ys5sxXqFQp#^jB|U85(e zB!oNN+{5NlnLbln6cmk2gLaH>rVSu_yYHvSaqH1m=_E7AL9P?r!zjd0J6dIG`>=Ms zp$mv%V7Gb{GQ_G3=Vhx^Cc2bC_XK)qPcX`W;A;=x-|=nGNnfZSc8?YZdzT&rV(EGz ztfDvT1bh)8y`r$60-E|As0zH_Y}4+Kbg5v&SX#yi0{j(@a1eha**K0JcbS~Drqj)C z1_~oxxjb3<+Goqn@btbXzasjn_A6wRs4wC02>t>cy9vjOrVVq-Xl+e%(T)#m?w#{s z68@*aCI0GtgJ8C@<5zJ+ttF~L`^PtU=Rfkq0UBd|+sWs)wO91@+utjzbnw^s+npm6 zBZwQtDQ(Tv$4{4AQ^5ajKwvb`l(yJfmBYs0G>DNsU~1zjZ{V+-RklDv&*Iocb$Qm?#@>e7Yl=KTzV;1%Dv6Zi^Z zvtD7d5Zd>V8a7x($w@xm4Ms;bHSptMm5}k&OLg|1^lqtHA!rXv{upFLw(cHQyBh|$ z!63iya>~;eFnTV;Sp1LX>szxO;20EN?%(RuAo(mYs(s~wK*;UXn4efpZJ%mWj`!-v z!X6&V7owq-XpH^R=?k&vAt` za@b1b#FQQUHeS@HGZwLO)HRO>5a&(hLwipm1!tPsSQZ^A^(GDOU-SmM*N`3mTJ%hj zs3MjmeiSw9erk{oQF+~x)4a(uQgcbOf~T54emp?#M=YYO_V8WyYc~X!cq{Rq*zQFk zwkSw0HHe$(Yc63tL}<@}g-`Gv>Yu6PH*3Ns)+}h9o*WdK-%1-*O4|puQt34PD{JvU ziNFs$q(8G7ALjwsJ*_8hyfhDo)60~w>l^+9m!Vk>YrL}lv7^TK$K5SZ_g*~@Yw($g zA{XWn)e2Ca(ktB)TP!O^)Gmk1rt|FYvgmi8jv}Ddk_>z(bMz*BepM{G<3B?gwLP0(JoRZub zm^>VPy}~&FhFIBD)GK1D7t?WNn9QIAn?ep-G!<02)jZRT`NEwqzTBC9&x%f?s;&{n z`)L@j<=!DjiGAjzYwR4WW{Gtl$M)H$pqUqTNB`77IzCWRK5&#QfeRx7*Eh?%;1kC{ z0pHbC$6KR@R;+Z`F!A>aR%=TTE<$E36?4DdB0Hl5tx$)^(~p!N1=>m8@l*nu--sE!aU5%*zd2 z^t0ZG-mt-D>yU&DTU8Y6iL0henfEM_{M9L+nqDxz174@BZ)=UMop1CX&X7@&BnKo9 zB&~{WaK6TpER`=<;AoBq7P9CBR-in-IuC6U6n#31LQzVn_`-gIyjI_1w4N_yg*zt|V7#I!RQdF;oGnc?C?pPgE&;83zus zPERN|Iv49^eApU7`e~i)-h#CF(@Ge=Z;>u6;T?oE`))r?_$XmBQ^JEX;<{4YQwJ7S zX~P~r+9Q76a9JQH(ZxBv68rZU?6R=jbdKqVtF=M$z|*4c!(^1vZ`%@c_icdPbsXy_ zIbWR8-!y2x5#r3v1O1M{Vfm|}# z(tB56%eljh!3}>&3?@;Gv}OVrl|XX_%(vvhjWq(2V@IPKd$Vb>2H-wUW}wMaGC@BY zD-tnMJ5*(x)W98*{#6@5l0xBxlK8tOJiEC!Dic(Ph)lvuPYWdIfE4*`G~ZHAZXj<5 ztBJpgtxaRsx)(Po z<6f4CFA>XB9K|SC4y2?(es?e?1}Q6$qwPuhO>G7EnStSNo28FWm^uw;S&0OXS-M+? zy%oXjt-4cLg2aPfIihj(8s~Ray&kxWd!TY%d^oPG(RSm3z3t9%<9pvackF%~bu=<6 zl=KG2uO@KZfS`}KuHAaj+MgvzS^{ramF7|!h;!?U{g-n9Y>2!FBPom}sqG6%0EGvw zO^wmsz(Nc=weRZ$YBA>M_B|g_`5Nz|tKyA1qvHE-qaEuXMH!IjNAb>pEM^IOu!XXp zvQfH~DMC00IM=GLK(bKqg(620!mMVFv6!C}osW`FEsW6!;7iOvg2vF*%D{sN+y1Xv z=Hxf-Iueufk4fvEyfTfFUrlivCZKT!o?o!U;WD(9p^s0#8>hrnIxG$dZfoFR{%yZK z969Cv*ea_<-X8%Se%lBd0Hq$$C&^1e@r-uul{|C>9}%v79MRPK7vm19TU$IPB^vou zA3fC~4YFKrxdYvRMyU{RrDV>EmA}*4xzn30uhVm;?TPt$eeHTi;^1E7^ zw45`WKg_p}h*FIs9q0S8)X?f8UT$#lzpv)TbC1Ofy zL$K6bJL!zlU3*k=P-O>B?&ep{ir%pH34fXu$7$hV&q96ah}aQI+5D|0T4oO$`&c## zvWKvxSmax-GT>ueXxi{HCjV~WtM-la(!tA^Z)t=lM4N}|WvA=Z^89LWq4CwL;`zF?%5?edcE(qM-?kH#z*+G)svKv!&v@4-AJ%9AoU#C+@jpl)6vhT-$DIFaMQ zBk)}yzPQ6FXHDm+qv&P^=k}VJWMVgMOq}lUSzip!jODM+v*h*nJ7+(JV!|QWO)TJh zWq|7*TN-gGvI!5o(8=~2J(pG zw$t7N)1KKU0?6V<*tzUWn9&bep^kO{0%jLBndK<(83@4Q5Gm#ucs^Am;ncss=r?iG zGH%zzVtBKVQ?-k!{*k)@!LeA$Dl0LvyA7=`j(mcR4Ez?{FET z0qHh4N6%DHCPbmaSZxe>T-7>Ke?*A`pG@KgA=v~0hyQ*l#AsK>jq=tEZBl@e@pzIs zI7sJ(t3;2_NIF86)pV<^ULeXLg^CbewuqSWeo5_FMmj%UY3QPTc)(b+Jr*oIMLns~ zVSMm{70S?ub3clVpmb>?b~ki15^@|I9L3WaJoUC-OE zQ5;mLQ2FttyillWPe%DW7GAI?LHWUW# z^PQpz$FB&16@Ehe*258L0-TPTwfC2XzpxF>265{XX@{}n{_S*^UMhpHS&4N}mB?^^ z+1*8H5pas$aoc*gruoG@#^Zoy`fSeP%RJF*<@p2|sw`2vX7d|JM_W9MCtLcsK8q#B zwV%_$Sv$4A7$M>{#GOrBZA`C77^JUtfpHHR-;-LM|B|eV)#LHR0y&}u9)gXNC&G(Z z5F)rsucu0Jm09vIK7i(Iq~yiDdz@0$*U8Km5k6SdLskec;HLt*PFb+p$!w0q85ZAq zJKCI9D@MD#GSxzrAV^Kmh9HJ$(LF3(xkXnVl^eLhQuo?2y#S)8!=^A zBJN!}#fmLofDFWN=Pno^;+SHXD+u9b&H)+aK2^%~$U_=M<96MCBQvAn(i+WGbfzV2 z-+If~7}k%d$dXo&l?mo6w=;6e5n?L7^R?01;iODK$nxH8%7YYm*+SA zKW0?SUD$`Y@tvLw`^F9U*xd&fnRRB>#ef7`2d zoUGLLatkw_h{pKS&@CW6(((;VZI;O5P};Rg@Hu?{;*G-5X8XR-K`cyidgkAo9bS#o z+qLroRHndwC^d95e#BmY^{xQ<7J#9?k;N`r`ui95=SVDX0pr4Fg{e1h97-8Ed}k4@ z@v)D^Dpq`ej22x?XkMQdo_~V#$g};0k~!Mj7RRSd%HLo9v?9j+Ov_6LM_|Va)2@%1 zsPKy(g7gzZ$jeoBy64uVOuK0KC~g5W^|g+g{ycrBW z&GyaFy$Q`0p$7gUseEVgkJ7s`gX|LIL)y+&&NepcaBwDoNFn#SA)p5uOHV**+9$QO zioXk2qNbezQA4;I-bQ9Z!Q&q%s@*}JhkG-|UtN|XPZTW6+p;l~XJEvV12Lg)S#vhJ zXIybVYYOt#=n#CJr7`}laXq2ye5i0AOg-*5oxl5XR-~JSnL5vJj8PoJ53){`OFRqh zI`9L92K3KXBro=lB9^O`Z5=Liyxu^Ni$hzaAnR}U;I}~SkMCB3GRB!!0mK19;zD zylbh!&5j4?szf6;g3G=s&0`TM&`weYB94;BNUPzjLj4uhlT$$<03Oo;S<%P`W5A3A zjz<&xpt=qJG%h{~#1^$j|1`T1WvNbcCx8KB>Yb$lB;&9^|q6+!_iF}Z&S>L$-jJz%tM|Jm|x_oN~xpa zV$mnJ3Qq-6`1D>Csl!FA@C8DQ|2BOoiOx&T!e@d*%I@>d@}mJ-v$LX}2_C{P>{qAw ztKULZg(45;Ae%Kq8%hOR)jPkFg6JU5{UQxgc18<>zeAc>*`XsFA*`NOn%8IcD7uV6 zF6;sh7s4Z61^Ji_y0oXAuotdmsY>$6*o%Z?Db4?ugscmcT-IsokDNi>o$ySyS)d=X zJ(!9%N;bVuyJGg@@ve}0*MPfhn%4TkV!dZ}oA@cKM0@jmEg1na-*#OCEK{{CL233C z19aiF@DA5w_XfT!y;SQ9iO^eR_j54s7^&K!PG&24yVk)PZ*!(@0tGs`<~3GL^;4o% z`4*`XyQKNJy%3qQp}$hkM%@A_&kR3CfR9t6b^-8Wh|Q9u%tW1`k^>Og2QR9$PT|LY zf&WI2r%%|4e#h9|W`cGe5r@B4i^>?LTg!8&Bs|75#zAJr_ni$pC=)OLSNW}*o;daP)L|X*q)?)_o^ma>dq7)2?{CI4SIDWRD#KI0lGZl9TyfdBYzWfmDkjjA@QV3m83f#Q)7?4mVRO{7eqPinXUo~%+8`p zPMuBB*j(?gF1__sW*C8w!V@CYtA}F6ZOC%rg(c+~k6mllHvq!i9<@OAfBN2s5tflx z2_^KaKey>}jAauBSlK->nrTwQ27IkMX8O&vqNmFUxh92-*ns3@WA;p2 zPv$BpcQW*javkO=mt>f>bR>M<&(i6jy(g}cES}0uIHO2P$J}5}nkRUlqu-_hzU&mq z-@=z6)kb3?ywE9Z1Kx~-AT);0fu%)y(%j&5vW#%1bp4ZN5m};`J<2t4LydG>9kTZ? zmiu6R54rs|rfmSaUb^IVz4_pvUXrFarsm*j&j!e7h=7}`19UK#P_YRmNpWcNvK$we z(lELFcR-!4RBH-I0t7;&}D`LM1aRy(~b$P|5wOeaUw-x;|r;EpUcPE@Ke|?+%tuE^a(&|40p`JYOY< zt0521KwP=1I~0pICpmcLMtmO&w@!KD%OrxBQQZL2hDtTjk^n) z>LkK4orzapZFcAlpWxg}X4CrqYhawGA@5s7ov82OtNm+O1XH*%OI~Rn+4bK`Y}9Py zrL@IBl8Dn~8N6vMtVstRdEtEG25X72_*fM{Zg-hp znfN)pk_Tinxe>a7CQNB-q_cMld8D4}8HSb=!-U!ZO_75f&t1WCgc-?_1+yx7EuuTx zs}94B3Pika_Ba*a$ep=g=O4_+s;HQeK{hu2Bk3&Wu$TCp*!EZJ8+3w&7q+S!IJ+q6bPubW*18vG)tFxDTF?Z9j z8CeFge>KP+D~hwS?Xsb1gSrehgCKW@+V|qtjMe)zq|0WcyiXgS^?-S97WoeK0Rwa| zu=A@ua!CcJDw_=0^36&5c8w(ZU9G}UH=JBUcKDY0ZNU!L$jrS^9Nfr?*Kw zhgDBtn}v45)Y*_rU(P3B6AYD=P*poWd*U|5DOJRYe|h8KWXOM3{TG{&ZQ;LQ=$kymP-!;(=N-bx*FZPMe^`YDa=}~=R^prRN=oHOz9*U z@H%jVMRM<$bsg>!44I&HKAkYMVbxom2|d8WwOO%sajOi5j6Bvnq*CEFNa`k<^eXFI zXCQ)bp_=B3-vm!E61y+Rx@1C0Nh)+`b(t{&Yu;T8mEx5OvQkQxPVr9Bo!DOB_7l!& zkfk=9^9{+&0~f(e?cL2};8U@~B~=6L>~VlMmxuH<N=8E340P4EYTH%kZ0!w?Iamu_%FWji( zbEYq4q}?-kwFo5r)<>G66t^Q+DvqgC&S@&q-&}k{F(+~Ek+LR%)Y=pxRJj{IcRFU(spu#q)1VI9H zizm+AJmy7)<{^u6<$kHwT&Dw$1kRvB<+Ss-oR?*;?3iFx;dEmqaC`P3QI1v}1UIsf zdc9rwxG>%59>d9jg<&b2BcNX`k*1Y)o&Csi)9|`bL)iQ5MY2n$PB`}`mpFdHCP+_9 zCeg7=6h1;!NljwYap3)wPHM|KZ$g{<<_7Y8ehmcNS9Te`KHyUJ)Cg9lSmwIwhKuj` z4ea=MHREck;mwmCBE&XO%Eqcs=lR+!BF;qzRRoRkX;v%Ek2uHX9#m3F>uOt&_b7Xn zr2PIjh;Yn)Ns^mP;mIs{8(#KftL^xXa_dRMjZgmW3&|RoZcA%vK=hu-X%x#9;>Q^k zVU!`eV+8&nn42tTUg>Lil5luC$+!=!HpN=R)9qn&V{mfLVM2mbT#renP`vBL9$eYh z>;w-|v}6mamgjO`3P9o)q>7kKrh;P2G@@?O&PE-&m%X_#Z0&Q{XqP0cUtjl4+)pmm zwpB%gt{|mB(P)&M0l%PU5ETUDg7@>!fMyIcDf)#==j2x4~ecPT&+D`s2u=ybI^!B~wVHsdBX@KiDDUE*wl$ju`S|&9Lej+c@M)2n- z+Bpma) zVMjsZdoZ~Y>{vcR^lRM%5@RTKfRgvj&nQQBKiuPbX_WS2R=%B#D4mjD&aW}7q zxwpGT>;o|MlYw51*a!mbd`S5Id$HuUj;4AGa_AQlLOx-OWy&HBB~o(P;0xv`!|9hN z-)32~*Fasu5u(s)Ly1qf-$jI$Z1w2XPHM(E;xt$8x{O`d?>Y3CH$=eLc& z1HD8`G`j)SP6CgMXgltTx&W=Z+i!X-U!HLE6AdV+!3U5Ggzn!*ree|?oPKK2Y-K!!d zGR%+$y8u<(_7(Y7V(;Cw*LArbTc-VZ6ddj%P+{yK#UZKp=(#P~skQ`cwRYEa4H?V3 z&bZQkeyt;(_3jS&I8p#x9wH^B5w|ytNYcB)HR%dW>F`1nLn^qpjsYK{K4uys@Pq-W z=vV=IrrMf*0b_U!(fk&7%41{&VJ^pdW{ycP(UmuH3#SavbM-}{4)?Oj1L>+9{4!?N zS^i{(+$rDwafTJ`Y!iweR3Ecv=+72^zQbYkX0`zO z^mO}WYx+S7I_#z`XjJCc#3OfB*VF_(wDXu^UvyQcSZq@PaTN|EZ7|8QB>b|34LyRfnQe$u=SlcBkQ^^yoi-bb|G7H<;_37^l#%^nXqW z=h)tQzwjR79pe4FR#mARPG?lot_%x`P}|s^7F?VI7!?>6m>z+Zg;7m1FfcL#p`WYo zjg1Lq`H9e`ytovI(DK{(fz2W30XYHCGXSSyV5IMj0T8~x=E$U+pwa?JAXWJOcMxgy zKM-kWJURC#m-N4bND}`~h@|u%h=lkbh{VjX_^bIJh@}62L!`j}4UszkL8MnctGw{U z>wgdlwC#)TA4JkM`szLNRsIK&g#K$l_`e|1zHZO|f=Fw>z?mJKU#(BE_@};4faJgT zagchD%%7px7KTK&Mo=Jf5o?>AZ5;sF0RKXi{A65y4c*o8+rH`|Eh(%yzr9_*lW`6V zAEV#|T#vq4hF@?-=hQamfXvEGPVb`@OhlQ!)E{jBb2zwr3{aXz+xmAA?rSvG*Jf#H zXJ+K_7x#S@{g*fHua>;Bl6c06FVx*_Lt1utcX@F(2mkOf9$j>n)Gzo~XO)@Jd+zmn zZQ8%;2fy>*V+RphnG{?A9FY&-YVgC}o?j7<-&hiAtJ{6)(V=nBJVSjGAo}`-df+xS zcCTMP2WhSBEI$|8U)HZ&^`FdN&v-w6xIBohi-c|n*)U}f$2D8N`h#>xv5a&IL6!^> z(z)aD8%rGINkAyYz(C0@F6AvCSCD{ne#4&ZNbB;>l3bB{{-DD9aP)&e-6UJ7y2L0a zJ}jBG62Z042p_8O7wj#h5Adt;t+eTum473akgC?*O<5LVjJ?Par5Hkvuf5~OG$E)S z;am`vJdn%OH+28>@nl#WVMNXqP#OBCZY$T_1?=GjSu$b+M;7e*!-DT?xSr@z-(hZ! zxbVz4-l#9E94v{3vWM=+Ymp$h>W)zurx+y`SwdlMJuX&(AHg!Px%lwlZO3X<(2uzc z#lx*N>O_vEa;i+&$LpbNfr-T~eQGApO|h+zdd^q>RpL5;+m*Lk(boLCxy1hSbYzGh zsexz|+<&ZomEeQYsVvnb&Vdy=$G2AZj`LFgEIb&aYq*WI0#W8*47D_L9GARoWvI{K_u*6IxPcs8*iDGbs zZy$627LzKXYSx>9{$*Z4$}AJ>&$8Ig6GCStYxCaz2X*JOa*Hv4il^?B#Y41vnt?AP zy=Rn>!JQCs7t4Aq#6S(3h{)kO>B6O*@qKeI)QrscJ>p zjQP~Ifrjzu-SJ67|JmLvjZltisG=ZO&%!G6^H(>zqMR{(;GVS5hP^=+Fjul`cztF$ zALezGT7Mtwd*g!^o|98R5ZaXn4}7aD+*tX$?J$%2P4_=e|&qtaim)=_eKw-w~j zv!z_{4FUN0_}sn#5yu!g|LjmC1TQJHn6--G23bt1#S=FWeXk=SpoUQUvn2lAAZooo z36_yOD(cCmy(*)>p3}8c%Y6 zd`>=9^sLgK9a19^c!hLmW_^{3^3yR1=}WzY^AxsrP|Qx6z%H6X`HnL^XQhjhy8XiW zq=Gt&fuX+#b4R!)^(qN*f&hFK7@jePFkU+g$NhTU$s-m+61U)9-!d}rg!waKtw#*Y zszx6CD|AdtA7-P6VI1epNo}xGyWR&S<|hV78`JX1fB1~!+an4z-1F5lzOB&v39(kKvGIx~5$~P}7~;I?rrAyjN#yKijQA&|MDV z=9o_Z1s@#2$cm+gY|9kw&^3`wnfZ8-(?`$^Y&;1j#GgRwko1LX&zcdl%sncCBq|QFOp|k2;!*6H%R(V@ ze>;F5dTYWc0W#h_uu&0@`GNV$J4r}6OG*7`Z*M3Iqk3;N+&L}N@(Uxgb)iT)q7*^P zT^oDT%q#td@ZW-l5`Hv!Z0B>cK-E3gJ*4OFTKFZB9CI=r+O6bLy@Rz-oA*nyI2?|> zXU{)3Ec~wGdRSWw+Y}nd?s1M>J2NmqXtLVNg_Jch|=s^FCr z^-v%@|nT8xE=`Z|rIet(zROvB8Ltt3EQ4yvwQp-ZA3rU*4%?){xfykADH z9d;8-b%F)PkvC)1eZz29&E3RppqfC_Oz<(j_eaxVr9u|hMcl%*FYXiJF|4c@E5G5J z6xyvDl8&s`QZmf(KM@WImx~_J5d7tb6*(*cv&CfC{36{d5 zBD`iVSY6!d>unP`XD1I-awyAt5-P4tsi`SK!Bqkw@G*SqM>d6xH0TtGtOGSj2qtB- zlWbYOfu8TOkK{MyLL|^9j;x(;8oEC;z}$2$ETFWSO`o+snr#a_Gz!uvw7kM)+*43V z=3#e^F)eb#vO$;k6)_2viak%iA19U+fXRpQJt((i-cMJyqD2iT zqwS+awx~bruAkJc^A1n(yH*Pjc9W!k{jHa4d$`4<$gfhJ02sACRac6_U8?khU(JU? zxg(>dBks9t1L*QmvM<*TIFNgRx@2*fZvpdggYm?PJ)$fL&u6)k z+IWDB*h7j}mCR-}wHyyY5Cz)&)(g)FrV#GEKU<%@UmP=uGnu~uPgDn~tiBq%*xO$z~ z4LDkKu8hrOE@$5rj)RyMKxVw6SCnlIB?P_PqeRu`C?XpI&f;M!5XRqJ8XFqWk#MO* zZWmZpUbmX}*o$!KiNSym%*T$qLqpA=k@641Ax3_25BXkzn#fa*wvpA@%hyuh5)j7u z1?<T0B8}2j(046sEj*))$xWmEsTvU&JD{ULDdlXi~w+ z<2!E}It@9rjB@At{&={51<7B}FjsmlYGa8gB4UoiASnfkdCpGI@fqBw}M?Qwmb#J!(hbWz|e zWxX!Xc%uM~O#5QbENjVc-$tA|>V2oFJ1>!Vawc8Km8@D8N=IyQkiVzi=FytSdkVsz zV{Gp%ZetFJA#9T}wcm&p3wR68QZg}@?XhoQ;fS)}SaHcZP`kO^U`n-eNggZzS-O&xo`L3VI-H@{2k zF%yexD5F##avcm6nfy}d!+Eh7dz9+jL4Xcf5yvyo=e-Us1$%FzCpk?&pKLIeZjXq9 z8@ZemoeVfMgzKfAh%j?dXNDXBO4Bq`ubl~{1MVi@Y;)j=s@f$|c}aM(hsLuPxUBT0nM#)I zu^3(Vv3SU3Q7Tsc-XcjDHtk0Ws-{{%)P6uzArJ!==AL~t$+>a8cz_x*8R=j4OKTx6 z`_mnlTq_l-B(Ra$xxLwjS$9eE{v;idLcW3p&EqBi2S2jjhG~u2+}ZRGKmkzmkJyij zgojI9RSFl>LRb?nN;cMCK!3j{pKZOOk1{2#^a&btuI_AsV=Rg{9(2Y(E6<0EbA2j! zFhpU3!f31Ym{Howzo4$6!yRbPi8(raxEE+GT!=jD9Sb;n1_4Sl6I`}BlZX_hp_9_w+D}g2s&J=q|LStmcESN zZO#N2>v^n$7`X{rz39OBAek6OuCy5Jh;{Ab#V4af3C=DnIsdwW|7?s73-n-3|E4Gl zX)VlV(6@G$tZ$%?h?)L)i*xhpc%T5{H(2}N9w7d;u>&VYkbo(Bbj2R`w1bg3vD%{sp@b~x7?Q{_BwC-}WA8#kOJY~nJj97|G+x~LXqke4 zHOYw3S3S)O*>LC*cpbBK&h+r^J45q1-5zEJ(VHeB-`e)?w)0i`)9_4b$1L0{1UZSV zp>Tl4wu`SdFk5TXB8&Z0EZR3`B^`C@lc`Yg9TO$5=3|1e6ZjaN+qz=6>I537bN9+& z7aGEkIgG2;mxqO2fxBB`rs{Hrfn!g#mGlV=U!@gW^v=qJPlkc)HFU?8&QGL%)X0T8H24C>pYE?SBaIz6LqD6FCv~E|}tgJ<(JZG`nfn$VN~b7@zxoh>6Z2n)#JZdnk}x;&~}G z`dD2?RoM27rK{etUlNE$@PQr`Gm=6dDY~RnxOmOfm4EnnyDkWU_P~f1ugb4`wieWw ze1n|RZ!O>?Fe_g$QE{hybYI%^8_R*beIT(^f0GMO28)k+!@d?+Q@+A;0SBoOtDz^Y@7C&||*oi?%*mpxj*~W|c<63|Vy}vEQ9x$Mb~v*lEd6AskY`$yz!6 zCOeP^dU(RSn2tU2l_!HYyI>b9&N>Vo7ZQcWqlV7QAeoGA=rZXqItB*;+l5JAKVk>+ zVDS8YhF3j>uJTn2IJJ=UmCC9^Wj+3#n1}Bg<77rO!qkq9ZWSa*e;IvBdQA!jAz8NC z8c7LNQHRu2P{?VL47qiAD=6d}(Vq4a226myCU&b34n9be`{#!;@$PRM2y~Eq06#bVXcycVpGx1$>GT0d`6z%^)z(?u=fsSKNw%XjsPt@t?rm<3Piez5qnk9 zI1aGv-i(=Oz7I4N*;GHQxUSMyThAjQ*OYJh2M|Zt-p0%sZE^19C4HYvUQ^DACaOzj za62-npY0)I$efXR-w}n10yhN}IylaMO8zw+^{?EVG*p{$V9kuEvfq2T_pJ<7ew4#o zE?{3^uP;LP4YOvv9V;#jIXy=jS{^q{^?x_ijYm`Sx{gi{#H60#i1NoAWB`lz-P@(? zWnb+%0Ims|~(}uIGvb9})axIX(V$K4S-SoC@ z5E)+V%mh=O6K{9>ItQkCo>yguD7)h-6~+jijTum~`Cl8@5e~{~xflWc0ai-*mypt& zzvnCJQP+1Z`4zIo_lgL@QgZfbJ}M7*=pz)EFAt^nOtB-XueQ%x5R`25~ipomVof zBol_wfP%Np4HN}v-M?7l4+0#o8$??6+9Y)Fnq_LMu-QvMt_Slk@gY2hoNH#_*Euo; zJJ>;_6X*_V^(hFoYq+Eh0zKbL`1gH!zZ6C?{t0~L0u;G*+)+u@XJxbG`OgeUuvYWRg@>WwX8c8>VGvjcGG7Qp z-kxcjY_qZ0{q|%@wO3T?WczVK`%SR)Kr=eRND1Kk;23HoLdSGb$PVTzuc zXz@r<@RV6|57mVoYYC|6{in@$w!!{6vVKfZo~p56`;(*am!x!PfhA}s1*Wxkcv(UG z+!da@g9eV7w3l=I!nbL4m%|CE_D_b3S75!Y-FuITVsLBl*1jX(*bv&ySwpx3wGtIO zJx0KSvjc#H(iO(mnx;X{dbEw-0lz$n0txrcmC7r^XTunNeV4icgs|gHCP?nscADU- z&s5D%PZ;<^`+t^Db_;4RCWW1^==et1*pXDIdo$frjZJe5DmFng7V4 z@S=Bx0|*jyfM@NRjNxdwStQ8=oDIsLy`J`K1%H5F!)rYb)iuN4^T^3Pb8zikNWzQ8TstA{pw*u==J^Z>qV zGh&6%zJ|q~Xj*O(gcNg`jTg1koUA?2a~T^}MgeT7?kNIk%(qr?2oEzy;F)RDK)G3< zO7co9&sG3iVzm2zWoej_U}33kQoHAZdRx|>M0>r6gFUSg#YI*hWzUH}9&Uu70^XpT zq1BJ8@Og~Z(O}2k6}FG_B^yFG9kIY`^hCQ)W2H<#4x6%El4O~4@$zLWg=$X(Z*3}i z@ottVzjj~05bug^m~F8It#dRH;$NUb?a#!bfWWeU5alALpwdD4;W&#(VJ;)3yI)#% zt8?{?eUD5SpcjYXA`sc{0Npi)d!dyV04n{{w6eJ6JGf|fjGC1%(cqMnx+Z6 zudkJH)DGeg*?Amdc+ReH15TiiMU%N#aVt-1KL1^6b(wui=Jqfp(lIeysQ36WPfW%S z;k7Dm1S@NlqKiwrSkO@Z{SD}A8aK#t9i>rRMDqmlXr-uO?&{W)_-`{tMtKB>peFKvXgHF#wJG& z(;ma#hlDb!Y&&tWL}?C_^Z(37S5JrOFT+G7`Tcn_GY7&@jIi_*h)xuXO9Xla-eq&z z+)+zMfH!4-nWF`)E%USj7#g$3;?9 zpSU0LLpd>0PK65GHiN&HAlu!6!bZHlRojZ2m@z45v887gS=!f!mzBMFHpCSO8xWd!1Me5?hyM>#=bH+|kn zy?QG(=i(3x2QoRTead|us^M|Q9F$c7ytIjtDrk|M_UeW0j7CQ*`QAlc*LklL_pzDd zo<&qZY;t18;)WE%Q(}?e(3WQQ65qLKmW2JDC>Hanr;JXJ0hzO+bMZ?JDBdBUG;m2TB zj6W`SG+E+#ikNU?jQ&lPsaB>IDG+|CG8B9C`PhK}A{v;BUgf*lAb1~Dkh<~G=qUaG z8DoSXbsyU42ulFrC~^tv!<&0gnOumB_j6_y7^Kl*ZU{d}~sO(Fb zY=ty7y&8jsrV+82PTSg#{tp$~ce7Nf56cvT1bR-a;nrmjB# zFxZd}?f>f3ceIsf?z`R}lf!0((HJG7`aHQe%Bi9*lW>-eGhzyD;1s<3sF0T=JGv!V z$8yR7yr1M?6baMM>lSzVVP%M@b3UVNG?(U?IGM2spRKgxIq==RX9DWy?Y9}V1${RC zs&zoi?P>`BWxiC=uSJqGV~92Wq?Bj$(DF|U?trs#Fx1bs#{wlw36fb9YcLBdBtRdW zZSHPOkn{_zflrE5?^qdS3B!gs-358JJgfU9`pRy~7+|e*nVFIl?^1X8b7w0>%J=-4 zF+-v?X!rv@BMOMCRWL{0(D*mS%}}UEx=R6C_&$#twuo%f#(Bc)kEiZi$K(M1tmE2e zgzxJNRD1jj07bMfCO3}`h4q7(D=ebC!}qtwkwqP`njbsu(PAkDO@v|x{M&@ZARc7O z4y8U8YL#3VuF#~kdyni6m%f2_u2FO?Yft08`P8dDk~ zlZjvY`gtb&75(X4m!gx^&>G&OfNRY=y&kih3jK_LV(0ljR1jOTNC_=N@p^4akT-3i zHl@~s9K-G^v14Yj7a9gkdcbo61+=5;E|*euxWJ=?)4dl+mLTiR-J8UfTFN~ti}hsr z`lO_-nKYHB@_F_MN$2QX_ckTOK(0`=2EkaA4ZwhNKyA``aO}qyE+Udl0Y2?YteFUi zOlvxYm!mix@{IslBzXP`+EloI_y-(L1ud|nn?)IV5fz04a#Fyr%BxX5qn8r zCOg(ur%VhdJHq~mM|GXP{rruQUi5-c+I#RUNEyD-V5i3=4w`+ZF*+77tZ?!fnvCl& zlMOT(JPN8ZFp=DkA>~1HB}cS^hN&|E69T$o8S)~VHNO<436l6(RV&v@NZ2%zoxJ6f z`tJyKyJjQw#^iG7f&@4JtHY_t;=S-%0vUI8xsKi7u^9+p5x*_}YQuvm$vj`JsRTsp z0&Xf^XP>#=Y8o0`w`#^)d{&OW7uh40mFyK)v0`ee+15W{$+Cvg zq8Mr!jS9u8I|7P`H8s#MUT)~b)wJ)%nf?;V#oOoWvq%0sEQAH;$g3gDOxKSrs?$qm zxzZU)p>@`T(Z{Nja&K3SMJt5r}o2m7N(4_Ad zOl*&vlx6&n6x@KMwV8Hf;LBtkszCismIY&6cXXVqUeict#1`<94m?|B3@(7!c*~<< zHELX3ll0nl&+k6Zkcrs!y9y&MnkdT_6)wGYF=uWUI>oz_4I{YScWmF;7!e$_pl`Bx zKujg~qMi6)NoJy$2%n|-b%@&y(;7cTL|1<5VlWyOQD4O!y{8TlZrk%m0V6Q~&Xh#B zdoTg)dr)zKF?i|D!^w)R*j(|{*ukS)&omMvJUbH-2-*-qj5Z336#hcG!pO)sC=sDfkFWM-0@>ZM?7XW0Ib63T=2q^&2SXAK{z0<+gWVIV zO_u4V7<`~|Qs#L+34&gy72UFUkB0B=Q26I2VMU3%?Foy-y@coQePN)bxuwUsPzx07 zq|d|>5?15ik+~rGiw&*szj0@=0l@>vYOhl`2@c48mR-nW$_T@uAE)y@xWnZeJc>{A z17Ho?zitEK9kuayEZn71lOU({%U_pD4D%cvLm8Sk{$Vr-Od1!Hq`$#OnN%J<#gIP*pthX*&s!jcn23I&{~si zcf1p}aZjrKXK!lId{@}pC1Yn<>DZg zzs(#B>s#l%-m@6|%ImG;#q7FHKBENZ;vc9=`^1*KfTl4xIx`UQ`I=DUQvC_%O?YD_ zPLcCcf;d(q3Yi=;Egr&>Gsr#iLn~j6j^ya5BDfF8`g2xD%UsI!ywk_)5_lwb#%FxjH4@tp77gdN^JZ6^=n%s$2W zoEu&A@=tvfTb~cIOjbf>AmYM zIQsi2hr(p311dQ-_J{ndf`18QmKmE_NH*4a3}Vet@FAGP-th^b{t{K<5E=7dM3%PL zr2FNNAahfy496j(4-7Ud1&N?M0ZL#y_G!^9gM^Hlvj zIH$2jv}NK$N>5jR=9+v8h+f;lNbdohS*hEBXr0O%jx4q0xMNMH%>=qu`@{C(j_*i0 zERUs^6vC}Y#Oh7BFlKS_uIKlPblm5~0l>67P*$)_FNFq)bs>APi{Z`iwcfjxm2#&Y zcuudlA0fubeAP?wf$kMfXU`u2EAlX|wQ<2(4Og@V#{a0GG}F; zsL0y&V2n8i(t2(wkEEC7Nsr%5EzL2ndkE5%qu;V)5nVnk6U#Oi0MlcX(3nD#$=n1+ zFmT3IJk(JAks!dJr^@qqe7b)Xy_KF_hQ>9PO;9MM)rDg~d^6YuBG;m=R79f9GaBDM z_Zc-60lBqSFY&n4J_h%d%aE3J|4oP9xynsX0wh?M3PFi5=M=`?@d zH~$xEUP-g*ttVrD%L^fQjnJqSZNPKMr*@D(@|H5W)hoM;je2 zSAItu&KjtjF<-RRO&F>QC%y0Oizdh0h~-Ld!nj97EhM_iiOKGy6<_hSbA=sN!Bnm= z1M?MnGRrtdy%pKLlv)q~6v=wm7Srq8(rYT7X@-B0>p$OfI}m!E`Rl*k!a&l;9&FN{S2Y4O9tJDx{o9SdA%8Uu)!vkpCjz#EYVTwtTi{| z29X0%d8FE1JlNKclj8<#`(wFAG`Tc2MBliEI~?=iJGxWY-L11Pd_m46`pj|KFyH_>rIABd1fTeJ z849hoU0a%`G-=?aWQ$2R1L=*dUyLhMK{Qh#c&^*hG0532|C}67)9aP7Qy_#TSY(6!Qb?`$yYn^dB=V|$D_@-*` z9GD&~sK-)n1?uIj^soL#&6~%O^ZO%0Fk*alm@*^&43PM*Wn(O(@t4Ip#v> zmaX1ZN0_(>k0IpU56V@@p%!=+WlRa--M5lWNpSV@#B}@Hj#e^rnsXZ~D3Wik;>%9~ zwy3x-czZqzo%Kccp9HP-~*D&z)h{9IJ5YBw~77=p~hKOq`iYKg9xj{v{g8C8V z({~YuB`N2yxSD2tpm>$Tymt=vwC-C`d+mQ8vS&O#R0;*6F$FCb{g=QaJrm?aUL!S2 zbFybgIBX6cK(&J3xgt7b3Kx;uP`8GoueF0SkHdiK=U~8NVs-sF<{?X4;HOI`H^59{ zT$Y~3ZvIt$&nxK|a3nLk-=tI01?4Uk>Za*NEFDa8{lp|`DtA0}QLVAJ>*qw-InBEI z!By3MtDkMN@ySBGI@0=|^5Pi!_Z4k3A16#nGTwzwkj%$p5LWI5weO*GCzb7xuqM6CK_JxbTBQ1qGW*Qh@!Tnp|0xeR51FIe1b}2NA5eMj2)VyDstVY8`u9ZuJ|#oI zrk+&DASd-t{zP=9EuR3~-9&Ws_-BB>Y0f+9(<>P}gjAqhjfm#!IK9>d~e`GF#=!Brp zZJQofN6DG&`q{_W#@<2B8?y>*?77`6J9zyL?CN1QIEHX?# zVU!%0a3Gc&GxpZF8vN7Hv_cNwY1u>z152qIeec13hYPAp>*3{yybQidicaKr#@+$q z*ZW^vW`#-K_dHwwzpzM*+WQyrO5(9ML|}VLPtaQtSOkFI_^YtShh~s2te=H&&SQER z#AcD_J`t*02%wu4;8jSze_#ULY=~baVa!fb`BSxD_0_AcLw9?>cKz2kBGvuDj$C&Cy&N%>2aq$#p0mtSEaV(P zp4u{{)x=f8oUM%%{ED{`)69!+k|^S^Q3!??Z7uIg*SsC?`qNiJgm%p#(i89jW&fQi zG3l4)Ofs>A`CCJ$C{Mk<$g1VKGEWsAHhr(b!i?BwuZ}Z(V=aYrUf@!|8Iap7Q;)1M z7%}VUcKI?2u-w&Wf#@0r%;J$Zj(4#a1U}qejh}b_ z?3^{QkFlb-z&r2YE>!~%xy66A=R>{-LgPcj0VR>D^?FfZxg-kpjNFb|!do|IQ)*ve zK40zwTiwMPdqBxPIjMlBflsRMC*a|TH--Phn|Z7|F>@(C6g6S_nNqF6)wytdrX*UjGU@ZIg=nZIg)DxJ7deHdPX1uspsQsY#q7lU$+t_Z0BacCy`&JWa%m z_!5J2%+8uhKz_!Ca&rp!eJ(QJpVj})Bo;Is2dRCk}x7%pA6b6^FiK?#f{QZ zwLX&4lU;#pXd5<}`u(P0_x;#X*yw>2-|}B>=ozsxSq(rUG?nUXz4CceePUY<&nZ~G z#FTMwy7}0jr4jA#mex_@Xu`CWsRx<4YgDsP1(WlqbmJ^ga3BN0_JIQ*E#MhMest7r zA6lUlToPbdHY}WV9?tN544pOTtoCG#XJ$QBgTdNr+#@pbCOm2uY7+Ec5VgBVM z5bjzX%S0`QBwQcFc)(3jq~>^vj*F;qK9z8APLvmR<$E5U^|_579&&RN9t@KRn0c9` zsv|eU5k{_4*$gHEkG)rC2_bqTd6O}tLqcfPmYL=Cp`&Hz?3E4`=yf^Rw}K574G*0^@s-qc|z}OCLqaZ4c`BPMM`^O?O<>=?wS3VE>K-jqUJ}F&6~ay{fCl zK=u*tbbRzx)Bzg`YEma>$TKlWJ$PElgRzQ7q6QOKexx8a@xHMzuFRct@iBM!gv>`f z+$eay7?E)zwT$F7+OkGn{wvc2pC)J1SGRDX^o?SU=2Q6UAaL95a@i=4eGpCyOYe4O zovavLK-9Q%47D*SO}V3&{hVQqr@_lM+Bi-H{#hedx70s{hMPJna$Ldr9fL8c%83q) ziFCuIW20pw-Pg-9pK7bJrbpxZ=pXPj>|Ha|`yY&*4eQl;fC4^64f^n!P4` z40`(x$QoPaSK)RMGY8_!MuULuRlb6V_55db`KOd@HjZV~25%K@yatKkUDNqK_J@Zn zW3gUFO6mpkI2+C@Qy>tlP zc|Na^*X8mQgi*LIQu())nT!c1CEGyIM-Y)^liy()OQj6ZNA61;%g4tg6{ORJoVDTn z5dVPv;39BPS5$CCRH`ju`~65=fa(@8ELm zyDFKRn8c2g@P5QZ?RbgyVZ>Wa>tU5-Fub!-QG>pAt6cmhsrn($jTw zCt`tE>FmKH5<$E!(|cyRKx%o$0~K|x8&=Sin>Mx~-R17^L;aTn-kO(fika3lsGvtG zJLne)mJgEO*hj8Qin^%DvoFy8)mS5cRa!S&G=+b61ol^|1jrE`Kl?x-==Ep$S?>Qb zDPh0}h4U{8fQ|o{i<#_-*DR9ZBH9gMrx#^I=~cci2}6^U(yT0rvU$?C`%(lPYm}5~ zS5_jTgJ|mFKPk%D1ypN`%gDMBZ(i#nPtqvt4{X%=iOlX^Zu$|(6U~);Q3p`tEf@RJ z!yEalQ)UMn<01n~b<6wE_>3*C#HsnVub{WqrYJKg6LoKgV?iDe|CM4ZdoOQPU_ zBAte!@d?z5xI@s9bzxOUQiGMZlkAUXAdhQqnM3J#8%x{!2^cAqGIj}1SZCAT*LDmYq3HH&Jsx^{Zjot;m)fd z91d%b&`##uTX4|I*>$;-I|184#{+^gNqAkmxS!_kMRLn}h=_6;1=LBk;;mf!seeG= zhUoI^QkxXRbbzA^0BE|I?TP|u9`$duKeP5Na*q0`yH;+`UM#Qpj|_@(WZ>$d1Kxs& zO?(TB?{%;aMP8*Qzk`UZz)J0%=?n0+q$elj{*b>Z)RXDnwXBNQ_A7leF0;#Cly%1c zS^1(;mxC2_R0!dD&_MTE^Er6rSIn(8$##btr!!Xi@uxzFwYQM%F8*H_vzVs9tZ z8>8uZDH|>bh?>shIuHl@zJQJ01w{uAv8LCmqbZ0NR@G%lwtySb{~X9>7v#<}-kd&@ zMvs7OBvm#OO=<3t76Hk1Cja9y2d{pq6ND|^;JcOBKyQe?b((gbi zS2_>A)eBs=StH1XF01MuhN>1{n3P{V`KBq$svE5Z6fsu=t+U)yagWB#jOf1ar5~>s z4uv#Smj`vyub;LPdw&pKPez6iRA=}ImU#v54$OZyZqtuC@eE2Yk946Mqn=&L1O08B z{S%mT75%ozecYYun_eKZXkv0|_*0-Ykoi$IHJty`(%uI)v56xxb@Ptq-W_`s*}_0m zAFkb^OF{j{=}AjHU-aPsHAC%P^E?*8SGNc+lMM&>X0bJ z$Rs%TpyB7%prA7f-wD5foKKdPvV*t`me9DKoz>;{VMYenV_FTtCi=S}DK>T}#i;&D zq_CslS4!EP0Pvwrpam1$y*2w~8%^LSTEX+64s6`c?gLi(-Ml!$(!EV*eLtk(iCi@! z0nyeG)3+)-IhW0B#6Uz`DNVv6xO#Y!xD#^8%W-|sqCa3Ht*?m6C;`;%tqoS$j3NYO zXk@aD{**6T1D0TlDcVWtAk6CF2pj7A4NHA-lX`kAYj~*_aSp+09d)|dhln?=vhj5_ zDL>JdK*jurJ7VKxJCn6kAu0`1BQAqPMVK9#IfaHWja=w~nfNlm_-_H6Xf>O|ndv#I zb2uW9j2ynOn4oxpfkX0MxLr@d_lpj|LNIa1oM02E!#4yT61P@RL?UuU9}hRHdJ0rCQ}W(Ce^Yfi;dL zg-H03Q8x8?iq>jR(r%xpo~M09+$kI~4XIgxpz&-K8IwT)osjMtQ4m(?##LImw#_>~ zC(e{HhuK(W$Co5lj&8>M4!CL0XUPM5B?oDB+hJEapQ_U&=ajLRTN*be2&g`H3u^)m zu8x-^X&0XS2&3JLS|#f32W%7wL;RzDZHI`0*E8Gw9dA-;RQ6yeB+MPAfzE6;hK^xO zv=m}d8Tk#>b7%Ig9?fA0t=PP1s9IGPn*#~Hm!)_)tba@nQ`LYO4exLo;+A?6ibb5% zfu_{WA@2-ReZ(2(?Gh}$jRV3Qj3k{J^DoEyN#euB=`I?^Swy|$@~bq(^xEkcgtfu9 zLMQr$KDQ637jnpff7vPycgsaCvEkkx!;3xeHO0R>t!giIT^L{ojx$mgm{vrQ0nyfS znk*Zy>S@GZ$BIXxPVGx|e;=r0dHzqA}qFY>=ii#|8g0FKXemh_OCqk6_kf%K?`tUuS9Mup(9RKFc`7g;bc zzL6Fcor|Ovf#Mx~Co~4DGS6X5bBD}$PrM`E*V)FIA8s5BkyY2*t4Q)H*TDukgaF)Z zx-Qva;{{*0gMbp&XI>cx@R%@-DRHP<+2c4-ral7Ae?|_aKDtC6hKwW`zzEM!b$eNP zW`_-h{EAO$2W8u+&xNR+Th3_Jo8PEjOZ~MjHzk$4L2}QHALmO}AcwV>pA{usxRFH{ zc@7G^futH@!zE15JM->K)|jB?9S#gPp?|Zd&H&uRD8-X#cyk~xmn+vu@7)y7+V1nb zQflz%x!oyjYf?7IF0#!^B55;+^o;rQ(vnTgfp;DjqkD$=!=6OT7k_KRpssiA%Fenf zP1hu%1HZBY%(n>nET>ePweoB{HVF>f_1t=(JC@N|y*did^YhsHFzs=5X+YZ}S9D@2{Hykd77S1kPQu9a}F$g<=h zj@;jAykUuLyU__-^IcT+cZ?%ObeXz`iDS+bTftG~kE!L!gRo61HMHXI3!9?dKrPu* z{Ye({gGAotGtmpy32J^eIp&_AQ?O3tE$5yWUVJ`byk1TOri8VPU9xr$^Yv3{7;kzR z1Ik$UsRunI8_84d-&XKvIj0Z2+8#1Gj{C$q%mFF)IqN$-|0h2U^Ska8-P3} zNIJI5{prOJgAiBWuI4SWIL8lqd8Xr?aYVQWe! zLB^xNP8;3(iq{E0 ztjle8>)!j#RV8HRr|ZN%`$U_*PwSyVd;#7c?k^*Yd`^X$?x2BO1tEbi^IjSGSUGDp zG*7&8@|r~>zIBHmysj#Z6iU;`pRk`jUbg|IY!M;k!JOD#V0gIx+AdA1)QP_RHRHgPwSm?TS|CcuH6JGIg@-l2W;(F-@uRd(OBE6il-AO&{OA!MN~9V$Z}jU0&teua~}EbcbinlY_hHlG;g*Q9G_f8sPl9-M$3*#ycx4!9&xHx~34rewdR1cBVwk`kCMo!SRf z=;lYHLYQHV=XhH+x9K|$bbO0Kr97z%tFJ^WWvQ!y7qEyLa~)(_hKStn8EQTb?tXSw$`UZ`g>wLU6j)b3LUkbFXAz#rUqw=AX|Rvk zw*-fpu^lsS|BiJnoP7dY!d!gxmA`#gVNZx#LN+2E6Od!PS-kXj|01j2e0YVh<2&8T%u>XpP`X^5PuiI`4o7Ft&avJ=kJ}HHmUYp|g1N zKxG7lIMI`|K?QY02*Q(!s^i+hLO38mstxFBd)nB8-JV_^JT*jE=Yr@gTQ=bqF?6-$ zgD>4XMSEoo4Uw5J70gD5Gt*K(VV*=Im+b8dxf8ni4PyN#BO{H5hd~s?5o$%1q=uGW z=1|3ZZGIBp1w$;(@)}rfX2{Xkwg*!9=G3O=S!Gt+p@O97SsIAC?u@!Fe%x^)j|Et-qr(=Y8fxXWNhk;a zvWwSyu@1ya#Emj$UVT<+sBRGntg_II285LU4n+%R$LsKVZrwu&w85uT68?uSRw5ZX z0VId3(cMzA)#v9^`w`OF!Kn5{;Zv~s&2PnkWyx0`v`}g~oEdlJH9sjb!?-y{wN1D*KX^-4;wqHX|&jy=Qnt# z9E z6;fC|Ax{1khluOS$@|_`lO)>|8LT`Uz;yKs_vBwXcRv=EI4nQvZOkSgs zx!BJ7P~GX>ditK;lz^g!JtU1tYC9fkERjB@)IJLC0#EyP#L`osko;FCT$br8kHmYJ z)#?Zme2m?D%;eEr)vBv{2Dxr|8GSWP%(y$+AxQnHeowD|Bj`+oj8I{#2dQnQp+!)} zre^(0^upl=EL4?cuy8T_#GBz`L4qDCHVM8@K56^SPbI9ij{)Zw1n{WVZVlLCF$3r^ z-h)5D9S;#%F1UFw8k`%=u+f<>o5J23q2|%)mIc|?9CBQMKvj0D!*8Yh6|}L2u*)@2 zt`ePI{(V?b;;4!cVnM^x3XI0`bV^T5vc*p-GQO+bR(R4)N>}l^zcUrEANhc z3T{p!;Kq(_AoZC<>s_fS4fAM^cd zu4g_Rb%RG1BfEf3GW`?+1D(8+uoi zSSsZR^i}`^$U)lYrZd{TEXtTX%_vqmFPa(WddYByUs(Q7XtxG_Bh?o89S3u#U!^t{ zxLa$O-EN@hkY1bh&qD;ztFNow^V@ znWJf=S&ki~sA`oZGC1{XQOc=QYSiC91O|89_iktKJ|IU+4*!tqg{C#19%yG?LE{!c z98MrGs!fBeo%D_4A>qT(HVpKdi??FE&%dNG1NXTml2jXgjke9r`>n!pp|qM`O0x|O z*d?Rit&IKyOcYPEFSnY+(0L%-xxq>O@gniEz0MsNyHrw=5IiD~fxF;$+u8C&%}VI% z2_ST#^zh{BgYFJYZ0tg!cQRdL94i7Y*IGn+1iDk&^`Eb`-CMdvtSF7jBhVF+>Z3I( zURJdPw{6`9#(NrJNwj6G%C}|3E+kW7yDLtVt3FF@onoOJ|+XP))}y{ z09sj&)_-3+F{u=)ANo371@WzTS?G$`JFd1%*) z@oQbU{466P(Sn?I#f-{k|wcpDQH#-^*Rof0AJTac|gkwEpW0?Wv z?Pzu+@?5IQJX!Rq-%x)M`DJvuuuy@dpoerl3N8@LHdp#h!-{Wm?Kt!)5C|4bstw5y zsl=cF-9r<>9o#Yp2ZCH=j``OIHyDonLS+5#_vcb~5VT%7&7_60)sTTh+#;2O#$?84 zC$p_ihmABx)_TtH!;nf0FWs6%B9lIPy2hD1gNI_EX4*-1iO0iZ(1gW2m8yo(b4_Q1 zn6X&_F(iis6_P05@~!H)C^dnb&P0YgAklzzTf})Nu6~A94sib(s14&!?80edNrsLL z_?6pJh^NPTehj|d%hix5U{(u*_xJKopDNZS2(CfU!JHL25A9g~m;Z)w1vQED0w#>Q z(ubGiA8`T!aYe=plJ1iiil|cM<|26XQffnwDAl(4(_6dCIB2_l7#uhez4BXas2Y(T zA4@00J_xj^Tg=sWV-RIFRjwugVILr;d3{+fsDvPDJ`1}7hrGm`mhMhI6?a<|peT{} z0H}^*LLC+&+RM^uxv!RlOSxQKekD@a_&<)F#H~W<*koF%lls4FfpWH*>*Qb&`}#%v zii{=S?R8UbZtuj!@@)pt?gUhY^#rg6`(v+3Xx0w=;&DlqV8je2p}_)Z@KZpNXBSKaiIQ9-9Vl->bv=zNFL|rk;5&{ofmKSS)$U@ z^-e3Zmgn}(MsF#LM~LA~onc_5forA_jUP;UkNSSYL>_W7zE+bg02WhEi@Vt~M+qp~ zP~980NfqrFj`-K5d!5X0Ew|0-u`9}t$um=<7i(=acyXhiHMgB0hTfK_@95vGFqU%E zQ>%%u4%!y2TrssocOPhFnZY=y@TF3L6(j#S`&KRwXp)puPXlsyz=sWpNUgO>NwOEg zn*gS5PW<>rotNXN=eo#YUXY37cb%2NqUhzCZL19v;-hINF8P!CY;i<(w_|b||Ih|X zu`xbt?+SIlnRt`#6a5gE*i<5pEeqc1WEpCuRWr}8?hvc(-d;~f-~edwiI;YWgUG4AU*3j0UHrC*Tkj9ra) z9P1JNKI8l8?`V2PU<^O`RC)kPEMBH7Q4!nSn8P%^h(r4#tV8MS`>E4#J}$nw-nc5k zS=FpK-S>7LD9!k}iJAQ6%XWgs-lM@vE7JS6tcBRbwpd2ZG*nJ0*d=;g4x-S; zkMS}&7kQvN>8CR@IUFSTqH31Oeb{VE7NuAIwo0xajjHyn<~ps8ge^J!@+CHg)5p1T z%ssH0$5So(N6uy#iX1e9d^r>S5!0*#T~zcWbEv)V7iU(Qpg6kp*YJXnV7dD)3IV14 zwjHJ|)`pXLD|8FQ&8@g1zQR{I4S6^+H+tonl6{+#wC$8Y{kKj_eRJd{p#hX@eZ(|% z<6O1d1Fpwxyoy^9o&QPv;UsP!v*2c-;|3$W{T&qz>;c`;-^dDoJ!J}3|{2# zBt=x4N~>D$PDjFlv}AAB?Yf&Wl0a%Qn%7z+fY>ZAhwdQ*K??fCTK#)>0yIA#{gOnw8R&2 z>I9Vp6L#wAq9E)gQ6XLU4tf#D@LEaEGR>!uv8gp7lhWzw8DW(hVrdt?f(n95DC`NM zjCC}UTO~j7P?zCk3gU+YOX{}FK*ha;=SRie^I$$sUCUai`FEGr&khfCEM;F^4i?*A zre-f#Jwil3Sx^#@phMsx+@;Q37p{8Pkl!f*zdu}oAKud3@Yf&LLqqRaOzf|5b!wE8 zID`3Zq`_!x_dj2>vZuy=#ZMP)1Q%1t?>8n0$b8svT6tKoWZnB zS@c`u@oj3|eBy2OE? zeU{R0=Bf)OH--Z$ljFd&7{GPvNmMt=(cs|5Av8KYicbJ!Xh?`eBfWWjP!eb&Y17Z# z?td)7dJ9dFs^Mt?SL66Z^0I$b=uN%63(i9^7YH)Je1dQ&O}C}}0Ml_C|0v5i#-;R5 zYKS|mO^;rx*b`tT_g=S$Cz^-XD*7^(JshmQh_4)~&&-zkECZ-CAV4tBS@Ni_)Jx!q zQ!S_Sz*L`FbxjU&#-o0B*qUb`svv|0C_tcmc(KtX;=~F(rf(T$elgRAf@_1Xw_x7$ zO4CV;fu+^bylN~yH`B)RS&6n33%k?r6%S@ey) z!y3whnI(|#v472wj{yy}*~-L|3<|71_?*X-_}uc6%~0$DUDW9DQdEh7qvnqPeyW@L zk;(~KGRHkK;Y*VT`1*E{gnoaGlf=|^kjxr`r|QpQ%f37s=-N^aJ{bAPh4Gcv>7tNJ z&mekJ19Kek^g|R~-<%jTL@x*OquUY|e{_?ozIK4DNuuNmM|jLRN`KLdFb14BgY^G6 zOK3j~fTTts8R)7pAaTEqC?^#zFs*~P_yaRebL}i01s-r3As15l&niML`oKSOXZssv zZ9#HN44vRQ&xoOETgEj%Rr&Jx*r&>H^_rU{y~J~8V=sBvz8U8PWcV{ck3|x64JUY? zoLSZP_A*A08dU*$c_=y_Dh@{V%t*I%(=jo&ot?HaR)50V~%nmW@O$DQa4XD@%usDU!7)bpJ;T^p%+5GV!FH+*Z7(z&qeCFJ@OVdA6-BUg96_8=N z4uS@e2}5r94w+uN(OwSE%37Kk3zaarXMh9A+U;?We*Ng@8p^F@1;BK2e>^%mw*#R8 zr*G2;I34rxlG*ki%I+??-||1M^(R!HP*q4+S7#ke>Fo!<=Ixz7qsH zmntGx55L!+cs1%}2*zEjBzVMl&n4`Yh|l&#PP}uy z@D|;8Py)hRl3?Y^D_JJf#M_-xU9vgo7Qwp624If1_u5vH#LPZ%0(Tbm@O}Kzj4uO2 zv@?*0GoXJ+Q3pRPSw8&0A6r&jPYHh-*jEA9cX!gwA%q1jguy>~7Iy&IbT|I9o%bt~ z?%7ibvng@BP5;3bYE-Pm@HS3IR=Q{3bTKEj;82~uE+}428xY!*7YNZq_Xiv`dDHh{ z4N|0j93pdv{11P+-zk0}g9@Or2(eWM zsd`2HssqMnxn-ScE!X+k7u3ZHiS22%v#~YAYyCua^GjEAVDt2B0@lFIUgk@~%i%gz zf1Y3kcK`GCT=L0#3VY0}n2#^2isx(LRU~T~C-7r_S=|Mxwite!ui$G(plA(^{X%cc z_%pp7Cd1(t8`HX)$-TC6Zl;XSD7;zTxXEF3_LOl7D(oT~=nE?8qj?dJ*_&+;#mt}N z1a0o=p;}>teVAx=gXeB6c};TGbO*E2#oMWuN&Z#7c?qZ8s!zdyhIsI{djR;!lX$bI z=pbr{2{s}G{ohc2?%vp3zY(dL?#<`FU#dyhj7~Qacp!{No4#gpI#e|rtp@ixG29s$ zTRD?v)K;*S@he<#tn_ct1q{wd2w=C%@v8%|l1|Ulu>m>X+Z;j_TY3eNiw<7VP*>>! z#uaGh*0M)~NG3{%ON}{_(q|>1Cl$ZnGW7DZ8Q|$sVWbs%Gt<`|^#K6fT^_L<3hbqy ztC!65cPv*ihe(YEEP;z<5teYGp}GfRO@LX}Iz1Qow?DzFKzj`XL-#OH4>x8@Xb=PQ zD)07MZJ8&xQtfB@3(gsH^#4AeL2&5$qb#*i}Wfx?81Jc*q=G zKTK3z0RT-zm9rt|I>Su>vkKGjY^B_GsCPx_pONgz4IwS;lJH=2=FHg6_~Fk|940si zc2mGBEBrtJ3AP^&nEita)Ag(E|PP$V9$&Y@ZhkP17x%NsxMi zTB7%JFx$egJJ4ID&zuBCt+#j)zzY80_16PO8Q$sX*u)r%Cy&tKuYmv`y+1R+0U>ak z6haNA!x34~4a+?u%TKlHm4PE?8x@s5D&R)O{N_o^iH z9jf2vQW_|hGIF`DQ)X($^&zq8q$PT;Y1l0?2*79qjU*ikqtJxwGS&MM!g);(r2szN7ikp}%SBG;&(7fT0ck>F>;09tsQ;|ts3HtzNB zpDqhr(8$}l{E+uh0Zw_ZWuo)8I7Zf9;Pd`)F2z5G*s02s z^meY~sLy?Ee<}4(yK(IedFB5%Iy1-rMQ3JYWMF3b-{{PYjBE@H|4%xzjT^AN$##d0 zb*b_7n%HPdOl-aJrrN0Fe?ZM_+-GZS`nkVbPPX0ZwQ9>1@Wv}RyJ>}L)1q=Twq}=A z7l!bEO3X|R4*mzu+{nNPn1-RTKQ=Ck6A(Is=GsyaI`iLfW{^CfCUAyEfFGf>{V_ly z*B884G}DtA04n1PzeoTVD`8}4Y-n-+j_l^_%8+_a|JCJX)w$*IkpB6Q-2Gdk|FD^@ z;Xu-~G=Kq#pdz)D9*_X2{)f$sc4lr4tKiJo(82&VriB4)lkL9*pv*1q|J;l0U!Pqa zG2F|+$@nGQw}N_h_LZ7eUYHFlASa_Lp(Ch=N4@wi5aq6a9nz-FkWUa~lpAn~rH<^zZ1E0VqRrZGiDdnw?TxnHylVcan_m z<=5hy^yn!S-~XaEbO``C?_9qrs=2u<9~MD?)X2>E_5j8iWNbYh0M`a^!j&zw9QdR_lG?MJu49;wwHJcB}uF4Kxk@5X|?-^Dn2N#e{_AlbsEzR%vFC!Ad85~Qfwss5iza6-Y1sv@oDs>ud zSW$L1n?j+kDVT2hMbCm*GX@L${BCbwx9ae;i!ebNB*Vcb=Wa@e4H08BC=rgFj2L3r zCEXz(dO}L(yP91O)p7Sy$fd4O+2I<-q_EC+mxG+PKD0_v`k%=$zUmZLihbd~2C+;O zHn%|{>yg^JZLNRvR*FTWfA1pzwu-BT(*IdWds&d&e;UEiQm~tX>_uY>?Q-IK486R^k}`VXqOe2(fz$ z+jQOKaH{ijSxKIEQ`>}o+C1KJ?1lOH#pqWbp-0`$7%;P$Kc?lQ^dQ`#S*_Jbd8>?> zP4d}2xm730O8wwO`>b=*Q%BwlLKL)zCN>nEFo_>D6~Q&Xl*n6T?q*7wZ{<3%CpHpq ziMw00f~XYM5A*lHM&Il+f$~TGdDp(PFM z8qTr_e01`b$*U@X+mf_Hc4e3f-`mB*f92H1?hoAn58qMenJ+a~RN|J|A1IAD&E2M{ z(cCO}MZOW-Fb@Jaze_bm(k0PfV+H>7x&VVJP}q?kvi2?vUU4qY`Bf^<&qWNbg$G~? zK2<$j>X7CZN7pHiOwWif?JRj5?-%YHYhJ$p>;0TPEq92uw8I(JcOg(`-Z6MO(pEVjmkOO2tk6nG;Em2N z8(ZBBlH1$y3YrQ%s}HKwLlpjK%t);f)lW0ZXysPr$j>my7yB*460QZ)Qg<9zMSV14 z7Yp;dPtfmyEi?g{$Em)M4rEnE(OlogxS3=y##GL1Vi37tUW241=%)BPP@q}fyOY@A zuL9)A#nQ?qYO{j^dwF|8XHz-fAfSq25*w`Yi`98+C!5&0$H^vn#0t0p7yt5+ zRTFG)W<@ZWmbTo?u$QRV%J1W_Dl5~_13T!v!sg35vsTF;Fb*60y4I=f8C1GXqJ48K zsn5L5d(XB0_vX$IJ5vi^0vh~1@{d{d z9u8z&e6#qG2-CA;t=4@p8g~}?RBZI!i^i#4>p52csqi1{zxOK{NlM4TqoRHi2i7xG zwv-EYpYY~6tTv(lpsVcj>?w!yMM&tl{Gx>4`{+%lvn-X(N+?*o#(IWz;#pNtU|0JC zo{nlSRe;e^}BL<`ESEgIb{%M-{$*k8!d|?iE(Q7D)!(v~*06RnPjGVH|liH(+ok}S7 zbKbhtJ`9@xHDs@|K~3`uLaFRcBqd%Dt3LvbZG(*@IlH|PUY@~;-Qy>|o_0bPYbXZ0 zbNfhhj$#Bjc8HK*;D2PU507?_u4%#W1;g#D7T+fZz;MK5Arq2vu!D)=kp@L7ccqdy zBbJ78iz7}V$Js{hUO*l(J;#ce{-E$Hapgv6qFbZ;_0z(~++?r93jfrFzP?6wFNP~z z!H+Q8R^Gd=Qt278d84x1IFOv?oRch{01$ z!cZM2GakzwH*aumg3l9xS~vzT-mGjM(;`&SQ{m%i9#JiHUp*`a7SsbHGSb?}JM+$- z|GD_kzx<5AR`{z0Cu(wzOJ`RP?#`;cjFh#G*#d(|TIi|pK);HZ9>rsjRu)SXnc}$) zW0Fe{2Bsg=Iol5%K3b)*g0y@(w^z+-O3l_ryV%#@(oVhPo?!tGvgw}l_a;oz9(xRl zCZr}!?~dp0${PZ|*&2%fQ9cFfiJl-8QMl)_EWgX^s|nA>ho#_)H4(WrIthoKR^v3F z=Ka$3K|?+EhgM+FxhKE%aGt@m3*Tbq@+F#I$NQzKp@gNbdSTVZsk+Z)5AP0c)y~DJ z41ji{j)>VeBgN(7{s2i=rFgLn(Idg2NuYh7PZ${D)Lhy^+`SjFRW+po-$$S!lB`+F zo~W7gvBoV*J!3#;O{hb~nk|`U}DN=UkR$Rf7cDOPuQD zG5cbU?JFmjZmsC43AEM`!yrn0DJ(bH(^E6XNFCkH@ zIeYL$dhxnf{gV#)sDduDA4%NFP$L4Or-Q^?VywgaUf>EkL`k6n3WyMHMB%TAh{Ffz z5%pG+Yib0+Y}~?e-K(xC=;L{2{0=oP=jV&$dTR1OeQdAamFrWG2}FbQ-8^HUGO~e#SayUXW+bDeJ)VgPCBe)D^ar&Ks zQS-~7s+3SOPD@jCbaN{QmGA8)HvG-F`Ejd9!0{~_bQPZniHdv;;}@pWNf||RDvsi! zJ!jdQfB-GTd9=L{l^eSO1!|a`%g%s!!8IyF@x~iW@#>?S)*Hm4C8I z>$^e`!SDOgrZq2H)B@gug__t7rN z=L>R;0SGuG6N=wJk(?(wCy%y=QNdIQ6SrWBozugI?F`8HQsyCQ}G_OylKnL?u@ zL=d}LK+f{eNA-=xcKgK!Qg)A}UvXPiT`2RW8@B$+=nVtX9y!mfv+k4SW?mqZkPU_@ zn#0`&P1y$}F3f%2V@KYlMIBx@!&)(~fD! zVT*W+VE55Qpx&iSR;4R?E2!J$44B@&i&ki=DUxy@dp>de`BdE9C3hQFaV|@!_qaj$ z?w94r*|0mT`_A^;3?5%e@&L79gJMba#kZ_-Uacw~#m$?cr+~qP{9|y=01L>zCUgL? zxQ)AJ_kKVX;B&qaQ%125$1W>`P+j8MK-tQA)?SL$Nw4Oj>X_i!uS5c zJ<|Ch$=>2i>hMME&217M$IhYX>dxbVJqbi}NZ+9%i4Q(l0=cPPx%NE>JZ$kW~YH6M;2NWMph{BHU+Q zaXL5`pX_3humz=)tS8$+Nnz4XiDTEL3qNh=$3}LBYeh+%u&cNCVT$5#7AJKK^P#wG z>|_yqJk^W;vBZ>S4CT=UUdJY)M=DV&wC=+MyOmoR7Ay~h)M8mCt9HKV<^wjs$h(Vm z*&zl5lPMr(zzKKFcT3R?Ss`gk{dFu~9%-UGxo7iA*y&CKVkp_7w0T@nleeS(ro42L zz@mxS4d&fq<0)8W+h9~fJ`WwUvH{5}5*9s8W8(#$%;H##?i|k>)PG5CjF;Ck$D)73}vqyFk<*&8&%GmfhZOWTag`*8q8~$Vu#$BgPGzHJyA12!5E{5W`*=w zmV2oq3bz3IuQ`=!2MO)&bczW;sXTfKyDvUTAa@2}Ca4vOZBgZs0+sWT5RIk^RTC&& zl`s0RD%oUqZJ?~E&_CHMmTE)0F7WzR*{7eSoc=D^>X|^UPvwv$O=L75(RFLrL2STQ zfIg@*p~hmgo1Z5f$TFX^Su>ihnvzZ(B&FUC!WT62ifH6_E^Ni_c?K)3>GP*Xp(Qj* zb{vEb4UA*&ZIssXl)DzqAB5eA>(Owhj67ipyg#tQBh+W-!GLkt&ua@Vv}&cSq_pi& zgqNvrD!2(3{dyZpv0Jr|6+{k5$VKwkmt1*ACYn{8(9Sg28-B`SSGy(Mi>9_CMY5Kj zW??4y1?l%-k~J#+$*%OGBPVH=>UZfp1rY|?to$AkbhQU-INNahWoP581m^fEPQuNz ztVhC6N~egY*ze?$6mEDe(Jm}92fCUlqd3^H9>&BA;K_X00&tIJ!hKi6n$^0qi4&Uj zVW4!PA_19yY~83aA*?HbsQzmN*3F%LVqqn0Vqwrd`8?fqU<&(`G3hNoQ#?E`2ywwl z2+O2UD91%KoO<)-Bx3VX=-4KWD$;nd^XJ=aT~+xV>AjSH{mF5g{-9{H8$H}`GOxJ+ zYEYZ60`=9q&>)1XsbD9IU#>fY$15wd8&&CH2BzT;rvay*HC}1D$7mn2UiF(9-Xu%> zPZm2RbPdjh$El|Elz*0rhafqu3}7(|uk*i(NlYn{e?RXOsdk66gEqaCS!CR(^A-t; zhdEAE1-9=Io)??SC$q|x7jDfuiamjs@Gw_hXyR`Ma!D?Ry5a=p1_`*EP6*C)*cyzk zx4UCu@zda+b1?PcRrupXQ_SveqlgH$|q0Ni;%@!CpQM!n8yCcDLa0wrX+)%zMIgD#$ zE2hEo++^bZ67b$s;`_71yar4oD-KE{V<%s1p2+U^2V&y0?`B$vq1y9uz$!z4ns~uy ztaMa*kFqr$yn25W(_D+)9{3zywATy;wm>r1MABlK0EcOQ&OY|}CIpY;JuS6( z#}*(}YmS+d)B?(D?sNHmf+wB%UmZGt*L#kQh^Ko3iTu=xH!(cS|pCCcbFw#Fag-E<X~<*CAMSq@%rv-yX9N2I8ZNmfh$S zaJiv-1$#4s$xi08m?xq5!q-&(Vot~_+%XqC;{*0w67Tzf%gX}NKhEX^I|fy7UW&d* z)te$PY0(79D@X@|%zHtMT>3>7Y?u_8v$u73L!8|rT~Lu}p`X*(T4PzWtPON7iV9=A z`uEP%KLi{j*=Ei@4-i`tKex>3hhl@a$SR!7bcbSC2wU|Sb3k?fj*6(a@PWt^wN2${ zkULrX+$ZAUBgt+{kl)3xoZPTRTpx8PrB}3K!$Wx~UTQrU+;Sc;uw#vl@SpA2S+k=0 z6c{<_K>;_VThW}`V(p3odmfR3sk-T@~uC|xVKUwn7i5*LEQv3A95DHl6(>l$>=v*Tm1-s;Sirvud=PGp7g43&G4o*XpM<4YVQ4bV&UP%AI6|yPr2*gf7Y{+ zsl5rcp;)<0DS~jtIpgG0HZyX3%49+Au0{#3H;c3HO?Y{|7M;`D_9P8Ng*9rNXlHNU z5ES%z-;kyk_X8cK0XBl>7ri+Xz4(-L^Fsecr(O16jGg0hE=+(1W7|048=u(DiEZ1q zZQHhO+qP}n)_xbTRlCIg^?Fw8^7&l0^g!<(82Jzwq83co{?F9W?m0dbYB|Z$c z*x>Ug3b$)}Da|a0Nm4e6QdXuIwZpCG^?*sBgdVF2^? z-cJ5rd}6Y5=d8FWvWV5CVAitC)TS^+9<%ULNis>QNz5}%aYu=Hrb0{CTG_hJC_}jy z#5&_R*NWKc*qkc9jnl$z6U1$=FXWBnrR|n!%-Rup-V{&O-wRJF@`nh+TPkCPPS7V6 zF3+1^d8^5;kv<+BAFul7%Bv1BdYw+z3q2%tX`us|sV;FO{$H4{5^N$igh`V!3FJuZ z&1w?xh>@u5cbWFG=%;2b50h(cmo2ZPrz{8zXtK;H_FIqJC|m-9$TU0}tp`xsokn;mXr_Cvv1@;x~M znWL2qA^9{q6tb$FMw+>D*Co5V%H{rTC8qa8fB~N%j7EgVx7tgVz_pj#-#cXR6+-B- zbIL_8o)`%gZKblP2O?6o>3YXFK^2!XEc%oYSlneGVctiZaHg2u$9i&YE=y7uc-0f$ z;*wNV5wR-69w=uZ)x_z3h^p1^PHQOE9yRf05n5nr?j)KHX%mrvl&PI~bF}vkX~ZKE z;rC1mJp1^8<`Q@G-$^HMR`k;)M$?s7sl%+$RE{RdQ;&lKh{_XeH+a$x;2(JO?w0`eF63<+S8QGIYB_^1aEG+! zBKDzU4EA9lz1gjyAobD)s7H)8-OL(mLmdpGF2Y&o9|)aYnf0yVK{($JYlv>OA0mPs zTe_$zj3P9&gU|G<*kLO;Sb@^%cVMIP&=u^Z`#D17uzTxf(Qk^;cMrDo{^iZdPp4MC?6Iax?gC9?xDBfXHhznafWngUtFwsi6bMQYdgRoWOKQ~C_3njAk(Qr=e zgrw&NTY6Qxa!aCcrQXx4+eCfYK{0sB2@a_gSu^6pNl(yt$^0d8cgr@qqosV?pe(n5 z10zo5Znki#JSeL1SE)N`Zl^qb^rW&#vi59Ad$vZ8cO{{y6O1H}a-FvW6HH-e*&FcK z%16FBKb4|{P^0tSxBxklm)@=w(I-8fm8A{4WS4;vn}ZRhOME9S{7Ne4*p>AVrBFvn z;HqL5o<#2!Z$Ya60R_0>cf8k{pXpLhMAz!&#SDOXmniY~ukR!}w(Rzh#!J+A@_v22 z5C-@JQee~1LDP%=RR2qtCgXO;fSWhaY0A-G<&}IEKs^0U6i>}KeEs$I6rF2;@P%G` zY84l?yD(&x?%q$=K2p7udrToV$`}-R9sP6*aYiN6l#=i!khdV-9W(@JhOrxF7Jx*(Dh9x1aqk<>lJNOOtXL50e2Cn$_9fcs{lt?M+BASW}?}<#g1cPN+Yw4~rPi z{AZ@y5W&#RP|~mLbFk4*4}EsQ&+pFTS_Qu)AD3TQCX@04KRTqFTJS=4g(w#=^U31Y z7F4&cKICrF!AyHs8ukR|2|)PX@PMVsaI{3a8WOy9H%-BL`WX?10mO-$c*oHq=osyq7q5&2iko5#K*BbDt(t!K-v+5{E2p=-s91jO{_(zI2C`Y%jE! zM>@`MXiZ~Te_#2X3eQ?lV&xa4r%oX~_0RPqYaz~G0uvM%I0_=6q9Z6+m=`qD@{^Rj zjbHdJ#*_=nV0ZGb?KO6cLDKtCH4;K#r@!SF2pXsikhveLLMD*aNweFF*Y^>l9j};) z%LEqf27DZde45QtDOv@~YrJx_B>WhiWb++7Hj1}5cAc2qqeckCG|_~)qbt@R$Jjer zJQQ*?f{H8KFi*c(z9KQC)ox9 z{PFPxZkI5Ul*JYqAVClWqkV!7zTLVJ8!9H8_cVH-VZOUmJz6I9SInI_@doHIOrTuMW10uj=*OQ6VSWR zP+U##m5k0rQ*y#R!V0X5PM)|l03%aF6F7H2#$p{$LKkS4=_p`Oe;{`LbSgrY9mXl@ z&JfcP*j47k!bGV`S1|Cl#?WUo{TO+uSIgRw6uE^W5;0ur50)3r*SuQtCvcjfw6iT) znVlZKwb@=_yazr#eGHzF^2zn1mmI1~G$5|csfSO(TJ7ZYbAaq|5J`md9NbDPeJQ&} zA>)}ty#cG@h6BSt?>h|rFQ;3j8f#QZ5$y}ZRF6H+McRP75Ev8{EaoeQ`;0ga1IN}N zeMB{hmQ;3h6L;ygW|O(*|9u@_P+Q4z8@1W@ZTHqkIz3H5&&SoX9T@J}=DG z`xH#*ug}mv7An22kF>4K)D1Iq(|LNRbK4JqgmB&lkl_k+?NnzUVB(L)(A}>mnk9pt z+jJj_>}_1kch@iJicN15lKwwKLTf+9~ShM&E=Q4sONGN*KfT1n@X2`;sw{ zJe@Ar%y&Z1Yf;s+Ty-EFLVR7Z|3hAeDVog>YlG}iZ;J;<8xaMa!5U=%5=I&XT>Wb; zi%$h#^3v*g4*rRg)lVe|y1L&4@bd7_i&w=1Tu)lA;Tt})+b%U`Vt_4!=ky4P?#t&UUPDZV(V@0X_c*@b``w@QRZ?Q$8X7O_e|MGU|%+8pm(Hf zY+!seP3~c&-vNHxz_yLONlr;IPknd9XNRPJ7^e}T_$b9pr7b{rcC3Z6-_`W(x>ew4 zi5|zwgT7X6 zDJy{U%3VOTM&vq4FmQw}>at6ot{5-nrgodoQGNQvQ!=1#bd4rr0a_)Kdf~kwp9>(J zaU3Y_aGUn>G8-%>#JENgid;?k~UB z+jZATTP;h^ych@a?U?=#_H`|lSf|g!qkT=0bcvNJ-~L^_h0FZ%C-p9~gx(;DeO3C}RemTfd!ys^$Bx&yc5mf?3t$zI{Wx z&zav-6riFx=6xJyCifG z$LX#0hG28X{&*Q>^_TJeLK}iun@HxC$qW=D9=eIVHp4uMTXAnMF~OwAyt;1qsQb;) zO4dS`Jv}>wwxK_Pq=GIyclH7_5VU+Q8^;D==hX80ARBZaJdoi1$)RpO3SVQ5zNuk8 za^J$5BOpW;Gex9nsv_uo$>>xG6x7K0gQ^4)-)#x*HS&-7{#dm#jHRK~Ef6+keWuTv)^ZN)nh0{jdh-ulVCg1Y=Q&#`!EoZd!%BgEfa@LT9HgHveYu~);vss_ zn3ZGwFx2@WYojNl!J@<`fP>p$Cq6w2nW;BhvAN1X6`+fExDtxuRNe7a0fZF~EO(|R zd~}-K%>5gQ#?U^r9`y$4Bp=R1iXgKcbljGwr2ehBZXtG2h$Toa^WhLFV~UQz^s8;_ ze!Wd52mIeiLPK4*`sBTUN7f(BOXe}gR?D!Pf*naV8Ur5G16*-K?N1^K>9`1Nu25`V zt-OOUrEHZ@BX-w0!wzVC6s*51_YAI4a^*W?h1Q66olB{-$AYZmf7rnDfM((zIl>uT zGRkqB5Gk~{e`+Ly)umK`=s{eUcBX^|g1X`TN%vb|cBeG9iRG=^^s&wx@ z&QEdZ4I<`-?6wyr|9?YP{84a%3kc`EvJ=8!1npN5nxlnjM5(55gFPJx1A{o2cpM>| zo#M}Xw%be%xHo$S1olMTi2g0(tm`#?UB!_lkQP+q(wZn{wGU1azoIiSK|K_;a*#38pn~{ly z<^RiZyBRteUoTi+#Z2RE{>N^w+q+n8wk+0H$5=N8-eBQzotN3>zIvT{9q!nVelS&9 ztazAAm-(`N#LHw5u7tt>`9M3;NVGG>s!sHMtf!-PP z0l3K@1IRfK)h`*oZ)9K~;vY1UtJ8x^eSL!q=v><3Pa>GvdZxx2`&t`N)1PZR9;>Np zU=VzKd}92X8!6fw0V&`Aej5MzWwIdYnHwU4h5fBOo1hX0H7iPH2447wG&j72pLbwm zVrz&XSH}Pupyl5LBq@sN_uUKX*A5sPIML0}O8-FydI0KZ`$ji8KR5%DOIkuoR!~_0 z5{qE63@6__YWv1q&-}qm|Hk}oy*PNb9SZ83fT^ov za0N{RuD1FIHTC--jbU^SwfEt=F|d8kSKJ$*^?Lz2_w^iyp$FXbHR;mYs>n`AHD+pE^yKK!{((H{0;tbz($$Vg%MK z-{A0N)k0G7vlrt#aTVg{QwPl-gY^dC_XhIk`S3PcgFWD?`}cJ0Kakszu(6`1CZmP+ z+ZS^$w}E7A>%VG@5xAV|=VftuiD zsz=?|H1%J0xG z^?xKcIJ4-Qnj`ZmV&k+`Y#B@(wR%}diEbLxe37mpxNh!s=Za_}c6|#yZ`V-oVjtau z5OD?~E9zGFT70)9fJqvR7*BR~C|(4+X1_NnUR4u(>DNv9`=gU`;tWOtcD7#&`hxRg zg~rnnAQWs90%+Z<(wS)&K$6a2nJH?pM8bJCU3fi)jAO1QV)2OCAxE*x?Llzv=j?i$ zka{z=1to5vaKb##K$%_ZXro#?r&p+T+AM+c(;hXtrS|_l2+|R3ba({&ZboI$ZjXHp z*1O5W?V9Wplhm#K;&JTi<{^w)Y*q44>D-WRTW{Q?Nv}8B9kajzh1tmDaE=j&nZ}Q$ z`E9y{sQ?(`Xplo$I3b+y*L5`)2Bm!1T#=S@-yzh8Pa=g#fAf-?(CsDeb)5eV84E2KKiZo&HHtG*7@YVrBVgHz&B?@Uvp}`Xew>-JhyV97`W41kAGPu#5RhVo7$ebbsOg6!Rkhfz}la44Eonx z&D?}kC*q?~lH~+ios6kFNWWEh2T+)%go4G=@wZHC5j&ID66*3M?=MLlj_K=&B8vyq z9xt}6EZ?uzf2{+S`s{f41u`!du>Mk(ks)JUL9YKorB12iF^NSsR5XG2((^S4T4SH`z)1}LmO-369m@Wf{tB>?1R-iF1Fs2iev#=eRXy!}WLh}wap1oQ z*nH9eQHAB}3ql&aOT%UiZ+L70L*h8;yJQ`HWWZ^e;}X}jXWlgK+jzO`9m{#D4aG1_ zGPmk#s-AoY!ftrCSg@xC%$j9Nyb>F2duJHUj^}2$%z%5Jb8NNs{-yio7^_I)2c8^r z-Y68l9_i{a(vh!krY@&2A{}K%y)3``q;?kxpGi8xeiS%~Bd`>*hf_ubo5PrnHu*vNq z8X{?+y!kR1RoH&PrB8oCnccZ88-KYS2G$-~lh{m0p!U(_s++?G(#=V|Dd*?lVMTE% z8q@0NwP?OgQO%@MHR{CbndqPzy!Yfg!SK~k+eokCZg$Y>714tM?VgrHr#S^g0tIO? z=8RGlsxDGFv;_iX6XsY7P63p(!1#+TxlaU56x(7hA%HcgSh6ipoQEI9FhJN|6xF`y zF#5OX1qN|)u7<-n`H5KR8e^8oPUj-Zm^ zxa=)6DjcPlK@EEsSL1=o;+h}lw87}zSM1K>{Jw#Ndfgt*f8P}A4M;4A$sEyh%P#Su z`}S8jfx{glW6)l20zX_#W$u*a16W$h!dmCF!(>hs%T5vmJM%vL`^b)>i3ew;qrWHHi$CTRQ zN&FNRuSd(C*_ppuxvnQdoy~F*Z?b8N1tE760n8GvJ^yvKv@xaO?4+zSB5P_ARB7f< zn~9D+MfnnN7DDMzrR|PK#-U;bOil#m?F{Ehy|tMNL=?i5jpea$v_86u`7+~*p;}rbP!EyWr4A`r@#oL2+JCsMr;jqy9 zZKTetHx0S^@dd&S3Z9GLnCL7z^U$1-=doOc6(LbO9XTl``rur&v9&lX@&*$$(w+|N zbh1?qLx0}y8{YM0W_yIUN@8H@2cXepoVfmcD-YqV5GcUE2FX*|8xIbSK5dVe1c_10 zJ6%pb4MFp@qbuQ*Rzb}3Ht!OzxWDuNuFngyl*jt~5x>o*4F~7mjz0A8+)B}1*myb` zfsJf;$Ip4h<#>GR_p@*4&le6WzTP=OnACvyRYdh2Tr16aM6E)cPB)P>;1$$0lV6v# z^`qCG(igK zZQJtKTxgG%E?4fFiqh*6WGK^+lW+U`;$Bf}lB#eNB1x-e$XNJ0%m~k{i-LpW{5$4A z#oK#DJ#BX0p+%SQ?F5z}uo0B8V*826a7}AFmZBb6x4~Hjp$NjHiL+4-5KH!2D8OQMB3;7X*jd*tN%$ zu1p6l>})Wcg|r7)768(Mv8kQHyWzM?X1>DJgm@_ipSu0Xz@hV;LD_0M?@x$TaO27l z_WUe$C&E75n09{#$pFpv`_XWrtGo~AWq#|%A#ECgB*Qibt>4&hkVfo3AamsXGDyRy z>bh~UZqGX~;g_ zLkrxL^)aMMTLv?!i@AfP@~p$2@_!_g^fJkEZnC_&f;3NxT{|~NkZsqh6b1_s`uKeN z`b-6B%p}uQ&J0TG`Nw_MO)ar$lv>jlH9bZyG>DlydTm&SillVKPp#<66L1Vs6+>eo z5J;?WVh1yssAXAMMSCk^97}*no zP4;wygNVM)^ar0zcgU2yuw}w>Bx#FapGU>Ivp~%3LTU@kbH-9sY0D%b?k6BovDq6P zCpy1_Xx`A}P9;eL7Kik=_Y=a{@S=o^g&pt&wQ@l0&q7<)TUPLQ0b;APGog^u@HbqN zgaxhBe`We70rhv$I*+G4n*X8WQA|iH5aSx6w;HF@SSZg;^l+zxz`HV1RNqB;Ao<~? z&LQ*^AQt^VR~`3oSeTm?!2Mw!o9ZNXb-PEdImVyP56L|aLxeOO!P3|C8c}nTR#vfL zs&F-a%=^G8FT`~}vKSYS4PcS64Wy^b^E${5wdjhNHE!h5P8+w^TCRTgV_U-oG)9!- z{Ujv9?Z$hcp3tPCC+zYk*7x`&*5f3+Y$21c86>^lUF3!J_6=VZ7;*I)N1r#?5}l1~MH8(}F7BS-)@92^Dn z_7*XZR=v95kU#&8RlhgeeW1tpRC>mJl-hcIKFRxB(@Q2|h4prGc64z&_4eDp*c7mK zX}5t|)eaUM+zCyAyWZthkRtPPnp?_uc1-HnB}_!Z6$#xDwax(U5!M+xp(b{i_8)Q) zUVqP|dc5t(vD-d_F*IZ_t!oe&H=_#-5C1?9#B|%YV{PUWk;^1MV60>5+P?}*b{B;& z-yi?Td`$bh7Fu>gfwS!RQ@uz}cC8#3S#@Z%BQ?_^TsJlju-->ls0Yudbb(GPcuB9&|LE#S zk49_ZE`IC&yEh6Dc3f6VUd~FM*w!CJuOT1FV#+`F`Ejff$s0 z$~tkdS2RRMMaxenq8VlD-mQeHEW?jR%`VIm-q$gHaw&R3sA$>j6W~I07k}RUq0BMW z)wqz5S%OYUS(f4zf2fW2a7E)2@D9`!dB%A4# zRt^_%&@$|lZNNsC#+HBxxO0xR>iZC4Uy;mq6Ns*yMn*^EPSVpBzuWobcKMjD@pYsp z&j%pvB)#N{FFnn*KrO1&#S3rCYtaG{In#B4TNFyDReRt?`;(zEeI3{FM1oU4j_6R1 zeQCuTyK;I2WURm_MhWJ7y3uv*@2ebx9Od%lxieh2dT*af3v=i;WMo$slk5jm=NE#z z63N=X*2-IPIOCiMC+FDM*+P3t@ZE%@+|sCm^+q>{vLol`QA%I`1;L#?>Z3ZWU`|#+ zIP&k8cCnZsJy@PnVN9`s4Pr0cBFc|AT;bcYQrIdaHa4ui6nnxtGIO$kfqYH8^a3;@Ai=gOe= zK7YzBFygx2tC+?8LCslbwTw@P`Y5*TyEN$TpZEN9UxSbj=`|z9FPh9(9|le4SoTZ# znkx!X>H3Z!O06kvR=;AEG-MAU<-?(7Eb#()i1ma9*Gu@)4V4h>tH^|6<@t8J*$~q( zAg~IG(pH%Mw9fiwFHm1`dGIT@;yh4b5m zsTgFNKewOC5Z=a9M3I&>BRBJIii&KnJAbbWeQW(@q%~9;Q(;w}$vOS;OEXH-KLpj{ zftqFau891Wxb1_IhkT#%d18{oT#F{Mb;(3NSkQWVd@7H(2B*Q9vwjt$Gnpn`L{COO zHiCb)fR9kE{pd6YfP-ICAX>*Fi1M^+DIVkTH8Ws`6v~KNf4s%A;AsJ`HzwC*G z)}c>bE|ZV3=mJfnwux1icgLCcvgp(Als058Q3LucmWnnK*AW^S4mlC=-TXJt4ltdA zdCRM=>55?o8pOMIBW{XzlN!Fv)G;jxq325mCpl{St7GYq1jgD*do>M5Ug}w~=?RJ1 ze!*!c2|^My68|AK|L_q#(Vo4BbV5e7{xvy%ZARyEcP(_^(tEy0u02Rn#hxs2IY5_C z#as%?zde2miqs5DUf}VH2`3*XO z6FLFiW)JbeGsdZFVI;=3aX0i1#>xiebkRx}e8Nv`U5?)|g<0NbYy)md^Js0nK*0{+ z)=4MSwAU4e>wGrGVXo_I7!j<;Y2gPx-x!MuBZ~28JPF@&djCvk#3hw-A6tav@bqkw z>XWz*UbyiGh1ijSmFD7Sn!waLw`-o-+x*ot$uee4=(ltvnF$b64qg%9VKMepw=-`nk@X}?GfuWEajxf$V?8mE$(vP(e6kSKy~+(kMyblH75 zR?iS&V@Wf)$xg*@S%}A`6sMT9ZC9emWF=w>bb^@uAFFQ!!YP1Du3R8oR)BCXRvC;QM#|JT1V9$uWH*=7<-q^-<%G}TJ?Ww^Gp1hIU#O=3xS}V=12dUzv z{j{m(nqtD^PmPwf479mT0tp7`x3#QVb?C$x4g$jRW%*%q%bLaAzmjyKO+viJuzhvYzBF}@mCA{0BJ8UOOadg%SPIG^jT@^zyhwK~KCg3%n}u0^64Vq>e$ z0Yy{?y*MvsZGJ3Z#*!5A?-pvs;Q5G+x8@=4N@I+%91N>ǜGY3T7fs&D;0TW2U zG9E71&ol*FY)0xbNAfMtw5`?`PqbZ3z7*kt)PhJjJ=jug!5KRJj;|n+Ox1z;&MQow zF{OcAE{U`04xMdv6&^z_?~Oj#b}xi$LAUuSu_e{y=QD#r;b$Vz`)I;1X9z&CL8ZbJ zKQ9*aRBNivk;evGEI5~qO5($C7y~+6s_QK6Zbz6v+M@D>KD&LN3ZEqhN=aQZSU~iz zoHfBGt#Su;C<$<+c*DLoCu|gRil*0@rD0RiaY}In=<6eVk7}|wh9INR-I^9t#C$am zexX6|!VmwTJ}pemaczl4&dG29k}W%LOTSvp6usfFao)4j_t|p2A=W?C0v-P*f3HAn z@g%B+uc-fe*B=t@<)_8lXALvfaq?ZHa?H1tTNSOT*B$Ie@tHVH4&V740r1zJY`Cs# zd3r$?7g7?QnQ!2mxFU0OK~?DtQBFt*Qb+dQYeYq2^Z?6e%MO(oRPz}`Cy zF~2SCkVT(|Sn?K$EioaenRUW}R1St^ZH1jVSfbi%-FnYlLWLj>JQ5QRI}5*)gjXwr z7BrH$DBKV`*7hqlf_6roGeY1UC*u;3k7Se$>J*Ls}?%JP1Kj$Q03YLjk`UPKxeJkOgS*a;FOa| z660nFcPJq}`=U_%pevN7!HOGF6gREik;!efs-C{ZLIyx3Zxy<|3pbj`Ko~*7-C-@n zJq}$Dl2+BzB$9&-O0->0ZodpNudFz}F&MJoLr7LGsj>|h?670_pXi7m3aY|y>RMIm zL<@REzYV?BEtIUXBOB)gKO(bp#xpk19;;xK!i6}Bo-g3Wk+ij_A)cVGevP>tY{eo% zsatc&Oqw|ld1sNA2(Ex8Pul|{MCeRzJ27WJLk5NKL8U*P8V6x$I;j-8ZQ(Mi~3s02bVzXlrPVxY-G0>E={N0qpV5#PM^-c1Z|Kpx>?|G8N}wqyoZaHa+^&5~k;*Rv9ioVQ~iyb-u&G;JYz$o{%Vn0D=@cY{GUHFr;+IC?TP@breRvV#%X`>maMOXu;dQHllbF8{_M7cLTUosaL+@k4gf-p~sQIq{U_fbH zl0I1-QjDM;JA)go8swI1C2@gg0%%Q6s@%^(Jkvg9>$#-5+Bmw%P)?g_WL5h;VX$lC z*^fN=2hAWO_I;Gg1!@)fqb?;6Qm;yby$#fJ1nQMWFmEl7RpLX@=)4vp&S6|46=!gW zdt}c~Svu;C<9G>gUH7$u!cN`%9ooqnSN=~|fVzyJQeoX=db?%6(hsuu;`^lOE`v8+ z!kQ|;UN!||rtVa>-Bbq{#0*wFp+phKv`l`W;21yhP?1p#1Ld>fnk#pxNbe@HA_br3 zYKk9;i{E^j!Xy!aX}v=;?hhgr`t`_j>DPBgc5-_vs=o~C!$ywjX$n#twf0kMuJcRz zv6&xuG~M^UOFe$hFoK2#R_$=-Q$AG#%ImEB|Z-=PNQq_j_yMpaOSukZwbv z8?wo62wmEhkkvYYStr?-82VKfQ@1a%!xRwT*!zN&SCF3}iDKgZVR0UXv)MaL^mS?fOPQg~46^h0kq{#(Dzv;79aF-Gb*r zdBQY$)-KkK=vo7yjA&N^g8L`Qe{!>m#%e5c*A!d>_>L87?fHNaq}PEe-o!U$83#_o zQ1f(?gR8FmpLiKCGTE*A`}TCt3hCLqtjwIqPg!Bm7}IZf3R6e;?}>^vc5$n5fgse4 z?7~hej($l$5wq3%WAl{S3!c((vIwn+WobgMuZt}EwqM8>P-=6}tmg!DxQ`ULU>k+9 z8+k;ow{BdsPyj!%&d8bXf3J2=JpBHsfsBk=gR!)*P4=-g<0_-9q%J=yC`nXz?xiEw z7xS3C0zqwD=MdDw_Hmst_bfU>#(@%cB*m)XaPHehk+sK6aW$4uOL7ntZSa9=xIGg6 z0#ItIGFa05t5`RTyn8o(4kCP%^TGTH5xth@?`z7>)6uR~Ra4>puA=rnH?VUKt$D2& z&Q4c2`MYCB>*n!}KN+85U1m&9QmP8dGv5pY4UF|nQ9clYDU);s`IiAZjLz5Z>o?BB z)SUyhA6kyBuG}&p5R@6GzC#Xn6O(n#u7!^SP(eqio*s8Ah**+M<01TbZUHPAU)N8f z#Jg|0N(3WgcL85L{l#Vrkbh`7L&?m>k5doI`$gm0jKnkLHe@knnIZI->>~|MG1MZadowK)YnW@TW%8o)8j?4cN0w_@r<8kj258vy@EV<*# z7#>I7)?=kfy39kN+IA$>HL1o8g8-fii4}vCXtCM=EOq0u<_>Nf};N6ZzZCZ#`xqbw4c@KwBnI!S#tE;xGU5 zV#R%~^$;M}jpxKt3=~E#;v8`bP>ubRb1kR1^aTc6)7j)N-uh7VH!-+vvVzsP9Xj)L zU^N**2tV(qS~rF(Z(80kq&98WP@3*oJiPH+RLw_DDq`#!3$i%Eh+|M8W&{y75RSr@ z{|?`0f?@AGTpEg|*Sc_7OxB{>`rQy9t4<$XiP|IK8j2-OA-&Z$ymXea^(JcTp@nhP zmr8rDF#@GSzbq{AEZ@+6m8Ys%>-4i#QJGQ45voBq;MQHZ1~kE>P$g zYZXbTSvVY)x3{wn34pZ8neGpXgZ1m`tHun|og3G>8} zl?;r$r|6!x^-_;ttsxi~87ej#3)?dOm&_H!sao4=En2G*ja#vD%n20ck?Py$ zrtF+7W+B81TGRB#MeKOsCm}*vo43<{ZQfl(C=CIoDs(JXx7^fcF18=~on0dFXTuYe zvM~}nrT)2n)O-VqHH0480rd}pL5md4hRb;kL0NJOz+g^`x_2+^9PjrPMRP*GAz2xkkx1Bw@PG{| zXt;d`i~=D}uuyx!d}KFk9Q2LPN%9N0Xcc(40@%k*tb+2^R+7kk6z*FXecT@__w`uC zcSQn7dqNz(4$*E2WtyOgc4G3FCelwgGt0r0GB6jsrvpTO6p(TeujqkIBj=}I#$vV4CBT7`UO25R zB|4nFwV?QXdAS8;8pmrA+0OeMUAqUg0MfNzEdm>`im2Uib)g-mNeat$xi!iX%=6aq z>I<8&y99HjE$0nd0HRMf-5#}~x>LUft4^hCTBAB`=!-qmzMj~2kS`{Y(rx3C1xrUV zc4jY7Z551;GBXr95Eo^;`a7!SCfN$7FcnNf%>yEF!`YXKb7zP*#&yZ2?8(QtgsSar zu6y7-M{}P@gcVigZ&E6>ZV6Egfj*1}z<%up4$IDG5{2ByhFo*hpLjEE?E#lyS0z@l z=QUp*I^j`Sh~dTfjQXspS1Q?!_0CWp9!b>@5ix7Hch-<5Cga18BibPW0~)0+=5S(< z?1blu2uAJ{IL_(GPUbf!05!>whX@ub2WK-+dX`wXgE@khU z;@M%*{=?9?AaFmIwX@JJ5QY^;o}v$-bMmOnLWpEd8JxnFc{dq%bcj54^A)?oZSmr! z1TwILav<4vu;O0>(sM7yc4cAzz&Kmui$lSYi>{5r>WC zo+z6O@eB;`Tnvh|1AV>+xYo8;QwK%(^sSkQ>K^r57>N ztM3lwLs}*fKIT&^?aoeFNCN-a-U<5~KYMvbl_<26jGWBs$g?3R&j^ST1Ac9t91kCl zhxIS05X7xx%8-xA#IxOfmKrQhy0O~Xp!^S;cM-vps=}PMG)W`#PkRDOTv54J`X!%n z*}{0Efb*(nZ&YE9^x^~)Rl`*y%u+Nep3zgob?9Dp8xv2Cykd+9UacWG^6b9msDe((#;4H*81D{ zAK`>iy?5sluGm+STeM=+5^mC8jn2P~+P>(IFiJOVpK2M?gYzl|2!1_Ez9C*<>wb&S z^@kB^t;&6P89b!l2POcCnpK-+k_y#@gvqs|q70v5#rW}A^VqVlemq&pIaL;KvO(i5 zb{)EziI|Jn|6%MLqC^YY#oD%Q+xBhSwr$(CZQHhO+qQAr-MN2~mt^n;nVmW{snJ>M ztgrUonDpl&rIy)>i5+`MuOF@XVmDq++(etZ+WwWJf#0pWr8Ry`So!zEmC(@~R=aJD zwyGz?Ek8Ljy+M=U3&{m($Q90>UKVA!AapC>H^#r+P$|rMevz zuEv!7pUsdWCedNa9kSg!P6L!Mx~PaLIg3U{dSZh+Y5}Fo&%iQ_R6CFmW0!(yYft?Z z?9o&>Xe^jOAvqHOBp>PUIy~~z_o?RZhaJk9qAeN#;;j@@PTWg1`QA*l?S%?wBg~P< z4zCJJ_e8;R4ECAo0;jcnu)H$`1Hv|%0L!L#a|YRxECQwBb?_L3aQlS zD5^meArUTr%4UYvz1&Qvcl}c7vd)#57&z14E#&pgq5N)F46}At>(eWlZ*pR@%*`de z2Phn$^Pm41(H!incJH#N5|iK$xeq6uhG9q^4KF%BX6A%?etG_g9Dret%1M zGb0jR(mVukC_wAq#fqoo{tjMHpts$vHUh83LmiUMb(DsCj51+KA~L63ABPPn1^8Wi zLN({RcrAUjXaDTvNFAHLs`gnK6?II~foJ1QqUxn4)gH)`r|!?9ooYkafYldinD{b6 zxixGZm0=iS+u_cVC~w(3qqt*5_!zHk+(JTD6Vb*x2}Di}*j%?jyb+{z>B@u{PrlPe zymeRauS!bNI}yLEmQNTsqUrinHZoxN%#$NkRHS1b+Wrt}EzM4XO_|{fOxhEHZ28KFDh6e!EVWlF?^z<}iA^=_%Ry>GkCK@#Ngw-2ZgY8v=r)Yit7i9|yhV|8mg7of{hi%R95S zHn0GWYi0u6WCySSFnf{v&-fwvNA%=Wob<79GXH4#=U~rIoZuUn%KmKy;AB)GbO7~G z@lS_Hs)XntpG6^{exGyXMmNj#TjxhcpYn4NgSUUTGd6nO8-MFt@T-!=`;EXjP*(>i zO(mlPFv{;J!NpnX^G<4HZUVRe0%vn^dCObm3(Wpq0MGv!6T13_-phPMrUmH6Xya$!-tXK_XXbO zjMnxHkV&Q4`DN6ekubw2`i;E?@N?#R>|dH%+xoi!@)k$^yIob$lM{3H%l(>X`r|{D z6xiOFSk1NLH@3fL!pM#6r6k4ehSUyq}l1c z?drGrk?*~)3=-ns8T)H!x3cbk8YC^?=>E5gJ}ZY!xk$?t@INa0Re=_qW(HP{_Tet2 zktr83f^0~J)2)v6)J`iR)<{4i92sfR#NbQXqaKuml&sHxDtgM3p4E^`J%RG0&CGEj z?XaEB;+nc|)#9A5gajW|+8g!3FscD03-!%i@Q6m#uFiXXa)BbTkks1m5PB%sXky;@U^C{B zehypR6Un2gC9`r>#}WGN(JzZOW=Z9M;2cW9`;#J7&!McLAx15%%UT5mHE>M7=|!HQfFr)xAQJ zQ~U2@FgZzu_&3(BW3VUDo<>(R>5K|@!e3@go2PS=4) zAG_+<`^IcVa+_u$VSR9^!Z|Cnk+mPZMX42yb-#3+xdf&gs>-wBwuZIeUy#%4ZYZCQ zsfTume`IYbtgQu#YhO}CLp$eU3>?}t#~IZ2BEMG_!0~TII!yB_&CK)X;`PzLW&|}6 zo)U$NqCUhfm@}-+c}9W^@+l|g^k5=_+|H%|H;iUqrYpYl_cd{nHJq9Py&o`+RG&ic z{z*FEFWlmVZ-N_(3S3C#6D|z8JzYYwzhcQKA&Z=uF`Psu?YplawE}s6!q*elgQZ_Cw4Xx%X`BvdQE9((mDKwdS3I?b$4+=f%Ct zFVHrp-k>k3atv|CeDeL<4Q`y_ybzeO=nRsS{Qhnr2w6*CYfQRo8gkcQnT#JCAT0LF z@@TPaceFU9c_@yuRYc%GjPm#)!({QK8OuMPE8{P{UKbR23Fw_rYb<-_UYjLDu6~HH zey>;9A#Sm+vzjL_k73sP!~ve+d^;E*i`Dfvu73AOz=8^m!>|rXO60w;Y3k$Jn!#Cy z-qRw~8fbBTYRKKnTJH5$G}MB+QXI-*-_mBLYbnhRA%YEVy(EPa6OesPIcW?|C<+n| z4rOs_D7Et*p(GB+f3sOjZm#V`VG+5x4i0!F)k9qKyr`)aVjqZzyqm-r*9sOLA!l}CY^}A95!py zLf-D1%24Mq<4l+Oh~s=^QY@y#y^H4SelImCCHWM2Cqg2Fc^=s-UAvn(&p2tU5L^f7wbtU?Du(0Sntiw`Lo4tE!>T5i!Em0Ya4< zDcyOvJX_GW{NMs{PWz&jO+r!m)XO0UTCB%Lm6AcbtMN$yS1L{=l+y$qt>DhqFZ1S( zx=Fl=KfkYsiFnv)j4uUbD{%yY1HB8Rg9Vrot4mrxGY2<+;Hf12l+&z}q=u-BEdUwP zbkHw_=I=>4?TX(9AK<^tu5lfp1Q7Ky4P2IfoYJ#&lVw-)SX?LGt(EtHJ1Xpx!3b*9 zMT;lm)s2er|A|hQ@Zb(#C$gx9|E>TnpqPY5B8TSMdL+Ge^^i?xSAY}!#v%Em^zqbf zS%Oo2?Kv`g5pr##hAD<;b!;3D3LiJ~wEWH1`U-Lnbp^JcNGp}$s5%+U?cnAEFhl{7 z!MmnhOA3lNm`e)tCfuBG(7Bo}$wIeILyz@mgQDoUr_%lgE?)MTKa#q1fp9CDmy*q= zUzUrMS>Pz<46;%Psl)mJl^U6+>OA5Zv|_|_+<3WIzaxXLkguRvEvi3hi*SABNj==D zA9!8#I8`O#Z(C)?D@iQ4PYl!_Z*eEv{I~#vefRleSH5jqr5*9H_76a%P8xCPe-`8X zXpRLCD!|h+3iLA2^>M^LIhzIg4#Sfq@#Mzi8uc*(9dQ)brA~fxI}5stR$Nacxyf2q zQRBf218Ntdwei)k>Q`Ps4n>5OKSu*iJYc1&hVpeyg;z}=gY}O}zs5}0TJnHq2nL`j zH<}++voe>~LIk^z(39iHK*^U@X|u!N zI7h6$DS;iHNaoWuS&IA!K5KUg{hn?{z`xvd4!puukD5+Qe;RVP2Z8di0u8I=ouo zcL8dprMro`%9Oj5 z#uUpY<&BqhM@Vd>b0yFUH+w3g`2e6*FQ_OPTY$FZ(ewuX4b|7hc>0`|W$=zVc`hDD zlwB=ua=05RRVj`qDbAfM=rUypVxp=dtPW;oO~SpUc&XK;^co(Ai4b zWz+ppt*&bvx~D<-;@pMXok2^ip-YCwtVH@iPLD`i5-2!~~0B~jF#H&UJ9l`Br+w+aKkm**^ zYNenXDR1W0j|@n~nz^O2v0i^U;eLy#<>N-{g@N|FD9aGv{JB79N-1x!c0M{+WeWVD zBC2e;+kgD$Z)%4UArZxR4N5|q(t1l6rDy@NT*BAQU^j1TB=98Svr>!3b(OFPoN;N0WII1va%cjiL6r!k zvI6N)=NMXRZSd-)cOJuSKP0F&4Gjf#Laa+6>68*K1#Hsx%!#2=DRYgWM`BSplQeyZ z6nOO;hCa^m`gD0V4U2!Lo^*J?D78Az!ItpP?WH6x?d+-8vw%@ z$}Ye&>at^p90wAHyp*c0CWX`WY1-t3bP|Yi!j(!gknKWiDNu0|{VcnDk<(x;oc4E9 zhe4;c_mHQr7@_SL^8_dWJj3RQ&u7^_-bL(21`SHhSEnds*+sHq-~GnhCVBEZw;7O= zh(JEZMJ(-e{HB#<`Hehwek9WqZY)t|=e{xk+_hsZtcSiJI$uQo;V-i`q$Wb>Ipxis zdFFMU)_i?jhv%>@O?%BWIX)8(JgLUX_a%%zu-LADtNg(>t>Ok(bGb7)PXOMZ<+?e< zHJqe^YH%-IlMpw-LTODwjXSEzp#sh7=HAkI&oP%phcq3@6sht0Q9ilO#lATK3_= z2t~SjuHM~rh7+r4nNJ`cmIquT(os8Zc(SN-n-cDYd&5$^O4e^y<5^>L9_bsqmKM-M z%CbKWKO7`m+t-99rX_4kPTtJEDffFFWSZJhjDi8yj@4JKR%gV?KKBzLy`W zQ{lP1Vv+^Ck`O->0%@L(UMFDGmC4dKyUF(}`nWh+#?M{P=IW9o zq^-mYHt%d!Iv&q9IX1wn>kQaq?DnD=#?AY7n`{CcO;)gMSzs}YoA`{z`-U8L9xNzfU8T;>|?g_&|uvp~I>X0?Eq>af%csoWkVNwfFb12{y%4bq^Pr;wtmx8k}KK z<){(=m^P+jSe}i^UZWR*g*9h|R5^_5`5gu8<)`Qa!SH|LG@{Cd4RYC%>lX6gnP7Db!Z#K$rw@X|Xoj6*ecQ*t z0khx;&5lWl{f)ding%hROu?DAaF=Pj?iKdAfc@P?8cFEdS|BoZB1|$zhN_=y;8DSA zuZuyFj42=-Lsay|tfCa$>euaoMWz)j?Vi-4c>N)D!3n-R9w}yx!U0PNBG~1GV*OL+ zC3MY7uYDtIlCPH6o6O`K!%DA4(Kb|QD#O|SjrkQ>B{$AXqaY%mVC#+^luT2B`S?7m zG`9c(_}c*qdxyzmS})5-q1j_^n<C{$++hq`|ju>O`xgnf4u&~ z%@Rvxk!^~Pt3cMF_b1pu)CE9`#Cy24isb3T;=41vBUy(?N`E;04^1Cib1}g8cIN&H zVEZU{DN&wR5GQaPNF**bth@XOdcif*2h4~8<@))Cy)7+s+jmW%yoYi}^1`XO4529! z*YN0M?!y^{!y{rMEg+#o8jA)0nEX+TV2VKRs5!;6_kz)_kVqs#3et&K!6zd0BOETLz2SjUZ<}J~Ro9-Z; zTpzg;n^81kt1xiX5yAe;5NV!9ioDVdI5#~rR5e|Mk$HkHZdf5!2#lnS4{pBwd@cvf ztk<^#TMzmg&&z!}>AyCzR0E*YOIRwB05v$9HaTR?W>e1D44X?@Ql2)x{KY*G>c$6<4GOcglNy!V ztfWF#p0qm#eoS0fEgmj5>w^kdc&+@*m|Pj@qlVX*1ny+X-vdmx23cPHQWC}^8 zOcP0t2le45b;7BEsPUGUYwaA(l77LMJnvHwR4^lSIIky3?=>4^*VCKPLfWMvwm1!Q zBxo*%r(&f#uN>#pm_ZwXxQ=v^3uV;dh|i0em@QF`E(!ND%jhAd1Rw_NFeY#+^Mggt z(jP4nf2-+*)mXf8q=Q2i{_dk^-;ZatwqeFgg+fCXSBgKDQOjSgWgE&8Wet|jSCP_c zK7+!`MzmR-)>`j+_xm+pb)!w;-M9}eZY;*I-+cfYp3pvi^9xijJm)5({WcrfKUZY% zdf;E)$TO<0Mo1Q7ur)$Rc0ckGVnye!1*#}_*YhZE&?PTHKB$M=80{kE_f{GT(-B8G9D5Xg+!&b3&N7)>~+r9Bw)PH z=FQVS-k@LF=+eUV1PNeSpaV^7NX83#oOvfovWzM9bUZ_M;!t`R-yFE2~IiXbjL<2 z+z@3ypj!p;@J9ev$(GOQ`~0&jN>K2g(XBrFU^t`kPU7b!KR!r2||A&f{D9~2T~E!(_Z z(H@b~!0XnJ>$yR`h>gC9&nb;QDgpR!3`mT@AHYswP2{TD9vbihtSte_avat_M=vqlF+sq|3xF9}+Zq8Dh@0ZDTXZU*5Yi@$ii?jwd+D5+0%u

z-hAPjun%VB^_&eB=3}4@heCBoeObBiV@9^V<*z5Bdtw$1+QJg~ zxDn=!f9@YNXh5a=3A4D!hnI)zmse~YH7{_-yjW>CV;kX#39M@(zCxVEX7ke{fxc_F z30>797}*y5-IHnh4NB^sj!+amwrtNfRDlP_dwR1gw^1QXlo!qk`C z#s%HBI_-e;-0OkrBuJ!=*zOk3mTQn-xT9Pl^T|frsb^-Vl{sNh6W zBUbXgSIPu*ikkk zo7=xQNXD(qVbP;0#mo;TNdEo?9qeAEq;(;z?3!Hkjie6wCch}z$E(z`^XTQ^y5=v- z=M&42XV|==Ib6C$i-eAgpz;j)x`S$ZE!y#wSzbZUqJN#!yz;PBbz*$r}q-y7#&c+VxAql-ePGF~J}cl<^evpbK*$^!lru3$ps6 z0j2rwXQ`gHmSbJN)Gp|GYeljXQ}4^r+yleVK5NL=8XNs0cQmk8(Klf7YC8OTybHCp zlO;2Bz`h0d=wjHF>K=zpu-k4{yW>bbM0CAn3zj1N0%`DSW739mt+UMAevM9gsmWBl zb&~@vS4`=&cK*r0>=((THZ~Z#NLN+lI$Nou1`w_#a z-CPKd9(TLfjs$k;&MM z^jk(~;nnk%2A!47+G(97WQ43=hS|0PDJ%HG~vhw6QB?1GD2<*aSv5zdrC7Zqi&o=!Y zeOXpG<*UH0&?g1US^fm+%#FP=w*ro2UinQ1Ji@JpAjRfql)|bXia%8AKSnF1_h#2F zyk>xEBI}#tRY*@lpZ8gVqL=7Jckts5c*YQ30tQ~!B;^S*$FTkCn;=N13pqziki8wk zqRtWFLyrY->|^Bk0ip%o-dXH^6c^PYT&y|52@u??+$YRimFfxT=%z{86SR7dCiIB6BG85 zA7-|w{#*kz%lPqxLM8Iv1cATig z$qGcBghqj>L>aUB!5429;pHlPcI-E{e-d+j`bN|rM?^cO=jh^vdB$zpwg-EU^pw%+ z?B+=jeX2kPf`7D??c8XLkF`B<6;>+>&Sn|TVY9^FNoaJztX8Da5x8QVYeNT@Z$nn| zBcTNvpL|t1fHx_oaAg*IwKj!V#3V9;EBUN|OQP502gOA^xf5=t0sx$H=DJ5aGSla( z<`EG>ig-FmY3TGo6i{KUwa1vj`%ii+vg8WtU7y>ALzdQ;d~z`Lf-nD>8z`a>(go15(0%S zk^iBvQmR zOnCs6HLf7mlK64z3`w`EwK*kOpz*Q)R!A7Zz3lW7obMH3j6$Iorwl>nATwIvC?cvY zw2*okT5|6}S)o4?lsjJZ zy>ZX>1Mxv`w|2;P!RBpGG5v2<_K4lKoA5Al2Ly9-`EEhht z&}8=~3n9hyvI1iVIL3fos9S~cGIj4P(yJsUUzie}vOt?*q@&tp5=|lo&rltcvkR3y zoi^B6MbK_$g0yw46m@vS1^y%cl@mpE_kuC{%pRI)5lG=;kvC01LOOB0w!pfd%8D!6 zL>|CV`Ih#01Db(k9CkJkyFUG-6m;SovP2sPAl3m?u)$>47kwvp2QS*FXPP6B>?9H+ zKch9iRiNG&fH^8-be0sm4@IC$xik@=Z16oFHHUV<52NwgqEF+X4(iy{_=_TYG&;z5 zVP4c0U5Q)%XgT<}y+?=JnM)Vwqic%J=Q^LfG!+kq#>A$)Hv2a*tBxA?3aik0R7ip& z)XYOMK5oC*w_>5Nut?q`#PJ5_8*T=;mIZj@K18iUax(dSvAbw^FII!I=CA|qIIW3{ z7`u~_vEo^3VVbxCGiEu9DT@JI3^i!U{Ti77@DMBF=lXVhvRFA)56mAqrEcv*6Hkou zHjyrkExpME8kNw+%)E~LtAX1x2yIJYq@dK`>*IFCH&m(pnm5fm`BW)Dj9d#_3DF4W zX{7_hBb1VEzh*Ol#dioA5rd}NSQ@lbzEV482_F;>8DP^d1l3A&EPGX>bW(xLqPYs% z>!Gye_!-?xV@8_cO{-cjIMem!Lcd7^+X-Auj1mhx?|}&Dky1*B0?1BxNvF8OrqQwl>XlQ<~@qVBcpG}+br zZlJgzg%45Pc-&AikbmBaGhrfnp6Or?-bgr6BcAwXWNBy83XKfSAnXVs0_&d-pQ;(G zTbeA#_R(2I0~;?CxNWON2r5B=Z?b(irKi!nL(hU&!sdd(uwaV45X|iI>hrzye{BEVA(l|I9Yw@_9@UZ zaA3*Hzu-?+*o4}<`m%P7n8xOE^I=!($)!O{4{o0x5_0nX)q4p+3vW{DKkBYs12ZBW z`25LZZ_#x)#w^p>^i3>SIn$%7*PGllz0t_V2%Rn1+2Lf@{(YWZn&*zLbYQ`2Q}^wJS2c&m6?@nzQ~jgY~{d9Py3_g(>=Pa`FEmhFKoA$`k(_ z19s|yd+25A_j1(~d4#IeLL3CD!3nykvx6*Urh+ECIkHfLNP)~3@{pqz!YW{b>0%=4 z4+T0FSOO#iRQWWxXGN==w7;zUdI))|Khr@2=#l*y1kIT{3DMYbdXTv;=5^81#YxS5 z#Na(HOuk1=3hDPn5c?Kxt(3tt=&TzV8K!dil*-H0E>*Rq<+z~f>jBEKmABaAF@V6m z*-6y%fjfjRQWC#a5=HEHHN&O8`4`x>xy07BXB{ww!o6D~+|N)4ozZ~9A+y#X;C2uF zs;rv??>kk1l=JH;5iWjI7Tea zyX}ok{6O>7y557#&8F>g%?y(1mV8?gHuNFIf4?x0*CE?%h*G($lcKV@<8;fn zuVgHo1)*U8|4~raA#=5<31QsqLPW*|D0 z#2Ea0YR)u6^;)*5pb8!oLMYd&)Ea2c=am?~Cyeyy<^bnzmu{Ekuy@_{&4YuX{I9W5 z%$O;x!;W2YUedS7_G8y>uhvi=*PDq}tGI6Nf;tYBO&WQ#lnQqT=_s89rqQoa97iO_ zXeKvl@UYi&2Bn}(|CYPC_~hK?6J`-G?^C=+Go1&nH!milqn#xZyk|@_Nim6sDNFFDS11#4X+yd?w z%7)xtE&TQCi0yBSYa=8T96{rR1ThLu)!(Jj{Na_Th7VGb{puTLJ?;wzz!nO3W%0qa zG>7$U;?`Y;Tch|x?+9&_=cydOHQEcau1(O83Q~!3%*SRUr{~<-z#hd*vll~s?72zz zv@qWtWOK{0Kdmi%Z{5;z6T6uLyO(nkBN*jGIBv$Gk$sYG{!tSC)OaPD-xR|akrs4+ z{r8UWQOb5`??gelD&>;}+icB&=KD}{p-2kLPam!vbpbskN*CK{(~0949u(03MVhvB z?mZhosZfMB!B6pGjX%kR80Iy2rt3by2t(NV23rcrFR`zOfdxgLde8)!$@$5(50o1%&>STE#G1bB~VJrf?KhVZ| z4;GK6Lv+V=CO8qQ*)^zxv!haQO_Q8y?eF8w_iGPW-VI^L3y*3kAH7Lc69#C$2P_?z zvFeg2p7fg{h_YsyNrqVr2`a+kn{6nG9lbPV6rIB3>Q0w%mDFA>CC$qZ`z;E~C6?Cq ze4&WR3YySR%SGo)3RXu`_Xrd}S@ltzC`}e9!sxld3xbV>!MBoC{16MiuCq!vD3RhF3R-b`QwCe79f_gfzPJh(1x(^3v@>sl`d)G41lKt4kor!m4 zkz1%R#1-P zzWO$(-?OZl5&RfY^Bh(r8-3Gvd&01)r?}l9;p$R^?B7vt6L*K;JOJ)td4~14cEkM< z)F|I{%X}H*z%&w?LMYxlqIo@8OYF=-xJ`FgKg7Oh%)Y8u`z}$KWOve_= zbz)h37TFQz3asDnzvCujYb>aBtyeBk)GIa}r^&XppW5X4dAF?Bbi$%yxj-MoMp;xr zz+fC;QLgnQ9|YmqY@9M#*!k4hm&j7Dai&@VFY>lR!z^c?`d(uQ*xs@*e-l94Em?wp z)=M%w)jV*R$uc{+`NkRKA1Lt_>TE#`)G_1qZqFvsh$RSS%05?yL4h6(I5rMrEe#SD zuo|Q^j0Q-#@NPX*FjVSR?xg;)NMs!+d--e#1;tIu4X54;)mU%1`|yWq7u8Z7bgJ9L zI#Q@L_en|gVd+K9tZJdQ)2B8WqWNMjlfd=_`U@ON4crWIZ6fsdh_IO4q@z=OLPncz zdGNuBVAFJ76|vz3zlHEcT%Mb5+-k+X_T&VBU76Ro?=WxMT<+zb}$6I8?BD5>_q|F0jYD zV8pA$a2(yd!XlynNT`3iv50y%N9+DN$1BC6QE#0{v~S(-T-4~KKaz!FQip`Z+R(aN zHP>{vDq#ObCZ@=y#7wVA%Ir*LO`CW|<+1boHYvKSb<3XXgSvPl=}XU(P5&FvL09KkK%_2dy+xR7_R`j^=v8Su9WxM+?Dt0F8UGYwCdxO;n@!FUG=u-cDxrmwL~eU zYepzaxW5>{!tk?d!X^Ka(}T*nFEFv3415m1fRU8Gc_`FthH=mj4sOaA6QV0IamxBJ=zdB7>ASONp-GTnI<6K?*%y{HSCrWK#Csl%>GBn6w=diM-XCX& zA)%hQm_J1+5l)~RCm0SZI^LSL@FR)ba|c9JWDHVn{goj*#)jvXfDYd&V25*F*?%L; zDhAJ??{2C~RgSLfzVE<$ebrc)NkakNTAS!BJ%F$er)L&^wx6-klDQFKAXP)EI?Y5o zSz-&^!*wzZsL7P1#pw7_=T){PYfbP%`e12?bt9QNoLydvhKDzrsWVrOR4x`z3SjL` zf%L1Xkd2lZH?146G3VGL6-PBBqu&KwU0OsN$N{Yx@2NVkAN5$h;njt~WiR7Dw;22uj6o2`HA>G($J;@j@;t65=0O$M!Tqjba`&JN^7;7W!*tgy$*+BT zp=CEfEo*nRY}hI8>|96i!dkS{Km5u5Oz(R+af%2RP&il2ig}JZgDh#3vD_`4+A7vO zuUtnoGD&z#mZ?e9A`G&xr&M>vaoQdJJ{8DT4jznJAjht069=w3zcpdYBRtj zKLKyLewkWf;jT$0)L0qD*EX3e%q#xJZs7ynQ_KMF-zD^5ox{rqJgx)uMd)iD7;AIo z(jKn|wSFRgb99X|$TuIvQ@u;7kb0ASo+F73XLsjYEN`g`I4(6y1-^^fK-o?35kOCY z$ph#dkLW|E*B87UNP97|!1XG>7hx0PYVx+w4P@KC@%BRzRdGRiw9NRL;7iRYL>eim zCr2zz`KcGD?uXDJud9(4C1A=GEeFsGLoyccv#Gm=_UY06_j_syJQ9&|+^)DeRn-o^ zt5BYx=Sr1p%e0&$g_CQUc0=;Z?mCxQcw10tC4cbj*O--AkAnSC;U5ZM)|CzzSw-cI@~&e@ z89yTlJyQ)VVCdXnMTnp8fB!d@zTna{7NG- zIGbF9-RDjpSc^GgvOVL||M+P_W9|!#zENY`OyvBg;nia;UbtA*4RYgrhAU7%`FZpU zN_U~G8$Rx2Dr+KrH1YA36+_4{eU zqr|&@5>kRGac`np05krln)&#VYhseJd#MvVg*PxqYIkay$BMaWXVs6#Bf2c9GUBLo z^$H+8BCa}f31WEuiWSB!embAMO>t>)|IUNJ#Zi7#hjn4Zj+2u3A}uqZcdjq6Kk37@ zD&g8UppoiOvG5}__u1{$>fP+u5-2JanR58KN%8W4wAH*zp`eCq*M3yg|HzB692wJ4 zc-H#D`12E|?vwMM;hLDLLjsjzZ?2ai7NB03l+gO=pr$aTT;QD1RcW)XpR<^;dfr?p zB1sOV9JBSs#dPcvp}Q1_vFA~u(t~FP;o>G#DUl5f#O)!)#dtyS5M2=M03^v)&)LCU zM98kIV8sJUwp)3 zWvBm+?)rb=E@cmU69RfULrW!R8z_2N0!D^^D3_>(qmwfM2mAk}x>z|`82@LFhTuQD z*3Kr51oWcT2F@nJCPsF~CQ!V*P)^Q{CI&W8?wcdpT1q%#jlO4U&qtgM1};1Fh_Ny8 z!3psLsq;R#zWfY=PH2Fk1F5fTcBg48%qvSv{R|YbL&wT%wA6jw%BnBs(nVN1#zY;A zglt@_t4a&3yQQP+Wa=yF>%%DJJrW6<6-|w`j2#P`!L(M`Hasg?qFQxW*jP7>MIKl; z7U@edu>-8Jqoi_kEXZ+gy^Jiq4#TsSA0)oACA4-}M?p5-WU;&K&wUc3EV&w%ni%wi z$D?DRp%-N7qnek}B3C#y>&RAzQZzQ<7S!^;!cim_)@;2InW>2~$f&fm9b_4!oQW(7 zJ!`!Zy$%WK3Q1DU>&aMkj@C#G%L6uu>bhb}#xr>p1r^@^ywbyhh!iBA^DGpfWFVQ@ zp`upjoUDwGPNj09+LVVjPpPV%5(7xmk(x1wfhRzK)i^WA?W0csffCeTn6**WfJ1W; zk`wpEEaMz=bI-=Cb9Jm%p_t~22}=Q*EEX}H4RC+1qFTx=c;#A@3q9v1m#4?bOF<9^ za64i>LD0kLHA3MCk>FcH<2`Jq$t_z+bD6nHt)Uqc4J@Qy7{P0c%8EVETH}x1X)5H( z`mc^uNIv2uS%|8x+sspx8-rnM5+!rhjxXrP&dY^e3sH z*%?-pZk}G0JxoQyR#77pcTqDfaZ}dZ5?-}~5M z@?O0m-W$etDEX8X%7hKx_`yA4`Bc-{y^`%ExZ>c22xkSubY~76kGEKqqaiv}aTg#; zYfY-MZ{zN-X!57Utxni~5t&{1wbvZRdg%QwX4GbIl}&!)kD>C5sb)YI|3&Wjn*h-M zqUd;aEP~O2Z;RY>w*{Pf$n>cpyd!@dJ9D^JP5$buI)}FVAW%_?As>JDvjISW7e!us z5Mp)8zB0zNL3iD{2Z3vM(z?Ko+7tZEFX}uzCe&a*dEn3Nc=X$_jc@&fF9KLA{cvIJTX{Gh~Y$ zbnmh_*Ek0)ik!E_k3yYsf9~HK;h>8Co8sMYGM9d;|EpkzK zQF%#HvHTd56@;GN$DC|AXEMhr9vqrWUs_VpDJIDn1Ew&SXp*5*=>%Ko)Ou-BjR`_0 zb*5m1?pkNfd)f$wq!l&NHuF;eB-uL^Aa9^=3L58-flAEJF^!Y`S;Vk0M?OQ`m_a2y zGBzy;gp8qXlH!xEDPMT51R|?5z)1BXc(8(7z?Munt$N0Fu>o%Ohr4CbTP-YW<~BK> zQ>rMp+*PcGJy~pP#Hi6HNI}y-PQ468T#tQg}w?w6drN)PxC2Gc!>9)G6 zg!NGGg~p9+8{G#yIT@K|CL|N4Kjj}FR#MHL5X{h6#F1`h3~law99kqPnAb-ZwUfN! ze20x)rjr~X*Q5#Kh%6vu_?U2%ku}DP7&el5C-WLQ5+bRZuuqR>}-7K2#fBG3;V zZ_>zRUhItr){-E@WTgq+t5Ik#h5_g`bGOk%w#2NP!cf(O)Ce-+)iq&Tj{K|e#I0%CfdES{wChOw?@-gX>eg7wy9Mw`@{ z^U5O(?jAF!oSJ%w6lDU;9X_Xy0|1>l6je5#)b-OGCLa^%LAEEws zXDayF&S?y=%ZYV>Q#Z_+o@IhtuUZbz38Mt6Yi~BE=?uoY+GIk(_EU{f#s3~Zg_!Bj z>Y*C}9i1G-lNQ43V;W|!Zq^LgDwIX7QLyqq8oTajIKQnOLL?KJAPAxiBDyidFc@ug zqC~XlMDM+mXfa51L3E--iQapU7A1P`LlC{s@cDhWth>JZt#$8O?;mIHcb{{fb>4l> zAJ4PieZ;f~-`!<9y0175i6L7rO>6iP<!;v`V^WSyVIKD0NHQXwLVN4F2>_!Q{uDY{d!yR{BZPl zL+cN@@IUe|kebyWKhFdJeh03kzOpJuXQ)eSU~?j~Z9j6f2iC*)Sc?Oa;>0~)D*|TL zd`9U%65}l}ei3xL7Z%)!N-`T%o6YDENkQjx#(k0!y;F=H3*!s1`@JBsc7`b!(^(LO z=N586Qmd%S_U`?hff;g7Jzz*qm?-D;jO2vU)9>#~1ffWUrI|Z@P03Vg0S`5xe2FO@ zMWMzov;%_JcXwooaXiJZrsVYERIJ{VFBwXcCyTGqM1BejBs^j$2BGNVDufC^-hHVz zCPBj};qu(MY=qE5o{&6?+Ar=?R31+rEP!_2Ja?V@CI6n^CI!-pAxt*z8@EY(W5%NU zF-T`;v|Y+8z)6J23x=b!fV5(jD;}t|SY7)3P!FMSl~vs>Vf9JItI(fMW5P(&tnjlb1{wMvO_-Kez z%rVg&>2o~*oFEVeZL*_5N*M20aom18nAO7a=ErZIZ?~spNlc?Teh{h}I7DCC5br#l zVS8J6JsQFp#BUXs*;22r5({MsF;wC>C$fKH4BS(oGN&O=W<-uQS8^l-e5C^-$t5P+`4Bb*cFtaMlupEAs1Bko(4Orv&*!gKW;iL@6I)P{3x$d;n5 zauqF_xH3CK4^Et_-wUuBWYIB819VI_XYQE_bWEb3B`Itg_isqHKE8(QIsCY6urP35 zqOF{F5RsUeXOgfJDO|A!lT3!c&SQ$BmUW4tXaHHR7lq=07Z^K&bwEW|))6 zOaCcu7W(HlvJSXk;$D;AP53z)mXeqvvj2@h$=EXx82SnBrU_7M=M1)~W0hzt_~=SL zO*^JT@*$pX!U<0D+fkrWpcpNg$a3PE1SY!Z=6c!)e=XgO3Ur7GngGQsszyrWw{P{t zXqVQ@Wy;_t1O%R;sXsf%~_x+xD zs5b)=u*;Q^bm&_b67n#fmWZr|F<2v<)DE&bA^9EiaW0g>jv+jPswbInyQ54Kc>CiN zJ+m45IS&kA8T<;4WjyGkonf}LyDVS-<~xn!f_h14jx0^C~VVp{0HO}?Fzy=^{xjvft|n~$#=&+`GWJKPkP4% zMt{5?3|sFM&M?eRy&QinP8t?c6_?Hl8W_hr+m3Z*;L%1=?gxB2jb zf;f^CmH|8FWp?oo3$#7x65i^Rz0>xw6!~;&Mt3D%Q0YsC47)qOc7k6fM1Y=Nu9kMK zL8udMYNY8@k>|)5*bz)k%;*xDMqI;ZgG0+75H3+(R5ENK@3QkcTHiv?-f^D;$XQRK zO{25jQCDl7Ii3O|qXA#D^g6;7R~e04o@z(lO5~q|Y-OtwwJ&7%hmefG{hEstQ04qf zg&XKuiVPVIN$Hq2GPsrNDWPf()04&nIU_Oh?KV>AHpMtl?;*g~jo)XDEZcAoI$xSw zPAO9R-u=Oz>=xebMN$iQ?yYAXSl#`W6Mdo;y2x%!IMjlwJ=wveL~|vq$~UEhale$l ziTkZzb#!GVA*oZK^0r?aj33Dm#EqCb*i@=)GYRVNL(B zoIhTIu0M64&I6+EN<8L!4R}WMn@-;X?!=PWs;$d==kIQf-JSuiYe{FHX~{?0`i!JW zRjbGq3K&M(U;H+?FLQ71q)3jFYasZAE^IO`lA^k>jJhvdSAKOxKwuMaCh5}N#`Hld zhU*)9dO5vcYcG@~rBrW{sdo|wvGSnLhccL-*MwvWk_xtA4ec)EM%;fivNS_?<`~bR z3by{P zp_J}>F_NLtop!~&pS5N_8Lo~5_gQR#*X#BB4r6i$LN9{l)AhIKel<+cQNP4r`=uUTOMeN_2af1GRK%bk5d8P~JMsiG@V_*yXY zDc!eaq0X^S#g__n$@{hxy2lvZ1*4MLp*~d2?^*3vQ8eB!oz%6&4W^Naf|lZcndm3;9jfj{C6${xGtP0EZ-C zeCuv9m-8w*+-iKWE#)6lSwD>(j@MsLlGsOCqE}l^^~G}$4645+`>y>Z!?GD31wGil zf3%D}y#}&x=DotFlo>U-;2)vhA4F2;Sy`$vJ*1J8F>$P7(U{EgsYf6#&rI9|FA&~P z;Wu6>q6UY<1x?-}mf-W`jQP#WOs`AcUC}Y+3Mo%F`gMVdh1b|~%lhLn?-cdN2=w~J z!O6&uhnK6P*SWj5EB0i2*~ZI{FF#SSdGOLoaXbHHebxZDaE)6PF~wqf@>TuX{W9WH zWuAIPvqpA9wuZMAwh~#44O6z>JTZ9`pL*O1v!Zc0b9?7ib(GdRzesaLX)TYZ!ZlBV zv!h77L=a($Z^RR}AAXu}n&CT7Tb(|W?OdL5O5tcX>Sw1s1KzE~wwzXCXVPlW2F%PM zoHpKk!U*9szw0^umt1-1p53klOK(>%kCU9#stWKEs%!Hr&8y)XSwJP4cxjg7eMVHX4X|a-;mNCRRUit^g`>Eyk?8ct5 z?&5fJzps10YiiJWavFr4$0jfs>)I})q69?}QI|l5u=p1L)QbEYvt)gvk%Uy7GjT2U z06(9joxxwW@43mvozbf!qH&Q8&wMazRgEiAXou8O`!`#=KpUqaa&-Vu!EM8+G zqTm$aZc47Q`JXTz&B;NCus{=s5Shsexu)1-zE7w5!e8`h_1SB@{kmXp(Hm1m|6(7QFKqOtu)B4O6}9h%CE!i)3fq*#=) zD@fZ_hqmYso-q}HBTK(FWFPyd?esNphrp;4Hip2der!xMXDdlQYHSc!Wjx>C)Rdks z&dHeh)5V+A-tRHJeB)qsm$qoSfk9YsIqT16U8PQbAzbxyW3oEjQ#06eNduA>BF>v^Za)qECcNaJAZ;`Q+-}%~a-*f6EhH z`qnMo-78ODydtW!!s^-d`=RD8&0gZnMZSV>vD!*+>}StfH*z_i@u`2OhL1@5${9}m z6nU3ceSR|(YQihrapf+4X(KPTm=YQO>U!kbQMhj93c{8$^rF%r%lr(K`o>5zRy4G0 z{8(oQRkE&>jcvdVaYr9ocO9VjYR=r!Lq!H_MTECwOO!%Q%$xH>(myM_KN}Yw{#w2< zQ+5?lLbhh$i}BdM&c08pNJWegbTd_gQsa9jw3IA0bj2?M-|9JT;fgzMG&6=&FMbgq=3CdUeDs}n_F2-|q8{f_M1Nzp-XJ39#1q_NrEQj$kW?5}qtP6Lp`A-uKyg6$ zz21A}*UsV}*-W6DFztp(bu`@WRh!c4Sv@Dy;Q0=)GaW@rmGDvr^0ZOpDCg?XbmPEm zgHW;uL%Y%J65BN3W9TS&l9&f@ZxK1mVP9kVqp|pA`+{~L!Ok`zX*M~F@TTArdFaj3 z^lrLtz}wK_`-gc>l_6)*8}J#7@wSMwoyp(%^V^oau@wNq$Nw)Zy^52)iR;^2(w)V@ z#7xapixa}d%gqJhVFiFCZdrF1``b6S?thq;_I8rD+&qXyQV`00Td7R|0)cWvAy5b> zH!m|cH}h?rqP@v~3Q==1a&Ry;xh49IY@AI2U==kfEiP$S8yjOIJG;NIs99J#gKnR{ zVd4O3m^wM%P7UJWg789M0#H6qC>QTPp#CpF&`V1=Th+g%ToMb!2e;&>b>5?=?KzMrU?Z~t5mghhMC$F*>kvt4i{l@cF8UEP1P|kB6A?Jj@*G_ab(BF{ z@8E+Ti?J>taT)MN-;aV`-lqtV#Am}}qPUNveXo@`3i2rIqr`Hwaw|nt8R#8=oC=t7 zw?OO{UB(11?p=%f^pp;{M7$#^F^{ou^coYBp2h0?f|uXT;x;M9qHfB=Z*O;~d%=z_ z3$0mx;&OElW0W#c(5qOLDnCRunY)c1$GBGLMn9MOmUHaWtZiQao(?-az&!7tCq%~% z_ES}seRg*@&k&LuEvTunP!HfsA4z0Xn2V0aM`wprrAL06Ah!*(@Xs6mu^wT&?{n;1 zp=S-eKmUx8-Jc+Rnd7lJTS6@&eIdW|@u%-O3CB7?c}q6w{0$ki+44=%T268e!I!j@ zl%jMrli7Lsb|a>{e0jr&Idk8(4E4)w@jTyO;cSdEf0(eqhaE50+A4RM=Nl(CjSd=9 z2A=Y8KP419lX0bxQ6d79sZof1kGPNgps8{kHy7C*sT56Q8rB|bK;Jo+Cgz4O^(xO` zn@{f5jL2wZd*zDJFAt>=nAI4?L`>};(s=h`?oK52nCu4Wf%U+MM+&eva9M<1G>w2+mTg9JCh_8N9yOvM8>|TtoKRf8Hi!IJ|sS=JTcD5FI z(*f486|CJwhE(e9+!1e`GY-Z!Kld;+^%p89_*$5(!Gu#V{o<-2#gl6^LXPhSr#HQj@c-N8@PA8fEmc!9 z09ek>#MA?%!wrJ)3Fra9uPwby|7rrjnjjqrhzA6@b*kFiyWBeYZii6)tB0BWt@YQj z@s}kD(m{xe!+E8lP`IQNk0cz)!;h4JN%Bg=1mHZ9{19#=w+QGzhuqHd($vn}#RA03 z$NOLJDW(xQ8^u@DJqL?>bH6<6ePPwzR@OGwY-!)Lwbd^N5S5ixhEm4koq#eBec7m_ z%~y7t&eEzX`nK-!hi|jU8Ds}q(g&FrZv^-$X@q)PH32j~&Yv;E` z+PrYf&L7V2kOgH*VMd+27R(PL zi1OGI_u0k?7An*g+V|1BSFwp;a#XN!v=+x_lv(ss&Mb8fvi?q|GGq~{t#P~-=LD)q zi+v*W#5izD7IFQju#m8a>c&jh*Rr0f z Date: Sun, 19 Sep 2021 20:59:11 -0400 Subject: [PATCH 0010/1686] update ImuFactor reference --- gtsam/navigation/CombinedImuFactor.h | 3 +-- gtsam/navigation/ImuFactor.h | 3 +-- 2 files changed, 2 insertions(+), 4 deletions(-) diff --git a/gtsam/navigation/CombinedImuFactor.h b/gtsam/navigation/CombinedImuFactor.h index a563d9d43..ce169c1d0 100644 --- a/gtsam/navigation/CombinedImuFactor.h +++ b/gtsam/navigation/CombinedImuFactor.h @@ -42,8 +42,6 @@ typedef ManifoldPreintegration PreintegrationType; * L. Carlone, Z. Kira, C. Beall, V. Indelman, F. Dellaert, Eliminating * conditionally independent sets in factor graphs: a unifying perspective based * on smart factors, Int. Conf. on Robotics and Automation (ICRA), 2014. - * - * [3] is available in this repo as "PreintegratedIMUJacobians.pdf". * * REFERENCES: * [1] G.S. Chirikjian, "Stochastic Models, Information Theory, and Lie Groups", @@ -53,6 +51,7 @@ typedef ManifoldPreintegration PreintegrationType; * TRO, 28(1):61-76, 2012. * [3] L. Carlone, S. Williams, R. Roberts, "Preintegrated IMU factor: * Computation of the Jacobian Matrices", Tech. Report, 2013. + * Available in this repo as "PreintegratedIMUJacobians.pdf". * [4] C. Forster, L. Carlone, F. Dellaert, D. Scaramuzza, IMU Preintegration on * Manifold for Efficient Visual-Inertial Maximum-a-Posteriori Estimation, * Robotics: Science and Systems (RSS), 2015. diff --git a/gtsam/navigation/ImuFactor.h b/gtsam/navigation/ImuFactor.h index 0df606643..266f2a547 100644 --- a/gtsam/navigation/ImuFactor.h +++ b/gtsam/navigation/ImuFactor.h @@ -44,8 +44,6 @@ typedef ManifoldPreintegration PreintegrationType; * C. Forster, L. Carlone, F. Dellaert, D. Scaramuzza, "IMU Preintegration on * Manifold for Efficient Visual-Inertial Maximum-a-Posteriori Estimation", * Robotics: Science and Systems (RSS), 2015. - * - * [3] is available in this repo as "PreintegratedIMUJacobians.pdf". * * REFERENCES: * [1] G.S. Chirikjian, "Stochastic Models, Information Theory, and Lie Groups", @@ -55,6 +53,7 @@ typedef ManifoldPreintegration PreintegrationType; * TRO, 28(1):61-76, 2012. * [3] L. Carlone, S. Williams, R. Roberts, "Preintegrated IMU factor: * Computation of the Jacobian Matrices", Tech. Report, 2013. + * Available in this repo as "PreintegratedIMUJacobians.pdf". * [4] C. Forster, L. Carlone, F. Dellaert, D. Scaramuzza, "IMU Preintegration on * Manifold for Efficient Visual-Inertial Maximum-a-Posteriori Estimation", * Robotics: Science and Systems (RSS), 2015. From 28d0393abd7cd94dd690b4a9b95805add462917a Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sun, 19 Sep 2021 10:51:24 -0400 Subject: [PATCH 0011/1686] add test for checking covariances between ImuFactor and CombinedImuFactor --- .../tests/testCombinedImuFactor.cpp | 395 ++++++++++-------- 1 file changed, 230 insertions(+), 165 deletions(-) diff --git a/gtsam/navigation/tests/testCombinedImuFactor.cpp b/gtsam/navigation/tests/testCombinedImuFactor.cpp index dc9ae288a..f7acfa79e 100644 --- a/gtsam/navigation/tests/testCombinedImuFactor.cpp +++ b/gtsam/navigation/tests/testCombinedImuFactor.cpp @@ -18,16 +18,16 @@ * @author Stephen Williams */ -#include -#include -#include -#include -#include -#include +#include #include #include - -#include +#include +#include +#include +#include +#include +#include +#include #include @@ -44,207 +44,272 @@ static boost::shared_ptr Params() { } } -/* ************************************************************************* */ -TEST( CombinedImuFactor, PreintegratedMeasurements ) { - // Linearization point - Bias bias(Vector3(0, 0, 0), Vector3(0, 0, 0)); ///< Current estimate of acceleration and angular rate biases +// /* ************************************************************************* */ +// TEST(CombinedImuFactor, PreintegratedMeasurements ) { +// // Linearization point +// Bias bias(Vector3(0, 0, 0), Vector3(0, 0, 0)); ///< Current estimate of acceleration and angular rate biases - // Measurements - Vector3 measuredAcc(0.1, 0.0, 0.0); - Vector3 measuredOmega(M_PI / 100.0, 0.0, 0.0); - double deltaT = 0.5; - double tol = 1e-6; +// // Measurements +// Vector3 measuredAcc(0.1, 0.0, 0.0); +// Vector3 measuredOmega(M_PI / 100.0, 0.0, 0.0); +// double deltaT = 0.5; +// double tol = 1e-6; - auto p = testing::Params(); +// auto p = testing::Params(); - // Actual preintegrated values - PreintegratedImuMeasurements expected1(p, bias); - expected1.integrateMeasurement(measuredAcc, measuredOmega, deltaT); +// // Actual preintegrated values +// PreintegratedImuMeasurements expected1(p, bias); +// expected1.integrateMeasurement(measuredAcc, measuredOmega, deltaT); - PreintegratedCombinedMeasurements actual1(p, bias); +// PreintegratedCombinedMeasurements actual1(p, bias); - actual1.integrateMeasurement(measuredAcc, measuredOmega, deltaT); +// actual1.integrateMeasurement(measuredAcc, measuredOmega, deltaT); - EXPECT(assert_equal(Vector(expected1.deltaPij()), actual1.deltaPij(), tol)); - EXPECT(assert_equal(Vector(expected1.deltaVij()), actual1.deltaVij(), tol)); - EXPECT(assert_equal(expected1.deltaRij(), actual1.deltaRij(), tol)); - DOUBLES_EQUAL(expected1.deltaTij(), actual1.deltaTij(), tol); -} +// EXPECT(assert_equal(Vector(expected1.deltaPij()), actual1.deltaPij(), tol)); +// EXPECT(assert_equal(Vector(expected1.deltaVij()), actual1.deltaVij(), tol)); +// EXPECT(assert_equal(expected1.deltaRij(), actual1.deltaRij(), tol)); +// DOUBLES_EQUAL(expected1.deltaTij(), actual1.deltaTij(), tol); +// } -/* ************************************************************************* */ -TEST( CombinedImuFactor, ErrorWithBiases ) { - Bias bias(Vector3(0.2, 0, 0), Vector3(0, 0, 0.3)); // Biases (acc, rot) - Bias bias2(Vector3(0.2, 0.2, 0), Vector3(1, 0, 0.3)); // Biases (acc, rot) - Pose3 x1(Rot3::Expmap(Vector3(0, 0, M_PI / 4.0)), Point3(5.0, 1.0, -50.0)); - Vector3 v1(0.5, 0.0, 0.0); - Pose3 x2(Rot3::Expmap(Vector3(0, 0, M_PI / 4.0 + M_PI / 10.0)), - Point3(5.5, 1.0, -50.0)); - Vector3 v2(0.5, 0.0, 0.0); +// /* ************************************************************************* */ +// TEST(CombinedImuFactor, Accelerating) { +// const double a = 0.2, v = 50; - auto p = testing::Params(); - p->omegaCoriolis = Vector3(0,0.1,0.1); - PreintegratedImuMeasurements pim( - p, Bias(Vector3(0.2, 0.0, 0.0), Vector3(0.0, 0.0, 0.0))); +// // Set up body pointing towards y axis, and start at 10,20,0 with velocity going in X +// // The body itself has Z axis pointing down +// const Rot3 nRb(Point3(0, 1, 0), Point3(1, 0, 0), Point3(0, 0, -1)); +// const Point3 initial_position(10, 20, 0); +// const Vector3 initial_velocity(v, 0, 0); - // Measurements - Vector3 measuredOmega; - measuredOmega << 0, 0, M_PI / 10.0 + 0.3; - Vector3 measuredAcc = - x1.rotation().unrotate(-p->n_gravity) + Vector3(0.2, 0.0, 0.0); - double deltaT = 1.0; - double tol = 1e-6; +// const AcceleratingScenario scenario(nRb, initial_position, initial_velocity, +// Vector3(a, 0, 0)); - pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT); +// const double T = 3.0; // seconds +// CombinedScenarioRunner runner(scenario, testing::Params(), T / 10); - PreintegratedCombinedMeasurements combined_pim(p, - Bias(Vector3(0.2, 0.0, 0.0), Vector3(0.0, 0.0, 0.0))); +// PreintegratedCombinedMeasurements pim = runner.integrate(T); +// EXPECT(assert_equal(scenario.pose(T), runner.predict(pim).pose(), 1e-9)); - combined_pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT); +// auto estimatedCov = runner.estimateCovariance(T, 100); +// Eigen::Matrix expected = pim.preintMeasCov(); +// // EXPECT(assert_equal(estimatedCov, expected, 0.1)); +// } - // Create factor - ImuFactor imuFactor(X(1), V(1), X(2), V(2), B(1), pim); +// /* ************************************************************************* */ +// TEST(CombinedImuFactor, ErrorWithBiases ) { +// Bias bias(Vector3(0.2, 0, 0), Vector3(0, 0, 0.3)); // Biases (acc, rot) +// Bias bias2(Vector3(0.2, 0.2, 0), Vector3(1, 0, 0.3)); // Biases (acc, rot) +// Pose3 x1(Rot3::Expmap(Vector3(0, 0, M_PI / 4.0)), Point3(5.0, 1.0, -50.0)); +// Vector3 v1(0.5, 0.0, 0.0); +// Pose3 x2(Rot3::Expmap(Vector3(0, 0, M_PI / 4.0 + M_PI / 10.0)), +// Point3(5.5, 1.0, -50.0)); +// Vector3 v2(0.5, 0.0, 0.0); - noiseModel::Gaussian::shared_ptr Combinedmodel = - noiseModel::Gaussian::Covariance(combined_pim.preintMeasCov()); - CombinedImuFactor combinedfactor(X(1), V(1), X(2), V(2), B(1), B(2), - combined_pim); +// auto p = testing::Params(); +// p->omegaCoriolis = Vector3(0,0.1,0.1); +// PreintegratedImuMeasurements pim( +// p, Bias(Vector3(0.2, 0.0, 0.0), Vector3(0.0, 0.0, 0.0))); - Vector errorExpected = imuFactor.evaluateError(x1, v1, x2, v2, bias); - Vector errorActual = combinedfactor.evaluateError(x1, v1, x2, v2, bias, - bias2); - EXPECT(assert_equal(errorExpected, errorActual.head(9), tol)); +// // Measurements +// Vector3 measuredOmega; +// measuredOmega << 0, 0, M_PI / 10.0 + 0.3; +// Vector3 measuredAcc = +// x1.rotation().unrotate(-p->n_gravity) + Vector3(0.2, 0.0, 0.0); +// double deltaT = 1.0; +// double tol = 1e-6; - // Expected Jacobians - Matrix H1e, H2e, H3e, H4e, H5e; - (void) imuFactor.evaluateError(x1, v1, x2, v2, bias, H1e, H2e, H3e, H4e, H5e); +// pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT); - // Actual Jacobians - Matrix H1a, H2a, H3a, H4a, H5a, H6a; - (void) combinedfactor.evaluateError(x1, v1, x2, v2, bias, bias2, H1a, H2a, - H3a, H4a, H5a, H6a); +// PreintegratedCombinedMeasurements combined_pim(p, +// Bias(Vector3(0.2, 0.0, 0.0), Vector3(0.0, 0.0, 0.0))); - EXPECT(assert_equal(H1e, H1a.topRows(9))); - EXPECT(assert_equal(H2e, H2a.topRows(9))); - EXPECT(assert_equal(H3e, H3a.topRows(9))); - EXPECT(assert_equal(H4e, H4a.topRows(9))); - EXPECT(assert_equal(H5e, H5a.topRows(9))); -} +// combined_pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT); -/* ************************************************************************* */ -#ifdef GTSAM_TANGENT_PREINTEGRATION -TEST(CombinedImuFactor, FirstOrderPreIntegratedMeasurements) { - auto p = testing::Params(); - testing::SomeMeasurements measurements; +// // Create factor +// ImuFactor imuFactor(X(1), V(1), X(2), V(2), B(1), pim); - auto preintegrated = [=](const Vector3& a, const Vector3& w) { - PreintegratedImuMeasurements pim(p, Bias(a, w)); - testing::integrateMeasurements(measurements, &pim); - return pim.preintegrated(); - }; +// noiseModel::Gaussian::shared_ptr Combinedmodel = +// noiseModel::Gaussian::Covariance(combined_pim.preintMeasCov()); +// CombinedImuFactor combinedfactor(X(1), V(1), X(2), V(2), B(1), B(2), +// combined_pim); - // Actual pre-integrated values - PreintegratedCombinedMeasurements pim(p); - testing::integrateMeasurements(measurements, &pim); +// Vector errorExpected = imuFactor.evaluateError(x1, v1, x2, v2, bias); +// Vector errorActual = combinedfactor.evaluateError(x1, v1, x2, v2, bias, +// bias2); +// EXPECT(assert_equal(errorExpected, errorActual.head(9), tol)); - EXPECT(assert_equal(numericalDerivative21(preintegrated, Z_3x1, Z_3x1), - pim.preintegrated_H_biasAcc())); - EXPECT(assert_equal(numericalDerivative22(preintegrated, Z_3x1, Z_3x1), - pim.preintegrated_H_biasOmega(), 1e-3)); -} -#endif +// // Expected Jacobians +// Matrix H1e, H2e, H3e, H4e, H5e; +// (void) imuFactor.evaluateError(x1, v1, x2, v2, bias, H1e, H2e, H3e, H4e, H5e); -/* ************************************************************************* */ -TEST(CombinedImuFactor, PredictPositionAndVelocity) { - const Bias bias(Vector3(0, 0.1, 0), Vector3(0, 0.1, 0)); // Biases (acc, rot) +// // Actual Jacobians +// Matrix H1a, H2a, H3a, H4a, H5a, H6a; +// (void) combinedfactor.evaluateError(x1, v1, x2, v2, bias, bias2, H1a, H2a, +// H3a, H4a, H5a, H6a); - auto p = testing::Params(); +// EXPECT(assert_equal(H1e, H1a.topRows(9))); +// EXPECT(assert_equal(H2e, H2a.topRows(9))); +// EXPECT(assert_equal(H3e, H3a.topRows(9))); +// EXPECT(assert_equal(H4e, H4a.topRows(9))); +// EXPECT(assert_equal(H5e, H5a.topRows(9))); +// } - // Measurements - const Vector3 measuredOmega(0, 0.1, 0); // M_PI/10.0+0.3; - const Vector3 measuredAcc(0, 1.1, -kGravity); - const double deltaT = 0.01; +// /* ************************************************************************* */ +// #ifdef GTSAM_TANGENT_PREINTEGRATION +// TEST(CombinedImuFactor, FirstOrderPreIntegratedMeasurements) { +// auto p = testing::Params(); +// testing::SomeMeasurements measurements; - PreintegratedCombinedMeasurements pim(p, bias); +// auto preintegrated = [=](const Vector3& a, const Vector3& w) { +// PreintegratedImuMeasurements pim(p, Bias(a, w)); +// testing::integrateMeasurements(measurements, &pim); +// return pim.preintegrated(); +// }; - for (int i = 0; i < 100; ++i) - pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT); +// // Actual pre-integrated values +// PreintegratedCombinedMeasurements pim(p); +// testing::integrateMeasurements(measurements, &pim); - // Create factor - const noiseModel::Gaussian::shared_ptr combinedmodel = - noiseModel::Gaussian::Covariance(pim.preintMeasCov()); - const CombinedImuFactor Combinedfactor(X(1), V(1), X(2), V(2), B(1), B(2), pim); +// EXPECT(assert_equal(numericalDerivative21(preintegrated, Z_3x1, Z_3x1), +// pim.preintegrated_H_biasAcc())); +// EXPECT(assert_equal(numericalDerivative22(preintegrated, Z_3x1, Z_3x1), +// pim.preintegrated_H_biasOmega(), 1e-3)); +// } +// #endif - // Predict - const NavState actual = pim.predict(NavState(), bias); - const Pose3 expectedPose(Rot3(), Point3(0, 0.5, 0)); - const Vector3 expectedVelocity(0, 1, 0); - EXPECT(assert_equal(expectedPose, actual.pose())); - EXPECT(assert_equal(Vector(expectedVelocity), Vector(actual.velocity()))); -} +// /* ************************************************************************* */ +// TEST(CombinedImuFactor, PredictPositionAndVelocity) { +// const Bias bias(Vector3(0, 0.1, 0), Vector3(0, 0.1, 0)); // Biases (acc, rot) -/* ************************************************************************* */ -TEST(CombinedImuFactor, PredictRotation) { - const Bias bias(Vector3(0, 0, 0), Vector3(0, 0, 0)); // Biases (acc, rot) - auto p = testing::Params(); - PreintegratedCombinedMeasurements pim(p, bias); - const Vector3 measuredAcc = - kGravityAlongNavZDown; - const Vector3 measuredOmega(0, 0, M_PI / 10.0); - const double deltaT = 0.01; - const double tol = 1e-4; - for (int i = 0; i < 100; ++i) - pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT); - const CombinedImuFactor Combinedfactor(X(1), V(1), X(2), V(2), B(1), B(2), pim); +// auto p = testing::Params(); - // Predict - const Pose3 x(Rot3::Ypr(0, 0, 0), Point3(0, 0, 0)), x2; - const Vector3 v(0, 0, 0), v2; - const NavState actual = pim.predict(NavState(x, v), bias); - const Pose3 expectedPose(Rot3::Ypr(M_PI / 10, 0, 0), Point3(0, 0, 0)); - EXPECT(assert_equal(expectedPose, actual.pose(), tol)); -} +// // Measurements +// const Vector3 measuredOmega(0, 0.1, 0); // M_PI/10.0+0.3; +// const Vector3 measuredAcc(0, 1.1, -kGravity); +// const double deltaT = 0.01; -/* ************************************************************************* */ -// Testing covariance to check if all the jacobians are accounted for. -TEST(CombinedImuFactor, CheckCovariance) { - auto params = PreintegrationCombinedParams::MakeSharedU(9.81); +// PreintegratedCombinedMeasurements pim(p, bias); + +// for (int i = 0; i < 100; ++i) +// pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT); + +// // Create factor +// const noiseModel::Gaussian::shared_ptr combinedmodel = +// noiseModel::Gaussian::Covariance(pim.preintMeasCov()); +// const CombinedImuFactor Combinedfactor(X(1), V(1), X(2), V(2), B(1), B(2), pim); + +// // Predict +// const NavState actual = pim.predict(NavState(), bias); +// const Pose3 expectedPose(Rot3(), Point3(0, 0.5, 0)); +// const Vector3 expectedVelocity(0, 1, 0); +// EXPECT(assert_equal(expectedPose, actual.pose())); +// EXPECT(assert_equal(Vector(expectedVelocity), Vector(actual.velocity()))); +// } + +// /* ************************************************************************* */ +// TEST(CombinedImuFactor, PredictRotation) { +// const Bias bias(Vector3(0, 0, 0), Vector3(0, 0, 0)); // Biases (acc, rot) +// auto p = testing::Params(); +// PreintegratedCombinedMeasurements pim(p, bias); +// const Vector3 measuredAcc = - kGravityAlongNavZDown; +// const Vector3 measuredOmega(0, 0, M_PI / 10.0); +// const double deltaT = 0.01; +// const double tol = 1e-4; +// for (int i = 0; i < 100; ++i) +// pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT); +// const CombinedImuFactor Combinedfactor(X(1), V(1), X(2), V(2), B(1), B(2), pim); + +// // Predict +// const Pose3 x(Rot3::Ypr(0, 0, 0), Point3(0, 0, 0)), x2; +// const Vector3 v(0, 0, 0), v2; +// const NavState actual = pim.predict(NavState(x, v), bias); +// const Pose3 expectedPose(Rot3::Ypr(M_PI / 10, 0, 0), Point3(0, 0, 0)); +// EXPECT(assert_equal(expectedPose, actual.pose(), tol)); +// } + +// /* ************************************************************************* */ +// // Testing covariance to check if all the jacobians are accounted for. +// TEST(CombinedImuFactor, CheckCovariance) { +// auto params = PreintegrationCombinedParams::MakeSharedU(9.81); + +// params->setAccelerometerCovariance(pow(0.01, 2) * I_3x3); +// params->setGyroscopeCovariance(pow(1.75e-4, 2) * I_3x3); +// params->setIntegrationCovariance(pow(0.0, 2) * I_3x3); +// params->setOmegaCoriolis(Vector3::Zero()); + +// imuBias::ConstantBias currentBias; + +// PreintegratedCombinedMeasurements actual(params, currentBias); + +// // Measurements +// Vector3 measuredAcc(0.1577, -0.8251, 9.6111); +// Vector3 measuredOmega(-0.0210, 0.0311, 0.0145); +// double deltaT = 0.01; + +// actual.integrateMeasurement(measuredAcc, measuredOmega, deltaT); + +// Eigen::Matrix expected; +// expected << 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // +// 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // +// 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // +// 0, 0, 0, 2.50025e-07, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // +// 0, 0, 0, 0, 2.50025e-07, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // +// 0, 0, 0, 0, 0, 2.50025e-07, 0, 0, 0, 0, 0, 0, 0, 0, 0, // +// 0, 0, 0, 0, 0, 0, 0.010001, 0, 0, 0, 0, 0, 0, 0, 0, // +// 0, 0, 0, 0, 0, 0, 0, 0.010001, 0, 0, 0, 0, 0, 0, 0, // +// 0, 0, 0, 0, 0, 0, 0, 0, 0.010001, 0, 0, 0, 0, 0, 0, // +// 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, // +// 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, // +// 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, // +// 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, // +// 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, // +// 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01; + +// // regression +// EXPECT(assert_equal(expected, actual.preintMeasCov())); +// } + +TEST(CombinedImuFactor, SameCovarianceCombined) { + auto params = PreintegrationCombinedParams::MakeSharedU(); params->setAccelerometerCovariance(pow(0.01, 2) * I_3x3); params->setGyroscopeCovariance(pow(1.75e-4, 2) * I_3x3); - params->setIntegrationCovariance(pow(0.0, 2) * I_3x3); + params->setIntegrationCovariance(pow(0, 2) * I_3x3); params->setOmegaCoriolis(Vector3::Zero()); imuBias::ConstantBias currentBias; - PreintegratedCombinedMeasurements actual(params, currentBias); + PreintegratedCombinedMeasurements pim(params, currentBias); - // Measurements - Vector3 measuredAcc(0.1577, -0.8251, 9.6111); - Vector3 measuredOmega(-0.0210, 0.0311, 0.0145); + Vector3 accMeas(0.1577, -0.8251, 9.6111); + Vector3 omegaMeas(-0.0210, 0.0311, 0.0145); double deltaT = 0.01; + pim.integrateMeasurement(accMeas, omegaMeas, deltaT); - actual.integrateMeasurement(measuredAcc, measuredOmega, deltaT); - - Eigen::Matrix expected; - expected << 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // - 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // - 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // - 0, 0, 0, 2.50025e-07, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // - 0, 0, 0, 0, 2.50025e-07, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // - 0, 0, 0, 0, 0, 2.50025e-07, 0, 0, 0, 0, 0, 0, 0, 0, 0, // - 0, 0, 0, 0, 0, 0, 0.010001, 0, 0, 0, 0, 0, 0, 0, 0, // - 0, 0, 0, 0, 0, 0, 0, 0.010001, 0, 0, 0, 0, 0, 0, 0, // - 0, 0, 0, 0, 0, 0, 0, 0, 0.010001, 0, 0, 0, 0, 0, 0, // - 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, // - 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, // - 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, // - 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, // - 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, // - 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01; - - // regression - EXPECT(assert_equal(expected, actual.preintMeasCov())); + std::cout << pim.preintMeasCov() << std::endl << std::endl; } +TEST(CombinedImuFactor, SameCovariance) { + auto params = PreintegrationParams::MakeSharedU(); + + params->setAccelerometerCovariance(pow(0.01, 2) * I_3x3); + params->setGyroscopeCovariance(pow(1.75e-4, 2) * I_3x3); + params->setIntegrationCovariance(pow(0, 2) * I_3x3); + params->setOmegaCoriolis(Vector3::Zero()); + + imuBias::ConstantBias currentBias; + + PreintegratedImuMeasurements pim(params, currentBias); + + Vector3 accMeas(0.1577, -0.8251, 9.6111); + Vector3 omegaMeas(-0.0210, 0.0311, 0.0145); + double deltaT = 0.01; + pim.integrateMeasurement(accMeas, omegaMeas, deltaT); + + std::cout << pim.preintMeasCov() << std::endl << std::endl; +} + + /* ************************************************************************* */ int main() { TestResult tr; From a10c776fdae8a6df2ddb5a448648a3a7e50ad69b Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sun, 19 Sep 2021 10:53:25 -0400 Subject: [PATCH 0012/1686] print statements in ImuFactor --- gtsam/navigation/ImuFactor.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/gtsam/navigation/ImuFactor.cpp b/gtsam/navigation/ImuFactor.cpp index 9b6affaaf..c0797d0e1 100644 --- a/gtsam/navigation/ImuFactor.cpp +++ b/gtsam/navigation/ImuFactor.cpp @@ -75,12 +75,16 @@ void PreintegratedImuMeasurements::integrateMeasurement( // (1/dt) allows to pass from continuous time noise to discrete time noise // Update the uncertainty on the state (matrix A in [4]). preintMeasCov_ = A * preintMeasCov_ * A.transpose(); + // std::cout << "A * p * A\n" << preintMeasCov_ << std::endl; // These 2 updates account for uncertainty on the IMU measurement (matrix B in [4]). preintMeasCov_.noalias() += B * (aCov / dt) * B.transpose(); + // std::cout << "p + B\n" << preintMeasCov_ << std::endl; preintMeasCov_.noalias() += C * (wCov / dt) * C.transpose(); + // std::cout << "ApA' + B + C\n" << preintMeasCov_ << std::endl; // NOTE(frank): (Gi*dt)*(C/dt)*(Gi'*dt), with Gi << Z_3x3, I_3x3, Z_3x3 (9x3 matrix) preintMeasCov_.block<3, 3>(3, 3).noalias() += iCov * dt; + // std::cout << "p + iCov\n" << preintMeasCov_ << std::endl; } //------------------------------------------------------------------------------ From 65bbe6b577c0d28a91652a6247e087d63757fbf5 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sun, 19 Sep 2021 10:53:41 -0400 Subject: [PATCH 0013/1686] typedef for Vector15 --- gtsam/base/Vector.h | 1 + 1 file changed, 1 insertion(+) diff --git a/gtsam/base/Vector.h b/gtsam/base/Vector.h index ed90a7126..9567d9980 100644 --- a/gtsam/base/Vector.h +++ b/gtsam/base/Vector.h @@ -60,6 +60,7 @@ GTSAM_MAKE_VECTOR_DEFS(9); GTSAM_MAKE_VECTOR_DEFS(10); GTSAM_MAKE_VECTOR_DEFS(11); GTSAM_MAKE_VECTOR_DEFS(12); +GTSAM_MAKE_VECTOR_DEFS(15); typedef Eigen::VectorBlock SubVector; typedef Eigen::VectorBlock ConstSubVector; From 3a3640c5e0d94c1108eac9ef863de6bc9e0e849a Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sun, 19 Sep 2021 10:59:05 -0400 Subject: [PATCH 0014/1686] updated CombinedImuFactor covariance with additional off-diagonal elements --- gtsam/navigation/CombinedImuFactor.cpp | 15 +++++++++------ 1 file changed, 9 insertions(+), 6 deletions(-) diff --git a/gtsam/navigation/CombinedImuFactor.cpp b/gtsam/navigation/CombinedImuFactor.cpp index 24e2e3016..cd579d716 100644 --- a/gtsam/navigation/CombinedImuFactor.cpp +++ b/gtsam/navigation/CombinedImuFactor.cpp @@ -134,18 +134,19 @@ void PreintegratedCombinedMeasurements::integrateMeasurement( Eigen::Matrix G_measCov_Gt; G_measCov_Gt.setZero(15, 15); - Matrix3 aCov_updated = (aCov + p().biasAccOmegaInt.block<3, 3>(0, 0)); + Matrix3 aCov_updated = aCov + p().biasAccOmegaInt.block<3, 3>(0, 0); + Matrix3 wCov_updated = wCov + p().biasAccOmegaInt.block<3, 3>(3, 3); // BLOCK DIAGONAL TERMS - D_t_t(&G_measCov_Gt) = ((1 / dt) * pos_H_biasAcc - * aCov_updated - * (pos_H_biasAcc.transpose())) + (dt * iCov); + D_t_t(&G_measCov_Gt) = (pos_H_biasAcc + * (aCov / dt) // aCov_updated / dt + * pos_H_biasAcc.transpose()) + (dt * iCov); D_v_v(&G_measCov_Gt) = (1 / dt) * vel_H_biasAcc - * aCov_updated + * (aCov / dt) // aCov_updated / dt * (vel_H_biasAcc.transpose()); D_R_R(&G_measCov_Gt) = (1 / dt) * theta_H_biasOmega - * (wCov + p().biasAccOmegaInt.block<3, 3>(3, 3)) + * (wCov / dt) // wCov_updated / dt * (theta_H_biasOmega.transpose()); D_a_a(&G_measCov_Gt) = dt * p().biasAccCovariance; @@ -155,7 +156,9 @@ void PreintegratedCombinedMeasurements::integrateMeasurement( Matrix3 temp = vel_H_biasAcc * p().biasAccOmegaInt.block<3, 3>(3, 0) * theta_H_biasOmega.transpose(); D_v_R(&G_measCov_Gt) = temp; + D_v_t(&G_measCov_Gt) = vel_H_biasAcc * (aCov / dt) * pos_H_biasAcc.transpose(); D_R_v(&G_measCov_Gt) = temp.transpose(); + D_t_v(&G_measCov_Gt) = pos_H_biasAcc * (aCov / dt) * vel_H_biasAcc.transpose(); preintMeasCov_ = F * preintMeasCov_ * F.transpose() + G_measCov_Gt; } From 3132cfbc868f0e382e2be34b0eabb9ffe6761f92 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sun, 19 Sep 2021 10:59:32 -0400 Subject: [PATCH 0015/1686] CombinedScenarioRunner --- gtsam/navigation/ScenarioRunner.cpp | 59 ++++++++++++++++++++++++++++- gtsam/navigation/ScenarioRunner.h | 44 +++++++++++++++++++-- 2 files changed, 98 insertions(+), 5 deletions(-) diff --git a/gtsam/navigation/ScenarioRunner.cpp b/gtsam/navigation/ScenarioRunner.cpp index 3938ce86c..3a447dcab 100644 --- a/gtsam/navigation/ScenarioRunner.cpp +++ b/gtsam/navigation/ScenarioRunner.cpp @@ -15,8 +15,8 @@ * @author Frank Dellaert */ -#include #include +#include #include #include @@ -105,4 +105,61 @@ Matrix6 ScenarioRunner::estimateNoiseCovariance(size_t N) const { return Q / (N - 1); } +PreintegratedCombinedMeasurements CombinedScenarioRunner::integrate( + double T, const Bias& estimatedBias, bool corrupted) const { + gttic_(integrate); + PreintegratedCombinedMeasurements pim(p_, estimatedBias); + + const double dt = imuSampleTime(); + const size_t nrSteps = T / dt; + double t = 0; + for (size_t k = 0; k < nrSteps; k++, t += dt) { + Vector3 measuredOmega = + corrupted ? measuredAngularVelocity(t) : actualAngularVelocity(t); + Vector3 measuredAcc = + corrupted ? measuredSpecificForce(t) : actualSpecificForce(t); + pim.integrateMeasurement(measuredAcc, measuredOmega, dt); + } + + return pim; +} + +NavState CombinedScenarioRunner::predict( + const PreintegratedCombinedMeasurements& pim, + const Bias& estimatedBias) const { + const NavState state_i(scenario().pose(0), scenario().velocity_n(0)); + return pim.predict(state_i, estimatedBias); +} + +Eigen::Matrix CombinedScenarioRunner::estimateCovariance( + double T, size_t N, const Bias& estimatedBias) const { + gttic_(estimateCovariance); + + // Get predict prediction from ground truth measurements + NavState prediction = predict(integrate(T)); + + // Sample ! + Matrix samples(15, N); + Vector15 sum = Vector15::Zero(); + for (size_t i = 0; i < N; i++) { + auto pim = integrate(T, estimatedBias, true); + NavState sampled = predict(pim); + Vector15 xi = Vector15::Zero(); + xi << sampled.localCoordinates(prediction), estimatedBias_.vector(); + samples.col(i) = xi; + sum += xi; + } + + // Compute MC covariance + Vector15 sampleMean = sum / N; + Eigen::Matrix Q; + Q.setZero(); + for (size_t i = 0; i < N; i++) { + Vector15 xi = samples.col(i) - sampleMean; + Q += xi * xi.transpose(); + } + + return Q / (N - 1); +} + } // namespace gtsam diff --git a/gtsam/navigation/ScenarioRunner.h b/gtsam/navigation/ScenarioRunner.h index 1577e36fe..cee5a54ab 100644 --- a/gtsam/navigation/ScenarioRunner.h +++ b/gtsam/navigation/ScenarioRunner.h @@ -16,9 +16,10 @@ */ #pragma once +#include +#include #include #include -#include namespace gtsam { @@ -66,10 +67,10 @@ class GTSAM_EXPORT ScenarioRunner { // also, uses g=10 for easy debugging const Vector3& gravity_n() const { return p_->n_gravity; } + const Scenario& scenario() const { return scenario_; } + // A gyro simply measures angular velocity in body frame - Vector3 actualAngularVelocity(double t) const { - return scenario_.omega_b(t); - } + Vector3 actualAngularVelocity(double t) const { return scenario_.omega_b(t); } // An accelerometer measures acceleration in body, but not gravity Vector3 actualSpecificForce(double t) const { @@ -106,4 +107,39 @@ class GTSAM_EXPORT ScenarioRunner { Matrix6 estimateNoiseCovariance(size_t N = 1000) const; }; +/* + * Simple class to test navigation scenarios with CombinedImuMeasurements. + * Takes a trajectory scenario as input, and can generate IMU measurements + */ +class GTSAM_EXPORT CombinedScenarioRunner : public ScenarioRunner { + public: + typedef boost::shared_ptr SharedParams; + + private: + const SharedParams p_; + const Bias estimatedBias_; + + public: + CombinedScenarioRunner(const Scenario& scenario, const SharedParams& p, + double imuSampleTime = 1.0 / 100.0, + const Bias& bias = Bias()) + : ScenarioRunner(scenario, static_cast(p), + imuSampleTime, bias), + p_(p), + estimatedBias_(bias) {} + + /// Integrate measurements for T seconds into a PIM + PreintegratedCombinedMeasurements integrate( + double T, const Bias& estimatedBias = Bias(), + bool corrupted = false) const; + + /// Predict predict given a PIM + NavState predict(const PreintegratedCombinedMeasurements& pim, + const Bias& estimatedBias = Bias()) const; + + /// Compute a Monte Carlo estimate of the predict covariance using N samples + Eigen::Matrix estimateCovariance( + double T, size_t N = 1000, const Bias& estimatedBias = Bias()) const; +}; + } // namespace gtsam From 53712149f98b8325ce91fdab22f8fc2b0f395e10 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sun, 19 Sep 2021 21:15:51 -0400 Subject: [PATCH 0016/1686] actually test the covariances and fix bug --- gtsam/navigation/CombinedImuFactor.cpp | 4 +- .../tests/testCombinedImuFactor.cpp | 40 ++++++++----------- 2 files changed, 19 insertions(+), 25 deletions(-) diff --git a/gtsam/navigation/CombinedImuFactor.cpp b/gtsam/navigation/CombinedImuFactor.cpp index cd579d716..c8d1b10fe 100644 --- a/gtsam/navigation/CombinedImuFactor.cpp +++ b/gtsam/navigation/CombinedImuFactor.cpp @@ -141,11 +141,11 @@ void PreintegratedCombinedMeasurements::integrateMeasurement( D_t_t(&G_measCov_Gt) = (pos_H_biasAcc * (aCov / dt) // aCov_updated / dt * pos_H_biasAcc.transpose()) + (dt * iCov); - D_v_v(&G_measCov_Gt) = (1 / dt) * vel_H_biasAcc + D_v_v(&G_measCov_Gt) = vel_H_biasAcc * (aCov / dt) // aCov_updated / dt * (vel_H_biasAcc.transpose()); - D_R_R(&G_measCov_Gt) = (1 / dt) * theta_H_biasOmega + D_R_R(&G_measCov_Gt) = theta_H_biasOmega * (wCov / dt) // wCov_updated / dt * (theta_H_biasOmega.transpose()); diff --git a/gtsam/navigation/tests/testCombinedImuFactor.cpp b/gtsam/navigation/tests/testCombinedImuFactor.cpp index f7acfa79e..0dbf961fc 100644 --- a/gtsam/navigation/tests/testCombinedImuFactor.cpp +++ b/gtsam/navigation/tests/testCombinedImuFactor.cpp @@ -269,27 +269,14 @@ static boost::shared_ptr Params() { // EXPECT(assert_equal(expected, actual.preintMeasCov())); // } -TEST(CombinedImuFactor, SameCovarianceCombined) { - auto params = PreintegrationCombinedParams::MakeSharedU(); - - params->setAccelerometerCovariance(pow(0.01, 2) * I_3x3); - params->setGyroscopeCovariance(pow(1.75e-4, 2) * I_3x3); - params->setIntegrationCovariance(pow(0, 2) * I_3x3); - params->setOmegaCoriolis(Vector3::Zero()); - - imuBias::ConstantBias currentBias; - - PreintegratedCombinedMeasurements pim(params, currentBias); +TEST(CombinedImuFactor, SameCovariance) { Vector3 accMeas(0.1577, -0.8251, 9.6111); Vector3 omegaMeas(-0.0210, 0.0311, 0.0145); double deltaT = 0.01; - pim.integrateMeasurement(accMeas, omegaMeas, deltaT); - std::cout << pim.preintMeasCov() << std::endl << std::endl; -} - -TEST(CombinedImuFactor, SameCovariance) { + imuBias::ConstantBias currentBias; + auto params = PreintegrationParams::MakeSharedU(); params->setAccelerometerCovariance(pow(0.01, 2) * I_3x3); @@ -297,16 +284,23 @@ TEST(CombinedImuFactor, SameCovariance) { params->setIntegrationCovariance(pow(0, 2) * I_3x3); params->setOmegaCoriolis(Vector3::Zero()); - imuBias::ConstantBias currentBias; - PreintegratedImuMeasurements pim(params, currentBias); - - Vector3 accMeas(0.1577, -0.8251, 9.6111); - Vector3 omegaMeas(-0.0210, 0.0311, 0.0145); - double deltaT = 0.01; pim.integrateMeasurement(accMeas, omegaMeas, deltaT); - std::cout << pim.preintMeasCov() << std::endl << std::endl; + // std::cout << pim.preintMeasCov() << std::endl << std::endl; + + auto combined_params = PreintegrationCombinedParams::MakeSharedU(); + + combined_params->setAccelerometerCovariance(pow(0.01, 2) * I_3x3); + combined_params->setGyroscopeCovariance(pow(1.75e-4, 2) * I_3x3); + combined_params->setIntegrationCovariance(pow(0, 2) * I_3x3); + combined_params->setOmegaCoriolis(Vector3::Zero()); + + PreintegratedCombinedMeasurements cpim(combined_params, currentBias); + cpim.integrateMeasurement(accMeas, omegaMeas, deltaT); + + // std::cout << cpim.preintMeasCov() << std::endl << std::endl; + EXPECT(assert_equal(pim.preintMeasCov(), cpim.preintMeasCov().block(0, 0, 9, 9))); } From 10a73338da8a785788bb954e26dfb7a625a3f3ff Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 21 Sep 2021 12:28:59 -0400 Subject: [PATCH 0017/1686] update test with comments --- .../tests/testCombinedImuFactor.cpp | 26 +++++++++++-------- 1 file changed, 15 insertions(+), 11 deletions(-) diff --git a/gtsam/navigation/tests/testCombinedImuFactor.cpp b/gtsam/navigation/tests/testCombinedImuFactor.cpp index 0dbf961fc..a8c039144 100644 --- a/gtsam/navigation/tests/testCombinedImuFactor.cpp +++ b/gtsam/navigation/tests/testCombinedImuFactor.cpp @@ -75,16 +75,16 @@ static boost::shared_ptr Params() { // TEST(CombinedImuFactor, Accelerating) { // const double a = 0.2, v = 50; -// // Set up body pointing towards y axis, and start at 10,20,0 with velocity going in X -// // The body itself has Z axis pointing down +// // Set up body pointing towards y axis, and start at 10,20,0 with velocity +// // going in X The body itself has Z axis pointing down // const Rot3 nRb(Point3(0, 1, 0), Point3(1, 0, 0), Point3(0, 0, -1)); // const Point3 initial_position(10, 20, 0); // const Vector3 initial_velocity(v, 0, 0); // const AcceleratingScenario scenario(nRb, initial_position, initial_velocity, -// Vector3(a, 0, 0)); +// Vector3(a, 0, 0)); -// const double T = 3.0; // seconds +// const double T = 3.0; // seconds // CombinedScenarioRunner runner(scenario, testing::Params(), T / 10); // PreintegratedCombinedMeasurements pim = runner.integrate(T); @@ -92,7 +92,7 @@ static boost::shared_ptr Params() { // auto estimatedCov = runner.estimateCovariance(T, 100); // Eigen::Matrix expected = pim.preintMeasCov(); -// // EXPECT(assert_equal(estimatedCov, expected, 0.1)); +// EXPECT(assert_equal(estimatedCov, expected, 0.1)); // } // /* ************************************************************************* */ @@ -268,38 +268,42 @@ static boost::shared_ptr Params() { // // regression // EXPECT(assert_equal(expected, actual.preintMeasCov())); // } - +// Test that the covariance values for the ImuFactor and the CombinedImuFactor (top-left 9x9) are the same TEST(CombinedImuFactor, SameCovariance) { + // IMU measurements and time delta Vector3 accMeas(0.1577, -0.8251, 9.6111); Vector3 omegaMeas(-0.0210, 0.0311, 0.0145); double deltaT = 0.01; + // Assume zero bias imuBias::ConstantBias currentBias; + // Define params for ImuFactor auto params = PreintegrationParams::MakeSharedU(); - params->setAccelerometerCovariance(pow(0.01, 2) * I_3x3); params->setGyroscopeCovariance(pow(1.75e-4, 2) * I_3x3); params->setIntegrationCovariance(pow(0, 2) * I_3x3); params->setOmegaCoriolis(Vector3::Zero()); + // The IMU preintegration object for ImuFactor PreintegratedImuMeasurements pim(params, currentBias); pim.integrateMeasurement(accMeas, omegaMeas, deltaT); - // std::cout << pim.preintMeasCov() << std::endl << std::endl; - + // Define params for CombinedImuFactor auto combined_params = PreintegrationCombinedParams::MakeSharedU(); - combined_params->setAccelerometerCovariance(pow(0.01, 2) * I_3x3); combined_params->setGyroscopeCovariance(pow(1.75e-4, 2) * I_3x3); combined_params->setIntegrationCovariance(pow(0, 2) * I_3x3); combined_params->setOmegaCoriolis(Vector3::Zero()); + // Set bias integration covariance explicitly to zero + combined_params->setBiasAccOmegaInt(Z_6x6); + // The IMU preintegration object for CombinedImuFactor PreintegratedCombinedMeasurements cpim(combined_params, currentBias); cpim.integrateMeasurement(accMeas, omegaMeas, deltaT); - // std::cout << cpim.preintMeasCov() << std::endl << std::endl; + // Assert if the noise covariance EXPECT(assert_equal(pim.preintMeasCov(), cpim.preintMeasCov().block(0, 0, 9, 9))); } From 755c75278215739d39b36fed689d3ae0b6ca79c5 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 21 Sep 2021 12:29:36 -0400 Subject: [PATCH 0018/1686] update ImuFactor doc --- doc/ImuFactor.lyx | 41 ++++++++++++++++++++++++++++++++++------- doc/ImuFactor.pdf | Bin 225325 -> 225898 bytes 2 files changed, 34 insertions(+), 7 deletions(-) diff --git a/doc/ImuFactor.lyx b/doc/ImuFactor.lyx index bba8f212a..c79a5f37a 100644 --- a/doc/ImuFactor.lyx +++ b/doc/ImuFactor.lyx @@ -1427,15 +1427,34 @@ pose/velocity/bias \begin_layout Standard We expand the state vector as -\begin_inset Formula $\zeta_{k}=[\theta_{k},p_{k},v_{k},a_{k}^{b}, \omega_{k}^{b}]$ +\begin_inset Formula $\zeta_{k}=[\theta_{k},p_{k},v_{k},b_{k}^{a},b_{k}^{\omega}]$ \end_inset -. - For the jacobian + to include the bias terms. + This gives the noise propagation equation as +\end_layout + +\begin_layout Standard +\begin_inset Formula +\begin{equation} +\Sigma_{k+1}=F_{k}\Sigma_{k}F_{k}^{T}+G_{k}\Sigma_{k}G_{k}\label{eq:prop-combined} +\end{equation} + +\end_inset + + +\end_layout + +\begin_layout Standard +where \begin_inset Formula $F_{k}$ \end_inset - of + is the +\begin_inset Formula $15\times15$ +\end_inset + + derivative of \begin_inset Formula $f$ \end_inset @@ -1443,13 +1462,21 @@ We expand the state vector as \begin_inset Formula $\zeta$ \end_inset -, we get a +, and +\begin_inset Formula $G_{k}$ +\end_inset + + is the \begin_inset Formula $15\times15$ \end_inset - matrix. + matrix for first order uncertainty propagation. The top-left \begin_inset Formula $9\times9$ +\end_inset + + of +\begin_inset Formula $F_{k}$ \end_inset is the same as @@ -1481,7 +1508,7 @@ derivation as matrices \begin_layout Standard \begin_inset Formula \[ -F_{k}=\left[\begin{array}{ccccc} +F_{k}\approx\left[\begin{array}{ccccc} I_{3\times3}-\frac{\Delta_{t}}{2}\Skew{\omega_{k}^{b}} & & & & H(\theta_{k})^{-1}\Delta_{t}\\ R_{k}\Skew{-a_{k}^{b}}H(\theta_{k})\frac{\Delta_{t}}{2}^{2} & I_{3\times3} & I_{3\times3}\Delta_{t} & R_{k}\frac{\Delta_{t}}{2}^{2}\\ R_{k}\Skew{-a_{k}^{b}}H(\theta_{k})\Delta_{t} & & I_{3\times3} & R_{k}\Delta_{t}\\ diff --git a/doc/ImuFactor.pdf b/doc/ImuFactor.pdf index 37badae9cc979302341b1dbac23e03b5be7445d9..933c71a749610b513627409ff903042378fbd989 100644 GIT binary patch delta 48287 zcmV(nK=Qw>;0@~J4UqaI!pjjxityai0V)|)#NN|*sas=V4M|64(Egp%ZJPc71)N0( zvmOEKO9L}DH))s60T4qCMat4{F5+;|=j)lC&erHW=t`>QpL|@v)MHDAgr@CYEjku=kT^|msPnATVL98W!>rAaR@_#n{XU3 zLWkxH&P;K6<9`KE8U#`1&#~FAtM10z44&LpWmxn#HW*8=sj-Nn2rCLw2BSNJ&jl$~ zA2z%9b0v=(nqZ7L<-@yoH`US^<|gPe=vIcWa&hM#md zr_&lqEQi<2+8LCQV|HW)DJ4z`J4=!S834Zr&2DU1*Y;~4#RJf~-fmH}2^^BbjY%Lf zBA(*He%%JuiSerY&8{zd8}HdDwb91IR7V4wmm{0X{lk1gqyk?(l)FC!tUHFK_gRfF5M(q;<&Br;^!ZGV+mWlNk1M7Dc3=sC zd4Hg}4DJjEIt4vg3eIN~M965ytawNiy zh#bLp*KYga_`why(*9kRw?TYgYwVM8%3gSUL?Tz1GU=T6K%Iuy7wsNNZpiloWn6K1^aoOd`cns()je$I+ry|is#R)4W^ zh=naY*k_X3WhdpblMS!;&33W2&`9L0!62y1@en3w4RDD(3*SZ`@JVf9pllo^?M#VcJ~_u0Rpz!Ch3# z_bE{y-?ar~D2_BBY}$R?l>0_--+vwW!r?#VvblmtQI&NUc7_W+A#x3Y?ZT!9#aQ?^ zVVU-&umL~~l|PYyca`GwT~qJ%sVnQt7+Cjk2IvUfVX=q>Li$b|jSNx=TCHxaZpu4#kb#(ljHH1U`~6uC@}=~%Rpb-8YBxr#5ju77pc+f_{Q znX~y;8S|s<7eDi_>`+7H7wSaxCQx^ovUmNwrWVF>|rY>(b%0ZNrP zCxCJ$rvda>#D?>lF+07>UQT7sh}aLh4TlnfT{G_ra64N4KCGhucu}ov0GFd1gC9KD z42JUG1~~9ZAI}f^)e#@m-+zrw=a9ROMf_Oahb#IjOcU;gI|p4r80x^gw(KfDWP$Z| zz5BB8pxJj1E^j+8uXi>!5Z7(98Rfu4v*0X+yrDwo22)VUG=3#5O|UOn<-xuz!s)k&efK91*tU zum!yu7nwbI7M;8JP*RUY z56dT80+q)^6mY^BPLL@HWK+oAllni}8`Ka$=-LqPJz%(S={a)rV7U0x<;5=-E`ES> zpbUUA9LfN$7z8ykTYqjYK7Pit6+8q(`T%j~NjFYcDBfYYp8b6BkBhf%vYKc{nHz%5 zxP*R5(20W|4rM$Jkdl!qJC0!xHpejcT^621C$oa9aOW{%z~NNa=F{`Tc|qb?r$XZX zy>|~sM}Tdtr|$bcC)9wllVV!n95cYvKD|6LhN7p(Uk@Vg(0_q#J1T`wV+ZUD2{+KTr*GlQ$Fcw_VniYW9}|`zvDwoq?$qY)T1lQ ztc#SC-llpAPkcTy={d+$k0TSJfEKd};Za=jb8yMdACEq5gfYSrC)^+%KP}X$64;YjwRIC7vogA^tq-^u4A)3q{V$DdmR~ zN1!QALlbH-18GD15gi>O)d^EQDG42ox#R_duKC8G`+pMUz&_~8-#F;1bAs-q7C3UF z+#HOt)9G129c}pZq`!U{{dg3k3~^zm8a)rW2NpXOe;%!6pvjTki6zi>u(M+9uWl~} zF^q}xbdoO?_YYg4v{9r2X~||#`C&ySbZMigG7X^0G>Rwa#zrxYaiLoCzjwLbT$O&_P-vKuWrX#sUXF&cmIPSMDgQp zW7}%!{vjdm&@reVjE6zANq#&ah50>ozZy}&q<9tP8SeEkj}(x74Y-6FXkKGWpog^j zKOWg%WV2vZgeDO*HVQ9HWo~D5Xfhx%GdVXjmm#zP6a+CfF*uhI{{kp~jrj#ooLkm_ z3*+t(g44m>U4pxN2->(e(zv_32X_nZ4#C|?AZTzWxN|w@%uHs!|F62YsA}G4`PzG} z7pj`_gR&Z%D9Es~09aVqnOIoZkSHnDEx|UX|CS?BYMMGa zS%U2N{>wtl(G&=NlZgX=!Ec5NAUlApvkici9l*-P$I8ve!UAApVd4F^A;^&rAP#h~ zGyy0u0c1gTrcOwdVjz2WM@w@H@LQgLKLTisX#uRfyxa_by8}dQO&u+bfp!1|AlSmx z_AR3^&<3CeGPX1YyZ=uJ8UYJ1*q)D>+11sR325uY1adV0NXr0!aJ2+m08~w#OdVZJ zO#pwj3{V8xn*OUbCL~ILx`n0FKMFOF8Q2x*XbN}}*jO5y+BvX z0ZR6!cK;a5|6{-a_}Ae8SeaP=6YgK$e+9C%``a04Yz(rs2imz?+L;5)ENx5yN|N$S zU^g%W0BC3Omm$!9#tHQ14|D-q+5nB-4E`=12#^#}0RZ1R{8xWY#*UWuU?(OgOPjxX zWd1A6+c8VnnTUaGZB6aKPDp>%CvNFzYW#NY?#%zXTx&a!tDWb+$;{Hu#O$v&Oq}hR zHS8=MoK0oK|7G(gLi!^!Hw6PYS$MeFc{l;44gga(V+-bgzY?gs+nfHaWc^G0)`PdF zJ;)wl_SS}}x22is+b<+fC!mWd0PN^&>h1a8ivJ}fR#t$Cr7;*_WNL0{hx8}x5B`uWe3-rIzkfb4AC|Cs-M#mriYTH5L&^#5x4KT1(ikQ>00 zk(~{|$i~Tk0$^p~-~n*IJ$V0b9A%*8zv}oeUl}_y5a6$1f7SbTQ2(yktx|KFJZ73KeR(*JKolFl|Zf9q-fG5G({ z18psB-2Y|qHoDH>w>3}zy)A>?|25Sz{bzR-Oie6*oo)ZGRt5}wTL%$4^S6;^WaVID z;rK^x=_G0CW@@5r2{yL)XKenFYy7ovHkNj#${;7pzg{tKUMwvCNB6d6#@27I5vRA= z{6__JdRsa0-xv88o4zg8|JEU4XACm=Yx~$Zxd1>%N1!{>+vUFzC%}{SZB0!~-Tt0# z05g++9SHp90(k4$8(;=mUI4Sie~6m}z%2QP zSOLsZe~1mhEd7Vr0n9Rg=q;wgA9{dsF-lC}fp|>b%e~1IXtp11Is@D8N zJOJiT{~_MDe84~SrZf5valU1Ldwtpd(f@USBg`g$@GXsrsSWtQ4c@9U`!9Se%lr@i zMZo_J_?F-L55Dafv)zB;+qr@MgY0kaAX`)O|8i%2OK1P*3f}6m2Rec+fi@H5576PZQ_47_Ls=zKgjl$$<6YQ_RZVl-{$`_f5y&# zj*f2w`uB_DZ8-nUfBz{kHFYyJMp{|~8S@8O)dh9j)rb(fGVV+Yz@DYuePUyrEYwE; z4@k@!Y$m8>WiHE=OD^@ZO6ps6D~dYYWv_j|^xUo|ZE)wfVI-B@HzzfUTYSBNoKN(; zB_dlyZ-L0uN)aXDD{&lvP$rJV=s^^JGBF=eqeSdHhQi+-fwezQcKiN1gM_Ha2i8N;f=J@e7%pK-WD|f@?L##?a{S3T8iXZ=}Dh zOTf-KMF<#Ef`6DuoCCgEb0r_`DW}Bc=nIyokrcM@k;y>CI&I2bo#KVX_QjEZ-Uphb z9&QW6B(o^iV~=}cO#2la(KN^0g53y{pV^_L(9J_16K|a~`_e6?zpYjNBDR(d4VH6X zp6{F4cyg9YmC>0R45DFBNDzGax_#{3NZA?fVip3`MqQJFxh+ADn@M}k~j?-M3FJF1IiT9pPGbK~9+e3ABzrw7MN{$*E}DAlq< zb);Q1R+Ps^{fgI@!n}twR_2ig$#A}AVFi9t{Y1Ur&{OR0aKdZ7gEw<9(410Fb z=i|0*WAS2c23tDsOerL7D+!}pcr#-Eq=`Wdz)=|vJV=O*>JZtuYR!qHovS6BKSAjz z74%17;w{_DJi1~xCnUIk%oIc;)#)-IeKmRo8N53eCDJThe;5oHgKxUfA|pM)huUt+ z%J{Ycyf^@TmUL2zrwvLfq&zcWyJ&TdQf#lBlm2)u?tOiZ@G~oZKsy<&7WtDqLMp2j$_F5}&MP$<)j{ zP8&0no*^2d7PIceJ{22loy(vfWt8yc++(a20f;;n%wZr3w{?gOi?#ANIQhVOMnAKR zIR}Y;tkqb@Hfj%l$`pUhtO$qha{D-H_FcOEL5EaNUE-$K>Wk`dgby?QBl7k(?jhhy z8pf&(&$h>>l?3~`tDKB1=?|K>EB+=;ADaC5O*rxk)QixUIQba19$aw9jpbtLRu=i` zJ*M8le~PNc@<6o)yf0LlTX!A!2y_@U;@V-2mU(EMl*6EZ3KlY*Ubu}H3_CPyZ4x-Q zl6#7oqp)tVxmlw$xU!|t!${}dV(bsh-Fa^flppgYSh-JApHgP^oc6~iz_H5>k6Fl; zT=q0l?;P(igA4g}l3VE+E|dVbH0n z>zBDrKBQ28k_^+!Z?flUfy?nR0xJSu-&MT$T-a29<;n!DANmkzX`(%&zaiY+D1=~- zV#&@=ROc@`&?-V~`uIpPbajmaJwsM0XMC`0fP{4Q@oD5q9W*0YNJoU-GBWnyUg)<( zZjTK|k*+aG1T6Ne^ULB?Vf)O^hnLk%I4qzoHRH*8_iC&ugI@#9MPuNoKz0`n4mR=g z3tTOKS3C+~(=)aNZr*TQz6zcZPdKKxySV?Xw$P{Rm6lto_0qlip&jmu-AJHtRKU(a z*VrH7!s*RaUc_7cz9xr^3)sTP~30)IhTacd|VS{^vMz30IHL zSUAgtwP-@v;ET=aN7sb4Plp1(q_v}K24UQPT(CN^z5TW&87VTzGK_FO&@_5ji>s&_ zf%)r)&kw&*_xQ*BYgAA* zNQ1=ejrJ#m`S1F~Ab3p=s3di0B9Zc+g74$*i-jifq8%Y3PSQHs46dqz;W1~;ln}Ik z)~2DhN^?q`?^#xFPhW=roI7k(i6*D|ilYioWkH#+9{l&v$);yiAJ z`%z-vy3Vie!>55B`M9p8yS$-zjntZ(j4gmdsLg}AG|{l#?2CIwzp2LH;Omo9un5db zW&|jhopjPmj}%a?m%hDA=+WxGs#ryTl}wN%wV=T&+!(^d%nQXoG$R9fI3?+kL{Z%3 zr}2YX4hq`lyBU|8!$vMKqB~NZt9NaHv@~-)9p%GMqh#yE>L=}5caYn3lU3Des#`&w zT4x%xu6rY`-Fu<7Y|Z@u*(Q9FdpLU1VM1$QaIOxn$I7@_TCE>e>UT34x>X&2GkifP z1uR_lIamH4>|E-W2$%;~B|& zGk=`qw8lEdyA@P%%~yKi#^rnpBPZlb{?3rEVSp>IEEL~3H2PjqtZG+H;by_|Yyoxo zV=@}%;M8r{4$97NcDnCYlI0`;inEb6ywOADSg2)e&FHSsyggr-xkQ~;3fE&En-0PGNe>+)&F{L!1_=y=i>@MZa*p` zQe%J>VvQ9FL_oe=6qz4bcekMl*pi2AodUP#l0u(p#9^Ht?<4l$SJ(=F&(h&O#;N1* z#{HCNg(}igGG|;)S?rBMuaQ2m-^D`%O2d(mA?SJ(K7Yeto}D8JlCaW*^~_=ozhoT` zRIg3elz*P(bk~ye^6;Cz+)6$7T5bZv7g~v$90Y3$R(UM3FZZY~%KCKd>eO{LzAUgC zKD*?;*xNY}+YL#by+%WB7YcqoP)6))WD(l!hvKD^F2NgktA_=H*fms`E`d1Cx zjlS$gK;*PR$Q+~mb4x<%3= zntY!J6pM+cRS^L4ktdmEgKoQQ;xs7%<94}q%Zr&mEmxw;r)J83qMT6smO7#Xe?2fc zt|8PwlUz#ZlrchoeQrL!M%xc8_4nvZ*@<6@9LcROF=X2X!4;BIgg{mo{?Yy`SbY*l;w7t*RdDVG1GTf(?M3HA6 zTM>_?>%B}ElP*Pmvh8#qJh+*J(k}b;j+@kXE%;(m#b|zsiqknYG5zaa`~W%lQ!b1i zk@eg8Aw$FME-OA}WT^KLpX+1&USBkdDd`@#2z7s4Hi_lyvB?0(sShU58W8Uf-BJQ;lmvZSGiN3c_egaF>0>5Yp&RCx}{z zmOi(<*i!(1sD5JrOVArAB+3&crK4>jXxHDb6|%#A1+S~_SZ3Hzuu!^Le|Q#4=kwz| z*fW@9Z1=YIk)ILXJNfzzbxcaIU%$fQ$04nCbw;ZtB9GBr{GG6q{`)&OsaK}>5Crri zJf+)^FP|e%t*W;qanx5jrcoIvfM34k*LdSR4 zVf=a}4nvL3A{oT094`B)LY_ZiAITJC49=&)ICkp(Z2A^3^7`vh)f8mtlCat4X!71( z=y+B(EEvf5c#j%{51AAZ5#)tv9gt#)}Aa2@g zM(aCe7)!yp;I2fxaCKV}(;1uohGTsZUk(ki^vAEJ`^(DXtM&8z)we%}zUKvb+iGPV zF#c{-*c6%ca58i<@{Y@nT6*qtY7xdUNObC8hDy!ek__t(LRU(V_*Ri>a~ip3p(|y7 zXaso!B;hIi(o8|Kb}_84!H!++@TFn?`fTe`43@0o)ulVK<=W~66CzqDE$3lnOoVu@ zd6$!^)QPW4Z-|gznyo6hvrfpSyP?h)2W$HULb>Sn>Vqjl!OufRFl)>YW&-A+cq4(3 zqq7t&vm$inIurgWG;44?8G2{^wx0^j}#?lxcy|u$kAZ4!f(F0&2Ls~fT`5P=T_>4MIvo;5)q!Xc-ev=KiUKtAs!J)vCup+$#Jx73gLXS6U+o?>z<4FeF zDt;9?YEdXm`pe;f4q{Cz(n5l<^Rs)ahN{2y26Wupe-7-K+)r`L`XBp@5`gRSS+7&EdCIfyBLOG=txB}?zm z((zI5R!`~(AfZK+a%ieToJP!QDQQ+7?I*>5N|Uis!KN|VMZ_2%{jMBgMg~y-B8ATPC}y`sd-g7f zqhHz@d0!m@VH@e7409a;Ww#>8m5CZWgF^$LI68YL6ry`niJ}{S8|xAyVLKK2%W;0y z_$a&Vgm5iprs~nlJVf1HJOrCj*~#`2d|j@iS=lqV62@4_i8*~= z`vhgK55h}ihYZh0l0MO@x}B{h9K=EQyCHJUFfCh@k|VTh zmiyo(i%k1^C9MlX2#4d%kTmO}AtWw9>o=BirdOEpTzHy)+A2>`5N$Q4-7ieK-N5`{c}= zR!F3+9K0}k5`IC{3>c}OzP=tj7~E=(_EaHt6yes_+Y`cD2#v*Qkw68%ux}~vamYvO zOuZh{u8gXGf03jkqk!c@d1h)^Qb)tQrsfX2lt^gT9j13MB$L62DM~p|1%hsMMQsDH zk;|w*iVb!L1YZ*|p6OGoXO(z&LPWgB@$z($H{JEo83f%7qIxSdVB2GR*7LZO5JIg) zm$!I?f`x+icEn-ZqaosnbYiaD#gmr0;cc~w4agIJj3R-rDPFF$m@PbGu7mi(?g1MOl_cvwU#~ij)S}EtiTY-rW>;06=SAL z7|fG@)D(_)jdts)hjIG+RrM4jttHfNTg}CFny>O-Qns|rBg-IP947^tYtg%@SS8iH zCG>uGu;;Cps8JG8DYUpp7ifzWCLtQ#Z?zOh(<6$wzLP6Jy6prIRmNu`7D#Yy6WeGx zh6=!Oyxb{_8W8BIho$>ar@2%UKMJY1BUx>K1W#udZYKHmBByyV))>oUzyw`2sKa39 zoO<{SV`4&Oz7onm5QK2g7gb8pf9@H}5sj){kLW%WY(b!-8uwS{uHfSTY}pj=I@xhPc8VlU&qXO_9TA z=F)sDqMLj`oGm>bX5$RA=-5AN^O9lWbnZ1&Q7*V$44^gqU6!h%GSqZH^8|m(k;sXc zT(4gexE2(Eqp)5L3L{3~l%g|#6q-<#R47H==<|D77&qUFIkfLFTV980~(?roHOpPBl%60HT>u3XMGVVd*UDKdU>lxP_!=sFP zFGXnd%cOh8Qs`+Sq;!hCW$W&%rm;n~9-a-=&-FaXzE!@~Zx~922NdLg!x0D{#Q91g zA~7L?DQThLae#PR847NR&%;Ax2J)#7LPXz8u;?E6LKj)i*z~yFXpY-B?2)UKc{=Eb zm|$EuiL;%?j0CP@>hw&Ih!>?Vn}@6;ytw<{ALi}@iHNzK>IP|Xjn7ZtS+k(ykgq_oB(&<`SF8!#-w+e^qRH3gQ0&EDPELhvMZPyityh$7x#-tGN=TewrGLTbJ{__dgP zcdlXTYC>pC8m?WpayRO=#BcqWa3&#B8TvJ8irS((#vd7Jft=C6`L0U*90k!jKQ%EW z@7ZHi@l_C0$^39a%qI8{t5D1+5B+`e#&vP%tHpcwcw4CFlu7QZAnWPn@2_m?$gqbu zIJSkQ&fUo!VOCCm%brrHZVM#SR&3GGAiNzkHqxeN^CtC)`n?~C$5YqY^>*X$f@*SU zlvqx(!{l^Uy7>_XZF#b7cPf+*FRPi4yTo~*Sff;%zsbwQF=h%{@ih^&0+bkuAp*@e zKE{{rW?SQxeMU}x4Nc97KdScoVt$yo0K=(pWn*axRuoNtGa|t{qq61FRFdM?5EBhy zC4^Od(c7Ta6Z?%$n3zrea4d+a4uZx+15U*PX(QYCGdgdqjkcQad^clKdaw!149#p% z`o^G|Qbhu|H4yPc;c~Nx8{;MC)#hnB``B+KgzN%v7W|VW8H~pK;Jw2)jJT0w35~K@ zrZ|NVBfP$UJkQsl&6#-`7>(B<-X#p!1VDUpR9Q} z%E=aR3A{hM0JkT>H=P$bqxL~r902&#U3Cbzh_qqOIOqRUoIPq&w-l29F^}0JjP*YX90n#G*rh+plAPoHLE^MI2bN{fh4eYa|Ad);Xy~Q>sH} zNQ=GQxxVna;j$#-A5cwy&JcU3KELi0X*2&QRK~GDSNT0buEZ+CF@H`935_BLo@)`2 zUbhl+q#7?=Fzx3MsPanL7cU>MJ$!yH9mzVuzso8jeh=pyV+Pwa>W>Og1xH>{16t(=nYJhu z_bM_PlRRJcpirh?`~};dE!TsJ<14^_-kogrdScxGdMDixg|oXQDuoms;Zcvo!BfkY zvq`uknMckGvMK^MB>miX7ssJOg+h9l=^+mI>kH*0`p})uo>HXNmRnIvcsk)XKIqq3 z_A}Hnwrse`Fv+zii~y8%9l|=JD@VsvyacdggMOVnhdhkH)yC2Bu^emOa| zvm)6UWzQOzqNOPt`6@(2r4xCR`i)e|_{aZ#M^@G|Y0fO|iZWJs<<(?9PHekjYBC|i z7GcxClcUqaYRi0D((HyGKglk^$8}ySiNrZFBUE5QgbH!AmGHXNb9H$%! ztyP6$z6{9ye9W7%r`E}P4SAA(3(9IX*;pn}N^TiK;Zgd@@f+TFTvA1OWABo(?M`H} z)eTwrcgj}To!y-fs@$kCpG`{ z>C;v)Q;n4Z$S|kS{NYv(2d`;;Cl!)DnI(#prT$VyA}U77M>p6qVt6}$#amLaEcQT0 zh9=beegQXqG2a7qe%UJg zHMAST8MbhqTc<6uWzvk(0n-=vNF6X*tPW5F^-@3hVgD9oY8K0Y|bQF+aJR&vcv6RFBEY9XG*Q}^LEhXDu5Cj4N|=$FhBGj_r) zemHl4NzV|beY!~|#W7y7eQ24EMq{M~FaCR$+~5!NoGDvO?h2THg?CeC%T!T}39#wY z%mYk%-V6-7l|RRgV9Wf7OJj!lm30CO6ixBMhssx z2GmbnvvNurc>%G1qT3?t)kJoYLJRS=<0eV39J5Ut^CyQqP_m96+e)hx7qhbZ3|FnI zyIiK3=W3VE$o5+zeRk|o0WQ7z{($o|uh@B)w4chjv-Mf|;m?ul^i)pg1_Jb;k0z@s9~bV z6KeA|9v(^U!&TH^R)u{sT0>t46D92e(2!UWCBxa;SOW7*+4G~O`bEij;Ttq9T!nyS zu3if-X;u$tVQn}48ztUZ284|H0f(A(nFwc(GIK~L@a}1_u05NsCba}GkV-lGELjWs zAb!;!X%EeRs>3+)y&{`2eX@HN3DWR zt;ob>zBwiS{CE>j-%$>>sdhqqWbzLz6)m9^&jg@*&|@d~Jq#3LX#g-2<17~CbS`F} z;5SdnL52BU)tB5A&plYCSrX;;VRXjsL}(=%8qS4(ckLUp-n~sFz307JMDaBf3S~sy zCEreeA`-RG?3ZtSq3Zh1vtVzAiLlKQWAto!NWt8aGDHfJgEaYN<3bS4j79}n^L4_{ z99{WqJQaS5fX3Ia=g32I*G+RwOcO^H(Y~ToFS+?v*Ve>IjMjFIuAt!w$d9HJ0pQ?u zl##@LrFnx5nw+^0_2A@tWlX^`irIW(3+tGth?&wpE5&ngJXErIV|;E~&$n~`Vq|H= zRWpLnpE?4`bN!!(=BWcji3djoamH``u7wXVo$?3@55@(7Au zw#(W1+kU)I`nYFeQ-FG2AKx7?T+_@IsR=26$Gx~6qCPycqP{P~kH_?D7eA^#6z8>o zQCAQGQDjT_sf+p-JIcmD(KsO%pVupmr@{FhyfP7>cZ=pbYemhL>ZLaW4#5p=U8rIC ziiU?Fd0p*Trbbso1AY;b(T;$~I!$_}2O8giE;zQjB-q}<9DX~W6>fN4-*s(I;+`;n zm*VGwXs1{VL&E!TTxX7Uy%^z-L7+}ftgAbR05L?fOwS|T97!@f!INKwMdMAc-jsyj zq$9SJ`G}>;bM3y(doM@_BG z%lklL$_kGUVmzmh-e;UFGocHZQ>Z~NSaxTWZL~&>F=@6DF{{CTO;_nOIPGqeCNmt6 zeezb7_dXV*)LdTMSt7Zh;t1@z$MDMDHx<`|$2I(JYk*ow~PY z-DqQ6={sM!$y?hLEg!BHYWCp8$&64NdQl~cGs{Y7wF>meMNfT_Mu{1JXg<+|1hqieN|%|rq>XcR+;NCQHE%x3?A^+XJ}0z=OK9@V z0YZ8kP7drxiz#Obki|bz^#;-##38C&vrC^54Zv0+>*1bEPey;Q^GsAJio=70@~=xP zQTiQ6oB4Sf*X#W$w%&+qnbMP}BC$x9a+?ATJwjd9`!9INI!!x&nqh%oW?@7$H$z-5 zR$?znAHqiT7Wpe%6@B*H?!1BnnDoJvsT`yF9E*uz(GqPQD>e`mw_a|<=_dR0p)R-M z8A&#Q_wD%Ja+o*mkEw|PZ@GUcHl-v+X)8fVQk5tF<2^*}nZY zirgeAl_qPfcbzJKV7)bY5q0{u+KvbK87&PZQi%#p6;uZiB=$BAH%e|%E%)nVmM>7n}3CW{^*PY5uVm8m{Z^|dK;=? zX{4X~>99Z3U;VTUbMO;2UnC^ofp!`J^)))f;;<$a1oWHJ($7>>xOyM_u&+d3HS}Bz zBx+JVFb&tmyPG|1V|`f}Q6hEPlZj`Yk^VX%kqiYhq_1`ch5K1TA9;9P=#j!(-51Q& zx#=);WJ=dd>)E%h%6w zJvt&A?`g~E$|JaKdqO+KeLuZkt_n*HtVD$Aocuh;H8jvRm+`OU{WNvushGr?xl$?U z-JEb*YwouOZ`oDS1nh?J-n(+EWcd(?RI9=qckOrL^(F%UDDxR}QNB z{#Iy~SntkggB`3rY&!u=K{5+|YiKT(zn8nLDy|oUsdmmEq1{RQNHOX3%?Bq9^=b60 z$|o92oDqFItVX!WN_?1PS+Iq8lu)mf2TYiM+sO=D$vrJ!!$aUNvmF#eqRW>bDP2!Q zsz8zvzR@o?klq8xg#~7eTX9T?aCN9f7&4vTFT&FxLli{E?t}7cA>$TX$aRhg$!#?xv-Q(VW z-tnL;JVl9gjB}v^YXl_a_D9qmoYB=8gb{PGM%mav_^8t;?*JMT555vSWMauSY}A7iTyF6$?n=Ws#RXSIe3wZT2x@ zA@1;g(UM=UB^S<8QtkNTkIAUl&qU9c=bMcx!F!i+xwSUyM;O3rPd4=Yij_0mZVXJR zWXSpB!C*1Eg&RiCCD(uzBu6#4?`=5xGptK3))!dL98TU<9mx#i5cH9-=`}8Y#fVNY zpE6?SYuJ!a*K~cxX3lb28j@o^6Ui#DPcSIhHuLR&@iefm>u9Lp;boWbW;y~pQu%M6 z=l#YHnDZuQ(R|PZn3F@hXi|&vjSx-dsKp+<=doyj&a9&z^Q@b_F61+53UjkIZs8Ff z;hvHynwfXROU1(<2%%_Z)6=VeiL~9HKIKK7mY51aB(fUOzJOKyghh<-G9r`y2^c{L z<2-=+ zvWXRK58vTaA*(t0|}75@U4Cd)&weUuq6vXTvSn4DGKe& z`g0Ok8$)mGWD932DB28RjZ)vgrTaP2Ul@&~FO-jsIyzPZ9;-i3!*{#CCf!PjAk*f> zL_qi$J52px>X$tAL%Q>S5IP1!oby(i4tlSf2_RTDdptw|UP!Xx8#168ZG#o3Y3it4 zDW$ZhoZMdqPQq8A5#w`{uFTDc5FZ--<_*btUA#THT)S9o!^0H)-EE`c_?3+omp|EY#&GFG$tD4_LS0p>1pVEf?Ct~R@+%u z#iH3O^xv?}Z!93ggSZ z^uI3Y!AaK`1^uvpOjWNE{MH!!ZaWec% zXP-v3?tFF0*s0SXTEhmAWb$+L!!Ck4+&jerhGXxxg7{!yau=UQcCDmQLEBqbv~qQ; z>1jUJUj%2l=A6OSxf^Y|(xY zv`#FTcU=sK|sSX=s!7MU9$B5>JXdLBd*-C+f`CrLvV-XbTlzyyxw>?8;lL zxVV!v+Y@PKVaDHY@1hW~?~Zi&`UzuEAYZ2kfO%Lg^|qG2ZcBrhU4kTvj#;`(?eh7y*k?z7$93mCTDp(Zd{vZD8(dx0Ce70G zY9L9AwKXA-{qAievdtlSR};xZA0YeAuf}oG__v4g!_fm^`c!^3OOd)md^5&o-qUHcH~c=qAq?UgqqX}Yy=0ef z{THHtjyqYVM_~iuWayayGA(Z6mMWyH=eu<1oS$Rs?j)FG)18UU2J)ky(DFZ>pdz{o zt@dw=XL1R*^^9>=&mfG1_Hsu-(c0JWip!+lZ0)|ZqUrfX#TAW7Z4rA4o3kNgc8tNW z?Hm1Glij7^dnLDfl{Wb$2-G};Ij_?epLSh;M+(Ae4^S7DbCN#Z{q;`9D|SENJ9RDa zfz2IEsC(@SGmCqaF=0_MB>&X#ONa%WS z%hEWhR6HBpYo{O8P`BZHe>tLE$o}L9MwL?;5tHys_2_F}-3s={!Nuf=D zYOC6$|8hkkoY#6sCFn##w>F^+o#@rF;~3PoH>%gCq)>9P>wRwoud72D<=GMKo6{iE zYBA}+hK7CA3jHwNKV-NO?d5Brgl;NSKmRG5L+T7aRXZI2m4L4VaIuR z1<@_?+?)J969r{fsTq4o7Sdtf@QCz(r!)gA?cfw;8C0+DC3)ImI=-$L`$D2azuOl- z({({?ZYkQFR8L!tl13Y@EfW`ee~G@KkQ5BVp%ec^_Zex-JeVnh-Z;FJ$~gmNZ7gs3 zS#igrw+q3%wkk)uwPN{lO2&pNl1ho&>cU%o9_h~DopPb|9#QiqY48|Nih3Y_Pg-he z!*SpNQJLrHZPp72NtGnvK>w0(STYMCh-{M*H@|*&lKH$W#_JO=^x2IDo-wLMGCg7c z%rD4}iB#(BPv1tq9)sqYIRnF&!?e;T^i!~6`kfl5ue!mQW^nH%xnJA0eZ%1Azlu6r zk@1$V{pe7o{?(RE7p#6bdKLSBT?G)_o5I+_Hq1y>j;^x!oK6NBfpKM33Vuv9#Q>9E zOqGiMxOTwt&ob*gO6sM$>3%->(vX`=_oIdCjA$5*=I>7j;BIMN|vHcWE20^d^J@8(?w*U84^<#j}nFZN~9+wY(X4s zS-&T_T(V@@lAffgQLDB`wS7b-vY8Vs6~?Bh;)rz5Mv(&`kmO zMadrPTf2z|FeAD(w&wc%nYm}5v8Jcj#|(;9Nzi*;9bm72SfIe=Z>7;<+sAC$F6N{vGD1P_ajc> zNdr|&eG>)p7kF_Po?|!QI=t~0B%LS)07gK$zf+^Lg@N3QZH3flw})=6#91NQyn|}q zNKx%9UUb3CD>G-|f9TMm0gR=@+}uTW)8odeV2Q%-_VWmgxTBumE)^oPjEhJRSn%{8nC;V>mL8f8&p`PD*G%Ic5hbdf% z&25hOVhMNf=tY))Ocz1q7?`LruoKG1EUq}!dI@wiKD+aO-s%(6bO^q``EfjWmHZvz z@TZ->s`=M-f0!1pD&t?`i?cV%CJfogdpI1baL!3xaCR0YMRYx=q|pV1G11LPh}GtL z=btw!0@eLqZtX%z_ZG7(ivlhh=vB%-<<5EmJl=N(e|g0BCAs3(Ki7<*f-`-H0r+a- z7b{hk8?l95`F+Y4sUw)K~Zi)gnJBD#e6 z9=?-t9-h-P*}7SDN&uTNsg-n`Rr363yk*R?t!2vbABkM0J94Y2zjurOf?-WAlm<=D zvR6W*e;}{=`okf8Ta%#wB7(s)I;jV*`>MHN($O(f?K2>jzt1c>rIMw;AR8z`+mq2Ath~P4Mg@QImftRyQ=hFG6>$U?o0btonvMZoC2A| z+>}~7nrc{_M3W8vqd7q~Q@W_D+PxYFy@R9QCn?vLQWfDdEgh~zi)A&#$2|-af4W#& zYk`zs^yVP2?cZnJn>7T%+5~GreVN}{%%Zk-ds1uBR-dSRbVSRZ?1miD3g{>SZby

~OfkOd`-4xEMWU~8bWDfb04Jn!M~#U~ zLz{eeLB+euQG2e!aTj@bi9L=W@^&Ur%qcEd(%UPfQ|jra_ol9dN`KUVMSu z`hNh=ve5stYqnw@5HvOlFHB`_XLM*XAUQWOF_$5<0Tcx>FgH0lmp^L(D1WpCR9xv2 zEliN$PJ%;2Bik%gG+$m1Pc;0!686!w-6wBfCLEc;gOlSGjs3% zul3&QwN9U1wX43W`gR>gI!zr;DJz5pR2~6$;{(2 z5D_lI09l9!%nG2!1yDx7p{`hrG6*Mc7nqH$+ru&cc?GaovI4+DLeDt<2nR?xLS0~% z5I8^$;${nVd^ph(;sDS=Si+!g-v5+tbsN3*zX?g@16d5ohH9c*5Ll z0oqVksEY^G3h=vOfI7qx`e$ccSd0K&TbS#gb{&MZnMNml)nzybJcHUKae`0sRoMgL9&gZ~i>v9v@uIziyxFt`oC8s-26 zXvnK_xp}#903dLy-+x4igDc`89^wIkIY2BP2!B)#0mw^f0U!?z{?(qVr3=i-&6Ud) z=J2~k?%!!1rYr}yl0i5+Lg8+%SikF&g}Fd2AI9#@{pZcv!x5fv-@kx03~pupy9q0I zCvH7B%-J2PB>NZT!G!gX%?9cQ;0Fml;}zruK%D_lFH2kQ-+$?Ky`7+cIKjWo4;}dX zIw70@)(=fU{bAP7hd(S|SBM7`;O62E_4oa^S}tE9$9hD;l!@+40{#X=#KPz?YMU z55UR84+4O}V1E$c*~5$ff2Yxe!2T)&^iQl3+!_IR;QvwX!<_z8vd3QvVEJo1SONc? zOdatcTPT3#AC((}_(7Hr5Agr9*8d3k|C9LdEdMu^|8GI^?hX!rxLN-2|9{*NN0@{6 zUxWwMy1PAWfEwaq58(exeGdI|Yt^7uFn7oQ^(whR9)C7L3U2eDW==347l`jqJIqxc z<^{FVgt=MT{;8Qi?Rvj=%>f37Y9d@=zdtSyQ6SL&_#PI_(*EHC;`$)WKV1;lhi!BF z;~IZs=)*q!cO7zYON7<$#pB@@06<(^Al_IHSO0+c0lwge4Yh)L{UL1tHy0e?_7DPi z=-D4&jel^#`hCrUJOFO(-=;qiAAno;A0!CiHuxI}Jp*t<{y`5ui@(wDPPnc9fe&e{ zpbl>T(7_ME(0^kPFM!+TUyvWb4f_`q0C3y=3qC~K{{tUn$_@V;@;+ojI6`gyl^pyK z?)DFSDD^>f|33Y<$>Sf$^N`T%5BOiRwRCrJd4CxGA1m=N`2XNPzHm^e7t|8#^Blrb zB+RZZtnIQ^iqeyFYfKdFF!R!YhjXmh6vM4gZpv&eS?6`mqDqDQ=U%Y9sa>bKwDV=| z%KVA%W<70#H{UrYt^AG+twrM8{rRJr6yFOf`Z@gfNCnT+rD=pqUHXtTsbdMcFeR*P z`hRp7@%@>ZldaX_H|M$P}i2I3zQ^1%IL&*yTjqreJ+1!*4Il`c`6#2+FwP7mx#^N5`=y6K>?g0>XqA9e4N=4F05w@xDXW6x)D&#IQBND@uVtyoPU7N zN$IX+zfCCRk=GsX9#rK=D!h9#6jr=Ut z!)*E2fhMz?nQd*3FDMOf&kJ_0W*baCrd|L}&ST7uZS~FPmB9PT=bLwrl7@0rFWx}g3wIPa0jzUinR`Cq zj?nsSlXO5vMe2@htda%Bud~Ny*a93c#YC235gZfhXG&^0c8O-U9{LEREye*t+k(;o zE!ZQ#hirZW(Uty+w+<4mBVC`bu>{(@`oEu;p~PR3&~t$M<5dO zCF#b=lJ$5)Y!y9p^NgR4^%zD*oKB%Eob!{{lYwA``nm+qH8O2`d+!?_qhE2*Y3^j> ztJw<1d)#ad0{WUCp8B43AmvxTUK?YWE!N7ltx+}|SRaS=<7*OP?tcP@wA`G#n%%`M zLF^1emU+VavwXl2UTt>UfJfesc=_K|->viUsDza_g*Kc!ZtX2U_u--}wArGwieU-p6mf^r zTFSC?p1KN~Zd$lU+Nmk8P3PT+gJeso2N}K`i>&p= zad6y)SM4=P8*1_MW-s(&|Q2Zfr@*t9)Bb9;*+w#R(?sdacM{< z+acPFuU>LnLUt$-=co6}$O?rKmEdkw%4mMQE_u-I%~Y89o|-l(&ZBw!2{5abbM6I% zLv%ibRy#dysz*K8&R?E}WnM0u~t$%Lo2Ca?3JMTr8p5iTBwR}&r-zM-qA9Uq3Le492baoDR=~W_fT%K`8 za^n_)5fIGcNulSj)*mKti$N?+`wE1-Sh)YaZ>5&05HYM) zD-DuE@!tY8jEs?6qIvFPtR+9{px3eTHOl0u(uD4vNIT0iFH9lyoC90Xuw*7eQaX-V;!* z$`jn*C{#@nsNeGJQRu}4CkurrCC*5H3!>&1IDZCi+`L@@8m;g%(KAP!FV^@IhIiY% zeevyE0ABD~ee1d+3akIV&UEP9{{9T5H(O!9DnPVbXK-SG%8%7NsLw%R&0yhbaI^0G zxFL_rznj~a!lXEH&Vj7D36pfPl#u=@gO-Qf)Ugydo@eUkL$gyVeMekyBeH%!WpYdDnl|q=FpU@&`QzUQ$xbMr*Z@u#iCN2 z45)R9%!A8u-2@uOPs^@4q?Ke)H$wtz{XF9Y*Xs4Mr@Qh`inS%*NpeZ&`In)V#0eCJ z28Zwr73qd)l=c0h3?Xkm!Zq1W)>r=|wSUQ^G&91Z4L-S9z>Z&BmMrT+AC}G|r=R~J zlWZ1}Lu!-1>@E}f>3On&tzuuyTUD<8bw*uFmjEi)ffq7aO4=i2%`pu_%yR|{R$~Iy z%;~1b;<3m{=SkYDUGDnxUcloVac{@imbq-E)yHREEsygKV^h%*b7)R6yz?XMuYa04 z?q}@16sMl?n#F!!h@NdU1r->DBn(a-zrycGL@vzP1@M0QydK@B0b*r1v zFaX&|ZTPMmAdFj*+mQHv1gEwCTNe@_eEjD{dqEsY?oJz>CSAw4Lp&JdD}UeZw#RI+ zSDc&F`b`D7S56IOUT|t{%k6A#IEv*KDNl=+*50TL8#6O%C3~-cuP$!_W+wD>oQBD} zD9UxnL270wgO@F89a+-Lo_U1ss5~f9I9}5 zgoBA)51)g!J<&D3SFm$pZhx`y?j3;x`+TSdW!trce5zp=GUWN_fudvR>%D?HV~5;1 z%xB`3yP`MHsKTPY}+Wbcf9(V%8#%N)Y6L{Tvg5T-edtXn`ID*dtAv>Tu+b_@r zsb*`LfmwFsoWsII{?#ADpZL-95xXDNJJLOgMonYwbJ~Q7zbfF~h=1zn02Mt8JOn;r z4SzzfYiR(0BQb)p;||;66|j$>%fQi)?;HRn+8(o!q+c@@H3HpeWPLPu&*zbGb2}`; zRX#q+*|e{`J`FtuMus;MVck4(yILDL++H=WU%0!Vxh8gf*;H!H6@T-B>K*7hbK;?gNMB4q#iqCULz zt|C-eFL(vU#1tm&42JQ)p|Olk^(ETZXYVq zR9@PimkXB9LVtFAW5mOf(RmSl^tlpFF8dwxIQE9;*#Z;KTY4W|AwRo!s>4m+oSvFo zYcIYVCo51;U3te9D>&h3l=9Q;E>f!5pVMdQ7&l?j>QF?)>tW?zIc0o076AmzWr|LX z|6uG~k8ttgT7T#edc(e~8(eu`_T$Z>uT(!0ANhq(JZqk18l)sJLKR@gDBOa=5osk+ zhJ@gp&qPy#57K%I(i=L%=jiV-zD`_THdD$@%%xqns%g#I;k8BH_mkOiy-dH(IhV{y zOY+zH`RfzAW1c*%(5&oi!EpJ{>P<}Ccn7q?&Zl(ci+@{&I`wxEaCMZD&5*e5^>iTE zlYvX1LCGtd5M{)IHfTh6Saxt>GOS#zZIAh0>*@ZF2uqAPHeECOK%TE|d$o(uT1LM> zJH@bKdhaCYXAnmc|K#&h+zYPZlPkTE*VhR-k)rX&cyCnrcKQaDj!7Qr8z<`(p#=m~ z8pM#^AAbqbb)WOb_ZD|uR29Vv$+$E21gHmn9B5+E+M)NMyS83CUoZJU=o%>7rPM(_ z^%?+dFG)M%Cam~8G;LJqIxB-^_2dlr;mT_|k77k_VxuF4D^#R8g*^b%9*4lY#%D{T zcMN~*i^n_A2H5(_XqHoc!c22jr6hV#RRtg!!hfLG^H|}7GTm~n8cNqi{5DQ8UMcBn z>6tro%a~)u&7&WpJXKsUp=05ky>1r7@qz zA%6!5+orzCx&n_9H}k0s7ct3xa}WA5L%oikhD@##W4KDNif`*XpBp~T*m>-gWD@F; z#3q^w)su0S?2BXC-H_qBVTM014y8EO7dIxo0YQLBl)1Q3oiXGG{w7|xAs*V+&8%)k z1Vyf@V>`t+%QCL7fQ*paF^8i_#Z zqe5@rq{}}4C0|D$5h-&&DhXTKele4QDT%TlAQ+rVaqi{jk(gV-6+>*TSI>ZpZGY<3 z>+86SRBs;fGUl2VxD#yjWs76<=uYeAmv&u#)%ao)YCmptP!xVO;5B0~O_C$<_xH{w<`W|m0x7ThAy1>ZJv&N;##{}h{)lHWZ#YKy zw-DRsX0l{$BSGSCiCw9lmVtdP>sI3GSUT=)3hNeC)B0<4AOjf}DRknNL=e7yS&5 zageQEO`UoL;^WlzTw(yF3EvSd?DagE`UM>K`Pm)AL8hQOs)~W(iGDj(kbk9OI;TGI z^1j02D2;WsGhs(76OlH=Uw68p7x?;F$o9rP!EhAYxRgQ}Uk}(N(edT(J?{Q!j+ptx zmry0q69P8QT=tyvyKJH9{T2JJ9bAO$t>|~n?NlM6DX4feyMUOTwOu6lkZHuO?X)R76s8b2k zCpkaMSQ)M}>ieikca1y>a!xT{o#py3VIfo~^I;kao?N2v#46e}s78;3^YO_sa54aViL7qoLKh zd(MSpZqo{hW-b1BWQqP=*!M%{_Dl9m*INl}cySp~dqCX4m25I$rfOWxF{V$l%x6GV zPVCKk^2<2yG8wtyUq{Mc3l}E5DyM3)lwB{f=}M1xZdoR%(`GWo*B5PEO)ka+sm(>Q zi5|~XJ=I4Ndw;*2U~69&{yHT=7hU=C+(3khy#C1qe0H&%INVCZj`jH%5dq{o-#-H0IDgnWx%S?S8HY6R<}`W<7rr%53#U zJ!|9hN0zu!hp&C$ifZY>MOiXaleMBYABt10;ljddBARVb%Gw!jO%5nxaM(@ z3)zfUu7zIUH{nr3{P$L8Wo41c~LBmJmxU>jB zvY+tf09#}B9b?1B^&=YL1Et4?dhEs3nO&_+!;GT9)V6XTlL z>+(Io@rN`Kyzm)dy7D_M^Plij%1{Q2|i>Zv!CYswXD zA9U9XflKr!Q?_3y!{?7+&&~LWhhC*okU>;Nb;~L!P8jBakw}prxX|_v0KxqkKd}u_ zAZU)?fy4K>S3*Y4L z=bjt{Rzw_vQ~B=)$a0LupS+nqw|}h#Zi6S~N8*ih&84dB(Ld=(*u7U=PhSvb*TIo( z7B*p5EYa=bCnf2LwSJOhte+rkJY-XK1{yf5E?)60O1 zB_X!6>tY~{pIz9m>7Iqn)4NJxbxqq>p1-wT-CIkjw(n_ zr6b)$V|#7Yh^-hcci=C?7k^M;51di(tMyFmNS@jMXgwKAfjZ$mvmIHcp8zhvnxNif zR}mY1duH*Hpn%YGYv`Mr^cxa)QCF0!nn}yRU-`n&p0Spt7 z9+jn%emyA*J;YgIzshY>9~<>7b6>2 zCfmuXVl|)Mwb}%~%1efhDEa2l^vUd9>4u$<) zfhD3d_2xjil-{5XOV%fBJjMA7zeo<^BszkAG=n+eVE8@rGeUB>t>G~n!6#v8eyjn~ z$_Ab_!k!kxgG(h$BILl1BnXFQzu6HAKY>MvEElVDqvcw_8h^heIpG0Ed5pbuV)eX@ zR^$Ln5dbSAa|XRGfSxHyAeNT~j*)taG$p(}dc=({!MWSJXFys?ODR=~d3z6`woW-RLp_*N%Ux1bz3cuj{zrxs|h z;I|EYbZEZ?Gk@`AoW5rZFbo)LWKZQTJjLxYOkAF2KbO2G^muGv z0t96;rvk37aRj@RxVRuO+ow^BItebLZB`A^bRCO07(@3^R=YT)4)VIfC=_%t&1At{ zro(MS>+|IVHRYfU;U)DM7=SH2vWbmlwWTR9i|XjCV1GkVK!rz)Oq+S;Y^We$p~yvN z;qmZis|`}0;C;(^*e^WM9|oPZjNVORd_c9=O1;T0Q!Ss&;*WM`chpz2^t#kk-RZ%+ zIOkmD>CToR1h4s+^!Hct`G(>)c?qh)iSDe0L#;`JVywpUoMVo(__j8e;S1aw5L2!e zTBNoQRex^B{1udiy!eTYYI)6_6RtNZuFd+Zz^=KJyMhkOGzz1cL ziYM|rEz^9u#XBu2r|iZkKAFd{82ae9rW2=0(w8!t=Nq-@o^P}BJU(1e1xCkiENh` zJVL>vZtnS+)~!c;&oY0}f5b2_if7@L@IaE@tX+Vnl27f)jZRy_B(ud$sniy`qjXs2RB9`2~ZVJOe zN{bqLK6#CFC^FA^Ht-8`FpBs3h8xa^}19*!w&Z)rn zHmg1p87zcxtY-H)zhV=rQKrN-3Y4gjCy4|{Rf(m~4_oCEjkAY}gHsN!lTGzZJ(bcq zK`S_~r;2sk(Pi%w6^17|@o2vg6Mqm3yeg6H4E(zC#T)OJC1iN8zSDQZ#k;XD8Wi-^ z26ZU=Tw0=Gd(knRWkyfMzM=Aty{K8eyIhQ4-kG5eAW7M%GFN#az!b_$988^?@hISD z_w8xQq|Mw=EVI)99m5XY+uNbXhCJ$8<9#XQdDf-Vh-_uV7!?&+LI}fHW`Dph;ddw_ zuEAe-O#o|TCG*~oi)B71`oo?n+8BtxY2S^umpaa1isY2bfo`J)FI;U&reIq|>iQYNzrf_(;DPx%&mEa}3L_*grd4KijoBC6n(?F4l5m7$# z~PPjYGzqBGRLG za{byO!UE6c=-R@tg73(}fFDZe;G`IAu8~73E&*8`p+dV9=V_AgYDHnoBt0c2Bd#C$ z-tCe134Fd@2~i~#RDb198bg;jdY6wg1T7M!iq-<5isX^3L)7AV-_u@;#h;vxb@Bd^Y|%q>VdwKpVPq`iYSVb zZdP+52i8m!TYKy7QY26>w*0Ja_ukiog>QzVgZJxC4%E%Z#eX~$-JX_kpN?b_k_bY> zos&0Oas5gbYs#(B*^jrDA^GFcsMB!@->uB;)Gshep^BzkVY2#MwYd66&}ln&jrgIo zpVtIoDR>9m3H0R)!%5_vZsl-|pH*<>&AZ@xQ(nf)-604_F8= z*{swkU(s*Vcs1jcX}uwM1{-Q20(aDClyU67`ci@llGFR5t-4)v+!ykA21m9_T;mQ2 zPxFFKlg4boFda#;hEhD)R7pu}e(Cc&lgW&VQqv^R_2+;lR(fsd}>0{TfsB#${(O zN8Co-q<=>M9+q3H^7Sqc327@PMdVUPc+#^rGy_Vo+_+@f(MSYTJ`8T!ufg^5vl_o4 z%Mo=1w>_WaY>!x#f8RaBLyI$7nXAV1!{sRJb~&8bes@sS8kWZJyu4$JWcctclS|6w zd9Qj$sKwDXHlYYFX4HnJ&7O6U?POwzR(shiX@8oaIjOHRD$1jCygU&!dOb#WuStd9j&#Yt$pqBTGsjZU_*asf_qSr@P1KoI4Lf?stP~;K%e-m%FljE_L6O zT;?&COFmo)U)$banZTM#wDiTaQL327{f48**AJ%B6&!(-23(dV!A~+mxxL52>X*kCo>DPaU!^jE`_o-S3QI zs-5H7lol{rx?{@2AyL8ab0zXdZ@v??Tz@1nbC6n*#W|yBabtSZzyItyK57*7D5hD8 zlxQpW1t!k^r-%^}Ki317M|bSC6S{!rWS0|yCrs7SE;Ujc$?E+c#6^)-JM2w*?d1@Z zFI`)%H<>q(% z2&wPHF}N1aQ$hfhKHaX4`o3ah#-$IFTKl`30c!8{uFJ8K`}lxJ?ZUx)l!A!qh8zoH zjEXrVD#Vx=rIotox5_hQqgLI@8Gl)CKmU93a+U%`eiyZpF>U1`URmZkY5%I9r@r5j zG!!#zlv@*!4$}6g!?(H|H&@!jOvf4}qw$XBN!pH8?-7H^w^BDNGcyr4_R|Q&p-rO_ zg`mx{tQLQ3H3hrGMGUdZ!7u!j7JT~Pvu?Ngk5e^tMVs>{p86I0Bbj{{Hh)hg1r_J& z2dDA6P_kL#I|fy*Sg#b**~??sly#fJSJ+Nai4^rwjVqBGcbrL|&ZZ*c<;P^5<$99U zk_<67JLA$)FxpD4$lu)rUCOV3)p4xU#bc8Y4g#+uP%kLUx0~?YDfT+vN>ge$MymzU z93erKcR(w14v(iR9FN;&iGO6ti^tN742I|z5(f7b3-IOomEwnd+jOL1iP+4sF=0u& zn#kMzBX?IyW%qk3&)7XeOQ_sRlvcM*OXSPM0sCKjT!ZY$oc%og;j@g+LIi@zKSyrg zjePse7BnlVtA8P?TJdfE$y(g0Kc}RYt@}FxkU+qxSSL~JH5m?b6o1R`C2W36p^>V~ zrD?Z)``L>DT3Ihe5w6BPWy(G2kD7N3;pVZrOhT|v2{h#Vwcow3MYmEdQp&jfTeOF* zw3XtZ_v+KfA;03({pFFKF9WmE38fmk1@keRc9mYT;U_nz(2)r&*&tiTRYrtIqm-MF zx}Yk72Kv0*AtD}h_p~}Q0p`9gqEj1j0!#d6|X@b_^b4? z%VH1Ho#|U6-zfv6LT>0{lF+ithWBWK5qA#$ilqV-jy-9wgMW?ko*(7CnaEvW8`~gy zlS}BMB@S^kuNQhl6|0k>(_FmRRJRIMJL%zp<&j_V zPW#J84Co5BV?B5z1 zyokeK!qit=T$*+wSWkI_%SM$bohq1Q5!@G)gX43C&wsN0LU;s0JUW~qXQWVOB(lSC z0vi+8fWfafooK!5?)l3H{YtHa`}`*XrjI}WG;WOj(P#IGRtm*Wswc>2YlZWL>u7LF zNp%FF$8*tzgnbJEgJb839-~ynFh7S^vw&%(Sq2yRx}npX0Fm1_{;xl@G|ty0SCx(X z{U0DE2LYFZi2k>T{s9lP12s7|mm#zP6a_IfF*!7se!9cnv|*n8#^m2fR*_h0u`0GGtk5pjV+6SV z&$2c7pJn<#>wj5i&;MA=2yAQsbC8)Uz!Yc+vPWR~mu|B577hTe|Afum9RHj8hmgxZ z`~bB7Xh;Vz2U`4tcC)orG_eB$XvH1u9Nk=j&Hx1mbD*<5K-Iy{#Qwi16FZQt*Z(i> z{~}~vP5#kA)ZX$Rm<+>@5LmuK#Fh;%xrEz`xVV zCZPXJ&wt7McbWif|Ib%2adifH0`yp!|1}=0|9bvw8T>z#n3#j7e-9HI4<~@>8#^n2 zjpLseF9*Bd|A(%bo3k^}-u2&t|I^EV{eKS<5aj znKIU3SYiWTp6t5PLkA65nHwEk5ZtO0QW2!pJB*0`$zN?vc#BFVq#c0if9#=nM{H5gU2W{dWZdx@ zto42HIm$-LozuF5X`)RwPRv;vMB$mLGZw*h`%$65Lql3P7VWVNp9XErawZCAWZ~Le zi98rF`fH*y0o#~#@@>*PR^UCF#3@$GRQ=)F=oi%nl|ZA(ITw^`qIk`sdt~fr);g~7 z?=iQj8sVd_e;Y?s^M}x`M9Zp9BWxo!au=G!T}Sd;ep0E=H<;AJzUG)6={)!*6#!@J zKm-(nX}YT1evO@NgM1=pC$SOHvm%H6Daq+dTvayX@!cuJIcJ74u5P$n5;>Gs==#P_ zJ~#doXIt23Eg7TtMc&X|4=?`{KG^5Sn5B9lv4nPge^%3TmVmh_i3_pz(T2_Hl!rAu z)*Q?~zAiQ2Q!_sYqu{pBtjgp4F+%A;ao-*2c+HRnZRmnQNt$HViN3iEj$IjdgE?D@ zy%g6rt1v}s`~1{=kk}s{lVEg&ACspbe)Yh%D)C?V*Q7!x5CZ(-*anNs>1=i5t)YpW zji8=!e~QO>1|yQXI)EpYO~lOv8%BUJj~-$__vLM zY;O9rZ(Ip3roPk!Sj6H~lwVmd1kPcY?rJ`TA#wJ^=N6pFy}LU)Wj@umc^14OW<(_y zfs@YGNycMX(h`RVYjuhF;EI9Wd3k3veJg6HHwFVlVEoV*kkJ-HQ#=)ZwaZs7G)=nr ze<#{Sc9vdVZJE-JnFUu~^?-_gD-3-qi`2`z_JY z5qRAvKQC6hD(sOnQw9BN@9LKvuufc&f8o{<#0|Kn2QSr5k@dETpSG~}c_!5uk(^2V zb4>djuOfU+l9?LIW45C1sl(|e2O3i`tyB=GZVb|a>Y85kZRI(7ydK=;|mJJCc~lV}a={NHYCNWv*(MJp-SAL_ zrsr-L7cIIvi(Z|G3+NvqT0OQAbcL<|%Au%BqEPp`UJ>_AiaiaGZr+01LCx1C?fpx@ zWjcr}S^5k4wr$_s$^EcYF-|w?e4)S9wJU-p=f~Sxi%Tzj#>W}!^H|VmH z=dNo&dhta$6CyRWcxjqw^iIi0gYm8J!jte1C;ySYY2V}v+U*E2@+mC`eYXmb*p`0mXg zGEa$fV6|GV$?Noiei0}g3Pg!wac+LH_j#)8(1A%8v1Lw{=*588Wk z(178UtIl_~rj8;bX!sGJf2PeKHmUV_euSxKg~k=JO)87$h&_fSWgROBKp}9i9;Se0 z6Q{cKhCx5HU<81yw6l|8*!9Eejk$tOL20+YD6T8R?C2b7I%80gFFzP4Z)Z_eSD9)f zqj0eyOn8rTMKkrhk-&Yw*!V9}WgWIF;8gaXBnaj7F~(b{0)v^he_!}Z!=^=kMq{1@ z$q0{pS#1DlL%(cfc`a7Aw=88bS-mT$VO`XlclUZt!98{a5|LcFh}ZpZp3f zn7Z&u1_Fk%deAz5f3qVc?XyvM7q0euLK^T8X^YM@0>8Oz zi}-%fKn9olOqFq;Iht|$b-2>w*S;zH`e6h%xLSF5klxmFN-onScxK4Ql$9b$*c)$e zj-SsLoV@z}xN17A_jLpglP5Rg|44=d>FpM{2Hj4K4J=r%ou@- zbpo20IWTNezSR4qrNji~LgjI*F4uqTM8K4;9_C2=A7PVy{3qV`M3{xF7s|5$F#ZL# zh})+)A_qYhcqS_I^X;LVp$c0}%+&ou*L31A-dB4?e?9ZP^zJS8D0N-XB2yLhTifYL zc?DJL^s(l;6C4U1wCmEN8PNT`Qp6cw*{Y}*;sQk@6D<1o6ON0{>I zpr({~e_NDjlfYqFd=mzpNq+-pQ|1*~JF_%QTNi__!)PcXi8L9zG7n^lRn(6wuj}fI zXF0exT(y)5#1l^5jCOJ~bf>u<%r%kH~2%y0F~}oH;*N%ECzn`sajCN?mBd zdXenD5chEmp8udL>r1QlhqtckxL}64l|yi|e>u~b4tlz=#S$nl_Q8Kd^u) ze^NV79o?J8Y~cVd&pS8Bsk}-e>yG7k!?jIV*_Y3YHM&6v#7J|>#ma-0WI6)7f z(Bt@mAA&gFES=v)eKXsv36`3)FYBg>-$xg_7o0NV+sAvq-xjVP@jnb)I^=)hWs;Ct zsFo-7(PTWR%KwF54tf;ZjEb<6S|X?#e@wYwDne?==m;{Mo}ZC@4j7-(cwM_8TdaOJ zaa}?VWRZ6nU}@+SnWWPkBB#@ts_gbixzt_yX*ONnyQzXybBksOHIqyAb&mhkOedFD z`<6@wIi=}&8|)nHIbk|;K#Z%q+wPW66>&&T4~v6LJHSJh)VY;Ek@?v&2?^zCe{%I) z6r1YpyNkLvsEw-IjYW<1-vn78Y#Kj#!j#bkaK%SgU(Az`EdWr3U3uGA&;=uNG}M zhma9c>Z+ghgM@bNDgAVBfI&q zNK4J3>l!1m7!5;eoM2j#--ddtj3o-mc^U-|n1Ss(dXq~|5>*3x7$v1Dbi0W$NISW@ zCMtT%@b;!Ib9L)NT!eXA<#WvIm>g%D36h2IgGP$aO;jPr;1;8Mr%zLqe>;#gV@C$9 z1y~R1SkF>u|5A5-tmbTx?7(64pBE9qZZ0glEEAep>boCb!|dRsE=$Eqtp>Q}XfFVa zBKnw5yo-?^j4N&zwq47g;Kt375yY}}apGEy@bV0Y%#lqS27sY%u*Lgv2z}zjm!rdL zlkV0w7cgwk_t$~xUv{iKe<^xVdyfGh$7CuqA&Qzf-dJ$iSQR79eP)SDS!2om%XTfp z`7WmHs7*(btXl=^w17r_7L)h_^Q%a)#?sZ^iF(+S;K6gpACgWKCBF@mf1Ru|c}HHq zR;dSBd_$iC+81HCyCwT!R4g0nj(rkRg7Z7Yi5?SKQ|mIQV5@z1e-eX+{ec@Exb#ih z@z?mW=2kH~Y>(M^a#s)J>Ju9~o{*wi$+`19zC*@4ulg)FI`Vnwlj3t8LCvddo4FIp zi6YEZNCtQaQPv6*v~R#1IIa0=P11@SezKu66$Bf;idSPX5rUxUR0fKvg@bt#^1WIz zz^td#L2f5!=gdmsf4kz28H<8Cn$l+Fom-b?t@JC8TxkqU{x6GST?PVVHyix`#iD1c z7WH})0Q&FpQEPl!9;WloGbjKjhS5S3tq%`8k+BD}vt5$;3be~cWW<3`*$=-2#&q_8 zSUEALR9>%A21AYyu1E=Kzh>dc$T@(Eo9$#xEyV)oCxst3e>g=VG_Al1syTUV?;9SmZ0-#04Ev6gQz-t32hDITcK0Ih;3VvzojUbnF_IASngc49*txha$!fC-YJ2XvbC2(~BsM?>@#C-6 zv|W;M-R-Ugwu@{x1LR@G3|{uTfZQuCn|`BEf>8D5tJ}G4N)s0m(-F1q!FKyWTUm^R z9DgIHCN5BNpj!hoi9QfDa)FDD-=dKtVra>XlCZf$M!JZVj9+ML@4W`$!%vewAOlLl zcjMTd_8p?~DWW^`Asw%C8~4e9?BpZf$TLsOcv1El(q_tsSE$&p`Wsi3eo5iY8yY)ib zjP5~D&y#r>Z%Gs>5zmfd#LpvqZ5AAFNXU>#WPI2UKB7c%OJ?U5;;|=PVTBP~e>?f& zo@fg8USx!$Mv3#i=-4gLdu1&vAVm$_*zqtsT#X$i<`2KwNQHyI@m|Bemyz)oHJD@hX4kVzPCf#p;u z5AfDUr7II0z=!;(34-;zxQztfbQtR=(wmslmNx5g`-#(^{+G`5rhDh~m8Z6CV!nbi z1@vSn8W1m0`TWdUG~m|5?8eqc^1ux$aJyuHyfvr5W_(Yhe_C|A5CsX?1d`cmq*~84 zfv@xteQz@fqF$l{#vj&71=In$VJk*nLG85L0(UpXTW`1Zd za*w^JSrMf39F``!z439l)xiJI?Tl$#>@3e_UT@MIMl(_f6@bpc4olWdda$DY0Rhy2 zzUs&D!MiKFdTKUGCV{raPl1-6kIP&`CQt( zGy1%+Acf$0y96{$b39#!~?GWq!|iargvYk$;Y5*WA@sUzA_mPD+-+aFRIPIPeReK@wm zenW2P5d#L(7Z@Z(6a?RP+?nD{?{mOLdv_^IGZ099W!#XXj@vFrjBgMEN=nc+^p;L8 zQL0~UjHM61r>J@$oi-=bQ^(%QlRG*x(or5=Tzh%X3>j?yYc00-VLuLL2wxEm@n(#O zPRhZ^ZR6+6IO5doB)i0Ad0s{#OP2%kGX^Du3qb9}jPuLSAGIfYFLw`lh9}yzf?spp zm42t~Nd{=!`}W8t?P<9#d%>TIYL>eR1zQ$V$$G~mSNRm>i{)xaq`iGS&nE_CGW-AD zvn&NDtzyZY9qtc!py4$P{^I+wkQ%{^w;3sltsYGB2+cbxX#gOT3RYWE*az|_{(*0> z02qII3cU3Fcz_z4=9~4O&P|r2iYEeSFA1=g6x&Q0ArV_I>Bm0D%k`hw)=g`z=tmiu z;Zw|7YG=N?E;@N92BBA}Ud~NUSGH*Vg$hn=aaHv3{gG?epC(YUD%dDgIfJ^DuQUIM zPZ{g$ov#L8WF`*QREDnH*DQ__Qw1kQ0vrY? zeZuS(80ZGHR|6MBH$q`=bBV+n#jz0-;NQ-+c?cJxHqaV$uDG+k19) zxRmy79G#I)U>c)%W7*4TSX=^CaBqypRF}vkC7}0{$_JM%?`k z6yCmAf`?z31>BHCLKT}zHUU?j+14Y*pi4+T+rO5QxP|^n$%<`Z?w_A1*(|OP#szG2 zO!|Q)EB=jhR=o-7qh&1uYS?WxE`)kN8oJ^lPmRr;0Al*wQZ!5hO_57mc!gHEiJ6{8 zR7~vD+W~ufWU$H3>uVkj0c;~_W!;>fQ?fbMwFp|mh2xL5qizG?-pZjxRhKkG_rkl( zyMAsTptm`d`l<&YeV3Mgk6zX^im#+UR=(DJKBqe4izIS=H|oj^JcwNMO09h!KSd!G z+6YiHpdIWKP6ta(TkDEf;p$t5)O(+b*v)?e%;|mP;MAwBUn(zC0qKe^sPt}~HpnT> zRJMt$M_BL+ime|%m|x4x;7Qb%lt0vvfcI}yjue4jlpDK$@0Oh(ntf}Cmp>DBZ1WAd zhfuQMIaSG$b9u#;P!;*+7S`~%1k_We1w79B@=A#iRu>+L8fbsCCk3HnkMWfJra@V%&(CT^LgS1xhdP!i%#V@WovZUuDQ>t|X^84&r zFEg+hiidC+0GK7&)N;>G5>PD%{R@dkx>MQZb+xL!=-hnwa;0fogc+&s<|rh~k`{8l zmvJk!PKooyG`|nLO9KnYfGW86iQ2YU89^wsC4ddw&%cvcU$3E!c`j2`YgT(&hD78~ zW>J+lmB!%aa3~bdNpwmUNa4E%5Y&b;|1uNHb`g_g1HjT<$}emfqV25>a=S}&CzCcR zsPA)Q?S5>J{+6c&bOPyaeE z`(Pqj1Ylo`QnW045r-YwLCW|RZrEN12bUXmOLe<00PTRqzI%iIi+9kp@hdnabe{aqqzSxyhAU>*cihSNWr1=FR>wHM)JSMo zmrnjZkheu@Fw;kJ=@N5|A3ri?60l4zxHFh103Zq}&s*gz!*Kj7{Uk{uMfWFG>S4aP zaIaexnU$3v2>Dccv@ebCZNCs&bTokKM6>=CK6C6xIc?Bm3J82;*vXC!G4$Ku?~@UJ za@PPPj&^Ihah?X0YJtPybYJI;%umH3+;BWx4#zD&o1%2V?&Im#!eHIZyt{w8HWha_ zDL|wXX0P$#I;-&MSX;F22tFpWq23LiHUce$h~sgk@$+IIgc#Q8Xj?W2O!WKdJ?@kM zPsVk^LyRz2!M$^icyjVZ06`ulE&t#hzQnuUIr_J|m}ibDB0=IcEW9LV3nx2hLmstN07q-)@&LF{S8nxtBJ(8wq zKxciMq$?#t9g}oGt3lFtH3SoGeEhU-|K<=ep%Mw5*D)s~Fb-#rx2J*E@M$T3;~jNt z!R6u2-~1QlrsTgm&32lGk;3GyhU7(My^$F|Tic~Xd5OcCt5DeuXB(m(KiW~kdH~A} z)tdjW@o z<9eH9CMF45batjZPTVMt?$Z1r*L`)nhsJv4SBpo;@j%9v+J$K@^N~nj{0=awbj4ml zgiuIQiZd%a0(GMGb&!m^a6qZMP$uwvAXVHw`^ThZXxWCTmsg8iR^`fQ0Wj!6 zT-`V+#zcGE9{dc5o|d$Ic*|D&iR5*ow0wrnavmvZTzMu%rpq{b+ycQ1{v9zV>I6ER z8gW|Ov+Nqbe-laM&4?mY}0CFU8sDK(2w=Iicp4e>xq6_bX`p$VM&F} z^Y);X>mGmy?)Da9*s5>iM!=%!lk5&Jbs`%gnET7*3bQlEmDMY2KITZjqMkvI$dTG% z6I?fvzi-FM<7QQlkozIsUOZ~eFe@^TS%FSE9dAR%l!KwgU;jFJh%k6H_zLl+_q2%E z?IqoJ>@(SsSdq}oxG714gDFJU`GAh3ozr`q+|d)1*(%xV3+9vSQ2>4DfQA8P{ z;y;gg%T>cMpG!uj zdw}3+6YrgSO(Hb{0P1@gXGI!M^TW4$`T~T`$D5D%VK9V(UEy!3N4Mt^ou4s?(`mbZQ@uz~VjMM4X zeWW9~Gq3dBaY6pdt_(AFl@KSE5*%H6SQDU9SeE-ysNOrglC#0=lRtG= z?7oV3qxy;>UK~adr3n%Wf6gG8O&WEXa0uGq`t(;AJ`yCeU;)=?2RP|JG})Q4HB_k%Jco)>&C-itw zi;hM-Z;TmLw`U$q`r}Hrq{H2n&<$yODUAJ}xvicyrG06c_W!|%Ecyo}(iG%9=77|B z{mVUUHfDQyC;+_s<=F=(IQy`ciV_*zV+r~hBoBE^KL@XApR6PvgFm(*ZjwR^+HeH5 zOM|m#P05tOF!2Hly)uEpH_2X(@zVqJeFbf7#E-r>DFRp*si<0}Z>g5y=`FXlZ>so8 z&-;ThdN00T_Z8(sAt-Q3cq}4O-4Ae|S8Bs=^=ldX*Z|`0)m2I9SuhHXYACcOA~l2h zRppx*MF+}s9=CV}O|CR*ksp=ac-Ub0+z>y7G5H3|j=1k*UoedH__)5lgh+1ws3`^&A&G(kwaQaGAsJ-7p4M=-oOGm8OZu*Am>_nw`Rf}3XAU6c^nU7B{*wENFA}ghyK2N|Z zMyF%or5hDl-`dzH#0=W)nkq4=%@kH~TmpGVHh_0ij2w~G zn3&uqVi1eK<9tSBv$JwIGFW3=(>m@CY+K5lvsLO2SHUZ42RTlc1}wV_c_ zf2o2jZDRu_=2mTIq$ir@Hx&6T#@^Zs9wVtx_Vmp3w1a6GO6mgzUzD(uL*dSV^KH_& zHHjRbihA~`SSyAFaE-yMLp{C}mfdo%4YJxjB zmL8UHsWxV>!wdRdg~Z>=9~62~TXaLkd&E@2=?>gj%ip5d9uy7If)GPD`R2+{34pF^ z0_nmva3}_C{&=MvlZfn$NaJgQqB7v#M+a&WPlPOuoeI>~uWU);PEuMn$rd-QVSe1g ztW8o7@cD{d{o0>3<%;@wlwsWPZ1_D=*oL*(WP&#Rc-7n(mYI*U%ie70k9o(fH_gq& ze?+}(wzAE+RYKUn%e^lxZk=B?F91fjUW4r06lCG;B{?m5;umt2Y1Op0*oTDT*_+>A zGWxP#e_x*$S#&O%r4i;|2_=Xqc>%+7MH=ZOy{yb8LO5I9 z7q)aJsJNDX)SGKcO&!ORcqe$%S<#G`SplyU3D-Ty6+q=)Gk`3m9SV)icT|(0LbU=kftU+=d*>!d@CC!$w^Bj*5oqnWbQ9!AK2KPv zFEdTr@I;(@k~}!;m(V14V3Lb?8!)XT)@Lx~dqLY~b=hXDFr|r<>43{rAkbCUPKO-h zX6`7u(?1Fw$0SN>U;qt@!T!C=uO<7mt1>2+xHewSW3czA(dgOG5MRspVWTb(A@L;V z3tJ(K3mNJo+-|c6kaI?Z3m**6FB_``y?Gmxz`H8-ouzdUmZJ8nV1yQ!l4D zns)4Jn4mn(bpohvC?nNbl+$hTxcYtSLCuhJZ%&k>SZl=}aac^&CV-TqpquIvGW0t1 z=RsM134DulpUZpLu{ipgXrS?cMon=YaZ z+$0(1%K-5X@eJ;Jvc=FOC<*t;KV*QqFFMVlLnc*gT2Q2n%VpydZF}UcQZaJeR?F0q zXy!bB2SEF~U66a9=>@&kUNUn!IBk$J4Np6RROT*=#hZ%`7I!312H%gdttw!OMWD2w zN{NHMx2|%Vsl(}mT`h}R(Gd-eFroA{v5u*g(Cz+C8F0p7p=BunOf_wL`IDZT6}^a@ z`*t-loIhq2fu$MM(S>IELeY>{pVIiu+5~US1i-DR_SJZ))>$GBQaVMkFw(2Ik?2?! z;w@B!TH#}U*{m%c68J4nWI`UTbo-2R^mzB$Y{ftWuMZGSUwLPJ%pR-)6E~>N+?klWBJYlBqYOIr=pFf?^ zUEo|;;3Ya@J7axQygSz0C{?vPHz{9>rH!K;8&gi_Fl~>yZD_!}2Vdi9=5tuVwOVs} z%6TgLhy3+ru8BE>XneYV{%eH)R!uui9DuGq{Hi|1x)As0sd&C*ic#~h&hu5V7^Q_P z9u1mWnlzvosQ_>-W3 zhyBQ-X@c95@^eIN31fOap!5*`QV=Hh-McIc9Qcsv5Y6z>6bV9mD?j`7a*}W`D$Uy!1%|S<$m`TLb*h|0v1uCj= z?8W*)E`z^TH8-VaP>eI1dk=K6KcJWTUt1f95!SkHZ>T># zERrJxrvDVu2I%wbxD_%3d7B0)mf0M{L<+E{Utt~~%4ksG-zzd`2qgcIbxk#zEj5lf&FISo>2d5y z0~_+}`WrDV34SxCzgz6VjsYvC7qFcb+|^<0YM56=Qvdj4M^iJul^DudQJGgfs+?r8 z>(tF{o35&z2YE1V>zvthjSNY9ns4AwPFzqF5@_hFfaxD|lgCUa=R^dBRHFM*!F;`Y z&orRTfjM7K5x-%g`!4K~e&^(#d^j89F}B|0lzd9tWF0u`;3SqTF96;?w@0rwT0NTC zlIdt{2O_Vx5s*PUx#lpca`)=%QC26-POE>DN6)WY8LsNUfXkTX)(xiuLn%fQ~(QRrm>~C2{{$`EDV~ zqJx*K0UdpB$E6K?Z2;C^mAf=RFBewxu8NNYVi5I+wRQAuHCV{&w$Zwjgz-Ob+5~Y8 z>+L?Q)#B9r#>sBn2or2$w{K+(!oaYIQZ1X`$3H*I_DsSa`VUVrDRzJe2^W}q+hI&! zf2omj;;HhO_Xl;p!l<>Lp#Z%t!UcSzicdbitx{@fVqq!X!UG`vG^e=KdkQ|-AKrlM zVLMo?j*VO$C(klDmaM^I<+9YF4Z~qwxG|efQ=3|o(=*bg{@?`di;aE7;40j4wxuLM zN0tXCWX{H0B9(X}=^#Q~TGH00l`wZRdTT!ahm%ub~$g`T8v3JQI_VwHkGD+6~M{)ty0L=r`A zO3(wBPa)@OX2fwuNmlOmzSdRw9(J^LAb&n8QUj6%Xp9fbSCoB0K3}@Rp%omg!;ESv zG9p#Z70!ersj-9*#S}q}vLQSwbUX=vKV#Kg?bWVm2>|2>u>~cO_D$=*Wc`BGcd1Oc zPRFDySNVSxwlU`nZBw4uM=Sb!+hH{#=7$&J*x@P?_f&mmu*+6chGs~aH!n`oK@uqf zS>9!m4C;eHhZ9b?A!q{S*4MF@7(l5vOy-~>mGw0BZY2jnUZ7!b*g1LL)hEj_9$p}I zZE&zeMBy>iSuEnPCC3sk=9p>cQQa z{;nD2OQAH8=cymCvc?sz){3qL3D!U;QR@BH9tBK51r<^UM#yR0TSAGTBd)8~a^(_E z*pF3%#~Pe}hFCTutB6@bSCh%;ybb_cER5=alWEmQ+c-ud20k7GUy{BV*c!C{OX3_Wip#7^%0OobA@T@6ZJ{!nKz z%mCCjaA-W|B)YFy{0nEtmelc(b{*=ovqGG6?lx_jMA8FrKePtorJDQIh?86eu0q%U zLPL?2g47W9vX-$C-S&)RS(O{=v!l=RTo&#rpY2@ldDuYXB2iJZxjO^x`wbrW9URG} zjtNR`O^r*>AEL~kf1@~3NtM{z*SLgZN&*Idb(<>{t1>Ad*jST`!Wk`-wOP%XR~fY- z1r8E=sJ*UAYjoCPcK@~hMHg?{BW%yfm8LZElRbqV%S`)WXOFFs!qC5+AyiuvU9jjW z)&&8(l-3*Vo@j@TO)0lbHb&#vo^mY{{sX=Ybl4FoVGXmA;sm3wa$DLCSt5`KCIO%} z;N?df!4jQfI`N>G-C^F$r_ylYqJ$?>sz~9;WCeVu=Du*fC`}D1q9|9C&N(ghXD~fFfJrPCDYNq&I zA9Ivry0NqSQ$90||HIH>$3o&hf|62}^A!>Xo>28|hE{T0*Ajcp0i=0{m(5~3437^Is-S=9(T6RGUp#1~!m7vb7y7cNZ?Fd%(Ew+iYQD*k-`P5=Ozxb4*gKZQW%k!~ilXxXv%K#@2%m=Y( zWpq|msBU~I%~~@mvn;v%70nGON8KVE+()mC-w3nL2--bCl8ac%Y-D8WYjvNy&pVil zc5987d6F3fvqotTqg#J9v5BxdHD1yUgxX?TqmsBUN1=P}h+-QkfiU?$<26pm=<&+l zD^o{Jdq|BMy_FE$?hn$7Yys%l9)Qo@W&~&i^dfpmXrMi-@574y)yvk~jf(K$C5%JF z_DJZ1;>7wx&svlmQN)L`#6fbys1Hq0Y6sni?A>Af5h-LD5^2G3%0)tW_^so3ms+h3yMTZ0Wgm2*!*RB{ zE}6&=pKKf$A}==hC*Hib+UcPrEC)84cJT*Y-C=H)6P#+EooV9ldJliFA(-TX-HHrr zWzFoqxKQa6Hyhe@pCKe4Byy#zpNQtz5w^uQj8>gx6a93(?%?LspVbX5)Pkd+s_2Q> zkj+a($6a;#9a-FSCjj@X0Vau$q-5SbB-BJ0aPN<-&guCeu&a8_K-Bji4GNa_V7eg- z&++M<98R+zAL-C^krbT&bZsbb$*RI}ehn0Y>PJx~ni5hD|9ba$kTwk?)%=^iUV7qd z0_6e{S4WFg({E_nZ`~mMb`FE!^d`rEjWvfmn@i^TDxm z4Pm=pm!EC2bg7G(sIf&N36UMNevhi#he9tKN-;wQAGx>Jls9stm8(hIGN?Gf;rY2? z%KV-U9*+V0BQ=GYX`h^)6T7sqB#&02DlBe7F&3@?=LXQ+Cw7n>-dOCE&816VC5q#J zj`i%aJ@%=p7%2Mj@{bt!MJM%}iRIYMs7l?Gb~pN0H$Pj}sX>MH{mB`9Af&|4bPe7X zOEhh}FoczZF2KFZ>44LJ+xjaM6ic3&m}_&9+#wB=)1~|qZC3f%L8w{boWE)g4;efC zE(M1Ca1lTP0yB2AyZZ@&1s>sJmL)SthiSK=e%lY0M1Q9h;7swj+PKEv#256F_YT%G z*y0Xa2BnF2FTh9M>O?SbSS}^0=;4YZ$WcQQXg=hq)&~HENOyRaa*$Z)hsU>9UgUA$ zD6j7PAg^p_>2UJ=9{UOV!0McvYmi(uz46;D&;oq*cygCXgM5pzlVvJkY=MKXlkzX+ zy)j4VtEHLE>?1iJ+kJ$>zdXl9Mm#9tYJOWrO(m%^+UqPym?Pe6ckKkHJ+0|yXN9mwO?6rKNiNl z1(!pC05{6rBl+>3|A3U*@VTTKGyo&Df?oo2+5Ki@U|?kAU`!R)1i}8lft4o67%)3i zV!aAEU|LH{2}`2E_f+lakb}XX<0dsMJo*kMmWTBasH-O!&lo*5nVF7m$8L@i+PA?R&Ir5r()!YBx5aYnIId@ zB3x;0#NuPxYT#2C{Tl5O-9pRE%Cd2}wI&V?Xtu?kA2r7mdkQCp4_BaNi($va!b}y< zBI}sS^%zX-L-!F9QcX0s3q!eoC1wQIM5w3F$l<9UE5G*-IU~Wt$`!AXld%_I%Tbka zWDT$+tRUdPz2Yfv~Q1zi}7Q}su!;ijQNM5avO)@&x#(Ls`6v#}6~4{Lq} z*b*Vu%WklSheb=)NC;a~GZgUx3AT|Cvc@Zm3tOWYq=v6y3Q{B0M>kbWl^v&LN)HvK zZrBHvI>pZs7^Y$)$&)QUj6rNvPQ@-UWFVBp{KKBPY416_pK358i4Bu0k!f`2w3#400)+yd9m#8a#p z<>Gs=dcQm7Z+y7$*sd?<=iLi^xOp<8XH8S1Nz69a&D};)7b_#b?nyjw!F8kINDIXl zYp2CTK>SxQ8sC}(YW3#4h!e`c@8Rfo2u-JJds(kh^Y`6DI*-70*y2>TNZwxn&%@3D zH*PE51;rd|mg}9rmsM{|^&PI!nsjuGyC(5Rvcm06%$TOJPI{O%FU^lug~(OgMXSL5oBsePNQ2kgJ_8^Ub9!3)PG{~72l?IHN`+hJT2qm15Zh z6_iVw(&ru}6&n65XU!Q>m%nvt{JuDh<|v-xLNl+Q*_eK^I5c9VW_jnYj8c7sv_3#c zWK;Mom!VBbE@3M)$Qc(cDDH@ATdHOqnsCO`B|AGhbD?B>gUJoIvkze@gybd{DHOQZ zW{yg5$}#q=E{E|4;~EC|RCLlH1y9kLo64^Vo9+`)oh5D_A#(83D7q;vnhhk#yi}pT z=Oi_)KG`i=qTr*}R)75CH>bufGc{j*OW!VktJ_=STiCge$EBt-3a@zp=R!_vHHBo! zq^kC(vu9D?@85+ZI-#$HNg>%t;)79VYY9ck z1<&CwPjm;=ft4Pp9tuDSs;F^#3uYjA2MzL|@mg6qc*aU6G2|kIB1x>ImRRfAQ`5@_ z+gN~VW^%;M5H7GdN79CDDVLt4ZJ_-f7_j9LTLxB1TmdCTjRYQc#zBcDIp#V?b@3~j zQC>kH)r>ASG1vf2^FouR;%D&21y$}#R?p=RB6DnPFgymU82YAXEoW)NC2$+Xt`>tz z7*tK(1X02Gl$o|qv6Un8o_d)-jJETr?*m@6Ac(~>eTr7x5M9957z?_*ww{Xa1RxX! z1lnrN&Us)h0fKs4FnDhntx1YFo%`a~OgwmH8<1)bZDW9OjC!1PyPG-9uLY8?0uE?=pO&s*UcLahLNN2Ei$d9~_=&Tk0)DtleXs{zwj1bz@ z&4@(E7fgH9Cp6$DpIp|mBslDA%yQ0BC~kNPn_t{xVqmc4G>Qt=B%-W{qt0X;a}HzW zvve(bSe*c{fmvq-)0@^1eF=96eQ04*yjm^xm3lt6znit_MV!9O$?O;u5$JL*)q7Hw zg!RbPjNy-5$BWH_fh!7>DQud><58I;(RYuX9&*d})ANYE5K^bWWF6NU=fL-o{su%> zmqj1Y5Mr?F!$N=&OGgKD?u-H_kTK;QW5klwS)Bri3#`|n-(qHb*nC#vl7$(}q29F# z2~1Fi8xvttg=Q;xnFD>-$tle*iOFLuL>eb{ocM^oBb%4D-Z-d0*zlK~l)O696T{L( zYD*gGx|(_%QKnQTJ8carzo+z32AXFEz;Huk!`taG)g$?vfzwxs%t+MmTl}YwsCdSK zUNMqDTQSbnRtC*yOHBKTmcb^oG|8zW zAfaX{!OKk}$sBTh5Q6iR3#&{o^rvtIP|z9!edjPp5F^B!g0VC?fYpWNbcEov;#F8x zFv^X`#b2;LHSaA7%V*ISQVRc7`M)w2@@D`^ExeLR!HOu>o?AByD^`{N`yk&ppq z{+4X?%<3v5w8-r-r^3ciZT+U`kz#3_=DwMWDI)?gh5U!wAv{tS-mywrqPEaorJYgi zaf-a@9KRi6;->dL7ksCxbSeFS=xzi?<6$#0;LZ6UMJ{on|?wuztWIRqtzRp%jK3O#X2Z1C93Bogse z{>)7H2fK$RN}epnuR@-qcM@OCtWyl|{rwf27%$3WvJVHlU!>rn5n31Dp)4yGl_7(w zl`vZDx8%t_=EyUaTo%Lr-l_OCm%j@T?ZT-WnX(vcEW!O&pCN(7G*K(_QJ%`?U8m(9 z$&jGDOHlGa$uVosFrHzbHG%OWIobB`)>8LdI~&P7)EJbz#-(GC;e}OPorq+b07s@o`KL z1R>ntZTPLvZ7LM&#$d0_XitBw6ovlpB>0AWcUBtM|}7>Y$&j$7!QnLCaD(apAJ z5$3KFdkEJ$T!{Eep)yBfUzq5@Fpw%a(#q}QMcNBrFrBr~)_j3U!P=L?JoGG|MJWu8 zmC84kqGEooN>1c^XY~4~rYQ`dQoLB%>_Y#8ohq?t2`$@+tpJ-Yp`<&p7K1Q7ljkVo z&6UFF=nUD0EMe_QAej@1uqCTVM=*rJDeG)cshtoeUu~4bCr(w`feH5SCW%fR9WJRm zagw`uUz4ettSiZhqzlu}D(oKAyi(q&J_`WNu?Q8ASN4I9eSB--~oCb#mI!c&eNras<7um z!%{xiScVG(4-C)%;}S5s08QMA&8<#V5jZQXc1M8cpBv2mj$=DwL$e)@2%b{M2ei6k zSGnd9)DQ6YKkDcS?hKSk(zOZ&>lNfgsWX-(#kN>vxP& zfx&QUf3CARQ{~|2uvqp-@L(mRT)HB9D108AHm~=XDx&4-*3m z-qfaFHub>`+Sf2P^Iv5jpcy?CJ`BAZJ?R;$BlpX*XPI6$lT2SeZUkoy61bS?AR;A`|r;JdaJ&3Uml0e0p5(fSv(oo&$tz( zv)fBxPVP;g%6zUxKbW(YC6S{$kEh3{8eh!cntanUouxaJ6{p{Qr~Q3ZuWfrVVupa3 zpTj&Y7Tl8r+FDsTvBvSID}6@~U&i;9Zvf9XCsredOC678tSI+G?Mqd53t(~a ze!dJWqjCJ~NZ-+YEho`Q8g66Kb!8@I^l4%DdR5}X?&3M`@sj`b;X3qso6V0_J2Gnp zjQyJ~`xQj{fy#f=g6z7gR7P7Yb9cx3_VWdIqXlLIHDTmBb`{Nvqy;YK!Qth^F> zX%g-F`^?aD!l&x)9_t|A6-XVx;Jd&aU#D0S`(A~xQ#tK z3xT{;jjVC}ZM+p1+p2hK8-P~3%i{~puG$Xj;r5aP$mr9XIr-o>YF3h-fh99bTyM=p z)}~_ke!Gh`qs#ezc$!|ROn#BQdP4Z8`zOoL;p(})7>9?3S>laV8r!o{JE_|gttb1B zXSX_0+^o2mEBCU)>-#cUxh+POOq7hvJ|RECxoNB<(gY=ikc~D`4XEGJ$IIHv2=iY-f-^$kvzw#HTec91;63t7{(z2GubZJm(mQ5|Xb1$%At34pxu z_(-^Dz4rKe387?PvfEY_A?2|y=jO_qoAH(Q`jGI7z`W`Ds_f=(cNOvaNNqVCvZyY4 zK5Z=Z>YN3|KUHn72griu?Y&9P{Yd+{Li|$wj8eIxXi?=p2zO-wR4k)xtd=)~~~lG>T5QZx{A6HH~ctw{3^9mKrF? zyWwUlE}h0UX66G0to^`L@y*51oilG zEd8x;=S@7jFEtVX8OCK?agMt2hz0#*;PH%Z>b0Y`pmztldYD)7qwJA3WybB&{L}d9 zTHe{au|VZ`9!#B>`^=R7V*Oc#x7GH)^;0WH2aY4S3-b6q*vY&qA6VC$;GUT|SM;gZ2k#B3wmR<(g_vj8mg}N4 zPv1c6QmeR94b%KDl=Hqm^Iul}B;z1*PR*6=!S&m*=$&p6dI{LJ3mnR{xGQK~-mbcc zJoZc~gVk4pEn0dn3j)n_oaLFqon3xhwR9ft08R}=UcarOoLrT>R6RP^P0>T&zWb0+ z|KewFx~(tZ7<;%&jFr2u=OY71h-FV{6c~Z+LC+AE(*;j(i~g5a|KLtgAG{aLC10sa z4C2T#)#}l$e|eFOfBEk#)%V73IPVl&^OPWoW zyki9}cF5_lXqf ze3+05GFCy~UD=+FL=Yi<+Ow_9R3unEHR^E08uBI~S<6sG8LEmf^@Uc7u&%H$%)HBS zAg6+q@eB_uAk32xaLqu88GevBii3d0VE8lI>B2ykAuPxoi8@cYA>4TepIsp39Em$m z^)9UV6bW>&w_pd2XogoqaB#oEBHh)~E-J3urg(G}NhOn#SflW8G?`3b7o%fzwEfc? zl?azx^XK7hn`In7+d+nbyi|J;`i80o1ALc6ErkGyvqqzy>IEJ5r0=dNfG>@KxChe2 q*4W9}(Zs;!zmc7xC8U$Hfupm#qlqabBO?nF8v`T>iHMviW6AUY delta 47753 zcmV((K;XaXy8Oue*nDZ?0Znb2TFv8EnYx=6QEoMI#l3w-{a zYnEB}p~x1+HY}QQQ?848{Tv>P#iH78bE>m8Y}^BDzql)lCajiqc^}_aj`A_5DzlNS zEjKnN*(-Q5ChI;aY19_nIgopsI}!jRx5m;+8| zP(J6(WH&1>fYN^;h%#@-X16YzmG>FEc`S>tXje8kOR%A{h@uE93Q{_!JBR0jWXt!P z{dKP7X-5-`5vRQS_GwivoMTo&mrl1LJj(f#ds#TIJ%=~_`~3Q@1iu$e$~vu) z#IpOm*gA(Ya>|d)Af?1PVHZhqNd}4Ef@Uil)?53jjp8BEn%3@6^a&VA;lzwmq|bOR zGW%&4REKrDiknSav~l_99ByMA;JMR~>rte+MhuQ@RPh6*IFKAYt&R~dvq0cWczr-^$wlDgM*Q?zyY z$%lVmLUFS}%eLCh*A_}|N(NLQeZY8=(iWnx)kVtc37@g922s`r+ZQ*d+$uV?DFCiF z@gWVO3M0k(TzHd6PmPGC=hJhFV=>0<$_07f1RV|$ms#vRV0Y!pohz@8gM?_^ZY;8l zftFCyN9oudx+c`1n8u7o^I^-CHXC32V1<9zRoLm;E0x762JKZSU_>J0F>xU6U9~;* zSKHF{RpDDO0wBRzi**!@87Kz?2mN3NPAmM<1IZ4W3+3u@*bfB}_Jb3kLc87rO0;`? z4m8n5Ac|b*!A8fTj;xDyZHs06$TeU47FsXw%AswsUGWVc<|ms7@crRno$bE_2h@M; zQ+sLa@-Y`s!rQX)KJ%h{FN#Ix8ccV-7B*esu|yj82mfs{JE^(|JUJVccjxXDn1QjT zKTz+IXswL8=s1k)rOOb4T|b(;Z0ueB96eIUt#WBYVmZ3DYfRzArgM~k>QaFZT2Ve} zx%%9ozC+wJE^F5zg+sfp0nx(wd=-Bh;?U)~HI8!$d~1uQ^k)^;yY>EI?lXqsn1!$# zLcHDwX*j#DVNUAg#t*xu*b_9+-IZ13?@uKBK9oHGz*Fd-r;|p1xIbXVw|+2zGhN$e zziv|jm9Qkxo^yk=AzxF3Cv757jk?5eV(qxE>)BpYwNWYI7dspN=?GI3nAMw~!N-A@fHUHXWCIr|_A zIN<~*Xk-ZHAe1TH6Ou^C;eZ*XWDFfJgvQU9$kAuQ)ekpU|GRSF0l}G3fH5rLGsdBn z;IqZ%>h>d^E#W0N(xbzZC*6NIT{(7ku4lhp{qyRryBQd11|`>}fuOKO#UQ}P*&=)& ztYq|ka++{$W{+{-C3BN#;#*z)l2(_FTHR4(eWyDg$AqRQAINR2hvEA%B@~)oF-R4G zQ_LWrh8^3ky526gf@)IrUY;0r+jf54CzL7fEjQostP zZNZ1NO#2$=7%(z|z@vYw66s2dL{gfI3XuGK0pb@FAT=#ODU}AY{&ML051oK#dT_p^&aaM#TDl;+) zFHB`_XLM*XATcvGIXMb1Ol59obZ9dmFbXeBWo~D5Xdp2(IWRPrp^gD4fA$4Xo!QcW z3*#OvxNh7Xf(LiE;LgTjV6?h@QJNYDU*;Dq4r?t010oRc}<|5x2xRKfeS_gdYn zpde9HVGuF_83DyXwoVKzjLbX$5ji<27G?l5GaDl_Gb;iGg{p;z#IPH!?%L#H=Ge>spXK-$?Fz`_P#`M|@%$-~SHU}a|J{*NKZfd?RJ=we|4 zkYfZ$gKUA02oxe9J9h^QGjpf6JpcIwP#e<#Sh%@4>Hl&E2-yG~EQ}3p0dj^;=0Kab zjK+r602Pq21<=X;e?n06nL9bz@h~yDy1FtN+Bh}#n8gq(CE$JuhICe&F!NShTk0=F?U>YT zE$p3vQlkIZyonJ0$jpFF01jp@PBtzM0MH%)bTc+*`kg@4f87rFmy+eT_^k(TPdktu z!1S#Rptpr7@a+$Rr=y_@5a8tC4D|N=x8i>ZfrSNNVqxqAFanxc*dqLi{w4;R{>^Xq z?_l8u&}M!cKNbM<@1OsE>Ap>v3CPyk{g3%ySInfODx)T^N%v37|5XYLgWLd~3~a0b z238Jc01Goae;0uB?Zf+j<0u+h{8Puje5GtnL4e=Ee%JeUQ2(jf<)0y-{%1pI0RJ0I z9`rW4KmhfhN!MZKU^agH#q$4o-v4s>|2O8pqx`>4`v0v++}YatFFp0&2LC^LLmLZg z_kS$jM%UTtZ4Kl=Z_8l&e@)eafA6jw(8R*o=KpG?f1C{8)}{kOSlAhv+5eVX zIEq`i0ZkMwoQ%!?9-F`AYQGoG+QJs72y(Re{lvU^F*E-k-P@KKTfIFaj&HO1x607* zZRMQ)y2#%Qd|RsjtwYS#7-aH$`&c#hsXz1g9M6qP^34q#IKLvM9{`a@g*CXN3R_gg;0 zKlG+E`Y&<3Wq*6HZ2stf-vN`!AACz=0)w`X!b96mbY|ve-8bv9y>z^CksPs6ARNnWpKQ;W%ssJpnsLl z@^+Pu|H8L3a{7aB4sW~n@5X+MT>gu!Z<*XI{%GI4J^o|K*qd5mi0lMceO(Jt_<7be9)(9cN(k=<3)OKP6J|7`s)cQ*;$J+ zpT&Rnvxw_icFPOf-{q{#UwUpe5I4HB-!Kr1@0k%B#m&9mfX^g)-V%_`p|pbKtEUJP z@sv6YfGHA2qV~WGn3xTyP@s5G)%PtVf4Wj)l!&Pwc4{*k zR^8^f!lBCDu!#-ajM52DmCqoR;p@6bNN}w|T^kx1UP9|9?2Yu7b_v)%BM)&x6XP8w z5M_t0`LtAk{FGbja+rbcX(aJp@X%zSVwEQ4u3rAaeCy&+mxMa0htu33$ux@Pf5_vW z5Y280LpaSLuW%>ASO2os}X8p#i#%*0!cE|=)>|N#2X~S{6Hjfq)1>yk^=ae6GM+8OV zFt&%2R{h%S54$F+gorZ%E0fQwc)0S%`aTHi1Y<*RDf5qdIP`cvgvbEMe^4HoW6#QL&2w$E7{i`jbOl)LTj<%kVz z+Y@q0TMB|G=H3kNe^JN03&2ns4%|apf9YeM2@`xOT74J{7=>-VP$wlm#)a5w&d&V0W_Ym=(h_%6 zh^GlkDxx?wVZCT`jgs%EnwI={E$V%J2KOsFen2xBx%0TOj>S@|I?${P8K#@XsH-hY z`m>>zL6>=SsgW;Dud8O@sj)UCvt`m*y#^Sk`<)rW`!sW0m6qTFe@bXyZ*;pChN%P7 zIX!^knk_ZUsgPL-+S;{=cOp{x+THmZt z=wI28>!PM}Z!+`;=51qJ8Oo0O;w{~$sZJ=ec>eHzkB4EK7alX4BfjWqr21v7(-bCT z<2bL%GhBA+kTR^N2Vq1bn|pJlWbNVhq-ph|fdBi&twzR8e~_RT2h08OxE0wuC@<7$XHladu$`3C@50_GXwCG&y9a$|GKr=(gbPYV zd0Hdc9UGl5%dwHwGFd^db3L#fm7)hJRxP_dc+K@!({);1Ba@N=$mP+`SrqlESTp{6MYmAV+!^?i6g|=NGvAS^hADRoB?U zaQ%k;fAW?8l<>PldWVbquNreb+FnVSpLJe3R|}fquJ4=hKG)U5QulG*st$%ln=(~^Q(yT3v00W|=6uh* ze|#GsZN-#OO2USUeVcV$}_so8v+Th^plVh+D)KXRiD430S+)I}j zP@|i^wS(``=D#doO__|BBr&VTBG?qdf5^lQ!8R))cO+E^Y-W2R|!e(0(5rc$)a+NQYt5OU~PY|}Ipf1T&$ z)u@T~pR1b{sG+-c7_>;DaEWpbrTY*hX$TyYZsM8FEk)kkp34;k1t{0I}n+oIr&hT7V^1AP^4m za!zPwVAb84I$%>4yluj%BaayJR4oquDZab`^)F}aDwt4l7b6LMEmZCpTOqNGEzU%wh86CLsf57Ol0#^%3bSb7? z&H!2Y+;Vh{ycbyJ@9`yNJJz8Z8s%VZio96(Goma6Q$*Y@PpdH2HDGRKp3+YOKWA#3 z#rXrXuA_lJLc&$DS4MjxbsZLa?rJIZ{+V$7GXt7cXGdGkV2V}o`qg8H3{kaB&U}wn`*aUFe;hrzG7#QoMpPTJD!M1y&S&(j`Yap~Mq?>a=$Xq#$m8erZWfeD zmpm`&R=N)k%w$4Ym)&aTO)6$9u82elvR|V7kKEdr{#7qtfDG)(2h<*+)!UgN1B0zD zOCBaf2y8H|hFHJX7qt=!+J_JLIt!Q0!aM7Ui}8FT2iuBKf8=(MmQ{W|gZr+1PQi2* zWh)ldMbe*Va$25d0AJLK2S(2v_cYtHErY!a5OlseNs1i6o{roTr86Oju5SZ6M&Lay zfc=|D>5!Ft`8D`m2NTa;Ul~19jcY@#@0eo>!>CKK7JWtF(&$dU6SNZi)M|aPBL`5P zqZ*c?G?I&be@+mWjJ5%zS;bx{VuP-9T2uflxcfX1pOv&{mY%V;|OPS8;g`_4_`l`%d94&@L>;Wi{gEAqs$ zW>XwPb*b~mJ9=`%(?C4sU$qa8rb&&3MGHDMe#TZTf1oYzh1F}P@~gG zdXZ}T%Rb7GXN~uVQiYj=Gigu`Uvz#oe+~Hdy78zC1R1y_thYOuVA}~CP0Uo+WSP#2 zjAO#omCv=QL*Lki%v@T*6ap}h!Flv0f!aQoF5@8qnMd%E|ywt%FG5AZE0krh@#22f`&bBcL zG4mP9Jps(XU_jyfwQ78WT4uCf#25sF854HX`3@2whd2!q%p z-ga;zs6*9gW4W7StEQ#<=?iO8*T;$@88>^jf4<_iZ~9K9gjJdQaX-8!)#oX~mq8)kTGZWo5;^Mkx?)U);(&YR@cg~mM` z4IGWU<8q>YKKD7c3S#IdI(9Naq~>gjhjj;`C?tq|tw^;#iCi()kuWd-@BL^$2D!@*eQ$kU}e zgwHFwv+DC1!yMk7+30h%Y2Lap~FWk!jm= z6=r`j36wdW_dY20`yk}zQ8AYU1zNb>e|YD&!@(B0bDrts2ixbbbM+2t`OQSm3gR36mj&+k4(B~!d874p z6FVJzfTjS+#F}s>rzga|%e@aG<(v{`F>Pu0-|%@*?uGfe$**D0hYoSbGih5sf5cxu z44XTkT$2RC69X%G_ePQZrql-*%S?Q3C0>}t($>e}!HQM{S+<&squnfOBR+k$M~WY7 zt*J<=LY=eQH7k+_cXiiYozux$a%8o)Ie8JtVO%JdX@0oj^}N1TZDS8W4e81K8e1w~ za5{s!2GeDAxYlp7=GH4^F2+9;e^?q;tec?g08mZn@qX8SA{Fp>oXNV3TTS+^I20=V zZ4GjS%^g9cX^ee2;)K4nWy%72Xw}e6o&%u#RtT{wQH^VGXaE#PYv+hWaQ{xM_{Q3*)JV`)iSBZYe^)s^$~Gq!SJR}nsQMS5apxs8%;UYEy{c@I!W$0OQ_sf*_Ze+e}vYX2o2Vfp-R3dC3my# z9toDgg~iS!N9a}C(oL4jZ}0(c5E=qH-s#=@aW1P7B8!4O7(S!>fVoG>~f zUjBEPP!hjz8jz6)-`HI<}A8p`>FeNDl}ARDO%dOfCH8P#kM zr6VFa$%b-Gf7UUlj)ZwlOdoV95YepK|JX(qPj-S&QOJcT!hQp`n-IpyL+?M(J!- zJ5sh`AwkL=cfl{mSR2y;OfWFP5Ird%rkhx&NjyY1#N^9sx-l$T&gN6e3H>`IzAGFS z7e@uZwm?u!krR}5J$VNg#J6BypL znr$Z@f5z!ES2Yt1G!_u&HlOBJsVikOQa07iBFn*F9LD*X>QK5VS;SSn#dOa*+45IQ zRVWB3EMN2F=Yx7ZodEss^YWY3&lQc5n8J|gz~|#zud`< z=;P_ChNb&ZrMc7)J_;zgBUr8l|Hvs?Px9?We@ydYs5O>Fg$lZARE0vzJ@N1vMni+h zdc~K0zzgA=DXx;B)9M+`6^^P~jp#n$Z-t|!9P?M@tl;wT4UHp9n_3&}wod-aMU2@@ zTtD!o)m-|qrKC5Hpn%#k`qgNg7K`7@DGHz7cq)+@eSq1z<+Qf(yCdJHc2}^EVjt8i)pD>Pd(%0?8EkBgwF7QeK;j}afm z9bNabN-v`Z;*vArtVmaMNg%eaB@zu?_vR2V%Uy%W%w!s;c^Qb=-(~dvD zPn8`FvvP!)ckZ3Gdr2{JIQJSTDHh(&1<)9rm!~Qz4K?pmKf&IzCvxBF{vzSi$9j> zKSbA-MR0Gmhi??_X(sOzq{0mw`LIu-ez=A(9`_)I**qxKcKYFt{!vP`mpnB3W!ydU zXXr^HxMYf*McdBnCu8#*T^wu5U#t1zeak#;Ur`l`_Q}bHBj89xdCI^df6>5#DQF;I zF${4wGv(Y8pNEG?^<`5Z1PH#Gpwm9^gw8Ravg&fWQ6IIl+aXpfa&^)YFhaR-5au|J z8u4AnH0a7Ig)pDe-Zje{C(qNh2z~@IGAx2VPsi@Ph~QS^qClnO5Bgb;pq>s+>iFO) z(_xak^np@Di_;g)LRR5kf871=5Aya52?#kI>j!DDjL%Lmtyqxh3X2$fpU;Vgzm#X* zMU!C-31S%+%2ps*;9K_a%GU<&t%(SGQ5W=ltJ!FgYMqv4uc~7ndKm1aT*8kne8Di< zxfJc~Y(PVg^gUJ0Ve4*c#d{LjF9hS`M-pu`>-Ihu{31{xG1DFVe_BGeGu=3G^<7|8 z5~f3^YA5Qo)Nl0&e=;FU5%M)@g37!*#vc)3mW)B)`L0^@3<=(1|Jh?i{*@n1 z!R+9>h;{G*dXb1xJ_>g7+I30jt2wrNybZ*2$~fm$kkyaH`Bzp|MCgMX44a}d=kDar zFiXcpPl;5wS)w17f2`4vAe?PvR^sMovu4%r4Z918M-$gM4Yp&LLA7~Q{vg%#NeZE~ z$R3uRpDdU2*o`tmeg<1uYB2|A_ci4`p;zrEjcCI>oZuN>dybN?7Pgf18*;sqUfB*< z{Z&xhdc5PfwIMAfI4LLAdSrN0BL&UzlLiB?DY;7vHy48oPXOX7%meiQs-36=tHZ*a6>$YP-k_{%#0cLnwysUunYC z7lL;htw<~Sz8ul?UhYQW<)FEVV5{mxN{p~LO7Qx{_`8G_4Vk`zQ6maZZ!PZA$z~ke zM(lp&Fh4GtjP9}*EN4pU)?*jn4t0_jyYfyu%r#kUe^PrvIRR--{4iU_@x+37eg^iP zls*iX5?)}Kld#fU)OhCjH=&u1mjzDwNn%8)L8J}j2wr;~g@x`P7GRCzpK5Z*wZ@_8 z_nh*G@gV9=sBe8Lr-k9mJ9-oS{g-_#^Av7lK~JQTBzGe#OYB7m2W^!o0U+pxsv{vw z#t$pze|B&ONT-+hcp@K*ni$Y1E+N8A;ls=s^QhL?DN{LnAtiHO)Q zE~FfQRknkUcRN*X{O+t)YoVNX#dnFauR2}mf8!!|41hv?r*nU)&RcY3B6aYv{&ZJLm;EyVjJ7s(4!_tRK0f7S zf8ykrU|yWTZbT=A`3dyfa0nAx?+SCu4k)M{KM9c1SL>Z)@OkqnTK@cHX{Iv87FUCE zI;{n1SP*>Gt&I|24`w`$GuiDCS8hJ6?D9A_WQI!hS+Vp}^H%_95{_$Pk?QkvewMkw z8Ak7UlVtc*t9XdIK^(&83|vIjSRsa5f7%qm5pQLnpwavQlDy!#{fQ96!Poj#@UexJ zbVE*_>F`S<`o?av_L>zQG-)=J`{xqMNv)}Xg@CQx*J7(!A79=I^J|(M4$^t10w9sU zc{#-oa2G6J?Yl)htnCd=AKNJO5(YGDttAr@Ge^b)YFDFq$kh_H4(u#M;u`Qof0bzL zgB*^Y9Qq%M?cZlo7@BTHt?W})qUL|7LU%NMAjpBA6J?gM?nWqY?-X_FXjqKfB__pT zB(6#(&a*!`rNfSR8Ib?tq6;(@6RU`zG*tJGcio*ecH%N+!8aU`i8_EE+`w8-@8$|; zpoy-kZyHN}OqJMbmLM~%Ajl&Jf1!KHh#jN>GAE*KmZ~ZD;|q`yOd%FZpFU~$Gr`j_ z-iDhv)igpFU0ifcA;j5?%Jx-IZB!_HNpx`}`58+rPN+~E@U6wOCAwj)2UP|=A^)!Y zgP0L)L%TSLBt=4|yR@N!-@_V;r3E^j$!Pb=Rvqb;fbD%-&y*)P>rzS>f79y2SAjyw zwe_x7Wp??E5{aMiBchH7{lKC34Rfu*^r00M@GcUg4pikjcvPlkpOJd8?W^3pw$GuI zrnjVI_4T&oZa-|~HuCx|($+_o#yV2$#+MT)yvApRCF40ZobTz7nBT8+7>!=%)9aO# zVSLHvqaw3|d@`hGh)9u4e+g=BNmx>TyuQ2|pEvCBcV&|?i9zcFW{x8s1`m&m)xS3E zF!JFeK>5h{+9kKKFx1f}%;X-S9K_&ioqNr?7lKfqsJOrO-*j&IAZB$-!<-hRi8eV+ zTJF0LF?MFtC+JGcM=20XuI8m2)rTiGxz-1mY5kmBTVQ{EWrZ*DfBP}@8F%Phd%nlG zwFiNhWr$PBxAl9fH4S;!hT@Ka1jNm^Gs%c*RHHU@J%ZakX>*6bKpqvrgEDkYlC`DR zib?^&h`QsTdcCg=@mfc6+rV3a#u#J&R)a z#&zc$(jdyf6M5h7ud-zW1eOv<-IpZ{0_V-NT6ya0X_C#+f8D;5Pnept{nQNfun>uyyW(UW>krTNSEPMplKIGvj9rDSz?xMA3u=2a~3OT$xDkN5GA7GuaHLp{<=rgCD|B|hI!!FDpJce-&A8|EoVYF`;vpHU4 zF?W0-*S_FV63wCh^+Ql5>7l7*9_8|l6(Pj+)b+dKY zFzJPwf8+9xNskHvX=j0e`gxO!ch!RuX|^x{yNk29C`wV{#FUeR;ugGDS*)|Wko4*E zyu+Ibq@gJRWk05*Jbzs6yyP<`lUSAQHd^uSes)-cu^)^OP>=V0KJVB=U|Ms|;p!$d z?qT)p8EO)AW+H%_00xYKjH#_5a)-AtLEF!@f92B$2Wer`IfekCeZFZ}hBMGxJBX|0_9ZEP1sq_^WS9U@HKs>)Y_{C*~gA=uG;LpYmLJ+Ru(6YO03At zJhYPb^_zk=_QmH)>Z4Y{uu3@yYcM>mFTtlMSk?|?Xj*0BU)@l_;!hz`QJ$)%v5M{M ze@WzPehN>1m6xj(I=(zB0V0zKDYFYQ*p*~_de$Z7t5G3Op?E~Gw#q6NWUN&i?9{b8 zjgZ3YGe?oFBi&OG=*XD!ygD@#f2Xo}fE$VKp)9^2qH2;7;S!VT4VG5CO6fo!a=i@$ z696>fQPOr@le_$2;wW@)6?ftz29h>S3!=vmQ-w`6b@@@r@ zA7-XmDIpes(b5DUv~~}B57OZ!fsT~P+?#OPgEMme94MEeF$V!Bs!%PImg zx^7UXkhFqnj)Xj(5Y^72BtWS$u}&8hUd$KZyzIFfZX9{_)`Gkq?OieOil$d3e`RDV zGbll3uBv$*zDo(n{d{D=RZF><&k4Sc)zjgw&HAn4Kp*R?ow+xHxI-q%S$4RjJS5|n zTE)g?^cPBai#3d)n6G9eqcvo?{m$$NxZL`kUtMUm=}^}6cV!`;FkKnB4;N{@6;r3t z^9Lw;;g&(75U-_v=R$A?yspbkGSp!>6n(5>T;vH zXKyDdSP0fTQ%yS)T?k=J&kzO;$7(nXZT6oK@9s@-Hsd_<559~|HDgKVe@ETEZj_iR zc3HA}t*M%YH$iW#i}H>PFK~OAh;0h>yrym_q$9XNd<)rbSemUFXDr1MTHesr%yp0A zk6^&Mz><~A$9h>1taMNQHk#u6J@XMulplfW=n2so6Ncwr^1F#(()NK{?|eoz!h&_o zkqe*S9#YU?PY*?D3<+s}e{5Xnu+|-#k%ngu@S^C!9eKec-hkL zajADHC8-g)xDnS0&Cup4B~dl^&_mXeg;zc0xf#c^zaYCM%w4A_afcN7>n@>Gu%Si- zlXk4~qwvInFTVgIj6Ampps^va{kcChJoX*`5QOegf_sv5`laYTe-Pg?DR6%pYNGkk z;-)a9C6%2HjB&lf#REx$9FxRUVZOrT5NOR=qz>Fr~^9 ze_}JKC0Pbp&0O<4vdkW|4hsR-HYKbxU;g&ufZe6wGDchOmp%_ofnlpJ*^gA#;^mUK zXy1hqVW!1Z+Q(Hee8JGg3>hf(3#9DS4 zZy{fhXgy$~9k-4z`2-7DeUeLy^10KvS1JtvbeDOe>wYoxREj~MPFQ@X&d>D z$qXh*OJpM8f>!i+sPK+L4_lf{1SDNjsmCV+Z4Pt)v|-16*?d1n*jp0UjOv;i8N7mK%uJ}Cvtd#Xe>o6qdH5>8j* zjhMPW3NR2lf6e&3)}ff&^Fm$Oq|K^@=c7=k;J-kNa9NO+pT80Yx?;!H?~;3oNhH~@ zyIMibn_!9t!ExYVYC6pC3H0_;TAfqUu+KeXJ(ykFD@f3OH+`o+5b)5pNia%%ADYy1 z);j*m38xx?KuY*^PB|FUjk}Vebw%VycCNOI$hguVf1w>~nl?n$n$b`bO{2EJ@Vbef6lnR@C^G6CZ?uE#}jH;H^0 zq1B0_0l&;AJUI0OK_527G0RC5so#+ZUxB(HBttdhv9>fKM62wWuv) zDt9pFH}3S+*2`)nswbwt=(`CU=RtZY|B$HdfAKzy5&K@gOUMdp4eHlf)j)OsNkJb5 zMt@W8?!Mq`my)56?pJ6Dbmtu?6edCU1~^9*l=#~i4BlpfGz)eKkpjs}IZj&`6JL7Xn2~u#wSUR7;#=5E7gP9zAKBt~|26pg4cJ2A*xAuyZ$wF~O^ zH~j>cC%z*ZPB}5_AubmKGNQK7^yv?S#1J*gUfWOvqn2qXf5|Q>-;*3Lc3D`OKsdC4 zKd0We^=B$LTd{)Nj(A)_Q6e@RuN;?6>HqW%%-aab-fMa5Qm#O3nWmRsPA~d}e_Ko% zd>=x z+a7P)ScWFc=%?`*WXX%$Al+W`e}nNWPE-huHNg>3j22wjKQ3b71jr&IJ!{;L^C5=} z!|zCj>M|7a4T!|DMlpqHJagb7|71Vh9SEuf_1m;gHKKE2?abv7Yf=1qS6`s2d5^3Z z`BQ*xJA{LADsIbqmu)@Jb_quBC9WLH7r}A+Q-RW&#s08zfi6AAsC_Jue`L?aZ+op4 zMo!&Z94={aqkvHqO_E1z5QGg}G^RA>za6oSTqR;9>FQR8K(2Ua430zLYnni47OI-+ z{wv0s;t=dL{xES%S9erf5^dOtjqckZCQ^%?K~!{uObq-gI3Ah4aDiI=@Z1^Fbq8E7 zuAwk)z`c?i%q-SIaj#a?^&{wpE_RW zjxl2#Rh+ocL1M8P#3j*@b{Y{-B9M{nt4yme+%t1Hxy;k}az=#|vvL?X3~(u09jUmO zx3@Q6Wb%Vuh(VN2#`Ix&r!0ixh)AxI3NBtuJzjmtUiYAeW2Iu1e`NH?p+;s|qZNtC zz0r1(1W+o+sxPK~DCPyV)WVEzE|+Kb4!O}*&k>yiN^h^& zv6w!-Q2~8+W_`?IN{P&$ z=jXy;r|W7vgbWLu-?!{`E}>F^Gw4G+v8Hbf8Y$TQJkKq7KWpFQooEv&4cMm84A1;3 zzd1NgxpMY+5%d#oxCHfzp>KZKglViKk(`$hiATqRs(4!cy1o{Py-ktWWA(i} z%JWCd!Rd_Nf65VEhTJ(V@J;R(F|>jp!UXE?=vbg2XEat4!TO~R!y#QujjB@~kc02W@uYEXtWD!29!(M@gWYXMtF3|_3!$!@Ve>84mcX&Q=M+exU=L;*68ld%# z`eRd{1W`#t{sMR_Nj3Ba?aF8zLa2U})xxHrQ&&c21M@;3trtynKBwXP;!yBC73>$x zLFLe9OWb_`rjY(t8EK%5btD#MP*)&f0K@8-yrCU|m)3B9gEZLgiD$mRlzp>|p9myb zs{0v7f5MDgq%^|Jo#t(ld4tieSOJb|&W%nKiE^W@yq5OdguU$h*42~-**J%1ZGqCo z({uNRZrH`kLRb4ki)?Yh4)|k<3>@@OdgU}R1NN@I!PS)O(wU}Nq ze<+M=OW}oRIRsSNBg-htuJ@YFtUY?hB;fGSgJ4da(E~<@T1ulH4hbzY+4CG|i%)x+kUa_K#kl4+^(TI2A0i)fv zssXgnFn#q=)ePJi5gd>JF$4#c%5Iadf7edn*F_JzXl+sxtiY9%p-nXu=_N8Djgtj` zBXp(tT0gpO)zgH9K}zXw;p*0LH1l3afad8$Wn7c{)35^`&vbqZ=5p*N_*SI07+N_9 zG4|GN5F)8_^2BdUO)%D3CnCHOp=GxVIXUodLH^@8-Fof5m#YfxiAvqZOL8r>e`f~0 z!@wAyg$CTs@AdCw-JgoR=Nr}0jdGn8tSRVmc05L50nJHh&~W*`>&Rs-BR zG-K&3qw`%1JaGs0@G1Z43j>v6xbMTqZ*BV8NW$t;c~GmP<~E{;z~S`32pr1?V*0Oe=ZF4L-}lN zG3%eb`U5G|n*Z{35o}5t7hlDX!OdifF|T-T$81{K{Rif$| z+raGXE5G{7^Arma?rQEae@dRcPfa;H3gPlX>r}1)t==0$nX=m%wM;)|)YY0#AklC-;xuXO;3M)i3r?!d_bHkG zSb^d7v;`JtI95X2YpRdL-9*Ugm?!_>FN&qV;kVETV#pIUX|j@ve`u272``4KQ15ef z*dUU#cLzae7yiJCn!2O9pi+4Bl*%o$XozUCn|9AZ-mXO1_C5^hpdF9ZnqxmFYvN{W#3h=JB&%; zY-*s&5(D-8c7}AANI6v^sTUkNsJtIX>jg8^@l$Y($+Y}Cf8t~pB$w&as8E{2CSGzQ zTN&Ug5PsdRuNT?|bkBvo?oULY<-JL%QGn!d9 zoR$Fl3B$B$e+_%k`g_|5OTjU-OyYA(hrRkQQ zo;NH5=wlo`k2Wy!K%0H0(9zuD;EUrQzoWm4it_8He@{SZn(k2FS@R~HG?LN@4%@-$ zqL)TM*~G@1*my==Lr#cpveuJ1z)cy5@{n=CkBXM8ELB5r=7nHnou;gJZknrQc>RdC zKl)i;eYBdlh^(^F4%K=%e}2vdrSzQ+L7^)GzfsL9>74Y<_u}LeE&91YcLp(vbN(BlvkHZv z>zY!sxI|4Z(gQz+(VQzv*r0cMOK}OdT$AzEu-x0mH_Ejt&hjBrky3}G@2F28$*M>6 z-pM(Zed;w8VGq@9XxOhQJdPVdTk<~t@lX+kZwN>!LVrAwQH)uTIiC|;i>iBXXQ(p^UW;jSpJDg;B6=;P^uaiFHm_e&zf*}@B0HdW?WN)8$gU1sOVjGurC?eDvX(VR-(HudV1UeBWIri#9EnbuS zx(7Z_Rew!tK9kHoj!#bWtvzh^V_^I1=@&b7JQ}jPXz!L{MQKL8x{-Z}J1|Ft;=+mL zj6;YQlQYVNjBnQc)eSC|R)e;I8=4X>V@6YUSE1M=;Ww-yIfqtrs(r4NyV9&cDN8f3 z`IoQWedwFq)XFD<``pd~>m6R>mHJS{kK0WtFn@Nzuq&ZI-Ax_3QCXgFOvx~t6L*5p zi0i1Ou@SPIpv3#8(QccFg0~j+p&Ver(JHb?Yc@POu7({#-~;SY#wwNME@+}ue$gQW zE{0LgKGTAMCvBc;nS3#T>V|??;3N#ts+y74$yO+GMzbyb0Bf0kJY+-7vT&~(!hXK5 zG=C$gNeZ?uPi%>|EavG-TP#(TdSuR!yUX0NKy?_s-kR4|=A@~bhFLg*2goPbu{)Mn z8pttQ<&ocbf05lPU_1Feb`dB=_KN5CdFvRX1L(WZL?>bO4IV8 zRXl9|PO`{&cgM5LaETLdm^yXPIkQ$E*E$Dg^my$1GGlE(?_QR$>mZn^Hv1Gi>w2Z|f6XbDl@oxP_~3Ili*oh_Whwu~BwcV%BIUcI2GoMn(x<6nD(u`T65c3kvyr%B9uG1&3NK7$ zZfA68G9WoMGnaw20u}@?HZV1pp^gD4f42otoaquSOpriu3l16FVUWRtySoJ&V1U5} z7~I`0L4!L45+GP05Zv7@K=2?58r&|~-E(&L{D0NGHC4>_bU)p1cfU`6HPBP5Yq3jM z!ptGEFh^H*E)Jj&KuSeLK>z>*@^Aow-01Z5+E7<}$X{l3dR>SM913$3`UgSEe+2?| zeY8n~T_1TWFh_u*n>~Pw2f)QA#KkWJ1Om8$K*9eIVJ<=dX|Oxg5}?8XP=q-`;OO*H zFefh;sI`sj<1znv1Ta}J1GoeQ`Pu#m2S_+TT%Z;UJ0f4NwTGP40ZpsqFmO$Z#~;tsI{{B9Va3U+|}*%=2q zJwV$A3jfot1+#MX0J}f{j|O|F1;i2l7~$q<32^~D9uCk_PzIf7AUH{W}rV@sD7zg$2yP3GCV|q4~IR* zgWbVUd$9Q<;g8C}09gqQ0Qj-NzuJRaxImp;;T&+N{qGhzf2VnzvW%mp6wJW^;^+!T z|6QLn)CFSkICd}2KX2B~5$56O^B1s!I$B!&Zo<;diBrcB>g)zlkp7GEXhQ$nW({!# zfPe!0JOVrbh%*4=UlmlNa9ya0A?5D>t{f5im^@IOBI{X301 z82VQkz`tV^9Iar0NB$q>KF;YsCA{^9z6 z*7_eI|9=wyo#p?g^8YPJ*3I7j4>!{v{{N2~>;Sd*`it1^ABkQI5`|)u8$#r$DaKFe^xLT^xxMkzzyKk{B8OZ z@d7xt|3(4;PW}HPL4E)y_;2*+GygC8-3h1V-|#VwCB)wKZ#vgwFyx;Y$OGWC{s#mB zIHCW5d;m_{f569RyT9S1OgSC@0Uyb(f5XSZ9wqkAvwoZ0|AyR;;hulMe@)WD&Bf($ z)PF3%Dn8u?5stla@mD$E?E=XHdRUI%bb1({f$Qz?rPs){}Ns|Wk*bqqI>Yx z5nZ?|o{Vrmg)}c}mF`jj_HAyd`+f$#kGULy6p@xnKD8zZdcRaba?>G+(Jd{izHL^N zO%nP(e+kZ)f{gFQHn707D;`j1h(KEIG);tcw2!68vaDucYtvlB;3V}diHJGq;J-8P#9CWhkq zM#Qgje5$C~4N@TnnK{N;38vBrfyFYPD%I%M{ymt}sAnIj2nAojv0uvPSW-Isn6Hb! z*uXak%taWcb%CrV$)F`%zMy0AcAQ~<-_<pNi+3cOwhsB`hM{PPsnre_|JyMik9*ZE41rySrJU(tu~At|J&aCA9a4 z0wcsBY?X^QkS_&0a_j)+SuUvuUfLbO^_d1q|FrVt9qAYabF}-jr=}QuZ1FFJmttUS zxVJS4RH+0Z%Of9I9M zH-zgbBH%YoH|j!}bvNeXIfxFl2#lA+8>dTFV|6hfXds(sAZq3lC<#F-nW9kE5swEQ z?h55~F*ZCRWqW(?J2t&&`cMrWm?wA z8xE{aLVI!4@t*C{4r;hMw|{aIf3*Oz(hXYV3jLhnr5)zcWVP{s;`M|F^s(}8otIlF z^j$+p-MPco-m;!I2YG?@7PW1h1TtB^@6?!kykHsx583&AXt~!*_LXzz0#0vd8lt^z z82aw{Rw+VK);2`~v+d;D5;&5meQ7m$St@r;x%KynbQCA;?KW{V6;7X5f6e9xN?fXX zId@+u$*)c3TnPfDODPBFzMcrLb;q)?-GzPFYmhY10P&y}$TE>8$Sh$5Q3(KUN}mq(Ua{FFyQ{&w zxO!YAw{9JJ#Kq@j0nH$Bf73BZa5~E&%CwKpo0f#k5PbH&#$`mgg76Bi4rTHvkWRZS zaQ9|1RCG^8lNj^K9L_iwv!!#+1(;1_F8GCJYRY7%WT`>Gf@ywDYTl=&=}Ru*0^N55 zde5&}jP>7%-C&7bpwS>G88$|Sgd^CBYX~rgKvtSv*Y%t0gLWE4f0l@_=dV8Rr`T=d z`kW8I*$okM^BtU>!(6%*@Ew+?oe^9)1;M%Ds)R95tt|`>iKb;EtSTv`eeKKkloJiE zIwWl`tUp|bRcDs^nN=MHZ)8>5&=F^B(`6)R%lEM3Gm3Oso672Y3ps3F3}4)|(I&jg zCKdYRkN(oAOy+#^e{8D4ybl!x2X%j;e9eP&xh~%8H2;o%{4KSQRk?oJ7NE1VFo;->(@-rRGxY-*=aFFKDla)RxF(0GSRW!e>C5Lgz#|(Q?gbGi8Y>L zRrT{QJZ!Qb$$Zg2;e6F{SLoi6>HSGu>9{r4igvI0E&%n{5-VIbQFz!7Sf-?rTV+Jj zwp3tu=?f?j2S zNQc(Ict3?Nvsqw|z1*7q{MEo_&G|`PE{9(Srw^HNQR1vUNoB(`;)zl`8X`IkcbUm4 z-7gfYy#~4BLq9tazxz?J(hFWq-Ra-~Pe^;etvsk$e?042?`{tL!ew$-g*k^eZCOEK zK;p|7l5`bPA#(f6056wF23M^}M1q|Txh9cuU^%t}SIvm1?5b5#K?->@IH20sBUWIo zRwr|+J@2$gQ~aYihh(l_8FFzfUqMJvF!x}gcBooe&pmlC>8E2Xd|Oaf{31W$ma#lDVWbb3dfsmh|%<*%bUfaUO zp90?hN-9G^bC~2)blo81tp2>^C|@OGs>z9H4C3qa*P5&CZn|@xv?p1jUJfyzXEPaA zpPqSsewuq2lZ=v>MfD5KD=*ycs-g8^+Rjscf0CcaG-iK3YNp-CrDqu6;QWA^_O`trS!CyK)amYe7n0nVY>_`ZZ?Y|IZ7h`Uq=`VfyNl-Vr?Jxjtl4`+u^#$sJ~Z~fAhNeyAoozj0)16z~tJN>)Gs3B-1TIt_IHw zJHs-JXX%kEnS1%XHM!$ZQ$eCJDh98@Ncf<=#Pnbq4@=}aqPV9Wn>eDcXZz+7XI|*S z#MEHw9JAW2h(uT?DW3i>-5K3jWTCKddt=*9UVBYD{A(P~Am_xKBBR|qTzl5Je-JhD zmTNKDWP^4@u-?dlyhBL#UVe>{ea`GNeo>2eEH}~+nPMv6XI8h>c~9irvH1v$P(mZd zu{(4G_G!L!XOB}kaGeE!cYt>`Um*z+pRA<%XIK%l4hs@Nt3QVNK&W}J-7eMER1f?S zlNh_K79oOfa#%MaT3WR79{KKke|_jfeW*2`>i}F4Xh9gUhb?h(7{`!h+L7RWHh{v5 zPSfGn_tWN8d>tqxJydskbBI_ut>$4$UC*;N?JBN+h5Vw82&>0Ozj@+%wKjaXy=qoF ze|JH3O#qK?D7E5u>&L^`Uh?Tff49nLONoE@ zNg<;3^tnZLy2egf-R>)nwL~Ef8q)Wn&9%jz=oHa*hONIouFlibBM_L%Iw_W_zbr>; z>bI}JiC79+-Dh0vCAEBw$NKG6ZCL4Dd5DnkDMHVXnA&G=&^F-(uG%;=T%M#CQ)AqT zXzS^{$wl`k$5G{4YJ}o^e@l`MZwirQo)?|*^A`LeN3GxKvC*ZpUPT=*R5+4K?>{?< zx#8xYXW)KMR(Pd^zQnj~p=q;|_*NN2YfX5}*9oy_Zg~ z5*95Fg@rvISN^S2THlE&xE@yp9k$@P#7a9uNv6Z z-@v4?L*q?-ZMAm3UfhHS50GwGXeFJ@2GD*fPC4epD_5&o3K>i^6R6W6QCdrPf*6le6S`$ymgm(`Ww47=>Osrsr?anyja57 z2&P3K&%ugpizYqrGxodw z^-C94f0JDqd{6_;p_2v8%?6IT9nQ#&!NYm0)cPT$39n#3N019WZcPsWG!^2jn-c`a z6F7N_ym=9OlP+2^A4f1*5h~g0@qwu$g6~UGrSxi*4liPUGfYvnKDu z*kS{6FIH4wBu*tDn?8stRIA_OCvdGV{vL*`0LAygXFzxfpfUmep>_Msi85h zglFxbhvDp=ExBBMj+#PmIDd2r+c0PgwtfEYTieG@kx4u85_-6Tk(rrXI?WBRWeO>rhpnPa`(ZozQlOwL+z;)MjaHYwEI z+EZTEn5VIXT84qnM^0uFm86A7LDBZom8;2 zNFV+CSRe0VXwEOeOH0)Oah^;gK|R-;gp8_LZRHERfFpXLpPNLJnI!XtG4H1;cPPZAa`T=*s(5Rw{CkIw;q!pqs*!T!qo#L3h$t#)0jZPi9lp6V6&Fa3auy0*!mNyfr;DyHTEmSmMg=I%gfsD9_|8;4&r5hlZ2u9R4Sb;0VK;7%77We+yCxN3R!eW)LFLt%?yjJ8}5%)XvYnl3!0mg=lXK3#R+V-59IQ zqV$<1+kV(xsO7?Cjf}|9dmh4QS)!V;vCzd7TWbHUhpW6&a$r%K#Kd^5u*DnggtbGN zx0)+0yZ~S0tq#63dMs7>8KGQ8k|YUL%LCR@lCA_}{(;t6f9b9B6kZCZt^3wxM+kE~ zQ7u02LG>~A6!v&b3n>P~cZLGm(?)J@=7tx-8MB>?0&8{?HJz{3Mr1b8LYZKv3Ul=E zyJN$MG*oSrc|I=n!Jch*GoTZ)x8RGx<-_zU=KF8+(m) zmekd&Z&cbp>$R#e+5p=9QEqzY#Gnc4jM7q^H34Lde{N2Ha`}~_-?r^GM;cuazk-$Z zW+S_RIS0Qtnd?29WGVjvj$G(RwHfI?92vmYs9o#mkWuZhT3CPSi2-S>_@#|wdWsOs zap`tlw77;?MoLJ%x(tbQpw_8TRm}CfJ;3sO-ezubb!e4TEy?w1*r|$*hDK8Eq^HVQ z+FNP&e|h8G*yg;s^XtmVl8QCOa+W6T^#a-@n$t;}ujFBK$51^}5W(Qv6fzR9(uj6h zIoT=Q9Bl+bL=y+f-T@$}H|+?+011rZ@IA2WC1T>3)rsCZZ8s4?!mewtErYjxn8K>Q zIH_x9P|vr<)rRB%vY={~>%)UDh>W6UE}fkEe^itixb?bBKat?Da-=Z1&`!-_gs|gw zv>6CvUFZ6BUJ+YPx-(xqLQ@se+QcpE;)o0p;O`T*;t^ev&LB(dQ*o=Qh=}+guZ}!*NDA ze`XRN>`?o(#B3Yo*Hh<(ShX;vKM5JL$`@<*fQSh@W2~OPHquQHG8(l0a0cu@tbDf) zNLHAvarHy*s)I>)+2NePA4FNF2Z*S;rRVPimaakH{8H@KVt)o}v56lR7;$u*>*uX3 z_wNbqjtS#OW;BdotoYGB^G*}C6nnX|f9s+ziIZ8-tL~P8!QH(|W_kUh=Uv{`dS!QE zfp$GwrxD7UMODpd*(h~sQ5qed3&AIK_DXN&LjTc-m#)h)FhH$Iaj+^snP!{c%?d{0?H_6n*nD6drfagl<6jL<)e>NZn7%99C?3c9*>)k=dm^TT}85l&`ku6bX7HB5pbUe z04j4HlmhQ(`lmd|h=B#brbvgV<0>&i9J{;L=wA7XiT!V%m1BzYP-Io!#w1|`yVV7W zYPd;O>}pOJBpNG3u{!C;`O}R@f4Enaiu-mZ&36)HJY%PEiew4H+;GOgi|#LUA`|xg zXzkPRet|*ed+9Jmw!%q0$u3$ZmQ<#bW%+6z4ZO(vfp{@kJSq~e{HSKK?PjoGh0(W{ zKLIgZh|ggBHi{fr&O?U*sgbwBFI`?UToZE{5nx^)vY1X@6h3S%J8dJnf1STo8c`cN zfPSkU4Ck=fh5C2hz0v%#iAiR6mu~@UOTIZ!ETz$JL6`Op9ZPcl3KGtOokoSzjHEFp z91Jxw^5c;@+8CU$;PweY@?!K6RyMG$V0JIi+&Pp&#X?$mOsss~E2t=f7?CM$3)D(g zy5)|{jf|5Pc=~7Ko~D{pf8G{!_2}Y2MRd>JKd;OKej7>j*IeAO49$Zv%e|k-v8T#h3(iIgk6;fz;Z;kQu%f2>bw!TDA|fh^il8UHp~dQ%TG zuE7HS1V=1jT0oGsQrb}X>Fe2NJF=~rR z0!)5P!V21(`>5&2sS+0iMwu6`i@%0+;* zcfj^q?U=rB)LlRECS_9&*Qg>4w-9wcw#pMbv$T8&N$H8&7?N}T{1lrGd+*Y8NFqd+ znUS1AcYPz4f2N9X0iWiy4^OKt&pbpLlb+9_lVSH57;GwZ?{3C3`y?%RhfwNvp4X!M z1wwpoH`*rNix(u*>N{eh*BQ2fS{(y|5Zcs5vE;xJJ79Orm31p0ON=+y$@WDf7h+Df64*Wu!w|92 zq`ruQSa?|;Pp`ZkG?mA6T*Yuu&PqZ9=8&43YJ{#}9cOLbYcc&m6lGd|%3@B5P4vbm z?H5O!M6SpZso-UG=(jvNHH@>Zdi~}A3u6@9f3{6@xHpcWTIO(54YLM<2GYu#v2C2V_c>lwn&1Lv~K%hQLmc;-mB|LSQn z8-6NJ-9p>)bJ}JQz>c`UzaUc(m ze=*5%F7QnOBbQDUZgx_1vzkfZv_$mmXntwnd+TI;hm zY{vJ&i2U@zHC_}9<*I7fkOGzCTk{=0ERk#%;Hqie3EcA3u+z<)a&ast~`txDXf7)l!qK~I}@yL7#X~n%D>&?cumKGw7>X`&_O>+zL7p-m& z_WXU4ZK*%OK2JoWprg+aA~i7b$KUgH$>j)EJLc&Ckoz#W%G%)HJ*`kBQ4|xN(r6uR z)Kuo2D1qX>^C%wnmC$1F+B61M5hSG3jP0WOwXR^Nw3`Km`%hRS=)$;7!&Qim?c7m=r4}J$6hwAS+bK0c^|UQ0UIYPiQ~KTW>JvP zPD#n+ak5b?RRpy4|X?us2D-jd|49bLL)~Mqv5$t}p2Oe`mE-S``GD09Hb6LKz75 z+dtH3i$R5On1GC=YHI{-biD=4U4K~tb+x0!t z#4UP5S#Ivw#I@v_b=~-2HgWy zk|kwOyf97Uf7>a(iqNKfhkBrA=Xv%Uh9dBSzP;nPn(?uGLlQT%QaCm+`d~HF6o<4L zKwnWAG}g-Dtwfl$f*S7E(w2k>7>I2+F1{xBqOwr#d)8$A!8a(7+Fj7_mt{v7Ma;|k zYkhF4@oM%<3jXKVM@fhHi#GUF9C5%Sa_qXGOp+$>e>Br8G=UHX{IX7W$X)k3+EBR}8pxS%IYFp`t4jLZ7N6coZTVi(yYq&a4} zFEv}Pf67^wcw)%9a7EK^;q&q``y1ad1{k#Ka_dmS4#W|{h-){q$a#h>6mB~+^kaB5 z=05v+I7c4b9SgkYJ>etVaOz8AO5Py#shR#OS1b^Vy~mrOa1!qNzlDJeRVe@k)2^jmS99N!fu>&s5%224p#>!BV^ zPc1#*E`v?YbCPN?Mq|pLQ>)lQg9{rze zx4EBxSLFB6h-ALT`PgA5w@Utu*e80T#9P$UF{4?`#q6M$RirOO7VT$yr1kqwP zG)yPGpgKLacrO9krw7gz6c<}9>lWn`e+1>9t+O3Xlk}BJ`Px_Rg`~tU26z-2V&^X2 z?FY`~<1&7sES8N-pR3p>m;go$3+Eu8`h3MT&R(+3{8s2+->i_x z@Qrt7jl%bc>(CY!n_zI~xI>GRZ3XwAwYT7%j4M)hFm0TryOY(g5|p0af3k*;f0c)Q zQuFJh$B#BS!3XdMSC9~SrRGWO(C zg^4DWwb;+p!pRKibY6X$0Vc448Jb-iRH<8HYLzqw>MFgH=lfd3Hdac}J1!N~)j807 z51y}kTtGIfiPtFM^T8M+33$SGe;=7|j)zi_KVBL`h%d)25ii&*_#ZN0IbZ>4ei{3L zoexjEY|S+(t$>7l(5{r2z>M|saJ7pGT-9}IoXDOVQw<}ZaMjqvfsT{hd< z3b)R`G*zj8j6{_dM`3<9A@`A=oU`5IIRvHmBYG#0|0d^2mL9QzIJ&%8gZPfOjd8+P z4QzYV&!uMlXa47}69nqvf45WH!nbZibvERKGDIi#q#taJ90r6VD#*|eg#y!uhs;7_ zHGY*JhzkzodsRB|Xu zB^~Tt)x8{ntcqS*bz~H!05npH8UQJvJO>VDAoecKwH#g|mYlKtV!XL{fiAQ5_&5#;h&|FtIlW z$V>lIZtv>C`wtpu=4|(`?ic{B|FdjO{%4u~&-!21+4DaZ69OwMz#L@e3NQs)g6t8P z|D~IZy@dnd`+vgbZjS#={X@v*AASIue>9{8m;){TLA%-7Dw@~<0W@L`c8+eYKxcr0 zgE`RI9-!)AXJUWZAu_n&&;KYILgqUH|vwqE~t%YWMV_lC@3+8Ux#BJ}?ofPbeY z?9Cj^LH3paHP?T%G;ucnU*O+qWfRbUrsuz8{yR+o*8hL!E10-CgFFFxEKL6z50-ze z|5^tB4<#z<;OWE2%FPL2WM^XmuyXwK;o)HO`~T22b8~hE+PnT+@PB&wumA5s0s=jO zW(aG`4rY9z)@jY*<^B?dvlYC1<<5ee;Svy_d%m>$FDBj+e^_JP@`w+ej)<*>8nv^t-=bfOog8J z)*yc5h3q0;Q{ov}6_f`#9{$j|WoKxzx^mz z;HD-i7?1W?flq@rW$GC3XZMsJ2`0KADiuprWccNugml2i`E13&*;+`Yf zEgy;G=NnAwQGZL!u2e33vkHK-Z7>3g-ZWiR_Mpbjwoxt-ql?Ih@L7?={*3r+HLfa) z;pFZN;({|n8AtbrTM`+RR@lboPhK~^Q)ho$*k>(iqxU7Ausshi|5IMr=f{}k20_t; z4t*BW3+90NY4JXe6dT$XH%-@Yz2@~N4hLs4)$=T>F${^((}pg4I4S{^eb z0UO#7P?9F8b)s($y<>OA-B9+nVjua9%^FOh+5sOGFC^B7#}pVX!N=4Yh)+GRy-I(q z67PmY@DzfdPYlaoX(gStexfZbk+TWZJ3;=qKyO4`Uk~u4w2AmT$%-D}86~-ys+1cb z=mx=;6xB29T;9}x(>L-dW<5kGiIu@zUfmYt?b`FnE&D0U9Z-^DU90xyfpnU(bk4Yb zjPiuo6}fl68-T0p`HjvHh2FZ5FgAZu>YJ}t(au;ao=H&~k7fNg#3>n4;9f7L+or$S zIGpLxP;ltD_2#EFryR`V(+~E|{46fIH1_WaE~dUz_?SduloVgTUhtj6G2GRB3PR)T zi7qTSll%5|bxM7zZF4PnLd^(^F9WBXt&@z$F{Q+h5Z3Dx^S~7YdvbHnsr!Fd)lmK# z3=)FzL0>{fTMSQgm;2SOT)R*=>*67!dD?pu$+S?i9_m=_^E-4VAuc-KQvGSignHVW zn!9LJnmt!%lfiP5<|+-1TkFdpDbF6-vpOTrEMPv%t@S8{{Rqe`aGzmCX7Kxl#MoO` zLi-mvf|c3&?xxq8ziv+_biRL1yt6a#reAJBw02F%BYU#T>;3rfr+R86u!6ju%UI`LTH<{5Yg-XejHxH=o@b%k+OSO}>AgadA0& z@|HoiNb_kzeYI{f&}t6fquG%WRhel5BdYLep_IPKXpiFCdHlwNVROk?V^9=>5}yQ!T)YLgdiFDh3VD998RH7KC8}*XKC*vgkP7C?5 z{Ubiz@shiM4AWF9m-4sRIy-df>2voDAie0ajPV;4l~_rdNc3*;XruA1@8XkCkdyyt z|BP?)CCyHRDA}}@gT7li$ZV;TFS_CJfw$jkXW~V^tU}`Yg+YJHoGhI_3GzfvOyY6f zjL3iNyO&fmx=*!6&BE2Fi*|Q;E==#W8#0*XwPvWr7$nNQLUJwL+Le}%;r zvQ8sID>AMn>UaL74EIXt?q-V&R{bONp4_byl)@PstrCe#+0Z342p>zQpLazUsIx7dm7wb3#Zeq(2BG@7 z6xy+36q|g|$iqRkc-m6`#*PXzZSM&FQ5{veFEunr8@vz4wT8U=B z13c8505c*k0CQ_Rl`di$iqsh4JIf?A5mR9Jlw67TX=||w@}Jp^*M8eM!xn!&47R{EQCV2%2-^x%*k)v+8W_Hz6@&4< z-Y@K3=%aIQwMVY+h8CVKZ`j^RPs+`=`Y=8H41kv&hq{KlaLp~>$eN#wNPpDybccCd z8PkkNmpl}H+gm=mWU!-mI{G8Nz?0Y#u+t^EM*4y*%0GvU%ACGMPiI&d`%UTXX^?-I zYD8L5@tWJVgI+Dwc@R7fz598TF^?8%T8XDsi6#jgmf1I9$eE-LIG3`Z(AM=!!?bNF z_$Hj1Jd#k8p*!}sneo*s2Ni>Y$qptlF)ywpwp3=gq4JsVs zzyO$?IR&u8EiXYBq`yGR||pTTJ2(k|@AYa^Spw$zd~fCsxpIanDO zp1|`985lv@n${MC&(fB(4tF?33n16y_<|pXxY#OL*h6_U+o}nXoU$+Np^iU56TKIh zHsd|OeZSukY8drD3S2(od*Od!6qjDCmLu`eWH_wKtHdha~WiA>=K@$)f^_H)tRp7@kqJSUH)k{ zQ`Wbof>?8lY6vx(L-}=q_tZiwn_K&qObR)z>3JLC9O5}?I(tZjqq~3C;g&}kaYRN3 zi;YAx$W5BmwVgMa`Pn)J3FT>W{ahHE>g~ISvQLc#C4P%{S-;u8YE}?A+%A?id8O38 z@E{N{Hz7uu%tBY*{B88nTsOBN;wP|%jA7_Zg(t`D_6@5&=Wy0%B&IYx#GvC_VY<<2 z-*8~9?)4zcqPvwElt+K@j9lr0TD0LjLPpfJf*@$ce`m<#!4OiTg4HJ=5d-#2V$s9v zUHXZ>myPx9)FCFi(GLypFk@QxmMS!7>nj z(1`Ili7I61T%xq^bZLsRhZ1INNTBrq>tP-1Idbhvb=Svg&PIt&YzF@YVPUM6g3_x} z!P({h`-ydoPEM-QRLsQQg@z5n`4PCxF6CG`v7)(M#0J}IHj&)j3%T~h%7!bbs8)R8ynyGB z@y??@2abkx5%#3`oQq%cD${Q6gnX(9a~+xi9!mIYl@Z!EU>=;te61#FRTeMV(3ui~ z6;H*hsfd3NLBMo61KHHV!8{4+UM(45)?4BryPLgxZlxfvxNF9&ppL4vRdMImtywGe z$}L+G1Cv*2QKULnXf{-Y(_>L3YG@>B`~D31;omVI;HY>mC%11a(sM`6qoXA5sHkQ2e`P|PSwx94_S6hS0wZsJLz8s}g* z=0WveAfp@GFr1tvxse5A2_WpAe zZ^XeW`+#JJEU3?LoXAv1k6Nu1xXT0~9#Jxk*`{I1ge?y}9 zh6kE1G0w{R^^-?d(O2Jif!A_m{xt1@eu&WaE3Udq54^ATuzpIneNnImA2*COk=X_N;g|wi1F7=3II`UBG0gE@C=DE7azy*`$b)(NxBrE;fB*@A({>w zN;|quBO+hA@P%EP6lLbhgycXI^ESFD%Yj=ZC}?qC5||7$8bYkwc_+UuKffq8=cwh3 zv*U4-c+L-E>Ec?i9+CWDhZfj2rC5JF-95TGR`C;Nki4QqUW;gBq20lMx|(H&820p- zx;0@1qy$IfTzTH+7h?SBJ2z}{6e4&=3mZoOLPOx7EjUQCjIvar?3$KVyDXo z{_~i$#nK$7pqv(?(ryiWi6lQoPNAKwLqp$78AewQEpriQ6u2Q-hSmV@BM_R<^Gq78 zq~(69qpMM>`nk$>v6<&yw{m~qVW~dtc`en##0o|$g{@eRmN8F-ol|fiZPaeRiEZ1q zor!JRww<2XwkLKnv6G3DiEZ1q{`_^$xjxlbUHiT1uIlQ3``LS~#{%|cs}zY6gaZat z#VywyFfpiJJFFv+fi%6?D!O*>BG!{>lWyz9)=}-l;O<+?DuMiP3Uclh^~kReq}psq zf!N6B90-2oDGJVjKwM zy@5Q@6dl*4(%HPH2q5|okegWZEZsOa7j}>8mNMnWn+t>dAwXI_I=LM4CNorRpq?mLddKz4Pdj~tYy-j|te7T{3PQ@= zpfD9(uH78h?@GeLCp2ApeY7$QL4idb93FmWe>&Qsa7X?I^)f{6c}Ozf{Sw@`BWf(9vfIZXT&= zX@4UeAgR0mnB_TG0FEUPxjB3}j)YO^{;XhFj z|MdD4f*|Bd?1zQBf^BRF?m`_G`Mb0UoLvrEP1Z8$(-&MJN|2{!H>w_|AZ88?PoHvz z@**V1^?-_C7$EN@i?fl_>)Xv@w4t|K*~8$DUx@J}DlI1?7)_2;qKQTszZ=SlVT*bi z7cBRwOt%+GugX3dC!BI$iWyy}{7-I*&b_mYo{dVIa9J{I=tE!87k#%rrI{i1L50@I zjh&Tt_u|ycZ+g&lxgZ%)YWu@+^hW_|Sq#jp=`Jn>H!v$`7wF1D;oR7uu)u3$RX#Gs zkOvBkK?@O}x8WcKUqWGxmdl!!``T|7I>V znVe)S8c-sX31hxP5E_*`*yhqrmtIKxVgzxc_&Hq?v2zAK3VLLYRJNDH<&tB?CRzFk(qm$i13DvIIS?7RU8mCIn`8{^-_jQG@9OSp+p46Os;Qa!fDI(Q4C=YpI*! z1x)2@?@~#-Dcy(EmvU3YI*S&mQ|~3F21*UL8e-P%X|XYcv$|o@G8%`ZjrD`w+@(Iv z_h0w^)p)ELfQRdr{5f(Lvpz^|^kCKbNZNOHvOAwOUpF`@pD;5<^TNKHU8l4JmgLhA zi>)a|Vv)qD@5_IkX&3eV!b}Nh>TQc41$HpLKA5?h?#F*wkO%!oxVEtHY}c1#<@8(G z(W}f!$IMVZb$`@7g<+qL+9Ntrzk#x6z&`$`T1%Ng21x^&b}=!w`hp9EYfoa8R#hrn z3Z%1N;QD}$<8mV&gu0?PI0RH^lG(#*j(xHu;*{_fOOIkDr_3@Q7eg^zB1f!|GC;xT zK~-9y!m$%8PsgqH8)BMe>A}4~0uJ6f`Fg-Jz)1P^gE?gIj!nn~RVYZgv4r3A+&{;< z*YH0!B>xZaGHS2TPfHgyk!4y#QmsT<{=4<*qrtj96lgf2`9qj?~(#P)3yE_cy)sCM5XK^t;rOnIy zQ><$CriK^bssy{ev3J$&LF=1&499B|#aRH+Y2n4Q_rSE%;nX`5IK{`*{;*6{Wtp}`Q9H&?QdE2i_s;xUXaz^5Kcn`k z^}HwbN$<=TWd9b{6R?H4`kznV3)4Aj@|J$V!GFV;*=&4PTFVE?Y^{}jNN)wOl@Ukx zcD8qmc7iMSI5?23;X=|2dVmdsiS_*xUs|dVC=V!8$5%8$pdkD-%6q@ttD?*B{qZo4 z{gNcbMUVostnAkb&3cwR10GH=(h6Fa)K^mVnnzno0hrj9TI%yX@#*YzXzyZ4z_L`} zEFD55>9?f`|E6_u^Y_SWCoDazlJ0KUR4fawrQ5Pvbl6`oQKj}FZD3)eVcJ{dj4Kg6 z>j##d-Z+(-+&bb*Z>p@Jk&E&iQH@lr$o=L8Y@1}8>&hJlrTz6Q_N#~lQJ9yiWP+o{ zX+>c`{UtlcKK=3QkwAHc>_Ce|;CpQkcq3{3Np=RzFvy$zKk^!l?5t8cijex)j~Y-F z7TK`1&2}xOkHtFaQ($E{(P2tZ61~e(6L;X`4*tl0!_iNMy7>zOeoiQ}^0loBT<6p9 zWVDXxbW(HLpwa*=H|@DYM%5j9L58j>GSIoHh_lvC(p21nKTNe0NN-$XkdHmsRBXQ6krY611TW%4I3R_X9seyjDU!J!l5dBhF<2X){b_yq$*nBR zxA74ws5g+T3n*g0NR`UrQKcBga?I`OYQ+Z&>kfB}YEUN_M>j~98?6?u9KR`)y(W#i zFJ&FCAKWrrt%g8@;V(fxwq6!VvUyCgx(fz{JLi4s+OWi14ck$fHl)#NL&s^ghrKb3!l?3`JIo63=*s$Z zJ94-+0SI+na(f8|(nWiYrrr+1kaPATd|6jGJbC195pe%n46cDojE;pg{=7lP!xU55 zLefP;q?2$ythQKr=!cYqJ6!GvLPCu`KY1Wt5@E=^kG_l5WGLKruhR+*dkEtDO~WKI z_&}`t;`{=Ec^&)A*H0x&Glxo)?rQAj35Lcj2EduS^+TM<@Izts{?`Wjj>-G^WWOiO*!QDdzUG4K1R1z0-ukYX5mC{%qO^y;GlIHvE#$8-LaX2gg(+7#2Crp~K3F#nYcVNP7gTcf&S(DANM8b&=&%;|mB=%yc zd2`pqtmbm*5IGst%vQHF%R^ZK4Z_a_7D!+#_6{L|L6uaVUfLA@Bi`5mS;e)|-_ndA zcNfeKSrC#;y5o$HyojLEJoWH!na!hN7cBvPJxpwzAU~7lClM^t3gv6Z-b=jhE|JYx z_hlBizFPso&K)7TAUsnbBORBHP=^>myV<7s&#{qaGQ7y+A55a#6&C~REj`y-Fkthg z?+D*4uum_0tP;UVZ~AL?lK2-tKjuwfQx91>)vv3hiNVpkQXHj0Enk^&P9Ho2Bo`Kc zF%FL!hkCb~EK>}7P_~l*dykGtC<|lQiRUE2@+TwNw=AM0RO`v5t#$8*_;}|^R!|mK zFEPhCKDR*Jy1Nla!Z*7nL+=wmCtxHfkk%$#QVRzcUgA&Y#?!Zb3RkA!@2P@1uN}nI zeomn>H!1S3qhGReCN2E|?gp%pMtF1!>_a-D`t0t**Sy5Xr8WfLs2AQ~&P@^qsa|he zlb!FG@1~bo(x_2B%92n*C{*mc>opo-^g4AxlbMLDRhb^pi<5zf5lPkpEdW|JTdR-2 z+OcK!4J3E(?m2L`Z6QOiYbfx8Yv>vgRpkkr=XbPe17gH#43+X%=)G-*EJ+5VIwG}+ z()<;;W6iN{xyLFm%o*%JoCr%P$pnk_t<_?LR=9Mx!tr@Cr2Q29t{KT={J-35jP^gP zPg(dFgr4O|Z$>*rxI^)x`9R(w{HapPe-Yv(&8!tTJ$ZE_bD}?;qNvalE8&Xzd|hwL zvmUrJSCN=@sr-FN;I7BUKvV97VB90_`?52Ss#_9NiWH80PTEa{eyiC}ux8VIgy8Hk zAYz5F^r)0(F7Fj@IrR`n-b0AiPM@>f&)AQVX{zH9LO+{8MHF;ZF#|6uH_72#uG|&% zT6r0HB_8oT!^%tR3%C5%P{KuSOS2|gHd;*Ng z@cI8KB3F3d0RFil&LCsMHN4<__t39W#yiwBKJ=0!(GTlV#ns-~2ht)$a&1_sPNg$q zdZ#01zu?!;TzRAY8GwfGo;?0JVev$!g5S>hpiF)sDlThHd1rj1f;;8eyBK&o2sX+Q zS^SbohS~!z`K({t51I2BC_Ou)Sv$E(s4Z+iN2nienYrvrrHzG5kr2-nO$xjYvh~fG z=MY(FFA-&Wwt_9DgI|gVQ?)PHJ|D2_{O#_bg<}}?_gYX9uVgx3& zc)@886|GDJI;@E?Wlyi#0XuC})P-&*f!^mdWUrb37Su?@sk^Qi_{2>h?__3x36Dk< z;`vf$LpYXbN@)8JQJ|dFE@rc5Et~QJvV2ODT2{uKYek#bkyMW$?B`>CE6<8MBw}ZT zh;d@Y4U})+UjY0!jm6X1?0E^@4JC=JW2Ac*;x4}6QF^)STL2TPWQ-xsBu-(-N77vB z7s5Kvk%R1ywwAfDRPBQxtRCA>$a}BMI>$M#es7ASrk6kU_T`Ggj9s8kTDqN^n~B?# zGFKjtYvjFtZ-hUdkf`X}UU?885T5#Q=lle`11jq7iU5(h3pM#3#<;tr<66CH8Vc#P z6!wv9qIj1UUjRE-Vkzy{KU8wb5SN{NgnW03rI z+WY93KNy)g@(dB}E-G`%3KOcu&$t6p`xucNohiN{4QLMaB%Gr8)1xjnr~ zBh2QCPRFydbM=D#CnxG;rI;`mZR;NV+6K0}CWU{=;}sYIqnVaQ{m1Pm#+J8(q%D@N z+7o^gsSuuwtc>*CNd;=U9cABxsC^@ej=+-*3IJ(MDjTTiTewRlk&=KiJN^$v)ejH} zQ!DlZpwQvm;@kW%Q0QDS`EI$ohnVKjA$+=lfxVYVtyF$oKXYY=r^ZS~hU1-ZSEpxf z>Cr(+wTu9j{)|Y;P>)A_gjpJ3>G9wr%d_iWj2!qaPO(tHv8x+I3HJq-JZy1Z0pKx?m=BGZm z|IwbN@G}WhN4*~Xp-!4KRRaSBuXsD4Bc^~+m_5e;4>41cXIT5StXojGfuM-<9Xq;c3( za(D7Cm)&gOoKKw_pI~TPEm@4&RFe+w#PTO-; z@ANx_zm(bvh~TfgSS{-%k8aVz6Lnv?VjW4Vj`cn}=c1J8=rg;g-KC^X6C!kND#Qhk zMRTiwN1YTZ=@v|QzdyW8Pb<&{P!?d|Hvdsv`O6jYb#~2RD(!~jhp5s4u9VJhS>%9S zukd2n$EH!CK~UsQ#uG{aa1Bm56{*bld##6GAK+K~8NGf>HggB&NsOAYShk<_?wNzz zvg7Z!xv7Mf%#)kCe^u=Argej~dYpnyZFf_yk$=88i+@hUcxlb;r+EU(D?h1rHyKH? zIQ`$S1d0mem%0;DKvcY$iA}du99~5aQD0R?R%27A(*Y2hzPJhso;sZR4=S{$;mh*GWj3(Z$2)4mPM4`6$4Tz1ONkdf2nk{yR1Fm%rE5?J7)D(sgPSgm;h)@t?Zx+r>LM z^nE~@nD=KxufZ*-J-m0gvkP1*AFfn)h7+IO!5Hdyc4W8RoZv81bLY9F9b3Z&2X*i$ zuZ_8rt)O16A{86GUkC4I<+uE*{(?#zbVr%k6)RX8Sf&8beewysto{R65IfB@a6x54 z!{h(!kri1wCkb!=z7rFJIvOwhYagM|PBh^UZU>l*wpaeqxpI3Tgr}6Z+^l~Ovxx2w z3pld=>=Cu~Z%g*n4e`LyDIfHw%QJ0%Wlkr@oYeG`?sb@&hr7FYQYs-6Eqa}cojU(- zh|ZaG7Gwh;{09PCS@b@p;D=SrwHO>0(jlVT=-GT)QGOPg1eW{3ag3$UC=*7cfGBgour;(Ie zg(rMcu3tx|=6d$qvN6kt0qBo_tN>d96YIONw?G5HG`uSySJKA`iz#*z7R+MO($Q@K zbq!SQ$+O=vF8IIu%G_}Xk^s!#B*0fv?B7QdJ8K_z(}%jDfvy_%x>>F%sIIW3sWqsA z>=Z0F$qtmv+2T%2sBTpFEVsb|sGDXSq$!yOIg+4x4};tFmd-V)J?U~vo+T$CL|m3| zi=I3H@ls3}e3YHfbSdJKRR9tdY>H)TzZ(u2Q%3@kF6bu&Vb;6|p$EDULg5tA@aH{J zt110kLsHXz6?2tz13WjCPrL91iZ>W4UhUNsDLgkp3kqh#rwpn~Eq!QQ&wAwzHX?X9 z<3v0c_5S_g^RnNRy{Xa>)=MvNSz}zA9`pg+%$|asUNah+)A+6m*UzkZX)Z0MQ~%be zz49EKF3jRF+;G{I-rNY)e(EZRt&!_FwoUKIb5=JCrk1}(iYmeVtz4mQTdp%VSb=~i zKdCY;z+{+dJ6(jXmc9)h=P%R3)|m4h;HhMX-{cZbvKHRF&*)}8Mz3nVdOQksJMRK% zM?dv``_GhJ%UW4x_NJ)Rr?-3S>ue7mOQp@s?_v%?$rkc!qaSKcGBoQ1re8SR5oY={ zxeAi=kY9+Ghj^%`;6A425u^6_%2@1t;q+=R(c@2hNByL2f)puPAgt4~V9|L0_(WT; zxaMX*?JgP}f2QCpxck&Ux`fF>#q0u-4#1{Mdgc=7kwSe>B?QG&W>5Iab>oyjiV2DS zD|Vv#*R0tMJDfjd6IAVL9(u552tE^O|LR^TVc)I4-5+D9alfkCQfRJknoj5ph0XIG z*+%7Xz6&4LQjUJ%Fmuq^Po+pjGt!)?C0D9Ys9)acI_|cu3Rn2&K4AsJ$x;jW7?$M7 zd443Np0hAOPSUK|s>d@b`SQDD>w!?IBxdf5UzOr!@?IEPZ#(!Uoq0z@pG;m6IdZq7 z2(uyWI7XX~ar}!+qs4+wzs{3=&WZapMAoW`@}7%vvWd*^SH!bjN5jMVqElQmkHKn9 z+fwIexcgKl=r6neMpF^f$Xy%YVBGwA44$$Ui5h%(rj5@)Z9tLkaDVB_zSiFh2Ozy} zWy8PJ7cTGHbjA}psJTiS5m`=#lL}U79R8QS4ZMuav8wF-E4z@P)^NzE12_gZB=TQv%rsoqMwJl{y74hKW8R4Daa*123x-KAa-yk($F6VN~ zI2vXXNRl&y7#Q<&@4_%>C_Jhxg%Kv%N-ZmG)#UEd8drd&4(Y#&;X_K%luo}gQ#e&_ zJfUI6LzxI%5HYMXTb0let{wNK{bqxZ+u=o+B9e+?RQsXpja5+xkNk31?U5yI+8bJ` zBTO~4{JD+)BsjykC<_>dao_K}$Bzb!Jr{5dlVzlaD9i|A+Zz5QF!%$wp?s*xuOx{@ zkjijL(v03556MgrPnn@XXZ&Nx4@2|KpATY!<5^XYsJT9-E!jnfoEZc;XCo)-Q5!rl zGT?W{PqAk5@;qLCG);Y+u7{?|BN4k(qL!G53RF1&=R@sc_w1m6&LO3^QVj=x{1Vg)=3!D_1ZE4lfw&5bXa%#HdMoc-Jl zea+NIr{Y{BXdx774Br_XHQ~iP@l~B_j-iNWs?|ZT-+^hqp$ncc? z&E?ul*rmI3%)2$KBsCltvTOkvSz(Uz% zWZD{$FvHD6VGR+S*3$RoEuT&k_C2kDa7{2NHgg5lEP(UZX!3y~6{p=b$P@L+NJz_J zVFv5q94lS*RYlcv#jB@DHZ@f)A&oid5(Y@VB~yuiQXr`F8(y4h(^%EsZDwn_*mH9- zWUxj5h~vdI#^3lL%J5|BbUHhvOq5Y6oHuO&9F?Epg%Ekd~mU!LBvzt|gjv!HKaF`*czjDj`0TH-I7flguHL z(Rn&m(?e^ntdM?K_klkSRaBW3+#f7SNnb7|RRXvwMqiSo8#WVBWnJDVLDMC>Hmzpr z`Q)A8BRM~raWP@qn^t)Q#|mVU@Al}wFXCOfY*p`LJwvLa*n=uky=id8yebwp`e7lv zwy8A1BVM9S*~sYVr`s{NVD_f{yldj>pDVVeP21wo@cq%%lpj33wiKnbh?VmN{Zx7; z9u2G-4U+%J)O*sGDiofmo$c81NJEAf#o_T5U}YsMVXw0Gj!aV;ljD8=g~XO% zXm(PPS@hi7WGWWaYo8N|hfxY0kq*-1-b5A&2-8`jU;0{SMH-l#@7)5*78}9nkOu&b zJ7J8O8RJn%OLkhu%GNz}h_0ohGL51gFAW+OI-0{(DT-E^k4xtYV_kOdhlCT?V~dI$ zk#RG6hNwg1a!O=>9CW3oA1Gx$I~|ZcP&fTaT7n_YSbzi=#%2(+Rn9`N4rU}KJ6C|_ zywgRLb=1gSnPD($pQ_=vpcl;Vy#TdXG^DMvvsiWujt}SOD)W~&oBuJRIe279%6U!J z^u$QC{=P#CduU20)+*1$4ehq%{5l_x@wL{an*BH5w!0s{cLrTbcdN=@?|;F*)z?0C zOU?U3U5_=Nw0%Vm1vA7AkHK*ms0rbgu+pR{u=@gI>7T?NJ zE~|73MlSst025c)&$n22fik&*BGrhvI{K$0uJ2MX3qwvriTb)k*i)*7<_h&P&xLwE|f!=B}B3$g1-lvY5*y(}b;Gr50-9C+Y{#ew)=KfzXo zcjx@AFo0tVdFRdKssGB5@DNb1ImxkS0q&+m4L- z&6o&LpVNF!gvUS$>p84LO~v3G(d{}MYEK<+9$EQH>Y|SgDCSSjw=Akn4ycqyqiNyp+GpjE%yd;-2yL zHI3Z|R+&8rd0=lKuDqMi0AYJPq&T1r18Ta<@sz$Pp>0{_Tm>5IyhhUiiK z4@pI(b-0!7!sm8s3osrC)!DXEYjwu&@lCc!6yGJX@lYwl`$l7i{&`pGN`f9mu^DHnMe zE1M^MS-0QjviNIk6sNjXa#BrQ=9M~+*5HERxxJ}lDzfuX25_1cRat1ZB_)hR3>ohm zGujWz<*mDrO8QZC7x- zE^Cx1;l7N26ezK(9pC?(AsY6i$RckI=Cvd&G%xvReWBYHqK8zZ<)Cx9KY||DoSl=a z7N52cYFPW>a!kauB+qOtRdI^CSeaAwPy7+HV3X=-5^bx5dj!92hX^e?Yy5_U#-|I4GSlfQhrv0Iz zvsIFxf@3(xN1Md$eA^&q8U*J>wxRr4LIPt%sUSm+GWjPHXYY)=p;T(xJ<}xU=I|KT z{z#B67m$I3vn+Huq@G1*JF6(&*6Z#OxTY#9e! zAq@dz5!yFTtd3Hi>^Y<#nW5$ncFqEyUmL$P1K-zmVug6zAyD%l6qr{aC-XF_l@l5? z0bF(%#Xj#T#CVH!m=+JPRxO-^=Kl~XGPi}q8mbGrEla6SQ@kz6$^`(<8iQ^%%AbS$qs(y zRemw%!n zcphs5p5ZWZL-41nu1(g@%{Yo`kD58^m9GcN8er>?n_toOFr~-IsYH=7^51nN46=~% z>DPZE@x|zA#JZrUEn*iSybd(XoXl)2Osp*QOl*`)OqA3xjB*a9qDHP}L{y?YEKDrS zOx*u>Nm_+2=m-cWcN%fa4=P|nM@I#BG|~S^<9^RxHofNUoBkwt`JZ+kWF}z1x7Siu!^VFz8wXT{1fP92ycs!$};E7g_}4>L^xZi3?A16Gvw~ znIA!h3vCgB0^bRXn*hYSDR)Z++oDZS3UjCM@!?n{&#^#{THcTrb<92NcN~GX0=i_vPdsC<+oK@i!BWSS7Hoh*AXj| za}g>|t}KOvC4s3rdo@Ig6y&{?B`0eAClt z?>ucv&eQx_T4`O1O$kAD`1_>Kypz(@mPIv%@4|%z;KmZ}R{0g@I-B%_@Y?3lxy%&5 zu|YdSzkhKM%)1}2Ca^U(y8e}BY+ZAkw;)1rOuQ+DD96PxMKyJ9+~7UG z&Nzm!&}6Cj8>GyJi&iVvukAdEs!+?`ij*Ubc}6k~+q5dIWWeR>`-A2q!!dMbj_QEoWL+KUBpHt6_MY8gf^ZTSN`$y?-h za|A~|)e5A2#E5iSd)y}&G>65FNdkc$_-m=P22vjOL*Z|vIeei;m!NV?P~kSI`2;eA z=2ZblL=(rad6;@RNJU({Mqjd+V3PQ6VF{^?Gujr63P>F9-#`P)DX(9Jf5G&uV<5jl zuFbMmjD#)x)V3qj$?-@Pl|<}~)76&wQ0beoaF-+|M*nm2F&ACcE9vofzRsiO)Xr z6eQk2(&P}~9b>v%h%wz(CLsHEh(GB!bgK4Bbo!h69>J^|zmySMzvW@4oCCYv3_ zIVbziqG^6rMy-l3vUWdbPK&ubK)iiRmo61WzeBl8&vLkH=;ewDm3Mn^b-8x=6K(r& zC3efWL|C71sm_ht0^=m~ImOpw7KC?!Ke_**7FMw6hYZ=#34%}g#RfO@lTC>qJo z2b13-4Q+(+e^HNZqQd`Z0xc*p8NzZk{1)Jb4hqUtbtr|LWN8!C9&_KYXAH87OD3nZ zuv>pbqlHp5E$^GBIC%_maqkmIa@6wm5b2@M9#C&qoBfkO3)l0SfzkyR5@u8Fl zrnQE0t!YWOUY21DxTu1@zJ^GliiKS%K63+6VyXqIs0&(bj~87hl@j^J&qyIRxtOMH zM-Jq3=O@RV4hWfBbpa}=;e#4X>5e05Fp;qs*l1UQu``)-g$J8=ifh^o&( z!54ZHkpHRWw2(?9QiJwB_$%8fQkvMtd#g>1zn2=k!Obi749R(Y9L;u04GTCzQO5im z;|Y$LFP`PETePijP2|&uk*p3APdyW=5p@$iyOMqok?VY6Us1p# z>S>n+XiDVsY%z09M#<1UN6UR-rYd#iSj_HSwEFd-xw#4~$ZbWpl$(AqNoEUr0qd%@ zUSlDFWDYfa1w$QV&&rL^2u5uTQa|v+hitN=$I>n`ipGZJ5|Edqv{d(%E$*T?*GULG z6TMIv-c1j43IR6aDrCf3cun{&T(xasT7;Gq3E0VQ;ZF-8WU)BdRz;M&`9aNdOC@^l zYFGk22JYTURDF14`1OQ!C!5YjB>YETZa^O3eumq zSW&zcp}_m$DEjer3AsgyNQyR0_}1(LF%KP+Nx-P-I^prcAB{g|`5C|#hQIsnPwNFx53xPf6Tg{|JZw|OVgv)8vszb2b+Z!?~UO)^o|5Axg z*=fgGs-z2#24h*u=N-v#gW`wI4>nVa>XTe3n8kT~+$C!=-uqijtHxN~vFHf@f*Y}% z;ZZY~tHS*P+p64As%@NgQyuC?ZnzF_qz?IW#umPEfgmI#bc`^>tkitBUG_UjrWB{^2tm$wgz1huBxe1vRy>;Zq!E36>w`^Iw`^=ZBa=b_-o>S zgT_W>l?;+?4c<=1__tE6lP#^TY7_E%Khjqmih!w{vE$Hkj1riLzG24jFN(0U`%oT* zku<=}>BvhLwh>p)#ngc6OgP~QW3_C(s~^bBH2IO}_VF%6wA5Bo3i7}Ag-#2-Z?d4H ze28LCz1%U9hv`ZwU{qFELh(`kIdBe}?)RRsgK~A^&*#VSRL<&=565&cYX~WD2T#`4n|y43FYl(f!|1ZAD&mEdnDYX2VIbuUi) zRUWXs@n-gRFz2B?(|2{W?>DPP}$K8FJq@))`AAH z2*ag&j1ASJPFMNfuj}-BEFskgrLT1&A5Wg@sCs;lxq^&>Q>UdjEw5JYGyD(oO8ifh z0*DmmUBlpRd?+ulpM;PbEj%dHl^Mc$i5GA8-l05LC;5Qs?i}V+3XB45!J-XH(TQp zW~tuZzvo`LVV~E`dm*@H@$Hg%dQ|J!B515#1DdW@mEPL;vlD4n3m+|gd2pKyR`(t~ z2Ux%Cr`D`^`Ed#3w2z$u4(uEPxo%%8#u4@si3>Ge8w*O4)q9OMyV=h$asI&99lRyrZ?=eP!C z(xaiX?4_<*u70j1qD0!<-J_$km#5$3L2~`b&V4dPY)Qim@two)#q-qJj1}*vyC)Bi zO^@s+PRmi!ofB_y56ze=bx9XjSIIS38(!Sn%97PvOu?SBb|uHDn`%c#Q`cAQhm~NJ zW2t-t&l=GtxMKc*a!ARtYOo>07ig~?PYGB~cG5$HXVy|}F zOK1IhvEkUZMQ8nE!V>-uQ`1?ul2|c|i_-N=7&3Bjc zcw1^d8nCJ^dKkW(TY~H;AUaZStCJTK>bwPcb}ir1gES3Djz`^=f`&uzozca2Wj5?eKU6WFFQbJ$q04 zN?Ii}wpH*+U*6s=UEP%VLUkd&%1T~Xy1IkEvVD8Fu=CP(6?Mx^;kpS+HNM$$YCEJ| zy?MYz-qPI4^YI-uQafa?QCug^mlz$_7gU>;TSsKAzfDie7xsFiRrPqs$K}MLeO#Jp>JmVT z5pCG*UYK#hx&vA~64(;IF5=T`^QsX} z&v`m%KSOyxtCH2UZi33pwVtFeQ>*;e#}>n*83?4wdme$YoTOkSOLKf88a zBKl|*EknNLhvQAK^8R`U7sn^%wz7C^9c|DErw{#zmjYx(<^4OCWvDejCx!>#jZ(r^ zndq76&cU0IuX)z!rC4cq6cme#yXoWm=$0Tt^5vUuAEXmO9R$RhIz-mI$8y; zidz``HkIJ_-Ps)qF`U1^u8PwLWjZH*J<%-s`z?N?fy!h<<{nyWxWJlp-;69Q%H1G#x> z(u_TN=QS}yAHjR@I)TM^?^Np_!uUHsCRwZY-;PH6(U2sd41QT8o%rBE7kWFZ%D6N-U(#Qzkb1z%%bgvpIJj9D8xp~QhFUES`-^aVfTpw zvkDL+MA#%sD5U+S!O@A#Eb2J3iGKm+^aTdp1ahKW$->==W%fWl2O id@X+lQH#?g*qKMQmnP&4N&w5o$;|>oPA;Y(4)Z@CnVJ{? From bbde7b980c732a3e70db397e1d3f43a33eaa7e61 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 21 Sep 2021 12:29:45 -0400 Subject: [PATCH 0019/1686] remove print statements --- gtsam/navigation/ImuFactor.cpp | 4 ---- 1 file changed, 4 deletions(-) diff --git a/gtsam/navigation/ImuFactor.cpp b/gtsam/navigation/ImuFactor.cpp index c0797d0e1..9b6affaaf 100644 --- a/gtsam/navigation/ImuFactor.cpp +++ b/gtsam/navigation/ImuFactor.cpp @@ -75,16 +75,12 @@ void PreintegratedImuMeasurements::integrateMeasurement( // (1/dt) allows to pass from continuous time noise to discrete time noise // Update the uncertainty on the state (matrix A in [4]). preintMeasCov_ = A * preintMeasCov_ * A.transpose(); - // std::cout << "A * p * A\n" << preintMeasCov_ << std::endl; // These 2 updates account for uncertainty on the IMU measurement (matrix B in [4]). preintMeasCov_.noalias() += B * (aCov / dt) * B.transpose(); - // std::cout << "p + B\n" << preintMeasCov_ << std::endl; preintMeasCov_.noalias() += C * (wCov / dt) * C.transpose(); - // std::cout << "ApA' + B + C\n" << preintMeasCov_ << std::endl; // NOTE(frank): (Gi*dt)*(C/dt)*(Gi'*dt), with Gi << Z_3x3, I_3x3, Z_3x3 (9x3 matrix) preintMeasCov_.block<3, 3>(3, 3).noalias() += iCov * dt; - // std::cout << "p + iCov\n" << preintMeasCov_ << std::endl; } //------------------------------------------------------------------------------ From a2bf0c4da4e3ac52a99da716f4067e0fc70b5b53 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 21 Sep 2021 12:30:04 -0400 Subject: [PATCH 0020/1686] minor refactoring --- gtsam/navigation/CombinedImuFactor.cpp | 17 ++++++++++------- 1 file changed, 10 insertions(+), 7 deletions(-) diff --git a/gtsam/navigation/CombinedImuFactor.cpp b/gtsam/navigation/CombinedImuFactor.cpp index c8d1b10fe..de4d3f66d 100644 --- a/gtsam/navigation/CombinedImuFactor.cpp +++ b/gtsam/navigation/CombinedImuFactor.cpp @@ -123,6 +123,9 @@ void PreintegratedCombinedMeasurements::integrateMeasurement( F.block<3, 3>(6, 9) = vel_H_biasAcc; F.block<6, 6>(9, 9) = I_6x6; + // Update the uncertainty on the state (matrix F in [4]). + preintMeasCov_ = F * preintMeasCov_ * F.transpose(); + // propagate uncertainty // TODO(frank): use noiseModel routine so we can have arbitrary noise models. const Matrix3& aCov = p().accelerometerCovariance; @@ -138,15 +141,15 @@ void PreintegratedCombinedMeasurements::integrateMeasurement( Matrix3 wCov_updated = wCov + p().biasAccOmegaInt.block<3, 3>(3, 3); // BLOCK DIAGONAL TERMS - D_t_t(&G_measCov_Gt) = (pos_H_biasAcc - * (aCov / dt) // aCov_updated / dt + D_t_t(&G_measCov_Gt) = (pos_H_biasAcc // + * (aCov_updated / dt) // * pos_H_biasAcc.transpose()) + (dt * iCov); - D_v_v(&G_measCov_Gt) = vel_H_biasAcc - * (aCov / dt) // aCov_updated / dt + D_v_v(&G_measCov_Gt) = vel_H_biasAcc // + * (aCov_updated / dt) // * (vel_H_biasAcc.transpose()); - D_R_R(&G_measCov_Gt) = theta_H_biasOmega - * (wCov / dt) // wCov_updated / dt + D_R_R(&G_measCov_Gt) = theta_H_biasOmega // + * (wCov_updated / dt) // * (theta_H_biasOmega.transpose()); D_a_a(&G_measCov_Gt) = dt * p().biasAccCovariance; @@ -160,7 +163,7 @@ void PreintegratedCombinedMeasurements::integrateMeasurement( D_R_v(&G_measCov_Gt) = temp.transpose(); D_t_v(&G_measCov_Gt) = pos_H_biasAcc * (aCov / dt) * vel_H_biasAcc.transpose(); - preintMeasCov_ = F * preintMeasCov_ * F.transpose() + G_measCov_Gt; + preintMeasCov_.noalias() += G_measCov_Gt; } //------------------------------------------------------------------------------ From aa4a163480424688835c68384c6ae7aad239ca15 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 28 Sep 2021 11:45:31 -0400 Subject: [PATCH 0021/1686] updated ImuFactor doc with details about CombinedImuFactor --- doc/ImuFactor.lyx | 542 ++++++++++++++++++++++++++++++++++++++++++---- doc/ImuFactor.pdf | Bin 225898 -> 243257 bytes doc/refs.bib | 68 ++++-- 3 files changed, 547 insertions(+), 63 deletions(-) diff --git a/doc/ImuFactor.lyx b/doc/ImuFactor.lyx index c79a5f37a..4b71a29ed 100644 --- a/doc/ImuFactor.lyx +++ b/doc/ImuFactor.lyx @@ -108,6 +108,222 @@ filename "macros.lyx" \end_layout +\begin_layout Standard +\begin_inset FormulaMacro +\newcommand{\Rnine}{\mathfrak{\mathbb{R}^{9}}} +{\mathfrak{\mathbb{R}^{9}}} +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset FormulaMacro +\newcommand{\Rninethree}{\mathfrak{\mathbb{R}^{9\times3}}} +{\mathfrak{\mathbb{R}^{9\times3}}} +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset FormulaMacro +\newcommand{\Rninesix}{\mathfrak{\mathbb{R}^{9\times6}}} +{\mathfrak{\mathbb{R}^{9\times6}}} +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset FormulaMacro +\newcommand{\Rninenine}{\mathfrak{\mathbb{R}^{9\times9}}} +{\mathfrak{\mathbb{R}^{9\times9}}} +\end_inset + + +\end_layout + +\begin_layout Subsubsection* +IMU Factor +\end_layout + +\begin_layout Standard +The IMU factor has 2 variants: +\end_layout + +\begin_layout Enumerate +ImuFactor is a 5-way factor between the previous pose and velocity, the + current pose and velocity, and the current IMU bias. +\end_layout + +\begin_layout Enumerate +ImuFactor2 is a 3-way factor between the previous NavState, the current + NavState and the current IMU bias. +\end_layout + +\begin_layout Standard +Both variants take a PreintegratedMeasurements object which encodes all + the IMU measurements between the previous timestep and the current timestep. +\end_layout + +\begin_layout Standard +There are also 2 variants of this class: +\end_layout + +\begin_layout Enumerate +Manifold Preintegration: This version keeps track of the incremental NavState + +\begin_inset Formula $\Delta X_{ij}$ +\end_inset + + with respect to the previous NavState, on the NavState manifold itself. + It also keeps track of the +\begin_inset Formula $\Rninesix$ +\end_inset + + Jacobian of +\begin_inset Formula $\Delta X_{ij}$ +\end_inset + + w.r.t. + the bias. + This corresponds to Forster et. + al. +\begin_inset CommandInset citation +LatexCommand cite +key "Forster15rss" +literal "false" + +\end_inset + + +\end_layout + +\begin_layout Enumerate +Tangent Preintegration: This version keeps track of the incremental NavState + in the NavState tangent space instead. + This is a +\begin_inset Formula $\Rnine$ +\end_inset + + vector +\emph on +preintegrated_ +\emph default +. + It also keeps track of the +\begin_inset Formula $\Rninesix$ +\end_inset + + jacobian of the +\emph on +preintegrated_ +\emph default + w.r.t. + the bias. + +\end_layout + +\begin_layout Standard +The main function of a factor is to calculate an error. + The easiest case to look at is the NavState variant in ImuFactor2, which + is given as: +\begin_inset Formula +\begin{equation} +\Delta X_{ij}=X_{j}-\hat{X_{ij}}\label{eq:imu-factor-error} +\end{equation} + +\end_inset + + +\end_layout + +\begin_layout Subsubsection* +Combined IMU Factor +\end_layout + +\begin_layout Standard +The IMU factor above requires that bias drift over time be modeled as a + separate stochastic process (using a BetweenFactor for example), a crucial + aspect given that the preintegrated measurements depend on these bias values + and are thus correlated. + For this reason, we provide another type of IMU factor which we term the + Combined IMU Factor. + This factor similarly has 2 variants: +\end_layout + +\begin_layout Enumerate +CombinedImuFactor is a 6-way factor between the previous pose, velocity + and IMU bias and the current pose, velocity and IMU bias. +\end_layout + +\begin_layout Enumerate +CombinedImuFactor2 is a 4-way factor between the previous NavState and IMU + bias and the current NavState and IMU bias. +\end_layout + +\begin_layout Subsubsection* +Covariance Matrices +\end_layout + +\begin_layout Standard +For IMU preintegration, it is important to propagate the uncertainty accurately + as well. + As such, we detail the various covariance matrices used in the preintegration + step. +\end_layout + +\begin_layout Itemize +Gyroscope Covariance +\begin_inset Formula $Q_{\omega}$ +\end_inset + +: Measurement uncertainty of the gyroscope. +\end_layout + +\begin_layout Itemize +Accelerometer Covariance +\begin_inset Formula $Q_{acc}$ +\end_inset + + : Measurement uncertainty of the accelerometer. +\end_layout + +\begin_layout Itemize +Accelerometer Bias Covariance +\begin_inset Formula $Q_{\Delta b^{acc}}$ +\end_inset + + : The covariance associated with the accelerometer bias random walk. +\end_layout + +\begin_layout Itemize +Gyroscope Bias Covariance +\begin_inset Formula $Q_{\Delta b^{\omega}}$ +\end_inset + + : The covariance associated with the gyroscope bias random walk. +\end_layout + +\begin_layout Itemize +Integration Covariance +\begin_inset Formula $Q_{int}$ +\end_inset + + : This is the uncertainty due to modeling errors in the integration from + acceleration to velocity and position. +\end_layout + +\begin_layout Itemize +Initial Bias Estimate Covariance +\begin_inset Formula $Q_{init}$ +\end_inset + + : This is the uncertainty associated with the estimation of the bias (since + we jointly estimate the bias as well). +\end_layout + \begin_layout Subsubsection* Navigation States \end_layout @@ -725,15 +941,6 @@ In other words, the vector field Retractions \end_layout -\begin_layout Standard -\begin_inset FormulaMacro -\newcommand{\Rnine}{\mathfrak{\mathbb{R}^{9}}} -{\mathfrak{\mathbb{R}^{9}}} -\end_inset - - -\end_layout - \begin_layout Standard Note that the use of the exponential map in local coordinate mappings is not obligatory, even in the context of Lie groups. @@ -1018,7 +1225,15 @@ In the IMU factor, we need to predict the NavState needs to be known in order to compensate properly for the initial velocity and rotated gravity vector. - Hence, the idea of Lupton was to split up + Hence, the idea of Lupton +\begin_inset CommandInset citation +LatexCommand cite +key "Lupton12tro" +literal "false" + +\end_inset + + was to split up \begin_inset Formula $v(t)$ \end_inset @@ -1075,8 +1290,11 @@ p_{g}(t) & = & R_{i}^{T}\frac{gt^{2}}{2} \end_inset -The recipe for the IMU factor is then, in summary. - Solve the ordinary differential equations +The recipe for the IMU factor is then, in summary: +\end_layout + +\begin_layout Enumerate +Solve the ordinary differential equations \begin_inset Formula \begin{eqnarray*} \dot{\theta}(t) & = & H(\theta(t))^{-1}\,\omega^{b}(t)\\ @@ -1095,7 +1313,10 @@ starting from zero, up to time \end_inset at all times. - Form the local coordinate vector as +\end_layout + +\begin_layout Enumerate +Form the local coordinate vector as \begin_inset Formula \[ \zeta(t_{ij})=\left[\theta(t_{ij}),p(t_{ij}),v(t_{ij})\right]=\left[\theta(t_{ij}),R_{i}^{T}V_{i}t_{ij}+R_{i}^{T}\frac{gt_{ij}^{2}}{2}+p_{v}(t_{ij}),R_{i}^{T}gt_{ij}+v_{a}(t_{ij})\right] @@ -1103,6 +1324,10 @@ starting from zero, up to time \end_inset + +\end_layout + +\begin_layout Enumerate Predict the NavState \begin_inset Formula $X_{j}$ \end_inset @@ -1197,7 +1422,50 @@ where we defined the rotation matrix \end_layout \begin_layout Subsubsection* -Noise Propagation +Noise Modeling +\end_layout + +\begin_layout Standard +Given the above solutions to the differential equations, we add noise modeling + to account for the various sources of error in the system +\end_layout + +\begin_layout Standard +\begin_inset Formula +\begin{eqnarray} +\theta_{k+1} & = & \theta_{k}+H(\theta_{k})^{-1}\,(\omega_{k}^{b}+\epsilon_{k}^{\omega} -b_{k}^{\omega}-\epsilon_{init}^{\omega})\Delta_{t}\nonumber \\ +p_{k+1} & = & p_{k}+v_{k}\Delta_{t}+R_{k}(a_{k}^{b}+\epsilon_{k}^{a}-b_{k}^{a}-\epsilon_{init}^{a})\frac{\Delta_{t}^{2}}{2}+\epsilon_{k}^{int}\label{eq:preintegration}\\ +v_{k+1} & = & v_{k}+R_{k}(a_{k}^{b}+\epsilon_{k}^{a}-b_{k}^{a}-\epsilon_{init}^{a})\Delta_{t}\nonumber \\ +b_{k+1}^{a} & = & b_{k}^{a}+\epsilon_{k}^{b^{a}}\nonumber \\ +b_{k+1}^{\omega} & = & b_{k}^{\omega}+\epsilon_{k}^{b^{\omega}}\nonumber +\end{eqnarray} + +\end_inset + + +\end_layout + +\begin_layout Standard +which we can write compactly as, +\end_layout + +\begin_layout Standard +\begin_inset Formula +\begin{eqnarray} +\theta_{k+1} & = & f_{\theta}(\theta_{k},b_{k}^{w},\epsilon_{k}^{\omega},\epsilon_{init}^{b^{\omega}})\label{eq:compact-preintegration}\\ +p_{k+1} & = & f_{p}(p_{k},v_{k},\theta_{k},b_{k}^{a},\epsilon_{k}^{a},\epsilon_{init}^{a},\epsilon_{k}^{int})\nonumber \\ +v_{k+1} & = & f_{v}(v_{k,}\theta_{k,}b_{k}^{a},\epsilon_{k}^{a},\epsilon_{init}^{a})\nonumber \\ +b_{k+1}^{a} & = & f_{b^{a}}(b_{k}^{a},\epsilon_{k}^{b^{a}})\nonumber \\ +b_{k+1}^{\omega} & = & f_{b^{\omega}}(b_{k}^{\omega},\epsilon_{k}^{b^{\omega}})\nonumber +\end{eqnarray} + +\end_inset + + +\end_layout + +\begin_layout Subsubsection* +Noise Propagation in IMU Factor \end_layout \begin_layout Standard @@ -1257,7 +1525,7 @@ Then the noise on propagates as \begin_inset Formula \begin{equation} -\Sigma_{k+1}=A_{k}\Sigma_{k}A_{k}^{T}+B_{k}\Sigma_{\eta}^{ad}B_{k}+C_{k}\Sigma_{\eta}^{gd}C_{k}\label{eq:prop} +\Sigma_{k+1}=A_{k}\Sigma_{k}A_{k}^{T}+B_{k}\Sigma_{\eta}^{ad}B_{k}^{T}+C_{k}\Sigma_{\eta}^{gd}C_{k}^{T}\label{eq:prop} \end{equation} \end_inset @@ -1313,7 +1581,7 @@ We start with the noise propagation on \begin_layout Standard \begin_inset Formula \[ -\deriv{\theta_{k+1}}{\theta_{k}}=I_{3x3}+\deriv{H(\theta_{k})^{-1}\omega_{k}^{b}}{\theta_{k}}\Delta_{t} +\deriv{\theta_{k+1}}{\theta_{k}}=I_{3\times3}+\deriv{H(\theta_{k})^{-1}\omega_{k}^{b}}{\theta_{k}}\Delta_{t} \] \end_inset @@ -1325,7 +1593,7 @@ It can be shown that for small we have \begin_inset Formula \[ -\deriv{H(\theta_{k})^{-1}\omega_{k}^{b}}{\theta_{k}}\approx-\frac{1}{2}\Skew{\omega_{k}^{b}}\mbox{ and hence }\deriv{\theta_{k+1}}{\theta_{k}}=I_{3x3}-\frac{\Delta t}{2}\Skew{\omega_{k}^{b}} +\deriv{H(\theta_{k})^{-1}\omega_{k}^{b}}{\theta_{k}}\approx-\frac{1}{2}\Skew{\omega_{k}^{b}}\mbox{ and hence }\deriv{\theta_{k+1}}{\theta_{k}}=I_{3\times3}-\frac{\Delta t}{2}\Skew{\omega_{k}^{b}} \] \end_inset @@ -1375,9 +1643,9 @@ Putting all this together, we finally obtain \begin_inset Formula \[ A_{k}\approx\left[\begin{array}{ccc} -I_{3\times3}-\frac{\Delta_{t}}{2}\Skew{\omega_{k}^{b}}\\ +I_{3\times3}-\frac{\Delta_{t}}{2}\Skew{\omega_{k}^{b}} & 0_{3\times3} & 0_{3\times3}\\ R_{k}\Skew{-a_{k}^{b}}H(\theta_{k})\frac{\Delta_{t}}{2}^{2} & I_{3\times3} & I_{3\times3}\Delta_{t}\\ -R_{k}\Skew{-a_{k}^{b}}H(\theta_{k})\Delta_{t} & & I_{3\times3} +R_{k}\Skew{-a_{k}^{b}}H(\theta_{k})\Delta_{t} & 0_{3\times3} & I_{3\times3} \end{array}\right] \] @@ -1403,26 +1671,12 @@ H(\theta_{k})^{-1}\Delta_{t}\\ \end_layout \begin_layout Subsubsection* -Combined IMU Factor +Noise Propagation in Combined IMU Factor \end_layout \begin_layout Standard We can similarly account for bias drift over time, as is commonly seen in commercial grade IMUs. - This is accomplished via the -\emph on -CombinedImuFactor -\emph default - which is a 6-way factor between the previous -\emph on -pose/velocity/bias -\emph default - and the -\emph on -pose/velocity/bias -\emph default - at the next timestep. - \end_layout \begin_layout Standard @@ -1430,14 +1684,18 @@ We expand the state vector as \begin_inset Formula $\zeta_{k}=[\theta_{k},p_{k},v_{k},b_{k}^{a},b_{k}^{\omega}]$ \end_inset - to include the bias terms. + to include the bias terms and define the augmented noise vector +\begin_inset Formula $\epsilon=[\epsilon_{k}^{\omega},\epsilon_{k}^{a},\epsilon_{k}^{b^{a}},\epsilon_{k}^{b^{\omega}},\epsilon_{k}^{int},\epsilon_{init}^{b^{a}},\epsilon_{init}^{b^{\omega}}]$ +\end_inset + +. This gives the noise propagation equation as \end_layout \begin_layout Standard \begin_inset Formula \begin{equation} -\Sigma_{k+1}=F_{k}\Sigma_{k}F_{k}^{T}+G_{k}\Sigma_{k}G_{k}\label{eq:prop-combined} +\Sigma_{k+1}=F_{k}\Sigma_{k}F_{k}^{T}+G_{k}Q_{k}G_{k}^{T}\label{eq:prop-combined} \end{equation} \end_inset @@ -1467,10 +1725,19 @@ where \end_inset is the -\begin_inset Formula $15\times15$ +\begin_inset Formula $15\times21$ \end_inset matrix for first order uncertainty propagation. + +\begin_inset Formula $Q_{k}$ +\end_inset + + defines the uncertainty of +\begin_inset Formula $\eta$ +\end_inset + +. The top-left \begin_inset Formula $9\times9$ \end_inset @@ -1509,22 +1776,213 @@ derivation as matrices \begin_inset Formula \[ F_{k}\approx\left[\begin{array}{ccccc} -I_{3\times3}-\frac{\Delta_{t}}{2}\Skew{\omega_{k}^{b}} & & & & H(\theta_{k})^{-1}\Delta_{t}\\ -R_{k}\Skew{-a_{k}^{b}}H(\theta_{k})\frac{\Delta_{t}}{2}^{2} & I_{3\times3} & I_{3\times3}\Delta_{t} & R_{k}\frac{\Delta_{t}}{2}^{2}\\ -R_{k}\Skew{-a_{k}^{b}}H(\theta_{k})\Delta_{t} & & I_{3\times3} & R_{k}\Delta_{t}\\ - & & & I_{3\times3}\\ - & & & & I_{3\times3} +I_{3\times3}-\frac{\Delta_{t}}{2}\Skew{\omega_{k}^{b}} & 0_{3\times3} & 0_{3\times3} & 0_{3\times3} & H(\theta_{k})^{-1}\Delta_{t}\\ +R_{k}\Skew{-a_{k}^{b}}H(\theta_{k})\frac{\Delta_{t}}{2}^{2} & I_{3\times3} & I_{3\times3}\Delta_{t} & R_{k}\frac{\Delta_{t}}{2}^{2} & 0_{3\times3}\\ +R_{k}\Skew{-a_{k}^{b}}H(\theta_{k})\Delta_{t} & 0_{3\times3} & I_{3\times3} & R_{k}\Delta_{t} & 0_{3\times3}\\ +0_{3\times3} & 0_{3\times3} & 0_{3\times3} & I_{3\times3} & 0_{3\times3}\\ +0_{3\times3} & 0_{3\times3} & 0_{3\times3} & 0_{3\times3} & I_{3\times3} \end{array}\right] \] \end_inset +\end_layout + +\begin_layout Standard +Similarly for +\begin_inset Formula $Q_{k},$ +\end_inset + +we get +\end_layout + +\begin_layout Standard +\begin_inset Formula +\[ +Q_{k}=\left[\begin{array}{ccccccc} +\Sigma^{\omega}\\ + & \Sigma^{a}\\ + & & \Sigma^{b^{a}}\\ + & & & \Sigma^{b^{\omega}}\\ + & & & & \Sigma^{int}\\ + & & & & & \Sigma^{init_{11}} & \Sigma^{init_{12}}\\ + & & & & & \Sigma^{init_{21}} & \Sigma^{init_{22}} +\end{array}\right] +\] + +\end_inset + + +\end_layout + +\begin_layout Standard +and for +\begin_inset Formula $G_{k}$ +\end_inset + + we get +\end_layout + +\begin_layout Standard +\begin_inset Formula +\[ +G_{k}=\left[\begin{array}{ccccccc} +\deriv{\theta}{\epsilon^{\omega}} & \deriv{\theta}{\epsilon^{a}} & \deriv{\theta}{\epsilon^{b^{a}}} & \deriv{\theta}{\epsilon^{b^{\omega}}} & \deriv{\theta}{\epsilon^{int}} & \deriv{\theta}{\epsilon_{init}^{b^{a}}} & \deriv{\theta}{\epsilon_{init}^{b^{\omega}}}\\ +\deriv p{\epsilon^{\omega}} & \deriv p{\epsilon^{a}} & \deriv p{\epsilon^{b^{a}}} & \deriv p{\epsilon^{b^{\omega}}} & \deriv p{\epsilon^{int}} & \deriv p{\epsilon_{init}^{b^{a}}} & \deriv p{\epsilon_{init}^{b^{\omega}}}\\ +\deriv v{\epsilon^{\omega}} & \deriv v{\epsilon^{a}} & \deriv v{\epsilon^{b^{a}}} & \deriv v{\epsilon^{b^{\omega}}} & \deriv v{\epsilon^{int}} & \deriv v{\epsilon_{init}^{b^{a}}} & \deriv v{\epsilon_{init}^{b^{\omega}}}\\ +\deriv{b^{a}}{\epsilon^{\omega}} & \deriv{b^{a}}{\epsilon^{a}} & \deriv{b^{a}}{\epsilon^{b^{a}}} & \deriv{b^{a}}{\epsilon^{b^{\omega}}} & \deriv{b^{a}}{\epsilon^{int}} & \deriv{b^{a}}{\epsilon_{init}^{b^{a}}} & \deriv{b^{a}}{\epsilon_{init}^{b^{\omega}}}\\ +\deriv{b^{\omega}}{\epsilon^{\omega}} & \deriv{b^{\omega}}{\epsilon^{a}} & \deriv{b^{\omega}}{\epsilon^{b^{a}}} & \deriv{b^{\omega}}{\epsilon^{b^{\omega}}} & \deriv{b^{\omega}}{\epsilon^{int}} & \deriv{b^{\omega}}{\epsilon_{init}^{b^{a}}} & \deriv{b^{\omega}}{\epsilon_{init}^{b^{\omega}}} +\end{array}\right]=\left[\begin{array}{ccccccc} +\deriv{\theta}{\epsilon^{\omega}} & 0 & 0 & 0 & 0 & 0 & \deriv{\theta}{\eta_{init}^{b^{\omega}}}\\ +0 & \deriv p{\epsilon^{a}} & 0 & 0 & \deriv p{\epsilon^{int}} & \deriv p{\eta_{init}^{b^{a}}} & 0\\ +0 & \deriv v{\epsilon^{a}} & 0 & 0 & 0 & \deriv v{\eta_{init}^{b^{a}}} & 0\\ +0 & 0 & I_{3\times3} & 0 & 0 & 0 & 0\\ +0 & 0 & 0 & I_{3\times3} & 0 & 0 & 0 +\end{array}\right] +\] + +\end_inset + + +\end_layout + +\begin_layout Standard +We can perform the block-wise computation of +\begin_inset Formula $G_{k}Q_{k}G_{k}^{T}$ +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Formula +\[ +G_{k}Q_{k}G_{k}^{T}=\left[\begin{array}{ccccccc} +\deriv{\theta}{\epsilon^{\omega}} & 0 & 0 & 0 & 0 & 0 & \deriv{\theta}{\eta_{init}^{b^{\omega}}}\\ +0 & \deriv p{\epsilon^{a}} & 0 & 0 & \deriv p{\epsilon^{int}} & \deriv p{\eta_{init}^{b^{a}}} & 0\\ +0 & \deriv v{\epsilon^{a}} & 0 & 0 & 0 & \deriv v{\eta_{init}^{b^{a}}} & 0\\ +0 & 0 & I_{3\times3} & 0 & 0 & 0 & 0\\ +0 & 0 & 0 & I_{3\times3} & 0 & 0 & 0 +\end{array}\right]\left[\begin{array}{ccccccc} +\Sigma^{\omega}\\ + & \Sigma^{a}\\ + & & \Sigma^{b^{a}}\\ + & & & \Sigma^{b^{\omega}}\\ + & & & & \Sigma^{int}\\ + & & & & & \Sigma^{init_{11}} & \Sigma^{init_{12}}\\ + & & & & & \Sigma^{init_{21}} & \Sigma^{init_{22}} +\end{array}\right]G_{k}^{T} +\] + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Formula +\[ +G_{k}Q_{k}G_{k}^{T}=\left[\begin{array}{ccccccc} +\deriv{\theta}{\epsilon^{\omega}}\Sigma^{\omega} & 0 & 0 & 0 & 0 & \deriv{\theta}{\eta_{init}^{b^{\omega}}}\Sigma^{init_{21}} & \deriv{\theta}{\eta_{init}^{b^{\omega}}}\Sigma^{init_{22}}\\ +0 & \deriv p{\epsilon^{a}}\Sigma^{a} & 0 & 0 & \deriv p{\epsilon^{int}}\Sigma^{int} & \deriv p{\eta_{init}^{b^{a}}}\Sigma^{init_{11}} & \deriv p{\eta_{init}^{b^{a}}}\Sigma^{init_{12}}\\ +0 & \deriv v{\epsilon^{a}}\Sigma^{a} & 0 & 0 & 0 & \deriv v{\eta_{init}^{b^{a}}}\Sigma^{init_{11}} & \deriv v{\eta_{init}^{b^{a}}}\Sigma^{init_{12}}\\ +0 & 0 & \Sigma^{b^{a}} & 0 & 0 & 0 & 0\\ +0 & 0 & 0 & \Sigma^{b^{\omega}} & 0 & 0 & 0 +\end{array}\right]G_{k}^{T} +\] + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Formula +\begin{multline*} +G_{k}Q_{k}G_{k}^{T}=\left[\begin{array}{ccccccc} +\deriv{\theta}{\epsilon^{\omega}}\Sigma^{\omega} & 0 & 0 & 0 & 0 & \deriv{\theta}{\eta_{init}^{b^{\omega}}}\Sigma^{init_{21}} & \deriv{\theta}{\eta_{init}^{b^{\omega}}}\Sigma^{init_{22}}\\ +0 & \deriv p{\epsilon^{a}}\Sigma^{a} & 0 & 0 & \deriv p{\epsilon^{int}}\Sigma^{int} & \deriv p{\eta_{init}^{b^{a}}}\Sigma^{init_{11}} & \deriv p{\eta_{init}^{b^{a}}}\Sigma^{init_{12}}\\ +0 & \deriv v{\epsilon^{a}}\Sigma^{a} & 0 & 0 & 0 & \deriv v{\eta_{init}^{b^{a}}}\Sigma^{init_{11}} & \deriv v{\eta_{init}^{b^{a}}}\Sigma^{init_{12}}\\ +0 & 0 & \Sigma^{b^{a}} & 0 & 0 & 0 & 0\\ +0 & 0 & 0 & \Sigma^{b^{\omega}} & 0 & 0 & 0 +\end{array}\right]\\ +\left[\begin{array}{ccccc} +\deriv{\theta}{\epsilon^{\omega}} & 0 & 0 & 0 & 0\\ +0 & \deriv p{\epsilon^{a}} & \deriv v{\epsilon^{a}} & 0 & 0\\ +0 & 0 & 0 & I_{3\times3} & 0\\ +0 & 0 & 0 & 0 & I_{3\times3}\\ +0 & \deriv p{\epsilon^{int}} & 0 & 0 & 0\\ +0 & \deriv p{\eta_{init}^{b^{a}}} & \deriv v{\eta_{init}^{b^{a}}} & 0 & 0\\ +\deriv{\theta}{\eta_{init}^{b^{\omega}}} & 0 & 0 & 0 & 0 +\end{array}\right] +\end{multline*} + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Formula +\begin{multline*} +=\\ +\left[\begin{array}{ccccc} +\deriv{\theta}{\epsilon^{\omega}}\Sigma^{\omega}\deriv{\theta}{\epsilon^{\omega}}+\deriv{\theta}{\eta_{init}^{b^{\omega}}}\Sigma^{init_{22}}\deriv{\theta}{\eta_{init}^{b^{\omega}}} & \deriv{\theta}{\eta_{init}^{b^{\omega}}}\Sigma^{init_{21}}\deriv p{\eta_{init}^{b^{a}}} & \deriv{\theta}{\eta_{init}^{b^{\omega}}}\Sigma^{init_{21}}\deriv v{\eta_{init}^{b^{a}}} & 0 & 0\\ +\deriv p{\eta_{init}^{b^{a}}}\Sigma^{init_{12}}\deriv{\theta}{\eta_{init}^{b^{\omega}}} & \deriv p{\epsilon^{a}}\Sigma^{a}\deriv p{\epsilon^{a}}+\deriv p{\epsilon^{int}}\Sigma^{int}\deriv p{\epsilon^{int}}\\ + & +\deriv p{\eta_{init}^{b^{a}}}\Sigma^{init_{11}}\deriv p{\eta_{init}^{b^{a}}} & \deriv p{\epsilon^{a}}\Sigma^{a}\deriv v{\epsilon^{a}}+\deriv p{\eta_{init}^{b^{a}}}\Sigma^{init_{11}}\deriv v{\eta_{init}^{b^{a}}} & 0 & 0\\ +\deriv v{\eta_{init}^{b^{a}}}\Sigma^{init_{12}}\deriv{\theta}{\eta_{init}^{b^{\omega}}} & \deriv v{\epsilon^{a}}\Sigma^{a}\deriv p{\epsilon^{a}}+\deriv v{\eta_{init}^{b^{a}}}\Sigma^{init_{11}}\deriv p{\eta_{init}^{b^{a}}} & \deriv v{\epsilon^{a}}\Sigma^{a}\deriv v{\epsilon^{a}}+\deriv v{\eta_{init}^{b^{a}}}\Sigma^{init_{11}}\deriv v{\eta_{init}^{b^{a}}} & 0 & 0\\ +0 & 0 & 0 & \Sigma^{b^{a}} & 0\\ +0 & 0 & 0 & 0 & \Sigma^{b^{\omega}} +\end{array}\right] +\end{multline*} + +\end_inset + + +\end_layout + +\begin_layout Standard +which we can break into 3 matrices for clarity, representing the main diagonal + and off-diagonal elements +\end_layout + +\begin_layout Standard +\begin_inset Formula +\begin{multline*} +=\\ +\left[\begin{array}{ccccc} +\deriv{\theta}{\epsilon^{\omega}}\Sigma^{\omega}\deriv{\theta}{\epsilon^{\omega}} & 0 & 0 & 0 & 0\\ +0 & \deriv p{\epsilon^{a}}\Sigma^{a}\deriv p{\epsilon^{a}} & 0 & 0 & 0\\ +0 & 0 & \deriv v{\epsilon^{a}}\Sigma^{a}\deriv v{\epsilon^{a}} & 0 & 0\\ +0 & 0 & 0 & \Sigma^{b^{a}} & 0\\ +0 & 0 & 0 & 0 & \Sigma^{b^{\omega}} +\end{array}\right]+\\ +\left[\begin{array}{ccccc} +\deriv{\theta}{\eta_{init}^{b^{\omega}}}\Sigma^{init_{22}}\deriv{\theta}{\eta_{init}^{b^{\omega}}} & 0 & 0 & 0 & 0\\ +0 & \deriv p{\epsilon^{int}}\Sigma^{int}\deriv p{\epsilon^{int}}+\deriv p{\eta_{init}^{b^{a}}}\Sigma^{init_{11}}\deriv p{\eta_{init}^{b^{a}}} & 0 & 0 & 0\\ +0 & 0 & \deriv v{\eta_{init}^{b^{a}}}\Sigma^{init_{11}}\deriv v{\eta_{init}^{b^{a}}} & 0 & 0\\ +0 & 0 & 0 & 0 & 0\\ +0 & 0 & 0 & 0 & 0 +\end{array}\right]+\\ +\left[\begin{array}{ccccc} +0 & \deriv{\theta}{\eta_{init}^{b^{\omega}}}\Sigma^{init_{21}}\deriv p{\eta_{init}^{b^{a}}} & \deriv{\theta}{\eta_{init}^{b^{\omega}}}\Sigma^{init_{21}}\deriv v{\eta_{init}^{b^{a}}} & 0 & 0\\ +\deriv p{\eta_{init}^{b^{a}}}\Sigma^{init_{12}}\deriv{\theta}{\eta_{init}^{b^{\omega}}} & 0 & \deriv p{\epsilon^{a}}\Sigma^{a}\deriv v{\epsilon^{a}}+\deriv p{\eta_{init}^{b^{a}}}\Sigma^{init_{11}}\deriv v{\eta_{init}^{b^{a}}} & 0 & 0\\ +\deriv v{\eta_{init}^{b^{a}}}\Sigma^{init_{12}}\deriv{\theta}{\eta_{init}^{b^{\omega}}} & \deriv v{\epsilon^{a}}\Sigma^{a}\deriv p{\epsilon^{a}}+\deriv v{\eta_{init}^{b^{a}}}\Sigma^{init_{11}}\deriv p{\eta_{init}^{b^{a}}} & 0 & 0 & 0\\ +0 & 0 & 0 & 0 & 0\\ +0 & 0 & 0 & 0 & 0 +\end{array}\right] +\end{multline*} + +\end_inset + + \end_layout \begin_layout Standard \begin_inset CommandInset bibtex LatexCommand bibtex +btprint "btPrintCited" bibfiles "refs" options "plain" diff --git a/doc/ImuFactor.pdf b/doc/ImuFactor.pdf index 933c71a749610b513627409ff903042378fbd989..041d8bf1a2d3e93d115dcfee3a9b001f5a6ea52d 100644 GIT binary patch delta 150562 zcmZs?Q+F<06lNLQwr$(CZQJ%6+qP}nwoYe1B~dyMA??29$meAeYL zeAhKXA{huXQ3i1bFcpA4URV~487}PZk=7*{!_I!$qny9{d=MtT)&K)hy(YM&Bvt$6 zZVQKzk@5cF?pJ>@KX}TEQmb+zRPp~=b1Whbp zr@zKe!4p0_u(ITJ#hAth1|gL_?iVq~oJjfcV-<)kDyNyQYel8bv7~eV9~o%0o+53- z8X@~kI=|@V0~>r$X-y&7(okD@QTlXX!>6?XcxJ8HcLR+iB16q3TFC9!M%ol<+- z+FnxrWYbMUmrnT+#xEps@Du`I3Q!hSu9P7SYCxa1uH)7udcZ=1(jL{INjNJW0(K!{ zPBDWAFlL`u5V%LjSSHSf9GNnCRpBYP;zhYyK^^_FUnypEY5FZb?#&BlW=$U(xg|tjzedx z9l+Fk^+P?#kTU5}QiAVDewgBzRr&t;XLEQ-{v^RRPg4IAfx8w3H3u(V-sI?*MY?xa ztE~7AvGd-qXFg8PI)y@7tuCeVq-cT=ePfQb{>k>HctLIx9#`$Dad%Mc+$kF)-03(A zfiN&c6;(j}xhsuvJyFt~Hsz=DWQcOJ7tmncUCZ%B54dMF zpz8o3I{Ze&_xK^@M;=fCfr?}G2;3+v}NCF)MT;0y+v3WheD4nL}@A1WB*#FN`@a7-c$?7>8KbRtD5 z_xazBPf8gA!}=$7BI6dBL1`GeoauW+3f%>cBFNWdftM(W;86YG(WO>22_R7HD?bXg z&mtoyLEoWTF1HlnSO)Q3yec$f!>qS9(wQhG;1Hccx2w~s+AuJHBZ`&iPxa+Ua?D=o zbdaQkugoC{vf{5^5qBvKxVpneR?;O&SS$d5!M~I{Lp&Wr%QN#wTfB8+TOY^5rHWO?J1pm~zvy_!$e`?ny)c!ktak{lP z_R`53BlUm=j|YQq9^m5)^|`=Cf`GEi{5j1$_ME(@HRV|%pqp~VTz47SP$Ua+n6Du9`P}%;+Q!x?>3LyBS83|7ep0(G+3H*Xe zAFILu!o#9vJ7zk1#RQC~rjcSZFTs4m!-~8UWcBeZ@oFT~4zrw!YRL2A^~8HY1ERoS z9#&qJ)2TrZou8NJqdmB_Y;QgMLOJ<$jWEoc^EC6tYaXSst4~EG<@xI$rSPiNq&@|$KQ`VW-NumI4J4qG${XHC#6BglzLEvVrS>g`R zJA|AHm%mX^r3n)3!&_m)|KnZDvR@#&Lof2F>aV2=?Fy&M0N5HR3xM1?xk^!c$Hnc}pQeOr~zlJhv&LZCAve&=OZX*OlpRY@{Lx;|^?5qPLLD|i+CzO3XD z5hF&&26RJvw;l;2hy8wxSQ9F_WUiDi#{+T9b=6W0Ot_Nw9k^jzOd05p(nsnIj-)N~ zQ!xSZ)01Mt@K^mxJ`^k=oKP*aiiv^wDSn1G&gY%p0^Q>(;H$VwzPTrX`}d^8vG2$d z$gYruXEzp0RCIvX(%9+@4W^Xgw;Kg^3;jM!04bD8IF*X49CXk#ghfvj>{E?&V;C`f z(b8xG&HYnJaXt!61Q|<%)t0i7VW&hTl*C2&#z(~>+$qE6r!Kc+(55udW!cAy{IYbA z-m<#*)%?Yq*Mf}v(mcj3-7mB}#%@cw@INRdTJ-NY-IG)#`weFWcA`4hU9#e(1T=Vz zfL9Qwa90m3DdGutCghKCED3V+dbZIwlu~IXBEBeMo`^j=fV)5Dp}3~)dC|@j6~e4! zT(fn;wJoo)Ay77(VaYUa{CkvXh^I1-IF5A2&(R{*$j@*u_=Qi6X9`AX&I$ZzOiyC` zp4eFcY2oAcaZG0)l$_|A9ZKe3GAtJ&K;f=hgpgYIqrPfdk-xYcPA_z6hzoqhDMJ&< zgoz8fIzA)OOep@U@Ji{$*S*FBJ2|0R!569Ey7UCb8Swxd{Peo4F;(*@cY*=pVu=1{ z{>no@`bj{-rD@E0&)BZ0uSEe{sf+)SQpm`yUt0mxK99>Fphz;^ zBY%qsq&A-Q0yNlmn)TBIGcdA`FCRbK-O-VieIZ$>8@1snMqwpQK?uP;<=6@EzP)0v zT@Zfnuy~+As1iP=r*xtOg|Kn9hq+9z6)3$?d2t^x7L7FBY_gs0HBmOX!{+mFA_UF^ z7kD_U26T#4y;FPj?&VE1>59w`Py(f@VBvS?Xc)QUH8V_4gl2yxRzeIV5)&MK$0~{B z@r9SNFM?TV08?33HcXGn2q^)ReTAV@Zkr~js{p6+&HG2&u%AipTs?aiRFb2a@b1 zs46#)N%)iU52?~1DV_$qcqFrtuF_Ww@b6yQ2Zq6!tL4P~6ekgGT#CE>`2ZT|{y2WbE>oFIn|IGP_j7O4?UONZO|JuVe$1RPdJ!ln)HT(_T73U2vhTKc9oPjprKDcP zHL|={)A017Ox@+M!wu-u=AqfEuWTh#(O@W{v7qb0ll>~VhH7Q8ac1S1sLq|(jHrOh zqWWr&e~IzuSS`zC1ueG~7-_&zV8x+=DWTBjyNJ39@RORBuh^uNvAk~m8}lhCRj9v} zL9vG|)<%<$EAIMNe1)?PmtzO0DQ5I!d#k^^vvT}km%aTG*pYa-#d$^G0?}q~v{AN7 zqRB$Vv{$~%29-mn^N#SZL0nSq7+AZtm~3kLkC$e3r1`w_c8d z70FenNHLP7oL*rzx54sgsqRjAC{wMQv*AE)HNt|VSHu6u{`J~frIG_UhVpCkS588D zdlW+Sm{?Y{KmQf-*-ZPa?k_89w$Je>)cfNrm4!y~u;PSIQ>x>Tj>OkxZ5$#c&qv+9 zl8b;L)N` zgmoW+Nq%rZKJ20Jxx*yRLt_VFRyW;mZNx|4Zj056TUMRn{A2)-&fiP?cpS-B3D@z@ zi^{sTu&Dkzf#^Ss=UZp8n5lPti$=`DE&_6GbDtZ!JCj##YdzuH;PnlV1g&RQ+bL%N{blPh5TeD+@^^q_Q|WQjswDS;S(%J&=qi;suBgrE+RA#xB2!w?X` zL9{#E2MKGW=^TvM1J=?95zf3H?o5Rx;P!+34l@5B7=QsV;z8}bK`W!9hj~K zKZ6R$rn%PRi(#_)I+0-n`uz!o|0O29q|<5J0SaTFdo&{st_b*)U~eB_S?5G7BTCho zCy?Eo9_@4-i2FiS3;w@9e_dxsm@;WNB!+S_m1xpza{nbz8NoybFekCh!YYXABy;8t zZ5ctaT>)m;t^ShjNoau7#50Pk=;=(C%8jM_U>nNBtgG;)@pY>;HgL?jHLlphO*z?0 z+5%hdBjgTV&kQN#As&i*lATd+Ic#aX`pXFjfh=~k68ElHg47ZmUDem->~_^RiADl% z64!9dl@aV##$aomVX#7j2l!E$+Gg?1xw4|F9s{x--!mb#orv0{Vntn;LZXbvu^ot6 zTDBF;0=q2Wb9#KeKn9Syj3y#7fIZO$7h>8@qF})qCH37q_cR&Mhxg$Xd(}*l*u9%= zna#&(&6Y>Vw$-2OH`4`tPp5Oo|Jg1-(SbBFTLAwBg~O~v#JWlBw?~emMoANVURulv z69&AV@MubR-Q+1DIT@;*1f0PX&yuph{S*ZU5*uCk#9w zDZ2F^Q;Y0_u-g**@1XfR8ZOD=?`S+X&I9O5ebweUd5N?=2hqywM7EBVR#xR(_VVh) zXV3Na#PBg}WtcrlSi@Ym74t%N-uPDtxbBOsiDlNT@NbIN6*qYATftAB>tw~^YTkH$ zqa)yuEN`>%3Uyk<$+S9oN^gSBsG{;oCtcZ2Og~(R!th{0%H~7|-UPatnS$c<(f|sQ zb3b)8X^YGlm*Y=uI1lue-akINZ`J4eSIek(cDybkzqN&3JyWz_^IZ?4ClDgG>h_4+F&yGip-dL*rDqFoa5@b|!E{nSUlCr_dgfk(o@*h^FVNnCMQgGnqo$ zZB$JqnE=Qo7OLdykC_iaTr{M$l>mCg^_VQ+Yy0vL^LHl9_7qd0@=e$CRHR}FEmSxW zKEr6N`f*}p+zPe&H{zpo?2VD4?Khn#V0mVc360L~r9WOV=!=2lNYaZXbQRP6O$m+7(gqlEaeh$ z#ECNYzKWrc_+;U1C;Cbw&^7Jl*0ScB!Z!(|a-dxi8ld7|_er^(`RKE8RnNlJ3xRP9;Y$3+)&EU8k) zy<;Wd?lXJw)9p_xsUwER_;_&;jlgl-{_SABz3&D89gvD9t2mkTTr%R$lX#c1`eKgQfjNb8Y~b6TqmrH77{kPuke3o2T5)0?42mE>3Oh9R4>oo755&7OAN*mnL$?AuToI67AGbxOiSElg~YtG!wQf9&W=Tt9_Wh_1; z>3J}_%`Y3uuU~J#N&%9^$Q?6{SZxS;$qExk4N7i$`0P;CT759WuX0X(2?O zA2D0qWX2(`B19C?f{%%h9%9D6R@+~(x`rb)igwG^=jl5Tz~c#rTJ&BTbhL-9(D|)@ zV?92Q1)Wf5N&MM5aEP#2b|=G{BqvD($K7A=^W|0Hgat#&IpHH4!F-z@e-FOSI#&Ve zVT9X)XOVnmdIx#SC%q8#f~Rx`N`*x3?c%0b0$3e9bxKycH8JFZGeiN`M~}pD$nlS~ z!WgpfwcC1-YesXpuvQ5@kYfmb@YUE_kc%MUz*l-F@zG**qXFOO{aD3=jht*6>=kvY z|0b{e9Aj`Fup>HyybK5ubzGDWlBl3Tf>lw#IK341c-LmOqtxjdS#l~+2H<-1!~{r>{lF%BoPZoNdR_yJ z|9R(s(fr8c7i`*|Aw_m+w0B?Yy8M_QK|azO{toTu)|rb7uwP{uL=vW0ubG{RZXU|4 zDfah&91jTBKneYCN=gaF#s^{HN;&AH2JGnSrfjvN2kaRZ^((8wj^T^3cw23np(yfZ zaqwo%aydlQoao@m9%>ZdbPn{N0qujMQ8{xybl${>%V_QI@9XtH9=u&`FbU=n$MXXU{<)wDa)mIri2F(83qI^)Pp>{2MS>A9!Z? z{n#ylH+^*E0#17M?cWAKrKnPU0JzpiwNa04N{{siLX*!$fAgrmUq3hJXG1FsacFFz@eZ}D@F42%h!jaXfD^^gX15oov@i9gQi^0Q@Jte zN~P6W1_k_|@6=p{K-6=}DXvF42Ku=X&T-=M_il{%Ktbpjexs?Hh zYqeYjp2l_>dcqm*H)}yUfPGIaRXIvKuA>-o`Qb*rS?VJKUzQZyL3z%ZC$aRoa59qu zcrsP>S7FbJNitLXQW>thc$aF`Ow5f+hJdtw3H-7iJp^dOksT&zfnRY0chN3c7>MO^ zUdC4d$-iM!-s2AK)ih5HGCLV$&}Kh{oNO3q5_FWqV@2Yy(M*dsEm#t~p@XGkq0Oh)P_QKowRMsv?ytkkTQVkRZoK^Sj5Y+9$y} z&GP1~ew|TUgMVe~v*hETsk}AEXh8 zO$M?hSKWYw6z?N@B?npZ_o5xHIz~eQi%|rh14bKQ7))*_Xupk~C{55EMD2sYmbV~^ zAQ$S~9>+~XlCBLhOMuFRx@W)|tK@D`UW5!K7$oPgTd5LMhovgU7NiG19HydFac^Ia zS1MVg`_Q2WNY&3;0l34d(Az1OgINQyYK9uiUrvM%*n1gkIB{EFc@1yyIJ{se9xa{k zCOmfeWC)>FEVlRxbo;1RPnOx=s3Vtzrf^}h4wVK%imB6@i@uZ&|7f|JDAHP#CD7re z$On*{&ZdlWO*`S}Ss2B(ux!`*{I+hIMA=+v)5OC96pKmR)PFwCi{KniRzppVm7U-p zOhAC*Y15H`a#^$%F^)B{a5sjy(;;j=HN>_(O%x{AE5{>;1I=Kams~;p1~r%(_$JiA z9E0fYhku{SA8H482X+r;CQ2iMV`$Xk_CsNxHx$NZ`O#U88<%=>QKRbVK1}6IxFQpD zWWELgA4XD6Vg_*Bup&%q$)k--J6oZMfq(~wb$@Y65RzgnE=$r;p~f6X2ge`xkSc7a zKOph3N*2I;AW)%j&AU6jKJu8a_eZiw62VS{+lxEHD3>OC9{-N!_8j^pXq?5q!@9_T zsOY`PzSlXa6Kr|m$n=H~%o!LOW3IK^3n$tEf%#;n@Q4fOLiDLFsd-qkxiW0Q4su(Y zFQ+2vS5u&g@K-0b&)YU}2Ce_%Uw|4}&~@gR77Ur6-JKlu-4tTx@xS`@cuW)8(?js&@+bKXxO(H1a? zra0eVPJ`(9-X2%c2#h05aJ<$WtN*|S5CR=Vcxo8lp+!dL6_=;h|48PQ)Q8?quXBk? z(~+3g;zwGh-&|2-YP4i6lC=Tpx|Avc%Agdy3q0)YA8Lvou!W>hu}dDb!NhB;lrhL+ zADzbtAPhVIvrKGqeUYtfIbW7uR#e@ z=8K34K#G%jzT2|dKgi%p`b0C!RK(Dvk42DbKc57XF7F=(H%#l_xn09u&EQS}7@Sl)k+!B!iWxG^ZRXqkTj^a!Ap z`B}vCm}d6jOstHCmJ@{)*_wE7;1NwhF6fkQE78UgJgGQ>){0>OsOpH0XV^7{VXRC zo%0@>d+5HBkr4JfeYV3Ke3Hu!w_2YIH0hXAx<~b5j7xg-<09-{vFL+mMeAt-iilQh zZwCmgPt5YS#@56ImaCMVl5llAfs*A+46#_Ng2NDKbMdS7n;24~GCBBwp>%iS76gZuvC(Q z6}F3&RztWo8z@Y{LK$N7ol~7U_;B=0SuBKZRrnbndBnLv(3Y-YQcK)ZO($`A%DgLQ zJD*Zb1%PrYSBC-D(GwGZY2r_4lQ_{X+kENT9g6!>Fx@w|UY(Cw^n+9H-c9>qOJwAl zvmpXE9SEfSLvTI{x7QiLWX$_a-_U`G1;uvG;=WXh^f~iBE}>`dna8M;3ApY;7rS|j z&D;d@ZsRcRoX#D#l(CS^eKwUkT+@!pv^eTMf$EOq7v`N$vVBJY@)J%)fhEnoofOZX z{6e54&-;X#s9QSFArJ6X|Eq9TA|(_g)2+eB#)ZxwNIdKC{(AvzJ1)--2vM3)lisrG z=SD4Bka6aySrXLtKhZL;NK{aQHANsf(3&7)(AT5ETuv%Qob+cknxeO)O-2aj!Ddl| zY{f3p5ciGGR%;C*h{#NU;EfTkg1>*}sBm&rHvod% zZt?B;sE5`WW0Xz|5n^`r1}&8W=>RQ=_I3P?T|u~NNH5ytB21)WrV>6(N`2AUMsbEY zYom=FTVii&d*~aqpJuH!PxU0VbTByco~nLXOQ)LSlrZ>$)M!9AURAMv4 zP{uwaATMb4mJkT0aUQ|&NtNIeNdL}F$fN3@Pnvp}eRegvfP85KVz zqgD**lsHX_x7qhBW{nfrMZb?`i7gP^_7Yzv4AC^2{ysJQaN`}gnl3U+lzOioh7c-=Rf(or(ke}En#>pEWGqI74pYLB%GhlfEvSSj|2L1EJGcP3#0Sa44N&POADVly)@|?7X69ol8o)H)WsA7_08o}9rZ2u zzW~AX`-PH`{kwY|G4nQ>cI}k4N6rjEzel~&Z_nlpkw&eG<-Xgo_FZ)K{$R)yG9O+{ zijU*XIUdhA{q`Kj(71_f+K>hUhJUd`I$6cCKlRfs}F-(P8!Fnf^!bf=o zk8g8u`kcpcJ7t3+pRrY@So3fW^_+$01JF3%aeE4>mjc-08QIu<^C-+ksY_SuC;{_KwyxTZb^T+_C72D$Y$h%F?Yh1n{6Yg zbuyVBF&J{wm}c4%;!nLnon1$+4hy4n>oC9}Ihh@;GS0U$CbzTCog9rb5vEo)f;KX8 z#OvQ{Wt+o**&Rb!Hl|3$eE?1a0XzwpLf8%cWzVJo&0GJgS=qj>%=QCuX(f{#l2Mbt zsa3(@)}xB%<8|dTMP(GBR~wzH!AEtpd)5I1+Z#-VD4;U zloJ}w{+XOD4rsuBeGH~^D<(_kl7^c~#;;ed#>OHuMQNsJ62l!bou5@Yymm^0&Xi~* zs}fL|r|6r(gWYGY2AFZ)Hoc=B&KYG>N?GI3*Wft?orQmj@-{8m11ocQGUO%3aT|1#LVUZF~2^r=#0Dv9mQ{12m2VV$? zv=*afkY&dQQp=zoS1(5j?Nl8aBppn_p}eF6NbjT7#;W#zQ8o6hoenTG5Kw~>M@7~d zD-J4(rx&U!qzT`DnL9CT@wJI1GeBKL0GOpN>n?{_zGrb3*; zMmSz3;i5B%9f1FYW(w2>9!CZ;z*8je8;@7BWr~g0B4QzI<1mA~7n)EnACXi?_`S(4 zYE4{hy!^Kd@H}H&@EP?4iBOD?7b?usaio2acO>`b&@Is@nXF+)b^NN9fyzLt_9HL^7h z8Os`xEE#0C(>uo0ayb0K-*AbEq;ljq4CLrpZpuJQ^&T3UUD zEQ8W300;?K#5HqLe0B%4#yA5`7OLF;Y3u3=F7C zyb0*1FNNQlOYdVkSe z;$oB9I7Iw%K4f=#U1gS@Ol$c@X>V}4F?Twjt^?z(GB#em6{!(mRlFn++5Q6}%duQ( z_gBpjSiX7Kysf&R(-yNleB761A+@~7cGmtRM_p-+J=YEOIgRYlG3*FYHCYryrMh_v zfKx3pMCQg#(p#WC4y>u}k)mpl=?)BmrJ1PdVpnamC+$sa!kpfO)tSOR&s}5=sUAT( zM>Mj;BRyMi=aCbfzUrF2rq;gvF4pCg6nlcFI=_l~C%ZO=g4yhm;h-|j?Um3ihNx?N zSmYnXmXd4q9%&V#Hh1R%&iWa~x zno2(4<|M`V#B44i$w@5*H$xeW6_ozU=2VxEE>)eb4`5)1r_K83ExY!h|GCLIU9*(; zRYE&P)A8*B-|HG8uCq=w2=NP=7i3#K&J?lPIHJlM7|{k;`E`{2Px0N9cS_g;-b0o7 z(d-bo7NkEp)bzy}HD?*IaAub4Sbx_$5lEna^ntP2>YD;<$6XRf#Rl})y9$c$5f_WC z%5!%5i9@sOISTYDjv#9-)V;#rUNdg@oKbN2MXbHE2s72a8)fKfU^Q>ccl7QNVTD2( z9VZ{K(ED~&-?Kr0(e3GTATW#o^qT=$pA~EU${|w^`Wr9Zy7X>v*FM1qONIXxc4iUc zKUpemm(P`wmewJ#s6WUh6h}0&|BY+~T&_#9ndd*?yp;5RtaxCyvDPFvuat~3M~cAH zsJNxdnh3HjVmWYR2D{f5-h^%4wWr$sG(MMHCGxm{QWn&IRCntlwvk@~5I_1BRYH76 zgOjHF$bU0;t~nf1HdeSPPMTzrjidHog)=g9H3*;-np*A(cOB@DNndi(dR&&_;O`#s z8iGiK-vLa2gWdwx9AkRzS0NE#4z*Al-qF5ioz_{5jf9d^`u&P)#Y5 z&tQ!gv3o81Wd9+g zGr?XSNT;Lou>A#lg-ipVFXw{suOTQ1T#Gin2nye>XMM^~e}NJUi#kDVFbwNK*LNka z7-bx4emuFQ8HQf2xyc+|0R0&33%9e6?WRP8;pi{H=XBnPkLhd$g=x)?LqWN|c~JAw zD?in@VKeBMk(A9%{lb!2&3gS?+%+pfokHOHV{N%WM?8>o6kxhsX2z`{`pFR@YWFu* zk|4fbgb+Szbwlk15pUD4beKPq-u*0iQM#R@yarraJ1j&1JX#B-1ZP7=>9A$QMi9VsO>Efmg4NMFrM8D<%WowV*{l>9*ckd{8?{CRa$ zn1-lO7pc@vlwav^82PF*gP zA$rZrW3~6^jy5BU2UVpzBo^L){!K>F+g~Xq6(uTX4xp}qi*o_rH@@GbgUdohDVlV3TT6=1Y9u?&s9GJC)2t`X4-jnKcUBQdr| z3z4Dh^RJ9J*1fxey7H)%sG;KG2~7o}A|G{r>p>NsS0>PZbw-7Ph#y`Ea}va6q-8UG zy&ew$=hb2Px*58J%zd)JrHX(`B>b|Fot*k#Yz)|M?hOi*)nQ&8>;NB;Dy!ZHX9CO= zJrD}J3m&BXL-TbUvEU}sM^nT^lmk2nzkCSAGmP)6sES8ows*<AaEuZI}L^4jwD#{|{HOvHwr&bfb6mpLIh14FH5a#BsJE@kMI# zzAu_xO0!6B@@Q7DwpWPC_VQBjNE27Ne(!k(fs-eLknd{0N=+1q1<5)!txq@xfe-X^ zeLj$Pph`rQrOPugP)eZCT#IRoQ=O#5ydTRy*c+Ul-7)n4K9rf+>*S-*&xMk#>P}Ou zIRCi-BvEyfe_Z-aw@L4gcAHWsRoPGta23F$tpKG#x zTe>A%_4tb_1GB1-WqnGc^7iqcQA}ArSNj3WPg4*^f8bb8_v(zK4d@f?9GZIhdADhs z&5=sARY!Mg(TnP~=aO1`Ih|Nrh~NAKjCL#lG&s*{y?wG6cj~%H9FS6~&_^eyQlXI& z#ZMXQU6G=Uq~Y&8k9n$^4*u$&v7W<29A>|181Q?m%9rj&AMHtzj*6kyR8ck+!a*3w zr7lW|o0_nTO-jc=k>UClkig~VxIi?B4|^9L?MSQm)G#%GXjYG)L-IT8VQ-!Ahegx@ z!kK~7NHn;MkR{YJUhDrNfwP4-ljF%dAT)!7{zxCmigdh1|96&&xhOb#?y z4!Ol;z~1r<)IZyadQr{+I%(|zc*5iSm7@JCS*z80w7ir7zKCp&3pO{g*-T(N^P$jQ zE2*99u;t=kXp5jjJn_7ZY>F44U0lUuHES=Oa!;|@NZrXhgK;Y;-#_$Q<6=P9!qZ^lCj@ttDn;A)Yd9YVkQz*I8kC{t0=k@{sW~O}^2odC{nj<&x z`G*`+K1fWSDsEk_n_@??ciK4|NVBvsHxEz_gl=dIMZpt<)t`RK!SNZE9_Wk>m($o6 zoZMBuRh3~hCvWQC|pH4`KDQ>7N3c)(PP#seclw?wlJURo?)bP&b zQCv>~v1wbRC^M8{w76e9{u4K&$v4oVnr@#S;*)VVOeLf>oC0jHP&H9A^0!=Wkg;RzHo;86s)gM-K;PG zc9xLH!gx}BeL*u5ReXUQ^^YT<4=?hed6l#TxypoNBmJ_b zQZ0;QqO2Mq1q1yg)f7z$LM@s&c!0P$0rneNCIr+(CYXO01R6ZrC;nVf#FxJ5Tb3co zQvV#N6z9)#{K~_iIR69m&>J_SYW?X{n1<-#iawTr_n`LIVuCFXI5CtieR}-2V#iMP zt(IM^TszAY$}Q%Z_!v(yF0(Mydc%c_<(90oH%A*Fsz}4&TmRO-_>s6dS!X877xAyQ zr5dF5G(yWTqh?MWO-WbixE68b7Mt$fpUudTNq5wxiw3ftU8jdiv=|h(v9<#i!yM0u zaG%UFU(dUTdu}_L*>xto2^4o60g+o8p~#^J`yk+!n+F*i{|L!XG}2&vr(_1d!oE8q z>Rli3!gSh#hI72DV~4ma+d;Ntevc~py8}#h#^sD^Vf=-+7>ycU@us*9^cBC;D*k$| zm*APW(08pV3#UmB_L5H5Z5KCMzgC)(^Rn8 zzOzcxZJ6UC(dvdi9?mf6v?2FFHT0~&daXPm&`C`8vf1USO zT^=Y2Qz%Rgrt!#fHHcCn)?KJJJ%t7pK6ovH7{hS+Ej*@QOK+ijv@7=hYTAW zhYGqt7I8B7|FB+^A2lze+sZGD3=c?>Db^p(0;z)edCXazCle2J<}jvB=yK!Va^&=cLH_|%v@z~nsgq`a6O;(g z_cf6q@8kl)gBn6|!HRIUSo$A~ z4QO=l$(J$8ji0L^6HUoiFxk|gni?w2eNWFY!lMjV0?CGW1p1gt^z>xGDxIA<_NPYF z=A=p|PW2p!kx#&SvkClyiVTFCyEC``B3?FSNo>n<>VCmDvCCOOD-HCfQc4b7f zVkcJb0==WA0XIKZWiLpc@g?+#F#ul4>bKhi*t{)^o4v>3@6RFov0OJm+~nx0B~7~E zondK(1=&y+HJ9qWRHzqoS1E@lAYmCwK~*ffPSFxHC%XAaxIjK}Pf?;gHkhDG#$dl& z`}7M<%RXNv&V=0uD?}HiH&X60_2ZF3b&zYWnIi5^TIRBPDit2Ktf2&lq;dD|tvspw zsC=o!w|;6x$1sIQL^vP7bmG+yW3$90yBYdPNpH0e2B{^S66x7H$Cu68-J}CRixkzi3YI za`lBM)BbjkJD7pFO#x@$t9u3?do^*w|?Ky_w2@ZbbZLJixa*K+IaymI@ zg*9XWiT1P-I?%cD35t$z<7L+l&GnG71ZtoXYlkPZDAHtA=G+ zZ^7<|Ql)JlYqwE9=A42u)~i#FxkUfCeD;Cd^lJ(Usj8r}ffLLR7d5s^x+G|3>YQ-~ z)o<=^%7+0$&~`js8;$krcNrgWD=>6KLK)kuxVPy*6mRA3+`o*BruFl{1cUg#wPi2- zI7oq9M4JHg=j90;5DCg5w!8R+;p2P5#5d%-w8MARxxBJ8{|q0^K6`lHn_%(>XwtzMe7pV@CA-tyy~ zF*I_*PP)z#Qzx+jYkLk{DXiWK=;bUVdT83JP_$+5fRLB zCxwExvn@4V2 z&h;0weV$q;Y?;hLsoue82iGG^##~iv`9{RUtuy&QL5_{-{{%S}rvFtR{O^*=aZ3W} zze_5kEle2p4qrn050pY-oI+up9^oJ|Dy$f3t#c=;P3w;<-WhUphCVdvtn@s}s1++q zk9kLn*Qxg@M8&EoCYxuB0G=@34biMvXQphhZb0tX~)Kly% zol1sjI9oDGWaa;2>m9oTZGdjg*tTt(opfy5wyjQbCmq|i?R0G0w$riQN#>b3>&&b( z>-`7yaqp_VuUc3qzDEH^1d>smSUb7$q+oT(@+l)A@RwRQ6nCuwt=*BaI^kV!&D}pf zJ0YIpG*-H_yj`?h&9vdU&$Xec(m^9iDlMLi^qe@o;#>u+1TkrNXmpSZdLMUwU#wY_ zOX*%s26`!PKIVCD|NQmaR?Qzi@Ta^QXtzb5&*<#K5pkl1vV2l}z1v^WHXw%aRFZrz zrGw}QJxmG{7JSBlh!lO5zfKE%!8cNPXwq7FqzqEQ1MeA#M~QtsU%=$Ph@pS^^H0kx;}ecwG0FuU*va~n?;-2_fWl93;g;5) zzQ56yo{;P6p21em!B{D68oKcMk^c$@OBpt_n)?b)%6udGsX75{t9p{|@5H?aRT$tF z*N3>o`x((?AdiQl@yzf31>*DSn&*<4mW6H}h+RyP;`Q0CtgL@TA`NRe1WMDWJ;ATjHzn>WO{<)L{t=_@&Cc`XBPAh^m4dhnM93#)q9{z1#GXuAb#&$kBhHh=agP6V z74L}7XH&J_KOp1dfBQU==FENI9PWdqxr~+l`=Awdc2!Lxl~ads(70W*8P3=kwdL-h zZOHWsJhlGZ&U!f$Kl2ZPa%?Km$yup8w-|p8)0{Nd@qKGh;c1A4aZ#d>s*wh(DedDC z1V`bu^=j3sjq>jK4Y{@WBkbQGNnDMc4BZ0;4nvn-^Lc+B8fy4p@J2%#E{(R<26Bzu zp?~r-hhy@t>;u=ra$ZO(`<~B-wEOAjm8O#;5Q$~iNm!&8HHNQmOaQ~uN8q#hGr{Qu zV<7LhANm+9oC*;kr!u~P5`VsnC<9nqlj~E(TrzH0>5}N_nQ4E;r|vFI0!gBhY1!ZR z2J#_k<*6N0H#U!0|FL+JQMysQBE_Ip#HBYRnw?~8<&_}J@{wVmGrDa+yP+1|o;|-A z2wHLfT&0It?P+?}#oBJWs3)a6vP{8oMNX{z$Mk3C_OG=pwYdN$q+_*GM8 zCKrYeMq0VX)g3 zXJbLz^DS16-RvR>^(dOC>JX^6f%@ba5y`Clk~DBie4ya6UZYmBO#FaypM_ggCK0hNh)_4 zoVc1hYvc6NICk zUPWk~oK)SE*!o8ju|s|myr2-F zdK(3yoA5cFB?D{vG~wVa!h#TCmSu7|=-Fq3GBigIC0ggTud`A$z*~`GT$fjlA!(doL3oNd{2vS(JTehgP z703<38daj+&dNtIhsWf)YK@6YQBa!-&Zlvr*0QI0uMErm$#DW34639U9BQ7g+l6WC zHUkqfqK|RQ*%_nsR(5=>j>LgZ!ra;ufkPv^o)LU2xNU-k*^4UED)+M)r0@YLb~H+* zX>-?}N<4_WpX4$sOaFt$_#Z+zY&@*&|EsTkr6=pUIfmMEp{c}OuaTbfVye$;R@Jp$ zY}1-p?b4`E8y;-0CM5zTJU&yWIEx?zx)%WP8h?3dK!HLq_4sJ}e&KLCx>Ur_%$7z=5HFhZ`FR2# ztv5hnDKByE5C*w%dfvH5rFQaQ(CrwX;SafrSe5UFY_#-Y!`Y_R^oC|BO%I_AN_gOB z2x}gfbjC3~aM-}w&*020-K?$YiT3TSk3N$N(|R#`IhcA&{NwmH2Q76lS#3&@q3YEc z5JmeGl#xwihT&lfNtP^U@;h0@e-8jEm8)4J$)#zXh7ez4)h-um#Cc5!a9%m)^9Gtp zg~bGxwF)<6=_q&{YhQB+IY|+WwSJS;ME8E*pir`kL&$zO@?S?}KZ}4lPvlu)@o*4J zCO7#g;jUqdLOnk0)n1-tW&M5{(~Xukl31e!=j~5MyXMBe9t#Cstg&ku8~_^U!(IKP z*DtI8GF@N-Nb+X!sE1wv-ahHGW>ZG0xRSztU0)Ybm~)>C1)5O=ra6Tee>6%`8|$Kb zfLBPk1Ec4un!reSKSP7apNy9)*daw@RTo)1sXT;6pN4VT6jhXD|20le=Mal?1hFnsB|) zt8NC;gc$RpPP}|(?fS7fW?lqsA=a8l5HGq!s7A2O_C7_=uF{L>mU~WPkLhHha*j8Z zx=7RlrItrG^N;UdrLjpEB`A16Pu_2Ty3s*yQnYk2mCDKNn;Wn&egGog{tL9s+Dld| zDi-gN;9koCks4N|u6Rpe?=HS6C-=sR8^XBZ&`_$IF zJ=rK+?Xi!MhFx1XX!PY}^E4_A7OI1nhLBmr_O&4H{eiD(i@?2aN>RowG5c%NT9 z$B~*X`SX;k^`MCzS+%mT*@+E9`OM|VNWj8~(@#T7b*|AJy8DkK(VQLD4w#s&fjWvE+5s4|4*vqU&?_Xzmr%L0gZobq z$r0K!sXz}4_72)sGS`%9$KcK zzMT4F=0^BdQY^F7JNn%{-S2MZxPjESUCr>75qlWc026i7@p6`@7h4!}ppMg{%l+R_ zCPtIxB`BDvaYxPXw)c6gz>Q}15dBawmUj$?xqL{rTj&XgFx!=Sp_WlF%7qmWScZaJ z(v$;)cp`-oEpW9o=@J5tK5(7tXIp1mS3_0?s(g(#m0i%09}v;_!V%CTOk+N74aL2= zWsa{Miz-H`ocF+=05aYT@F=Aqe~MUuqIQWhMPP3=W;^j18nI(s$w;S|fT(r8`LcL5?K0hJJ43)WS+Oz^%c(@@1OgnG27dYo4s3e)<#x>`5aV z*Su{RR#y`Czf5k`{8Yro>?>bQ#3DS(O7ZJ?W$P?fIg;B-uZU|wy*3i~mS~XlT??5=qZ!yAtjB*Z`JEe0q9H7p#AX;H;5_ZS{ zeC<<~TC{HhL8soloKc|0kP!Y#FoAiXx0d38csvI|&O>93^%pfee0wwYZ)}dLjw?rpI=YprWPvNRY)EOKd+S)igGiaST&}>J;;qL@pr0(}vZ@ zceW`BirRnBAag_(I(C}ig__^9pyE9K}p^@((MsIP_Fm5$g71@{cwJt zP*n>S!C6!_?xN_-x3EdsuCIWA*cJAwf)z?le+RrUA0VuY%NzncgLR9zxdIRX`3TpY zOk2IUu@4p&k@Ykp6LS3ty0x#MdmXGgSD_31T6A=KP13VqafXOCd^4kmMbJy#wmYI19 zN9OV5hnWUbj~eCKll(3}(gqPAYAOGPP#0d&kJ<1d9Eszoy0q$V#u*VKC^5=r0+@WI zIL>y$53tP3Z2!2HhIgZDk!jUgFkBW05H{xur{m=Kp1bNoKU_)Rx6U&tDj19oy){)B zHX;>a8-ld8xC_6m)51OR@ts-o`o6>>s@}ABVM#I3Y{TAL)QvGs+B^?uPY=u zaB^4;Le(lK(`vMLDSsU5r$_gplV31bYSZ#uq8f43^(9Sa@=&;c!7xZMSc- zg}91#8;`KUP(>qve+&SK^ssc(xm3FQ7l$~`qLOBLit-%Us^(0fY@N3OM8gexqF{`Tde4ea}eIaaxO2mhY0zF442!PTZfeu>3Jy8FnMgT=0NQ`(ia z9^KUBy0q=XM#(n&dvi zr)^TP#XF=*Dd_C061%lIBmX0oJv+%jqGb}$)g9pfm+Km})h`^$LM@VVU{< ze0SiE2Oo_w=3dmAs}z{L_UiN|I#%60J7lV=^FH$F_%AZ{)g*6b$8hR<(F<06Ao3zn zHdQ9C^5-Hs<0b+ioi}aKQuBLb(OkF&CwpQRt-e>+!)lTLF0grO$Ux_>b?A`RXgW`D z*S51Lx#*H^twU>TMYE88ib5~GBgayh*Gr1CpVBUUV5o3qC-f05oej6edlkRj2j8)4O8YaJ_iu9E=ibvMn~4cY;QfI%2)onc9YdYfAfiAZVSDxEGX%ckUgjA$)!E#aEpZ_p8XaLvu~0taFZ=atQV0U z2vcW)hFmI8#q%2S&o8!K$R9-9J$^&EF$|qAzs9y;9Q&ogr^`1 zRtY%^gs(N0+cF**iXx8FCpo~_SWJd9X{djyCW5FnYxJPDd_q6Jac%f!Jy^yhJ$I^& z1Ys<$SS5#a8O2tQWI0==@+zLLIIEfJoniFnNVrL5?)eRFB!hA4DUHmkYVh5&4fsbB z(7vwH*wOTaP8CteHi3-vyJiYu-y=Xxl7@gjY~B6HD3$%I;biJm8>}q>`#9Rxu}rJ^ zSrorvpFy&QTm*J4$-^StXp)^EOS!NZx1S3Vfj`FH(2UzAU<`SrgWeBBD6I7Gxt?8`F$nMD8be*r=o$A4K|N6VP$`%b4Pzx+ z&X$%!F;6YsK`$+Qio*u+M-1evou!b{KuX|}0`K|M+@07ru}ykytqabvQhwB4J7xG9 zR;!*7dw+OVaTw3CDs{PW%Un?suo(~&{Vyy*B#vMwj#5U}aN~*}DvA*xRb%XT-v{F! zW6?D}0j{%V3NHgBDQNWixQbm_!-~K<&MWLL;?cnJL z*f+Wu*Cc*CGcBePiLjr#)~n+xdx@^EjKXeb=ruv>+c`0}=1;={g9TU|jsEapMtWIT zaJ9U;+MQ1+YWPGZ@%>HJO|9T)TLF19m{EU4!~)WheC&3p zz_nw*pj|SQ*nVb=M|$rJ+YnF8g|#u7(QmIZfk=377{_rryxVcN`RUS$8H^F~X%+9h zXmklo1Pv9<>ulNJs4lR<=3@)Fp)RE|j)nLG_bu=arxyR*-_! zDR4z?3lW$M0$H<;2~zr3{=MFJr8Lx2F||Z1s?z|&VZI-|aSp#nYqvk4oG-lf2Mv`& zkR7-;Z*5xXh=}g%0jTGhu_nrfL;7@_?NQ~~RnCMh@amivfz0H@j1&;p6~}Fxm$KaM z&|Fr;IVjW!FzFF-!(vMo)WCAP!ab{Mzl6+^T!z2QTKQs=5Ta=VEnb`RauR)6fq#PS zS=&stO2}dxl(V2aD;K&wSE^2JuC^U(IVd-nOCNP=qZxt8v_&Q7?xVRv-?Nhn}i%%cQ1&b`tw0Zxp} zq?^Pco5lPNs+IA7xiX~b7_>PbbCc|H{_O~QxJtPZhiim|(FTG_L@%ggrBrBYQmTI0 zA-Q8N$_bs}0QTmiODUhMOYT%4Z8eb6M=0Mbfs?w?={Bb%q1)BWUZ;zQUPP^Lc9b|* zej_KWw)!Ok+~k0lcm4>44GW9o-eVer{MLptN5ece9&VbYerlA01$m>EB-YED2;7W} zNOF|5eA=tX?rA*~&2$-km?Pu}wKQ8R7@@8Vc&zj-&_Jmqn4f1f{fE$vf`_g%2ZZ8R za|g-V?^&xKE3u&)HxCiw^a`_my_4@;jFY{R^D~r$wJCqKE~zq`sHVdPahob@vf=WlJT$g*|4j zGEKZ60QkajjL<)O5E(}n=OoZ?&Gb!BG1^W9bKwW_x`)0NH{-mE)Xw`K7a29k-+ip+ z_L|DaWHd4DMsrHFU2e!lJ(xC1qA?^Y@He@zbnG~Z6Ffe@f56uGYOR(1>L~i9KLfkn z#)_?8QM;A?$;a$^$-@J?!4JE%D_ho}b?Cf>1w2&xtE)j18Fo3|S9o*fj55D1`Tk11 zDur8x<^^N}%B4JrS_moP<#cO&u4yrbOy2Fpi40uYFYLO#)>4NLT5mmiv;_p!1#Hf5 zsPF`Ry|R6@7b<_jhiKDh>Iq4oho9-)`hBRW-xY?)vsU0hRvK@f)DGEZPhrBBm+1{^ z0{&5K&pmXvGE~2Y6wsntkp^CuKF*doEA9taQd|mz;Sw4a(*2I5&0r*u1G zOfVTOD)*HMAj}8!XhVTh-IRv-CC1k&h|FN#Yj^2-> zZ#4ws5OTA6+1K;-b@dEgw z_Wk#~5y+dPnPoqtpc-dX*^(yj-l4wOUZ)-m&C)&@W^(c1k9C^qm@C2wc%fEe?C*az zu7#8hdwApj+`gQII;^*8A4qhXV&UVi>1~V#PP3M6nrg8(Q_PD^fc70A_IQ8O`xb9+ zdAmg`8L>=vT){|$;fLj4^z>X6U+J>rx;WA&q*+o|1mw=j@&nVgfYZWnpkY$eROdEh z=+$G&cx=e08-m?(>(18zVKTm)2fHD35&`5ZgKPZ&h`x3yu)8Xh%R`rSmcC7hQhP1}fR|1(VL}XDc-_Pmogi0Y zH;o@sZ}o>N&3x%%9-2=Eh1b?vpKEI*Au$X+fkn7HEf2}-=`W+ROw-ltl#f8RB<8)e z$}_qThNa+V*tW!Xr;b>QeS3>t*80GrP}g{A1*Tm0SrH_lI_?aUmP?{kqAtnSTc*nr z^cn1zp}l>MD{QDX4kx&ZRm}6xV^z$JsQdQpzeVw_w7!dyq{PAnzpw@&S~Be_^U z#eb!~{ZB(!75$pp4KxHQNjWv*RZD&nBseNi-sck(h?-%YZ;W&NuCey@IlQ4l^}T-P z1%=3ms$9_mcGvb)I<=YhvQyT;vikJi9#pSnp1y2ARqF+6{LY}=uaWyA zS@<_9`)A!yU}s3&*B6*Rqy5q-`OyIXJ-OrmoW%X8??E?xe5UHh+cTL%(|V!q9fGPNd98(>9n29rMmF^^wc6I1 zM1F4oa(OEcF1l$Quh*9K!o4B0ziaw?1UaZE;Kixde()iX&}ETdHf}d~B-VSJdIp|o z-7P8kUb#XLMn1Sq@uXYM&v-R-)vtd#3gvril+K(D-e--ji+bxm{o4xMiK>`P>)*G_tJgK} zF*|78D|!@KJw@%#NdPyncwJvff1gu0rurfC>H;2WI45J~j^aEJu|4-}X4f5>sL z^KkvIK)$}L>;G#I)p;V z+BXr%frxHJcYfQ52#;6mnPdCnT%CvTUR%*6W|2nfSRQFF5 z%LZmNS1*=n^9&b1!X{_S6lT8NI^uz;X<~ofd3@gQSv15MM}KYRx|<6}2f>9ZF9(-j z9ep>B*P2f+lNV9%AJpfT?%qK^JKx^k0|otSH+?%g{mStqeE+NVI6NSS~a~oecN>NL}NNU zcXAL_c}I%6951*QrWmLqLa1udG(<}#bTnJv1vptWY5&<3VP^c8FAC@}7(wclb+el9 zJKxF7eJJ3X7W`sAoN`SEmo z`u=%!d{`H?$8M#}Pu5dI{dV7Q9W(uNXIt;jC)dv|U4a@$qAaMFD%UnZjQo4Q)c@06 zzZ3X8WA%ctC_JqF^JDzD*TH2%V)Q!eVTpDu48%Om5(qf5t2|=BCm*NcFVGREI zOtsCtJ9+blRj~4HY0f1NQyqtn3}VCdn0Qre9fWPD$w3+v-T9DbX?cz(qDn=vB79qL zy0oVE&f|xlDOkHP8008`M8(p0rp{I4Tb2?}R~wfHk^n1BwU+H3>~>{kEU6P~uNgmt zme^L#v-nqS#5_1OW;l=?4-s_b>7TV6yU%UR&>j*sz|a470}Be1<%~0+sd1i>(AcOq zHB+Y`_;1Pr`;{C47v(_J%17K({crj-ljYCce@^#|tm2ktB9U)2OZ?`QnKV@2`JZe4Rh#^PoAxHlm)zWY;%0ow& zCEv?A19G=(Im#JQHnO{ymd<3(&bG!Mw<@^FG;mK1J;XeG#X8tH2H#LC4jJ2-(tM)F z9Af_xR|NiQTa&N^GE2<Mf$N!YNTK? z>?VE}4AxU-0$vd=tW*{b8SW~0V%mS z#{JPi?j_>?49lo!yWv7Ag_gwAzSB!sEC z7u5~Ai21#S_Zf7s7Z#KhN0!#pj;?+F?jd@QFXm2hVt}A-aqJ75T$SPTv9L^;d$+CR zIX?{m(`>w*g3pjTpJ07hZtvxLNz;N}f4})f?+In;hnQjJ{0*)TyoL|Z`?XaDCxlZ0m$5$jM);s9S ziJd-qITxn;UR1Yu;!VCT==94#U1%oES^vnzAS<7OM}8^v8A`N(V&FX--hjz%*Y;M; zMHxW?bI7>aA`=hU`k7`|8``}YdR?*;L7mPUeT^v=4%~s0#X^{P5P@43kR3ITWoZ<$ zJfYbU6V3@|%jBRS7_#kISfV+Ra}@+lgeVX~7<@4iTGn+J7iPgxz9d5TL`@An2Ha$z ztFx5>1KqF{sFu@iw`L)!tA7F^n`27?$=z~*YB~mlf?#;vh}to;1$@soOwMHD==aU)HZpWNr(A3*d(aZR*yg27kr5v;v^BDD`Ra&>c-n6ij^ zYN4J`nt6(=k1qm~Hx}u%dTl@zM*a}R*!i@QdR}VB6SkKVP2S+;wA%NRTY;Z0==lo3 zf%;cSUr-exRLQ2fl$JiK;%bG1U!S|NSd%pS%5BCTY)hZ!DM<3_c7&NkKS0XOJcoWx za#BY04$TjQom7ozsVw17uV94?xmSp;ZgpJ9DJcr`{3yvHPEMXg>SMZedl;X)Jcf}; zg_w0a(XxtYIGkljqYhkXZC@j$4jM7=fXY}@UGYcmy%eJU)`XGL3C2#Xums$(os|(^ z`zVVcaZkaf#aL03Ne==xvZ5^s5)YRc?gA1Ic7j6kv?f9Pfhtln>$e1#$x%A65X$Y> zTW?R-h{|q#r!~3JF(j`ATHx34H@JHq=jX;@D(lDZfcbx*KTkEgRBPhQ7 zQUIQDG?;xPt|?#-wU^vK8`&JeVwf+_YA%G||0cNcxLS&V9$fp3lCWT?K1U{BA>)t z8uX~W1c$)J`=V@Z(-IaGMLlxgympjJdgFg+HpYMJ!`eu8)K1Bpqm#+SAK0s;ciKPiVD7 zel;NOf9Moa=7Y&%BmwJ3sb1Xi<9Pf9lw`7)T7~I%^$6*n=qkB2Vp6-ml3QCB5+?6u z(jLf44KeCIO>fD-z-P^VW4~~!nsvceFGX$)OG%O`BA%*!B%XG1c?Xp76W=?7$gygy*Y8lBA4YZ--U>>D@!L#nR$NZEnf5ui8(QX$j0O~Qt^;&fUR z(CNf2<2SN1bC@7hsk-1U2IA)t$8~Dw?Lp;jXxr2^h4?5X_qR4b;^2ZLs_(Zi{^UNzTxR=7ZIV2rh4^fq z<>hWHY|?ak8;Ypx`WyY#8{VVWP>+o`{OQIyuMK!$8sR8ZQjir`gnyUH!epTzKb6=k zeR1iLwsm}Xxq7Mti+VX!^@*=P3|OVY<^e-ro!!yhFnI8@(4G^2E?>_FR=+A76&S`B zKC+)*&8xx4v50Xthx-vt`?`+r*gv!kSx*K){jd~QEs#zuLpS~C{K}vg*cwAeLxz5z z1q0XQaVTC4b@5HQIg>3@PAyLou8jKGw$3$!j5=W1Fm1e6uAGq~yEB9;BnrhkHi>Go zX%;$(OiP0|4;JGRa5XeyaHWo^{Zjpx$yW2KfyWuC*&K@pNTLHWU;*&VNc>F8;fZe2 zmDyai&7008#4}BL3FiYO=Y@sxf!FIIwm>rFnXteMoph@%0o6gmr3=5*c|BtqvP9Y&cZ>yG4Oa|XOM`U)4=fR z2X4>K?5)O)<(eaPtE?L*2>Fal?r9{Kcu17Nv;=#sQ|R@hDM)?#(RXi3m6YqBU*l8+ zq~XXCSAT@RsOr4JDe-M(Yf<`qM5TuQz>Gp5SFVd`!_^i~nQb1{i%^g9{3WC8$lY~w z8gh#RV|Ishi(LaS68<69ki9?{L`2`T(8dj1men?RWJzfIop zlmatRi*H0FaJ9rrZewz<(ssKO?;`fhi4>c?<_q(seuVfwyn1{2KxDCexp#zKOgPi~ zG7k85feCV@lbEvB?oQh{9RZ)7dp-0k1GGcF+RjrybiV20vS_ga2ZR?ji!c2JJZBfp_&HagrWa>q7t|FE&$uASRv)E0UV8?FH>+9q z?%6ZKeWWS*jZ~ZDw~1nM2G9%{(Ir0#8U}hhOqtV!r!zR3{kQl~cGq{Q~+@-JAvM{iMJb65Z?^Q8%L+aC>jN?R=G8#GxM&F=rO+5gLB zv;Plm2{snq|9yy+kK5!z>AtB`ax`eR7|+;WEf7-9XWY=8@1_*siP*%E=Q^X3ngezv z{j?j+qhd4M8_%R;Q+*D8%>0;%SMzUce}AU7r7KcjnpfinH0J4QDqILKO893hC8P4{ zzT4iOHuKih4aDm%JcPAxs!EiJ(mIxR<*Qh;)k7S19nvv$ z`i$L$MiPH9Bs}OxTgdu4OP4+EiM`e)aLi+BAh48m~haYYKz-el`+>5eHK(% zzTz8{0uXaI7pctjgA=Mlv)Icwn!Wm;@p{((POv7tDQ98~?R_`ZH9H4x$1)m@!XfmI6NDTtGF`D$Vaa{%d1o|;BHgqrM7)Cp)zBnrm|0h5A#>H> zcck+`Hbv7D>+@+@xMH_H5>y8lY@QEC3;oHs`~+OKCm$eKN|YI`Zl$pEtNb}0uAdke zC?t|CJU|f?^VLxG5S3euVYq`89iX1?%NeSt7epcaIZnxu-F@VYEAS|2=8Vg7GP>10 z`ukvLEJJT1escP%`5O<@ZQ*_nQMu=PCEzdq5q@kyDu<{vbNWN_Q518n#cKCVV!$#r zP0vZdYblcuq;Ixy&*CK5kf#!I@=L=bkm-F^LL>QSwP4%8<^DSSnd}O?#k@H!Ch|Z~ z@=74_*1Bv!ZRF)T{9r06v+lq5nwT#obg{4>Z#$iXk*Wc&MCZo${+S2)Loq8a^S^1V zCn+YOe+98A$8|iI{pOG;86#nIYaxtWx1vqy+Q~9zR;gy9w92ZbNhpcfw!sCT0KS@A zKr*3?cig+`9)hPx!J|W`Y-U;m;*ztbp5BG+L7%pTXG^Zyuhc9pxBH<=V7Jk_@;P%} zu!;T+i3H|pDbXy|8hX_uZib5Uy5V$H&b^IW`H5vkRmX2#M8bD1rE5XL#7xr26`V)1 zlyZq-lI8q4Y8*D9%v6wG{$#CN1|}pb%64iNO&T3cX_ky7k3_LOw%TY9WVE>?*)T*x zjm{%2xcuTeu>3C=Rs3BwLKjTiL25Y4%xM1Oj~_aRtr)q*mqxQMR=h>9DC~6yvkI)V zk6bcFix+OQQWJNwa%IK`xfa!+y?hq7D=-{MC=*frJxMU!AiAHUIxdoB2a-&=QTUr9 zi!_2^ka|+_qAI4Fcx_7xMnx*IhXAQ#C!-S3oFbo^dP8fTd_5);qB5QK1z&?u z(k0P!L`Ev1qCszSp}3GffaA_!abEvJKHM6T+U94Khc#WaILw*}CP_dUtWaiJQoQRu z6}#M+BwYKV^WTzu|As%=ICs1eff5*P6E@{RuBUJEQ6U?=sIL8-w#85=EBY%)Cukq| zPFRjE>O)nRVnkb%=`Y!^z}A$H;uz%44cUo7R5%%5qj9^K?BTvUK>KL26MJl#{j0Sz zhlVeN(zF%*520u;iY$%Ow)bWZA(pt=WY3X*+4tU+LU4n)!tdOM$$an#!Lsd4G&eV` zkTa`i5-49^fnzApr$5u%shr`3&BzJH&((9!TIEnY@62YdPL{idxY#Z)=CGd#UiA=f z0xOVX#O_0!^fw>tz&t3@52BDVto{5!z6kJ_27-8YLKci4*zp7?8_6pSrz#K0BhZ?` zuS8XC4>{?XVdc$D>oe38Af;pkk6OrTpZD2{rg)PZCAZcdscci8TG+QeIrbe&vmb{L z-+LKQ#f|l9Srv_cpWH$Vg@cVkS1nT$bs5a)Ui4%Q9c)jdfrkvp=R#r87%?P2!E0dAsB{4GVz_UI_yCZLN~AX;w(uW!5zLOc4zTxB@G*W@8Mv z!npi~boqtR8SvgzSG8stKROrIg-J!E;h5Z3Br6AaB`Xok#*TB!8^ehj&0)?OWY`;{ zNrD!p5F4T-0m4AiUhT3AFoUQWr|7fWL+vvko{$b; zXEclt5ysP-9Ysx zS?|6#j%}!IJ_u-ERY_or>CV^M|DJ4~Vyl69VN`QIS7cbU+qg>V+O|m4LRJd>d`OWF zQ_ox6pRJdBFz~jVjGs5gq$2k$bYr?<;I}oq-@%3rAi9`D$vdn%dw6SSzm3)keM7nc zo4RQOy3wY+Hx^5lAq#7QI`Z$6$LHXk=1u($CKgYZA^-J`((Qj6D#aQEyc1neoHNH4 zgTtQKC|L8(HE*}{4=wwy3ng5Tt1~4M;Bg~GYtO8ZV=KH4k$#iMbTlP;{rN>~dik;p zzqnhR*Sz3apHw$GENtD|ccUYFnUzrd_4W=+Q%F2z;HOyKkFyw>k) z_#BBy!T;{YeQ%h%jo#n6)!(nxzsbRgs}fGVjMJg)_KErKPKn*ECp>%#jrmw~C`5*Mn z|Nph#f4EdOw*QSwz0%Ql-E713d#TIcEni22-#cJu&$0H%l3R4}Y_U}&#ybs6NKZ$P zaG_k^ysX;=|6NQO)mWZhvuJH72G`Nn#q+X-9Poa9f4RB3K>3?}wp)tnC&dn{0vqcH z>$JNIuk21~Z(djDzlYX3PJ4Jh7@agT9F?|}-)t~c1VOpu0FT)Q>0tAMfT=}%wr7kW zraftr)(K;sJZh$P4Laq2N7l$sCgr{WUHoaY(pIe)5zzjO$9NcLKvkSJv;5Tt>(PMB|mfH3+ z_!8vsh)ZURfVo=yfZy^Esy)iy!|i9A)1Ua<{ z`y|uN7@GmN(xqcnPL#%GZE%hZwV(lV^cHvjHLE^@QjBJ^M404yq`NK#C9O>L z5ul&+rH?u#PVs)=DC97~QjatD)7}ii29orKbN^|f0ET)7b-GeU`<#ZdRSpB@&+xDj zRHlqlI*ZT9qxNE9hjgL*`Ri_AODS*6W76dMNQTYm38%X^p(EQYx6X#7oa8d8L6^_a zkkGGI2k>BUy7TPc`$#4!aJb-bYHAbu0+#b;e+Wmdmyhblu%kX^92{r zY1N={0;w^fF9KNT?1@GV=#S~cZQ?r;Da{`I%l#r%xRO3mrSCzd9>N91JXVe3m{i?Y zU&2&*FPzA2?mCnkEXMe}8#jb@ii$?Re8R|G^l$P%=0v6Tscl%F%c?KnEoe-gB5l3!r+%^Q6LFDO!$;z!qZ>&Ft1@YQE3fZZv*PMwPjp)ip zh+y(0U%E(RJxZW8G4Qlv6`*5bB;uW1Q1>~Nr{YBNtbv)jV_`>R!DZ?0W;ymzSWm>c|CLqLZ=16{CVPm)=|jJoAX8%SmcI-KYL{jWm^^mV^W2zNu6hE*1VZR|jn%&a`4wavP)AukFs@UHxDw!HxCIBuT2J$@ z=WfQ!G#TVjT3?*STpQB%A_P+Qe`6`$fjRQFBoRrgA(}SNj$C}t>R}@@?gr94gxxhlfGOV#s>0cpS4^tYlAhVO=0jm4l`Z#;A`c`r1<5}u}ttWq_SoL zDQj-55?;Hlsuh7gdJ#qQC7eFb%3MOP%VCW7cg8)>cDb#Afid&zX@3D^?#7=efLGHK zkNLvjP8JNFl1;TpMe-mQyu}itSf1Xh&(D^M`e+^Z&rP@xW&$!H(Af9LXUxvBn$9Ry zqe3ut-gL<@UCz_^mrs8YemA%XjJWFRE{TitT#Zs){h1xdUvVR;xG1`(hKWm7Mk=m` z8fC|e=gne}Bn~5>Ju+ z2@j&;C8n6_h5SQoqyI%*o)9j7IpyQc^j;PuzV}^LU-ygsP{NoXh|ugeC)}7=p;lJp zW3p1m1=;_a%vur)Q>t;8ezP+bg`geUW8-$+uz1P(#G#zM2k zSOq`|L8<>KqgtMj3Mu-o??d%mIw|_B2Z|WY-NXcnmD%Vq4A?Ta#|)#->d=@u7mbF; zDJ=gX_!o2AI^gy(MuF|@};opAiD(s(hv6xHUJEY>hAD>@7>b2bF z2J&nJtE=deXD)wsFsgP#P?Nr#_@@sYcTcO{8tKlR@hLUEpJ=~cM@Sl!NY zfh{W0wEm@kr2b~in-}he1ue*+c~{zYU{-35`ZUte>Ef3)+tm1b*<8?3{a;n|2t(tK z&i;J)G|-s;C_wo70k#QYWzZKjio0rvbso1=)W%g1*YmvSj0?c=N5sjQi>ksZbEcC` zv4@5SDnm{vEGS0}K8LgG9c~MQ&*udr`G3s@NbYz!%KAN#rW0nweR-}#<4}&m%{G5} ze5x+Jl;I}|(G{uP>Zs)|Em7&$m*u>B8^Y0VRA!(%hQ|PV-SEB(v-8y#TO!aR`JL9l zzl&^A^TMRb`Up554mLE9V9duTU;IH*S1A;E`|}U+1ldQM&dv^jSzqCr9^h)(C zG%4S?n|4$$Lbw9Ackun_CS(^MB9gTP#c3C|_K%Gl5PFqw5xAJ>%JIKgwsMYvwTAx} zS?AcKixP#`v2EjwZQHhO+n#r9+jGXY&e*nX+g5IpN~Kcy(zUz#2XyuBXRXbc4ROYP zR1W;n7{|1By|7;WQ-&LKWsa&TJHS3OvM0trTXzUp8@?`6K#i@3;RoS|F#+rzFl@oW zSa1#4Vpynp0ln6KWsGt{!(2K-3FxO2)-|o4QX2pTe3T78X#O?24b>&AyLFiKx@$Z( zESIdpI;b*hvHW9;f9y}S|94Z4r#;3AqenJ#8 z2q)uzH98U($N!!)>}ttO#Kg+RmLAvwf&s?H!Nr(f5C=>NcmY?`onHuuM%ls-V$pQ; z@bC!VV+`)>>;!+^L+IazzL5{u!_W=-BpY>}`PEcH`+3=~k;ZsbYtXO~ry^aw= zac`Y@nu3$%1yb_zvN9(JLPezkMMZ_>1rN;%ZDKpyb@qgTPbf+b&83?KXhm=b#pLXo z8H>-{hCR3gT7j@JZGc#40y2ZcGn2z3q5B4ghQ1v{cq9k{G7_u6k%(r25*nJox%yQi zHr9POwKFn#dQab9NdhK9aQddEr=?yIJp$_C$L0ry#xRH+j%*Pcy=E!1 ze7+Q*sQFziEPM#W#W^@QAV_d2Ab2ELfUUU$vO}8yT!P?7V9u`Kz`y`)2uiH=fS+X? zP+oAs>8*kDd>Azz6$=g$38XzeLpvjoMmKK{rv~sKJmA}P;K~JOATghWYk}C~A1gt~ zx7B^14D5_w)Ek2x0EpJw&*1vl(9q1t&e+P}zzUq9wGliBrSupRXD81haExsr04}yV z_i6|59jhBlTOAv-3;(0kfh;JjiEa3_v)}vS!tB&s@8NFj*jWFwNOG9ZcsojK4~y2) z)BwEB&C~x|p)fUoZ2I7TLlE=Zp-ZE~!=Y0LNUjK_n|o5g6~y!rchiA|#7t;j>$Tkx zy91b+6IlT9pkh+cVDbPR0RgpVXR!Q8{XGE~A%27>y~n?GLlQFh@c0Cr``{80!m7-D zVs@n`C(=OeU7dkE+|Dy1+umD*a9l$X{WNNJq{Ko#!LuCFW@80gt58(eDeB$?? z0xA{A|K&aJR=}E@S=l(Odl#t9P*T!YmzE29F`)aEp!#Ecif~tGVFo(H zTA)4x;-&?TF8~-b8v_`{rl+R&r|6G2!$VI1*IONPgP8A?ACy z(5=jKuUo`s)*A4yEg>uqWZ&5Q{21uZ_rq=^{@(CcPpM$Sr$8xg-i4veYYjMN03iBHiU3qJW^e$;81+MD4^;F9h)9O+qr6Yg0FFrlM1uEGKBsE} z$1DKO`AWYGyyGk02oL^SpVD_ssDDddGpPUP!G(b_C}ZV!$twZt4+>_0(xt%Aci#3H zL-%FOugKMHOIPod?au|^cMFl^j-jUvIH)@JcXIFhPVnWnj+RH~q<7#I@9!_Wu{Xo^ zQ}123dsFXQc+3ySr4LY5?^{n=OzUsx?Wpl9p{buoTN7~RcRJ6b5BFzp+lzj4cVbaf zXd>I(z>@>^)ou4?uS3Z;;Q6%-zwCG5HQ4nh`WE4K@^d%#8@V0u1F5yc(ysHh+~ec( zv-t%OUl|&nzxONsy|4AkKmBixx<8*Fkw*gb*F#}0v_rj_p5v%rEMpJu_YNuHlGjG} zf3{iE0{-g9fVb*?^`MK@YV>vI$YXzVXunB&aOCjMt7k$D{m$nhcmmtDry&$b^Pv%^ zXooh!6V&b-C`n9!l6Kz%tBPoZr!*d9UkX%_qR$>!pgCwI+J9ybH$Rz3`+PYw4z=dgy;_@~vt)IVQ z3ZGG5#KFh@LEPvigmV`~J|dt-H1w<5RG*LtoTmIEu=wi(z?LzF!Uu(r;&rf6a6tZ z%1Q}H*!s8xT+peFb&*FSXk>YXX9?a@dpKtIV&KrwBvpxNr*bo!9M%zM{JGX)P-tEK zs;Z?=RG>jvR%&HBo6pOBuG+y4^@=~8iXnj~KW~{Y%(G|LY1>)8(eZW`VRskf-{s}8 zT~puy{2dnGya$SCnvClp2{v)W+V~^c`@MCJ*h^dq0E-6=N~Jzh=hcTaRDj!X3uqYV zOoI>=An@tI3$_44+q=f)Etp8H_hd8goaPLBfJEv8PdneC2j5Ue|2A8*4apoaP}R)F z(6M3+@9waCY}j<4Z=Y`!rqz8ZJxX>*4^^DefJVp#K+oS(Xb@QFJ4vY6l9gdf+UNjT@GXFBS2yi17{;Txwo)e1`V)02Q zIpqxv)3@#1=HykbXgAzFpDYLMup&4ahH55|wpVAn5PhR}S_*nA;(bfE@8=6g;BRis zmeYpfr0sh<^;k6;c1QO5zbZDF(yg)0`bpkWz|dNJ$EqC9*_P-jYO>jaSS|)u*=RR5 zuXq+$t+k8f4+W(Fq3fr{$2!TPm|wvBVj=JsP!C&n*~tEKV9ms`IY)sIoMd@N9>mrn z4;jDKVo*V*PY$;`C7%kZDx3RYq}#wnk9Oct8 zpsasf;>2Ym6TP_|k&+@S){VC4#a+u-K?@xjN$&=vs8pc%g3vAEd1=VOhmJ)xjKmMy zDj&(+qahv$+p64VMYl6gy9)ZnZIvt2phS}OMjbRjj#TcaOR)6|q~%YFnL9y8u7rjx zGwM16YgKetbDoMOqxSsrS)QbNKz!%~zy;SH6hs^$cm&U9ifJLfCb_XZUl>ei5!U1W zYhR+YM$Q*At#P)&2lu3_w=k7(Nqpk` zce9_%bMa}u4AKuk9@#;j0;{ZMCQq||NWyK9rUDvm)>!C2s;-DjErxi2`CMm5oUIS? z$Q09_x@=a+?vCptn~avq@AV=85C8#qWtucWixx@@oOMQ`8$bo7)CG=xBT0y32wr1< z%N5*+3u*d@!m8^BbpRy>sv8N%{&M#sP^* zOKgyc7ydP4_JOl}aDA2nDKh@${;j*3pv~9va_nJ0M0~W8nek-W?aj0VNFJ^TIx1pw zP9*P0aE1eYe+REjpvQ@5J;~C>wA!!N?!3)HQ{XLb>hbxjXJ0NpNsrU7dSB`@SV{ad zVm%lq#H?SKXMK_AX#8YM!F0j|RF4xMGhSE)2=u1ST{vJp2fc}vP&4{N(E4h)ri4uheIcRu-*813iwDWLHyDc`_&#LMj!OuQ(z|no1C3VPzbFTb^*8H*oSNV-?n# z8{I}Sbw}tLz=uw2F1{`$n<2c94mz@K9>WfnRc!28Jb)gIR^qLd!3JBK>IgEwiJtrW z+bqhEjK-F$B|DJ->IYH|e8z$;`X4v^Jr*{7S;EU@rd_1t;BMvxBZ?5>_KrIR*yo56 zDkynUN5gtQ7cw!8dq^t+vRqsE>@LvzynB~hzSf{6#aNeClmq}A3LP?a0h?9twRQy# zE%n@z4$P$r_fnxVZ&u|^e>B_46;7xWs{u0afKoDokv3)k%=mKui!MHgT-CFL!nYB% zTvMq@)FdK(eB3m*gxtK7mU?K`nWFx3u_X9%jm&Q*DNZ`&r)DXlepFVU(mQ)?qGINE zYo7xAsOC(#l3~&|%s1F+oWVMs!F?)f_BU4!Tt3A+q+U-4aBEJIq3_|`nFRQJrJvgS zCV2ECcriL4(A2cKzoPSwZ>U>FJ&Q2SG|SImIPM=p;TT}n>vx9SDlK9Q3qRi0YnVqj zQRay4E*O%!Y)mqlqow4@3Q>h_-*B^>6VGr9ee7(H^ev0NP}p&?MAdQ00l;eLPn+@R z21?XSn2ub&AOy_}K!ytv`=^bTN4R!ZUkbC8_&EpQKHkccfpe-Q2={k)23if)F(P4= z3I0Ya3meCORp~y99fiN^X%MEQ7pf6afK9J!QU>j^8MZaTx89 z*V6zTUV>EZN88*~b=R0Aa2IxknR}hk4Kl#ld7lP9H4kPvxY6brVA3B3NB0fvy{mHN zWa8F*uEK4`vb>P=J8$$A$2V9&!I$^?%lBq+02M@$RB@A_S7g`c%SPBki-B*z*B2qQ zPe#hQ!j_4#zjwn?qM^!H^?@7}$~VbEZodMwhRT&eM(tcK)iIj7@st%n9n&5kny@$Yl5^Ayn~R$^q+Srmm_+zA)ogc3|w7Ig#I zd>Dr-EiXSR^wP>F$gSlpxBn_;IR8q_p0>6VxN34cqa)=^cV!?9wPoaC`Rq1CS4KmD zS=KCz?qky98qFSO8)zl;(Sz$RY`YrZon?kB(0|6pZK_sd=qimHoBoQ1p66t({lGiu z2hdJoLt4k*jck7<6ztollOd9Tyh#A+XP*tecJ-H|sVoV&?%dLAvqWFoP&5wS#p7R6 z3dgUBX?x#a;RrgOxx(kPQ)+co(I--7EjR>bLAjTsAx7wP5Sll8w8P$x1~2_R(opz< zxCs4-q%A@)H#b0=;|IL70zN#D7Ky3fA1d!V<4X0rdRaV6vX(-$c3FloLR0{$hIMa| z1EuqMa!Accv;cdr779q;4pBC0AuA$G28D!#s0QGoowtAbV=!vxT?LI6iB@tmqWkt@ z4}Y>|4rl$|CJmE%wnry4?8VPkt&Tm4nWTRFzhNFrNUWM2J#qdW?*^NVI^t2_XtjLYggrHN-_u`|JUs{Sjy+?nKTXlV538*kZ~Oq%xnf~xn>zjVI<0G!&~7$_+yFE1TtZeZ+8mh}=@vjWMQ`*cC_Fd< z`lCCWyujY(RFJWA&GW`mGo(PjTSX5=r>84WEycUdUdH%2_hLq>b@6w){64JXBZ>q? zNWzSx2xVsEkVaK`+=`Qw)8o4WWRRv1aR5lnG_~*GQ5}!)mJ+Fzdxx-dq_}m3H}wn@ z1!dm$a*8Kwx5q_S!4u$s#nXp4(*4?cWYcE*s&jdIdp4I=N)H5`qVWcy+D|N-1Y(9P zWS1H7u(aEP6`&Zxf*$jD8$AlE)<(vZ({$#*y@Gjvq=+mHtr~=&o-(p}aq3ldn-=DO z1pc{ZX^y{Oz&_yst>Dd#&5ivzWG2DT`^41(WrRb@?Zy~XW)8TO4Do<0q9l(1)JeAR zM{9Gern0jBINFE~sb$Q|%D4RZXd2|A7i|z18U392o=T%dH6Kj3@Khd;JfOqViZjxk zI=RVaIR5uo$}L!mER%77%GZc0p)PKcpX=x>m;poedqtP6IJ?OL1Jk*CjM&NKa*srg zccR?MU|{8PdIk(%L^{pdfPOfVkJGy_W0Jg04iOE_NFk?_f@_C-n~sj%8#aBB&FVfB zT~B&AqpJOy__`-Ogj}(g9*te27a%32knid-{o`V$*B9;W+J$$}kWUEV`jBAzGB3n@ zzlR652||P%72q}UG=Y0U;lcA0Dg~+-x_}ZtwFv2{0tFzSL(p8$za&ArM$q)PGH*`Od)JL*Mv zwN+4#Y!{L%7i|GE`FE9c{5i+HDEww<68?|&Ch*3M?$D}|r$u15s0&($lM!o_i*M`F z=isoeu>}N{7w~cI_NGuC<8Ne@Inp*-OMTSN2lOWIj1 z1S*te(%Sq}GnEuGN;t2R0OfXMtGI)OCZ}g0sJWm9R?kLqy8TULjT7I~kOgxMhw$;R zq?$gpc12Lc_pY7ATlZ{tA9~FwgiK6bUFoVY}8TGmTHx@vcj3%Q?R zqk-;?eoK8YQl_R|ZondR=r)u4wR}7rX?)rNjYcIm@?RWDb_~`kH$4amx=<`0Cz||n z*#sa;xQ5NO;Lm{1Yx*fAZq<|r#>~O0C(@IsmaqgM*>@x1hvn&gre+36$iYfmCvwovKnGanB0a)-UX2AyV}^P8Pl3p z$@;L(RG|>sW#=OGA26Y7$KrQw9f>UY6Z!ljtt!9}RqqdNL(k2%Wtdq!X8&OGfza6k z!zX4ct80um_&8xK6g3~aGbWXa)*k-$<=baODBQ)5^9wT??n;4cm6L^erL@Sj!UAj+ z&$qRq>y$z{Q8XX({*4#~M)7f6+Y)iF*;flnSNNo};67S!oBi| zya(iD+h&BL?-X}C-EO&*xPUWS%n>$~$rNs!8$LFVr4mWe?tRAYaO%V>xb(sdQ2oAJ zeT^k{AoP}?W>wpIfxh3gh!5dxZN93pZcOScmbm1y==$S=c;V4od!%ih0)*wC5(|=e z5oGo$WmB_o8AegYx79o>Re%qiCU2npRZF<$f-^@Z^@)edtFX!wY@jnt$gYCIE zlSN1NTp2m+Et*HYL&i>Ss*g5^3cvDStCqezm?dX#*~F+Cco1!?4S>rHmuLCZ13a=_ zJIS5FqD6a{2)~TH(Z`ZyTb@@|@vMP{!n}%3fWd|(t-Ye!gjw;GWtLc~pQl^SkwvxG z`Ogq-!3jyN$9jKOn^K{)(4ADzFiEMPPBSC)%$reJ31=9F{2IJWE6`6Zs^A?RKWwdF zj!F8Q_99aZV%GJuKEQtoNI`*)cRQVVx+UvQN^u=@$C<^HyVH?oybhCiI=g2?6ak(2 ztwRVNh3<4}(E|$}p7#>o;0Bo?#ii#goAmlLuK_RdY$JB;hU5oBGfUwR*g6MYx5wYe z$<(STJ9v9#e78NKAuHk%f?H?GEH5kC#|8SKg4Sdw=GC(P9nhUybbl^uj+!|KnNgiR zYlB0c^TxWd)khtkVUc|E5MdS3E4c^pEnmWL{i*dEaB^xjO2DeytgVDt9U_SSD&vdu zy%di94~$P!+4GiSb%JPYsb0LdzNyffG71V~>>NmWl5&WCpM_qyzRjc7MnAvCNqte3 z6^<;U+t5VO6+q#k;P@Nrj_p&o9F(oYWj;bi6KUl*qN;#WZ|QNZRgLY+#Bbiu0#>sw z^oh%?*4k6_>7@j}aIKM7A-e9r!0}T;kvQLb4IYi{oQl@FTl}6@+`bzKB^#Q0K6q_26Wqs@ZWtsYsM;u<4L^P;wu%rU2S3VM%{Tt;dapcK8`IqTd5vTg%U)M{n zQNHcuW^D#9&8f>`i4*5FtpmskG@s~|Zw~nX+S|5#c$W$S91o-)E1ufDMbsDsNy+dM z14$A0DM4ZdfuV|u!Gnf4`&XtDofJKAh>193CHycbzL15BybmFC%(+cxP8}+_%?;}$ zs#H#Hb4ZMW9gV2wJh9l1+e0gt<5c0yxr3EvxIEE^YX-yu zWdY;3Pi+KZe1tjk&%%M3%0 zd_Bf=nAU%E2bZ2h_A=01J8#;)&)QIaV^O~{Lukn&+KQ>9A8*!xz}~=_y+PAIsT*KL zIjg>whElpPXO%)Z{8`1CilCJ)6G)zfl@57R;>WW&hK(Ff2>A}|`V5rGx$1&zN&y=F zT@B^Lg819U8)#`At`r_2I@~p$Ql%XXNOC%jLxOAjSHw+79Nigg6>>|z+S0t49pkla z`2UGJsi1pg0wqX1HpWTRfN!rc-=$_S-B>6)*vB;=TG{pVg;Y0|T8?3l#tpuEh#YSa z&6Z-buoz&e;ix^FvDK;XM&*!kAplkanE9I7blKFF1Hl+G92cZ25i4^K-?zH_5J-ii zxBgM^eu|ZtG-DL#3Z+Ybw4BZqISsPI#3LVFuL!;x4Is+`qU}q_L7uxQ~?gt-hHTM zE)p@eq*`sh#6byCrD?3w`by#bRTBCvic4S&JNub5vh$MqNG1-DaAD@_L^ZT8-MW#c zaCIk^m?)209g`M6F{Yy0BNt>8&~~!kuE2>-|P|#csy7rRG(k z+5C#_6l^;e``IsLU6y3}$HGFyBa7bLDL_?5n!p1@Yq|o=NBQSYPQf*G;K~!%77wo+ zq^pvJorD)8dZhUj=O?;;m@W(P!?#c9w2E1*ni%7`Qh$aDIov`^rvUzP*6xFRQQlE> zg~M4e)kMsp2-7OU`jDcI^kV*O#(gUKnerN?#0?snJe2e$u}})AU4PI8OD|8BoCJ5Y zLkb+vbuIfmmEfNc!h|bSH%6jn`MhW`aq@2qnP+x-Jz*6B3J4EfozqcVMf;g3!*Uqh zEAu~>(~PVNA?$**djZX(+#OoP zQyDAu$mOP^2Kn30aGqNtubb;|-2LM9*43B8D{vW^zc2D6CJu;*0ZZX85anYH?=!x&Xj#FHJeyHG8l`&oj zJ_C%TidlnH({@^EtxHuFjwci1MZBQ~|C9{FM!u6clA7v(?0vs&Hd%B)jbaI`$&eSC z3a{`_h%bhM3vq?3F!ABM44_-iOx5dYTomE$=!NHo{U@Mei!~>CX7X11`(q|j8QFCi zcXlnN>9L@0MaJL?k4&$V04(w!QM^de$CT86n6Ao@h)1q4JTi?QEWV%cj^UpyeVpk7 z0loH0Q|R!=>QE(ixmjQcZq1yfQ>zf;sf#yzCNL4$&-W{{%lr-Kv%WUOOjIf4vRzEJx&2={2mbU@S&-eV>IE5x+P9`SiEl zPlm@%Jip2l+UxN@FMx@h)vNE>){fjf;-hz5y#{Fg;rb-DLykJrvsL?ef15&{p8TwM zjbTD=Jh15m-042vPPt0>bR{4=NONV%L;B6=fM8e0BmRBZ9c>yolI>D}jk$4r$++t~ zvx$NN_*3$*Z#Ok5E*M5IKMrpco4(0aUJ=*q17$gy7JIr~@1}4~%#o~Ug_+W08^~VL zb^z4KU8FZ`YG))8D=@K3M>Rf})tAz2uPm+y7~&84O@NsT9m5n?{4l?U8a(k{ zN|n2U#gg!hV|wvqXFOmtqBhW(2Dis(O}6Q8GDB6j*Oa#>xmdirZu0d)GoE}EY;8?- z{jIm!&Um6n?bMagH5KVIY1>&gE+EAzEv%&bcC(cEWZu>GVa`@V<%_&+46a6 z6{QLZB!X1fw*TRrd&<`H)$SVOKrM^N`*2BBqI&1NeDtjch4`q)a}7fsE{;K837PqI zMyU4;Nh7!r?lS9dd1?s$0*W~(u51rgHJXbWzVhB##}1s>fgR_mtLQkyF#y7+?z!|b zdi#$JZsE5F>dOS*VhvewzMaO6Lf)O6w6+xz!4A8dlNQL$r(}+Vt5spDJ6B$`oKLnA zBo6r7NUz;nj^SFA0c4*SWq#wwV#CntKQ+iT(w0rG8S}I>F^SsugV+=F-T)iFv?rE< z+hcSuy+BGks=a@boa3F*AArAHWh#wDsi9IY?-nJa@tF?5>CHOHW|6xk%Sxy$%5CcJ2hb*8XtflOv;4Tl>z}b(@hBO~9mAwRR+ycJc6i z2qIM)=~yff2tDy;b67qWgFi4jUuI;)DqJ6CR`EZfq05-cisy`iIl83^%~tZd&r2`! zp`y0rKNbe;*vgWea^s8Q2s0orxk7Js2m+a$kZKd<`a zURHN{Md*}y#TRzP`@oV`JyxGXT{ZZXTFsq0CB12xBTNG_JiuTLe!hzfhp6@gSs)cn z+Ti?`*ctWofR1{p*uDU0CPuA_wj0L?ierZUU+Hh_bDo+==XT8KKKgJyFTa=u%svPk zv}M^@rg%o+Z+izO`oeKRjaDk;aS_!4zD@o!AhBP01LIGiZv3P!Vc4-X}SLC8#BSKa-Mg+u5itW0y~2Vi{0^c*1_Z$2((cB0>`fN_AG zte5a2m(!D?uYaINTyDxxto$^DsQ|$eDppt z+JgP_@*c?#KEi(vy@l38Ag7dpJX1?%8;PyV=|5{mXniQDT2>&b^EB~(k^M)F)e-CK zdpvlxCcsmX!ig%(I3p2)^tRP}rTUC`*I|zn;mah(okbmD5 zbMf-o24t|B54N3_Dup3ZHQOzlb;IAMcZhDo6K&MiVm6@(7o9oM%PMnEk7jN>CvdBvkYe}<6ILERVK}YQVj|kZ|0$V*^xQCQ^N?|r7}{3s{Yv*C>(bFx!-6T z(@1=7ozwT%m2rv<~!Q?CgHE6a;4TD_6$O$_ve*Hpvc9f0s(22?bruWttB_*$9W+C-{y8C z|N5B_HpjE0TqFKa0%V5b)YD@N+@$q?9KL=f_Sg$M!Gs?mq{5_GMyI+^KvVz=N8RA@w! z%Z#eCF^myLK!ouX4G-6es z)}@Nh9+Ryd64K84u24Mw{xtPP8$jacl#z`BQmd))PTf@?vrEjKLJ}!cg19;iY*s?2 z^y+xgmXD4~RK8t5ktw>*eEDU`WX72C-^#VUSXxZmo|m^k$GXmnI0c-z4Rz9W^V>$$ z9)2!Gn?IB5R3h}%?eK#I@1zxQB_>ik2o(0~ed05l@Ex1Ss6Y5<)1`PCIDjyQOe!4X zNU|)0HDH)yZU%&bbv3i_Tkj03i4+;?zbP0Lt{Dd@MZ0s-v~%4xl4H4_X7^De%}zp- zk=XR;ewt0B;;g}C#_|QMh^9EIF&Md%nk2mYMt0lp4$72yPhw3gT?zX7J2Z%3ne;W7 z$|*MF|9Frcv#BiFxeGZB-~q(MT-iLbTH?F9msajc z7Mb>r6G)0p&WH8@IjB_^ue}XMkkhZKdAZxOmr#?{x+_(DHmLCqAi#Gbse{vDmMm;t zG73oDi7XMv2n2_^7f=gsBe%&uM=ERM(+V{iDQmY=xQZOXznKlo z)aYr{i^^0`>O@fw0}e}xCC7NjL;FAT*l^Q?Vp>oLGo-by_@vvaYy8+ry&&rMaR~k` z)6W?ELkFHO4)ai?bO3~XwuM3yHa|J~Yd%eQ{G`+B>VH#TE86zIj`ihKM@A}mJW=c5 zHkd_yD9VSA-ti*arpAP1wkg{~2*&)Hi(1?jr?+X-2cNLtYU z(AXJJKXTDXWnaWdNez(8p#$qqP41F=ESG&Fwdn=Z35_iUC;{XqL?3CCT1CRI=bHKq|0M(FITPw4!O7+88$Zv^C7u zC;f2Fsk(#BA<^JM-#zEmd~4cSfY9b9-3`T57DunI*iDer)EQ1GAI=E=dGLI(rjYh= zFk7|i+Ita8CIbG}_?wN>e4Qy_1q+qm{EPbD!CH9brJA9 zD3BoYPy!?z_4>T1*XJ^$Wr_ts?{5x=fBGDh`F0pL_Il%uV7O5ykD>{g~OC9SspOOPTa4r8X4_LYd&C5 zpn~RkJnb>DWn}UFi=8(t?mJ+JXsq(<2b1o9tpF;9J5}9PH=Z85;`e+{)!r2pRvQnG zR*J@d*o=|2N41n66-_2))2#Q#+w=_1%UQ7CnNHwCYy1nM{U&qJ2>lvO4qsS952fk9 z{K7;Amvn1oQU~g|#X)^iYlde1gWx?m)y1*yP`=1!T<{(2YAN;QRwfyBS^TYnFQFjB zngD~Jy4ffqJXhQE4(P)fnoridw14|C&C9wptZHo(CKXFjzAm2Wu}h2kY~r*f@BdN) zx>_^I=WN)DYKZ@VoA1sh*k`78a@39(w)$i;)mI?jkmg3NMg`!zv&Q0Io&}Ked=%1m z{XM>gRxOF#JvBxy(B zf$}B&AywrUP6{ua3Q!hG8CYn(+zO}6t;8y#iwWPP2Gwl9!-mRBu0ZzYh|Q5o^Ftqk zX<(rw9x1;HjJ6}3Rp)(d3dIDH~Tf!<(a`Rt=-uCSAI zqZ=!S0zW2D!0w)&TbMsoRgOOb%JNx4gs?4)%_9Hkqg;k52~*@l(rw~CWcE!DL#OaB z7l$B_>js94p;vfhy?Xkh=r{X};bbjc7Yn_mS<^?EJ`;s<$)1hUjR+D(H33|Uc**Sq zUU)f5fdt}|1q%S@L|MyZdEhgfCeTKT)UP;PYMONyO}bHPC#WI0C>@9uCV%_qwB&Pp z0%%v*5milN)GEjWD!u}8bN?GJ(!k$)kvt`1O^)hLJrE|x;!ljWp1ZNYAvGm!H82;R z!@MJ{{@}jKP=S=ECoF!TwFI~uY{T8kjSWzJ^_3pjP;uOGqKB+TXXKEClzJM7COmL% zsWvLFIpE1crvzUtB_f`{eSRqHs6$Y{fQ%iTr5#FXO^zI0HPo$+-)Q1S|0D%D=P%Dg zUTpKQ#X?EsK~*>_^HjLlB>|BdvatS{PChbKs?XJ` z2?&UQYPi&Nx!}n4$Oil_wh>7y4Ln$sn1cVcntFH_%@~yCWHIF|@qQ~^)}WU8K7Q&E z!hFJMm-grJ6X*UVEg5~j9#J8+{TR1PGz4Wbs6Vz(eBs@~Q_}A6zR-ww9Qv{DF~RDU zLBOUlY4;+P_zupR@~?aDH}FpYV=b-$^po{K`yx!9G^wly?1l% zUo9<+$I)@r0(emlQYGd55KuKD&~GrGyvp5G{b|()(h9p+RMUb`^`&khiFOs?=jGV! zo^x4nu%EJ!QM8lfEDQVNj__lTn6)9?YRMib)h=MKE93W`f}kVDEDJSp`A5_cm`UDF zA`N$qkIC!UlmRB`By!IymqYJl+d~C4O@u3%cSuMn0>IXVIGPU-nBg~;OK4LRu$Dd# zxGR}Xt-b~tQsUEW*4TsBv5wM9hDy}WuKGwvYxS=VdUvMGa9Ap@y9eNe$h5s?beaP5 zra|FFI5%_4rsXte0ZLXFo3GUdPz)(%N=_xggarB`Z% znALZ76q0c!QS8TLnevb%BSG!Ot#Ds5Wtp=#h#I>oqthEB1isA7uA&)bJhR(*Q#K>r z@u%N%cIWlS!x6h3LI)Q_&A?aFTeyJAN2k02#F`dk#KWi=O4Yc<-`D0ag7~B?b!&b6 z6hH!biql{yh%`*9R7efKZVD|_74h~+cjk||dt1iG2qH!R$2;;0vm1boCXu;rS0HIx znP)KLs#$Zuho^cUT5^;kuGnn>;y-+Nw`9)6H&@EixzRA^_@|zF^7S~98cWycbnrA+ zEv5pxenOFtnQ^?F8iMmehn)7tc3t6O7~sfhfR=GYsz~^`-wwiLhxr7-;V)K7G#4xVeGd9NmgeGrw1*2g%QP9;9sdUp^Cd ztEHZ18}UyGj7beQ-qg_=W~^#MPYa!8TL+X-7+q1y0$}|4L%V!n9SAwqD4tMaACTA^ zvt4Mlg(${08!zVL=ub947B3cgI8b4`*e#X*W)^_(19g@J;|_T;$VnT$!`&k%9tcn6x9V@sc` zyAP7Zc4E1Qymy~{G{63qF+6Y?1>jV)<-=Hr%S^_P)A@v&RE2)WnJJ02Hl(PC3*uO$ z)uJWzO+P1|)w?_Whejnb$B;h2Mf3_M)eWy<4u%a966(FO{YWQ&oU`jOFy-h}7GE}9 zU4ox~qY_6j6@$?Ke3z(a8|VQ;O5FRv!d`mH9w6hRJ0LM!VY_=R4A7s)0GMddtKA8h z^|;H5f5=S-@O{e_7|V`3y?%N!WSPSk)QjA@xG#?HUft}Z>_x!k1z~fsmii879vkj zS{`v%+>005)KDi;THxt8A55Lnr@PkZtc)pYcADeqpOUKdZ;QePsUHzcJ;rvTXMA*bE+77**RyrB}fdnb4L5+-ux*dB7?k*Ak|?DOZ47l5Ql(-3uJd9Hv~e&y?6M|A-rUYGV^_VDV zJ2XNi@6LZHruU3+e02&ZJ}IWF2$x;uh94bZV31y}U2dWg6OaqXH5N8{!ybv&>S(hp z;ENxCHpDV-k3)NVJjh3Fepk#liX>cE9?v=19G^gQhz_~BOwA;{60aH*D+Wj5PgW`b z&A$QBRxJ!6y++cw4^C8Z7&l0qY*{O%TK(v25jt?I`*S>~-+F_aCl>c?J-EzJPmq-} zD1Ip!Pg{rl1Xx~j4J;lPZIenMQHZeVEub~Tk56F`2E&nO2Q)cB%U4wU5n091lNp{)UNYlqN%_LyO zROZEE-AbDk8Qp8MV|P06(vEWMR^)yn%QK?rU>=tV19-hhW=?YI?|f25eRJxUqH&Y- zLCk1zh(pwTxqEaK9)PQ|a$Oo@jVw|dPF}=g*y#-_Ab^L&u`gpJ4tlki4DQo@$MCJp zgd>wgE|P4jLc@b!>2qh_eXM#SZ&iVsGCh&a+ES=suqh~X`Pme zUA$pz0!Eav&xfroDoH2h2NA$NnCI zxAM>2TmH3+b>#T_rbw*rgXWdc1(AKvorL7z^d?pied6CwZ)Yg1zO#)o-o08CPKO;o z67|R@X4M-4B|Jt}{YjAJ>5is0I6Jl=w;%7c2k^%zh6r#3@A{|56o~AbNtVZ=$_`}F zQ&W#=KIRdo4Ko+VxB!+M0d@eT2EP1<+(P`!&&K4zF!P}QoAU_+Cei1=9}h3qaE1wL z)&&x+D(FYMcS-KcXfkPv1W52UG7VTaJj*FadeV7J_u>yEXTngj<{}%T$X3QK0D-+5*Y`%+`FW*v~9NnU+XA0 z#gd`~eZ&YF4ET6e!x@r^afLQ0dOdV>-@h}rT6X7x%zYM2Np|FWQ$es3AprCzqs5}U z&Jvl``4az^r@P;@;zjhhjDSpN#7u_eHemW%nFqbDK6B3C2#>#(=5l%O;$JsJYbsQa zs_1_m3yaLG)PaH{1bKDdB}fxT&3)g4h)eV(R}(GOL?+m2LV^haAMWQ|jzZc%Wz9v< zftYZ>kte7dGc6@tD2iqJaHT&#wlJz&k5AwoIjPm6kX*Z^#DoctPxCX4c08uIC%{Z; z6iWX3tTcj37Byj=XbM-{t-@6X+)KwS{+v8}W#b43W-Iy? z-oTYg*Y4y;K6@V#R*>NE(A^)C#rKYCV1D|vB8gD$n@R_Os}_x+<*p_mN9L0Qmo z#(BWz$iJk7Y<*+;Kjbth&1|q>>!hjqm+gQ1|L$4`snRRggw;qY-H7^mC6 z*Uym1YAFr9%0dTIJ}V_v$Y`OWTj+y1|EDD4WaD7|pPE4`fGfCa%Jv33RR!fX+=8-*%t~r(LIfzr8E3HCmUMe%md#Hn*2Mv@sjrTa7DFG?Y-l63&nJ zK*K-}I5^Y;KtzfGkWfdX7Dn^o#P|h(%zG`kf?9hpM9|$mzw?M&p0Qeu>VIUYo#0)mUV938w0V3OXT1Ut;JGG2DJfzmy z06O3+Bm|)R@^YxvTi1YU)FpHX;6Y#P;0<1!T?RM6Z8)=9()#nz8%c% zk6jO8gY*QuLIEg)BMbtCyP-1N;nq-B0BUo9o{Bm^%NYv)6RiFxfD7=~*#P)>`2Jn) zuk2riVDR6`UjmHh<_=_U%uQI4pR)ky2Bb=O|aHJdlul^KZu22Z- z*u8oG+^ho};R*Ns3)sNm);7OLSi3v(8o*&L?obtlzd}$Z{J(9sP$WPI_*g{XF&_Zx z0)To!?0A2b*Y|dY{&s)0X8TSP=A;W6!nMi>jw6K0+6omP=DY5bo>+H z^YHjQ{PElS6m`d{KLH^9un1eEfoZ01?!}|DRQ~!LWb7x&Z#2ssgt`0Qi7^ zxyAVXfCd6J2Jrt5HG=*bS`DZ*%-!j~y(&mBY7k`M zwkR=k^9k|*1^<88VQwIp7t~rChJ@Jtk<1^v!LLzsgu$WO2shZTw*{321pb!~HD3@1 z)cfIv(&Zl)*bOyo$lura3qw)k^v^yN;ShxNueswF5(a=>UBTY?sH;aIA(RqO18NQR z`mJmLFAp4nM5O>woc#ed2v_`H*Zi0tz^nVq^c#ta0C<1Ff1}3$UaP;6D1aC8Z^Q=_ z0`S8AhA8Rq!v75g1OU7UC#Ws>KLUgSyvX11AN@nzU0qQGf6ERqWIJjVJfUhy?aQ+J!Mc_sFZKxX50`35(Svz3i+xwKC9b4uKaO>Qdql$QQh9I-oSWX2LPH&x*8rfxk;h)K-wORb+>FmU<~5 z)D`kLHTToQ2-_%MYl%gW?z8r$&k=(Y6z8+pD}!Gg3Eq#juxBy(*;SMr1qOVS)r+=I ztAu};aPt`DL8nRbdx#%-LVyJ4O-g*J5?(pIua45%!^8~i*vx+BmN7Ju>cZ&g<`7nd z2~(!*dw?Ua%S4xZ(y_Gw&j(GAtTQ1_!odIx$;84B??ua7K_1yTs_ z{2+4~%_T4$+s5!TCGHAbcHM1L;0P&=8+?C+v7>V|+A@#3z^r&kxnHzcR1*8_-3ai! zL+FhRep%*x8eEkSVzrdn^|X8f_XR>{D+4F3E`)8+luuR8yzb#_0{#6ESy-e-8QLQf zc9CZegazRqJ5!%^JY*Fa^qTnksb=JTSyPt3SIm7J2sN9FX640~RsQfs&IZ?9i?4sI zRL1Z{!Qku~f)6P+OkLS#sZewICH8=YC~N~Q1Tt`JZdS-}7GP_)TSaD#&vB_W&ov}a zK&z8nx^o30jEuLCcvIB8SV;JW0Fb7b@>32hk+MwLaKYXbITYh&-t9|^ROeU(ygJq`_uQv#=*wC>G1(Nx&TTl;eLrJ5j37a}F}j=9if9xGE!cgiIOOMmjS5AChU5 z&}FFS(B}k>tQ?O#yHqE4``_JUXY;ax+bVr9mmjpo#&+1}r8HlKaVL3j#J&WePBnA4 zL$i!8bN(f9pKt$pg8&tLa*odhi>Pl7G&TPT6XQvt?RQnSLZVHlfDM@eipl56r zk}0T08{U|@cVm?vk&2>(X$-QyzoiqWui{w!^dK;V=OK_I!H6b zgN7LMA7JJn_s97S)~dj*rR}Mn@3S2f-g(=@oHnBM^?H95L*{8P_Y6tZ z9+nHgVa>$}*%-v$Gjw>rAQ)ZS#8_JBAO`E<*T|bzy*}QX4zHvwPgkAHGpyoJ*a}Vm zPxPG}4(QjjOIIDv6vxM;8Cz)PHJrk>T%)|oAM-L8@7uHi)>P`R^F|Vq%r5y3Nm-PW z2=vk15xJ393mZ?P+!%kTD?MD_a>eXylbC;^LJou5i?ggkiE|{>O_N<@N!t5p6vcKb z@7J2l6GCJCX(TW{#J-#D8xM#DWgi#S556%RBz@r=0^*|8P-7Xz!5EVFEJ?Ss!g8lP zZ|dOMp;$$%4?Jxp9epLWDgTWP-ap!ue&kHrhWaS{qNVbTSo^)WtdvRPir3YW2Csid_u%u8VAX zmA9b=8{gs<%9I9E%9xTOAJ@k(M4!|A{Kli7_%(z9ykD>z%!v~VmST1vCxM^=*K-tZ~Cx8oh`341e&p$g^m zRrRW~gd<4CZeI)L!BhgqIvP-V3=#7qEtDmjJo>p*SuyqmL%Mp<4fVGs8u!3D2>+%# z@r=RkE>*sR+R+qnv9{RjdCJgT`j+K%QlF7B!U7=JGdzE0N=Oxf-jGZ>n#pW&dGd|A zXgb~K?U9B_klhtajgm~kOZ5O=CH@atf!58oLOIl@n(lC?9AG~QBh_8Y>(pIMKFKDF z!|eM{vm$c)9GXSH*IXt31l?_7=9d}pbohxDhGiW_rEo}`s{yU_hFk?NV1EMaKU>^; zJ@K5?I&Xh6?SSWwF%mR-M?dtPzHewB316t}M;3CP z%=AphlNaYl5-YFhb&au79*@gf@dQmLMKHa=1%YqQgw>vpODTnx>5Wp>mlI^Jb;25| zR+b+1yv0njn``qP;!0@MJtp~5|7Ep^w%C8xdNPSLj#__Se5ysZ%h$Y&Ctc;_bmU8^ zQSHO^swt~pF&m0<;|Cg@ePkz!Qr9nLH7$Zfc~c|%7|GD8NK>^|-f%oj*VxB<2Cr95 zO&LEHrzveb2qADu9b-FuI%ghV1We@FFIwJc%^f!Pr0uJ8)AIib83GEn77o2ln%JCB@zxeBMnMQCUIw2(uDM!o*fSQ zOLRq$X%Vy8-jV<2XBM`KYcutRF zfa^fyTa;7pJbR`HW@{4f1eQ`X+&z5}D&i9LEebmRpkdBIRm1j2Az8`^?_9UY#H>7& z5`t4!3-NDfE(u$I1M*6Fo@jq<(UoY;$u{~7y!qZ&UgMJJaKmf$+k1}BqrOb9E+%y{ zyA%8qT_!IpI@)(V(tH{j7a}v55_3j|+bNhIUf$+)%WjX8yv{Tl;=F?d*@`;2<<9bI zzD{wHv#f~Y(EsWO4Hr$Cg4VinC_ckPv)JD=R~okt6~^mMsoni3`;F_mhO}xwVivSt`}a)INA-m&vXL{ z(Sc-vs@Q&L^z)@Tv7vul4Hntz`VjsfnFr?Rn!r}Y1iYT@4)N0uEvVO{X~&>U%rbGa zMQoticvjx8%-Inj_l#$crfJ3ZXQavxb-IkH65-WU6+jt&)ZORgPv~{l7S1oxV`}Rd z=u8u|_CRqdva)o{JTXd3jfvh}OyD`*a*Vo2Z4j<@!UJNMNw&o=lJTNYLG)w zEpVJ9h*Z~d^Z`$Z%CzFqpiaewEe{U7yG35cma#POc+g|`r>Y{UTi1)4X!=!-i1BuU8vVg`|VY0S%adBU&AG-gHX4=mJ~=y0Ad z3H_X?wJfqy!j*y@4&)RB#bhF;7C{p9RygEfppSnHD(N2l#z&Ps8q2CZ!V9YbA#<{z&Oid_ zx~+S6r)O#`aT`kEjbETpIJ?Sk&HYB_%i>q8J+uQhDY~@4x1#hs+a8SM!y_WAZ=X*; zIw$sK_1*sb&gg+?#xb?`Zt_K*M*0w%#N)G{ERYlC`MX!qMeCF%W9_M87$=tvK4X9M z4%u*L;VwgJy%+a4dc{W}Xnr0=Qi1Vg64}W*OovB2L$1x?MUIYuPP!kBx0?7vS$DX@ zuV2zN$*DG+la%|m3*Fs{7KLBdF4u`uv|8t)&9PpYz)lKu_|%D=#K`hqUGwkCeBmVU z4p1)0xJs{4bHCRRZ{$I)3DIVLPGNtAF2Wi)R7!M=K~^KMUgk7BsRQnKQ)C>p*tI<# zlJ~G7lRDGO3p~(|6ZrA2j|7H1%|6riHwu=HNJ4wf{IF5GM%TDRVd3RsrSc&<3vwJv zdg0j5!B_)si?>XSE{|(jmFmmU({8RNuv>fkJJnl?w#0(h(jB4!ZI2A?XxD%Bvefox zdS3|S247yn-+{V8ah7{)g3h~AEp5Bx=0_Z~Pvcs37G)y~OZ-an4(BpI{b=mB1K|fN zaqXK~v~-pZ%u`X++7}CR^_-S%l$vh$A}x!plAh|7i{|0_mCDWIg|oUlk$2azadJ;w z^a)`nJ~*;xqt&;iEO@=4Vb_1yA7)MXd>y}BXG%AFoJqIfS|yw7;ud7w&z4&V5-0d@ zgx@9n_3(vFT+N!TqqlfNeD_L>iu6DvxkjX0EOL$qaze~0B2X-ZmaO9ATsXtAkW3Xi z`%wft$jYvL$dvFi9WAJjv+0bO?Yye>iTR7fHe#JqgNlCP$OPMkhR%PJ&I|O+lpbs= zUCej+O1J*0Lr?;<3|XqXd}C8qe0i{scj?!LUU~$n$=>D_SNj&*+R(cboi+BvUcNRh zh1>f>+Q%2GZ^ndmrO#T&=}a69a9dU|S0mGhr!8(?=K7i*%?wstoW{I&E$<|KQ9rovT4-+XXMGkSH80=4~G9@}xaTV`IpCd7gXZ|KL$`K)ec z>lhN&xd(hdv3Re1o#MgURp)$Jv-*Ywi+BL1d9GtpD~?D%#S~8#kd9bz+2CZzg@Mb4GX z+tx11d7QSdqxfZQrv0I-n@U|o_g8H~zW6az-7as5ODL%_JlmP6(*v@6aw!AfUt-*~ z*_DBu4*QgN(RVb_%x_n#Z;!lK++7YHgf%tcQt%S&QJa5T;}D;FVFf&9_v21{&4O8y zx-jgKO8~6Itx7E@ExQ-%X&GlGl=f4#0KCRhKM zCl(JmBhEbkW!$Rz!#jt2Z{34yrl~ZFo<|37Aht@lTwSKtm$;X=3CVs$|%Z5x>cq&uAgoc(*4+;&W2{RoldHJ;rV_S zm&~M#53|D**w)^I*si&z$!8c=KzC+wfQE+4*xYcu8`8j2pkmScbUVJ#76+!z5p>5_ zHT0<%fxXnTguEQfI(Z@rpO#F&2;59bl;dqi$JBr4D1Mk*G#v3-hu#oZ{4uv_&5(NU z(X`;mz&n=vvsuY5@o2T%*Zb+UA*YH=K>#!jl0BWr5srM-iVEi}kB8ng$_mPl5*3nu znO#g}Drn5Ub9@#yT8{|MXBQSs3w(;^NNW~NzdhPDiOHTtpGVpzDsry_*HS8=q>FvV zxI};1qVIq^w1x3CalJA(b%@ADI6vLcf|ICRSv=DjUp)RWsB6M3RdMB#^ibITLPO1D z_hAr|T3-AINkv(rV>zv$G67euzCDbB_8}7~kVl^2!s^IJ8_ymI-=ujn~3g69$^Qf?C^EN2;23cE8u4(;8C4^mu} z9`d~Y__eU_8#mxp1xTlZ*FcN8Fnqm?bOx zNp>pRJ!|w+8TmK-R(sAmL!xhPo3rPyXE7v%_Pkojq;cz+n(gb(Ezr4#f< z_2z$i)H-D)Y<`D7h^2QU@G;=04yGrY~XuuZRV_y**WUwK*XKtH<F>S5Ps|7IVfJZ3(>%R{}|1Uf>r0bolJ)|CoK= z?W@JsqVpKU`C@N?8Dm%W_RzW+KHyup9vY&5dkDS4-Pa610H`~ z*wC}oXn0su>C4E$*Z^D`o4Pm$*(u^n%}RX&j2Uy)p9}-sjwsDbgWt9LFc~_^Ts9vw z9Etd44b;Q6aCbLI+fjos*I0AXYVcvBAl7))7B7G2LQmkwZhgYh^xdtP1V`{;mh5O- zBV~;gB&D40|) zt9nT23-L7Cms;%Br8nDfi%UATSO>$%_j;_l{o2-jxZxa3vZT5L&8jEs$1ouJFbSOw zqvn5Q@hcAcUK$~KC?ma4{~+%VVc%Po0tCVLrgLIjx$0Xw^TwoxtS9%L4&Zfti4j?* z%YSjQPwe%P8+3a`)=0=jKrzXlbZ9`n)Dg+#Wos{-f8f>=mwp)Zp+cSL+e>+xy#>?p zpk}q+6ti1cJ(UmGkwd~iLOvZmUjVUB)^7^J%w@&D`6XRj+&FmaqT;EPr zK+8FUL49`0dk^WaY36OA@;l=sUq0(%lZ;4nZS>iP*Po_`s31nO3m$irBothQC6m-P ztS!O`mVK7DilJl!Yt@UnejM26>tx3ZVi+2dEF3%gzFSWN%uanKs(d7rXX9~Lsuq8f zW+7-t=WJZ5<2>Pq$f#ZA2L+6A)@H0T(HgEt@Se3Vw-Z6!8J#jNj+T}AVmbunZ25M? zigrJpwHi098APvVShTgsU&SY1(<^Yj|M2K)TFkU#V{Xljd&@xz$Q$6>8Zl@WPe`9D zpSs}Dasu}}uEq-i?N4}nP@EjaXc2!Jlg^U{fN8yS)XKTulv3E)Z|Sg_J_;0=oIC== zTS@b3N!B*{(M=K>v0%q)GzH9M8`n8)946RJgftl+x$rUj0Q2ruY$Sa>RkMiBU+U7C z`GC!BZV*&H#8?f%G}$vf8IF3zVwq{Mo~>G(?YN|MHQ4d$0pP0A-!>LTI}m?x7wc?N z&>NeSf)^tDAj5F{>tH}P>!U{wDg#n(=>G2tW=_+|W8NI#yhuQEB^*9@S*U6ruggaJ z82gf~9Nv)#omKQW43(d>^fnShm~1ON;6Pr&%NX}G~p1@mTbnoe;}JatzwjWN%_>3OF>A;CvJ- zH#IW~FHB`_XLM*XATcmEH#Z6|Ol59obZ9dmFbXeBWo~D5Xdp2$IWaMpp^gD4f3yWu zT`GVOK=IUf#47zcyN1UX70?~`~Pdb zw|cG9XIJg2uj;GXhniejjY-4|VgiQPr=VzV*#2z5)VhaGV0YIF*ATC}Y5Worq^8AMg zapDDt8@pPW0Th@4vJiVP6opz0;^5(AWnt<3e9V7d0d%JH01yuk*V{kB0U~x_Co5B9 zdw_zmvnAN>`9xD=TYwtG)C%nE@n0$E_${5C9e7z-+}zxljqRY!5GM;kfBLroH!EjL zfGQXYc5(%q0e&|OP&Bp!|JfNc3N=98(hB;gT@7OH>}Ko)20R;VtxUo8(B}vjdo!>T z;Q4TXnv6U^$pLKtCt3ba!dt*!cLM-1gZ@tUSM={hR`!1c8=IO!>>P~kJ*@040OnS< zV1SaOJhQXA^IL$iz1eS~f3YnT@*HpMYHVd|Z1PO_qjF<_q=*W@__@Kq+Jl-pSvfdE znW0v;zguMao#y$LCG5?_Aa-_OduJ%h@A|~8oWQ2f*Y3gc=VWc{A#V0we*tqVdo%Oj zO_;ejuxQv@Il6#l#Q&l^n^69-S%94Z96)X^Hf}Zm*bxABH??H>f1O_4!vXw<6ZG5s z+<}jm1H=Jf{@euE$I2Z1{DMVtlR*opQ=>=n_0Qo{jXQXf7$q12_p6u&)dudVrK@j z|7o{^N?N&t&6KU2O)dZ2nLq6szqMv-We-+{K&^g%T%MzV!2j_*3(VB!`2zxdUd%sT z#?WWAIsY-n-x&O?r~j@)!rl~O_FH(Y9Gn1SCnsYMl;_buBMyKU=vkp=VD~>(8^FSB z4{?4D0X+BYe*-XwIHCL=GdC-MMfJDoPs9#jQU3>V16Z{GMm$^q7UO@=v(Mxo!~_Pt+pHBq;n*?M7uvq*HJ_lL- z3vvQjtp5d{qiz0y&%4cH|2JfN&IGXoTl_0I==mlbfBuG?&m}q-J2_h!+nQOKoBxaU ze2Viw@c9~^7y92t{x-S(3qD_l+dq)?xeWI|;D3$L)Wyl^dCq^R?|H`m!GC;A!C-f= zDazs;#FQ`Cx-Piwx>kh9jcNNUKm2j}wKgl$*CGQX=RS!k!}Ub9?5riZ3dzM@kfeci zr=qCie|66H`E#$Wda?!&_Dd!*$sZPECh>DmmoH|Lysn5T<}g0PJnqmfp9Dm0RN}^j0=GwsU;4)S(e@S;#fUIla_6b#}GnNG3Ah9?*VvXi< z0s4Jzsp~-owwH+%ju@_*LO!`FKFXk2L2~mkzTQ10qPBHbgk=)S0X{~1LB?*eCB#4N zhK-{qh&wHJh9b-&(#wp0MN-wjqj^4Tcna@o5q@oW%NDh3qLnU-(%bSw*_og3h=^L0 ze|37bsV)<2xvI%Q2-6RHurfe2@DqgulsMXwRM+lE&1tb zpIJIPjXsKD#j|n!(zK-*_FvkIzq~Plub9PC1S^vW%e5kEn&zkmbBkMY^Hdz%e_a&h zIe2d7Wyl|AN@n}%&u*o+wb{KR(z(CP|8XWWITfKA#ZZG&D#RQ3h>qi2RZ$j6+TWXp)7CK37Z=g=690YVsvO&f6C6z{w_MT zcai_EoXJn`XDg_m&@z=UDQbSYX}Z+`W#2z$>meB~)k?Ij6Ez;0p9S}0C}Sb-Q4Xs( zJ9ag>2$}*JsfJB+c@JmVDM#5<87+NZc)Vca_*nh0!OkidT;3SeaA~)_zoO;IOjKa8 zO>P|{@{%y$dwSe8mM0C2fA!Mwa%837L-L(tμDPa3SPbqLDd<#s7dQq~S}9KH3_ z`w}ReplxX_QCTW$U4_N&WIDWq`c9`Xk^+m@yH=AUIgp}O&Oe`?B9k7%im-=blDU20xa^UO7fuRybWNbAilgT8jT&>fo46%qxE zobKoFpimfVVHIxLAn^BA=MC-FPXRwZ^DpC~FWj^oq}c3WdR-1dnRH=u^X(iRL!5eL zu`-OIsY~}UVbk(|u`ra>_T;tOx*EN@>!gf(mrcOi-DW0(s1-XhicP7bBBjBL>>$U{qg|*ZndF_L1J%uBmX{Isdepz zo1v|`f6KFmTxOqc7B52mqWC#m{OU$zyvb553S24`SBa@<&359oew|$5k;5L?T_0jb zYMz_v2MsLX8A1Q*_a_BYEV{$bco7`z1#})f2;L&i{@Uh*T|gi$~!Mo75*s9ESl?6 z_OdvdvmhuSkaf6FJy@x%?~y2wpy?D%eaX@5?MrLM|RTXr8w}2Y6v?5&Ag*YOb zOF%LIQ!LRiFbmHjZ^cC{Xh17b+fuqO@`F6{;Rdz3sgo};bnu;6hK%Ycep6(_FzuZ7 ze}dUp&T86JgEPS>*o4aj)wM1c&3Sjqvn)XmyQr4AOqw->3-=a;+~cTZ`1mZ+Uq~K# zp*A;-9Zxeh?$T3SY=%(>3lX!Q41oE%f$?hN)GMh=l>%wj2<{x(S~}uc1wRnU!!JJb z(*@js=PbW)#zYi;vTVw0oEL4p6GnVPe-M_p!>Y7Dr22-Ad=FplHAC%k4QcE{`sZZl zFT)1AhzsbahZKC|Kn9{=6a*M&sroyVjwd|Z8g5w~jCk+FB{GzjN)9=msNgt~<5}$G z(=)p)M4jpKfl>R{0Lj5CK_(&kMvB2wgeD%%^WuENMeH-HzdIHw{0^XRMA{@pGZK*;#XReOH)>zp5L#iJZuY>~JJonW4w)4f@NI2a+Os)zWnT>84Dsp=G_sso#_PX2&D?=XK zaZ(zO!f@!Yt;o!98XH6S2CT5Vf6ZHASa0{Pt!0+H;Kj-5;naD0r8$0)kRAdo?O&R+ zn$a(LLqcu!t$WyQRc)|uG285^viI}r z^lWqHkhug+%Ng#(!4k!!-pJA+aUxCTVuQ1cuvy0i@f>SEM+P_$^B{X)6gyJgu*VFdY_i&TaaN_!?)cTzD5c%< zT{#C(Mg|b;S{eYLFr)y~=;O8+Db!Q&3guYf!CQa~S&!jp!sCod4QDqzejn+B);ug) zPKQZ|+?O|5TQ-%qzk+^Ie};v8!bZ7!;e4|`dc3n{RKM_WMS6<^jcqJ7XO5`sLA3vA zY5HO0sjR^MT!JG;mpzV>3h~~Djkc?#sj64uYg>tL=vg7G#muE?cDl-svWC5P%oe|`U+ENf*vZ3-~UQw!U1<1;nCo#x5@sid_6f#alRRT zw?1Cv*&`HNGH9Crz+PjF;#Y%eu@dM zaP@Chmp+c;=S#_dfB(oF#XVuCn{;CM5GK;(!{oVqh8DMEcFf1;{w(?T4rv2td;s6M zbpEOFpVXZjp-%413mrTqj4SE^l}}|qOP0Ju`eE1!t~_Jtb4^o>i~U070oK&KEpTtc z%!JBdAWZY=@G|y8WFFiUI*#^p6i-O26W7;GMB)>3Dc7wEe=4)q=xt$7{rJ|*v8lIN zm%>>o2|g+(j{}T$xsqf&v*NS)BjqR6TgYfJw(td=xa8$a+d69X525yoaK&4J(K{Qd zlpr@MX3ho~_e?CfQ4=!%QQi^pp@qrda)Gve+9wsqp=w$oxikmPvBLP#zrO|^R)htWClA{3EbrrMostCOl zZ>{vgg|_9ZUB%stZ3|eP24dztm!U!hLRS*q=#rns=A$%IPOJ<5lZv zrnz-kUtY`P_Zc^!F`OoLxsgH|@m&}HZ!;tth$*lHYLPl?m}?l8Uh_F2lUEAyoeBkD|L3F=%#-p_Z^8W$%wq`CL{?sU4le+NFzY$<8!hi2f#4Qw6Q9I`*2~ zjxRq4j^?eAYX=d;y@MQ%y)1OQH#`DRR0^+cP2%WJV&uuP=Y{Q0IjKo}9DBtGQ~mZ6 ze>O06jORm1s<_spWF19lnAp>pu+{R;yO}g(VYowI?to;%OLu42_?!ynNE~yGdMY$j z1NUApyFHkCqtMvMTQbTY0lMF|-;SL=sN6lO*5y@=FEzgGM~mxj!&vo@NMcnI$-E`;nt%;;Q z;#-gm|2ZauW|aWl2zS9XCF3>Yf3^qLo{+uJ1hu$`KeSk?>U%mLTh5#HM-Dgx2J68r z>4O`MNDv~7J!v0HI%cgKY`u|MV`id7g)ouv2U_S9v9xQOJF>*im$oGX`ji%jz?V~T z)8|98}LYE1foeB66PTvJpbTT~ke`59^OawyTRX*`q^64epK?{JJ5Agd+Z zTs;ay-Iunql4An{dF`Sey0ttV<4**C5p1>ms#1bwup#pE_C+vzCzi5?$O{VX#r@3Bqj%xUETRTC-E?qq(J8{{_EeOSQy6&1(%s)zeiS7Gkv1Dz z&AaEE-p*~A!H}-UoQ*D1d<;G~c5J_9Oo!eJq1qRfVYmB658j9;Vx`MR*PJ1HCWUur90Go)~j8Z3Gqn1bKOVAoBCNYGcPro8GT zPvd;q=hk?dAF^>uMwB_jmWtI*OUp?C9qO>#3nGy*5&)V~e_Kqr-v*hV;3crqS%3~P zAK`aYXz<=pVm)R!geyfip2NB72w zCLG1Q7?!06gA+^X^3o$YVKO2}eRGs2-8<$^Uuh10z$n?eYHzU~gvl5lmZ9|~h}Nt` zF=KP_3te=nf9+}?sG?eQXh|I3K!3fk%@gU2v0I+K7L*oRfUWXg1KSZLnzZ8LwNyru zC_ZW16WVf;rU-5Rk=jM+z2h`i$}4Nv?d$F!`dHk0Z1$ttQ}k){iKsRLRIv9fu~lCu zk*$#nRuD_nPBJ{C)kV;7pY&D` z!h=6~_RL(Ku(e%78%Z4eCvN+wUL8HKhK#973*j*X@*P4-aw)qR6)}78(r#D4g34!w zPWa!>Wd^A|@DFZ;U&55zGga0WSNCqHv433bX`JzD`Z^a=taI`XAMcCOk!5hPMER;! zbnc!We-;4)wy1jqtk~Sdd&=@rI^QWuf&Om7@dUJsq%Zy2dZmMN9&0LJ8#(rVRv11w z(5Q0sM5xKm82~cAZp}0~{Yug9+;N#Fh%AWxj+T|UnO#7igWaDD`tVk?lk-kaGn~6_upiDR+hOwD;n!3;KJ}t$Fj8x7AZ6mFuz< z49)5r1(eGa=Tny7h(hL1t+Wg|aE9Nf5aJuljj5Ma5S~-bQ-;BWH8aES9{~dT(@s!z zf8dPa?RNdY2*AdVo1bZIQ1;^D#O*ovThn;jhRCdG3llhJ2K23dUTaMDBMhizxII2< zhou!Xa_V8xCMC(h{G>^D2nU5!z=cQ!_ox=bgq(IE&4OtgdNywJir(g=J95T?c~NmW zY}f7{CzX%ddq&Y|Qn(^+Sl(1;5!7W|fBr;~NOEV;$;3vyIxeGH*zW0DDd}2|nJy^F zJIpyh@~a3v1|@Sm4dQ3%3BDhQa7>QKbAP%SrS$~$^NL}D%RC^`f z#H-IJU98^6f%m#6%KS}&o@N}c-mpd01#s}Vx_kqWEHhQ-?1S>90V4jz2ICC+eXTx-9(@?7_Ez|~K##fmQakVa%HTfl-Z&q2ct+zG>USSXWY07{ zGa-Q=drsP-7?}nA$}SnGti5Z5X18R0<$2p1)xCuU>YtE$^x)S`YwFI+zLJ*~rBPuy z;WQ~TReRDG`hE=)NI-ltKv)??w|RmV6o+F;!%(1n_Jbl+V@a%54q@9c!< zCnl5QZNW2Sn|(r+j*vL=;bHf!u%Voh@~(A@??{|E{9-;CMfh^UV`e9;OfwFYk1|2B z#V98*_Tj=L7Be5qZF_iELA2zx3qKU@re@OA?=cSmlxI0A1wPIWPP-A}e*p`C&Ea+t zr!_*aF>D?>BKxH)Cl6LzK;-qe>^KQ7{JFRy=R~&38FQ?ALeFPD(f{h9lTqkXg zUAnTayDsE3#!bI5Vmgz&#CP0LcHW75zi=-%rZj$JwOTtI%51r3<@@C!QMG;R6`{>T zzA2Y z=KChPImCtx$(30ym>=Bsv(VVFYpyDZSTy@!IJIFabUM5$g+j-J=7fEK`*=a`+l*-x zrxtgl*SgI*RrXUkF`X~?&UQqN=JKUM3%a(-F>=?Z>1%@bDX)oT*5YZt-b)6kQnK+_XpR- zA!FRvLknQC5B2`7SZDVGiIN8EYc+jd=-t&gSV)=_3MCEi+i9tNwDQ#-e;~2 zY&iasCsfo8`fAy1zpgf{65E8A!_e4?=6pCCj4k2MouDn(fArqViuchYm1gKJ8LvVu z>a0LbI)lWKKDdm>wddfqBeDO?t#+29(n#V8e+4BV%Qyu0ozf%HrxaKTSIDM*M)%ZU z07F%;^n7b$YUeVz5|8ubRpq-kt4Ead*-7eJqi&2m`wxtko++EciDx)ydhmha%^mrv zu(;05vOQT&e^QoVl0rd>D>O*bw$2+XW^GHKLaS0CYL_1%>M?2xlCv_~{q&$6w6SGx zYtJ55*`k*()|Dz#j2JFgOLWID^!ZwI&E8Kgg>D|d?`q56bhxsaZOZl(DsN^(V($yC z)L2ZxhHFGD_iPo&x74buuU3i7Tlddm&|wR?+?O|je_HKkDmEDigqxV|sJ6rloy8*& z?b@b9`a)bR$Tth@qxp~F`_<6b4ikM<6Cq~eFFJx`1S&h9Smf}sXTxld>Eg`=tnp5S z!XaBAj4vl7?$o|N$As-w{3@qs6t;T^ymPV;%4ztmeLVWRd|0QVxH(!(gomrlMn`-f zBgf@`ZXRY|;Fy~N$SLDtiI~!b^Nyh!@*L)QTRX9XyUd9Z^Ev8qPt)V>nX60& zi$47T`18HspQ--aeU8V{Xp7?cZ7{PlOh`1-)JEpp5l&RF<>O06M9d+9+~bpzKL1!C*wo%%L^ zHi1goP7s&6&}b%ibFYaN<^Vw^$FAW-Vqgh#H%UT8j5O~9ZPZu~kK+D9xXvpS8=z2N z6+;VD-XhHOCnB~G{@$-l)dxiky(+OAS*wcM0q1PZic^E%TWPmzhGo^qXq>sau9S0Yo&}k3>3D>p9RU#4KKAT zvD0&S?Qwy$RYrO;qG3)>s#5K$ACNhO^Ve0}kd`Yu*X&#}B#(O`2Rokyd~*5AgwU&W z*9&aYJ2}KIf$^^AwE!__kmovJjZ9wD@8>cepW4|3ztli{>!4<~nL5`uomewS@g^ja zaVA(5n@CQbO0e5BFlYCt#FN{~4!AsmpGAKC4lI*kQXCL{5lbe6l-`$g&W$?4I?rOC zmvP}d=GgS=-Uv69wwmZ5$?eo6TkByM2Y4ri-)wwn=C`rnRsxW&4phv742hJS{~|4i z1>R|kYx~)=khcn1U|;_UsDZaT1VL@Q+9!va3}(y30`z?YTFd-a-zIB=GQ;>YtHR$?X~FRMN$K z*x}&r+*aUPngcN63b9kBej#H$@MS{~%feU7l;+nrGO9PHrAV&JRDYbfZ3xEt;vO4d z*KIq={Cg;kCqsV`0yAG*Yw|ao;|UB$P%&-HHU(04Z4E-P^Z+?QT&&&-kkKaIK)Rwy z?UVvfbbBTD)?m38l%4=N4YiB!1;mW2revVfhXZ%+-uyd%5|pV~Ch}O9gT*8NaxgWf z4R>C<@TyeCN&Anw&T^PsdoJHSmwZ!4YUX|0 zj!Mv}(*R?ODK|`*pt4k)-vJyaFO9v`?aqp7!n(=>iTQ!-brqijkohF6`#qozb)bb$ zihN@D_bHA~QFl?IuyP>b!LOY?ix&BI#zO_3(+S;L%N+iR9(?`>{uzz6wcz>dnDDAB zoCd`ny>5$iqdq!fB7_in3D@a2DHHmdh6ze$Dge?FZ1fW;6+*7R`pOJ-!uQ1Ufyyzlg#^bq_u$zTNI#uS+_jeUq0DhI08~b!Fm(3`P*H>yT1NWdA6Oz z@Boeu%*(pJEYOd)N$k1&`x+9xbq*pJSDSQ#EhA(KN7uiNd*LH7oVV|Cd%+=)Kift) zBEtVtGZqdG{c_!zq%*<+Bp+bED*u(i%7_9T_ARjrsDB;h30zjfiK5PxHMxElBTu+U z+jjg|(1@}>5L6=|#ra~2@vo2ldUkh^HUMloqbw;?(*7OnWR5i;kMq&;cC{uLb=az$ z5v9Dc~4?nu%WOkGObGr1C88w7#VD4u`r#S)R04!m4$cDAs1d@x-Sr%I8z< zKO=A<&02_#9dL(6Ca)|7=k4>o!8AGfu+vr53RPp_^0Sz}fXj8H4n}Bm14RnS90OQW zq?0`ts%UA&Vo)BL7V!t|aPcSKr1++_GYbf)P7L#7k*F<3VkQq3Y>BsG_bQ&aD8sKK z;P%p}5VF+MNWsHr*WjF?_mh98Js+HejdOKfiFMwEv(OfiZlcORL|8M#@P&ZULBIUfn%Dg00;^(@FPY)yCVE&O*B#5c!Lu>J`?Y@U>Jj1ydggC7kLe|zyMc4OWE4S zwq|-TZug|()-z>Ov8gGZnRe<8NR7{n<&l;?;A%TaW*dLo+M31KM)Yhy2Qta_<9vvo zkQgIch>r$tJ@m#j?9FS_Z-oL?(uwZ2OEKL1il1+C4YIYAH)2)guRGuLoCMys&9@Pl zCL-yiUbEt@6q$M1nNQXK=|7MrW@W^ag?Ts8OkZ2xmsBE5+S>)J-6NODjWl`aVn$UpIFk(bgVXaQj3>anf|_Vm=< zf;z?S1DuR^{}8A-0vys??5^CKjXiiq89z~d_t75py>jmrNey5@k+`97^KM`05-rL` zSU1WGu*PIzc3k#*>Dc;j$C4MUMCf?osT+~ z_Tb8`b9hHPtCqzk;{f{Gj7_xY9++7Sdx;)~$KwgqoGDcLrM^+FwmWdpYz|_kfqoJ_ zw)QUKjYXDiQGb>Z{zckRsxyPSot$*KV`i$ZNZQ2IO1ggU-|`QZRsYJX#r^15h_LmW zpXI((y;3UhciHefxhDCEFihz8M5D8!?VyynwG}x{&^iI8Ed``)M4z2gW6%=(c(36I;W&0t&pSculF{;%%qK^c8 z%ZHEHJ;d6AXznQ*8|fp))c^!H+81i4%T{?rlc7&U-P_Q{$~|7YMZ}W=POjF`! zuN_*R`An=d7y)bym$)G?rMuN}zy9S$H%e%9_Uu=Q!(y=JGROg+UjC8`V|~B~g0Qqf z(N77@sxrA+%9#bCNOfkQ>}glEDnbv{F%yJn_nz+hJR=T!1aI3;3xI+u$qcew=TnuR zB26@UZiYPn6-+%(nue;+C!ROA;rj_eg5LaoJ`gr8wF9uV%3o2~ZUXk(xo?j{>{ONZW1E;f0cb*DGYte7T(GtkTEAJWA2mZ~TPE?{X)!e9S1V#44*{{ndI*I?S@weWni$g*l`2V}w4QudJ%2AsX+En11hp!i2z|*#fHxIc3Sy0U6&hlwV{j6eO0D zErc3yF=r)w98#$)X16^h;WFFpQOuW-8?QXtc!O`6izT!IANq}<(iZJ~={um{*f$$e|u z8>eB9J&3F@6nf}}6%qrw=LFBZT`k+-O?fpM_bAnpsgj%uk@2|2o6kHaqE^w;4bSYj z!|^V030pvtF+Q#ooE-U-hNMpM4OPO4lmk`j(NOk3?nQK(nb<)Ls(i~&5JLRykpYOT znX$E=@Po>+iN+cuzG?dE$S$^@vhlEc@`6{zB&$7qCnIg(t3&KJtH4jyV?1 za4MpqlHNkqldQ8yx}kDe69rY{xd3WV{3iI|H*5mWzZiC;gY)+amMKMWqm-;$+$u?; zso@gl^iyG!<3qbe?0Y(JzUppwuAXRPR9qki74Vkfo_Xh2ifN}1jw_;EL{^cc-S5!5 zLxWywRvQLC-Vh@-6*~+~sUd8Cxh5CdXXe5?NPp=tT*s@zT>;}CtLkL4NCVjaMjL6R zr02(MaGCbHg|k&^+JifGc9+(?EiguAgR0^4YS+ONR6IPrncn~A=U@j_2f9~A+uXGi zp#Hi4qMnw#wx!_8*y|Z5FYz`Is0erWbUt)fi9=tDOtI)R9Poa~em?R!m+COSiMyF>TMK0|B?qzS4+yixz#RJg|Yx=7gg zjhw`ck*_a?)?WS1wKpm@SHTwfFwiM?NJsQ$jhy)+_>oq}>pP+NvkGV&voKr1FEC}< zeh)N9NYNspXKS7y_7n_``g-xP_cfwfsR`JAKI0L9tcXk#L5?$0WQ^~kD+5^1&(|Ew zJ0`t26u4MBI8BvO(V^xc-Wc$$EZ9zAtRx^u{8`YFHGWv z4@_$sFfctM2q))%DT*vy{~wmfOvuj6!u-Dm=sB1;S^pnJ(H)W%$7Z*++S2x)zdDT1 z*uHsrr%5~vexiS!vq%I~H3JE00v>_$O837&F97x1t z0MVY)&ty#qASghIGn*ST*m+T+514z$4oJz-uPiC6tO*wi3<=cV^ye^4Z~}O#pPx~} zuZK|(5;)W=9&{NAACq)y9Xz=5K9|G~V*nBLV<@o^5+iONqIkRDwj(-` zA%`Co2uNT7-#%Q;C6QqvZMtWfM3Xu0qz)t(ceobo?lU-uhtP5 z!qENfrax%hABY7bZIz&zY5@8eR$LgEGZ^O|MbUd7q-#G$krYS+$FQOrlJU`R;D___ z%Ml6evl-j3tnO_0{5#@184BVD4=zLy=^EdV69U2=g0p`s4@g9g&j<~h3<_uv55N_$ z-G$T!@Tfz?Jb`fQNx zL5sO3{#nlDhJy~?Yl%UA`%_)x5X7+cGrJBA;qLOz7Est48peftat^<&{xb<$O8g^n z3MU3kDnuC96h#Yk0qs{nL{HqCkZHu5*Be~`=v`|22L0kg!Uv+*f|?UdLq&TLxxN8^ z_6Jdvw71Or`C2 zIIcN~_H8r%wEgtxB0ICup{tPi?}Gl=Dyxa*0e=e{6Z*xakwOttQ_~>Cjo^X&WDi3D z;65s0=LG6E94Np9pA{P0=)Ovga(nG^Ul@#UfxojSf&4{i(fU3R`)mah2%)ZJ9)EC7 zdPTnN&%Tq7e}Hd)t|b;Xr>|O*UsB(G>H@Zn?9zJwa&~zYI;^cq>|p}^*lWm~5p-OL z;2G^)|JW{z`#a()`tx*tb&IB@lEc9RTv-G13F!fO_Y(Hsk%o4RoJ&yq;2%$UKtZBH zc|Q&Nn&6JZeAxP&yx;6Xjzw?oQt+H$`>&CD#tF(mj403}afdaS6jC6cVvejXK?ML3 zOhRHfi981)pe+x7APTUA&(%NDV<4gqvkMHz_E;JcV8@ZKIw^6$VXs2*0JI-K1>BuD zv18XqG@P!^Pdp$I7e-8k=%`TzD$Hjna3d^*V40f3Cs;iMox+bMMd3B*(;~ilr!=X^ z%13S8NM`JY+UiSh=^>ZRBQ{B(F8jlteL0@r#@FWa-J&mDuVH*`;`e>J(nwBxfn0K` zy?y*P8ncQ%Jm(8s9h57X&44{%75K#4>)*>3ec|i&YDKu$M~D4|-r9QDqgh%y^`Oc| zm$ILChrH>Cuda{CA|X5wjLhW{M&JrR2B++y;()Ojcy69S?@X<@DFWfVkW@>}?ewIUh(J}+LY&AB#2Yq|m z{A0HlhReW`2u0NGru(Vu5;=K6()n%+8ubIV_`iuU&KpLvwHU;bcGNi-wa?qJ-hgdd$)FCEh{?FtvI< zbQ&>Yv)zgHXsOQ>#y|vw15y$`Z@~?-(oJt4yRP#~u-TNUcyCm_{UVYe2$Y{|;%Z^N z=DGLh@ro)(EX@eckMVO#&Be&D>c+CT z1-4OG$f1)y-b=!~*!EQAj{g0R)?VXH&c1w&+i8sAyHk{1(S-rl-GfLkJR=e56zO`+ zRSC#@1{B!JS9GYyH@H*U51xEw8Md<4lgGd0-_+!0xmZepX=0f)vglB;dM0TwP?e>mhk%$dTxopvsWlX+BZS^TwQtj*Il4D59qXa{(dP0n)Mz_;s zJO=Z`m>rC-pFNgUb5{JCMLj-oo{)RmukHX6q~rcL`!LY8uPuJ~sZtk$3PqQg2RcJ~ z`gRFNEjwONO0*&g179!GA^Z0k8$n{=@Z{F%zdK5W!Q>?nwPW0vPrgE=3^>rDq8nyF z8#r2LboocUp=lok%-Jy}YK(OX8qWDoyVuLh?5@U2eOjPMg@bX69~^tqh~y*6EabCNC^%&QcXswfni&YA(;p0!;{f7$DTaW_BR0vXgrS4o?xIDsnKSU5y= z#Wj%*{p>LuwGf&0VlgFCZDOL)FtV-OZzO7|iw&}Ulr7Snr3V$a`@K@P-<{X~%JM4} zd`a~p#xJ(|^~I9^^OU3DI!2KS`LL4iz-{ttq_Vb6O|op-9O!FJ*pHkxL|p;`>NJY= zo#oI|t47F-qIK{II?%Ds*498fAtjXRo$|#s)+2MxX(0@ z*;1fYkYO|<9Fdw|23L6dK$pmhXZZvg8}jMVuEnlX^rsQu7cQ4`#_uMK4m+x$$yrzu zan?%_3f$%=nX`{J%We}F4AcOhNkZ=Z{fnlSZ8^U4ftv#9y=j8j7*9h+hRp+y_m@fb zpefJ0zZG_Ri7qj!)sEI>CVpjUJ5c?3pxbIbo&Q^sktps~c2r(s`_~ee9Pb*%;UW7l z`Lc+#khtqgXba;vp7`=`MMLcp{XEfK!x2R!j%lo)EI}-|*@NVrl{g%r_RLPs=8}mo zo#MV-3LwFlqi@B_bkF!*lBcRi4IJv{rEmzmAg0itqADh6tyU^?n*4WTLf3l%L8NZ& z4iwxCnWO&R0!z<;eS=KPYr&d3i-GP|#cRB#_BL^z!F$x-*h#Qh zA6}V`m6F-`W4_(}w8nWCiK_HMW{(l{cf*vFsuK2J6@6=!iZK*qa@BKK z>v=eE)R=NGdq3km}&)$l?h~oW*QBgsUOx1T}(*JzfUp1hiRi z{B=?i@s`vC;M5>s$w5S>SE5&>F%31OL7{*eu|Ah?^Q56WVoCVVzQe@_xmsVWk6#^N{5Jlg;00q2wOTMrcYW4 zmRWpEdRzr}GAlM?ma)%zkI|8IPih{jU@6DD6qA`7KDLyGL*@P7`kl;lH0kQ&$ds;I zwosDuhyyRWqa$En0ve7fbQBSaNFz{W)U+@cdjGt)6s4SI>_BMt( zdG%b+uKO*L+PVeyi1ALO=wNL?-*~H}^&MTPCUna$LqO9XJ&beK1uBDIa?EFe{&{3Z zFPw`ot3(LAZ6YRq>;&V79I`XhYWnzFN+%3pBbF!uC{=x4SX%)v#uv)>eQ)0?CnKGlQtBHYI=JTksOC&7L>hy*j$^1jQ|j zvL*74<290+Me~^379jDo!L$WcL^(>eEjsBhbDX87wm|*YoJIaai zgoZB;z=uJ@)%skkc4(x5&e~YCiy96!hO64ViDu)b4b?m48&v1mts@FEY(EZAks=lR zsImwXn`qT+#xGepH+oGf2uYE4&SMz_s6bDS&{BU1XXltQN~=0L5%YCLQPwsBzbh+se#Pcxw;u@T`txeDCzFLll*Y znooEL_5ioEMJ=BV22a$}Uo>}l@#KELT5>3iJ`5)0(rd%D=U23C^mJ@hC0NPp;xTnj zGSL%plH>;@Aq7g~7?>;SDlo3@hU!#qFg=DBZz7W`QV(|LZmr;8m@2limIB<7fAF^f zVWU-NcxfZ&`nlw;zd@>g*O=?Uut=asryT7|Sh3?bo<+ zz^osmB$2gdt3s$J*bQ3u{xIw*zMldN;HZ$050@Hr*vpBTsX@3iQ;JYKIBcj*t#A)o zy9;2XJDkE#yfGf7xfM8-5M@wM3I@uQC^YFfBLi2r?L${U=jZZ;Mowh zvhl4DC7(Q?H9$rs*G06|#bXw=OCk7R#?Qst{PE^_@BM8sJUcJyUwh>@U@MB?sW|zG zm(d{1R7T|`gC`&x@}%_!Kcs&0F7ea8if4ec(g<1`*Yq&}P8a=re@^q2gHkkVF{uEZ zCR#{L7jk_KP{%E(!+P=Esmc%syt{q$Wob;8hR(e_XInKumQ51!K6Me3vs!<+5O=+? zst-~QcOc3IYw!~#DB>s)t{{zQaFN&PuEt3vOK`C(F2=_AP{c1e=t`%P7XKM-$IfRO zeyDSR(7&wnD%>1_|Bz=G1{bdLJRua;D#1DHFp77rFOxsXR-hWDVth#kNc|F$)~#P; z1M?o2oV<*RcVUU%1gyO-_Ex7R4OF>@T`+!oOCLhL2WED5Y=_iOd=8WDcnE#uD zAb_rIlnP%;HaoMsagYeM8>ob>zMMrjn;!lptu7G4(qp4s$q$(EievQ*Jy4+-AVD5? zzW0}0bZIo$%kcdDv&Xv%h<)GLH|I8wAjf#qYEZKM3?N*X+kY%z=jNM2&`-0fAX`h5dR8m# zJmH{V3(d#CH9i_NpwMZSOOKz!i=S#!wh~dsq?6^dOJIa7>m?}z@YT(!r!x%KFtMIC zZri7yiL*Jn#(YqVE72ufW;IPJf9NvZwW%bWc!E3$+Yt4S3@|#I6oy)tsF%4#zrMSP zj`GZBi5RxNdFZ`S2e4xHkWW(T&1$KCP+8_l2wb00dhb+~9J*y!5Dd0jCD!McdZ#Qegme7(ma2;7bdO@kG(sHuKS^d9qA z-Qn5LQ@x9?7K0;NN!K&p1Zg~#f8HDRCE$hUYweiQpKnh)YI&>E9fVa{=!&N_ip_a< z?teI&M95?Jy@-X-PKD#gTnxirhx+~*DpuKUA;`omur`nbprd}c@-E4t6AJ%k(QHfj zNLU%e!@uB2Jn4*;lYz@g-fpx!q~&~D+Dcn40;soHe0)Lz?Drp8)@NDgMaxjhrR0k~ zLKS$i7Zs(!Rvpxhq&5cH{Bq%RMeo=@``2VjwwUy3&s|;!YY9zOoCg(|3?gb_l)*C` zBzq`7BBT=myYP`pi8!Tj+Z*Y%9Ol;GQ@T7zt7bI0Q{zf>PdXb}q93HtDyW9Ss-#%T z8r~gQz5872JHCX&?(2cR+9ByC93G@vn5VRyL=-8gsp#E>>2t!Mx(_)^b-U$TBbkbN z5|AJG2K#zt7qJruHHBTdu8e3YsNw_`x1VFirrqWM`c_NPVuh!SN+1rQR40Miv9(0X z+M3(46H1;p^M$DhhNL%foup z|NM*qo{>^;O)!qh-=#Zs%uLV-DEdrAYbikVd`HA3orBKLE#lEZ;z2Ff1^o2sXV#xu zMyIBJhWW9^i*|dfWj5^1XAOUCqPmy(q)EOlK4|Dwlp;zz+JZgy}t~75-68PMc!tUop`ORbp5@M?J!Ig1U~Vj|gko zONGd@O369%jh~H{!Ic|^dk-oam$rJaa*lJXr*Kz@=;HJwTXYMO+-IX6O0#iUnGebY zWb!wb7AYI@SiVJJK z>Vz&3X#Rk*!-il#l=0o#@A)-S-aEYc4D$Y$a+VG2b@U&Mxkb$01 zB_j|5{u=%>AKi?A7>n6Cs}`=KIfp+*d1OpUXUoA~Rc!oYq+ICin3-((NYWlRmZyek zAED#(*FsEVR@y;rIL9HBayj*Hx)?r}XHU794s;7&zg+p{j^$X!PL(t~r_VD#!23KO zpG@CY7Dl3n!-RfwQQ_!oT_|Fh#JcbRdBqmUNGaX<^9^!?qSQQuWn^_MdXNEY%}Isn zp=%f$?h{WSd4t9y1)u((B4J?S+WrgI2sxqNkfF`@C=iXKGue`Tzt?4*dd6^#-MuH% zL?bt@td0wpDZhtIP~9oK_iUgJFovQ+Gb7D`Bwl*!2u|Krf9f47R^w%yR(Twe#%*so z_~tz9^jH23tdhQfcr=-&G`6KE+kk(>(B+KDZ&5ihATubZ_%Y4-^K{Y`n_M^?Y@$zC zplJE(`|>LbGAr(@&}ZW-zSQQAAG-1Fgtc_nsH0+*_e#FOeI=dVjy5?w;EafI!fM53 zc=c|Gf>5NCj^fdp>T%zsgGD4rTVw1xop1~@8Eo({0x=8b5Nglin%$>DPm2Culr&MJ z`e0d9uB}(N_wuaS6PB7tidUrkBS@gb!i&EH6icL6?eaIpeOQSM4d&CW`1IYvVJp3s zz(X~<=CoH{Gq7J6BDA>=U=TNdh#IGwg+Pq%tvLl$5$)F|dsU0)?1IznW`uq3%zSS< zTucc+vC-Fl_x;QqPlGah$eYM_YOTTSM6X`eWR&e0_#G*4+6TWzoAbQLqiXrs;3IF^ zM!b00GGBe;G6hIz^u`+MJqTl9qA#t zmIS-~l&Uf8nA#ypaRy|MJ;`LiaA!Vr^CB}|vO!6Q|>9ljBoR+^j*9S`s0WQxTH}>|V>)SXi9t?_@@fu)qp~Tt zZy_sV!HQeD21AeSJ^*n5WCdxf&~01<{fx+-^VB`A>(b|Ny!Z>` zjWzLQcg#IliaOB=RyvQcUDe;tJoh;vVB6^QTUV(*A|RQ zXCVEZQNLZkgLMWHX-!QH;Q;@g6idrte^(7t^a(x3d-boKOzA9O317J2vV+`ouZP`gXtTI!){G~bewOxpA{zmOj8 z9TcEfybZ-i{dspS*~rFG`^?eJ#bO}G;Et|ZXBp+3E}pu+lZv0BgKSpP+Hq0b7*2$` z0)}`5kjIe33OzLRj8}8+1iH%Qt#tB=mY@wgJ?2@`c^(VBj4Y2%h;RHYJemgrzLGSZ z^>I-B>3Ys%Zvg4~dNwna7iB8e2*r{_S{~tc*gRuMK(Wl)N$P{G+zoT@bI>0tD;4rs zCA-)d!;ahUZ)w#KY$yLC2r;$eRMS~0dpS`mW~-&$ep9h%^G8Kh^zs-Ha(p;NPIz3i za?3|$@NE~?MrAzvB;_5p3AHR#E1EupW@%@^xo*Y;X2K^8NqNg`5B+k#cFm^yDr1) zjL6blS{adA-$v+@ot^3%5-TFDpd6eU8kZj$>VpxHr#}K>bYO06MrL;aaX>ByjtWl# zauc1R6{VGxonkx^6>f36MmQ-kmlstP2Q2-#p_FT5VP@)N@*tIOXs>sq;iMzqwY9ZD zwQ+K@aB@B{eI^!x0U>dv1Bb~@RRf6%JKbZWG#HDj8aGgj8Ux|@1^T1McQxiGwpA#69BeblDG80b#M2}6A0pX%S zn90Fma5holMZ-T*t&UDd?~w3}PIccJt}deTKPFmOpRs1I0xLhFcw65lOnrzki0m41$6Z`vtf^>zTeJxJrK7rtrk3 zw}D3PPvn0jZH*0|Vnu(RD}lco>6w8{oGmVYjzGWX4|CDkTAJ&fetK2DRYrO#OjVQT zAF3zwsEv>Y$wDq;MaL#qjt{)6N5(`L3zv#tY z@SoC@pO~L*NgzL*J}C1)!z*DtW5ms5MOzX@4mBWIZg%1Z!EV7=9agoRV^f+p zXW0Mv&=j-i2!NH{IQJWCfW|?7`ViqSAa`aibTQnL#()QHS#6^WmBz1{xF2{ehW+2{%j4dqKK56trGr2O(od*_lo06-z1f+-sdGINZu z@;i_`87(D35=0{V5X0QmSUB_`AYhMB{DT^4&X+~{3*?A}PnTTaSBQ&IhMs3gI0PxI z=IPqlneUkNgkl$XJ3Xop2l28}UPHLW7ZzO|%Qm=KJ9`|irk8yrR${X?zTW?R-Xz9s~O@?10xUnwN6y!SlZ6D)`i>g zAF>;wov>9bK>ch3IUl{+vRH{=k~~U>OC58Bsehs)H#vLe6S}V96rad>2G+WSfym|T zCSU?BP(ubJP5;k6(=D#p&NsLzDj=|ykO-4VNe$&oT+lr?`8EV7vMozET!s%5AWS}%1yesJ zECkFe-i~hz&XUTlNaq(ARE{YPRXI>Sj;UZ`j$ zbom=Z`S)Xcj52jlk)n_@T+;d0nP|WU2)~>HUeq-bO5N>N0706J*YI>}Gxp8rh8&IC zzvxVNKoZlp4wYVMNs|kRN%A_lx6G#X!%Y((u9$Ie)D+!SN3D&qDGC9W8{kTc&c8y3 z=i;k54c^{qEFKqoS8wfa+QBBbj{^91zwA&|-VH9;1DgI1QRSv5a(Py1h0KGB!q_I?P4?9N{&O|Ip6Z z0O~o8EtW^E%o9Y|q&JmBr5KtJ70A?i!EWnw7N+D3TF}L|5W0!Bw~8Cg#yRMtXEdT2 zvj#_DIMwRfk=#KG$=A+?Ih$iW8-PdOqPSxoy$965yts_bNVOm_hn|4~vG<|}lXxVP zfTs_-PU_R#5n>VuAII@R5BT&-QE?m^psps@bRX0`x@Zoyy!Y->3_-qS|N9#6rUZ`X zwJJZHz4zh=8N*2JkkgGM5dpQc4>Gr9%9U7zmsqxo45CK&e0i$?K zJUX#3crXy)Tr27QvVzv+=N#E{k;}#9U|5MMVd{3Y{dbQmT*oD{fJ*kVac~bUU?{)! zECz0X4IZV5!a=~-AeQfZ5F=4<p_m@p}jD#IBDbSCpx*KskwTYpjW&3bzy*seNfbXfYdZY+L8xnz$o3)s>LBnUD#|-xAMUkd{b_` zIQKAwzr+!K;YIOWf=@Mrgxz`1_K1*oU1$L=8f6<@Z+{!T=Bs7*0G1xXrs%1OVr&i* z&IyYI%srR$jKJ3PQEyu3(3NRkieVD8aq@OLC^Um*q;aSS8CRK5A#3IBq?HW zI#IVYchP(YX%P*Y0KQ;|>i1gCT0Ob~O2MA9_;)XB1C5;@spzpT17futztMSKyBiVz zvEEU}k6;>hIxT4A2$Em(VjV8_jwThtN-;6s+0N zLy3t+!Ip1jY?YRlYtVZo?Bza${-~ppX@4dmpbMit@cGGN0bF)(%CsjtUFibsJW(Myf{|&yk|VOYp~e?rbp3nWYsOwQK>rRW5b zLEXkdJ5?V=nd{oEaKdA2$NDCd4HoE~Q5t0+gkr#e1W*mibDCb%=CzLo984qf@UH9| zq3XDFn$)y+^srndCBCAV*4apppjRa4^^814VwlBA)7;djU zVg_CC0k$nBE{;h50$y+#(;yJhtDB=aidKU*{0uqIH^LB5YvaL;8_9j6`7KU-X$NA= ze#2PIYli=ETePIMHFTQ9JSp;UeA|9y(+03cVaaj@T?K}SJKix!&^}@~o9TX#ou}GL z!F(GxC1K6Lu6E*m-FKs7LLqkZ08`)Jfvk7?0FD?#o9pd9G^30<30(~Gf*s$_n`s-d zSxs~DgW0Hg87i?-$tvM3mQHdhrTyHzeDf`FBqB*&BR#XIheeE_#SH}^q+WH*weVZ+ zb-XrXHvv%aSo;Z+*wV#OF{E@m00U!a(>+C@bwG5@cfm2PU2nP*i^zGMT-t6G zwKL?jVv<=bF_K)bIvJ7OWA7C=hj&g#rhSzW?xC@9Su+l)Kxf4F_(W7%fGa;WwD zQQF`sVo{nF>;e=d#Jqde9)ge_Bfc=aGC`UJkpU-1M0dh?QPx3$SpKavJ9<_Kuvw>b z^l{Ie1_7V{wB99!Ey?)!Z;lvX;nTowJJ+l*buihYI)68q%)Evt;ws@8-A!e&o2o zW*3|t@elLU9OC)PCX0dPsW&aAdlY?dx#N&WO<4gBTITtCfvrL8QHByY0w%bj6_wb+XEET8se&@5~;X5#LXn zx%Vqoh8gUK%%ObqJcbh?D|92(Ezs}UxYaR?-{Liu=t)pqe*`$UVS{*k|BPkt^WIMb zen*3`2(NKpNIMgDvB)950wN`_!W?k`y~^(1ZK_haWOi|Jt3u^|`vt}84l;lfy4@tH z19o7_3n$->5hnA~95GKpOvwk^-n{2V@aDsdKOc@>2pmA{flHGa!q7In569yNuOUAc zbs9@Jt1Y0P&H9SB?nOv;h;2 zHWB(FN2e|NZn@Rzg17g?=5*&&)J zMfAPqP_f{_d<q}D{Mvez209hW0S&_WSwCMW7Y+UfLsxhVQ+Vm%Q3kS_z1YA0W<-Y$RLo-;i2eLH z_#!hys#9POfB@1QG?$CU_h!HqCy7qr$u~u=%4Lz1ls3qO2`obsd%|}*7|6Fn!Ki28 z-;vT!d$eEJ-s8D%j9!r5i8bhzuE=`m>K}r?738(wJIphJ7IIHOk+2T%GXmV-F53d$U4Gf>6_QlOM3vnD+O$q9@}&Nh@|il-_YmDbue2?v zm2|YWWlz4u%Pz^lij@|Fx`A{`z$mgx<_Ay)*YW<_$yPQ8IvqK`9`&CMx9;p#VY|iM z_Qlv&2y5o{SFW+QNIwKT&4)M(?sa`RdFKc4nKwOQ#_>WUjztsGN+ z;OBF|!{6ihzF&-R`W#XaH^c42SeKbW-ls6~G9m(~!g$o!Wv~s2gg9!Z4I-W3TXzii zDZ*a%0d`vNkJ?-Na6@FgtL0SaEjDjwBQ2}0x+lm9?(f8kM7QG=)0u0{Mp*D-lA@Ty zX6~~shq%uS_CnY(e{*}j8i|i*s{6HPFqohK;!|o0{>kEgn&|Ew4ZR7|dw9otubXOx zq}zfyTDTCvLTM2_S@JBd>d|NoB&1N@m&_OAY0-T12|RFxIpZ72MkoGESMla$qf1up zFi&BI#5yw9u#8j*--$_@V}T|0MZ9FwLSuL~o;+-+=$M%L00TE8{dHUsC%4!dNn3m1( zAQ=Lox}Kmzytfp0K%;aCh?lsCMKsCyI?Jp3yN{C2cR#`!H@a*PJdYp;eOzkhKV` zihl~~L$GACAzZ+9fZKwND*$I&2|QE+=)Qa6M!r>t3Zm?XQo53>JI_363;@*%KK>L| zQ>weG@}49}VKGn_lH!~k7lYwF)9}{^o(wz$yC=@QZt2@DRG=soAOhQtJP7ZkKCE0e zJl1^QCFZRuENm8C{HeekQVxcPL~cQ48h25CF^J0>A9vM?i8f@d zG=Ed9Uy5gC;fLz2!{W7{s6#TeDou=X$r)88`h3IY1HYWEy2jL$-^zTL z4EGdW>6?(bfFNKJ!Wx9mSURpE!hc$2Of|7~7KT=$9fji+NP3Ii+ zhjlL_e)Nb$y>goxbYt!~yk~i>;To>vm#SRw?6(bMDl9U1q)4Wd`AYpcej6V>By82@ zOXWAeB=O7%T_EY>9GIuvtoR*9zD`+rH$)r-Gg45VAGVK92Zs*YsvQfzF#V(tJ9KXMRQutOSI#(IV-wtbQ}h@;Nu~ zjAI-QDJ>62Yq6_~iBR{tUU>3A#xVwO@9tM^qa}h~Q=3ArhH?E+#jEO{Z39AQ+hZhdY?cB19ahH z=GLmN2}vS_04vr1%YolX_6YnDD$br)RCF?)EA0;?H0)og@d=i~ z!pF|vc9}_QbAU6_u3H6K?yX4IZg<>wIin$WKTIwxjZsml+}wg(4EBcMKoFwOjL4r> zmp(XnkY#LOGE7t*(|`4?RSxJ#;-v%_^YDyR#>H@KGkid*8{a9LdJr;{eNt|W$g8Rjf6&<0nAIc|QhT{09Pp0#-6aQ+EH0+?4tdZ}8nthLy59DgzrU}2d(Vk?#w zDE1bmDw5A@kJ1LmkvCkuvxuvEIh!>6VBEB@lOXTA-&X^B-lT&WJI^wZSY|~toZmYp zl#4Afs1HfvF@LipHJ%V%*u`x?rAOpjIOn)p0!f#LVR}If4EU{^ErtnR?=S>?t9Us=>vY4$5c%wsD9vQIc z(jWt)#D?D?B&Egk=}sgZjg3@4ywh#e8FYyKI%Vr-Yk#+n@%tLtT4OpM>{35{tJUb1 zM+5t1x9i2*lZO6H3HC%B;11%Db@pdeu{ckTG}=8;Ajq;kFGyDM52~U45Bgll(R%d= z0M;x3g-XyxnyFY@O#S@ad!&j~=L*z3(BcgIav-7td?i$CS2=k5hWt=>eI*MGkS%0+ zr&@(Ru7A6%eTaZ$M96QWCX!$6B;o0Y`<-zFmN-e1mfo{kzhtXtl0AXYnGW7gI)|0@ z_+Y?GXWq9U{?6vIL@?r=Dy$?KbbF-WeE#`KjGe|D&}d`hdMl~CH6 z)nypdjNq82{77oWV&)p_($qMvy%MLOMRqj@OuPP}lcx&`An|gq!4xyN)6Hs_B6bln zUw_LOxw}~}*O6Yb%5K8dUR0t7qeMA@*#mR1c?;6#O0zb~mvf%q3mS+CF}>8JWt*%Q<-`zh&6S0&sRPU-Q|rKY*Aj< zwPNjhh7l1H0ez25OkMn&mEoaVmcpe_?0?<`1gk$78ZtG(j4gJz6e?$uxN^__`}ZF~ zt!)r==(3w9PS96qzvwuj{MEFq(*Ryx@__}w4BY6ZKk?Ibf#O{sy{DMw^_&A7kJz3sM#;O%7)L)qvw&{_pqivVm0V&6{$G4r#uyyr`>_E(>A zQ1Mv}sG``yqh+aX{dKuN1GLIYHGeS(C>j<~nDCq%RTk!$z>K|My%3_J)xTj82}@V) z1^CeaC@NnxsQiAg^74cgoXX2KPj-{!xM;Zl4q0r9*JdnHH>*mg-crpsMu06 zzbJDK1(OsIXd>YKH9u5k!{%8?`jK$YsuRD>7qGNgseu=cnV6!&p-^TXL4TV3d(9XU z=YduR20jdwuI86*=g8FHnV!Y>ISC`Cf$j%rwP#8rs>gn?>Id6BxzVMjC={5p7tR@g1&-X2Rl8U^j%FO+0m%9r zu~?EqADV6ztrZFTD^P>*7=Nt5K;}+*Bk^QNRNiR=MEIfFPJ^B5JrM5}SiL4j?jq@p zi3qREdo(#mEJ;2vM$dRq-x9h0bq}HMKBszNy+pXzF@(%! zNR$EBwKpGGJ7CEx%+DDj?AI_nE<=|fQ1BgWDXNUb3!>XZWjNzOGh1oVyDvIWJ+1L~~7sTKRz! zOb>E8@sG|T&5B;P2DCfveBhmSacXSlRF)BlQ!X}>DUQaAooIPBNj0Fgm!;cYGFF0s zac`sG{nT~$C9t&>^^rg=p6MQoKu`uXU`+oD`l!G8*7K=@G=E*dCL>lYm>l*MDp&$f zMA7eN?ct+A`UdiloaTeBdCZm_gUnBlB zV{nD4Z>L)JdVlN^T=T;(gKKo|k(56<_{e5d%+$Oior{$4b{+%t(m0KsOvmVBa$bj` zJFh}~i9gQQ5bVpL;!1)OGGN0!s8h1?ArwEX{?zrti?J{k6mWF|J-phZqD53=qpb)b zwkV^+T#?P*>nU28aMmjFk1zS+42LMqFFad9tRVP*5`W|>ag?$w8wDb5>jWZ`*@D$0 z9A>KW-ZVJmOMa_ruQL*;QX(%g5&Mq>SfxtIfc(wEA?#O5N(8p&^YPy2-P*nmi*H_c zk=@PW!CEs-?%c3bbtK~@ zy`IPSK3yMjh?$|&!4sY*3Qw_;v^%s7i}08X!P=7o_DRUuvcrNn7krF!>>Gp&u3nV> z;MhM1WQNRjQJRLjIJXL65~mK(bVw`ZBl6vU~FEEK*GbPUE4=zw6se{pC( zC4b2Z1Cw=sue)Joumm4i*7^y!E+ZnxCG`fud@Ffle2p)b(#A_lz6r+oLffW~3EQBa zZAIX!X03K8fW$A!`gz)2b)QK+J+c2m3}Dx$Q6u-6;yn^RQ8m6&gal88{H;+G-YWFJ z-wi6@)hRiTwWUylMby(mx!YpX3c5O%*MGwHDI;diYtQ$^i8f4;Oku8<5ES+WvH5<~ zg2D@WtydR)Qw9AX{ae9-oh*>jnK8?cI8ACpe3ZjmS>PqvFAQFyd4A=) z=g%SbOgDv&SCfN*m%qjd3xEO{B|mmXvj)8>tPz6_^hO@k7ltKO+-JzF4_HgpMSmnv zhZ8T*NFDR8ZQl$m{(wuy;^P)*yk(p+NYh|*VG?`uto7b<59ku_X%P)EMu5frsgXfN zmY=lAHbqc_qlX2H)}4ZzY!B>j4VDGiooI_jl291Q<*-6F0sy$=7(Zs~#Xule_jDDsNC`!g{dM{;yNvH@ zI*|%%XnBAzFuX9N<{^W%!c{5y{w6J)b(KF(yTFv4HTlYBUBIu8age)1L4SNJR;!Yz ztmK?KGhZbN9!Nw`ACwnty&68?j7_-g;dh_MlgW}9=T^f7fsJJ&#iJ_4Ma7Xbp#w^+ zm}t`?zu$;;r6Q7EixuW-2_;`}2tvcRDz&ja@bKIETTB^?j1iSOy&<%=8sFAdQ_)#u zxH>rc>(x7ouK03>HBuR-q<;zy-gn1-)1HJ#A-GMeh}gy?Bx`k>J;NG8>SQf&wS}t?jQnKM|2;hA@J$5KH%)O`aTi!6`wP?l|m4E)tUnnQo(@WU{ zauUCb?eN6{ccyAGahr_4p6j4@Y3LP@P>;u>kD|MyKI1H+#2%0Y@|{=1sU3 zKf1bM?=2_*U;8yI8-KI7uoK|!Si=HNWiwic9;m1@T22xCdLySj^N4oe6o2GTM8jOb zK0AV5TYtvA49jS%D!%M3vh*6q$Q&s+;y&Eg$%82V+t(1;Yt&906Bbwv?=m3b04S!|Bo^@{y`EEOlN3JYd zq!W`vsRW%Yo^P!98<-{wtf5<`fgD~5Zjo2SBu`l|!dZjyz;BD{bv|HynHjC2ynI@StbFOyg}5>z{rcD@q4)E$|TZ+Z=g z7`h&$*%;ieYk!=Wk4~C#?e{b-_b`$#LC4R#nZl1;wa1dK$^L}zt}NJwpI|~jF=n*& zhi^-Pr1{84xcBeavojw!51Ypk5F+jRvX(?b%-ANGe3yMm>06zinX{v`>w^>a{h2wF)$eh@yUOR$!V}G_ZrU}JQqW!?*(I3=t(63+h z2yuse6BD-E#6t2Eo=Dovjmup@1pagSw9Hl4@eso0+wp85bn-oYit#D0U`Zjz$OE~W zg0p6U7&x8ie4<+GUVvGM{_g2+Sh3b=BJbxxu5{r`)hF<_!w?w^MlYjhvAE+g4 zu=|i6OW9@Y22z~)0N1o3*Gd(gO`BA~8f8#@Kv@F6Fpxs-5#nHx9lt@|r%gT)QwiSA zLoshm5Z!G!V)B%yA`yPVTA;BqVmT(8D9}<#Uc8Hze?0?OH|nQGLL(A5qDb-krwrC+ zCx63<*)?T-GU3z2V(}__MZHc=`2GB8yPdu<6GH8`Z<=+x#R?gdx!hRdb1ri$k&Wlr zFJk9h;{pQl2~(?#JYKj(#|+|KA9W*_p(hkE<}Kbxv{ccjrbyX?ST)M_uOdjBjfc=% zHrJZFR*;$L?`s@g4zHi}oO42-8jWvjb$^z*b~S(6CXV_uh=elz02$*-f?1~eK=wpkS=}zDqJsPwg4yB}iZxQV&fv59E=i z6FGmcfE#BrQPqtVY*n6&>5Qc*)_;N~CD76N>TcJd3>vo8u+bm(faA?6Gm9mYo?iOz z9wSbv@=S$51rs@)QRwo9PgEXPv8}Rrk~w%RXtQec@o7*Pp*k(vU?u{aTZiMMgkOoU zL-0Q3Ob_^X;4E=utrJ8)bN1lf?MMr3bf_gE1h+<-dxia80XRQPV4j0$zE`SeDVr7{yNfM|IIu8PrH+Cm zH?k*YW+k+wi-J-nNN3&87+6 zgw+xvi_sEZE;?>$ijdePWQ~+lTO@Kwko|*d=q-w&FjnU>WMADUB^H-oGf45*p>pD3 z5!*s|l_2_6e{8Qint$r^Nh`#s|Fs)HXH04lC;yE?>xwn!-3XJoy+u%76YmWxr`ACV zd1YUu(uEE5ZV?2PdSsHx!`qt)VbGYru=N-p^bT6|dmB~{FzB5B2!3U zA(@+7(Y69X?GRChuH~2ZCiIM&gPrVX`HG}(OMiTWyM>EG<$wEH-pQUavp_b$?)tbd zp3+{k@g<=B^_7zGd?>u|^byaYtjRGI#nSHQ`-_@q@XACQj_1J)x-;+upz>@-@V4O=z0{HZ)SPes($)) zzWAe7?1-Srm+%9U%Rn?~Wg>wwITGzkTtq+ERMFmqfObM%-)iNY&Gn%Rxz+ZT$U_2m zFkaX$S>_$!XSgjzxtYhr6Nhx0xsutdh6UJ@Q|~86sfKP7laNw(?W-O6-Zw=}Z@N zn0ua_7I+4{p6$bE1+DOXak0HvgJv_RO{G&7R=^8DaXIKwlwjeVu|H&){Y8&{l>XIx zN>#EQn|K?^ZpL+@ zWtkOAw(LzK=;<1z(QQ?7p8gv1hOlC6V6SBCeLOFJJXHndq?VRfA#GaBfvC4grHC#v z?|;chItTJCw;x0%);#b&;}m-$GP*`v{3E-3w@vq*XU9Yn|3gZ;K{`dS!h<*T zOWe=qN}}Xo2=%Hn1I*$F`XnBA65z~Ta(~ddECONdL$!)KPQEFWf|EbM(D{PT66rkk zyi*5q^azxw<}D2L?zrxDVt*RAH`gUk*bh8n=CAmyuFTfXtlxK(?eeFy&XdZg#&BYi zrc1)%px`YfHWhzeT$EbPr$V1+V7!|fqtccq)XA_jG!XAvAWgH|8b%(K@UM5ETz^fR zIrxk!jV~c{Bmcc$x;`DCM5kbAXD_`t6UZ91tbhELbrQdsD637J{>k{DJb2r-f!7fL{B~pf-cJRIV>`}Q|qXR*t-z9FjF?ulY4Q~T=br#yO?PBS9zq9Sz9uL}Bn*^pK% zHNXt9L{{ZvZKJa|1xEh`t>k9P;;{nUqz7bnnr^!Wv=GAv7 zUU!1bH~xl2BJ(u;n(9t>n1>>KC*H#{0LzDH?B&(Ow>e%8^0njuA!2QT1%F$4EB+NT z5VVAYxL35&C>xywzA;7OI5r0M?N?{KK)i5fB5+S2-A_g7!&{z*FE1CRooe}B1o@Ao z^HVbk#)L{$7-dF}$)aL=juoLq>Dj!QBes(4BP^nLSbJ-5Mm2cw$2Q?+*4Z!4o2{-~ zHcGOUOC)H091=L+1zAudPk)h|wJr6!9qb{DIeut)L@t1Rk$uE&ZlXPr8SveNI*EY| zByphEd2}7ZB${?sRV%zSgpv2Us|0fS@cA~sGjZ3M?d`4T;5GlgwSXh0=wrS~RAN_= zH{d+u{n4c!=oUIPSkC|iB&Nm=I=BLB^f^ZsM?Zs91^B3D;%c~LvVT^QR0Ee|2o4`> z%g!pGt4Z^{ZNhYaag zD8xK3fHxAZ6W^N7u<*GpNMMkzUV00429%G$=glt!=ONJyT3X(h>F4vwBw@x^Rh>#jXC+A|67I?CsFuQRoD_r_33aD)f zR8&hb2iN8_WpcZRD74!ehvHQCW4JlBrN^QLRP_|{WB?6Uhq==!rUl+>XFlUufsf+| zGMjLPpebm1nt%1Ha^v?Si^O#Wb%8%$D5Bi*U7SUPcnM#DQoAv`B?XZmr_6r7pii@` zP(PSjC{hhz^ufV4u<}w~9(*ykD-Vq`K2+J&Il*G6__YQw2%~*4|7=CIUtr(`w?rdW z4Ae`(R*FY5$ET>Av!Bkwe7ZV98$UJFJXe6fT6pJnW`FCIv*Gva$ARxU{ZN12msK66 zMozE(6EjX?Pg#lXlKu=4>oNE@jF7f&>nQ5R3n+5S>PO4J=_K?&T)G(AgMOqNrO_oOL_OHWX2)^5Dsl5ie0-_PDK)R>@O(cK{>bQH9^8kzeXW z(KMy=scFin9YdiWRV*b`uUUrYxR^cp`onLo>H=2P!@tSv#}!+LUF!PjmwkSn#Yj8E zD0?s>{&^RY8Eq{tuhu*A1A>O}gHkf!!GbVpuzy3J1_!a8d~p4;_S4s}`3En7dX`}F z=}8R=65~3d=B(pNLfG}EiTg~9n7##GQSj#yvszq11jZuMm{mJc=b24jObM7eXMs9} z!B4A9th8NpaZ_uLkS!vpP1o*KR@Vmk4wGhkq+J(^>_80)Hp*~!K`r$HXA6=R1;*F` z_ZQ%N*dm8136bRd#2ap z6N)vA2j@toQdN?3t%U?^M5?t9Wn!`+G>D~19YZ(&qSdY)|7Zp(e3L5PSk-Iq3ai#t zKjBQ0UneQ_+GQ)Q0UN*1A5$T=A>U3beSdgrP#K!(MLd9gUyU^68-IxNjWMq4z&D5X zuY=*%UL$tP&JTNFZBvbEGG!4fbD|&fj%tCO$Hyp@r~-zl_Kr2{k&JUfAt>B*M%tu3 z5NW8hkf14f4Ze{U6(;^8-b3@DsPqWAiF499=!LeXrxGHvZ-?7H>#C94$+)Xe+JCCp z0Uu)FocVmm)`Iin_rX}P#1%s>0%YuFK{?p}-0u+{RvQ&fsS7#O zaJq*s8sit*nO=QdtGOqgcygE{{#G~%=ZxW3THN)|T4r z`QnybP!l@d%6UKN7UX4uEPu%Jv)*97qo>?Vg2s`V%T+JV+GNqQ-zN~Q&qKSu zoq|qZ)i~5D&OO-OzGj-{3fR!9TFn?;;!UoetNTWt>Qa}qU2822C(0bfrUv$;pxFo6 z0)b<{CS(lWYd5ma@lMe+%Bb&vs9mOG1GV&({FJt0g)^F@L}}qg!=* zMP5~*suH(hlKh(cki}$NQU6TlaEs>t>~q`NMehGuQD+#-<7Mcmmu>b^pCj3}lOjNk zNi!b-p1RY9?yD6Nccj33H;e1v9MgcI;}gxF_1FXkafy?60s3n(oJDmWQ=(?Le!jZ# zwS#gG7iID1E%4RS0U}0C-+y-Jd_)${LU*eJ+OVfx;&O@F%rBBO=<^yrZA6)cJhwp_>Ql@r*vkBg3jp2Fb9ZYRE(CPk}Pkr?16RKrR)k!JU zd0||sA5Z|)N76TIHk63WH_n4lHbhCQqd&_r;kVE!kCJXv{t*VPPJb>E9=rJ~=MBP* zN}_Tv!bQNcv)VUeRT6tlF^xNxWYA>~Ri8WqW2yK_7fJ(pc;@PH(R|xGCApixm#j#l z>&+2lp`eJUb7;3uFhXsRMIh9Gm~(OyPl0*h3D4|E#WRnC4Mk9Q$nskimfn`?VA>dM00RV$LJlM7wk}tA8p|UOJ?o_vor72rKM& zFY@aCdx4{)uSdEeN}n_=I$lK4C}Bjc1J9#n$vD>Vr8Lfz7ik(b=5CVaWGAr(n{hJK zkCBGd*&rTEm z@mJV>L96*01G2F!CMFxQD;&FX(~lv63;p;q^8G;OH$t+uI*+4Oid^ivrS5-=>;rTE zb>lmB$3bTbS8kr7aNItzDnYVEQ`?#%$Jm}^$KQMd?|))1O6(5;Z~cRZ*E0qMtt}Fi z8Df$&&aCSAQ3ZScJ5Z;2e^xHHHvS#}PC(m_PG4-H*{UO+KjfE`s6Yqr(bn4Xv72*p z^4och%jO+od@DN+T5o$AG`Q_NcrtlZ0EPW>ta#fJ>TPb8W-EzVvDkdgPZFQq27$Ht zxct)obAMz~odRyPe@HS~9I4MytaHLIv+kBYAsAWLV{Z@JvFn$)9XA3o2x5pA**o;V z$M@E?y>Bb@4MIm!{9VjJh>eWB(b$yNjCU(l#lt|FJ6NiNn`DK%XQ@RpGoGk(Qu;1f+-b?$8?j98x~#HaLx%Ae=IrSjE8M-g&D-aN|sV1fCpN8EP< ze0H6d{U^BiEUj9L2;()uS|mvk;fB;UH!XAs4WE;H6nO7W z@a6>m=qrhWQ zvufFFnkw}`Nth%v?_cV#O%!gYBkG;}u^J;!!Q+t`QVt5;(ZHfcPl_s>^hhb$w>EL( zKzxm6mQr@qKi3DQ_`ei5y_*wuO)N;v`bRU?1s_{yDk$-?_qdQ-n8YdDCY)_2%zrdw zRdWoRzvqxXL6+1RYp@Kd^ObwTogW94UPGr9KsDzy%7??MX))bQg{bZqf&x=x<3F3^ zV=-}|KD@{fDP@IC;grC3O+{S>Q(F?{`@C6QOx| zG;w-byx?lR(0xOykuop;%OI@6T7SFoc925kt;x0CzMIUs6}#32<@&n zM0Gn8vukvD%B^tFiqvCI>IYYIFEFt^79_iX7HZj&_oLDkkMV|qL{brVkb79v-)hLR zz72%Z+i@%Oqc|5O*lEZHqS=_)_xCqo*lu>Y$B;+cmQL(_Pv!fqb01H*5$mAH(-bEm z5ePrxCEe}wC%e4&1p}PC@_$Hrday4Trxs>ZJs=mRoBjKa)kcF7mH2Z>8ER+2cVLuJ z@NdZtu(^K}t2`h!?6YvsDi;PQQrWFTx4^`eW(F3MLP^7_WCE>)9P-zAcYqgg)vU-C z2NTL1S~J$>^5oaoIQFWUy`|Oq9|WC!ebpw{?mUBjp2d2h30HdMNPlfhqsSBG2htQb zH3RgPepd_T5xf*CGz}HESIW4gRz#;BQoQ4f>V>%-kGZQf?6%oPTNwy@nQ6@*~zwG`PId&je1SYs*jYPp$xNkRK<`S?B|v9G_A& z3aemBW$x=E!pg)9XoYQq3Hk{mTe-^e(7>7(+h(WAWp$c%_x3(!Ityj;6Fusbp1fVl z0ysr#;9(ii+M)pZx5Q1PUKnWhO$5li_Fx?7J~jh_6DkYwyMMv{n2y`C{-+RjnHt8v z@7nsr5g&y9lZAN18hSNImle;OrWiIBcXfE)+mI&NKNsSaYh^RSv>O2P(2036g1yy> zHz`W222msi#|k7A>-d$>%y1U5!8@- z_ZY$$V?6Fqm&dzpa3wVZ{yH43RQ5yv^%gUWMU==+S z7%$AJ1Ak(?#r-|cD5corz3oHsBuBH`Z!0msi~MVCYx(wKBj&|LY~IoTPXLlBZPqG! z_s?Kgl?YaK+rPTO(dZo->z`e{PaXIAvwE&e2c#fsn(h`Y>(5y=k#*lygT~_``Uxl_ z8ODebn$1~kx6`01$JiI}vsCohr?M^f^4H_U0)K-Zs32g(8_5Vy znTMVzf%5s6ALX3x*!nvHjH9MBg2ei0s`gg9#d>bf6i4{``4uY_dXpp zC`Yf$W%JT`>HU;5R4*sitS=|6=h4#rFMXgdQb?8`bS|8Q+=M=!Kcv|*UV6?cAZXI? z%YR`KkEY*em}r>|WV{KVq2Ko;jrtqPl~<=Xgsl~qHmsN^v~aL1#Iu&O$QcPVwH|}) zh*VLdxv%BQD$tU12Ay*o#@0B}y>P6{;d*t|i2IgnNmvfyUn{%aM?RI0CSBAxu1eM} zmWPaY4o`|T2Nx+9ltI;3RjzON)4f~prhk7`f2jSEk29mK;f|TZJASrsBJqDZTewm? zNEZgL{3q(5xyoHu^*tisK3jsFl>Xl%L-(;OIoc|r>b6zbHzIl(mZx|4JI=%+PPsVF zRFg}yK+iS$?ipxhfb~6Pf}qKLZ~kXhe75IXB!Ad<*HwOjY(Cq5@W9w-yb5I9Ie%_c zILhF2-HNS^gTf{nX;(l!pLwta^7P|?6#clvMT&k2>$*^*LU)u{KP>_9^1FB~$sCB^ zC<-QMQ$%y<(Yc6Drcz$-vt8ZR=5kiQZhQwS1UZ&vXaI%!6b$cWMo`quu7hl z&Gf2)NeOaH!wiEE*xOBa z8bcuSN~(%Dfl4%sL~)|y8r=}Du>0`I=N_jAC_1QPbG;jn@1QSQgNyw`3uM?*f~$=S?G{Ro5eO zBj$a4?wrd98JqRJlcA(gXMalYJ)b4zqOoyS|5RExV(lP31ao>RF1@mS@WdEHR1++X zbS_`e@IlqBH1c3q6?WsxV=Wk(B=vdK0-qZ8R;3TF~ zj}OZO(2zKDhIB`pgY{H3$Otrpp)k;elK80$!m~9UX^U71vL*J{EBp+PjBuRP5f(5s zBX1zq6^lW#+McDCq<;%n0x-7wp^>idXYwG#nb_~Fwx7UFwR<>b1tn+w+tw#{Z=2 zpHJHv$$XFDz0XkYKUH}h3CG~WS_RX~M6Nf78}2ohlhx?I41biful8_Zh=Y7s&*W{K z5*r=1VgH1o+f!eFDI(CpY(3f3yz0=ZdV1q8TT_~9FR^LStUxCHSY9xI!=66_Q%fvPwVRUzEUO# zi?S~La`cWgF@KqE;)VRPvotTcwfLmpoXl6Tx~^GsPOs`SKS(x*vzs}>h$q9N#Y(aI zeZwt{qy^FMBHs|!aXRqL_5t!%o9*EPB$f_^-hN6G!{P(})OR^| zfwtB&%HZh_HPW~}ZS7e(Zp*PwfZhy(0xlS-`tqz9+J6ddVvzFEt$T6MhyDVa;gOl$ zADP;3W47gGWrRF?u5;>|wd7ln*J%?t31P=7r?YgN;Lo-a6I(m3TY)>^P#Tg`ryTGX(L8R zoxV($v9f692C{!BHK$^^2*}wg*aod`CU>WQ}oLg$OEXRwQ}K z+YGz4!}WeJeDVHQtcfLbNE2fQCgX)=_xYl00kPXf(v)?DFPN-^gAM(3D`QHygfaVO z02NNVK2({V%`s;?BSqWH%(IjufneZT3x5GN>lxJ9HWNwMYlUeLsi!jflRL!A7zvAG zYGC2|Y`5e7qGw_E73RRkZz=*XpgRyjRW!{Sa7yjvh5(_B!?NeyVE9(23VOMDD3TB6 zx^i9Sgv=OcKa`Mi9f}m?eccYZ-&Dc5F=8oplk7prfq0J25uoXtY;tTl`2!>t`+r28 z*92Ax4{TERJN`o8U}n3!2L~U-vxz5wEmMgFcmg$gO<;3K#xD@Bst(u#-k7Pa@xeU( zsobg!XdjB`$=#!d6^WT7=EL#i0SSl0Z#iqjd)W=vEn~N}R-|k*#PW%#OMOgpoy$1y zjy>(>cpKt6;FUE9|8(cqOVCB?qJK||Rwp--eEfeORQaKU_w~i{`kLep*(SdlHa zrA=l-45gM7GQBlR7Wk&n)r8l~>cFdR!LE~?*4o(X+bewh1Q>~nL0xV3FO9B*lk5%# zUw1@rSJD6<^Ef{9yOPQikjL4Fv&*~19kJ=i)(t^Xn4!f5)ow=u)vbLH7=L*b`KO8d z2~8H>d{0r9NeJT_v)Q#1NI|rGWIbc(2u%|6f?i86Cu%9(GnnYN3Wma~+QB_^spv|= zXC}o0FQu?2Nf+3idRapn+=9zTzSb8jGjx9?bXkoadOrIJY72>l@XGzEc2X8iJpijp zIpaPT$az-sdXaWA@+5n{4u6v~3c`(tbNnej&>5o&Dq`sjJUe@JJ&aeR2{|v<{_Qc| zQw~8#S>_4M$d7Ed-ufMBw)SA{mDC#RSA z%!|EV4pGbQ<1N@#s%We_yH-C&dRg*ZsFBy0Fn&YJMrhZW(swlFK7ZH`hY`IRz<+D? zEB_;i)cUII@|XnI;1TsdPg)a2rXt;_86CN&4x`7xMd`%$OqHH`cOMB99xaCRz%hL7 zvwc8n5ghZb7THozwdVFo8}!$Y#9ZqACP)+_dED!<6-^rti+a8uF{=4Zxeb8jQ{Y5W zYU$1p!Ea2QtkccEXn&-FPUlo{AZJcS<^nZ<4E%ub0TR?4tF&OJ@BiXH6G2<{I2-`q z)rdz&GX_v5P+fBDXp&$*@yQl{*H>T00fAK8_&wF=1HTR&e=dfk!_NWCW~nN71t-}BFO2u5+_he**|`2MnsUTGv}JK zu^#6{jv@#;pV(7G&6%!Q*y2^Nfqv;Vkw%Z1i|Y#Aw;%+ncM?r$J^a{2G9-050Wj}` zcM~xlQ07+06n{EGA}Gu;UbeUwWI)DOD7&{#+IM{u=6Avyo1W#f4;4G4Ml;>hPfy81 zPXVs$*CC|yR_~r?w;L3+O9|IR*b>Q9VYHzF1xUs^t@c|k%0^mbccs+ci3J_*r-T%{5K6X>->5B4L9DmRbw!bi+0?YO;eufYEs<83T z?s#)6jK?{WeD#Irj4B9_TAc`y<*gN!W}uB zpb%hkNq;)E{>q_4f{ntP;@ed#c~P!ZZFkqm7Uo0zmb^TsH z+*D>ZsDHH2JioE_?WzrUikdX#(x!NiIqk2DpQWb2?u!zy-J)8{7@%0e!oP6~@V{uL ztgpL7Dgr!zn>KXG^3@m?0C+Ct(-0xO$7uqT9FSEL+rMhjp#Oc8YgU$Kj1W$YK2h0_ z)k#HEu^47td^2r(>u4B4yN9V{`h_u1fl#&ZKWezJ zg4J&}ooG9NO|hhzbJ&q-`!6Z8OPd)D-QmYooQW5N+xI((+FssmZFd;8RNQ$~ELrR5 zPN50u0D*h#67zUm5tsBqy(y(6$B9f2=#j(nnbLT@u@jW{Zz4XA$iqoOv7E54Udmu7 ztbY({Jc7!ZYka+bgH&A}H|7BRZeT&H>1C@BAE_|4sM#j74;EtvmW#VFhe}h$YuY|m zFJZqUiY7*kabC=uQaZj-D#~u3J(0-#EWa$|iQw99nE;2EwRZb?NGYDYx=(tiS;84y z{Ow_(HVCMnOpn+xA?)zGI>wsSatSFt>wovuRryi%`iLsdH<#df?2u{Zr#7MbdqLUq z6vyxM%*=_ZRI%*v<()+Tj`v)wmL8>jv6eznorhIMnt=}S*q2PD5f;WfA!ewH9#KfV z@RcM8AR4kh)=EBmVuojfK{-Zt1?-+*J7#uEkz~E+d3KJX#dz>Z>3hLD_s@j=(SN_F zf6GVEjj#R6(AT-j_A@EM^-HBECd#*Ux&#Uf#~SMJ9;I2TgN^-MCWV0ol;wl_M=9at(|H5^@Gz!eC1sK&LLbbs~@pNush zOj_BItncH-!e*S3$q&HS!(AA%G%f_6lqZ=hf09^RR7CWDSEZ0OK;l?F&N0ck;O4E- z4`mkphY_jykrT0CrS8yj(jTE7r zYs#6xB39an;q?$f_Pu4)BQ#;!r!-m_rI8k?dHtFshkZnlI0dar;Ll}CC$0Mlms2v^ z+)yH2FSHYQgyq{#_q3{7-Rll0aqQI5Koi9X7E4O$9N3$@E#Yp2>wkcD#TWCVwW}r@`D`CeI0+g1aDu zYp%Kk@x=;R3GL&{5orTIhGD_9quEw?-xmnk4x%iP0e?#0+Bbk~66nsAaUMJ0DrD9z zI?(_kRP1~DAB`8x(PP~H1a*%v;eDZcrRw>*9nq_&mTi(c^)Y?$Y&9)dHfVArUIPQg z@0DGd8T>mq_bZsdw8$p_K+)Iee+CUr6NCIh58EB@g2%19FVr{8-=_TAW7_>$_UbwlSLp{~3jA^!W5n0+I zZUyCHK#!csP|pkJ@SVA}Ttyob1$38GWiW|Xa=97Ut|WAKoY{10RE8V0YH}Ud*>9jn zi)>I_(dE7H7wVozN_9gi7M(395UV_`&i;2ATHDk-pZkBA03}QNNTF9=hB^<_lgCKn z)?^)Y6or&y!)p5Xsfw`<1!acapNIC4{i`4$x_=wOmB8TjG!=daFvWgvPifDUnK%3; zFK&P6gvKp<3<(W+f1Ot7fk0G}ey;QOPKNHdhuXT0)xLZa%n&xGX4r5go7J1I_yGwB zkJRQOU>AQbyX&k56{8CDGj_IM3;*2EZD)19ynfHyb^9psdWp014z|~G4k?^U1RurX ztL64FA)d@OTH~{!QUvCL1Q=r>X>Q0iSte2q_Ab#_Y9!I zkUSt1OFL4}1IAe5uH$f$P$cw_HKU_UR+M_8CryO%OOy%MO$&M6)go_(HRzc)OZs!h|4Lg7ImUnk@Y?}(pX43hsaV(S(@i>1rxx??_ zvzWx%&Q5+g=5zxOpQ7pgtS$H~EHeKvx4N~)ind`RsLAYg9dB#zF=S*O<2X-0wCDS{ z+zzwQP9nu!osj|Rqw)$I^q-1`86y_O&Z2L9h)#8!A;s~7J_VFgdfR%i{C8IT_+pX207`078w(9BTvG6WX zI2LeQA&;Vc7OHh{%V?(ol+L18CwqSrOhJ<0aLkD^G^EFOuan|Lj31 zEQopTiv6pMZX0d1R`(U-%$_BQ9tLP=V^KqIX}LalX1n`U0!sDKpS@~j;Y5&UK(M{y z9>>#CjH7Yn8}N(cL++&<@xXulH4!+5hHN5aL#yG_Q@U4Bv*@rWn^4heEG%BmJ2Fd4 z%iC?c5)1alzataQ_}R~TDXT7-Nx_S-4D$u8k5OCHWLQAseqPf+DMrAFc1ox{HJ*C#qO^#Eb`Mux`xF+Fh5nXy?j?U;lts#Gx_I^=IEn=r} zx695oHngwpfW`J*kg~ON+8eEhmwpA_K4 zhqDb(X`t`#ZNTY`_GEw5*7b&s-X5b24Y8Ky3SpDV@%%r1pYZ0Iy!GwvIPOn(D(x#b zHJH{Fz}c8Tm79LL^k4RBM>Q@tDsFA|fV=LwdxQFLB@Jq`NW z1R0S_Xhh+}pnRf#4wd;gd)OJk6+5-VJqTqc}+tvptVHJPtW66{+duQ7F{DV#T7AiVw8b`*)IpkpRni=&@6ZZ3H~sYLfO$ z!}*3_0hwIF|FTR^<;W0$r(Rboo9Xmz`nu@dVb!_;7p&}tD_E9jL_lz!(A2<6r-cd> z`*Sp33q4i#RU<V`vBlL9`VlVSo~Y`Pw&FV9Q!)inw$q5z&~WmJi0i0(X8bPFlViw zAOw_ghiU-)oQwh^qOQ%9qhw@ zKSXWmeRY0KHss}K!hTF%k^3fu-i+s$!PcMYcVpDVkTD=h_u4CzE2K{k;Tmj| z*um9kscDRrUziV$-*SSB8s3*N!m|6fcSwH#K1c9-8&l~P?1Ws<>8jwoW5re$O7HRQ z^=;7I%&Jsc%{x<7?IfwDi-EiSrZ{l7Yo;Axxtl5{uwLg1!L70^CHt3kYs?OKuWIKv zo)3_#+ru9u_F7tilY=mlc&}V!E)Mpr^DhD+ipqxd0{TU_C;Gtx_e0x#3PpR3^Ob*m zs6hv~3MA>pdtp9RpG{;76~i@<`^*#i}}79sCUaT9ml zv>4t~A%f~!lAaSde`l7b$j6mkj*|Gp)Zp934xO!>n*leun^(Mv{<1Tno&jnN)c|a8 zq!~C$_4M)^6G_BjA4_t5Tso$BroMmbT*~>1m1R*ejzrvEUW_&&ZI7E8riT090Q*IH zZ|@6NW^Xm7q`yypQ-!mx$m{hj*i0|Bs6DxT(`b~s`oY6pOk1s@VW|VynISiNg-3*P zm{25p<9O1aQQ}~r#iG&**m4ZQ2MeG3h8e6#TV0%49BYci+*e)xgG=m zpgFU1@+QR@)l@4L*Ww?DwX3-pYKBXXh1T;!-CKLzHC_@`$N|2Xc_gr(%UCZjxHJcX z5OheJ`;EU_WnpzL7N^FbB{qLBnX{FNMhPe@vn}-VJMcD1@TGNFALlH5U*T@(en7@F zpVECqUa0$o30VE9r;in9^EVG${N)SEcXf-Z+*d@13hiIewlkgC=K9z%7j(RR zHuO7!AsKUNep#h0|F;wN2=*DL6_O@t0|*|wnc@rr6$}l95yI6Q2>M?Q zA4TfJmZ$YL8V5~+FqW_>e1=3CQ!HKP7tz4L zzjmkbkUHss!h~)bW(I!~Fq+_C&`1GdmvES*#WBgV%gD{^>E`R`#2mF}w55SO&^G4Yy%p`5aZFnhm}nt0!k6Nc!^UXe56an@sc`NSP>1 zw!~A$B+Vl6yX01+d*T&T=&CCunl$fKro@z*Gb+oJM?L5G^x`kWdU3m8ym|S^x1J-Q zU1@)U9QM3eZuvWr1NUx&$*I3wBg?)>tf=@~(qiA(%aHK-3~%N6C6l{Z z214d(@2TgY1r2Ii&NFQc)Qw|ExKy)C38#E~`?8tI?2lQ>Gy2-#h903SrWs%nYaG>B zxC2MBKjWrYdYy?Nd4CI}|JxIoS%YJ{1x}#yvBwWEA*|tDS@sYIQJiBNyY}G^JSy-3m8| z4nZPZ;V6Gr?<)(_Ep1b!Ki_uG!`*CXe1}{Ln7Yq4n6TI-Wzy*xnUcHG0;#!O-`=3u zvuWq>)Xqvrsh5{eHbt5rMRHe+z&&`ZEIdoMk;u+5#mS~>H6JgbuI%6I%G+C^TGn439 z%@2Pe)L)7*`Yu#xs4}scPsUh|M+^XV7Nd5Iomr}&j5W4%fDRQ)ve!ru-@B$<4%ov^ zN&$B-%zV|%PA>FvlLOxP_X0+0|8b7Bm2&)DG8v=4aTPSR-)lH^T9F6YMQj!>YA!*I zse9KsmE^xUj0OOL^Cxrjr$S;miQ32{14CZTkVS zl${RGU`$R05{R&vT4*b{6&40(B{Z!j%xp4TP{vfnRHACEoA=0=+nMy=p7{HHR*NaG z;`xFg;t`q))|nht!5>HLjqGofXa=E*WCWVZy%KuQQns+4MNZ8^xLW=gxZ{fR47eP0kuu*znsrXW#2A`cYv zjt~!7j5;q%hpUC#d49fm92aoAv;CH}%-3Ha)m;9CY2@``boiU8BzdRU56+~rv-nS)9?n$%pQP)=*tRrG=s{@4o=jI#NvhHwXxYh@)?s; z7lgF6OyMELaR@y|@2AI>2Gai@e@Q|Fd06=Q-oR)qzPBFYi^DEWSgkC?*$T7|FxY#K z1+Th+K*cqt$J7Iq5@?BnSWxBVy(0ZSqxEt+;D3^^qCDDW-LV)t-w}U=!+4%Qb)_Hi z(9e{K4)Tgt5fKa<_xST0cGlaaT-v>^(%9MSQ&^Y~4M6f-vDi^&rfo_x$4_j33R4W{ zk9c(Hq_(z$#ulbqbgz<=XV+cvs)<3rGZv7Hexu7PAU4?xseGkf(8XdQnz6omu-Iwm{K=h;*RSBP5VZ_p%AGSwIn@jb~%yq4V9^59e5%bBB>y^v&vt|Av$zpZA=hQ&866lqAThcR!FLnr^FRK*dud43d+=2W zweJmmttGEkXB{rM63>OZXiOnVpqslJyWC)dv6d(-X{TyB;z@s{OS=OMn_v!ny4sK- zK-^yR40BOYCn6<^lJXSD7#Bt=M8>j{)-op%1ZBi?2*N4AKLOa|`XtKjL)cmvOtkT} zIuao$6fHJ4?{gzMs_}b!@d-cYC_%FHj`^)+;bKXIXmpBoX$AVbToZrtgR$K2YbK?I zXz`ht(lbVk%h!MPD8kH!D>6E8N-6a#FV}e(zk_6mL@FL~x~~Io10UO+ z7P0`@aHC%siNUf6dGK@)grVZ|iBOt$VZMF?;#od$grGN$1TxCBztN?0xjxuIbu9}& z^b?iJ9CUxX2fU~rJWEqB#n;A^p&Rx;cPKxT5t}86-VT4~RUO=1G*hrR2#LVZ>Ctz3 z5i`yXQhBXtx8sDHh3@5_)+hS(-R3M!uFiqCWR2It^=(;r1`fof+RHGEng0AG6YuF` zWYgfCl#d!iF`7}bIaq|2{7y@3!D?TQ)!Pz{`G_#@amJMyhG=Heu}6YZMCW`?6;>C# zoU)N^YpH)TypN!O)9c*Sp)`ZDdWb_N>_$Az`{t+!k;w+BzI7@)MAXeY)Nv_?x9>)* zri30;^2jWqys6fuFMd>B3Sg7P(l4AIi zR@w>?%RJqLD-C8_g=*fH>kjfU{H!?3#2?-}JJ z34MQp)D0sylN_`ni9@arGkGmPZx%!ZVSYcOTW2+QQi7DACalME)jO%5Npug2zHR!k0=IK22}W>XuhqElY4xRODSi!&^$VJ5+m z5zl0aF^rX1abmZ?NfDd1Pk{Jt43tN68eT2zG_+a{eW3{k0>}%XN2I3#ywsmOyU;6@ zf?FRe>bD4ZFsusTQeWwAzt{i~3<_m#WOH* z+g67=JGSklgAO{jZQHhObdpXwwsZe;&OPVWt9rGnR(%+==J>`OwQAO)B$aZoch&H6 z1hF!*GO_Rh)TPuES=m@v04z-G2$YoK&L9(4D+hZC6IT!)KpSKRPzN~zSlIyoKv)qd z0pbphUd~n)f0nKQ8X)bzivTTK6EiD2D`$X~gRO(R70?nO;O_1&;_l+ccaOA8U%E<``2^~0N4LTwkH3JO#c`Cuj}mjpNI*8l@(xS1#|_Nf-J1;5t#p_o2_7k-aR)m`H&>7|K+(Yr;D(`e-W~-CjaOlYH#t6axDKTS-D7Ad4kMTtX%(*+T6tUABp~5 z*9QIPTogfOR&I9xSr7V0kAF_o%)#E)>;G=~&lvySkXcq-N?cBh{(lDecU#gP=wN1L zZvjwu{YOg^XS4qm{@qqFvHFjD{!8Y+ZUV6Wf4^MO#MRl#6QIw+^e=m`{OkE|Wbpq` zVqy-SK8&n9oB&34HWmOY$3HJ#4mQ944_%;}vopxv_1}X3Gs}PTe;Ww|@&o}9)>j;W z{GryVE#c+(DZXN#+vjitl+EDJy-hQtcEPjjDBC>-)i9Jc_0zZ2AK-(o$t!t ze>Rhu#DS2GC#QarMi{K%KNpi%Soqg$zpCcH)JGUzLTTaI0hOSxB5z#NH`aqy=%zR_ zbIxkyoJs}1NwfYmF6-!rM%#&BTfDcIrZu2O&(Qls0v*s-qs>`{6?1o4_>_sH1s%uO8Qx(TLhp?Umi>huTEF)Gj7wUw4N3vUf5~D(%e-Ox9$x;Ze6Y`tF)Iy1V!t}SvzVSU z2Q17;T!?j!H*QxaKWyN#WMee>y3{D7WPA=s!R`LFEQ|L?52Lk;Q*fZ=1tJUD(1utg zYLQwe_~y_%_N3npXYVNWlV97c!xX9?@>B6aVtsf_gV7RvOrKftYXo*we~DM(U6Tl% zLJ07SV;L;3rm@yfwudEfHe2;gl0Poe8xhyn13W2hB5tNw(E~iAq_$F&a|49jAovrb zdgq+Wn;UTYM?b}_hY6*y(wWPv+k?Dadp~*PKIM1)!#gjPm`DbGHx8BJ|T5S z?%(eP;OcoI(ix)CTNe_>e@03p`f3;LjJ#$7l>&QnbN^Bgf2^sa-WUuKg7HIN zKt`L7%5UrDXlBYk45x(3Oa^zEd_VB*t8F5Ad^I2}KM=9(_Kt_T4EGr6wA0jeiUtJ094N3$n zv-RC|pS3{UzHaD3f1N~ESK#%4{GwRxy0Ay~TorWX!BwRks9s!&{?^fo8*ohrUZRsM z>unQ1Yi{lHOrkj^IhW9MLh~H2Dtt|xkrK-TT+{H><#dy?nou>ZP!y{qwAg%h{8+EQ)!m zPcz!9b+aL#H@=Vgtiw~3Jn2V(uFkfL2vYo(&TY`JtD{`(SV97iIfj=Uk!Qh0TnUtr zYQ~bN@q~IthdhX6%R>#Cj=OPEwD9V0^!ij>z~C6+`iYI8D{RA8HhFy_xrW#Enz(Ob z>{)kix=e`=l{N&g>wF4JKg$&yOs+m1ssC-L@oA11 zJOyN!rqa2TP2wBu(50u(J=cJ=qKh&{L@Fxrl2p;?z2dP(<6GaQC*dF`|FMBt-=qtg z-3T$V8EuE}Zsk_Mb+uk6jZC7&HR(mdW_UGCFyIpHbn=z z2PfSQ)+~Xdhgd;;?{<*PQ^EpRt+s2@CS9Ok1WK18A;a!uHWAwmgnIC%sZ*iOG(Cc` zp!IU-e;-e?usWThVS8^5YB1a~wZ-1{lyPJPO+S3p)H%c!^#RY1aE;8cxI)%x74dAb z$MD3=6GZ_i1n%{tWUwrv6nEZm=!Z7+04qzKtRxt=@8J!`T)}5nskfEn*A?M*v<@}h zF{sFwAM_Nr^Qda;jJ1(bI9L!SyeB!L8T#Hxf8f4fto#=#vJSiDaH@w-5(IMJ(I?v| z149^hU-(PHXGMNSWBd)45gz-p+yc;qec8zJV)S>;>m?VNPmFSQ*)w}V1gKwsnAOFE z?ID|ltVF$G3(3cIb>XcZG8Sr+4ca$%YJiBJ=iTVhCYN=WE7F`A!}3X8R@K?^z8}<(A!R-@rQClVft-F_u5@^{Zz{fi=z)!{mL47?w+)<< ztF*s7)8%7IOOPb&jd!;v&lmGgUwwnFe_H-_M;BEp#w9AyNd`MDI@v0@aP ze9$PsLA83?Qa52og_(AA2LGszsyvV$o~I2yfa6|A*?V$My{gVmkq zTW6`2^#q8P)r>ZKV`7CDoe3zHLW;|_timR-(o+V zdz(E1P1E%mmaG+_`IR`DWI_R7BdNmZv++;IPcTzlNPj>Ok|!i;C^tnVP2U%fZ*-)Z~$b zS`0lIzh#M3HBKt7>l=#ZIk>l6wN(h@VEZV$Czfn-IaaEy@$*9YFu-x*U zIX~A*e~<_aE(o8NxX^(0eS!8AEUX1|b*Q=Gn+seYa^elUyC%&k+{gV#^I5LUn7cw}C zygj2M1fQiNWgYHt`YnK5pW_RD1mb+VWN{z$4Y*wsA~kJa+DjdO_)Y9ya0bYCi2HuO zE8H;Ve-yZK#Q(y}e<&fdR4q^9qs8#MDz6f+%<55WJ1W9XY6ZV)IQf315UDY}E7){) zaZdI*U~)$Db>oI~x%%D2bp<()S>9!cxv^VhnpSIsj8=E1qSqt&Qg7uaaJH;}TNSD1 z7R?Z9E{F2#9Pg=>RxY>pEr}FzM$7Xy#5u%s%5?5G5suz|f2Ug>WyBE~9V|97%@7Z1 zV)stoRK{o9G$fR#$<=dVY>Kz#--bMY^z#6b1a->5%YwA+DWAQ;SV181Z zGKqz*yajRW(M&J5A>t>fhKynOOqDms?e-0;Bj@*=&uC0(c!)tKVqu!mY5z!It=`oT z%aXgLI+RE8f2@4zqI$I90z!J!m7}@o=Q(DaIA~U8uK;Si;ckr*ZIrIoN^YH@T!l zQFX9~aT3Y`x0@J))YGeL!os(7Z*QtnSGOL-WtgXRe?G_DuIWkExnNlcKWL=*oCH-e zbZ#-)ce+$1x!;mNHe{=f0P7K5>v?jWN)6Y?YR*QMG+CK)`HT@QlYt(f&0k~ zj4n>9(iF^;YJh9D&Jw^VVu0z?y9oKgxcqi$*R|{kZqf`HK`cuTJFeXbH`j2)4B51C z2o&Z9e_M1IhcF;cbU8k{G3{<`a{7oxkne)g1HJ!2M;C8Tw{dx4OjrDFA~s3N;f5`E{6)7R@*D4$txd3o+vz@M~C12wFB=_S6 zCr^N;5jaIPBa7{Sqk$t}s=bE(+Sy~)i)=g4NRwkuNG2$|g4Im!K(rC}b0T#MTyz@g z6m|gG8sbU8mX*N2I0{1{4Bs8GP`psC%?tANSUerddXKiFF(0-%7|`oD8hp8pf4L3f z?NC#^<(2#KoZ|RKx)mly-HB}@gf68Bj#v=bO4#$bEr}wLwKVf4QcZ9$9P^_2FOt!X zZyHX`kzC6GvIG(KPI9Z?dlFHPwHe_#=v_$C;k`_6dpFNJ%Dr2obFod1SQfrw`{Q(~Nz zmHCrbPRaMX@gkqa=)!601N|_e?N?lNl|FcX?eF?&y^bZJ8Y_qShx10znV!=DRG18` z{FYLK-EAwOkg~jt+>$%=5;Cj>kQLMYDK0y?U2-_Y1ZILbD5Ez9TiLJDe<~6gOI_C` zCu9bbWlyHX@?2b?Zb}e@W)pdaU4v&xl(FqR$221H zr5j(wrCCXKzD!u&YI4Cw4|OGQy9D)H+?OOK1C6FI>rUQDlf~y3#nwEvym59sZX)mB z!&thww#!FkKiJ_#wk>HEe@}Oh?#?y*U$e+wQKGL!w6W0c;6Gh~*&&9#y{2x>SOLkw z(Kwf$xA}z_fBOF#Hn%(8u3z6LTmY3ayt>g2Nf1bVcF1$s--dfUt zd2|D{NHZK~i+UB=`-OLDgUiSZfex5|Im<24H8fj1MXQ_4%@IyvBfyHCE+6#IWzrT) zYl4DuMx08gE$}6h{1hdbcB<|h`hM~Vx=Lu7i(sSRHOUIJCU`%A@T9(H;#egu&r=;; zjdIn`HMaAuJomcQfBQ}gjTz4?=~gCIFj{GBrTTB_3uG_aLtU16WExQJvH|tYSBX%B z5Ilx)E+BllmB`AX%SSqsPJQOf7R~Fd6;9|&kH+c~ifB@jlO5&wriXZyJn#uLBrY2C z1iS~4NJ{nnoYl4{*LxW?U3&=5Wtm1d(xd=iRFun7<%>5;eF; zzgxEg&jKNVJx!M+MeR7eXu?T2gmA`#905fISVyqF7&!tUpuOrmQMcKKhulIrsJ$aPP0y%QX7+p_tt!*!+k57GIbJck&PNv8cG2 zaJGW!^)G^ee{bsE#=9NB>q)t7`exCUa7-Uw1o-sCW;dZN+hJ zeI?uC;lKGeTlJ5Yj0hCT&@Ab}P zR<5EoYA=tNqi16~oYtC%TVoy~1jwRa119VTe7jwrpB*f=1J6#LMtFclOuucFK@w^`ypE+c*n70kn>Nm*jSwv>9+}L4Q_w$qyG3$g zNE&MT6BJ$B+i1xXeP6FtwuWW69T8Lrv^24*k_r*2o(<2Bk+pRBg%MqCx`~5Q#^*d! z#t(VmVRgaOY-P>sr9`2f9Nno zH}Z$Ek)0t1Rxr29m?(N`drCad2)cB+0D*h}G^~DAy>q8qE)3~NZrB`8YTN&$OIY0FhS63jgh_Ac% z^+6AlVVhDRrA9AQn0A`d z)aOL;#z*S6=)aZ{K!3jhIudY`7VrQZoiuh0{mEYgJY3lC;v;tG;O9SWNm(MYe}IhN zv2+Yd6QtKLD);xf4-TJ$I`hH%MH^)*mY@LR-}-(St!b&*rB`;4^SX@ z-0vLeEZbum+eM2c!>L7Pd75U=u=!{O-B+DeG(mOAsyL&|=r;ZBIWicCi+L;$5oU;J z^?wU}Osf;5s~&amQHKcH-0Sah&)6v92}l-+8xJuF#?W7iY;f0sH_*H+fAgM4v%pc3 z?xyGuWlwcX7~_aYsZzluEd`T_altNP$1`tSlwj&9R$0OdFIRvG65uQEt%u=#(<`b^qR1$PR&7XvRr8z;J*XsW5w9gp;f36oBscLE z8Zj-0ffbTjg#m%#WLduUq!}g9!?V!0E-cpS&k?o+PDra*$r#5lf2oj{JCsw=shIFY zCzPBjQUhq2>-xITBZh}GOL$|vz%VKO{+Pnzd76B46a5CIWKDbc*z-EwiopPAApE)k zs4IJh{%Cg}b8CjDT}-h}V+%(L?&vKA;a5oELDE{f8-jXRk%ma?Zb`?NzLOEL?V(&g zeyRk_@pDUwVc=Ule_=@9(^t7Wwzf)0P49ns=jScPbaYzI){k*%pOC1fs|kLjJj1d%#BZsM&8Z^$cqZWtTGufqLQK>@LAoHX?Bdom>I z8R^Tyenf?oDek;}w+KVx?)g|<57N>wYMkCZIkGkR60SLjP=#S*E@ttKX-a1^s4r-- zD>LMAtYga@fAOamw0)mz`np7IM@V=EU`**8>AZVM`aDF-q)tL!voN4YPhuV%apJkW z^8rVnzcMc=0AhX6>*ZmD&VX6iJFZgpJQgk20ImX8O?COC-8gePd`lU;bZ;K}^Zf?z zYN>#ahK$7_2hUMg3n?s2kZ;bE>}@|O7AAFv4JB(bf4&a;k0?p>wWQlgyZ)}Ppjk*^ zzNlcEtBPTe)Uk$Wq&?v6tFEB6LQ$ZgL;-40Db-F;T6tFO>(4wYTR>MEJWFPm<3hA5 zpMhRGG^rEGQp{uM`ji+Skw%eed0QyC%!n-2b_E*}s~ci;PR3s+ntsgLZ--CssrO3e zV%t#Tf2Pux!#Fq(g_mDAR5};nKg3!%Hh!6?z3^l+7-*x+IXB?hIgLZV z_9e}8#>|ac%$E;K`_++uILR8A1uzUs>A5%y#>Qc@gX|&X3&L30BucUuUg!q=mG%|u zF}!O@C+DIV3^9);sDY1~NH^DWhNxId_vX$-f1N*5KJ(ATtR-KG`@AE1H0VgH-8H)k z=(g*yr-Wb=<0f9xz{P&u~ZA|_cZStN^6DgxeUy(P_%@^F*)8I9^_`78X zhOWcjL-QwDKK;WD+{xd&A(iC3id_0E=xlz2apMPHtakf9Q3#oLIP(bsJ0#vU=nL1n z1CKuW^5V&pHW#uk(X`gMe*7lNMmiqpe`=CJXsI+$;&jXMrfIq!MYj_fROUYK87w2; zsBeU|zh%6s(DJsdXG`B$W#_#w(Z>)u{7xljvh%_LFZ(N^^n)PnZ5vWqs-m>TcC6ob zcmT!i=`PAHX{fMGi?EF|6;qM*{E=g#qtk0&Ypjf;g_^0eC?y_FBSYVT6-he+&EHdxSAM(B2AoT9-l}a8W}4zQ*ViTSRd$?sU99 z##Ef)6|92_GF8PsxaZkJA=gj_c&jcx-C1Nk%n41SFPdZJ$?3ieS)G+u5OOWN)}ctK z^|8bs+V3jAff=Pq$HU`>P_q>4!1yuuKPz_bElV&t;oB0|xe{8`70Et^f6ZP8m%JV} zV~Iz%aRPUTQ%tajP=k)~Pb>r;&aMki|H5%r0*EjF$EQ$S_fh8e6vix zCr5-{k|Pl%=6hj{m&qiqmIWXUR*Q|CQ7%?}N7R7dgC(K$jH{)%uU@TXIA2cigX0Q( z*c*RF8F{mWi`T8;sB4@;e~r<~|6t031)f~)d27EGMT^(x&p|JHlqaW{hOG9~Xla?I z)PXtX@)hIhMw@;7c@~F@Nx_lE0C$d!?l{~G`{|{yLLH4+4O^a;T(08vHpMB#j1;yy z+wMP=AKM`jNe0tyh#6UBCE)kCA5vK94BJG}+G0gBf!la=N?S*se`yzuRvKrDo=>oh z4quEsz{)5>P`Q6pRc1BU#gbk*sgYguv_%!h{-t6xtGNWv`8_ygU`tk0CRb?+5jz)s zc%1BV8x};12uIx?Wn_U(M(Wjtfdp@`N4%JdydPdEA?UDYR3n|yc28iNil4r2Hj`9lg@bm$GiDo0hB_4&#P>)08#?6*~4e+n;JKrHV(%Z<_bpvDYJ zA2EZaa7u3bZwbUrnVe(ar0X?5(GG%?eHr*1loOB-UKc|Oh8*=M z2p@FUUa(l-e-GFsVF_>NCff6J0X|JUy1}5`!*9eyxKzhbL7NF(z>_YSg@mHX{yO8Q ztxPZ^AV#uSr{y!B5Tbj4@zo9dpE>lM3jNSBK7|7!|3FwMoO|?Nr z;uI-V==0Dhf9_bW?X7lHx_he)n~s9Ph*yIMbBFwge<6NKIS{9j{)lc~?+2LB98&w( zZB{rdt@`Wy>Lzkv`a^+p*YRhQmzYZY>u+M`mcecrax$a^Bx9cU;N6Q+jyl`WZS5E$ z;u(QAQBHj?7kJPrTzxkdqhWwV&Wc!7c((jCqJ)QS6)ax|BgFY=zz5#s#J4@jzzLI= zg{I-pe=QDCC*nZamHkhb-OVb5nIOhB_n|n;JRqY44@IGTa}}?eO=Q<19L5dlQ~P1k zL<%bhLu7#9G5#+7Rd`(6Pr^<1ao@-mZ|t>>ZPqcira)gUF}XI#0arH;iPtl4jz)h4 z^(iZ8U&uUQeOWoWr)wlyMxi}p6LXvrZJ{6ke=7-j?%T=fpUe>ZTtg0z* zf1Kyrq=Q>UCxsa;ST9-(we~VJSz73+i%rK854A6CFD_~v`j1J^FeZ$flBw+6#HX%Z z^Q~j>UH3$pI_%afjI}0#XkFX|A!nr}a9WC$RZ)M&^+K6zVZrp3Vm7a+gz#kdThsE6 zQK-^_;S<5JkvLQq{)VtLh$qH`5`7m4f98!tnT}^r<)uwTo+2%U(h>el_y+P*Fx&VU z^ZZNCirpm82EoYNwULgo;3BDWQkz-Stlt}SiX!(Qpp41)xGDeKbLOWa>9f!kBSY5& z_3OIlda-}yfqQoGJb8lI|6cyu0u%J*5zeR)$$WK2VWKI@vBc9o)(g=HNDUVIvy; zGLSmN0F(WVITLTiv5sAcGK$<>e;4U{C+|4^2f_7{aeEhrV9U*L#fjt_q%d`LdBJpK zM@OEUd@7w80oV-p@)Rk!0KzAHx(&2w-Pf+he8p4UFNJ#yOQ_U-we1vXTQp!wYy0e` zPgrWmEtMrkV!QY9>4}e3@Ci&ao&)NNLsH1#3)LcNVS~0x4HA8X5Srs7f1KeEeK9|# z5{6aZTZRD~rB{OH0QE*J8^n=JLq9_k!t`p?2lJyFiZ$D{CD9LFSayoY1S!;D%cY9T zCYNw0)q28h&zsZ{fU}eLvzB4|FCDJ&kCe>Q$|{HMl|ZD>HXqJYB5-W(6-*}>$wxo)I+8~p=kLT5Cn z^)kRD0;-uyVq9$;YkmDj)fUJX@GvUg;4vwS4M-1{eI)mavo@UL@nW#%5|=bX2M=C) zTww=s+~+7ac5rMnnOVgZylW14tk{O}8W=J*oQPvnlz)I`?<8$3ETJ1oows{l8Zb&PCYrEDo0#8 zIK(1xEi+P6G2e51e`bzC5t^TkpacqcSt4v`{?@c-$Y5I`q#t&xj;0f^KwvzTlVn3c zk3i`ZQbI_DP|dwdQtm5^b`(^uhL=Sm6Vv#EX*gbpp34_Q=VnBPtm&xns=uZYvTMVV zxN~V(BB>z2Yv-6lt!^VT`@+lpxKsP1Hx&f&m+8w0x4eyRe%68aetEMq(l?>JnD zp^K6w$PO&R6XnMjO#f(Tx4v|Ot)&4FoCW_e8tygDa{E&dK^k3!iSMVrj4eN}u|=#p zDpihI_ZyOa6s2%iAX2<2ZcCx&9S9WNWO>ot(G*>2D zs~vV_WX_<3s|*_X6r4+=)Yqa@vvSQto*|K<2+M3f8G%d9ja&Ak>0%*l$eN-w38=1z z@@Y*yzW7e37WTCZxC}7$M+l8E^e$C+JGRtRn^HeTf2;xb#Qo{SPZ{}WIM-rJ!i?UV zBmE;@nF)>L_ERPft(DMv&QN-v!xF#Yq;AUH)GwYM4H5!24mKR=Juo!6kB;2}tgo=NiT?&FkTcXzfVUdC@N81U0SD$IVt*`mU{Q&YZgBKz4FuyR)# z1)JxT8ff(iz9KaoTA5X@?#z$gWMpR8iw6-?Mw!VIB3R>{Ro$-O$q>Q9iKQSlsB+7K zp(cfyks^xc)(U`cF?)Vj&}kGT;f%b&A2&^SG=C_(4}?<_N=8pdDB|~|0rF{G>|j1d!e(|;%9StbS7vZ74b?`^!bQ|!ufkc` zTDgmVH<6o<2W=Ua9q#Vx-8&!c<*v&a~3b z3sDm(%N$b%-X^P38-3uiXSip7tPn!CY2X~zboLBVMz}yJvX7Qt63;&#_Xiy={-`Bzc`=2y;Co@;Mg@ zzW{5!e&eJr0$bX81^1N|CdcZlMkSRqM(bVygYt8604uH*dV#G{hyqf)Iv78F(0`(R z^m`q9+GU2u-g(>yB_Sy@ocroIr9f}@5)@SWr#hW$rNUBy%W6;4d&f>$_a=$@*Ew;B zwwD(3@LA6SW6AFZ80#J_*&WNPd^FUsBs|6nHBGme5YiIhG?ZWTNp`h@0xO#>hqU+0 zVD9OtA18@6y{@vLeb#`nb99dGB7ew*38!r{Lb6r)%B}-OTam~!nj(lgw)nKmtmXVQ zuW=&@R_{JFt7nW0*QBOga7O#X?d~=bH|yktQ|EO4uH1aFWOewHNcBOmA-6|Ri-pSu z+8j22Y3t2gO=|rVfh4kkKyRUkbjN_=PuIEi`u6(kdaz2T2 zOq)ho_`#29{*KA=jq2c$$47-lH@D2?9)8|!KFKj(3-`sH;i=xpQmsWJ8h`!prT~dls27IAn z9-BX6BTMmkWE>)KO7nKvpMA14E1Nl!U(BIbBX};QeEh^L>s-(y=LTjFhfree&oB)S zu2XrL#FPQzdofc8i#&!mPNoX-T@ZTm>zPUiE|C6M^OrwOdTSi<^nc*}iVNXqp&{2o za1gcao>3ZWw-SsI=1UhmszuqfFW>=7zgV&72J$h!>w?PU4X<}I?CLxseUo(P1|GES zSa-Rneb>|#IZ@sO^O5{6CI0#5_ zunIV_BMsPa8Y_}UV+7i8fxN+FC^9_#W{j-Z_KuT&xK1?RA25)u+Wz|!(_G&qKjUUdAf%1D8lh20Ca+e&X zarbY#?|&r0bglwXi{QS}K(_dG)XL!81Q3j~s7(X_|911Y(%u^Wohs~zE{FD7JqmNw zMJ_}vrOk<=scqU0>3W30DTSDYJs>7zsL*bWionZmK|cb9DWS;#@H8!wtz`huA7kX5 zWrj(tYvVnAJFtYyi>(e75&MWqp`)oR5pvJAd4KOT(zcnKxtR_tk`jNH^h#6IAN~lr zfz(H0|E4vPNoqCGWtN`1>6=8OY2jf~r_H~E_JD5Grq&%tIq(6^I*@`tXU$Jdl_{+| zR~>FE#N+vd%34V>`-|zAzyTh980yxK;W3_+|3J3l3%%)D;1@w;UW^7*LqwwtQ@tfx zv42X*ye3o9$)+T3KMpr7lPHwO$k5^nh>A(dZIs5`WiNlb=i)CcI@00Nyuyrwj(SBTqE*9fZvi zzW{%%aDB<+j&8_l7~aX;sO@0w9%VL^)F091INnxQhMQf$LwQ#9bvlBv^KjtSJY$%+ z*EtbnVOf&u){rahkbp#Nu(RKl&Bp9E2&FaH|A)Z&4@^U4#ix`fOmXYqCjj-sMSoa7 zG>?g&g9?QXVk4}*=bh8A`^^26T(K!}r4>Rcgu3l6Y}0)>+Xc%U;z-mNJe=&z2SD=n zbxI+1t}^umbDit=X!oVAB!gDbCmp}{BGP?V7SXW+Q6xi7w^F1=z%#3wDN(DEs*9mm zY$c6%uZW-J?VJGX*fPbZ8k-jY7k}kbi-mUKLu^*20O;N&Z<_=8oq&g&KmkV7z46`; zS){GLF-iKCI76exYXbi%4BGdl&qT7rZyukrJub}ws^N40@&{!B%3KvvOHlRLuWX$~ z%><&dIAQNPQdNQIsv(DGm^6_{V)rz~+E1g{20 zT_mq=GJliDMZpvbBsQ5%Qpvsu>7^l&9lt7P?|~Bs#w2)`?Dh3fK#t z=KHNdg5mnc2QnvH%-4^mB7g7FaFtbSqk31W+*eVRbq>k5nb_OLb;{HpIl}Hm$ z>MQ>pYCFfOOM^&-Fpx4LGGVMyo323ySjjS5=boihO5{gfHGUrS+JA*{&JWp5x)?vy zEmPba9Z19v8v<{GKUW);MGYE}2wWPl0u)#;&W<6t`IpLNRby+`r^6o`h?gYY9>1?Q z*dN1s6kcZ7GY)4SX&UZrV|w?+Fq->H`jN}Pzhz-MQ+))addb;m1oApeNB&I;N4hNu zBN)c=bCG2Rmvb`)JAbggZcoz6SL(vh@7G&FP^lGHTMBsnsJZX=XV1IHYBDLt`7JqDFfrTns44uGoTjd%_Bt0OX@n%?qrVSn+mw}l$jit=S#@juxCV%G`# z%pKB?2X4XWF4~p2I;Nob$0~4{u_`nn)#bgrDM3}N!`&pCK_ZynL!0$K;6qDre_sR9 zU;FrsB5 z4gSdXi+Z&C*a3y<0H$OLSTf|7@wB(}+cJl=gnu1-^p*tgpAM}@-;0%4aWYW9hKC%! zFD+@2YB0tG%B}^OsZLg(0K3N--wVU&EO-w650VAiR-LM!&hw!9ff$OC$#TVsyjztL?U~p!F4dcOIzvu11%_OH zIJQHTj@sRQLA6~7uvLyoZf+kDrU%lV-$?s?(~k0Y;?PrSwv>yJvM#+J%vLhLHFRDS?e zN4`QJ*#%-|Zz)VUUT+nre&?n!p-qU8>kGVRj*9&`=(=UVQLBfWJYhk(Y{gW}hTX@W zx)#=V%ucAZmW8S5!7wPBUEJDXAF6RM2R99Kdc34M1FL4#FEQLbsL}~P_JOcXAqGTv zhM)Q>WNaZ${vS%6oSh0~Ze(+Gat>u-Z3<;>WN%_>3NbJ^m*2ku6_-3s0t>fh?E9$+w9o3ZQHhOqvNDwbl&ft^X|EIU%lG@OpLwOm}AYVJy+GH zAd$4Ub5Zwn0J1Q!Ff#K3)FjnqSeSV@0L+YRa1<0`PC#Q9D|x~RZ)FO! za|Y4?%fSce1wyC`hP_NGd6+1AipMnAF7p z#&%`^dFg*%w{vmk{Ra&+b+P)d>gWM3|FLY0|6`f_$NEp!$>ZM^BOD70z|6|j1z-ZS zu(E?=`Y+vN?9A-}oc|7+xjOuJ>K{VR|L_A)|Dz!dzzk^q58BnnM$y<72%r|Tw{>uJ z0XhK`?9G5qb^sX{<9{mqZ-1Dvt(A@E{}=dw5&wpZ*jfA|9RmwHBQyKI<5td+Rvthz zWh<9|1UEOf`A4XK#kGL{J{<+1nU$;UzZU`iqsl+$YG!X|K|DZ%g?LE91c-R39Y^=-x7WRJtJZxOP|BJ1utCJJZ&gEaK|5M6; z`~T`DAkYJ73b(OpZ_4+}I;}Od!cU@Tz7mpde%45XZj}XeZKn5D7u9Om(#-Jq8t*|J zFW()3a4yh9VE<}Q=6|7u)Hn`^a5^;|O%krZiuYPVR%zi^yYsG6@YWD+a08)d-kAE`8X%>Slk)RD~OYglQ zK~{o!@0xRe*~_$YI=%b0pT~o;nBYyF=*(U6)$_sCYtr-I)6D!=ef|5hi`})jPfR-+ zEb7;34~V;;CQF^+Nu1TzTL*2c5CPNpH1=7OX}fIOjh?G_odTKeg@VQxP;6gL1!HN^07@5V-8%lD$i3orbVM8Mt20Ae-?u6YlF=Di2aVnBPn* zVyh8X_u@OmEi4XyzBgv8aCK<;&w;Fq8H3dZw^H6T!;?8%$!avJL+rhGjWzYSVybYUTC)qgeX~DaDJ%_Fk_|NaC13ChTu2+$qC-ln3{y9lA!|d<(n2 zJ*FHE#M_)d7buYny!4*?)Tr7yn3g6~dL3L2dr-JoZmC;zhv@K%#na75`X6U?nBBRY z@y}@{YkyDTqL`qdAl)F(^Ei)pv0A5;4@V`q*uK5;Q++jJ+bvmHp3U`vyeHkE)zX`Ptie;1=wisJTwM@eIA>>sXd0j5s`Gz4K6bM z5&m>wwx1T@5ACXn3}Yb|Ef`am^iC#z4!<<>rhnJ6o`X57rpwhZ9y<_v;*IiqJV6&T z1bx0elu2`UD1begF`2nA_-VN56)2(}`jF48ih0OS>XKv)Tv<-rLT@Og9mrk<;uwfc z+q7?qo$n9R!RQ)~o%qWe{=O4k;xN?;=hX45O67cHyd8)RJ)p^9HrffxT=z!Fs^rez zFMoS3CXyM@iyLO7_d{lc%+}UmDne|i0IQB$9?6%$Ot5K`C(?gN9psBU6^guS>Vz?`QFl{Oz@uBj zZ~wD3!GXmVV_yylcWbaM(0t<*p8u*FIe(XeEnSj_Y609B^ASE^$AxrF@d|!ZtO^MO zM|GKI{swzbBOrA;iyyqIa;W7V{xt&DgZO1+XlsCu8N{WgztvOu36d@}^_7*cYRkRw z%pPFU^t#M&>Ll%V(Pl=_mqJW8FhSTqX8;LP+1ip8BxdXFc)}=xQE5tpj4}~%kbl2z zs@ug^W(O*)a7T8MPLG48JF~Sy$ZjECW(32&7Uni?t}T$a(b^&9iP(wW#uuBpqp5w6 zqL#`b?W`v~o%z-3CvZSS1$lfMgswPD6kz!G0h!iNB6II9Zeoop6Q+K~NVT}Zp!HzJ z01dGiNY_T>R&Asxa2YXUm$wSTo_7udCE=frPK`rhvxxaltB~>zLI{E2~@)4HZ zpQ&RicNjS;ZS8Bh&53J${FF|`AD;Hw8boEu5&BTu5M2AIN%NM+@#LF=f`4FHRY^_+ zb1j+>Pvk45#6xJb9DTn(QiVZ0=v(??t{eJ>rgO5soh-sb&;^NO`3q7t>IscA)O+eOgK0aAS%)(=3 zZYb4;CakMcqz-J(8T_un`mMw7%+mTOg;CCT%O}t@WGRYEc zxxJp=4P3RJ6~R(vS?c>;y77uNvcDG)30n0N=e*6<`-cQR{Vq|tD(H3aUtGB7O+m24 z$%H>VLlHl(8_dp8UH5PZNT#YVPJ$p#N#4e?=SilX16}+V&8N^jW(vrWzvEHr%X|V<18zxAyMJ?)SF;DkL9C~2xAlaO4Emp|8OmtruPH^ukcuF9>B30|XT8Q<-GtEIBWh&ZW;-ceXS3E6d1#yS&wh zU7J#y!S^4&J&Z0vy{@w94|hq=g<9)8WB8W{khk@Qrqnc*Y=1J9l=1#h`=w?2{<^j( z)|Rpo+lNXWy|W)1%tvk22+DbNd>$@e z<>aKv!Vd|Xo*d^whvJblTGG_n#`Di-rueW#sb;QTq%@0M;&1IZ#h8#vfXR7zq}s5D zjQM?jvodfDY=2O&5RTb$T>?8SnUQ)S+0?1&0Z6VE;7^&^-6QnJ`F0AOV*y-H7~X-< z2D+Tr;15YTH6AS+@sbbmBFqn$?c6`w{K*tN;E{-q-rh_yvTyOA<^(Z63*LUVbS4($ zV`~D6jfmi>clPyaj=Lkhf*q{h(}Jaybc(uS0SdU?!z#aWIIdi+I%*ZvdY z{n7lynXQf4R)ij_CLkF#q?IXIH}3Gl%^5ul>>5YUkSqbQuoDHVGMgSlhCglP*Yj9VHH_2s`1G?xl_@k;6D{C_fh$RdL=;7qG7`D6XtPB%p^!*VIzWq^Wr=_qQD(Vi!#gM z)qxdk?fvf0Jv{3Pu~xR{lRCSK)5_%r{%|RdGPck{}K?6Kd_Ntz!8CSCAV@xoBl+%1crVkyM{{w&6e8huWNE9ucO-aNeZ(*sX_KA z$u4zgq)nUbXX@{RI#?!UaBcHLwhA0CA%D~E8`Rx{%};My2_> z?L%d1B}Jmok~J)aiAP9pS$eD<5I8j~n=u4i!;8p5B2mTI3EaMa!F`mDUCO+Oxsxd! zXp#s9Jy~ZZOLN>i64|8kCiYV*FulD>!xokUyTs>$upp~eCaIg&`6N zvQ#Bgiz_toF|u>ef>l#L8#$<#U2lrIqx!dg6*Yl>Xf4|3$0q5W8sb|OsWRRsQ{w{U z*c(s%i|*$3qR5JYxp(jRaXgqpEHXE-ex!zjdj*L?MI$fS-Ly^?o9_Wmzfe;wjInZ3 z%AMkOp0osCY>_<@T?P^}rH^YPMStqHWIGmKqnEzRAKI1j=Qm%}f9Yk9n%iA1UGIKg7LK3rsVEC64tB9B&$ z_QmLfGVY&TRRbS=KMxW0ZV%eGA|b%K?okb21tL4D<||rem#wGgiqlR5iGL7`Z;nuS z9L4q8XH7#H#UXj8;bQd%_oAT|MjCi@S}oIAwYb}|wOWm5_y#1K$xjMX(;_OqdJlx) zzm7umLU4`nZ0RAp1rOnE0D5(9@C%a5DCb8zBfNr+bV~MHNSU^|v#EgHWdwdHgT#vh zeCT3C25NqRouQ$6MB-0rB7f-YkXYroB!@h9acN>I`CUeF;|*IA9aVgSP+%CSC*ys= zqtM&CZDHy5D1FQzeDtq&v6NA3ZPB=y(#4GZ+ML}OYd*Rfzi6GkykpY#iIGDF#Q7Qi z%G;TPO$9qO--$HPha#}iEq~qNzzJH1N#|ApyQ1lHJKnA{p3MheV1Fk1_=>4*;nV_P zrxS+({m+QALe<*#LZ{jjeSRws%^!pr8OCouzwUbA#4}Ls*>l7FP70B|mR|y75o%4_1x+o#ozS z?HP#s^MpR;FjaGpLDtl5t118$7vgRvDOTAfo%LvUqfN~ot$Rt{rh?T)ji@7h>;isk zywXFWHke40gR}+~vJt`Fu4XJeJ7Lxlc1c}i)oc{-^?4+PP=8&|AyyoU6LiaGh1AsE zEC1qXXh;`9dFq*DV{=OC0uAH_Anx2#{N5uVT{widJKmGn5rb5dM@nZ5@9XbRBmcf? z6d=0?B;As14wKT=@*i&{Ok$C2zlIK%Gyy@7W*H)q;g<||120312lI@6Bb_Fn-MHOk z7aL2WQA7d0xPM6*i5eljDv6DW*n#OU#pJ%i)ZQJg>U(44+=BT2J!xO?yMmN9c-^A+ zxTjXU^5Tx?KDK-2U8>4)0XjlfPfvmaW&K3Fj8KN-W3YVg1Wbvhq?om4x>5HN!SjbJ z+~+2a6LqMhe{S3&3O4Xb1EoGWJX~6;TSIrO^(0Ys9e;u$5BOt{4LzO~!e7aK;Dkd} z8V`lqJc)aua4Sm|!p?*|3FDjCorR57^{~Q@m$TggEn(o5-eFwE*2Hff0(u7*7Fx56 zsMpP9ovbN-S()VC&9+Y@LD(W>m!`~#ELLb+t+7(o$|?!BJi@HT^LZWpz0TUMks1uDaZ(2t)m_K*SO+7>*%$^y?dC|h z>IGk3g)o}i7sAmcXNf?M!?ML8F*0>QlK+JfC4Z%)l+Ng+|8fqR!BILEh=GqGLPUL3 zbM7ndxe2E*Iy9GgsYij;fAbP@^|K;)q-gS#YzF?}8P!rP3% z%=ndV%keg4DWQHsH@>ayq*AF6O-1`kpV)2106U&6Mq$Oo-%1;Chfrh-&-Ky?n5E}y zWPgc8oq^;o(wwbHGp9?XAa33cn94ZoqI{)zEpmt}o-V{LzP9_MA~T`=+L&9W_^P*~@RX&iZ_xg6;_1!e4dxz`=d*x*HL@4e>%&Sqyd zg%h<#j8%ET>LMji)1BSJFB_}+_<!f~OGz4391-+mybiTi=>yKkOtgk@F?m{Y!u;JJRyWb(>N4!yKQEu(Mn)_Hk}~I+ z39AibKY;f7eRnC*$Bj@7?kJywnhQ|}2W%J?%o}n@GqhSXSRe=MY9R;i=ew%xhG%&x#;lPazmZDXoY>btaXntwzEuarSAC`}rS%IP0vY3a*p7>D}OqC8^W6^ zuT~rS-G;!LHIrSk#}vKZ09}r?ckfXm0JTExPnFm~gKYpgg@4V9KNxE8sU1AXBoDkK z*DX^KHM;W&VJWYjj|bG5*vo4w6UHU}jmOZqdHn&nL1JQa2W`|6uPRX`XOVG-54;~x zo?D>-&CH z;xdbT=djj$&=o{#?)RDnZNRwyNPv;y<>S@nW#U^gxS#PMyXgAz$A81VY_0(>u@kry zX|@Lz>ZOu4dsK_C-0})TK-ziBU;c>Qu8`^}=nY4alC%c5i5*_c@R>&MCobn6*!ppT zFOFZ4h6wwRH1FeL^+I9#NcprGDjwZKut7|a>erOD&Zp_Vwzg(m+e~xx$YtyEc_pWB zx?pO&i>q^~cpWmfH-DNw-;*SfF>St+i#hVABqF^}XC&=|GvEr6C`|u7`R%U-NNn<( zuI@vDarmOlq<%;z!yH*I+-&p7(SZNn!S~K9D)pcXR9{PsDc6s~w?9sKGW{^$_KtBg z-$Vxz(nHEyeB3AAl_g$I1S^zC>eU?o%*ZWL3PV&NHXOcon}2xu8`vRcY%h#y2+wYc zB+Z@yVGqq;bM{<@UDIbu8-c{Wkc&J=M=-&O@0iR7=chF9WZqkqowN*?E%(tNVPG2J z=@{`D@8*|Xn9SrVcl55k;IrwJbG{JA7ifM1J_22Jjug27W>0me5OuN&0vUUGZ9)rPpSFEdg(!i)AFg@>Oxqn1y zXzp(6kAFWkI%uT47$!`i-Oikr{v3pjP{^T^n7qkjfRs{|9?@d_Zg+l?WeAiyAjLwll> zQCfh4;&B!pJRI7h6Y~159>D-hH$?Gwubah=)?Ocd4Y?pSDhRysFyXd@nIK4A*oyoYKbijrnr|-dH-~3=dM52 z3cWf)9MuOMVp|wK_u$jPy#4c(Zmjk85IYgmafrsHGmSKwRR%$DB?&%t&nqOU&(gnY zJJ>Uk*3|6?_7RKI1Dg$EJHKy#HOynH&3~yVi=VaUwMczpc7U2V)uEs$s&9j~q(IT9 zg=ze~!i0ISY~oe4!Gn89RT_PgP=~^M&VB`AtZnRN(2FbWMxw)zLNhq1 zUR$Y$n|4p$#UeM`Rzf}y*~~fp#@Uzl<_V4Ad|`7So$qUF+ys@ntrD)V7E9c<)_(%| zu9v4awuHT8z?hVb*{_r9Y}Ko0A9E%|QUQTJXC;ga^ee@h2q2G+VV8XohWa+E&3!9; z{MN9ZqkYxN5KAqxabD8aV*Jr3qNv~Cwhob{;7;*_k5g|;DtGAD?lfLnpi(T~ z;@2h$8V2J6d%6jYCz;G> zlsZUQ0%}O&*(wTof{XB8m)>J?O}f3|PmGmdafn3H9A3a#8G2kQ`{KrIyjc-hYXJ{xN}AR%@mgpb|E)Gt#K z=%Lyh-LlaRNx4`TIjUorm4Ad&dAcTee(88kIHfr_j0zrO`w0oqeskMji;4(bHMzBN z0x{5-y`FQd34K@R+UkYEL_|##gZ>Jp-~Ac!*lTybAB&Si6RueCs~iR;W0ySDIyrrJ zqujfheEqv?n*Rb1*$igTT_$eM9j?uHt^HdKNQ8_8AN1Mx>Y|SVW`Em71cBjI?J!6E zj#@VKH(@qJLxWW7N@xe?u%ye^=0Qa>F7%WzUu^l1jNFhWD8_f<2Z}#qLJEOg!EBM? zXJKC^Cf-AN75|GO>xY6`>DrJQS@Ml2JE_500#-fdGk>lzv`8^}K^Q-T?vxR@VJK+!2!%XS3%VGO5xyVNsWb+w87_#w z0?94f)2OeYsv9VFe4{%~+5!F?5JbQS+bT)eGU=r)l)}s>e>#=4=hAEJW_2avSWzuKXX%^Hyhs(ZL zk2@5ww>b>LP=B&mJ+r^GD_rGkGA>Poytv-MU8j0aD1VajLmX?1NzD$hy-hgK81lRm z2y_~GVAn?Xg@EQF!n}8J0L4`h5}G=n{6`dv@O&5+8N&0C?DWT#rYQXz_D|2S{BZr% zN^q0ap8vGXEb>G7{V|rC6NshEu~vY0AAO`udWO^NtAB}b?Ay(h#xLCv>GkbdZ2u!t zIqCnC)e)v$S1cwp`+V%R-hFWE9xWcKn5*?^_lw`pzxRZ82Re1w%k!+m+r$U7dIT7q zkXZQ*5h&bvAm$-mC0Fs)_8a#{nMXnOHi?WNo!jD!I>v# zoq#YoK7U^53;{vC6g#oeq1bAJ7gb+~<{3C}$1!m#6Om_?*+X0Sf?|cnnELusydL0_ z@%q&y9HXE<+5?Gi4p(&lrk+n!(h*oYulD#(p99;uykGGFbFiA#SNVR>?^XXELczUP z)(=%xAtZ~$VZ5e6M=nFM^;sX)#0F_(U*_u%>wnL8?tt$x$m{k8{i5oNBdqD7vuZj;rBx`JRIloZyIPv{Y>vtWxB$UH;lZCm%X#p4xN4kTZC48wB@ZdZVidNPmCIr{ibzsosyu**3W8s=4lh$s9MG=yfDj z&cyV9I(x2^wvYhjJ7s~-aexu9 z3Y$QEKmJLhf~u*GkX66}O%hZ9?Up!9A)ZL#eqM^3Z|4#pi~6V4*yXR^ZemhO=YP*I z3N@$ouEnKJp4GxDza2Ods#(Iom$Q{qn3l&!^M*oRy48qOOMgEH(gY|AczN17n!Gc0 zYXl##PJxnspXkUiZABVA2W~^3>4U9Lwy)rA_xI*&cC7Cp@fpY%FgyI+b?PcN7I;jl z5BtvLqt_*gE_*@^;`vrKNm!w|7pO9_7=?#xGs5Y&zJ|7 zjyL4@`RaF6apL}gwfDb9nys{jhLln^TeLjU&l4E^VjE5nUebQI^d}MI41ayWgdx*u zSCxV*F_nOf4lr(cJY%xrm=^MMGp4%#!Md-GUt z_@2BKf^0k)u;a6Nv<&%K*67O|4L#L}^m8{TtvXT4kI9I#7F7$LFJGQ_GKb=OllmtZ zp31ohw<%Na>Av#tSyt6tzJGL&>cvJgT*jqP`CvzUFBm!#OHqwY;!5VnvE_3YCzYpR z&=5IW!MnNh{q*z=GK%ZS+sq~L%SaQY_-AVld3R?HA{?^;Q|0W=Dua^aPo5Yt0~ly< zOS2O5mv7cf&MlG)KWXf@+BFQSeNC_nxrc1tymHq0O8MS)aQLU*4S!LUH@Tw3#fK^I zUUU|oiRK!@`NTz>kv4uFw_(oSpNYDyniE9Zi~Y5!K?v$Em&$39U3Ubt3#MUUfh*>S zqcll^>JAwQ_=wOD=P?iRby(M2T76qUB5)a}s5@_=_L*7~OANrrGL8g`ZYsO5Io})( z5fV{YfIJtbefP@#Jb$EdUdj>DKTnB&U6am+28EM-i0-dah_jsN>}HE9$T9L!kHpqU z+UlfZXHR!1IZYMGSw&6^zITubvdt1^W?aBi3!&R)cHCHfwmq|b%y?1n#)0vW(%=++ z$TnWs9m-HM4b@h3q46HW3G*wvQwvSZVd_@h8OT|mOx4O%l>M&<2;9Qr4&(bWb+L z9eIblsO!BYJY#`rKkPK#lC|_a;8=k)Cz0uW5%cSR-&0Y+t6R!C7||^S(#ceClHz8y z0VK;|iP0VF^?!e!1>Jhn)4Hik`F>C2+hWp_eGS$Lf09b1iD@P(7FQ+JXCDY(|(P6P15^w9)b-ZkyhDaY1sW)%6NRE`Uf0yI>C6AtfDWqJ%GD;}MavXb z!q_(`A%A^mV}<}rAMW69hzb5G0?Ww5;}Pr|3vtb39U9bUe?#LsW0Ib?7#!k5Fss+! zPNfAVhXUjNa9gn65rlrCZg*VI#dhrnzgA2toiW<_{kjVJ zS{V@tx77H;Ku&BiTiId@>e5Sjb(r~o*>Lj`WKJQ(Q>EiCOM+}cDtuQUFkTlq)fwC!Q%b$+-SaEcnO&y zipYdp$^IfUr4DE!)4?Kd1G!tl$FD493g{!ZG2|<69KbLwiidFKiv1Y|iOES;89roiD1Utk zMb!_uB@W!&2>%r?DjQ*&@6p*|)YCCRflsq0)RkgC7~2CM8rs1OazK+QiG~v=*?P)n z3Zu#NNaun_j2=YccgEEVMc>y<1}$E_RePWXX8lHrRiTR28#%;tgIvyl@ayNBgA`Zt zc0o25Z5kV8xZH67vCMBTt((gJkALke9JGe{SEg5%EPoHoFyG(JO9zpVXE^hoA4u0l zH!n!ddq{~3#h+9VXH$8Pi;d>G+xMr}9f7L#_V;at$co9TG27m4zB1S0R#^hQ?W&UC z0e_zT9y@o0d!Bo$AZY8kvsO7{nQf76O+DQz2($*jv43#ku{i>5 zs$yDw!Pyrh8?BS`j0q2t1@qi}E;EMkW0JzHLPq$+dGH~xSSh2hgU(c;tp^ZBH}&o| zQ62u`p^ighcGhj7-55R`MD)zK0-`Fx57w8k+>WrV(DKCQ&pyf51q9y~jJ7mvYRt7- zY5|k-=nUw-FqS{sX)b5b`&Zhx!s=}tlVM;p47gi<`=!@Q^@p^- zOW~Y<3Ki9$QCWe7Pc(C&`zpA7=*s#ZP*H+&eT9O5l|z;*6^I8WV}CaXAL8s637Goh z%qq2eei7^cMu?e(+pAUoi~{sN^#ytmNjUQIebd!~;6q0kBCK*X&n%D*V8V`J%hO{p zHG=SWvn0Wg2j)I5r3fdn*t@1T)AJpHy+mAB;m}y93;0HhBVXDZ-?~-Xx^=qt-(YmY z#phzieRK1EzPxVvXMY6G4w47f5vN2Ns&)O2le{dVkwkdPoCgMvLV`!e<<}l1&jyRx z<#~f1cL86h&g(UF#adnjb9QFwxE^jlGP#H^%dI1QaT6kZ{dC<)iBMVNop%8Y@pY55$>G6??J(w6D1`PgM9n^dGQe z`!WOZIGR0@xPR3MF0xskOqwS2$<3q3aCCYkje>s}U^2$c0;QEAb9L}F(r6bD6=SwL zl;KKEY~Bg!WAd0x{#=xy?DW><1btEth!JoIR_9E{!%+e4-w$zBYaM;iL(- zq3l91U3ZFl>7z2ty6tCS_ z7$BDUqJPcW^;|MMz^3Ff;w;K-nF!0Y6J$mVi5r+hzH+40Vs_7mJuF0C9^YX&_G)&G z5ddc%+FKc`FP`0~%`$;roQDm%C@bfID5c7>?Wp(IMoh`Q>qNW5U>m`wk{$xr326^8 zp#qv^Bm7VWr2pGdi>^`xH$@=E$gaY}w6jY)1b;J`>%4pM=)^Jwy5OobE)U;jiE%dC zC(iv9LM#j~ldDmjM`NQ8`Kz|;ieEO&u6tBgpdaP+A_k0O%v7|Z3_Tyx#pvS*LYbik zoUk zkCfq|+JM_kKLGmw{OLmoZsCjW;Me)IKY!O>NIYtRa{Y&=xz(F9Sw2-F-jm$}`birn zkOW$cxGEtclvb;_sY9h{YB~2YcBb|`)hzgdP({^yozT!Hmj;+^JuA+Y4Nf4$GE(~r8qIM7UG~K$t z)_^1*s}IJ5aV-D)CT&Qzie7v5QCgOcfdALyixJDx+K!A^x6fmXT z0OKz6ZnW0O#bbHg|6^fjfPrD?Y}oYvDAI06i&EvBmJ;;4UO&F1oD3}k6n_`anE(~J zc{hv#BGT&GZkK`!cu+Zp4yQvIJ9_)tj)W)MxVL)MoroIR5pQdM+LzX?pFn-b-gje! zWWT~a2cUQT%96=e=L>Z78)xns4b4ZS2(SnFd_e!oYuxi8Qhg#DT%9BBwso(41eVe~ z(t+KN6wusk8bn{6>o09+*nhlNL2^w;3F^zZ-_D^yRnlAxg-q-o>UG5}ADG8xTezlj zZ_;#8sKb5?MBf}wx3kZ0`H8HGwQ-z^LY;s8rSS!0I?F9L=U1)d^b{AeINFeNPlV=R(iW2rHEdt~?{G=&tt13%rwU zORuZ+R2Y~5ctD50t+c(!<+(rw*g7`;J3Qi)0uHX7GTJEoOvJ&zW+{J5z&XLcqCGT% z9aL7fl3e#XlFojisIbj&7b?bmaB2_eyn;CV@Uj!bcZS1E0{Ux7C1(iF$-IAF(7ht-B_D#N$D(7x=GM_4{lUYS<2k~8qq$Uhss};D7L|?W zCr1RYlV2@pFX9&E}zbcr&nDyyqagm%1rXBePHuohEZ;OjY4Uua(zrggF~8QB|#X0)a$ z?!9G&`mOVsOOVL9q8Ta1OW+v#)Je7N8h7OEjF13T&kH!`k6kLJ_8z*=;dPuvph%*L zkf00{z4^NwFPneUNU~aJ9~=}4UM7Ojyyx#QQrTm2c22Ufzlygi&3jdA-&>(v!QwZv zmgMbB=gyD3Mw^aU_t?Mn9Uz^KVXwihQ7T$swOL;>vmFYuX{5s=CFV>RV7PA&6NRcx zO==Em)xT4M<|u2SRVQp|H;}67g^G|ZVY|jmQK>~4NNs;E8;4G5Mlw(Zz!&>gy{WKQ ze07!W9d<;ZOd3#7xTV|hS4@gZf;l~}XM;Gy+A++Z_eD9uHEbCp3Ve0u2oO{>Y z!d`P2Ol*JtP#2yd&68^AfjY4wB)pDo7TdUL)$6+@=)d`g41W};tkO9}U z#cy4fDuX~9o076m;YfS7$VP{wAjvWCMR{>JgcxNME^K{Qhl&XKA8)#N{Ds zVQwE$fE_=yX#Ye)OEQVV_hw-zPn<4^iHQge@%kb?xJq5SXQ__fT-i^F*`z?$&ps{- ztm?J|7lPkNbF;V~dWv29E8>ifcs4}!E(8|!1#~YVb9X_d??)||Vo~iJrkjg^BkduB zd!m022MnLu2dt7Jm83w}fx9-0E-cutBy2z~yO}d=NF~nLbFLzuQ6`xN=y7RRf5+Jl z;oro0_|amY`W0eXih{Le-=C1H(_v~MyCC;%W zY%jBxaNIC_*=_7M|NCOnfrIZ98npP_N*I5fM|Q<0xVWUg{? zmNxpF9r{P@_Ml=Zw_6v>UBVIEPimu1ZRdjACN$Kjw}K!l&S8=6Kkoq7eSc;WFb;oT z<&d7!iuJ)AN+Dl-*|_-T8jUtbx?;0vU~A97#?NQLRw@8*+3a%fo2 zvdHXkm2|emn=fUNNY*S9E-)_lM0OsR2oD@P48zhV?Il^#PfO-7jPAmEP0?Paa?@I} zgMOeOIxqAo$gPjZ&&MbIs~v(vw_|@%ac7`?tplxbm7UtMf$(L@USzK`c{lB%+lfve z;C^ipB5!1XU2(9hz{^O;bwc9&qGwXBwpV-d2O*ndM+#QhcBNN_{YFi83Fy61;`{2y zf&~*5rUfIpJCiFz#Q`=v)9ofBJv@;IxFfIAhAyVwgH_LL*;?g2E|U1mP}(#HE8SIQq+8_h`h++#xc9h3}naQS*0UNFT|7RE^_ z&DJt=A=TC=ufP()M}X$sHr_}muV2@#*f)RrZC~X}Eu0BfQY*J~M_D$@exrHj_*ib5 zEa(Sn=ww29uY)aQZdQLaSxp}v$H!DEy<(}iSx0{d2ieBG!aRod7ygZQBXv1Myxxc2 zo!@|{_2wi`5G3sCu9*oaJb`rKzP6wgoz@bUl73IzXkZ3785ZB()9m@@+w4$Uaq}*$ zAf`OQCcW@&;sG4==NoZ2%v7aR+u_%b;)sLkSCp=`v-r611y-z?1MO_r5ihf zEG%i8f!`yZ5}WsHzR3vGZcZ&0@u1M3FYQQ76u+_#mh=&=kv!nZ=hhmanQ(^1=N`^omi7RP`Y3gCNSj=Gn$Tmn=nRzL) zX71F}=m7M`xbVbMHC7pJ!|WeOZ4CG?j=(pV~9v`O1H2HK16e zlAQeNm695hMxpl}{8UT*dvMu@X$n)HiYk%YXKbn3Cp;VKROG#Wml5M4X5Q#K5!>~o zj9R0GV#Mh(1-t14^`l0&Blo0veAx-zZT1}PoIp6HS(#n-?`Rw++h)T*V?ftXOuFU; z6>+?PKazjKBmsMkPBp!HfiU&r{n^k~(&3SRA2AW|8(`6Ck%vU~MSZPNn&(bO-~Cy( zYO2bP#ZdLvZT9sNMq&+Vi11HQP{3+GKG}QbrLv*OuMtz6A$N6HH&ZxO?+Y}Mv06hB z7sP&o_l>}m=3*)mIjffeyqpli0xszTql;Q+<8FWMS#Q9>9^bD&Uyg*y{@#6?B6X>I ze2jP4GJYW^f2moqns*@2P?oWX>!2&+e|?Q#jkicw`mUrSE$o@?4c?qrmqa5uXin5Q zy_yf0H*L=_YJRQ>1fP(>KLod8K!6%%2_;_lG8c+_t;qTp2LdO2g=Y>2hv+8<_sxO$ zLy~{_1O|((n%-m>*HdkfZIeGR1_4zn0lb_PaD@gj zAOfS4^ez`L;y(#rE0(TFz}NEweI1}%U?8wyN7>><|ImU6Z&>*}Dq%@8K-hmVxEVv9 z-Q>XtILH!J*4gDqCP4B8peM~qxse8Jj(Jch^zO~>;m>dOg2{_#gFaFyaQJhQ45U&b zlQg$oDypfp4rbby4K*DW!ps`XZTCa2ER#RRzzXNtV_|H&Q#=<@)@K#&L2pH8 z)8HwE6&Pw7ewomWz*6SSj+XA9gK70=?t^pAfyEX-HL}TDk7I%4i9mlB2%8?6ApC2S zirVpE2fa!?cWYz#LTRm|HR_1S6P8rT<6$=2FehjDHmF|#yE+R14c{JZB#Oj>^BE?2 z5b1!I-e+;=(+P#m75w|cHIIqMaBW^cb6WqkdBQahM~}zpyWKIFK>dMkMQ*3sp8sL3 z$ScUh3Pm$Y*)VRUeE5HPe(gPy!8CKN@Nmd~FG z-i9FLf{GHH$~_r9wtjlLPd~TNWLQUbb;7agVJWr(pQ<~Cw5Q-7w0F;8E1nhHq=;@( zrX4I)o9gO7K1qM->D9T({c~xp)2<%-Ah%VjjcMs2@tJjNjd9i<2WyB#ps=#wz*Rah zc?nFK(DNXZXlNk!U?@2Y9N*#-F7$&do}FY9b|Q+YS(B~d|C4BpW`6ll3?d7YRXYj> zpaWNi>A1UquvQvL2X!%GA8wd6{rbHeS(Pd}&e`z&{WO0H9a=khWw8aqSu@dT%bR*&C;v}|(+`-y^vn8B$?z!37g4?Ist=zLF?={YD>pn4Y}f(Om8=Qt>kxHO7~hI&))OhpZTMo<0RPG3U+6}nPsFesta}6 zSg0fX>E3_80n7YKrEn|z@RFCF{@8-;@g!59cw<4tOg%?XlkOB23_y_pu)4;o{79i` zjvvvqH!NDmT+r>$Vsu(3`pTf~N6hvv6*KXjZ@i61>qi|(b%ldHMmS$on^Uhk8lFfM zT*p18Z*EydvDWhHd>#$C`8nXU}%aSU)rbsR^S<0&DXtBu?k_lJ@Yd(Rz-gn^_w zU2^$!PWRVnN_mC|#UNc@rOe|=48vOku+V>*8{=%}qH#f1WxTn22PePg>R?*9LGx^? z58;1OY?a7X&@f9NaJYuo=Yr9kIqa!M)OvFLZqv)*MN)4k87Tix0LmXV;3Z}Bzqq|g z5o9v!F$|Eoe5&;r%i+p>E^c?ME6jgWMXrcgHpR_?8B!xYP!eH zSAOs`Xl!wPYy8n{Z^+%W-Qt4^6u@;~8HRrle&mqbrpf3!$^m}uB_F8m{P>H(vCN(k z^17ta-H6^^?+Hx!qf{_a0;R=nE%#P|4ST0y=c{$(wJ(lx;;oIgU;&Wn(QqawNddI| z>#G{@Z#to#gw5Iwad?6sNI);Q*W6dl2`fCia37+$8sHk5^INdQI3e&(yGghKoaKKV z=a9rd$lPH)16G0GDDT`4#bz9b;y13mIc_<05tvY{*^mh(Mz5293+S{HO6JObdtN1)((y&MjN=tq=yZ5oDPf1=6AVVik#n`)-D3yCAp6C{ALn$wrjD384uf7tZj4G z>d?_f-|^*yr!@(9AHGl@mhWqpy|sVe5Bv50YYq9+WP>K;MA6JxdUGbfhLztbYS;#! zm&qh|O+%R+e4j>P29v#&_vt$cx9gA$3RQ6=2HeOyD#JEIfKGUw+I}m}w0g1ZM_oIg za92Z<_f(z31ac>Fzk4jWZV9vO_e9NEah8M{Q#%QbMeY2w=iM9*1)Z~JB~O1TEklE!BBPIgjeo$n zib)$n@zl;xY^a5Cmx{aB{|$oj?pfFD*SmcNJQXQ|(}>%83qmS52pE4enJ$+@Q&xQw zvZ*0K&0MUm!a5G^!uY+nX(2k#*5GGs>x%L4(ziBODj>Mbdq&r`1bH#bB=g^YN!FX1 zyb;DyotOuc&K3!`5nKHZFOl7l=l~|E?m{vGODze_$rAG>bRe^qi_dV}T{f z8$Qqt(hTmwMFs^O2HO8tCL3?O`I<-6OJ?vBLD^K47yd9#%N%fp6kuPLW0KRP{;WR6V?4In(3UVBfScl}sQ2Nq_xxB%_T`_H>4 zH(D=9!i+>jNJmDbgH4BGAL>cNA51&k+3R@VQiH@vj<&c$Jav$)O%BG}kA@cXZftRQ zs&eLAINAvMJ<5L{xr}tNR4n#FFCy1;fJ!(JCMntP{!96TH23}J)c0y*jiS;%a56_zpDgPV-S;-sgX?{H~33}6& zP%C87FyVi2z`(}Fq6x-@O8t@mo+xPAd>(u+D;@lZyAv6hCTt3q_J)dN+6E_}+{-qn zqc8%#dJ;W+qQ{0nCZ*%~`iz2Vjsg9o3~hJw2FXCa(KWYBVSraTjkeE(op2nA?!*P3 z$pMpSpEn2>=vkYRO(m-|*WARgtfs>flIvF&#LRzHYZXL(zVl6?&}tpH7{Nf4Y$#3R zFw)pE1#+NZHbgh@V(0%w!U`#OT9_GlZeA%6 z03R+|GTv@-uT-k)Un7uev$kD;vnGb5aC~k^%*0t7)(o#MpjTLODt=?la*BL4ES2$* zysUp=F{C~I+%fm`tk-Z(Ih6BkKfxhnI>E(Ctw*z>>{$fi=kchXxsfs4sm=KRy5W{1 z)3exE$H>`7)}J5)Nf;08EI~FTy!rKPY08?^4K`B0gnau|#NKVtks1honYVz%%wr>i zPN81pX!?+jv_i{+%*j0mGGtltYMQ?UO+DZgXU-jUtkJW*3;vUwJ1=>Dx?Wb)%nrW>kMY(8#7)~P}>dg zU;`zUbN2pLpmR#T#G3B81EPKQ@-cto?4M=6`r5H?oFSD~_8&SiQuj& zTe($Om2*4%_Rl2^&^OEKYVq zDw&0k?1_%cc<>~qZA(kcbL3iP6yR;FOBN<7vOL;kHxizwq6R1`lHu`7zlc*G>T4+T z$QHIf+zKWMd($@EMI@}v3p-wq#Mgk@9`#FYI#9c0|(WsUWOsKft<1TxxE}d zl@QAbqm=$a^e&8O#7}<&$3D&_)TpOW(<_4L#`T*?qI=i~59G8&a_GpMc7XGRg|kGF~`F4Bdou?I{7O(9uqh)@*;w=ON|3VE9T@ zlPTmmSU6vH4!=&8HkC(werC!+IMlaXmwTYfy#BMd zfTbiI0}Er4xrSR-Y*Xcd9?4ZteCYSHoc=B3z;y4GiUjv?ge{2hfBE`w2FBI(cvu7c z#xq-Iyv{U2_1V-0DusXlCp+k8BG;xE`l;x0^P$o^)gz1?3Up0u5sy0CDn!9ndeVnW z_9PMYpKCg#?LK-n?^iL`di#zF7zg&56RGo9?Q*O^6F?6vx^{`?eBh`gVN`c_-9}%E ziW%%JJHz<>gw{R=Xy@RtyL}3Z&W=Y3eRYNzOw)LucLBpgCsKbw&Hbg4R$_|puw zfM+EQtHpjD_&`w`e|ziuFk5qI)kE5EmE~i!_8|d@(wNp1KmYZl_19EcB_f^&%L<5b8Z-Qlem|UF zzQDbn7c(<8j}d?W+2KFn4PZI(3}^T;k|G$DE3-SV1EN9|RmRYY-3OT%`6h`rzDi0~ zhpEgO5tXnrMm*Yf-|FW!t5g_?9;jasnk*oaa#X9MR~$|#rp;@3Ir%*(XSzAJ=LUd^ z9KLq_J_bNTx~@agkF2Oz7JU(d=-DIu6FsK|#We~X(E5LZ16Rr@f1VV*THGn2H(s{? z>AQ5={v9<58VYDX!RL7nHo&guWr~D;+oN}dGLGRSx;9%{HKTWT3w!v5REuvoXU6tI zOiRm!S|!xrOa)y+$=xz0mMCx-d9|DZk&FVYUO%TOP7=spy73dJ!BrQRI=9$ms*Oj% zbOnqkYBaB@)%&y1#sZgjHc!}hgFqbLXZ%X+oR;?oT~ zD`z~90Io{V7NkX+I*RBK!ktDo`)2nEFl%$RO}u{`{&Euoc3*R_ibi-kYrWa9q1+?t z(kHZh*OSFUSE(b3<5?k$ev9Mb=)!>Ych_484AL;!*ofj7Q3VnxfLF=UxCi|l|B!Sd zhH}ZbRXL;CB{0vbC59#u!r5bx3_o+HQp?!%{;|*;kh#NlYwDTR_D?nW#~4-O%5qFR zUH^Z*N@YunDGDc^kGW)Q!IAioV2B=@Lr5>1X+ydlhApy zu*%HGGRD~j4$J75DVrE-&jz=^_-d`Sg2I#$UrN;eZJJhcd{uyZZ-b{n@pW8!7pCG? zagahT!+U%=KS0e3lIg#0Pq_Vs0dS_qxt`{#tYyFN>KGmxrN?zi0*&* zylnuMe|en+^jfBdWFmkn(V9)86QlAub~y*{a?oTre~X+U%D`I>i)#1B$3o?O2nbO@ z7M{|yhSr5_M5ok}IYIt9S(D*IpoZK-QK?({?Hnetr7g?tw;r*gG{k#Lnbj3UPHe?3 znT%@o5Ep~A*A<3Yq+%FZuEWK;i2i@ma1|P%T)9J!c=N{m1@Ca{JQy9O^%|D-MY@(2 z1&t;Kb0)wr^rBH|XX7uGYmLpZSj$i$c;V_D?2qXjo2`Yv>N4S>21-j=6jFlI*oWu9zj}Eae04g#jyE= zRiVF?p11zpN#LUqAbKU^4<6?!(xIMIqTAHw)StM99jIk^R30VWkjC_j)Sa4uw<&E8 zJ0sI#WV+VX3;ab5RK6Dl;?OBFpRma`wn!gi{fX+haWkpkO& zsye)pe& z_O0H52mBQSyW=AZy{W9j$dM%G0}6@;2EYg2{~O>I(1cyb(=cpYFa>`NPeryk#HRXn zlcB=@fA|F%t~5W4CvNM59a`947UuCQ6LQ;=OF~Dm!ECrKo1Nlr+4g)!)V!$q+nRL_ zB*u>8t<*HHY;$W=g5$eo6~dx_%eS*Ql{Kf2VHFObxKo-oOTKiIEi?oYud(#TXT|*| zQfb}LURhe_Z$QtcEBJqR_o6gYN4(Abil+Nw77f94FFdIZE5~vivrpQO<*l%ysZFQb z6O|&ULH|2=g*5&{bWbvnkITYT0BS^f&u9cgz$3Vy9kuV80X;OnE1@bajEDncTLEUb zk;>RxdEU#2)0BJrtVcqZTKPi-%UA3NSuTLu4wkyjh;%@#);oU$9u@`GiU3z1u1|lK zS)IXsCdcwPjWh1d;N(!WxOLlU|3Vc%PM?6>HE2*Sq-HM5#mN^t`GdB0;|TKK(X?W7 z)x9xR&mP4_afJVt|NBS}*#b~EB(xVE!#Z5sv^7MM_%{r5Et}f!xq2eUYt5fO`*0&3 z-+%3@JXCj*7CV0u)1n1_i%4*gKFU1fruHV@2QY4#PGrmCE-Z z*|cGJPk2!v#8ya}qAU%O1o|mG(dZuiNqIVo4#T`36qkW66qsS$Ok9WR_AEE8&Sh?UkLtY8?-a8;(q3Z|3jm%Z35P=Zne!Osvm z`fcEILho709Ah_0HOrY%v5|+=)n-xbDNf7%B^Ir z?D)KJUY{KM6!WytEkmX|RuBA-@+elFQ;vEOI_c;-|3rK=v>m zT8^-P((`uhho$6_f#sR=Ug62#npfbjJA%44c3f^5{6%no+KpC73dyPj9*;+CSRr4@ zU)6uEq{~X_&%#~taP=kQpy>~f{s+)+dV--7?G@h34>Ca&V}M^o63=OS_X401a71Gm zC}x4_CEHv=rvFkkfLMSmS@>fzT=NXKQUt`rb^(-+ymFSt$Rnt@>DUT^2urRIJoadI z(tY)#bov^q@>t%=Al=lk3Hu^RS!Xc>O=5pD*F9exus}(!nA5<5N7_7C2OUkI2{t%w z)63J;!G4#I?G2kV$6>iUL}tOc+~lLqk2Oyt50xiWU>`S0OLgikp(%2r?b)>{!L&aK zYvNiMPR63mdJ^+BUl*Wxsmv<+FL?;{RcXR$g7?-K%8yu2*EJ3Omvg-u+W@m`{1<YEwJVpPZs^gd*pVVS4Z6cGDxhgKq3D46HS4 zD~{trdDlNVUV3|HDCBE_7 z&o7L0`2|$Hck9BQ6+M~S<9L7F!(eozu#VxV8w2hX@jac`4Z111g_lJ_T|5IR5qKFV zyJ~(e^LMN9uC-ZRF~Hn17OKOx4-2O?9Q2rZZr-Z8(z;TRq=@PI7pM$3#Lgk^5UmQ4 znXx^6y>}OycK-`ekLo>oaeSW(21O_-Nhv0v%!3zGv1=@=} z>e#S9arENl*d$_Mkd-n_2{qgaeW{x>%#%JDGTamF)2{DTb_4{y6Gif!;>tqoTwL`e zyDIX?y^PEa$_%dxsDYvmEwg-2h{*QV`4YGb+`EWtqO@ns#dwLYq}l~X9~|nyvrDX8 z$lEyJ%wIC~v)8&bnI@?C*RNQN3)qufgA_)3Y3zwYg{kF9@s+$h@PRC6vC8&)*3 zz4?V45$(})!E?iEO4tRdv`tgL@FaG*(lOU4cIGWb>sQo!0@SMv&jn=PI0FT4mkEaA zSQQI^pHp1Ga4Z?X?T{1cJf(3k7;y70T(WLW=9wzNUxeuiNai>hwXb{-K3rr@U~@1g zVBh|T&apd13rc@0z3}#UWNM8n25Ir|7Cn9x;W&_S({}v5H*ZBuo;1J%Zc0+=@eR6l ze&3XTfvR5&>ZpkA$f{f!-BfV5uP;tFm)m!G+Jf0pEgX4!Xx3Q^j35gU5=b0`tMS*_ zya%^zjWu5EX#!-w`E8TQK@#lqbZx^;EHm`4#w`9kTLpiDx4g7w>xQCoh3P-Y{d41# zoba6uP93yfCWbct*qe6oRy4&D>G!g;+?n)fPr9cnYk-U~h8 zyu_Yl1*O25Z#W$iI~XLCFS$oS!Uq2S9enjf7MJd2CAiUs{>$SDd>zN=B2sz`I~TE! zTX-ygzMFrBi3DR%3fy#vh|YSba)u6x$Mbgp;3K^6sc4q9RuYgPs1+^;LgWt}Uea~x zc{w2hc4UWR=zLT#EQ6;AYfKu-k9n19A{+L|g&Q|P!@kljDI)WJ(gb1x$`|rHL ztysZ7u-K9wt^<8vh>fGn>!{C&9aqe`=Jwl>5x?Yo@gxs5GZ!eE@Z@+hE$gbd1PemX z6?}ivB+>#5rML4yA`G4y)iKd?O-eXmHE5#gFw@!S{(^*VEf+snyH85QI3b~9pd*rG z>HoVJh+l-F&yP(Wm|o5ReCEe97DVD`SdpGIZ0LZe47Z0Sw8)YzS0`(p0lWfS$)9^( zPFO_|Wd#<41oC-;Jq4mN+j}*X5{)RQK2m?&^pc1EiWVY3Qu6_!LqBV8nczX)MYp(3 zi{qJUbV9pu*r7?1vwJOJ<9GR-A|nWhdiD46p3P@=2b0w!j)EVAdw|LYnjvB|T)p%m#*C1h(^my&F-T7zcB{&80TvP}*IcwXR+MbcT2WKJ;Y}h-ep> zB;z|FxaXiC4wo2r`m3Nynv58t(Exv!dbAsB02!7qGlWBD(pCu7J9T2+A6Lw>`Dt)A zLjXWGIV~6D!N1p_X%rq`ls&AfubrNa$PC-elPGWXHF@cuIhZ*M2c?KnXduTSXQ6*e zP|r=ZG*-MAhomNhFy*w^kGw3#Z`|JeD`IRzFN$I|LL?y2%dAM4=YwWL27S*H0;Q=#2RyCnxoxS<|hTgE6|<}rAs&y2FG>!5$H z7cCetiWi#$3qM(ZdFk{1d2D}dlLid}cg>6l)#&y_){ya>l-{*G5!9on17Qfix3o+v z3BEU5sg2JoHO2X$cFMA=o_yHNpciWlCTe#i9lhS|J-u2kPk1dqRGtmGe&%25r`-BI zZSPs&w3Exf^!6A{6x1$fEQ zn^E%t7-ke+5J1ku4O{+%cumSeTN9F6yy8bu1#6-1)B=LcZSsy>S-P)pC~pojJ0Q1; zLW2)X%4^_$NqojWQo5Zv?#y*d)J>8DE%MGE&g{KW6)SxVSPwa^S{ybp#*Ubvdo|-4 zyO2h`d3Vn$ISTyEQ~lntUq;&(r>7PuokSxLH3`i!YH6zNphpX z4S(J}!CFwo&GB5Wk6XJpClYx7pEzWRO?Vop2Ktzm0SlPki$hQEAPp-20i+bdz3=|R z6aPA!VC1l3Un{s3>XR*Cm_BpNao_l2Z|;SMcXZv|VWEGFK`ehs?w#G##qQJty;-9x z$@BPIazf97wfe?uxI50@v!98)sc7?;1NbQSruqLKCW z78uD30(VKaXhlPNCxETJJ+T`Uw)BV}>2AFqzoeKpSYKSBi_OTG(+K3v@ynUJ(Cry{ zv4;wk5Nbdha{E*HhYb4gr_GVPo6tGon)_UhR-# z*gKvN67a8erRA(fT|_T2FAd%k!$~PktQT-!oZ+a0)D-2~Mm?m2OT3iqN}e9KLqQxf zc7grp$z>&7dYYC`RI*AVmM6Ej6d<8(lQR)njX|Zag`NA5PyCpu*WE{k4TjkJRxlY; z%|sBJsiA+v#3=+Nl_liPz4Sa9BBNdj^k~?hz+ng(=C?{?@czKkri`%+j@^QQuSf3a zZrXOyxKD*VLIZzEAG3C!FV+F$pWpbEoxF**ab*wj!>g>uG>jko+R#c&X7by%< zW6zez^Hq6n?$rN13CrX+P1OeH)5iXck6>Y7WP(jQ6%~p;4E3)r8O8P4CIY6ILE)lE zN=QnvrFCR@-U}Q2$$~$X3zh;c9ywY_BOVQcTSj>WN%_> z3NbM>mo;1iA^|d&SX=`s2RJb?G&C_emxx>g90xctF*GzWIhU(k15GqDEix`PEio=M zFfKAOAShI2SRhPkc4Z(kFfuVIAZu`8bZB#BVIX#8a&u{KZXh-;GcGfiGF<~G88|Zv zFGgu{b95j!IX4O~Ol59obZ8(oF*K8*87Y6gT-#C{xw3udE9&u_m@rkkOA!-0!p6p9 zkMVenFLMb$w4n`sHqZ<-W4yn9XRcIrtEwp64a|u!YL%qQRIa=zQ_$8`Q>iMZO3|mc zRjRbJ^ix@*GixhEMyGFzTl#zs}1NSR3EL?W7|@`+xh%>?SYrm2GB z&sY)3plCnAR3VTM!B){EdUgbp(_4RmNt9l#8xUb)FDu` z($t~F+LAa7wGJc>%;C?su>dX?8iQ`2&9EVVphNpjku@-C5RMALsWYsDk1 zH$!xMBJ?yVFf_D(o(-A}hA0PP?3Usw%Ss}e!86+Q837b1yDjAFy4Li>w~fufbs zXd3ZsAFOQ}jE-TZPolrYa>vMfWco3Yaujci)DX9R{Bf&(_w9UI)o&(8)2(`EezusN zEiNlV7X5asemlLKUtJtbFUfzrF|ap1oK2q0ud6>B8t_CiB>icNUcaFCh$*l7*S|n` zmxxtA{#ez!gtO%t?kbW-x`ebxm)6&BF6IaO(?#_sZRP21Rll2FFRD*1sT=pGRDYA{ zKAR-dqm{j_Q8%&{rSI5&T0x-ZJkI)V`>ecn4eO~LPpr1w*Q|c&lLvol)vh;eAGsgc zp6&sU_I-G?y$?R+Mhkp8n3Vf3@L9>ygSo`Ez@&p!iLGI;yA9_%Vr7~ER`EVqtz$o> zZIrSXGIngNz^#Kbg3EX8@V>TWY#$$^{{des@hNc|wX0J0(l!b_J2>Bn&s{MI15Dfl z*~~gPbYxrulkekDs^x!@%PE=k3bXVaA-eBEBX?|0IN8P`4hZ~QiI|}axW^W(N>^o=SSpG3~evG(7 zDSXFL?&|_>kT*JYKNlF0xTEe7wU&`^42k>Zpl*<4IeS0Nj|qP^l1`OEQt{@(4e?@W zLAML}XH;R^&{kCyyxpcMi(HtBylvE|jtB4{E!8*MR5Uhjo2pEkwo~rQcyw;tc4nEZ zjd44o$F-v2vT8XeYcUp^<-19F>f?>&N}0FTZ*yI2w&SO*KWUt}7A=iYfl4c+wX`dp zTVpUzJLFO;(2jp{n*z;B8;mDP(mIVx;G#c>%KB<&f;1igdVVWT}^z7N8HHU}b0Fe|D6DW|dUzGQ;X7wt0a=dc zgEphjxkAIi>Ta!REbrwD_wG0umw+ujKv>W!Sv?<{U{?43ne3{7XY+|Ao<3@WV7;L3Z;|L0gAmivItLYiO-3G*v zs~VweV}jrEUM%Gd$O<{M@{vW^16hBr22cDV4F_q0od-sfkuy0Tpp+4LCy(%IulQ|_ zjtWT(XQm1{3A{qkcF0%~La^tkVaeM$jg+XNmlTZT_el?|sQWQY4j%SUAM;iRNhG6* zk_*3ViHv%(E~NI$03^EM%7YFeZ;f4aq46EJ}z5KnKIdDn)IBa@K!}0@xJz zREy~23Fs8bE%Bo1Tf-FTMGO2l)p zPbDcd?7<=fREX`ARCA^$Rf^a!qh^q_^Da3dmeT~`gijpybrq2I+8kdg;WYtod+afB zw0111gFWUdwSh#*=GBx1Gj)IZWWDehOD5SXPHiOD-tjD-S4Fj?C{Hi48~? zdr1u%U8Hud$d%Ul(cei6oneobYMm3Dpm5;*N~7tu|A{3+Q{CO z;McJ+hzoL(^KB2$1&4K#EJvKGQ7`Wiq$FiT9IV!3)@Sc5+Z8Gn8IylQAY@x1`!k@3 z+{${kCyqkYhLH7Wkd#@a@;Xo67h%;AWf9Scu&%}+TaxpgW486|X>6IKvjAQ4NCWjaSzAQ-Qtu~gk%DqI9aSlZW8&HA|~Vu5%)4pZc zwdg6oTdbEglp%j{i#s>bTsg~#Ne?Yqj6uFsww#OF+~RV9DkY{vt`q!k4# zCD$fvxHa#*M56sE-MtJa9Ur-!vIK_quGK40Qpk}w)Jkikl*Gj>%4q4!?0s6HBdu^L zTZ;oJkMOSp=@0_Q4V`5+$XzFX&%qaDxO&4XgEN26;aH%zk@oOkmWDhp6#3mu8&#yU zm}{1+(2{oD@C1QtmdpxaYfxzyeVuTs6l*dZ7cLWlgIv zkLn+FaxqH+;kT$J-zy^a!(bw)X#^GAoJ6ikBhpV<6HrU>eT8ZJ2{#j(16c%htV5en zp_G3kF5p)NzCi`gwXXDKTqu^aOxLQAIY>{(P|V6|j3u{xJ4A!u=IW9T=8eZm7H|WE z{%Q^qd@B9|fPYv2bb5JkF*{$(FXVUkuP3K8^Yr(Ze>{Kv!_MBb-&8{rCzGSg%F2o- z_)~yK+E$Nr^87nS$7dn`MZn|B1N=n*y|RBZIsa)oJ33xe^uSDb;t`c-TlI^@FEcm9=7V=@*CDDB5*vp;NR~5PyP8~axguaepx)39d#axr_b%w1ygv^ ze<~l_rT?BTN}{XB&hzK~^P+s3UYAdc^Y*E;i{iOE@Odz>=sd2dFH!Ko1Y!dF3(RU-|D}o*Nf@d;pL2h{$J7E?u;-Goj=?Ao+ zUW}Q7(PRqprvj+GR+d2JbZH7cn!*?qPnO2;NZHmLf*v)8$MutXr+!xN*3avo>KFB1 z{Y(9({Lr2bqV%n5&v`mjEno-8Ky^!##mGCx!Glpem+NA=N!r~h4_ z)$@9OIz5`y0CzE)oE*-+e5udLR_2HGWxc2u$NbXY_4Ta&5A{kUW3vg8dmnapc7Fwu z{zf2`$~bDP9tg+iMsa*AIMp)-0T3)YvgwUvd-Czso1Y+Cyd_?+aFh-_l#zeLTZDVp z8p3U+a75DopP0c7MzGTT*ZR7Hjok#BSC2pb@#Yy}^LEUEY|}bWlkS7fGMf4{ip*1> z@aA|{@6V11mm+?3qD_4;xtO2T2eXTVtJ5zh6pIe#gj;<$UrY{|e?6_Ie_c&Z>gn~t z$>g;DGW&a4pUuvu^_+f+SXF-ns`~uoihSz$VmhrCg<5Mk(~AR+2@h5##W9yrC=YufRVT@3cr;*+SvR2f}v7qB=H@CJHX9GeiAzrp@Wbxq9T<`X}DC@_GcnbK)&hPiE@t9&g*Yw1tik3|ILuC*xfMoHW2Lmd86{$eDy*l(J2(qMP?V?%u_mHVj} zTb_*+2&L!ojdc<35STqfOlv<=37GtN0`zCwbhp~ zHDf;UcKzDrsnQbj&!kuU!`H%Lcv?@rn!AvbRN|^H~ng&W~xo@X)3@ zLNQxbB|E|nO(>f7eDa&V_0F-}?~K`>qN1Au=tPBpjGEE+{4}mCaS*46p2%%I_yx8J z(}tPns=x%h%KBQxSg+^v^nJHI4he0h-$a6aLer|KODb4jw30;o-cD71UK#8LqXYI1&MAjhw zp5BYAB7ltK@zzihJ_Nspwjacd801j7VAk3$sNM&aEijmw4M$ZHA;8vW5CLC0u#UD@ z1wYL=P~&GN$vHI!yDuW)H4z?mO^=p$98YO)z!s?&Rju+rxprRLq`JAN7|n63AoTV5 zJ^dL}dzUZsK~zCb5RxY^SS@{@u{@$SxnT%+8ua31>={xPE=93TX4o7km0y;mQM`Rh zGkeb2#%=F?yL`$R$40Fb5kUhIvX0=mYN+uA;g5+RWkxb(DPyE4iNm4(Bc#v0K~v1m z0R06`Go!*|cpjiopG;Wze{&|XBr+Lf3?NVuYVcnY(qmx=1WFAa3=2oV>|lr;GLS?f z?~ryd8(5$k+$SlHw1e#bhcK}4qqb-a3gL-GIbx9R?hbZXqzBR-VTbgvb+<*^*tmNf zgZ;N;&rXqFY*IWK53}0|FEMUbFb7PBeBho@x?SIXUBXtSStF|xFP7((RXzG*OgJLy z?CbUrm1TiztO*!Zb)&a^Ihs)CXj4elgW04kscXOzZE_}ZSFclcfufS{qpsp8oJ=)(o*Z-Ebok{SF=60}iqOSyF2$3{SyavoQr5J|` ztsYZ{m4{IW=qAyW$!_9lOW)kP)JrV$gX>pNL3wHdn}nFgXC^0;h#I+i0#RRgEW$Vu z%TUcrAA*@-nRqSUW9-X36h!N*iM103gTdbLcKt|Xbmnh>UgZ|FoJG$Ugnci(o_iLa zMkb7U#j$HQIg9bt3M*Ys8Pvi|ph3^X)u{Fwr^30~f$^JbHN@#BF}>iubfp~1gl4?( r9c1){Iiy3QpNZT;hHSWT0Vhi*i7#nVMn)j;s9($W?l* delta 133077 zcmZsiQ*b6+)MjJbw(-Vh$2L3e*f!qSwr$(CZQJR%<7B>nW~%09s!r8Dx941~y`Qx^ zu8}T}5#uSqm`T!DLP2SOjIlE^5G*Lcw~rXUi4byf?%#2fy!rbR=i>ZgF>tf903#EF zz2WPUF8Ip6$}D!hnPbo%ie{)q>UfC?vVbNE*Wf2mCI(+@0J~Ld>Js-~qTEpyXJReC zJ*1Sr(hn$jf109}Wg{{fIH+Ka7+~lOKT4J7mnF!9jb$@+-a96!m_vpeC# zdzIO4cbVYBVv;a^1fyKMCC84iQ0kG!zn!O1@vM?q;NTRhMC9G}5-1(6`ta_OM}>~D z5u&uD+5C6Tl5OTU2xPW6bP_Qr6$BeA3)}yB-wnRC{dW8P#~0j77S;@_PoxR*OMy5O zP2}!@gLyGDMVQELimjd-rRE~9Bhc4e>hf2HwLKc&uK>T_0uncAV&N?%6~lJYjDtW|^C$XXkL;a&#b;q}yyMt#SeXHaPt!(Pj*mCP&~RX4p3L?-WJ zXk5cU8cP9iy`yqWhAxImH}|kL{w)rA;Ol!&pXD#C`fYfiW+MH=AaI}@_|*1;5|()~ z40m%+ANQR{PtL0ApJAiZTOzW0P}_%uO(+AM=HNbaa`?=sqN1;vrRSma1TF?n>;~RB z8HENKy4PFxKIE34({w!wTXI3Ci^j>v55+RKwh6hR4zgV2aT^cY_*=H1>G28;m?~zs zM&1>PW5nP0<*EZFp1pOw7gi|YBPyNNIWCIlD zZgAYiwXs$t_*g0p-oF>d5{C2$V5TbAD|?dpRW@_}Sb!fkO{+8aX!sv1l2_J|WHOZ) z6d`IYR#|{y{53MJh!lSGxSC>ERfdM;t0$EX zDVC9lS8!iH&7wvDQmyWHE2Y84|rUmVh zeAiu;06e%2g6{s^05-O5IG$}2GV%i9hl85mxpaJuK9nMczS86xeO05=5??9FWpCx= z4%T!3{C?8GfdPFu9$0EEi(Jqx^ju6=+hbiHG*?ulgG@b9P{K?Tu+zm6wU${1obWc` zVK8b*K$1AR58$7_3SAJ~1`s6uYI`+m;tNhcH0WaHB$+cFy8+z>Z_~Ezhe1VX<;6w| znr^stOZh2(Y*QDgP71$q>w(O6g;v9)soggDD69o!>8U*8CW&1xsQ5|Y0my$xb+BB} z))xso!%w0Ir$a*n1F_}d?>i+hEnh}z;T%^Mnge#OwhA9Qg9efEAl3>zO!5f$Il0@o zNf_jEaR@Ww5-kJ=vlRcbHGSTDz-?d+%NiRud}m@HfYc{cF50Rzb=6$b+Y?58NvPL` zPES?nx9?)K0Ka-&wPottYubkIYVYc|CfEay>DuPfOCXzoQX^)iDMhX`Mr@)4KbncY z(!pZfAZ#qRs3Oy}qudXvbeSSluqM<+OL7GPhSb*xh~VDfH}8Oos!$8I&NWS1mr$Ak z!PrWa_$0Z($TtjZ0#8~Fkc~zD->Hc8B#N;CxDa%tL2zi#b{xMl4N)%N5=T5Zklxl| zR0?)r>bCEILGLZSdbE(*XM~qVgQWO!Y!Xp@;>dij#^IC}D<}K(hbhj|PMm+=^39_J zQ~(E_%Q<%)d%hexK?zM{-Ol7{r{O)Xnf0&$b_!(%0w&KKL0 zl@4TU=b}3d_ z)TyIYjOJhb3v_OCZ1>NcrHhuIKv!N*oIU%keOx)J8!qY4 zg=*uB4Yq=BEskwMPmtaG;Td%#{mixuIg;pKIbZutZ$TensJ45oZ=ftJT1V3X+g3QEULOl%fF06kzjD(AyOs^!aaK z2FSr7&8J4KQXS{6yUH!>{TD-TC$uVqYYs0_B#rKM>3Xm%Hof7@AkRkF0))t7L6C&t zk43U-6b-d#)6fVvhnfuRX9v|ECzP`YBxMB%id$p}Zf zvOny_f^=72*B(y?b_{?q2@rk;w;0*TgC;U|H;SO01;^0~tD8S+9s_YN-J*l2=Bl(t zr~3*S(re>$YSfcQriB9fR7AE+Q>NY-5;vxH!K#on*aXX{og5bP2v!SHvG3==Xq*vM z?zDrP3ZK}=xG}5biIhHtYUs`EsU@xb$CG#QFy2GZsxAuTd#r8IOdIhbEU<*d&QQV= ztLvK8C=;*U$Nr5-dyo2xgM$JYoAm&IK{R5ze*h&Mgolo+v^)5_@gq7uW!bZ|;3BS{ zTHf$icR|F=VWtBieS?&TfR+w0y7i7U0GiWT#%x%c_bDEZWf1p=Vo4@k9F1I3RS|Xo zIWboQia~xt1gfv3gLP41<116Syf4XX2$F?Nh2TAW?+D6?^;zinC09J+I>@E;D?UF_ zYmFf1`CQ+)8sL_ag%dvQ`Z*?;f%9&X)AvXYa-s8cs1I)ds00SPR4@bk-HgUh2OS!` z0|apKy*|^C+JC({p!edIZGYDyahn_InP(O35zW<@-@p4gk036Xo=dVN$S)y>Vi>6T zMjdlQ!zlugpGW76wrhxw;OEVeZ>g_^IZL_a%(24+`P-3b62OE#>W0|Jl9pbHk}z(s z4lFs8c%xA#ZLM$)@tuJ-qha<*e9~bk3k-oXr}M2R2`03umtVy&Lm9ddCv$){MVT-( zD?+0;RVPCxCoo6o6@4qWLnUG0O+kMlSvKkVMmVcc_{-0=C?bKmf?g|0Kp zYxB2Mj%dsK`1ky_IAC7f_PcDFpJ;2TNRQr`GwJHT@>Oi+0xbM|RQ;{VztZ`e6AUFQ zI!jZE#y~DK+4a#8^PRDez|Jna$WnJJxT+#;P#p$O*Gw}dPO_zsaE^S~7YHQ{apuGu zU+*S5!4ZqP5Mmuos2P@%b!CkT1$urlj~rMQl-FE#ls#YZ`6^0Q639Aw_okg1<+3_l z@6G}4t)B<;8)zZn`T`0!tjYEK4o3$Oe|}SqqadXwDX9`UQ@WjUV{_hVagH`Us9nXRt;o;tVGOmlSqA0E|-r$(Jte6TwS7dl)c=SZ_Np zrk*et@pqUc*@qf?>S+?N+O8-xA?+|5MT;;W)}@`urMdP2ZF9eb`L2)&3mjV6^`JIYK^Hj-5J2(FN;gwQT zdCr&nA5_$PZkNF@x;1P5Vg1#RGLn#I!PKbr8?a#gsW&=eQmvgh)|r3)ZW0o8)h{IJ z*P%5AsDV4&_l5R(lO||hqOPwDs>9*=W;SQ1Un$Jw!vdNgj7|XkZi8fp6SP| z`<}VO5Ar}Bao}TET#)5UT3}JkL~zf=nMFYMIb?03T7bAbp5vhKMMUFVnIq*Gd|6$k zI(Oazp%R8jMaLciimJ1}YIu<_-#4T1rS|31%*)x{C-!>U7CD@$or$xHlc|yI|J>~V zSi!M!BsDmqgK=}FHROTQ0(XAv#2vL_`sEoM^iG^-9(*N|A{n~l;qE;nr4d`;7dgk)Kk z!It>Ab!GO<`qiGo4>Xzf2G~zE_8kaJRSs2dpSU_^_x1Qb&&bw(03YW!0#ysMVN^dG z>!xhq^11<4J3a%5bD6icy;)7w-F2K*#vV>IoTjLCX<;u@ta~smFeIHZokXS+c-Izp1$K-*Yo@Lw+2P&qou=+=*M$74OfZPvCqm#=ZdKPplhW*4 zfzvHvu`>R=AQG)J}7qPn_67JQoqJ&kponvO+IEVO>rhMiv@(L$R`dCSF zS0kW@>Y$W+uv0ihT04b&vfgahU#B zl=y7hMA^3L5E0V}`}V;CQx>*~K}+0q7R1ZobYG$!E&$M>SfRxG$D`~QmMJ*BJ3aGo zVAeidHDPViOh4GD1wly!Gn6EYmt{^qlC2p50n_AVOP&&=rdU(1MfRAo9e0jeP1P`J zB(j`XME)NWAStEfRTJB<>_|bz#Xz=F;hmj&JW&KE2_p7x`pGbk&W{{TKUb|HOgSu@ z1~}s_Euv0T$dK|0z+72JHz;s^W}Y&bHe4Ay><{Mg4D!my4jpBz<1ih|Ld7#h*=md` z^=h-BLg?@yrSh`=1g`BOZrH9Od%Nl!u5tlwjMU%}7HD~t_V6xeh-;eHoZhA^xRazPEN=?_wkzx?FK-Id;>3xQ z{!dE@J6W?TG!_K&RH^tBGa6mgCBc7vGa@!E($wQ51tnC5} z=Tvhs6vZK-^aJ&WIr38sW?5!{TnU8#qZK{x9zo&{a$?*15t};^4prMfD-oV+$R)JB z`}qMS%Qnsho`gENEoVvNp)r@bm9=JnVFM`y>;*HTsJC>` z%UVr|S6M#XS(9_2Qes2q3AMg}RypwZPH-x7oG}eY{0hb51%zI;W913{3)9*F{w38D zh~JE}&GHw19Mr$;sc~3~OFPD&K$5ZQ=G#|qI8yKL;N3|nFXx;gr4HI^4W*F;63cy! zcoVig>j) z{HwlHOE`=_q6HDMVDFk9D~_{}3iq!lmJwP_lE^zYs?LZvuZYfQR|rNixvKrnt8hhY ztiJ_TpQdf&UXSBUGm?e=F8PDyvu^qCg!I%{VX&7Zm&cLEj-=UeA0mw{8pm_t1Y)Ir zo|cF@!=Cl0ohS@e&7dHU#}aoAcvwVzmS5Jn#(WQtl%W>7TWl!+WN@1T`vA8j>!38H z!qU^0U!#ZN;}H&_zJmma>%?Xrx+6TE9ayUq?PKP84R2iv`WTx#k2j1$({kRQaU+z- zWhjc)&TE!#gRFIEylwfMz0H@`biKIhN{~orju2Me=^>p!KC9BW+d(t~(fBpN8{YYLNl<5M z`*}JA&&pLZ!)BwWK+nz_sH`}U4Yqvxm;~yDhN>O^_!fOpnAKbuqdBMqGVzCKEh&<% zE^=xHXPu#1w?(9j3s>icc`;kyl6cHhylg)7ebQ4xSB8_9Y{Xmv8STZqY328w$gV~} zD-^v2gdX2nLIC9iT}}MAvtz|tvCL=h7Ze-|`R*v@+=xY^@ z9%}tS)JHsI{=AC*C|cTp??2wKBdYAos9x$BsVG*E!K9ooNuWw-NNgXv$83MULB%uu zXndqj@n*kj2l7*a%F}IX9H^Yjk^TX4WKH8@Rex#|`OtDLbe=G^@?a^Ivi-9sYM^h2 zpnB}M4SLR1i6gLopQBO8Qk0^C8}kJp;o|tfpB@XdbJW$4(Z}Bsk<}3p@smL$VLb$9 zq)!7*j3G;vr65^37S3*t=x^K0*w;v5*5;DFSY~M&2$9}_q0J!SP>lB42seG$VGl#P z@F=Lg0vBiQ9|FHa?dO(ZWtYZ4J8vHE?ug%r=x&I(Vu^(a=k1E&ciEvG8eko`x}lk% z#$nvQh8~sHh!@Kd?+A_8sKTZxoTP*T2s(##6esSR8IR2U0bw#WwY$ybfDB-^WaoO8 z4K~2*27DWMGI0!#qMWW=fUlt^IuG&0S{7jIUKVoP+DzW8{#xauy_4dpqKzh;Y+d%w zqBoe6SVs9t$5&v^u&r?)$~+PSfi#KF;kDHsfpo(#l_}8eI^AZ0464n}|F0mX>mi|y z$$d(+A;xkoj8Nrsy{DRmkotli?yV77G+i(WoG%vGI&xXLc7yCx$%bX=E0TcRfq9EXmg0Cfk{Pxopj9Vz;Wx^*gxEofVl4`zzY(5}v zq&E}o<1?cH$Py)2|7i+iUFtM++8ps@AYgwkiUA{D)8HE_@i}aJ+)s-02U#MR|CR&p zGwujTvg8kux%-$Zg;;OK*Tps#eslszh>&zDkL zl{`O3^?Hb~)ae*EeI1zjoP&dVgt!QE4-oIP{HSg|s5dfse_1kayv$#;3kDNobzbih za(uo;KW$4~SiDXw+`dao5nU)XPY7vbwmM;2XAa=^IYJ?e#^QUFNT2idvZDkhi&4NW z9}({<?HTU81+2bJcA_xZmf|aj@f;|$_2uc>|@oNz8b@!vjv0|a=Qn1a!&6MX64^f}! z>Nx)oQSTWP^e!x6ifj+KJS563QY6W54lhki|7{&gv51OcprdF>1MWG4C{b7_wXN^k ze*6hUfdPX)d&q(RI(crI>qYgFP)#hs&C%PNj;5fUGow?bkl(oW;_=S-Z11AKbV{hJ zJKdf??wY|gm)6-{_0-Y8U(9P+0|vq@o~6uQ*R&T+|!@QkdEBk>66iZ7rg*}TI=1k*1i>5 zXr>T$*cc-8WWpyLB#+8hB;Der2T@sTW%Mxpelh8#(sZU(dr0i{L(=l?Z4ij5cMY5$D|%SMqf z4Wmhr+pPErCd)RVn49Xv9WRpzyNc+OGMPL?j7QE_O&V16Pc(1LOcj?wb;wDzkZlg} zC$h#K>0<$EHo?MjyFJes9f-FcN>mHr%pj4we%Tx?h1IZo;WFQ(Fc>x~3bioq9M~Jy zqaBu8f1E24G^eWZr@-C|qe&$&5 zT8rYc!}MlEGy?sL18ktSKitkjE4lxVWz~Ge78=tuX`dgR1otUR!&Np}lO{w`i`eF+ ze$!Vez(`X5f|Yk2cVg8o22%;5n^?ZzL2w~7ZrGqemE#A~D_y?Kme%S-`yT(4@U9(X zJNwh*VoQzRAAZ~By1<^>wRBusS>zR>OeU<&@`qPB>dF|39jM{45$A37K5T(5_ekKL zNg34%Vz^&%04S$9RiXL;VA+P8zKPn%gD4lXf6-S&XEF~Sdu|0~sAVh3Eg17Hi}@$J z1^+&&*;?SV#|y@BbEn@{Y3b4vcc+YCu_CFD)9iXn4q0NbcVH-Zx#=&+0^>7GEYB~?Cv=0` z92igAAg`XaA8k>$-|UXg{OL#)6U7!LALK(e<^>cHGXtDkk#d^zNU)$v(mq@n%dYuo z5~7>Ng6`&ed;R`>uw6sd2Dt{1feisb!i^zJfsQZNCs!`5!Nh%eC1N0Wp5|e@GdSgN zG4CbgEXrwzG`0Kr5=UdI*+V=3bFNyW}L&K>4@_R zKxA94*&vv*z?faT^srI(xHC~*3vR7thhWyZek&6aPwH_Ws7Wc4FcYHm2pEq&OI9Xa zWkvdj%L;M9e*dJ^F@7){Kin+Ip^9tVJ6MR@KJ5CQf6)bCHB&C>93Cm946!50B>t&} z(Ah9I9UoPfc3Eqt#D8h<<0k3WmZ-69fbJmSAO$>f$6%*_15DFRhN`pV1qZ{Kn>azw z(+h@`z6=KnWQFg)USaS@Bqc!N@l4>`!BCD*(UC!O@WkG5c9+6?2rnS_>wC!LmuPC^ z&E{Cyi7r71!RQj3SR!$YKw~?=L=o1A8Bg(XV7aFJq1NtQ>Fd)U2kIx5=>%kLfPmSW z&?omUoOnzme}(!G1Y{5#DKQR6ZauH$+MGX}TE*9l=RMIih#ez1QC;YGbXr7bs)G9` z3gE;i3k{KG2(!p)?4#TAntlP8_}VHh^g8;W@>RiAUK{-GF90dTm^KZ*EsB_)v1yG4 zeF<^Bz@n;Q>cp@)OgT!oeIiZ-Z>pJzMXm=6ugMR`^;PO#F0agLtv=fri+ zI73`yR#xILsf;`;eODJ-eAa63V=m2}Wbb#?|EOmfwLpD4g>n2|ulGQ#4VdolVH}Y1=B44B!mQgqDkdtC|L zWF1_ejpy4(-W#B*ekCjTby~s;iC+-cM>VqT*t*w1roVZ84Y=}p^;@NuP=^D7C$+JO z^Efuk0Hzo4$Ifu9h?D<5W2ZO^zP27j4W?_=iik0hi%+MA%Kw)(P;-(h075IWRR`ny zBE_CPztKmtx8p_=o-jaP6NfP7(tkSM#lEessByH#Wt2eW=PoZyV%X1cK6JEtA+2#Wio1l22~~m zGSEPhv5>ch8wEqUZueK`&hP4o^_sN5vn*`v-4o8mp@b}12n6-^ioseEu=&3x|6*1l zvRFb*?yw}Xkai(9#e>x^-9L~aCaqtR;WB5Lkao+jSp3Sb0gf$<1w<${#DKz>P}Nfa zBmWeEq#8JR99Xk_kd}mF#mFacd=#0CY}a<=TSb+jCwMW=-IG0=dePv2*tnF3*_9GP z{cu*@RxG-;EqI_OalRzFogss<1*lgbro9F$!j+<@zy$VxW6cx- z_S)w_`7&JN>}+MS-fDc9fZWnogMGC@(W@QKzO(ere)aYL z_Wo(;K)+Xx@+u6by&Ynf>WhQ!RBEO50y2g!=T&t&@SBrI7F(+HuJCra;NASIJj~Gd z@xwqm#X#T%PhGj%!98)vTL^b0n@Nywk4WO2S&~=DH=mU#dHDOE>SMRDLyt~R0k^SS zNE+@Cz;I3RIZGgEe|o>SwZifqO!c#e?QML2gyGo1`g3za$~T8y&6sYJ|_Y zzGcbEj_wQ2FEKy*=f0k^_3$WGL_O`Ryd&3$1s>>|tAxa0*W9F`|8vt`k5l;6_*@k! zBakWw@iS5}4_E!lLeB~tF#AM%(xQ$E}F zPrgFWc|=M7#Cx`9r6j)3s)YR_Yspw;+GzHB>wEd9;QH@%iP!s+?9uMx!2KZ(I6jTw zph3Xn^P6vinqMPllAMShhYMmbVC>yic}zYCMUkxbU`}bGzk167LwFJ0Gf7$NvuRV|WeoP%Id>IqInx zG`qEQxCZkGO6}mhjmQ~1Re-I_sk*n^Ao*Y~WW?sQH(;9HZj_IXiXBOgRLgt53zrXy zK0gw!av1JC6{q$`sM)(pFx9(?XuQXix})u>9O&%`@!1){q6lDuy6TX0C zJ9G40@V)aLbe%<*U=8?232%HUsun@~JZP-=Pm<}P%i?>9f_|xCa`887h&UN3kM9pX zD;aHU$8*`cK!{}EoN5;pU%b{&&5-UmAt4M zmiK~N6Q@MXC-C5L@!lGU_{u?4EKmHZ44W{kP&L)gp`5y;h)`u=$Ir?<&{Qj%A&6%| z>O;}13>xGwZieRahxM=iJH@o**mXXA3Irjpc;Eb=mKK|hgqh@j@*;kII3_t$J98Hc z5;j&2p8u=9>1sP4jiUOk)fw*gM{?(WNKGO)&;zzw9MS3;6;}Rgz{!fB*+dqDDouWW zJQ09^T9Alz@gFA}h#4~DxV${M0GF0(>S_VKuc1}21LKCGRGMq(j3{PiWHDkmOA{-9 z9ys6ZI850q8nei19-ggujWa1cUwvCb4Kk;fN_v1}6KmgodJGThzfDh`zE)lgd_+w@ z$URt#aA1c%Uxnm3WE(G{RZ^-~RV$OAy~&g0L4yWv_@}UXDL?Fa>r#n*_grKW7Y+Oz zzE~~V^|6i0t#0|jL$@#k);svCQx8e5v_v$s8|us0U>K9EJjoFuW?`8xAC z_(vzmfMK{(kv68D<^C_*s9?U025lFAXWX?6!GPhw^wa|`pIU!-(!{(b&lZ5-``cls zfI+l$aXOd+0rV~Nh|zEHt}J1Z3q9%pV`HGB7*7qKdV>)TYkokN5y1xU+u~1m45AF| zV(~LliQ_x>33Nf6`}h{uWL_B?nR;UcB2-#65V&w;DCB%wk{-y6U0gaeC z+iZyr8`~^9zoy>>%+EP#on2AW9O{rww3{154Dkh4tn%3Aqc7|zqN+Uz0E z)By?eA|ShuUl;WR&@HX%&}(ipti~!RiEIod{5ZJ!`KN~im4F+fhYbGjcTjq~$>K|- z(|{4^l5`bzW?;1A!w}weD76v@pQSomYT7}iIgxG=M;6|6X;bd*Xpr<81nMq_TSeRH ztk%$qB)wq$!pJ*dv?d>h-U-2OryB^0S{0JlA6DTGm6~ab3)r^VEIS$F``GS^eqQXz zfa!q9PNzVvB8RS-HMJp#NVmb-GBZS|;p08`jIfLr3FZ*n8IuS~p)_r>Tg!d(X&FCL zQ179srh+I){>5OKu;N?e!A~-d)r$zQZz8h*W0O+dQHR7?6oHa>kEL((+Xfaw`y=kR zeXe_^==|^;Wm5@lxZdtIo9Mmg&L9jv*SyU4Qj(!7$uS_#izl3R7wPHYgPP#`As7=> zM-$JuBukOEWNi@#%{Il(ssgfSt(Ww0Auxt$D0|RwFT7CeGjmc%JBLM?B9jy59D>T+ zUcJR6aJ2#?M(Ut-do1KB27ss?bj2wbQ3R@H_Z8S#@SfO-;>GhuM% zSIOZ|w0`YCuaA#p_I@Z>4$J5Fqki*)#=7^LTT3yHDBoJ9h|TS)TGShO^{mH%J}yU3 zl?VLzGhf|Ym5d`&O*Zanc?>ZXimh2KLv>^*i$tqn@f%Pv_pOQTe?X4cQqKfWYM2;H z2i^}ZsbC|qWD8sZR4z0%etYd9DOP|t-Gy<%vttWZj7g9rv>&IXHkg?+gGSqkmp8ij z3X~zwMNosHOWKnv`#vfgqFI1|p9>bnD|v^aOFfj_kOuavdl>i~wA2JZ5iVBY0eprL zpRLUVN8sG($zfW$5lGU4YZm-UcSto1@`EuSi5YrzpZ5v|;#Bfw`JR(~c@Ndd$F(c`4}yqL zfqc|!k_`=XLYYX1XwukSXze*}Q3CdNPHoYaHONR|-yA=h7%-B4FB+Y2jiYe0^+Wui zEho~|bhp8TtHFpjpeBL&j;ltkY$T#Zg++XfX5|dkU8JN?pyX1Av#Z56tI8FD3G|dw zYGB#l10{7J?hPazvgLy5?XnaqKpSS-MBGmZvOG)U&6mEHHMlMPS70NHf7B?bW}1mN zRWrEf4anTPC@|$zc}++a!RV}57!WCNGQ<66o0pC9iKu-zmI&-}a)G3Xr&VlQ>-4A3(B#G>ai=T?e^XT6uB?YaCiW~-(KsE zZnc&$QZO}f6$RAyIYGkea+Fq*{B;3g!>vW!V$6Qo3;aa^CX8tsuAPL5bMWkmr$q%g zoN-dSC1Nm{9iK5QaM;Dx8FO+vU$8h&Qzn)`Y(g5+cHLyiM@EtAMwp>RD>~!MhV9wg*X>p@tl_*Hu2DI zW&B0t`V|ddd>xvEKJ3XXVo-O>X^EQc=R9bvsPcP^eqhh*%zjAkdw_4+qgD4cELGY} zy88*ah?<2CHhs|4<~8ibm^@DsY;H$e3FAzO0$400diV@`cMJ944*u2^@aY3Cjci5o z9K{;XU`6uLZMoQj^K*uBgS?>1lD(H23?%zOa7V z`16tS_l{TvSXbB77Y^|(PmKPJDPv4IrZ6(eX|>fe|I+-B0-o2O%R#C}B%05jdM!zn zG$7xEjlW5Y+XcXZTmZ!CAuE62WVzp7yM(lBvSs(w6o;zs-w^+@Fl?=Cn!-s!GR#HU zzrxwnfP~E8j1pjp!Xtz4TmUm7IK_&>61OBoUtaDCo*4<{WHt-VXZr6=h2BOl=6D}S z`h;<|&LKa9dD?~xsy``P9V<;+ysv2zLO|i*7&M(vTiwp}DM6}C+`+>E4v7Q|bMZrg zpVO5J<5%Wb5RQmoyJ%iqZgmVo^!GpApGQ06(S`_>Fnz+VglC@wx;1kZ5)JGEx4}AS z-H~#a2;gQ1oQqOd?NqVEGH^Ca6UDFzi(JZx|6y5?Ld-FnVvK@aCl%Y#%`^-o5AZ1W z=!9-uo&e`iPkWe}80+77?1_5w_^M(iuDot)abnpX26BM9r`y%*xc!!zmuXw_P4o#g zNcO^$8C2SbnbH>W8ni(W8;!&)iD>jz|u3VjtQ_Cf1L0V$Kp8*Vi>pEbR_Q-zLwK zJoPJ@NyrdYiJK|r{e^CgHr5o8QO%J=+%GEadpFfPthUn zqW!XsFH{4x=yrmgAx~Y;R)(PM??0NEBOyNuC)Hf{#H2wxSv^vm13`~3-~b^U8xWwQ zh!d^(S+g4!26Bk0o|+PfF@3>SHz~l>uszp?dishx_vb9<{TvGXpYKWp^@Pny5_YWG zdi+cqlBqs#eBP6)?XVu3sx%KhrwmQf2eS{zF{5t9rbZbbG z9~~ux#OWqkoggZHAZ2zUg@H*$PvPvsW~%0vylGCI?PEdz;-1#*jeSQ0W$>M&d)toK zS}ll8;rW}>$~$GCm$~jxhwVOvgre#Y#>${)Tqur_3_e*51Lp*z{HQA$MRpGf&S zw7hxdQwUg68m8iUf zwgE{>IYF|%E8#`%x6$&T1R=6TY040R2$usHm9C>wxejSpxhackRTc`K3%j;a>R^PK zIy{cPOPF`hI~s8YKmyQ9_YW0ic!ZBtz4=@qZ;u3#+PIUqJ?mj>>dG!|Io>0v*0swpf!{ILom0tNit+7RBvd z%{@PI~BB1)i@y2%$WPA(zr>^)~l6zJ{ye0EzQ2O|N6 zpQzg>+bo=(A%+*hTsra0;F*H;f?m1g>618L3zvqhf}8%zx8|dnU>?k*&JbCSwZ5j; z6&{MB3s8@KDDsP{CN)CjoGy|Bg0?}1hd6jhgbf$|cY-MQ#!`=^(7)IJbi^$xws_gR zS1dZdM@YzAu~nvsp;cEFXsqU%X5U2{f?bjv1c`wy9~O9_XFmF7-$E^aOP|Z{{_4Y( z7ZQl~6OsyzHfKhUCu-lu9;vMN%Ph`94sl<0ovi>ta4hvc%V5g}XVA{{5mx^3OW1OBZ-A^uGY@GU6 zs&YFR;w+LR@f9P{q~PsVAW>_8#D9AXFbZWcn!|kIEODTa>m%PJL-A#C?;^GnndqvD z+~!x@*EEUiVCKWo6a9g{B%;z}{y$n&OIcN#_71E;w|-L0hy6W@cE|Ey1sO81#Ml#4 zRR*=auKf%q7~q8Ybf{?Ub6M7Z`5=Gw>uK}Q4O?eP>-@5KoGB&g_NgxA+1|Z(*iXZEW+R@ofsE z&kU?F-)YNU1#v$59PE{6&o+Wv2g*2iNums+EJN%L5!blXm?e*%Lfn*f7etMD+xdk{ z*qeK!X3hAAMg)alZsl@M{1b`VfuvSCFJ*LM%(T1b80G#W1p**x)_6>44}(B5iOKjz zVey5`jp0o5#(x3oLR_=Jm-A+1=Twn`9NL_^&@C5(*X>1QKCO>?Q0?4+$&!twu8Z8bNjZ@*n=gwPa>N7&@l94v_s5=i2HD9|Mow z(DQ^6p(dZG(8L1_BB2t4nejq=gGIJst&HAAuT*=rt}(0-@8ock{Ok*UcT_gd7qIb} zDDzryL!tmrhezvUR8ah2MGHf7RE1#TNkN}lr@1hjom~eDL!;v<24Ajl>`9P~2nbj? zgdbN$RS3*mm8=k&;#y!9tWjqYV?NMV@MTCS7tNQlirUCtT3MS94X9A4)Db0r=i`%) z66s)x(re(i->&=TzdKUiQPF_F5h#=U$E&E}UK0b4!q?Nl@s4I|oj;e+tgCbxGX2*I z#Pn<1$s{o~kB8KUxCilua>dC7d??JT1=Jyt!C+StAmgwE)@vgoEbMyJ(NPEgMg(19 z$H%{{h*1OzujrsB2zQvlQjZqI5^A^R7q%l76ZGDiGjmc`>RuVs_ocbto;7mpc($W3 zn7RU`vzKMuL-7c z@^g?*?ZQ2t8?OKUx;&p`EN~jkq+grpgnb3V_eO;ap4s`+*;8%?i#g6)94$InyGe8^ zyIi>)O+b0T!~Hyft9|@Q*NtIATdCyzM?wqLNG2T~FXqDbJ>LRZ3KP4EV~f~98~@ve z0tM!=NGfMjEG^})TC_-X5;fi5hdN<0$Cqgb{M;V`cwv7(NPIz945=f-XH?|^_?LU2 zW0;l6t@P94q2etzc%;aR6C5=v0=lK3^5~a*R=9V1kX>o-$tPj8Q5#Hku*IbC zcmbtSBnVT-b=hZ_VL*Ql^xeS^^!^uC8xu5QC|+o_?*zEArqJq<`Jk6x=Rn+ijO@WE z+u4R_eM6Jg49lzKyeug2^6sCirK~qF`S-d-K-Q0%K<9IPWBMBq`o0*X5)pqeiL|R| zeAX-9@TF;x$fBxQYj!miC$m!{rF@+yF`YnSm|tR8|Lnk7E2HV@MlVb8u|xoB592nV zRK53PZLDh>$g(#bRVzY!05P6m9`!BxL;$(O9|tXmZ%xEgCO9$MPbUn5*HjPu&S5eq z6gRZV9gH~lt1ND#P>`4=RSM7<63i#qVQpJk!ufuDTg zfkSedDxoXl(6;!OnJ10%jTAYzeeLTsInQaOPiuvl&0|c51=vy_eb?J*sn2_$bT{3o zRyapdsM!}dEQq*f6w}#zcH@PlT#kT5*!{Or@Yp&r&&QM9R{~$S&07+1fFUO7s#X9M zol{cm8FoK}RM{0y(Yb+<=9)wMvX+3vc$xDnL;%p!;69I=z{Xt^M1!~d4*^Vh`#!t5 zwoX9@%@41(qK)|G$*%&Nk#MpB8kcBoe7?tK_6di`%~mSlgs?d$N^2J!hoFhSbR1{u zqZ7$EH}vFrSBOVfg_95n5Zrrjj6X4I4hWH^DB)G~hKwNtk+rdhLGQlOIEhzTXJVt<{*{Qoypb?QGZ;xg-`@Yc9)%pb1)bRJ zzS)Tn1wdB$lmjz4^o>N+JvtoxZ!-U9PIQW3b^S@X|FlpSc)1TOljU}yCg=}f4f)J1 zzVD3wC3jy0b|6mqyc~3rUp!BdlwJ0pT;5pVra7hlyE+>|T>X%R>iK!wNuVy0=ifqQ z_srhf3Sm)IB$Cf#Yv;^yH?=8AiQ9mk2A~RVPQIgZN@(dKhj9$BT~cx>v7{qAo7SnM zw&PBXBJ^nKis=OW8>KMvvC=v(w)miT1(kAhIXk&hT@Fz6rNM5xX&fo6XA0^}o$^TH zfLa`JV6bL4ejaA+pl*{0dgi)sjDbKlTG>xrVNB~!G}8KL(NK!*DRE7Ji{#dZ6pyaR z53hxT<3XIoOBxG6-sKY@$MlIuxP} zYw1IFX8gC!5mhpRD0jH@2f9I!1CTWb_wk51^=CEEw908o*p}zqcDptGqq5&>5)@!&pDP7x`F zj^&Toj-oP7@l{@7e9O{1vEJbt&i~sNNy4Xu#pe0{gaFL!{}+&NbYzpZIMI6N>gIQg zBO#Bz%9k~6yrybRkae_g)lT+bg=Goi=o|y zRzRu0D;De3RzfZUw=c~z7S~-5a4^LwJIN@fThv#g! z+dt%C#C|nfZ@2j}o3L?_&%?`Akd9+3q0%;ma;}K741{~3e+y%T7#ZRW^+OC{FhCHe zTp08vwR%T{Goxu^Shkv{B@&}*fmuSJB1Y?z0wrObMFQVUri$}%aerU#xZb=RuR$rL zCd-fI_%|x#3bnNi|DUZNHha_@2!o?Ak{H|(6GX{U!nb|4!c!?0#UkIqsR}lJTr8L2 z=^p0F@N~k-g_l|Qvs$mF#dZNBzAv(J{A`WmzE6}IXWK=#nw4MK72Ex+*l%HQ{wBQo zGMVC(vuwXB2Nm$?eSi79SfNyWlW!mL`64UI4_fO@oQ4#P=)?K{MmbNOh}ShE#@I0M z_tcS0rO?Cz@}~@k^5Zz5L@-+k{+^V|tqoGm5vlM6Ek=z|*=7Uk0wc+`@K<~N_`eUR zi~X`#Y?e8`q2tXmo8>zK0AO}}J3%ukhpxTG=Xt;fzVg7qhkq5k3(&&U$L81@#m%^$am zU|xLu{@co9M}KnAprVXT0U1odGYbQ<(nl2cdn!I!SA+aj#|`|4gjNdZIPNk3~p6cYnw2qJLoxtlsw8 zL%dW+D1UcNgZLq-8UI*m=3R0D+^DN+#x}Q;%^UlntZh;8YJup29dM$ZIlf?ddcg)F zjBKuWfPVg!+)<#a*F;W3KVQM*^!Pj_F~gclI&amnFMwxmWxQ~Rw$jI0?=&SO6&n0S zWcQFVZPSzsoP=PfERmmH8JsfA(-^ft!e^CttA7doa|^kas06!mZ7z;`Rv(-!v*hAFFpYAPu(4SY-W2N=8F|RF z-F|{(dmdh#&SSaMkOkHjTQVW=BTJ9XU4k% z&I2EHrCxXnN`y}561TsDkUG6BAJF~bA853;e&u`3@} z^SnH7cq$7OVG(y>M7d&k0Z-fT7!KTo1INiKoiGSaRtBA@ii}_-?Dxg$YY8W;!<0yB z;t^{v-k{2wN>xbnrJH8mCYdf92>VDZ1)!)D{Ex|0>Au|A)4hxM<<0xsn{PMx5`QTF zhzkxG0c0bZL)0409&SE;rlUE02Cc(E&Ww@Qsrq7J!8CFBSeL)KcdT~YBr@?zrWPDId=VWh=hrkceq|#w zCyh)rWBrqij7NN6IJf94AH_z-v;bg=k))t=IJzfU8G{3K+>C^SNvn$Fg=Q8LSV+^D zX_=W|p{9M%Zp$fd;ig%;@@;QNATte)m8rgzw)gkaZjgfU({65F-RjRzifi1GefxHN5 z5&~4F<&Yyj&6vl1S<$yR(~~_#!u-2wo~dgvcXQt zr5$|%n@nL|3+XX;&5l&3__*KY$&kh@@CFQ{*iEbHbMoR3XZkEHe4I>eb@&}l%0#0w zpi&u>#u~5%>oSnex)Xli3U$;(jUZBs5w}1VjY~L@7~@E1c$8WBwD4rd{bO2l;=p*X zYEo_7G??|%cz+!SnxH*RfbF%?u$pn)WwWAsl@%SjS9Y0vL7t6gdCm6XS+?sU>%E-> zDHfA#pl36K>PO|Mp6-MqRO{hpe3r;X`=VC1+~(Q*&+4M);bv$TWZ03Y_3->&ieGTk zt*$)zt8M)?$A9KcqO%fi*)ErVmKgg|WD9>8 zH{EMy()znfvZ~mgxF~b1fK=ayv~52TU#2Sk1lW^{vqA`Y;Kpl{ls(s(m13Ch^6J9t zc^SIy%g_%Vpud9Ho1~j`k{-?Eb9B7tCQK(uhY+A(Ack@ui(x{@Vx2R+i8{B~sB*r^ zMCsAmJ%47~v=tPhm2s=QOXUzg6qAiJ={j(vSJ;$eC-U|S?zo>(XTw^o;B1J4*T;#^ z6fd4jY=VV0*9GqNXaW1ViDO5J^kwyTAddQkOO{ve)tSrM2sEyn2z#DI>RyW!SP%n7 zjzw|7pJb2%l4z{wam?YQXgW#jou@CLvB*$67k|z*dO!_%m>c9L^>IHb2l&ZOF*CKK zhOC!gQL8}ddp|MAPc#;F)L3k}5~duH{?{0e^J}D_C9OD>gR(375__R9;V+tm%2)3D z_W%Vv0N%Jyw4gg}8s%hjr{~?yxP~dTNSTI1G9#pdm0uAlQl`@BH_|e^2renu_~F`n zd4I#byl4b`w7wj9qz(?0cUz_fyT!u>sBAJ102nyo$t$F?gYGihAwTA^QFST7T-6cg zsw3vw%Jhvd8vqNG)i|0CN$RCMGUl`#uivr2gwN+bErAfX;9sWn75FXqQi~dtzKQfC zdaF5s4KsiWaU?G=YKHDnY%hiJbyRrv``6;Sjh+BN~cU$N2Z(V2TmcKs?7Gs z$nkY=GmWP@3rz8R;C4Z!fx|Fy+)c?B zqG?kIPQi)4>Y`%!;t#n&!I*tJb=vA$0n=&lS)gV|39I@frgDP+2V`12`U+)kWDj$6 za%Ev{3T19&Z(?c+G?TD#6azChH0j0`qp zc6mM10%2xm(ny3con5YGAB%U*X3l7FRn>MiUocII4?p}fEZ)zJD9UBuwDZrGe|dlX zp2{gRJX=tVgkgctzvh}1*1af-Wm$(sS8b|w*{<)y*K)aRcJ-Xc71+J(a;MW8Ni2ug%i0-~kz;mb1}P;@2|G)Y0~r9n2hDD5Sl9MzAH@UE zy54S4v#t9CSafne5gS9-*|sqksKG?GMf&>)F{aL9Nlb?4ZJsB24$rF$PlE&_Glqp%B$4g)qdxa8DNU z-BBT_qam2{M9AkH`Xv%X4<7EDfY7R50{qvzRYdFv-QmK9UE6L#Fw}oTFa!vHsRF3G zctxZ}%INfp1b%Rz>Za=ACEK>mw)|4|RRbdGuxEeSxs5sykJmRjCJ_L9OS)m*;9$=z}Ym~b`1gtxTrT1BlFc4%kO6850=k)nZ zj@yx|sE;eA0d`;sfq8$RxeV?M2Ra2kSPIT(6hz2q#;ke#axl-I^I9nNe=rY8e0xl@ zER+tCG{;EBfIBKDz~}In1e0ImKl2Q$ViHORX1Opl<$Fm}l4&~8Y`k!F8oTZk$GD#hLfpb%h! zw#{|UN|H{CkL!H-goqr$ch_$F;rPK29Mb+>mbXECUu*1>amrqJd_*Ewm@?_Bm<&S* zTzX%CoVW%r?oxe*OVwE}ZE?GpODfl8U6s;uB`P?VNWwFPe7c zi+;|EUA?qzUsivyafpR2JlJQF+GQu@vXc$3_sw>(w$MoAtid3t%kdBa+ZKoq%5j_Fvmk#)Il zZMljsxvqb8*V|Q0@tL#vRvGi7?H5Lhk5~I-=L!`YW-1rlhuROrH&}LI>AG_lE|xam z9$^UqbZn2_W&ui-I46K|CZ_@PSj2|&nlU@Q%U(`p&WP9#x($aCf?YH33UE7G{XVRs z|9DZYYyg*|8-pJ_*bIj9-v&7FNgvM-`qdF1)Zc%NP3Mrijz#=f-iIstDohjZhC2sc zKp5)4ySD5qKV*URcD?(u@Sxdu4=!&zFRyntHW1fsvl->a7l(;L=#-%~4&}e2X~L&( zFhYocZ(;awIHnmJ43|7=Kh=Tj+uClo?z1@^mab^x25CdSp|(oX#9@yOTEsR&;7otO z1h9XNF_DhPfgBOG%6+aOpX6 z^kBI7)8)l47cPE)bD#`>G91bPt{4P0GFyLcE}dCGKQk3$6pU3?$CdT zJ%li4Q&S!RUjpOotN^YID7r{lk?f=go5Z%+P_>{^ASjN2GF&rH`cppXY4-Hy`D5-b zdcWgCOQf1X_SB;*%dCr(l-{O#3Qv4KGU++URF5MQqJS2&3E@#(@^f&>&L59HZGYa8 zBh$BgpzBK@lPTqg6GxyaPD2xFF#~Bs`w<--BGm~~Jt+wtjk)9ngRc3;p!>%gMogs*S59wIH7s?KOw*&iuy=C&ldvY;!RuGoB4uc zR($AeyS8q=z@e%C-p|C`{=dV=4{;24V;6rd%Yp3Y`!ES;`#|;g@bTj(rf}QYzK?W% zaOR%830#`muGeK0P}X&c<_jr!@wdt@zO>D5JI?sHZ-h?$9x)AB=}Vv`KzEAcgrob-x->!K8Q<<{9qwFpm_F zeGRyT8fac)OQ46e`ad4oUt|hpZe(+Ga%Ev{3T19&Z(?c+HZzkEsui=#gG43*HZ_wG zsudA5HVQ9HWo~D5Xfhx%GdVXjmrx1;6$CXgI5C$Y zU4pxN2->(e(zv_32X_nZ4#C|?AZTzWxN|w@%uHs!|F62YsA}G4`PzG}7pj`_gR&Z< zhzZEZR1#zdW@Kez;RA>%D9Es~09aVqnOIoZkSHnDEx|UX|CS?BYMMGaS%U2N{>wtl z(G&=NlZgX=!Ec5NAUlApvkici9l*-P$I8ve!UAApVd4F^A;^&rAP#h~Gyy0u0c1gT zrcOwdVjz2WM@w@H@LQgLKLTisX#uRfyxa_by8}dQO&u+bfp!1|AlSmx_AR3^&<3Ce zGPX1YyZ=uJ8UYJ1*q)D>+11sR325uY1adV0NXr0!aJ2+m08~w#OdVZJO#pwj3{V8x zn*OUbCL~ILx`n0FKMFOF8Q2x*XbN}}*jO5y+BvX0ZR6!cK;a5 z|6{-a_}Ae8SeaP=6YgK$e+9C%``a04Yz(rs2imz?+L;5)ENx5yN|N$SU^g%W0BC3O zmm$!9#tHQ14|D-q+5nB-4E`=12#^#}0RZ1R{8xWY#*UWuU?(OgOPjxXWd1A6+c8Vn znTUaGZB6aKPDp>%CvNFzYW#NY?#%zXTx&a!tDWb+$;{Hu#O$v&Oq}hRHS8=MoK0oK z|7G(gLi!^!Hw6PYS$MeFc{l;44gga(V+-bgzY?gs+nfHaWc^G0)`PdFJ;)wl_SS}} zx22is+b<+fC!mWd0PN^&>h1a8ivJ}fR#t$Cr7;*_WNL0{hx8}x5B`uWe3-rIzkfb4AC|Cs-M#mriYTH5L&^#5x4KT1(ikQ>00k(~{|$i~Tk z0$^p~-~n*IJ$V0b9A%*8zv}oeUl}_y5a6$1f7SbTQ2(yktx|KFJZ73KeR(*JKolFl|Zf9q-fG5G({18psB-2Y|q zHoDH>w>3}zy)A>?|25Sz{bzR-Oie6*oo)ZGRt5}wTL%$4^S6;^WaVID;rK^x=_G0C zW@@5r2{yL)XKenFYy7ovHkNj#${;7pzg{tKUMwvCNB6d6#@27I5vRA={6__JdRsa0 z-xv88o4zg8|JEU4XACm=Yx~$Zxd1>%N1!{>+vUFzC%}{SZB0!~-Tt0#05g++9SHp9 z0(k4$8(;=mUI4Sie~6m}z%2QPSOLsZe~1mh zEd7Vr0n9Rg=q;wgA9{dsF-lC}fp|>b%e~1IXtp11Is@D8NJOJiT{~_MD ze84~SrZf5valU1Ldwtpd(f@USBg`g$@GXsrsSWtQ4c@9U`!9Se%lr@iMZo_J_?F-L z55Dafv)zB;+qr@MgY0kaAX`)O|8i%2OK1P*3f}6m2Rec+fi@H5576PZQ_47_Ls=zKgjl$$<6YQ_RZVl-{$`_f5y&#j*f2w`uB_D zZ8-nUfBz{kHFYyJMp{|~8S@8O)dh9j)rb(fGVV+Yz@DYuePUyrEYwE;4@k@!Y$m8> zWiHE=OD^@ZO6ps6D~dYYWv_j|^xUo|ZE)wfVI-B@HzzfUTYSBNoKN(;B_dlyZ-L0u zN)aXDD{&lvP$rJV=s^^JGBF=eqeSdHhQi z+-fwezQcKiN1gM_Ha2i8N;f=J@e7%pK-WD|f@?L##?a{S3T8iXZ=}DhOTf-KMF<#E zf`6DuoCCgEb0r_`DW}Bc=nIyokrcM@k;y>CI&I2bo#KVX_QjEZ-Uphb9&QW6B(o^i zV~=}cO#2la(KN^0g53y{pV^_L(9J_16K|a~`_e6?zpYjNBDR(d4VH6Xp6{F4cyg9Y zmC>0R45DFBNDzGax_#{3NZA?fVip3`MqQJFxh+ADn@M}k~j?-M3FJF1IiT9pPGbK~9+e3ABzrw7MN{$*E}DAlq$# zA}AVFi9t{Y1Ur&{OR0aKdZ7gEw<9(410Fb=i|0*WAS2c z23tDsOerL7D+!}pcr#-Eq=`Wdz)=|vJV=O*>JZtuYR!qHovS6BKSAjz74%17;w{_D zJi1~xCnUIk%oIc;)#)-IeKmRo8N53eCDJThe;5oHgKxUfA|pM)huUt+%J{Ycyf^@T zmUL2zrwvLfq&zcWyJ&TdQf#lBlm2)u?tOiZ@G~oZKsy<&7WtDqLMp2j$_F5}&MP$<)j{P8&0no*^2d z7PIceJ{22loy(vfWt8yc++(a20f;;n%wZr3w{?gOi?#ANIQhVOMnAKRIR}Y;tkqb@ zHfj%l$`pUhtO$qha{D-H_FcOEL5EaNUE-$K>Wk`dgby?QBl7k(?jhhy8pf&(&$h>> zl?3~`tDKB1=?|K>EB+=;ADaC5O*rxk)QixUIQba19$aw9jpbtLRu=i`J*M8le~PNc z@<6o)yf0LlTX!A!2y_@U;@V-2mU(EMl*6EZ3KlY*Ubu}H3_CPyZ4x-Ql6#7oqp)tV zxmlw$xU!|t!${}dV(bsh-Fa^flppgYSh-JApHgP^oc6~iz_H5>k6Fl;T=q0l?;P(i zgA4g}l3VE+E|dVbH0n>zBDrKBQ28 zk_^+!Z?flUfy?nR0xJSu-&MT$T-a29<;n!DANmkzX`(%&zaiY+D1=~-V#&@=ROc@` z&?-V~`uIpPbajmaJwsM0XMC`0fP{4Q@oD5q9W*0YNJoU-GBWnyUg)<(ZjTK|k*+aG z1T6Ne^ULB?Vf)O^hnLk%I4qzoHRH*8_iC&ugI@#9MPuNoKz0`n4mR=g3tTOKS3C+~ z(=)aNZr*TQz6zcZPdKKxySV?Xw$P{Rm6lto_0qlip&jmu-AJHtRKU(a*VrH7!s*Ra zUc_7cz9xr^3)sTP~30)IhTacd|VS{^vMz30IHLSUAgtwP-@v z;ET=aN7sb4Plp1(q_v}K24UQPT(CN^z5TW&87VTzGK_FO&@_5ji>s&_f%)r)&kw&*_xQ*BYgAA*NQ1=ejrJ#m z`S1F~Ab3p=s3di0B9Zc+g74$*i-jifq8%Y3PSQHs46dqz;W1~;ln}Ik)~2DhN^?q` z?^#xFPhW=roI7k(i6*D|ilYioWkH#+9{l&v$);yiAJ`%z-vy3Vie z!>55B`M9p8yS$-zjntZ(j4gmdsLg}AG|{l#?2CIwzp2LH;Omo9un5dbW&|jhopjPm zj}%a?m%hDA=+WxGs#ryTl}wN%wV=T&+!(^d%nQXoG$R9fI3?+kL{Z%3r}2YX4hq`l zyBU|8!$vMKqB~NZt9NaHv@~-)9p%GMqh#yE>L=}5caYn3lU3Des#`&wT4x%xu6rY` z-Fu<7Y|Z@u*(Q9FdpLU1VM1$QaIOxn$I7@_TCE>e>UT34x>X&2GkifP1uR_lIamH4>|E-W2$%;~B|&Gk=`qw8lEd zyA@P%%~yKi#^rnpBPZlb{?3rEVSp>IEEL~3H2PjqtZG+H;by_|YyoxoV=@}%;M8r{ z4$97NcDnCYlI0`;inEb6ywOADSg2)e&FHSsyggr-xkQ~;3fE&En-0PGNe>+)&F{L!1_=y=i>@MZa*p`Qe%J>VvQ9F zL_oe=6qz4bcekMl*pi2AodUP#l0u(p#9^Ht?<4l$SJ(=F&(h&O#;N1*#{HCNg(}ig zGG|;)S?rBMuaQ2m-^D`%O2d(mA?SJ(K7Yeto}D8JlCaW*^~_=ozhoT`RIg3elz*P( zbk~ye^6;Cz+)6$7T5bZv7g~v$90Y3$R(UM3FZZY~%KCKd>eO{LzAUgCKD*?;*xNY< zYM>}+YL#by+%WB7YcqoP)6))WD(l!hvKD^F2NgktA_=H*fms`E`d1CxjlS$gK;*PR z$Q+~mb4x<%3=ntY!J6pM+c zRS^L4ktdmEgKoQQ;xs7%<94}q%Zr&mEmxw;r)J83qMT6smO7#Xe?2fct|8PwlUz#Z zlrchoeQrL!M%xc8_4nvZ*@<6@9LcROF=X2X!4;BIgg{mo{?Yy`SbY*l;w7t*RdDVG1GTf(?M3HA6TM>_?>%B}E zlP*Pmvh8#qJh+*J(k}b;j+@kXE%;(m#b|zsiqknYG5zaa`~W%lQ!b1ik@eg8Aw$FM zE-OA}WT^KLpX+1&USBkdDd`@#2z7s4Hi_lyvB?0(sShU58W8Uf-BJQ;lmvZSGiN3c_egaF>0>5Yp&RCx}{zmOi(<*i!(1 zsD5JrOVArAB+3&crK4>jXxHDb6|%#A1+S~_SZ3Hzuu!^Le|Q#4=kwz|*fW@9Z1=YI zk)ILXJNfzzbxcaIU%$fQ$04nCbw;ZtB9GBr{GG6q{`)&OsaK}>5CrriJf+)^FP|e% zt*W;qanx5jrcoIvfM34k*LdSR4Vf=a}4nvL3 zA{oT094`B)LY_ZiAITJC49=&)ICkp(Z2A^3^7`vh)f8mtlCat4X!71(=y+B(EEvf5c#j%{51AAZ5#)tv9gt#)}Aa2@gM(aCe7)!yp z;I2fxaCKV}(;1uohGTsZUk(ki^vAEJ`^(DXtM&8z)we%}zUKvb+iGPVF#c{-*c6%c za58i<@{Y@nT6*qtY7xdUNObC8hDy!ek__t(LRU(V_*Ri>a~ip3p(|y7Xaso!B;hIi z(o8|Kb}_84!H!++@TFn?`fTe`43@0o)ulVK<=W~66CzqDE$3lnOoVu@d6$!^)QPW4 zZ-|gznyo6hvrfpSyP?h)2W$HULb>Sn>Vqjl!OufRFl)>YW&-A+cq4(3qq7t z&vm$inIurgWG;44?8G2{^wx0^j}#?lxcy|u$kAZ4!f(F0&2Ls~fT`5P=T_>4MIvo;5)q!Xc-ev=KiUKtAs!J)vCup+$#Jx73gLXS6U+o?>z<4FeFDt;9?YEdXm z`pe;f4q{Cz(n5l<^Rs)ahN{2y26Wupe-7-K+)r`L`XBp@5`gRSS+7&EdCIfyBLOG=txB}?zm((zI5R!`~( zAfZK+a%ieToJP!QDQQ+7?I*>5N|Uis!KN|VMZ_2%{jMBgMg~y-B8ATPC}y`sd-g7fqhHz@d0!m@ zVH@e7409a;Ww#>8m5CZWgF^$LI68YL6ry`niJ}{S8|xAyVLKK2%W;0y_$a&Vgm5iprs~nlJVf1HJOrCj*~#`2d|j@iS=lqV62@4_i8*~=`vhgK55h}i zhYZh0l0MO@x}B{h9K=EQyCHJUFfCh@k|VThmiyo(i%k1^ zC9MlX2#4d%kTmO}AtWw9>o=BirdOEpTzHy)+A2>`5N$Q4-7ieK-N5`{c}=R!F3+9K0}k z5`IC{3>c}OzP=tj7~E=(_EaHt6yes_+Y`cD2#v*Qkw68%ux}~vamYvOOuZh{u8gXG zf03jkqk!c@d1h)^Qb)tQrsfX2lt^gT9j13MB$L62DM~p|1%hsMMQsDHk;|w*iVb!L z1YZ*|p6OGoXO(z&LPWgB@$z($H{JEo83f%7qIxSdVB2GR*7LZO5JIg)m$!I?f`x+i zcEn-ZqaosnbYiaD#gmr0;cc~w4agIJj3R-rDPFF$m@PbGu7mi(?g1MOl_cvwU#~ij)S}EtiTY-rW>;06=SAL7|fG@)D(_) zjdts)hjIG+RrM4jttHfNTg}CFny>O-Qns|rBg-IP947^tYtg%@SS8iHCG>uGu;;Cp zs8JG8DYUpp7ifzWCLtQ#Z?zOh(<6$wzLP6Jy6prIRmNu`7D#Yy6WeGxh6=!Oyxb{_ z8W8BIho$>ar@2%UKMJY1BUx>K1W#udZYKHmBByyV))>oUzyw`2sKa39oO<{SV`4&O zz7onm5QK2g7gb8pf9@H}5sj){kLW%WY(b!-8uwS{uHfSTY}pj z=I@xhPc8VlU&qXO_9TA=F)sDqMLj` zoGm>bX5$RA=-5AN^O9lWbnZ1&Q7*V$44^gqU6!h%GSqZH^8|m(k;sXcT(4gexE2(E zqp)5L3L{3~l%g|#6q-<#R47H==<|D77&qUFIkfLFTV980~(?roHOpPBl%60HT>u3XMGVVd*UDKdU>lxP_!=sFPFGXnd%cOh8 zQs`+Sq;!hCW$W&%rm;n~9-a-=&-FaXzE!@~Zx~922NdLg!x0D{#Q91gA~7L?DQThL zae#PR847NR&%;Ax2J)#7LPXz8u;?E6LKj)i*z~yFXpY-B?2)UKc{=Ebm|$EuiL;%? zj0CP@>hw&Ih!>?Vn}@6;ytw<{ALi}@iHNzK>IP|Xjn7ZtS+k(ykgq_oB(&<`SF8!#-w+e^qRH3gQ0&EDPELhvMZPyityh$7x#-tGN=TewrGLTbJ{__dgPcdlXTYC>pC z8m?WpayRO=#BcqWa3&#B8TvJ8irS((#vd7Jft=C6`L0U*90k!jKQ%EW@7ZHi@l_C0 z$^39a%qI8{t5D1+5B+`e#&vP%tHpcwcw4CFlu7QZAnWPn@2_m?$gqbuIJSkQ&fUo! zVOCCm%brrHZVM#SR&3GGAiNzkHqxeN^CtC)`n?~C$5YqY^>*X$f@*SUlvqx(!{l^U zy7>_XZF#b7cPf+*FRPi4yTo~*Sff;%zsbwQF=h%{@ih^&0+bkuAp*@eKE{{rW?SQx zeMU}x4Nc97KdScoVt$yo0K=(pWn*axRuoNtGa|t{qq61FRFdM?5EBhyC4^Od(c7Ta z6Z?%$n3zrea4d+a4uZx+15U*PX(QYCGdgdqjkcQad^clKdaw!149#p%`o^G|Qbhu| zH4yPc;c~Nx8{;MC)#hnB``B+KgzN%v7W|VW8H~pK;Jw2)jJT0w35~K@rZ|NVBfP$U zJkQsl&6#-`7>(B<-X#p!1VDUpR9Q}%E=aR3A{hM z0JkT>H=P$bqxL~r902&#U3Cbzh_qqOIOqRUoIPq&w-l29F^}0JjP*YX90n#G*rh+plAPoHLE^MI2bN{fh4eYa|Ad);Xy~Q>sH}NQ=GQxxVna z;j$#-A5cwy&JcU3KELi0X*2&QRK~GDSNT0buEZ+CF@H`935_BLo@)`2Ubhl+q#7?=Fzx3MsPanL7cU>MJ$!yH9mzVuzso8jeh=pyV+Pwa>W>Og1xH>{16t(=nYJhu_bM_PlRRJc zpirh?`~};dE!TsJ<14^_-kogrdScxGdMDixg|oXQDuoms;Zcvo!BfkYvq`uknMckG zvMK^MB>miX7ssJOg+h9l=^+mI>kH*0`p})uo>HXNmRnIvcsk)XKIqq3_A}Hnwrse` zFv+zii~y8%9l|=JD@VsvyacdggMOVnhdhkH)yC2Bu^emOa|vm)6UWzQOz zqNOPt`6@(2r4xCR`i)e|_{aZ#M^@G|Y0fO|iZWJs<<(?9PHekjYBC|i7GcxClcU

qaYRi0D((HyGKglk^$8}ySiNrZFBUE5QgbH!AmGHXNb9H$%!tyP6$z6{9y ze9W7%r`E}P4SAA(3(9IX*;pn}N^TiK;Zgd@@f+TFTvA1OWABo(?M`H})eTwrcgj}To!y-fs@$kCpG`{>C;v)Q;n4Z z$S|kS{NYv(2d`;;Cl!)DnI(#prT$VyA}U77M>p6qVt6}$#amLaEcQT0h9=beegQXqG2a7qe%UJgHMAST8Mbhq zTc<6uWzvk(0n-=vNF6X*tPW5F^-@3hVgD9oY8K0Y|bQF+aJR&vcv6RFBEY9XG*Q}^LEhXDu5Cj4N|=$FhBGj_r)emHl4NzV|b zeY!~|#W7y7eQ24EMq{M~FaCR$+~5!NoGDvO?h2THg?CeC%T!T}39#wY%mYk%-V6-7l|RRgV9Wf7OJj!lm30CO6ixBMhssx2GmbnvvNur zc>%G1qT3?t)kJoYLJRS=<0eV39J5Ut^CyQqP_m96+e)hx7qhbZ3|FnIyIiK3=W3VE z$o5+zeRk|o0WQ7z{($o|uh@B)w4chjv-Mf|;m?ul^i)pg1_Jb;k0z@s9~bV6KeA|9v(^U z!&TH^R)u{sT0>t46D92e(2!UWCBxa;SOW7*+4G~O`bEij;Ttq9T!nySu3if-X;u$t zVQn}48ztUZ284|H0f(A(nFwc(GIK~L@a}1_u05NsCba}GkV-lGELjWsAb!;!X%EeR zs>3+)y&{`2eX@HN3DWRt;ob>zBwiS z{CE>j-%$>>sdhqqWbzLz6)m9^&jg@*&|@d~Jq#3LX#g-2<17~CbS`F};5SdnL52BU z)tB5A&plYCSrX;;VRXjsL}(=%8qS4(ckLUp-n~sFz307JMDaBf3S~syCEreeA`-RG z?3ZtSq3Zh1vtVzAiLlKQWAto!NWt8aGDHfJgEaYN<3bS4j79}n^L4_{99{WqJQaS5 zfX3Ia=g32I*G+RwOcO^H(Y~ToFS+?v*Ve>IjMjFIuAt!w$d9HJ0pQ?ul##@LrFnx5 znw+^0_2A@tWlX^`irIW(3+tGth?&wpE5&ngJXErIV|;E~&$n~`Vq|H=RWpLnpE?4` zbN!!(=BWcji3djoamH``u7wXVo$?3@55@(7Auw#(W1+kU)I z`nYFeQ-FG2AKx7?T+_@IsR=26$Gx~6qCPycqP{P~kH_?D7eA^#6z8>oQCAQGQDjT_ zsf+p-JIcmD(KsO%pVupmr@{FhyfP7>cZ=pbYemhL>ZLaW4#5p=U8rICiiU?Fd0p*T zrbbso1AY;b(T;$~I!$_}2O8giE;zQjB-q}<9DX~W6>fN4-*s(I;+`;nm*VGwXs1{V zL&E!TTxX7Uy%^z-L7+}ftgAbR05L?fOwS|T97!@f!INKwMdMAc-jsyjq$9SJ`G}>;bM3y(doM@_BG%lklL$_kGU zVmzmh-e;UFGocHZQ>Z~NSaxTWZL~&>F=@6DF{{CTO;_nOIPGqeCNmt6eezb7_dXV* z)LdTMSt7Zh;t1@z$MDMDHx<`|$2I(JYk*ow~PY-DqQ6={sM! z$y?hLEg!BHYWCp8$&64NdQl~cGs{Y7wF>me zMNfT_Mu{1JXg<+|1hqieN|%|rq>XcR+;NCQHE%x3?A^+XJ}0z=OK9@V0YZ8kP7drx ziz#Obki|bz^#;-##38C&vrC^54Zv0+>*1bEPey;Q^GsAJio=70@~=xPQTiQ6oB4Sf z*X#W$w%&+qnbMP}BC$x9a+?ATJwjd9`!9INI!!x&nqh%oW?@7$H$z-5R$?znAHqiT z7Wpe%6@B*H?!1BnnDoJvsT`yF9E*uz(GqPQD>e`mw_a|<=_dR0p)R-M8A&#Q_wD%J za+o*mkEw|PZ@GUcHl-v+X)8fVQk5tF<2^*}nZYirgeAl_qPf zcbzJKV7)bY5q0{u+KvbK87&PZQi%#p6;uZiB=$BAH%e|%E%)nVmM>7n}3CW{^*PY5uVm8m{Z^|dK;=?X{4X~>99Z3 zU;VTUbMO;2UnC^ofp!`J^)))f;;<$a1oWHJ($7>>xOyM_u&+d3HS}BzBx+JVFb&tm zyPG|1V|`f}Q6hEPlZj`Yk^VX%kqiYhq_1`ch5K1TA9;9P=#j!(-51Q&x#=);WJ=dd>)E%h%6wJvt&A?`g~E z$|JaKdqO+KeLuZkt_n*HtVD$Aocuh;H8jvRm+`OU{WNvushGr?xl$?U-JEb*YwouO zZ`oDS1nh?J-n(+EWcd(?RI9=qckOrL^(F%UDDxR}QNB{#Iy~Sntkg zgB`3rY&!u=K{5+|YiKT(zn8nLDy|oUsdmmEq1{RQNHOX3%?Bq9^=b60$|o92oDqFI ztVX!WN_?1PS+Iq8lu)mf2TYiM+sO=D$vrJ!!$aUNvmF#eqRW>bDP3%xLtvmypk?EZ zZQHi(bjP-B`-|PNI<{>a9XsjRww=sBZx%C)+0~}DwWxdVISS$x!igw7b4**8T+WLk4e|#d8PKJ9z^p)3`u8@-rv{QqTbng@L!~mh#gk?dEaT(BWa6H~$-Ug77FC6uiIO+}{GWZu98*B_ds8T=Kze zAjl7&q!tOX=9X|mP+aOISN{pWlr2zSgWw7o`(!o{X1C3&2p|G?drw8aw3TID@+5?T z&NN19Dk|Ckt>fdR@B*TuPmwU4Yd>D)W3RWU7QdFXKJc1bcK(Gsyy7JVQxG4MMcki` z?kPtJNFp1a*)RbOCO*ftQerb$7Tn+%aMHVG326cv6B$%?Pb|hHS2zB1i3YV4SkubN zmoNKqV`VEd;xlQ-nZIfKebSuTn>o*=u=}hPI3GTuQrI@^;eVE!{(ar=H)QDu#gm+& zSP8%&m*Qx3Y-xcZHl zPdjVlCYlJMjnURAFjN2IyuSo)+3RY~Ez5Rx&C+hndBOOUUmbFfKSz+#?e2wM9(3OHe1RV57?*vpAG7gS9=F^3CNI14)J zHF%@n%Gut`*uRUIlH-2!@~VRqRthN$dUW$nGyd7;Fz?$t98y=yaJh&4HV_{Bl>r5kqfSo3i0f-y?1&dPLYiknKaHVmNT2Q>0g z_Fa-{Ca1!YiEuxU5XQXpx&+#FJ2hsCexQtbQ5$4rYdIC$5=kAgQ{o;xCC>w=Rwuqe+6yo0>slJa1*>$AhD+ekZI5kl z13Tw<`}uBEi&&%B2AQoc@7hW27Kp?FiU`x8A6y^N>*GAr1SpLM`~ zqo)Ji%c}r`NB;41X_56mlk4YjEz=ejH*tpFEIkVnIJw?VtRHd~xsuISzHVdx$`^>W z2chCk?_3@R8H0E?_=ds4Os-pkUJMPLv2rEdtBaIG)^#+RoZTuF_1KLScXOk<%4Jlfda2N(%$Cqsv<2qGsZAt9wXjbM%Bijzw z1<3W+v97OgFeXaG2Bkj&yfhgO3UujsT5oVW+C(FA(|G3U4Tjpr(!rx>z##x9+{*2- zQenT@qdW32Ki;IfF7>n2ydC#~DWa8rKAFfuu4~Quy)|=kndtH@J=T>A!K;!L8t6!d zlKWyF;40; z#4#aH&Qc_#j7{6ugP<&uB8%a#vWBThZ@jmsFHj8(CC|Z3| zIA1BC7x_bYY8Nnb-Sq$|*a0gfMXXepM8U1kNBI#tccC3VH-?+QDW;zLn)!};5hLuF zoSv97NSZZzfir{tE;QB!!7Ev+`P9Xf8NB@?DQw*HF%%`~6K}_fdG2yme!LBvQlcfr z)?HtKry$);uNa!|H|Kdy4kS&pn6hc*2%z^Lrmz7{W2HtW{}*6gxmNV;EJ2dB;w?pS zA}-p>nGc_RvedATz1YH4u~J&3=v;s9=KxV#DTZ^nigKB`K)hhha@rRb=C=s@$-E_G z+J+fozmFj3V zesz`|38PJvja)w)(D5fco!-fI&VM9Sx~H_d!B&X!CI%F=t*r)~c0iT>9G}=N!$HfW zknae8Cpv1f!jVMSCZTfm`gU@lXSM{0-BJw*z@XZMkUsVCEAF39fVt$uM+C8cp0zwL zoh-eXA3dc^bk~|}ayX$BTO5`eIrN-fFRa=Lpa}q*W_t$mD}IFA^p4y`u6%=N-ouU= zM$uD@uhifVwCNu7ex!cq+4w+Y)O*B8;+~4~u6-qAv#jk(irWfFeLoLK!-fWUP(A(K zA_2T*62y-=#zenG55nW|@b$5#YQx%)RY=reX*}q^Zk1p8Pjpt;)guk?SdfU43zk;f zwWz>*X$^+gRAB`wfi4D?o4DsMe0kv+^dVj}wP6eCgvHvw-7q2ca&4E9rhyiUaQJvP zmXf1_XTe{7vSxHfL0@H`lGrwmE<*<%Ox=SC5({5oDB_~VD>jPapga;8`u49T+c z6^P1~NO2{ILZ5UDgxC%}wN6N97oKUk|2ljs^B^+J7caC{N#NNIhN%R{*|i*PK-PZkOX=r`t$*rZ0z5|>pB`N#JI2{2_ww1T8kMy8c#x{#iBN43PP($Bki>SzLMeuF4da2rV8%$RdbBfB9 zDqEzQ{lqC6{-DugjFgn^MYy3c6h63&4Ia^w{U9$mjp0q4{RR3WF-CZ<(;4}LnXH4O z<>>A6PrF5KeM#xcD14Nf%&d5^XGwSSV1&0-fgnau}{ zDIVI`kZ@nvA1ODC9JqeEhmL70%-LqdAl=WYJXH+Rd2u?y?d0rku6Lt$gsjN%SCn}3 zt(&o@z!7u+?}?@6cEw{739aU zwE~g6zYGlIsuLO8jyF^v_IDyBMlbm}+urPSc6;G8x{*_Mu`k9j9yccvslZPxkpt}X zGL|~D@lpC3?j>&+S9Zb9dtmDfZNU|~r}x!~-!tWdVDF|hySL(X#SKWutfk#I*o$uD z8mESIBc*RlxeY0Q;bQBmfIBRVuD2!a&!+OxNVItoO5baR-#;J@P~&@_Z(2${pfd=+ zV?IL()bQcPuW+1}(Q|aiq>ykGC@Y$S3}u;{l8#t9@;=Vxq6J&})VIGBm3hW&q>lz; z#63|P7d)Ky2Ib%KfC9XRo+;Y*mW5Vg@`Kp?B0yiP_ps>HQt|3T^-F5Z;2vxi}{=@%X&Sczk`f^F(yO(nrYAwEd+>b-`)mE{B)A?zDa}n z*?6lcM?bK0j$pQ8B%S?00}EvIq{*sZwd$>EVW_574Ucs&Fav^HSGnp3%{HMMk$6D~ zDDqFB4ARQPb@m4JLylwA7jGabXBh4H8m{UoJs%JpRHNR1c|zdF zX)f1THvpN&y+CwvF+3%s@1@HO0-;RRIN60)+dj|C(3D!^j;3uw<`9=p@$C2wf4M;p z-K*SYd@$;s2`__-AKMg|Q&)T3z-zKn<@TEO5Mr0V^yX8X>Oj2{L#CvxsZ0bt<+tO^ zXxM*|V8bd#pSk=h;_e%=#0~ZbeE$_wmiiJ~vfG^|0^lIqeD#KCuM~PihQATHgvpv5oc&|fJ`fB%Fq`U9@&T86Ez ziuP{kU?e-gak1zN7S8n79XsOEDz^=7=w470x-1W_ITy7(kYELH+c@%&em`;IyI-Mjx^ zbP@_XGX(J`DxT3cqt1#4eOBnL+AFzt^=uP!lq|46LmSE3d>Pi7S>j0uUxhp(oGKk< zm22I&Ke~epx2b4W(v&fF*%%0F#G}nP21f?mo&kbLzQezOLdEITvC0^ROq>p!QOUl&Mv_F2XXI-h^mP>>(?>9b!6s zvBDcKq=zPL^)B>6(E3iwZ{=I7h+~k69Z22x$=A0f0%pP^2xPe=Bf;jQTIedn%!u`s z@xTjqG9C6x>`#`Sv-e8z59g&QiZ4<-{_5Jw%2($CdtbojPH8c}5ES z?i3B`VySqehvFeUGwLS1ozzE3fUl@^I@tewjyuuO@Ux7Fq@x-XZy(mMhgY?=zQoYK zePwBY$mPScXRR;%cl-z$#3DehI+dnRC8UnGw&DZ1&M$a^`6Qc9d(UjfId9(N#GE7F zhDqDarjFDEAl+yCDFqC;?TvT*-zAPWtk3aOfG(^`T~E`DlG4O)()ESf<=UX&1@j$;^s zgB=D{+}WujEX-S!AXx+n0YO6}f=r(B-^2VZ^!)K$<940V+~ehO{dsll#iL1hem5qP zpw7&U8h8YL3r+z7i;G)P079%7K?IFXey}qeTu5LDl*91A8&YF&qmtZi&muB}~RY&Y^dL9KnV6_KdrF2SJ@j9DzF8L+Py%p9Ge(~e;k2{wfE-*7=VMbGY}X7l>1Z%ASbH> zdS54Q3Corqa_H~@O5A-U%pq`;0~ny8`5@_gAbM(U0jX&4x1(C0ao|ilwVj{=FCyRa z&l(T4;*LYthH}slrzfV7Hz8!UAj^(Fu!Z5OrsJN3@4@I%W({If5g7sLpIyb76dV2X zu=_WiE^;86@_2@kI5)Moy2R9NXltR{kXJW0;(-QM%&k=+0kp&f1V+$JaJ#i%=)2U| z5H6QFU;w90oNxzO*Eed_E_B&rElFODJlGp_TO-|1wOb~vn5Y|vYy@}&WKcn5G;a{F zzAR8?q=@Ri+6V6(`8r^GWZQZYqGwB9nks<996Ft812^oI?7_X>H5hc3S|h#o8Q}U* zA%zG8QRId|s0&){LkR&aM$3$r0n^DlB}b$H80269WRREh=j$XKD1Alpf&P1k=k0e4 zMK1Q`#iip{w%cC2yE|#50Im|s+&pMx5L9$1&>`j@+km;3EdcXf3AeMIUjc1H4g&G9 zz;KlDwN$@u0J8HIjlU59P%elYE5d<0ej+%l{C79#HQ;Mo@tfeTm*hhu^&9TsdlmWL zQvYu2pYzsFAf16=7cmFmF%&+J8bKBYkIV<%6VgL40;DTJg9r2oz85N@T85BC5RHOC z*@&dmiKssSDI^cjK>@?rQAhTnCnVFalSe>l3N$uAK(eC`=w?W#CcY7}#r7AuV7U&5 zgGvK_rZQqTc6&`>bgL83;4y$J}& zJ5t1R>Bu1F<^};As1h$WQ%De?V7$Gmy%flb5X1n;w+=)k7{qMvFn}J~R-l+(<8K1F zFxPvqJsIB5Z-_k5jzcca`nQI&?6OKbb}QS#PxWlXf9+2K@%Bk{Da46jvCMr6#O6iS ztCZPJyFT(uxn5~W*S*$sDbjYg&!2JHu&h8k!gfDA*(DUtoVzVA8 zO~Piy4N#GgVlI`^$lAssH4U4h^-muz4}w3eZg|y+O>a8?SdjqtV{CZq z*|f6MB+u>3Qd>s(U{IF_^Ow1XdpDXcgs^h4?_Hi^^UL2F7 zwc@zIwX=OtZuSg62h9c!s1W3-KL@S`MI$Z!JxHH+N;e$Zq*b~H+GxDA6CF)pRHe=% zS6S_`ttVi6ewAp9q!wq6=3oK5P0rk|*XsWTdN*&Zd^$ThWj9a|lwUM*yS$%e%h|+v_ zCsB12Rkr8L=K5)OGX!o`F(f#lj!vcjq;r4h%r!^O{fw)$lH;#0X`o7DHSa!gYGUcxM-UD&O*DfZ9@6 zbk|%P#DdE#C}g-SSOQ@x9V^$z@xa>xG?saXESD;R!{QTW`zktv_fSJ2`2=kQy_D=G z`KnfIS7ENcjBzJ$C!c*QWvto6)Qvv9ezM~7i8fQvzq%cb8%7HsMva;c*53t>8^=9z z;}nLmVNkNJz1u#Y#p!WpuTo3A0+riBg!yAzpOd2uYvXwDMzs_uFQoKl}jFH-a9$+cFO^{=`7qTT>cz}aEq+*;}~GO z;uYAsMYRatj3zx7Okqg>dRs{kWj)MKW^D<%`GHUmmr(k!V(|L77ro*|)VXtOzfiw% z)r&DROQ@=$gc>b4xghN`qv>^W@gAYnZ6NjCa3 z2a(I+=h`1Y8L3y9M^CAiHac*f7hmb>>~tKSCDYk;et z!o1?tIhw%M9k;gW@Z-26WjqVoeQzN-7iLivlpAnDGj-sm8e?BS{+`aogqPPvtc-S? z{jLMlU>gcCuMEs>ikEr~JjY=C*1g$H#d4jLv9eTj>PBrR%{o!bo0htEP9kVqreX>vP{A^IEh<-W$u!3}}yK-`Ln0PC{&$CxxvBJ{P zrKosmLDpUw?ITd16eSGZ(qm2L!L8DK~P* zi{&}u@4EG9$q6V(J^P>8%-NU=f&RfiVc8CKG)Ydgk-sE{7hro zMw@gliag*Dx4GmVw~`Mah6VHK4d zoZ>!QRj@b_C*AJ|i})uaG~BFop$n5XB=eRKudWt_Phz9pyYSap3hf_&c}%w>^2xis z=OppB9;s31EHkCAADEBwbwL(XX*(K)+_d=^qalqO*_e}Ye7eif3iQ9B%@Hpj4unji z&}14ZuzLaHBo|m_TxfqSf}z&nPqQ0s$bV!M^n})11W1Rw`1g$)p8M5#PV(M$SM_&~ z2+!dx4lP&~*UfA`d%pWX_I7UX*~LF6xqEA4E$A7;=ouV>(>!wvf!^`+g!K$!rfGKk zqxMLs^@#P(gJ~E`%u?=govx_e<@Y^sI248S;2rXi&Bn7BngTZZzc;Z=^QFhs+)Ezb zJxUevGPZ8z7Z}9NB*J~az{7BFyO_F~Mg9oef%3&1ZsO7)A>3F3s={-uD#Bb20$-%( zl&FFwrV@)D_JIaM*V@o}VOT7e4Vx@Iw}RK6q*Os{dI+N@{E2wn_KMc|pQq+HZ}ln; zL&KtpRl%3>=e9_B$avDPx|d-{mlJ~Z50ueiLlYVTrzYH^#H>$U)<;V70 ztJ7Bsy>xni4v_i-g=)ri!>rITZz#Mh&}a@$=OegrjdV%aPvZ^b9F6|{LV%t8N^ zk6@CX&IV3-+*S1i*a~H`mKnJzCFElhvV~+{RaCkxxH1pBgn8usUQC$#_uD#69rp=O zG#l-o!~a=-Ti5w15jX~IcbCxI$%66@uL9{k51q*^0F+ zI^$+!bHYzL!$bTgrM?r0nc!#0_97AzKC>|go6v3LeT^PiVg+9rszBYpW8ehwKimkn z2p&6-hax#}ihcnv#obl$#w%j2t~MzmA_E`-b`2v&f=BFOZ~eZP6dR}9F^-BS|7~p47pSWq`N)?*s5{l zzsf;Cz}vM=-pJJt$7qPuAM)j@DksSOC|6%skAWNjZbPf~rO&Dao>m$sc{fFa+BFw9 z3H1DWZCKFY3s&1xr8v*+`QQltdW``$CIJPf%>s@P1B5!%I@iBhe;;*HbTydAT|EYG zXI$x@&)L3(q&)k5#vkE^X^9fDBWtLbd{0`LM)xI9;U*W9foEb+L(y|c+foB=<@GL2 zTgk|P#=V;Irt>`bwy1nUW%rlZ#xEqHC)+r*7Yxipm-SNuij0UiLXbgGE!j^7mPGxd z+m@zSe1$Ac*~tSRiI#Us69EaHOnHK!QZq{6Vd{GQGB=dcVVS?3h}pX_sO)lmqX~`|$UXaIcKZvjN0tFV*afb7W0t-}vquZ-OCokQDo!f@gBJh7r(?Mxbc` zjcg#U++E?^;^CQz{6($&;+$bwL`%#d#rUd&sRVW*%kBu&<)S{#a^wxj{iZ{msUTYf zuSKEpY08`aiFnde0r)j~c=P+iNnQdnnt7Vst)$S0m9t-6FOUvcHn}PpESFxtxzWB; z@!*#Jmi?3c^>6Z1g>}YfONU4wZwq7QMgF)w$@f2&l3)zQf1T9~aOa_~gaZrHIo#j3 zo>CPM({o;hE8IzboC7jV>jCmyx6|Ia2iOo3qt()HUi8JP?hTyl{UqPa6%<9l-+s{9 z;g`Zw*(68qb4r815~wDPUE2FJUhN*?&|~IB+B^{&aO*kS(iqBXvExIQ4Bknu> z^@hfRzkh*x9~)BUxMr3l#)Uy((Ag2>`;`xsi3T6?O`xT^b`d{&cgQ{Cwcn)WS6RBJ z(p)j>;hmAB3#~6M<=hDpsAn)^w1zGHG}74>4Og;Bsoqys*W5DKZ1I+M6U~2;XnP_U z%U%b=iMo=^M@xqmCM9aFoe%t5+zs&9`hR*D?rRD5cH8-^d2Vtebd>-d>U%~l{!0I=rGjqYLrwPg>zGdx>I!BGV}W! zy};j4+%9naiQ*1OFr5-WFFv{U=wi(px2G)U$P>L(`8a%-id9Ibc;WFYiIge7u_y(p z=2(Tkd}!ka+*p%{%k_}`i_WS$d?qqrXbSRt&z>9al%w7(z#Dwwt)!m1>{-jqoh>bq`o7MD-8F&30t%-5JCZsfOGTngk&^r@<8nK&~ zFE(e8b*dCEHGY|y(pBd|KH4uqSBNW!?1%c-##5{&QD&+71_a`+XOO(L_E?08t+Qs1G#E-Q zG?q^*0C#$j&or$PzDnRRnZ}$i3BK6scw~j!FN+Co7hs+H_h|(sh)m z7(a~_J@f$)|H>P*-p{mndiR$lLh`a6W0-8s#M(0-rlZ_;EQpRODvN)~(3o+U_g=1g z>k*G8yZkxKR-orw=4*)GN2yIC{Fy!VK-5~X)GCRF<&g>&wlg&au?QyK>1wX%+n|Ef zWr5V@`?43!<7iOA7}Iu$3Q7l4p$sQGVK3FGGxQHg!IcLati*G`8iF*qG5cXJWTq}~ zuNRqutXs(xHNNydP2>kBKsWYvdmp0qxW4k#YNHEoZDGj~H9!i!oRG=1;BX+OuVlv6 z4j-g(rlxVFXzKIoB3yL$ka41?t!;4-Cp#70U_K9u$6?*gj>7)zR`Ih+NhK}nR4_~7 zIEWQki`%aBKl+vw6}H+y7`S8yZSi;@ZM9}Px&I@DUZ2f`r(H7JYHyt zh1Iz!V@UFOVaBymH7AF0|K-<{r=Duu0EHpgAzc56EHbhSDdqIqpxJ_^NWTl+<}(kl zt69Bf?Flbl{oGHuMXVHBFYNl)ij;C7-8*6Png)~K^yc9N%NzE)xZmDu0FJKkx@yy> zI3{TQ_f8J=mm>O>M)HTFh2(*J!b}7Fr;U_fA+3Psm4Jau%L&Ku&6JguSLQ2LD9^ex ztXD?HfL%`>rVN;lnM_x{WY?TGk3|E3)h3}|y}&tB@Zun%ZoquI12H+OP@+35r!`q$ zhWTXLgSXWkj9u`h<=toSaV1t>K#10+OraefRuvty;>mE@S>%XhoTK3`w09MdMXaGa zlPvV>gSel|H0iH!%Kw$4;bZ|Qv*+x_*YJTU`{AWYLLxQXL*2`sp1A$fDDO( z@oA5xVcuWU#mUteQz2??RB{ z`#XehsvoX&U<3}*g{;sAd5G?Mzmp!bZIlt0HTxPJ8XX1Kt2egFabf%ptba)=EpXdX znBGz(ytC^v1760{d^;NkyVU`v6bZ*oi{j@ZI_A5(3X1prVf@(Szco^L#qc8FI?;OF zZ-bY~17pZK9kwIZGfdu(ga2Y42qdf4HF-PAp46_uX|i{A6?D2OG?zU|?1XGv)E$NV zZrXR66ykVf)8cP8Wa4oeaiaLkc2zgFC_7sFilX4OxxJK$+YdxrSR^_?s&B(lleAXm^unpS&tr-I3}Pbu>u?_q?#9ZfT1xqvD5 z95{CQSVU$lRxu#3gK$nFQUjTQLel!&llBl+7`ben)Q{Y_e#*oA8mLd^GL67z+wT2QT zTYGRu<;6HD&S(rKIzb3)gHcU2pSN)BpvVzTLKoW zdBkA2+lcBwfBCBaF0Y@zM0v&B>*b_W!BK^06MM*z!+Fc^T-U%9NcG$cGQYN9_dl62 zlB=_s(f=GBjICigdHyFf=KOz&(L7wNEdK`>&CJEa^FP4ow0Kxh7$AN}K1fV#f9*G< zhX)dJRUj1Z>By#Duw1|n1RN@RKZ&qoD>AWX00i{aZo;2-Hka$~+Q+T4X8Byb=E|Om zH+KR_-d_arG;|@5s)V2(`w%XHA)u_**0Mn$$PsC95PSW`ri-ENJi_0sCM;)Sdb&o? zZ8yEptc;2g>%qS;_kgE96|p|h@he0SW+o7NVt9W_crZ{;VdDI6WE92$5Uq$GldyRs zkcyIh`8Ap`tk6^rSn0p3*9Td?y&&r}8^HQRMQ6Cbpnpj7i0T=pB6ABP?3u&4`Et*p z?t#pTXb$ArZ+)i(Nh~f;P06HZt}iSk!R?)lhdS1ySR8_Q4gedrplga6WzjztVQ)H( z0(gf|-YhJ1HDf^Zbkfgr-3daPGpU9kVLh3-`{?r>SHht^+AtO&ZydRWrDQPjb|FH) zWz;{D`aoZ7I6;`PUanmMiEnv`;BOT8`X+I1UXh(G<~D>r+#?W3%fFS*?OyFpAjFQ9 z+u{+ybbBO(djM!4k1#zUG@yzI`d7{hlo$!&YbmF)7;bWGDrExW=%!QRYTJsig#Jfs zq6jyy=&pT@X771YXuB{2(a6=*=ke6qAWDwoc5eU&yuI0HCk&kjmAwG>Cp6x12i&JP&DeT)N0;cQSvCOMs}?Nhhz>^y+GALyMzB6xY{CCLI=M*1cEX|y~W zE<|sj5%B|k=V%Y{@%giLzZV4)8@?_`s{@oikCT~uS!k7LQt@2qcJQ#XuM31p7-KhwG0t@IjMBZ5) zjQ$2nfw_>rFIw;ig(}nyTu{%QZ>6ijtS^;@Q3F`RR~tS}(C`0v-nYa$)B%S?DR{vz zBB@A7H{XrR-_Wn$NiWy*-&`r*4kC9~h=@R&*4NE9uz@U<9{g+&@?)u^Q@}O=ch3lE z=UdJX@zcd-DNmi*WAyuxwq1mfQv}xjKF?epU?#$fxK`ksR3kisY@QEk*IN53|08ti z-Rm(03Kecms%z9M#E7IsJp27Zh&eg`wF|!YMm#B`hrIHiI`DlT7ce;)6#VocaCVdn zS-KwH-^BtE*3~86(nQku4tN3W*$GEz4)Xpau>;}4!ry&D2J<{wB{KZ&*#G7?6~qq$ z*k5j!2%!)K=sXjVL+^0D;K2xhJBodYAPGkI&Rxs5ReuE{SykmB+JDdf*Wa84OpuuZ z){hM0iTV)UvCu&r*FWI|#n->ViA={4zVYq^O+~py?Y>g*Kaj7UkbJ2hMO?oHKU>H4 ziT>Wl&z>W_7&JD!dN_Gue-Y8$GQWHSJ3>8}`C$7XCrshNFGs`FNIwoLMOTPfeir7SCR80@J}vQDyt)ihcW;elExe6nU~H zB##NHAUddApHwhRDEY}!6n&fMtzQNY2V7x()8M#lb(n~rNM<>?hIwOlM_GeO`&V@&@4{;_1S8eb;;dqk^^=$PjCfsg}@MS=cFv~eB!s+YQg zc=p0f#KSJ(eT!q~X1M^`X;Y9w@#Dnez2$hacWnIHJYZZmD$^xzp8GWGxMRAJziL>;!h}I`7U`FP&#QoOJ6uJ+xolMy8*>ZTSOd9pjCu%lALRXpK4ecm!?hgNT-l634J!4E!baO zLX1@WJc_C$-A3Z_!ls^4rc=ZeJ2{*k%r&s4A~>O95a=gh_dU#i^SAM{Iuwy!IJl#Q8x?CfHh zs1Y1y;M{A>@qP-H=!3{ln@q;qJx(2`^u3QCXL=Oo(rwj6KJgyD0^ZWPJJ>4Cw65mq zx>r|65ffm{W1Euok6R!B0c>nyn6oO=mhd{92Rb)sm5bpYAHkj2**DuHS7Awsvsl}z zM97ia#!>TsVE9bK;;F_c_-JPqverEAk>;(0Z_q^yBcP(|LGz#t|H%5nZT-RLQof>E z5oz-1)y8M*^e1;+fPvJMLDNJxb|vY%aJ*l;7h!mCW4fkN#HjZarz2yDkDg+-7y_>M zF}bmi*piZ2^7-^x_em>Bfrg=P9S}1dtad&=*LZ}522Qh9SEl=wtFR+J8@32wZy7{6 zZ#iznhZ?>5cqZu#%j3<}N}L3mMB$J7HmJr|VBt+0S)Cc1z%YZz1-w|Q*T8$DZy$=j zo%?!#)K;A5>$ci<_5E#GND5adXBMCRC4XsQycrQ}Dp&pkrw2c}>T$%$aU)dYl0yd1`u5&j z@acNqdwI74!II!kr~C|Udkc{9Wxv3$B}`*W!3 z-~D{ofJ9o(9)oVPuR`NC<&6N5>mj@7G@YZXJEF&_8mY5xj+3PGK4#E?L|M|1U`sta zuP-kdk(J&rhVx^^meLGM&m{&s49HdC_F<Lfj31QEhg@Y#3s*p+<=?uY!j-I<@KTrJ+&3p($36qit+ctNubQ+rGO{ zIvIwbf(xaln3e|M3XZV2q3k!h^gwZ|fg83tHmNM8t3UrgByROJ1&6MT{6G&lutl(mc{FPCB=sWkeiG< z@2)nwG+gM!&GH(+sg$J^V--4@O|G1kom*EC8|W%^hQJ*zP|kucbBmk|o^aZPz#UPT zsNpS2F;(Oe1GD+$--lQ^du%A}yi0(cVtI z8Um}04JLKeYChd0_2kk(XjcNUShZx=$V{hL5X2^3py1R^z?LRYOGfwV|H>T8tX1k= zz1{2g?c+N+jQ&e)w=G#3wa{mXyGJxpnL~B4lxOL>C%dT4;JvcA=teIEa&9w*{S6{= z?AReOutUkuV%QivFJ{okw^oXk4_>c?Xe1!% ztWwt7f7V9jR)(U=Ii&Ca$mtgiTbCbbphO|ac_SN*1)ooLBgKNVm?o{MA)Ta0P!`H+6VpjO*o%Pb%eBnK{P{vMO!&QiDevqm#HE z|Kbl(+Wf79g-Y!EaV+5@f-iF=kC#oUH`*q~k9|P5ec3WeLw6*7sI>e+=h)!GHDuc&kW3#64sST)QbO1A_d~nSQ8|$PVcl#@1ZB8AW#$ZjL zH9wIfhPpaaY2y;fCv5d7U2D1$OvZw~RTFv4Ozcs&U$FgZEz4&pTl-{6_F*h@XMu0XTjLK+p&Q5UsVb0tp~v398>m zT;Ic}i_4qnn~T532ccLaY)mLJV8i49+q5+GWA~UjPH=MJqaRQc6dYS^s_ha)5P*~n z<3css&$DXboX0TwVuMzTMb71HnMqjf9a`0_9q=Bau`YjF%|B8 zJT|-XUeH|vDmj;*D2eylpjXY0HtyU?mgThuui$E$#f=!f?^=zjA1U-TRau@S2}-Zk zv9NIxBBlxaWQfJ6;7to6+$m(jyV-^r#s8wVjodp=-m`gGWWDsHo>Pib2P{ zYngnvaKWftv6{PJaf;1lGT%O1nT_&>GP!Ol3 zxTmJOqY-PBZk1i!tN!`vR~)ol3=gLs+q-a1t-Vik^sKgIuQ1WljuR7$K2;VB-~IYvGtgevY({1y?+yj$-5$TKG3 zp{I&53_I4w_5@M(!w=umcy2BKIlr?-pU;5lRrmy#dcAm2MDP(8#Fj~hZ;!I-g`eF{ z^@Nu$*zEBD{$+REhBwYw!p^vmER;^Qh$mD4WPvceuXDsguFwM>xQHI*n}z!KHg1`! z;y>`yMXi|JTTu;?7-t}FXnb@{%+qUgw&-d-W>fcp;(9g*_ z=<2TOs{3BoB`4|S;uC4=@HeyUpFj;sR9B&hiTzemuzOw3dAf=S5^AHkd%PV45Qoh1 zPzHy=H0I}w@XjpK6`K<(Ta9AeDqS0Cf5G#w12nzrd6{B@e4a2!o&mFz zzt?UUD!>3=#JP;YLEZ%{Gf^g=Pkiog`V5#M%-~Vp_~glLh!6W*nX#Qg8zq1UxEOM z%2|LKT4&vlDJg&|qMm>dGfUd>`sg^}k4_(&h)tEojDM8v`O?KjYm}-z0RN8pI0L;E z#pcm8%J}hA{^B^z?e{-`un~%tfSrpXsvp}fn=zx@pK1Riev2x#{91=hYez4g!>H9E zp>w^e-L{ICmud226cQ8=s+xBqg@QId9_f%_-CsrD;pR;CoZ_!7h#MzI`aC;N;qq%T z-G(k|%>OjD$}oc-6f^0?fLA=vpg-gNpI7Vd9I1@$D1FSuC8_$ocQY%lQrgT-fE zBcLMa9VEKTC*JgTaNL)-HM{|#;ymv1$bh{FKOVLCA|vh+{=55bK>t2vjB68%p#%*| z0{fu8dwV{{>$}$I^DtkZ1L{U=vM`oD!YbL^-O)AQ^|wXrpSQs@MY1^*5cV%>rc}ee zei_0KvX9i4hTqVwgJ1=fs`1tl!b{S{Q1;hJP5Pgd#WrrBT#-99k4C+xk`5XC*Rp}y z3Wr|K*~OP8nJ`k)fKeT@6)I}6ICcivwyQYXsNzaXI(ec}73c*DE`bS6tZJ6?k5Vc3 z7+#peA|2H`RAw+f4{DwOL_g3<`-9w9^Z_S@5c;Y`NHWicn2?-~BXW~}KO^OOh!Ec< zsM|X}+$nO+imXh={=_cgqn3%g6DDp=zlv);j&BA~m7ot<0CmNLScSXhWv+;HBc8mG zOJoy+mcqIplmP9+--+V-#m&8r663Fy!#S+P!iAJvD2N%~i3#Db_u+9JO_>iNGj&Pn zYT{q*(IC6{V2|DXmRecwkbw}OHQDcJl5ebF&icZLWaY4eHC2^y zoymc1(DICZ0L;<;I^tj)rpjWU$;j~?6t<|1L}lp$kyq`#^BBSsiDa}d*2F~Hvm_L< z`&Rf=(b+4ZbYlbKDzbbL?u($vgv+0VcwX?%Ts8 z;`{gNi^$2d%(Lu@4z!JjBbJi4;AU@%4YOgfmF^T%u|oZ%xuBZ-<&@X`1m_JiR@gE%MR@Gv=Wc3|n0}`eCrLDY5zp{25igB?)Bjo-6}v zeT;8z0GSZR@3;F+!I*G5Ifuc=h8cI6(+ZEj?PCsH%P?20S@P|0z>EAd#RY-4PbAvo zmsr~_{cdJvz+NkT@FQD_R%Fgh@ni*4!7Hw%PYUy-_~w^c0)K=xN8sFVW ztFt~aEoPOZroZe2(ZG=+quFWLqbcqr+jMdQ9yLF3M@!XvBhuluvv}(CU zc_EY)UpP)kciz2%^+@DGU4M|0TMo}&fSsFbApU&xg=uN)v10=4S{h0bu(*BwjYeXr zErynb z;|@lXzaNIBX~;d$UnWKFLGpnjzbb2)1O^$DqU$8M<4y*&cbF@DA~9vFTi z!QKNc8VNmgOiXLOon$p^E||Xx#gw9psBD}Sm*ZkyBg{rQ$XLC&=j*)}{x;K-vek@{ z!KMPEK3*7^cwz#DOPmwJv|YJzSiZaimy}quCI+tiT4yJW{AM>r)P# z#2L&?y+(xT6)D9FsfxQ!P*cid9tR{yCJ?mFKEng`ePIdI{Zb;dh}{X~k0hdq)gchj zhkWKIlV5ecXfeKbgwoJvizjuTfWQ8D_iLhJizjYPy?VdR!%NrN+$;(MZ1{(AN98Hy zni345DFq-`BQ6*G4n*}^3}J#bwL8`7nPxa1opM3I zdPI9kI>)_luY4fTbfVI;30)IC#RxNngVo{lov?3T-YyMY{a ziXO`COy_T@0=EmIIFi^0#5hkCm0!*YoJp>BY3M5GBbu%BCD@{~8*0$bT^&%6okcYH zC7M*`658;ZsJKF4b5_#pLl#oYEw#NF``QSO`ZbOSxOHKe=VJLtFVJ-S(|fv1{VWMg z8PeGah=z&W*UtW__}C-_n0gv0c)05ZQ&Lx0qIwSzgr6l58IchInj0>R2xD@8uhyL9 zgiI}TNE^D!ZD{25H0f>WsFrSo&lyKIn`x=IE3=DhXlL~ao(gYPj%i&DXrnTsQ>6xf z!@`pJHXZqc8%<6zR7L>|x~CiTEDo)<=6s#;2XaAecD7@wCFP4qwnUA+ZI{BUFzMWP z83r*F4H2@GZY!PuvX_!MYd;ozSTX_JdwdOeTE)3Q^t~B*+a?-FIKJLycZqrav(DD1 znHi5b$nHuS$rTw=6TSLxK=ITsLR6$P@a<`jSPjXzC zM47oGYxm8!R8OW9_h1_Ie;U9Jp$vfsA~r0f6~P%m*&F5OGD=-Mr!3_9O;zJveOH~x zU6l@N3oZ)*4`)~XRpX_@ufUhqSBhY1SM;>I2fypxKFHxizJ3Rg{bhMN7Hmu2&if^^ zOku-2^ak4_3BOOu9q7jz#ILncdn z*c(d<6=v46h6E!JAQn!GQQ=&0q}_|%L&~)WEa4dq=yEZ7>Woo81d>4lq9JjH=%V+} zp^_p@O@oL{@QPq1>$=B-;gJy?}XDr%-Om!{zdj3ll3rx2V}|`Q_tc(F4wMXPVV* z4$BA!z_dQpF)j4xi1=f#GGlC_a752Lbj2*In`0`F)=BZ`VWSTMX3AUwQeEu`){)%W zO31WPq7=mqOC+zP+Ck)rD!wr0;j}fUW4o!x0$UQQogT zvL`G|e>&d!h#1qRA}WTc^V3QL5hcM8iD=nOfakGIDWO6BsF?ZQ-K}}WFXh}_-wDrE z2HrUWi0r25Z8;+!!KM}It}%KQy4=bAI5%_mMU95X_C?jLv%XHw6Wyb;=~N=HnzuiX zFBAlmBaU0#<7jB&FpD=u$wrDD%I%Ph0O?Rb|c@d+3wTU zfHjN*vhP;s)*v;5FTKWowj|PB*vykasZ_VC;zMN$r%umxnzRcLd-(q4r;$tFibYyd zsCESKsqoVG@Fr;lq05~6W#gGp>$Xl-(B(9o&w`k2uJKgG+8)gD9D}C<)^^i^GDq); zyW;7StVjL}>mTlZBeoH4`7d?I*JwsUz|ZBA1(v-ytg}onq-kO##XS$*f=~Mp4;@v> zWRbXb{x+ZVo2f#;rCUYrjD>?&qp+I7Y72fGrdZg$(j3Kjd!ZZQ(h+>&8>wRIb;77rt4R)+Fd*SLa zLMc}&9%O?_E{&&%0FzLQD4IdgIYNnP2#X9-fv--Idy?f#ndcIs;jAf%blsRUy+J_> zrQp7^=s`q5gzcnGxPtoxwBHZm+@z72c+_?;xDO0<)G=VAJ}yDHQhw-a|26cUW6ClW zR~YKfzmM%I)#~cdjn>~z&xa?JS}SGN@FeO*9hbqC&Ca}|+%vK%j*+Ek=%SOCHs zfZy8K$R7#iJ=Z?)r8@LnE?Nk;F&)H2L(>w58qhTBW!Q74B&qHL=)21SS(}hOY{x~J z@>9GIFfmlyb zJPbCUpzuKRV8jJ*HDgdKn5*4!k2mQ0b6a63=m3+SETNC!?O{hZeEZbGvLEn}pI8Ma zpNVY{m+K5R>d6B<408(o=P+oBi#dsk8Gh0{D@f+E6!%R)_ttFG`~H+2$1RiG7;t=_ z%@aLMjH_Ht*c8rF*jmLwGP}L{Y8MYLd-xkHpU6i!{vh#ufxFY!I&nY9%<<`Ze{JB+ zXum&!^yzLPrcHH%2sJ&h7GAz^2kMDs;;ogK;RGok897Nc!Q1v#!V9!dw;r?-8Jg;m z0=7sRr&k&vjs=VkxhQfOBtP;np;BaV-*aa{FKQ?^E7o-`75@nPmc7|(JiMo%V~1%1 zeckBHO=B7RvsmZ7AhXR-4J3BF0Pyfi<$NB{os_%KhZ9K|nP{i(Obod!i>l*&aji_M z$k6;*Y4@_d5)@(|S`hSdp#Z-)H8RADx|NgakQ)myK~97c9>`AO(02TiMz+=PBSf*p`L z%(DMO*v48l?X1vZ93Ii-4i$kIcJpa3l~7i|(xMD1XApO~Zd&bwobWbomRt_+HHskl z5*iPX8no3$BjQf+j$e?-UC9SSw{B&9$L};SEDPlpsH4@NfLrH z^1qEe;N~u6wu&xKHgdz2 zxS7=Vw_bHJvi%+v=4aD@f~<#T3YWd!ndUOD`h_oSmB(RIa|Ve`@y$XBApBIFiu)%3 zJp!~P4Y}B%vV_Nc13N3IbnRxV$=aMGm?}S<-Fi*m(|rSW577jYD_9F(?x9VbW(r`3 zZ$Ko9MLWG>_;KKf^1_WPYt_$PaS1zh__njtILhSpmM%$V{K&J$OQLjWj-5Rpiot9# zw0J7VHQ~y{C|uopjm9z~kE^VPg?b!N;M~cJ#OlQ-?p`C6AV@`3d#V2D%H~;@?q$75 zGD{*OO<)Iwm|YhADqPYra+<}1Abjl}WVJi;sG8PM??dmpldOBplqSQk3$4Ggt)JeT zA>H^m)TmVcXXGoiU}OcMcpeQmAQ?h8mHZ%P=i=U3eT@UsvUBA_Z{M1P*Bl+tw-$#2 z$CB8+rkV4Et~Z^ce$=PHEZo*L(tn;df^m=<;f7iCrBhfGx&2_|^C}ghGRz0k87_#V z{Zvtz#zJq?k&k!BwptyAtZB(9pu%3+0sNHTnK0u_@ zcjHWUFK*wB(xgkuyP%{w@heLKav7 zO_OlHY(i=GKQ>8238au+nx|(|#u+>R!XFe%Q0KXn^SU}hOlH!~A+3waWu~p!>@r3_ zIR^Xp01ewIf;cM-fB`TlBRxT5YSiJD)|(d2$kl07L8DwfjpH>kDO5xwC zj(zVoG8ryHNYei3$ON{!d8(eMOZ<5Cm%Qrl^GOa2KMTc$HI9ztBBdVugISc)e%vz7 zVp5>KHIAiaFYx1i@01Dv5%a@nN@TJ5-AyvM1qxrk*xP~^O$eUPO4Vz4Wafuo(ALzV#U+7;`y_IV)Gsx@m+ z7uF_>SCU;b`!!bO6(dlelwxQSaNM(`a;J-l4~|AmvX8tHmlENaICu``l^NHit4DXX zzykSH=xPPAm+Zc#mRZ%eCKaf(-f&*2gYrML^yIK#)4(BQ^x zm`0e4MUBiy!G!`&F_0l%&|q(m-c$C&d^TJP4I@@3>zE9sIx){wN3*_ozxEoUr-i`+#{?woc4B-!Cec}G$|?Xv<=S_) z-(%XFWdbFIsZ}35!102;WttR9muy(@&ZrZ&WHx>>`3ZpXi6YAu-;cE@U~Mf1F{J8Y zKGSi&v$za*xV_`Lc3I(C1!&g8&!(NO8nG5-I_2@!FP+A)s>YQ4yqEKZ5u%>`#jm4; z90t&adFUeScJK$LOt%!h`aKGclGy}k+BHI*5jF8(iGt+J`1U;N0EqX_O(J4^m)BZ) zmO$or-%oim>)_N9{%9D!FSHsVg4c@2`UxY1h3qpOk{v40LSeg8 zqr}2OHZjYpqkFLyQ7p8V&xIMOqLTZ|(UDnLr5}9N#qpjjYovWEv?kA72E7 zRSu^A^j2H=xPa*yK{#0cb3kNaX#;Ls5~Po6s`{5M@E zo8I3imp>oAJp8#oT%h&Xn6Q*wgqQi}P@LL=nuw&JigRpmV%0}11yxDYKsL^_0j zB*y~G6q6z0fYaXWz0d%tsL{h?s(lt&>GUA*v-d9GP*EVkWG2C6rh=L%4%*_Uq;Y`MTl>u|iBC z01e>zVFmu?L*xViYB4a6VVXy=xXIhYM)h-HkwH4jI_w%g-nW zXzhv~0w%KZEc`j4z!H-aAq2O872yW8PBk1*Xp!G_s6GKQ(G@#87!iUXxQ=xH%B!)8 zn^Bu9pqJp_c}h8ofSsS}*OM4sP0U@OpgiDbMGDNU&znNx7?>1rVacc3Gm{&iJe_n`sW)RR@G(=!vFwsFFAVWh-C4bWE z-Jcms2m`>XzMB8{^HMMmG0;39a!Bq>AKd$^$@iZqtq=6ooR$v^zD^P7We2DQA|i;e zm0<6OV-nEuX@B~ScJu@E3Ro_4F=nx$w12RB`i6$GV!gNQ0e1$o% zI0YK|6lWBaM2rU{ z4Fw1@DMGzXqJj|Pyw}n&oeyTX~azkKHkmBUU;l*V_ zd4j_@wqqRMscVWXx3Zpn^*V#S()gu*tWFDbB5NgSg#~fqm-UxnQq^m{U6()E}LxU{KYToM`JdX(MY3d`` zq2TO`sFY$dv-Q}8bxt(()gR0?W3f?BF)B3}eyqn!8a{MesRH$^4~|@4dB@`0jv0>m||2`4Akp3^dU&yM3jF>`e9m3tiH{G2~7+Z&cp z@-pgs;2IB|y&Awdc zp456&(DElfKRZL+Wd(L#DBAV#Wc*M{>RSknRr1)Dw-^<4kF!T=bS3Z?DK zI3FtNCeh+vjJb)5qv_%7UdC(6J7&^3;WeEq@h;V3KTM}<*rPfJTBp^|Bs}De*ORhX zmxDiVrA(SRpLPShakam!LMu8}8)~A6jM8>?Xp)KRboKv;u?W)>^rM5FOq2id%H5*C zPKFQv=H)d(_dd%|gHfx^_WHm(cxx*zOb^w(6nx6Y~No`Em@@x{+{ zmZ*okIPa3NN&fR|HyfaylzrZct9E8cTL~e6$lo8CM(g6h)nb4*X3bYxGXo>dhh2tL za~|AV%EmbenJw6{PF{@>Jlb&9!2-h`ofeyG1~oa-6FM!0&A-gJA*)sGkMSGfpG>ud zNUue6mqBahykeW}#8}d+%IsGQPie7b+v4qdmk8c*|Npq#4L9zUlBQ%XPi( zG~_U5K?4M<(_a7?O?9kw3zMXHWFyb9YWbm`e*o+0W-uRGkcgdpq?lvznvGxfRH++g zyDCD4M7!;5JbUJLX|a>tbZ+Uyh0)% z4EYeh(|!pdL2ZSUmfC_@dF->?ms)Vws&{LiDQO5ZBw123Vs^Tp(wb0y>s zvpsV`nV=in1ait#rt|g2@B4CfcwYAz^Z?P*ya87H=MxqwrFNDx>3fQOFWecd;9m>B zsmrn^Gh@GQPb|FzuZcHmYZm zkhjzyW2Ek54)4sm*jwnvGsRE?Y!6ea>^VIChBN|Vl(j*=^6q(@MFvfS!Ihq0oAc9R z2oIWO16c2tPZ^c=5b*52{-}jCRwQBldgm%xbYaV$e9@}nhn(>lrHE|dIeQ^?`aC}Q znLA|-kd3Ab%^~#<%NR_u+qgJS#16CcH0yAkgmqq; zkF*Db)iTtjB^Vi2u{sS3prgM)ByAq4v2p@=b1Y=sa8J4{A#;HH+-M-PC&Q>C-|9rx zV>CaMRr-cQT1ZM}db^of`gSSSVl?S^u?g(T)JRB>Z@_-UWU`B|PEN|otL9Rlwl~P9 z-jU9Thr|V6mw%SHWWcglqx*g}HAdlYevScr#9o!TsugfwS4QO+dSu_(4eVYDt`EPg z>;3k)J*&HdZNAIEPv%#4gmt~}XKczj%S{E41=Lz1@MHRl`?A06dYoIGl9EkS!#ha) zANH+Fgyib#A7N8uWECq}-^TVK){F@UMo9e5c$Iz5k-liwbx=0A;jkV=^;#@%?nVIf z)X^hhc!S%=X%>=11_vrvmfx{X%LxrcYWqo=OXtg8L|?9^)g*>t^oob4`M4GF6_RfY zkJk)1c>A(^Wlh=gX=bldT_zkF9%B|54MnWZO%jC5kZU^cwB}r7dnnM~-{h7!5-zX; zmW9rC6|v4W2*Ob0h3>G-ym<@JhFpN{4RIvpMA%B#0k&|_xI%OYZMrk>?DtT~wUmp1f8kMtGR2-)S*?O66&;lhq`CZ%^9rl7GBTMmDMK}E$pluN+>j$z zKMlBOy<8rzTvvrc%B1%ve#AJQ*6m3#drs+kuD6C5cq~{%Z~*<3+i^)iQz}4B3-#Xp z4>djON52=WuDsfGvwM+M;0-nAJIh8`8HOg3?W_;O)7x~&dw1upSAM=Xg2F+0FQ4rfhmZ$t#!oAalVHMpJ&E0Tfi$lfa7umFZG0sWMi(!g) zF7lI}x(II=kD|982kV0EBr717K`lfF=jO83a#$mw(n|^A*fTzXv`vSwK}sCXhJNUa z9{Nl1y+P?!=oN9aojLs4JF7W;$K~6sb#;zd68sbK?QE@Bq9<8-W_=>-u_ie;j9pI` zT@x`J+D6XioVC)YOItwo%PbB^yso3Rz)t-F_OcIgTbZP}OFMnangdW?@U!l6!Q*Kk z=_XM$EckJ*KTRs!ok7N`@|!sxj()rOh+l9hamlEwwq#l0mF0LD6Y z|L8tJ1q7j~t#gw&_muejkCPdRZjvVYJiodOUIZ_cZ@1p269}OH;A%tiTx}mp>J4qa zyl0A?`>Yzz+qwn)tHb9vL#oaErK!%0@{VuKTf8J|U+;Zzy6*>j3BcHrwHZqvNLi)( zIf}G!JoWY_opA?`*%hF98-7U9gBbQGf~-HWp*mQv z)8oVUQIqGBxd-qiAm%Q% ztG36#D^Ob5E0!U+6kQmq+J@dA{;_v^NYK&@WLzdtwG^#eu;+5_|u!I8Y2pHKdx<<(?T z{*IMqTsvZu^WvzXDA7Sls^MKx3-Y&Y!@l)6Y5H;V=UymhI@rt>&zMd>wR5$2KA*|)Qd!qv# zoA1-x}5U6`a1SSxa zG~>Mat<~hod^^6jl68hE!e({uwprIi9s#C6IaYc|pb%ZY+(`3Y*i~lnCQD)Y{WQ6V zkrl9Xh?X$NW!MKgb{6A>;{~`lrB@@tT_`dZ+|)&~@w1&LszHjG`;nBNKs62eT~EX7 zP50UIi7dee50iS~^|Bi~rUSGWMoKA@EV;^o+4gqXLfAsmx^)YDU=<}jeOJL~?f|yf zwK$9KvyE*TX~Q?GKSPY?+BPVZCm{nw%)^^ff)st-oCuzeNl4awCnEhlmV2gfX)mMRG$iA!-rk56>eY$r2+dMISK3tksP1cwV+<;@}%V>mwEs?)pA z39?Q&?Jn``iVO=a98^ zspzL;X4ifMO>GY{>#c1Q+pc{lYA~o zUe9pOD54-K#t!!7*s$}P$fJ^OK18NKq!8@l2~tYzAJPw&uyvTu>{}z|$pF}`T%uJE zDrpZzn2<5dF4<|9nKo#_9k|8_H8^9AinG6bwV;SUD4n3Y`?=_eJZ*_bd?e4sMU7T`F0{Nb}#-Y8qmyA*k`UAM3)CF}Xe&z&ymbXh-!h>?&@ zA3NUe3-0?JG%G7z&-g1~TMXcz&}b(y8>w(K{*s4=uT&mfiMQ2EP&o8L?JULA(#|l| zDwz}s-bTS|C2yJr`ITxT^(c2w?ksguk;#W zX5S{yC;rKol9S>OyZFso{@SSam9E`fxN`128wS68;C08BE(yRGYY%^mXs>FoxxT6} z9Zjxr?mBF$E%R~+$h7#V2O)=YGklS zOON9zBRwDh5D&PGrlt- zYh|E8OO<${zM;+y89f=IbE*O|4mwFGDqFcwP+LD3lT^&3No~hNzb#=&DB>}4(5xti zYqkuf-YD^h&YP*GZZY6gS%^cqu;M6Sd!QF@oSvp@tOHQ?)|txSx2ct4>h6}alKMGL zPpnf_KdXuP*`R)y(J~%0vUC?=gF?%v{!4Sosfyq4ndqbUnsQ=Rl0{DnDAbEeH(t#yW!FogD8tU3cvxwL4JEup4SUG(e1Ph0#7c|wBgr$Gc!b)h zx9{dx02-SMu@5}uK=!iZyRbIVTJ_*(@Y)~>AY}(2d;{_R+euh>$L(?$`e*Tyq_yg1 zCz9dYG3-H`u>x0mg}u#eN6pmccub?5u-MP2-4eh@{cPR^efMOPOa-I&>C+zd(T}6g zlQ2rTF|%~1laj~xM`(6P(dyjJ#zAMuPgJ-;#j&Hv;m|leuhw4;(>>AJ=F!{}Lxt>=girt9T`!f@ngO4e`hMPsYX*WI{va$%0JK4ikNy_Fe=dq1e zfgh0YVh%Zq5my==8LHg`3Kmi{eRo1&m6Mfm3SjIMx5IRj8cECy%s!!4FF3gRESpv8 zYeKC`uw@G*G1P2Q1oMDis6F~wwmI-l6J4oA6FYI2K~eF;h9HkbmGZ(e$F?oI|J~4 z(}jqWE@YjNsI~{W&AbYQo`PZGOH}@-GG-EFF5rAoWT+hqHz7HtyIMh*cG51$WL5A_ zS16Qa)T?eZ5@Vc#q4>cC3u30LdeglKB!o5VYWG(o*e~MKk@dJvzo*-ijo8eCRy}|Q zPYuK3W>j6z)Wj6qh2)cPj0tLB7F?a_L-6~z<|5*EWTzd4^OBFs(A19g zgZgr`Jv$O*PPPg2pG@al7FEl(FYldAV^iSHIQdjpa zD`oZ(m4Vsa*6-bJvr6+a=KyHZhZc&?Ut2I3${L-;i#EnL=`2S}J5QyZqrOC3ebTCS zqOuxmh2ikfcG}`+UG?Q)A#~YikaOW$GiXSaYGE`aUKu;S)5{9XU5f6^*Zjj`jS7#j`=bn{AgnZblS|`MV|WC;{y5si(!ok+sSt zA8(?i;i10dxnA$r_s1iu9->Pq2h(Pq8>0kOzotiwlS)F8ox2~idFMcV>8lX%F|j}R zT(HC-Z@}FP8XGDwg&v_p${7q@*#2PS&TT%J z{j79$Z~XiW#jGs((iMV+Ky=!_7z&)c>=i2^v}K!K;ks7vuD;My8c^rzyn-(}%C-o# zCchB6c@R0)B|qrNuhLEGc*H39kO0WE@kG7qwP`jIWPV9JDOB)UnRK2AHO=4`AYnX1 zrk@yNm4b8sFIxM*$r{^#lQpPN;08hvj{iDETIPy@P5vGJ%Zh1{839hk1>yYP0Pf`g zxCa)5^S=RH%j6C45fljLe+HnmjJyJ~n}KltX8=mtzr(K2SS=j!`z6ZU1{+nG9*y*>1?ISKjb>?{wK` z>*!Aj__{1wbj7GQSUqMWB`Z#DPm2vL^d%>xCd3B7=Ft|DPK@@B!5HKjhZ2#YxiPc3 z)HSxCFu5=tfs|%u042-e0Y%FKkwZX;V=DXCb_JCr6}5%H`UCp^-0RExXT;=36jc?W z2u^JeZ%@syg7h97ACvDMUrL`Gj!V2KB-EEt^$zu;8kkuc!yu+=%qAzJKq`h$lz|M& zUCCy{*#f~-i?gQ=17XP+tMHhsNc*REq4XZ_!1~v9Wk($S7&sMwU;y!Os8FN<{L{JC zHb6|o)WC)gj{vGbfBPS)`+-DwQ2e6@1&-Y4r*(f!GO>Bqz7^bAfzp1o*+YMtqQ9-b zIL;66?4#gA6OasyEH6R+J_B;Pn-_LackQ-H57Ex4j)pH^Dvv-h-!dBPP zaQ7*o^SvFgPBUMpBP%-}VgywC0jac!xTq`Xwx8FwXaNdRms&YX+j^F#<t|S z)Z@0F+5YmoCtvGi=0f{t0zItGh3=*Vr&s+!mu-6R(&L2wC#axo zF@{Vqw)o9PzV+*>gwFb@DcLKwI`Yy27aaqfF7G1|W7O*RWk5EbIQGZjZ2i1Te#Y1D zs^F&)8slT#HcbX&tsv@($&jZ?v+QAkf@{nBk$vpfC!=fF(4=4Hf^D=)bclEj5We+{ zJnYx{kp-f;YkR-19gn<=cFE?VHvni&GmYdd^uHJ6{z8qC!sv5rVu}4*h2_RW$(?$G zp<~|5A#$II{T9)Yz#H8Fj3b8WD41|}z4sfR@Yy!}0y6m;*;K?_}&ghYSzcV_a97(F@K1ttb*VLE?pP^okLX`JX8i^50&1oiOoimx0eA=>T|f2&kV2?jK?9Mc1p+4 z_?@potmeQmWp7Bre~X(bk}LUQ1g|Y*k@*b-a_`nXf-5-~a`M7yKmp~V8oGQil_XM1 zEe3>RBPcAK!8LK@aoR!qr}ePIqm*~mo|IX)*<515Fzxahdou1X>6{H}QK!@f!wA^e z>(elfTBuaq(REk-243`7J_(P!%g4n9;9IWzA} z9(I3;M;8WKn?`NED*({?N|bgxoeotgF+{*u`lBTLC*>?Tri6%{AG6t$rl`F>@OszH zPxWu=`gWqF8m-!a1x_iHN1z?@S_vk+DEC6P_@(Q*;q3?Aj$e1shAzuNDH1(+kh z8hKQ<^J~-UB_hxW(YRCdpuRhcYiL=c?C-1=T^OsPOCluQ6LEu7!obFL8keS*z|`fi zr0gR-I`~RQ4FH(-c$uy?Qoo||gS>thGx+sP=(8%^ivVy5?{-1!M*ADbPOvN~l0E|$ zY(DB3aR$&5un$b(Vuf(PPiR&9y3fO9jxOPPzG5=sPGEP?t3!e+O}g>drC-P1JnpRx zrX#5wHk!?M7FvFD{BC3u>E6D@u@MjQ(t_+6PX4>{rvsqL?n0EOH^NEi&Oh6xuTz;Hn>fMt^hX5| zdzIjgAV~WX)I+p=aOFBntu=RnCnQ|b|-!>ZBxypE3O)v7wALo3WQ^Kk1QD|}jeO5Km8Xn7g zQ?aInf>&@M5A#hAquS0BMiW#-kj)jhmr6sZhfSB8C&=?R0YyGblXVNkzv14?f>TbL zEQkRAfY*Fj?l=SX&K|;Dga8Os%K+@Uot5I-qh*h&-DQ$q_irI3dx#}yG#2_DTOnxKI6KA5z6yv z16PShZ(~5_y>)mS^uDg(|5z?NL`*&uCZ6OY%yo_x52_yYab#Xzn$A-mV>mF@+H&gp z-JjP=5VqoT5wzQIF5Wl^8vX^%>q`Uv_8z|(_&o__LpHxAHej+v%Y?bq>$>P9OppMA zpB+W%A6YP{jvMij+iS2!_6jtdqfOkYRU2+|GnfQq+UhB#&{I5p``s-;n_q@Tb;ia$ z+fHcALV2(eTRtUoPkDrjXM=E5u8ZSV5(m17D^ZdDHu%Ur8-ZQjMPOpGFLvNAl$a(@ zq^$_)4)d>^8X8Gx4q+bN@ty~NX<-1Q3~WCgph8`y5xxGgV~mxz2!G!)pALOIie#S< zgs7#|inRoPu}IN*YQP9@=aCGeAKJpr&a+w}>O_G!6XBcZaHx*7svp!qss|4=T+`AF zB{aN13p$5B+8uDARi*_~FeX^%L&s>Oi$!;a6;D<9<5MdxOHkoTuH@=claK-`ceot5 z9oqf}H$ce0(%(uUS^?Xcmc(tNTacI2^f#jK=V5=|YlJUgWdjoAapM*7eFmoFC~z8t z0$jg9E-aZ3?E|2}Lz<@HPXzvc>tsPwPjrm)-dv$X<#f=b5gRnw8Xfp|uR?-_quHp< zV*>pg5KM9H{*}GuNKSb_-{n)z=pp z8jA+kICYo61vy8_C-eVCm zj-j*dur?^G+~+F1%MT9$*T}ih73jP79;Lhx%M||PNgY%pw6f9~+0nfUOpLyrllOPW zPR3E@T?dS;ABt2bFi=OtfBT3|Bg*I(uK4`u1!_VdJ2*$)=yr03eMMoA(NY0IUB5k3 zVJHDfhI9Cb>Bb){iibl~;jwREu#&mRvN7* zxpo{()VYX5614kSf1|$4D)5G6c0+&BjK#3B&ong>bJR9tt1c~#^hvYBej@Jw?Cb64 zx8KByc_G0(G_02#Y+Ze+*)GGQwSuid9`BH04D>G3d5Mm$?ZC}*7KWFIO$rl*IMC=@ z-yU@H?}-O!q(%$#OtJikXq;RgF*2q-@biJ$W z0p+OA)k|hK9iYMsF^dyS2#TWAM}>yJmxtg%S*yHS7c~APx#}7E9y~3fh7@@xbRVc- zFE@4cf3yhVYjEv!iV6=hTrow?wZl1!b8AnRO^$QoAW*lfB`HU;OT%#ku{wgv{&dXepW!sY!n}&Z}c2UL>OcdJyF`aZ27+ zny+Xeg|aE>HPp^!G19Q6B*h_{M&ZT|Sbv8CdR3{TBRhclZn{gkKEM1m-D>K9afT|h zf2E$G_$>uNuX@j(xM1!^tj;SRO7w!DX`a=2E8aT>6^rd#U6ir<{BQ5R-`R%wdba`c z_2W1U)KpdWYuQ}_9~|TDRtoeq5AEJ8WKeeGaGGYKa6dJ66U?+Iy*Xoi^}dLCRj4^M zPYuYe3%VteGt{PFoJ|g`hhL-4#q#P#yMDyAH?*Nhoh8MjBuS{ zuZ}Q4#AIy5*`FsFH=%3?yHYR~e`LU1WAf*wkaPaf0XA(ZGAcCvy!zzlU2O!@SqF%H zbSe1IT*|U35?orQH5O;#DE;PKh|AHsf>_MR^U?8Bhrv_4G!Z6bO52Nzd#t)toxk3z zjHFN;e+kIF|^09StT@F5A59R$PZgc zzx!dl_Xc7|l|~v>BOD2?K`_lkmi#8Y{2O03znRaL0QU0gh*D1SZ%6hSpzz6EmtMld z`4*%&(2?+_tc`|BflY{Sx=r-lkR@KQrvM56EQ0DVqLw=_c!RsTI$14POW573*R@q z9nYv`9B(!nX6~z|e+SC)h++I%@x*?5&Uq7P! z2Yqz7>}Mdej(w#|o?-b7nAhTJky5C{s{x&U!~?zQ%A#Ckh?{n&1~CJ)Cn+@j6uR&y z)1iYpAgu@m)*l!@-=w?pwWIq*gAS9{GE~hI0ev3+oyA}re?rTb{_LGwRzF>}tRlR2 zxcr-DnM4~0YXm}R^}v%Ac&jcBMq$d99?^AwND5iXcA3}1nezo-3Y?S87OXdSjG`&2 z5a_!kyQ*F-+Etni0Z0uM<5pM{+%0zdb-_GuHGTJjU$_^+9*$ppU?aB_c_tZe{N-8q-V(gL<>8fYm^Zi} z7v3Kedn6k>TaG&AYsqx3tww`Y?Ydy=G_VMIAG+=f8cqz|p6AbwC|7g3F_!f*?H*G%`69Aha0Lp_+MgLFj&I#VJqXI5cv{oDVqADj2(hfnDiB)bWtg7%WWObBZ=P<(BKW z2K~@QAAnP=G`(RN`GaM4$Xd`N<6sV@;D zlg{2KwKLjPeMuas1-mc)@rxWX!IoA>-*@hXf1X5mC>keAPawP_kLMvO1fNk}+>|M6 z?ehJjGa~*&a>?m3U>ac*4NSoDO(G`eHQbgxWf}+~bF@L_QZxr`yznt4$C=07g(aG6 z%r1vB{v$3Nts5ZN#{Gf>iwnyAPJVcLkoAMG@>a+RDxq7H1ZFVV>N~rs6`{L*7L$uP ze<>4WGt`fHS?Sg;3@hcS=4BU(cRv_eDBud|3#x>L?F8l6?l~MTgZaVPc*jBK z-ETv+rHFAydgFRa%=?0IN-fDBv{S&In}r>3NV_VapZs`{a6mKpR$+6MP+ATRA#)Jz z!A1@!QlejQLuoAiz1+3IfvjPxG4@fLe@b}bf$a2x)e5un?y;D{NcRvlSS#*CvXg$p zJdwNEif9Zum$Wr(MY!F)b8{VGkMC6MMDKWRvU{NG9{rrN;p^Y$%#MaS;F+VCyTl2@ zAg~=Hi#Pn_Cpe&6JvxDVNz^+4+095T6}xn(s33_yNxMMhVBaJX=9f+4Ej z|HCReDFk6p6RCa|47m$oi`?a->k?(XSr3T=4q{qBp14`HK~|2IY80kb6%<}AO@Dvj zX>8&Zu^@mQFau!bU)(X)=;_7>f0|{4RM87t-YEbAyBzxwBY*ivZEe0_bS}66G}R`1 zqfLcPVqbXMFUDC|#*Ww38kkNBOG@@ef^uota7STtQb{ph1@N8;W|@`bzPbVJ`w299 ze_mtBzfZKs+=@+b`b)s`oMy4^ii;>Z)o+%u0?}3D44Y#M7B6Ik6mRTWf02nT>uz$p zIXvjh6r9xhygGGj6P_7jBmlLJ+?cp44UHvnJMus(>qzS5GD)G<4urQAdS-5Yt6E=y zv(;-YTx}p#uzG&gPDhILzB5~sLF>F+kzl)}}JP3c8; zpF7T+nRfs3r=)CzOLGhqfA{ie+J|o@&5~_SI16t3ob`5A_@3&vq_M=x^9CkBQW_A? zetNA%Ht*<~VLblF6U8r3y-NE+Ew-Bi`Rc?^KNVY#i)g=2ZYK{(Rev44yM$v8%|34! z4qC9g-h)EI@k9dek6-;~b=vR`VHjrhM!X`po^)n3G-C_!-t<@Me`tQ3Hv0w_n5sx6 zj{7citm>U<3jOXsnixLTCXMdn-t!u^4E)Qm$4Vt`UZ*m=SUdJx)XT_w%AUkH?+;2` z;pECw>q2)*x0eV@l*7ENb3rp`aGYytI~6ijS@wHxH-4eA%I*4RS)aOL@paP|pYO>A z9xrdCT`^U2Ir(ise>V}tFi1ve?ZKO-#Vk*CNEl1C1w2jly$s3DnQ?6euv#2xQtO|N zk}%sE5z=ZhP+o!Mr&W96+wK^b!^l@6QdT5bIzHlbRXUx=6k1x~85(K5>tWs|&N1X{ zfy?@yX1{gv(n_UVdSROoTJ-zSb**pNL#4oGzLwSp_3yT^f6svbpTXfQdco2>4N8F= z69m}|4&cypwH0G*K3=YHmMhzzc3u?%2iArxngt6p0z&;AnuW$i@W2d-c1LyS@e7rZ z(oRwhx7!<)$q8)*lVe7u=utj1M;_%iJa8jTgQV^2B3=|SYiyU~_XDxe(E$J7*fQD; zynrro!Lmfwf5a_i!CYM|a-Wh-;lW z!d)+CU0f-Hh4~Cjp7mgxY=FP-iO2NRYciN$(MW2y(-Lsd&xq3E#8drjI1$iOUCO|p zro%vXI72qf!SGOjB4GVa((S8v*Dof5Uq?lHO=o8mB|P2oAu$A!DP% z%YDz3AB|ChF;8>Z?Wt;VLK`YCbS*U)#~CCYYFVt=4`EOM_>qoOtULAa;^bB~V@?BY zA}x@sIE~YsZQ}vEMTv%Sw->qy29a19d}1VBt6phVC;IVTCewBFau6W&^4z=(-v8sL z9-n)ESncSIRt^nJCAT}f)nlw^-ADMcL$P%=QvBAMUEZ&b;J|4rw;GOa8c=P>1d8Q zyD%pfuHpbFu7#lJ7)Vi(Jo^WWSS>`KpDsFWe<4mNGaMV!UY(VvuEYG6iYQJ*}(_|;Jd}S6Vxd8%*IjLrfKaLtS1n5MN zZcj@zA3^Pz5VDRn&R0JMq)ivIBJ4e(TM!p9b>uwn3wieA9hX&Ic3Pmf9KpbOM#G{O zf0?_uK|~GVaCqlg*4J^xz%{K$jxT_ajinL6x99MQ4W5Ba!3|3h1OBOK*S!_!S&xME z6`4vO!Do5jEPNbZMY=#eiOKctyEe-&$f(=NpNFaxE&T|OV@hF?ccs9)&^fq=C_c5XvI2qXkGe|~{) zo=UWUsu0nT*a4BPWmArmEK<0IN{9CP;&pKSS6J|5YE`4E+6(ataR^HbkG)9tssdRG z`T8#X!&V$BRr2^7GOm?EZCR7!=ioB89-msMzk?}L4>CjKU|+zB5kBcO-Cjw1ZJ1_Je~zOo4JnQC?U71n={nz3so*qoveh+K@yP7Roa59G z@NXqCOV`j4tDGX2C6GM0M%vVo@W=u-s~Zdr`Y-5876(><6l+r;lq$)?FMvn zowoawQp%;FV_&^^3*A1YhVPy|fyejO$M<7)Fqfqu0tsp1IN$DYyWc#?~Q1? z;Alvo_9`E;2RG(M*x>?ue=C^#+h-xc!%Ljv8UtR!Sk4G~;<}^=ssRgeo2$7feuPGq zMz@#@T6bT`ry`64Wk@~{sITM?32y-_w5M}Y3tjQrLGCTS2FU!oe)~aS_Q_)PTuld` z$4Tv%?<2!*7`~T&%e1V5QHWJLSFygdZHXaoKgUhu(t+{#i(hzAe{JQs!p+e;?)^iR zraw+~HooSB`~Mlobc(_&9ClozYuZ$G(X>zSX-19L!cI;5cOX7uTA<{#Wz|i@9}Zb* z`v=JHHC$0*Dvi|h%XT(-))%U5a(Bi>53$tCq_KUZMOYx4Fcc+^oRw9$CZFg>Tk-e|r19DVoQEuJ{hdI~vEa z3jzho^Yctf>XNkj-239-l8G22_*nOeLiph0d(J-|KuxI$+XC9mIUk({5qT>C^My|W z{^C@XHWtsjrzD`p%?>e+y^s+gNOHX|h&BojYT^A420TwMtIqP0@BX`e-!LbHB_; zCF4VBTaxzS2fYr!@`~pie}2Q|h0N~5OhUQsXl1;xe=f%U@0%hRx=#I{cN(g5IH!3R zWcpr=VN^-~@7sDFfC1{uM1$@UnlXKmmEvNC8NDj^^^CT4p{)i*X=+~>`L&dsvs8lD zZsC2*`uv}1ic%6mg0_=nPJ~I#-UTEHe-#9;5KsYRxdvUy@^l+-S0dILuN65sZCQip z(y9yIe}GRF{sdKxx|(biB#xG8mzp3oQ?L-y?KyksUNZ=u6Yz18X&4HRJ_^D<5(k}J zYWm%JM`b3hOUbmG#p$@igrL4)FAPmi`hHjzK0Fq&&~JE(f|ba{buj}%*Usx?wNuhh zg9*LwM?@@qYDkTXyG0vN%RswVZ^Wd-_$#O{e{qvF8md(c0p0mOW`EWG2n(CRXF z9zQ?)YD7iyG#2?@W*HcecYH4X=tam-IkrbP*_yY z-S)dW5B&$v)VWME{=+hVkrIcsA9X0Le@#nc)*W{p@a%epoM0#z&EL?mwk_JaaYDRa zmk*d6q>HG6_N0UMC#Ct@&}_Gte=D}58e|j94Y`GHDod40`+j1wi{_WJFR<>fk6bj5u_X#eDxOGprsnLzZMS&8ke#LzjoIMCkWlILKnPA zlhiF^cM*L~!6@Zu%X(6?EQrR=f2G)f^IqHxT85R?=Uk=rqqTc&m%WVSABe>?{iFdO zoRUYfNo=`CCMBPZo$N=2IDH1M|37=Rx6asVr1h^Y&6ug2=2qc_uOwNe|W6eVD%b*W+* zoJ7`LkvK+LB@`Ubl5=J^p|PxoQ+s6u>z$;pkNd_OQ=P_3v7y#T4TEY%HbA=|>2A5| z)pXrzkT*!K0FwgSVZri+D7#HWG!_A0pyu!O_>}JH z-pkSUUhtUZ$uVwuqiTT9H!Kd#N#D3*Rf35z>+BNKyhq8dm7EHO^QP*)>Q|y4AJT2D zF?4X1xg~_yE);f4)}`=vwZ)0c3z& z;?{5&&eARZh<~P(p-tt&$T1Bp%%e|NIO27YYEO`}A;NsYSd3QDF$;*tpX3w@nFWL4 z=sQ#G#5^^Tz;2=`cNOTSeoFx>Fv%_J=ETq0m^JOn-4EQZ#{?Ta==+mp3D+DCc13QJ z1?(s*gz(FF=5gZ^e;7m`Q9*~+%}L%#YhR?l?BOU+5~s|Z;{()$mFIHc8Q_nGE}kf_ z6-2TK1&ZHL+|^s{@vbV2T^3Od*wRH)aAifCoj8~|O=QEcc z_xuNZ&$$~aXipMg23qy|&l1;$zw}k|ujL$bIgbbT0cPBV@Y|riI{XLSIZOEoc;@6N z39lJ=az{1D0dOi9F3-;~|i~J<4AKbhNpb!#U-fAY9`6PttEEo}j zWeyOUe_-689?tpHK6enqZt6dN*^%IJ{(mlZ`K#3Gs%(l6r+cI`h4&G*bI}ND2$dWh zH2KJ+t6I_RF1{;GnnoJc$F{((AOjAZD}%Z4dEu;5T|*vlX{#(C&c ze+id2g7AQwenph&ovT*BZ;1a5PPvcQR1u@OGl4ecXen*R*}&6F7zzCXgTkEqDMTut z;z2!OtX7z)g>2k@X*J%?OiuUB#o@R6zv5Obp- zC!PSIHT;==s`G!KDu7;#hsnTV$9+(J#uS88QMW5s&9gQ{CG#Ide}_bPL{EpeGdKv4HyJ)SV)>C@+Hd&xC@CK0?)o;U9K zZG6_s!abD6$i7$^o$7)I!QPoe?z&tmS_dk?nA=A7^Gsima&ZChF4jOJV^c7YLy!1MzeGM^j@=1RO)mp09FnBM8Erk|kpoYF% z$+Ar&EYCa84I#s<67p(HrnoI^0$2rX=hyHj$(1pjd@+bMiFBbfE)EdLaBr<&dh96$ z4@t(g{)Q1!dicX9B#H4tfsJH13@B8$^EuI3Lw;fzQbgyN{j%%tZFoLMe+mNGj6mh$ z=>x>?a4=ph-UR1QnLzxEd3h{2??I4yAXZ-a)0@5JpQEM+-#bVK*=7qc(9L5jhf<+G z+q}WvYR8j;udDo_u}Sv3`)Wk zu23yObcT%ll)ySmsPN{se-)zv6Qnb5SYJhbtNHPq`CisRn0|n)Q`;t=kU+Bn2#gf+y)DCAVm4v3D?z z_yce}&CP{=Z4bcvf=R?)jF2Th1%1`z;S6CkTPOjEp zG#O`Xq?+ga`EBbJr{W@Jk>U|i+zl3>gvj^cYmGMfWU`UlaCe0;j`%poOy5alTi7Re0-FzYDq&SBYkr`b7oO$xJu&~m z1HIn`)#3t7NJ|}AO%jOo5ZPV3ZqMGNT#k!G#|SAdhH7&j zPz5O3e`IwwYd0a83^{(l|l|}SO&Bvw~(JrqYia`j8gu$5Oy_2cxyLo$(k=Ju)m<7@X z2%rpCG1;hhqp$^I={t;+Y8y5s*Xmy15m8F@f4eCKG7xL4h+it|JHMKfuoz~g^)*Ln z{h|q4IK?Q1D0bQ8=`2@@Z{;w4jaszfWaIHbq2zv;HguSRxcy##@QmiI-uRKgrR4J+ z@IqsWS9Z2YrXQU!N~-lwPceNuuRw(7;Z@XZ;EDQU3v9^8nGyF~`l0l!(E@68E&vMU ze>q_M#KAo5?5SqCdUVBBj3nbp(cYF~w>ki0b~APk(f)RDw{P|0xv7^aSZPDh{9z82 zkIyrf^8y}rxuI**-{XBJxe9+Je-nYhEm+W#nvP4E{at|sKE@#P$#W2+bFly7 zlzva^K*nBVHKNXpU~_8Yoc@Yi3YJH)++2sUYMI~4~BgN0I=c63kAg2_SGpxPaqcc;cOjIrk!{&CEft*i~e{Iqc zo4a#;bvlicReB~8OEKcK{W|rG^-+j#gz>6z!V=Ype+=3w9k_n|0mo*q?c2`w71n@3 z!E`}$m`x163`q!i(>Y-Id!F=@+e>-se~&kHmBUQX8XYt#aVLMXSn-sV`+(p!##0W7 zF`d&jhxiS!Vx`zW1Y=-RafLVpf8e_ok=wPxLs9R9`|0|=APq7nUXDP%0IybO0XDhA z-OVIA7>3_r4!c!?8AAXe#;4rX#@I6um6h*gMSX5X+nh)YsekG_t#?W@*+OdDF1o>G zCcs;ekw1CRic{X&dL+xIABo3A3oK6SQOcm9_GDE#kjq3RoKS-lcy(pce;1P&V`l}R z?w=qb!!M;B+A-PS*67Rr7%2ja8t+O?=6Jc1!5(ae?gqH{xx76H)rHhZGIzVsZt)9yxfFii*oXfU~ z`@7Pvy#9q|%3$vn-+n(U{P#|ja4BOT`m0`?c9O@{W%!wYegTh-e{6~>AIzQtq_yQN zy@b+;^VR6G7RxVA+W$L6Tr?RRBQG<#qEPaXRPcB$NP5wM6q`|UaTzwPUydy|P%6V)k}c=PvGJwrXL1sVUSqOk zt?@2~g&{aFf7@S>1!gywvBGvvMGi#DNPWML_EjU@M2x)!ul_daVQUN=Vh$#duyKJB zQHW%V_vO5>3_{ybOr+$M7vQJ;j!si94(;Xt)oXMgD!)e{82pNcoQ`ERRT4YY9_t4y zKXHjd+)5J|N1We!Sj28a=kz%dHEeYo4umeju3Dq5f4uUU{{oLyGMr<)1^UI~zTdoR zKX|v)#01or#Har5X-&(RyYb#&EUInfnTF+J2YmPO$9Li*|Mg8cNzQQeS9$2jL6`yA zOe+pp+D=tKvY{FIS+fq=6FsnfDlV@UdS}L!rp>7TL){m5YoBKQH5J}pzVUEHf5^w+ z{58#!f4%e~)3;}A^9`26HZ@g(m#A1g&1zX0@en&{b5^>{!Iu4tBE#skF4QcY{aOx? zmK>xDy1$&@in~vaUD)@Ub?tsZOQNt4c?lBd^waoId%%N{R>C|MGrv~RAz6sUO9bb) z=$#rkWDyuJa-OdYV$F-nOJ(mN5}mnS6XK91e?utp>_V`hA@>Mjz2q^b6#bU?!7sH3 z4mK!dUDL2a5~8j$EGQm*^}$5J5+(Z!$ke6t)F$UVXnn)N<$ORlMLh7S{|Xg1h<)lKjwghoCeQ1*a*RRuULbn}oAE@vMhL~_{X7=|%vqr! zy5o80KTbJ<`83TP24gajWfXGidzXIlbM#Wbl;EBulq?VaCKFcbvGMKLbJ96d-q|p! zriW=>I)@7?>HnVQI>$(|Tnl_d zB4+0Gk!-lN2LeqTNhWe-gHohe+96l172EjVeS6F37hbRk4b`FKl^$zhS2pB_Gp4H? zPzV3|1YboSuY#hPC;C#7e|jK+<|8$`z_~*uru>bjJylZX4`wj94kK^|BDD0~ z>z8b&hlWwcpe}W}kT}Q7ig>zaw896tl@fN_jJ&EH!o0-+7PgI9v>q*Lpz4qtsX(FZ zJ|NCZNB}Pq`w|J9o}RF;p0C;XG;mE{Ece|Bvga!5KVT0G0o)q-uI;0le~09M$|z#M z@j^u!`r{3WUrI6%J#nBLLiYQPg3N2kocl?Yji3`fTvLzyZCd555*YN>gTS^1Z+r=$ z*tf@|k8F9e2fjP)gplwZXd%#v{)Ybr9j|rTP1(>QnI@sUMzKLz3+9D@P5!zGHFSBt zkYExfyf4(}!{5)l< zTQf@k(t~T`(i8|$nvG!EJ@KP1c@W|$`GqjjhYRkveCM@xf1@+_7b#k$?vKMKX~*5H zf&5-VHDmgE2VwJ*Rs%MiI5<>(vFl*}{7Yn9Ong>n@#&})@=Yf6WzMK61-8t6 zS^byE6KEHxf1=u-ha3J9mxL_Mg%glZrwmQ-8XG%sH~P1htY!Ys{?J;t&OFsoIV6xy zZl(Q1v)LDfB3C*BupGz z_cOhD>bf7$c4=UDzM-WDe(y?iW5F~g!OKlGbE`QC)S*dB?!Z{=An~W)@Ge_|J&quz z-i#lC&x{oFj5y)J8gyzOvq7Db^wn_65hmh2`esa8f0>3XyfYo-f8HPey8R6pK2wM( zdB;jxe{_DWm_`YVMW2$Oi}a%rbFtayaod!V2Sti98^*?v_ZCOd`QyD*q+Ln6q?Z>u zl<`?;iEUl<(M>cUYJ{hXi|Oy9;T=a^*TFasO?75>X4h842b+MatZ+S-Lh_`FtQbYi zi}?Ls3ip;<$55LE^}HX+R4Sx`avq@+(Xajv))hTZGK0l}lUj#j18E^5)>txYCk-)o zfBn3!F7FAl^E9?uJ;N+$S~drv9SN(OK2Q&@j@N2F6&(`Muhh3|rF(Xx>qiAg1n-vS zUnMy8JAbPNC2h}~R=}XP&HOjj0F+M~M$atQ+fx)$Ygm^G1B%{5nmq#)j{SeRooe8w zmFpDv^=tGDy6KZSsj*6&%E-0mb5s4OUR5 zwp2C{Eq1l6gcbH?BTP}dBh9&dewTe@E4#!)-wmKT6VoJ(pL>{Y1$@a-dE5_2GG|p5 za$J`Rn(%olKo5GUuf(^)`2d1%}vMIe;)dR zS{CqQoQhfm>K$KeW;{vZdm*?{TP-Er_+{@w#8I86cUDAmW$knxg*t<1(62NKtoX-N z9xSAo_Ew@vp}vd`ZHQ?&8=r%gi|UD3q(&BMVUWJrPrz(@&KS57Z?uV`0PvC z5l6@ve|Z~1_Qn7}(xunZf4K^U0YrVRt_J4oIK++|EV3?Fpj-3@q3zn#j&nfzFQH5e zE;@<;J#dYmfW0VW4QPf0D(7cP0I$$YhOX zd_6yLA)(h?{hksvP7u%na4iQ&S#Rf~SqfH{`=f;Bvq_a3#RHMQnE>I6d{x`SxR79O zIemc;^R5YuHY|GopgQ^OBb;6ykRqw#xhys+bYu48q(|&GY(DKcDzBVzv30e}=xQoI z&Wr&W{npyNC>sz1f4An2xx|SLdI2yC_?kRQ%{kUVQzg7r;syzHXqrxPpt(1?M;pq?+bBk+KQn#?jAFjs9hIe`ITb;yKh!%C|4eY-=$P zy-oX!eXq;_tHdO+cE>n}*~PSGTn)9S5-M#_o0M4y#wjt} zL9ROY)(YYynlc-k$xjF3@{q5Tudg z^kvDhC+|AkmMU9|G~kw(1p07F1l5jbaV1taV9lc4Uz{lgrIyckE7P;?l?DNYQ6{ip z>`0$mS@F3A;5&k&bUNV`&I5ki78M3&W|aq|=QVMuq%WeQ@F7X?kuL_l!OEvv)xUP2 zAm!I$e?#p3dOh7eYGS@+H@a2IgPuGmv;CCy4l0`=PxulGuuVy*LzSkc)&ehOnCBLy z#zv^hwQu9pzhU0N?{M8OE^}U7>rIk*OL;v2yORL<`VKi@?~&7QS);gB6*xu`fa{oT z?a3Yg+J7?}T$IQzj1IG7N~j^M9o~etoG3f)e^DJUZeOr_0^Rq*C!kXdmUf^p3E9_< zHO=gmkTZRtq>OFrqGX|YMZ!V2U#Q<3ACQv&$HY;vOgTPBKLn>Tl&=5W4qMdZ3aA7V zG)hZ)FMOvvQ!E<_vpVdMXE`G-%NQ-kZe?-tFcBz~%9J5o-Wk;M8pdGL-xWB7l38O! ze_%F46+@>mc=W=$rv>o3X$tUAhKOTr#-J#Aj>{H@IX5Z)$cKWWk$i_Hplp(sl>yQh z5t1_J{EYpJE4fY5$>x8Oh^yhY#U;N+Tz&I&aHty8(kMKiWgHy;6jcV}_TcDZ2p%4a zyZKZ_Vqr3UcXGoj+Tl%-=3K`~rh}Q#f33nh-A?Y#J&C%XwqrItnDq*-e>s}f zJQOj4#X09!*{{_@LT=yCObZ(btjs-bH5M+E6tFvdT-xxCyn$t_wM`T0_i0<7$+dPX z1cwtTb|oG?&0GRN7r*B-I>HSay&Acl;DdcKKCZwtdMMZD5R_MWDr0x1#Or~=>jU#Y z?u_Kf+^XrVIGOJ+9e>R#2H+B=fAwA5nKa%F1J|4u`k+<$gfwqRjsUy@6V123d%3KAI>%{A?p5Q%f%4Eye4ezLF5WjYG`3kSf3fUZAp2>Miugpy zCsMC_@Iy0d8%;;5^3znuWA@VjLz7=T==dJuPtxVV zV{(?eNaKC!T+)v&1_heIH`ysT55{KSwU_tja_3LQq~NoPf7~n!U+op(ztQMWzhc24 z4nG7((k1rRMQk>FnDBaKBS%Ga$2u`k3OJ1ayH>uI?l=AIrF-wV6YyO!j=9HRLPK`5 z5Ne$DM4HBP*y^LT?Pj%^MVGiyTCbzpTN1{p@VXDhX4aeT9?#LDARghI5ElAesqmNI=Vd*SG--@tGa%G#n{fqbeTSG}jq#{P%x z&S6&Vf9Vqs#kadgcP~d65yu-K=}4F8myV0NDYHKGC5NDmro$Yu6sOv;(*augYTV?I?a8( zo667*6jEWdE>b9}><3NWT71fAG%qJxvw!+awygtnHm1-E>4H>7V)M0#n9iuOOchN} zzt#vkFIIt9T4Xlt)>{dO*rA%zB0PrN2Gia7L+FK!Lo?|CPK$*g^T0b9M zEUOwG;(up+Q%~7AftPy0M9fUNP}&~3d8MQfND|*z9N3PshbvCV;=(SPHxmjPDky5% zj2#I94opR|wM86?J$&voaj)No8#%fWr&{J70k(oTk6ON;RuZsG?d}YA;)9HZi&yj| zPOU9#A1bsXmdLt+6!7~=7EDam-<&IGs$iMA?tha+{5+I$jKl(iklU4HYki#ENED2+ z3fA-i7>_r1piJak5A?ld<%R0LV%~kXG7zC7{d)RhuylY`tS=lgL8(;~^ar^Ge)zLl zeF`?d3{iixk6EUrE0JTzBKklu0?PCO)FAa6V?@crvaYaXnx1!O@A%NNfiTBqHvp_ILz{MQg8I>HY^@AAN zh)o>MgHkDK4 zgzr0!Z1?@~lD=U6d@sAsjBV7wg!q-@4J67D2fokSSF=Yiun@x^I8q>@u>(4c{&D!z zu*n0zLeG1f_VW$i)svUb$0i7~i+`04W^yQ0wWnjpx6RWpkp=xHs%cN{STsRZ;zYbU z*Uy4AZ>F}U+WOiSyqMGRn|Kw7v2_=^9b;N5e_8}&1V4VYQXaDJ5d0R9wtuU(&~14|B-4-_KLy#9x<1{rXY>0=`yV=&8$wpMdlig; zyq8s_o@VitHO(=E)k7^V~Pw5B4NTGjW{#Iv-IU6hfA6v-FfZhv3Wca82|XL4BB z;1h8-iHuwlTV6N-TID{yez(9=IWJ%;JOJ(SFlRWyo#v2u#yq%gG6Ba{${0(v6(H;< z5jU<5p~&N-j+l!n+y?nl*%F7%qRapGhb~LA3 zILz)YcNAtCI}BvY7lVgI?Dk#&^|@8*h~WRmd6vn8Ne)T8r5l)ZI}T?dzx}?zrujzA zR>v6rUmavfGx-@gt=+SuEgc8vp;Xol51tAed$nHb``%8~`+v$52|e(7@(117g(gIv z;3F+pSHk-)x4L=!98ann)l|gQiCJKg4OZ;Cv`^+pgU@mmD^Ju8HOZ!7EY+^AN1`^U zwVkdOBJV~XX7dYsn@=aRqL5%s?n+6z@qh8Sodi|{y@Vy}gEAQawB_lluf%e$4^U8pO4a$>K8ERIHQ9guT2#3ZujaQ z;$W}G!Febjwk*`aK*mT^0FT|50kc@nAMSC{iqub;Pk(UwT@nUO0D|4OArIjk!uwYM zXTG8F@;eH_&|FhLnTHashoBmo%{IoHa*%ZeyM8yn1N$l1Q&;w%>HF zC5kPNq>#1mlg0;fq!6lb@JcscwrRbb%qvWSTUTuC|6D2H8{J$V^y5qa#I5Lmi>T|Q zqBVbuwHhA{x7E`&;76x>pYP`LV)4=*!g^m}M1K{>lVz7Ln^yoHXgfMq|KVgSa2t&G zEnTV`Uj`h3-DO@9+3N@yj9Pk<0L&qiRq+3l=tub#%6(d0<;7W#_JmTgXGP@h;auZ_ zY}P{f_}__)#4~!7ilCBb_53@rdWpBr**hhc&fYTD~@CnZN^nI@Pl$1hCr!M z#eeV&7Tuy!L#%HI!yIBx?t0}NgtcJenFo3e*ff$~b-9dPFBk$g!WOvGrM*X z;Z548lOn2)ai5y*&~_48fIb=Kg<7F$RtA9G(0p2mv{c2Uv7YRcHG3RR zLOObk>pVi;=4eGb8G=zhmW~0(I;}w?(tmy$4YBmy%UW{7(E7U4C*g5HDbv;}Ilq4o z*S)wU775d(fHOAq5PqK*UYUXFSOSTL*7Il5HvvW>;+8R#fTCY@pEkWk@)HSIY-PpF=DgJyXn9|ooInciGZq;k$>~3 z_GHsSMzcT!cJr>*OMrgJ#6(@tCCrBZZksMjP+iy6qJPq_DM2t)Oc#Ein_JcxT%ze&{VrBv zkDUAqPl)4e@hpXq&6o=n48c;b=~655~sH<-iTjJvM6ZM>GKM0x?3HB)76>XYhq`J<#f5jljSg4 zOz!chL30y6ArSnGxS!kH!W|U}!w6eXK4Ks91@y`{V(Nhky4q@-RDTJ;=EhbW!V*cb zIozr#mXpq4)nT|GlJ5>aa5XvfSHAsMUgpvYg*H3%={kV6@X-7cDroZiLsR+O2@}+& z@ZAi-D|}$N*V*V8F+#3=dY$YB>*3NX68DCTL&LFxhg6?G$blTBNA0}t_=Vs?93TvO zsBFghNMqo6nWgex{(sqQo%KQ3@=km$=pjJZ^YXvRm)3sq8j!z}rX!xbc&0|~StR`N zID9N}nJSyj5Q~zx`r!j8I}Ktr2}bJDf7l5ve~F^PfA1{Z={0$>(Y3zHg<;ZbllOuf zbD-%Ef75B?08R6e8-=#!_8*S}&;+od%m-S?^GQHQdgVD^(|^GOyOHGPJK#_$a+qe^ zExQ(QWqO%X1n$cmvM9hO+(ZR#kZr$_f{Sd9yL?AuC3DnQ4KNywoxbU0Uf7nz#)l_v zn?`B$5ALFaO#t@aO7>NNvj?If;twlyeIs@d>2^x}Hz}aPNQeZIQXaj&n+$`s`<|tQ zY!ZVKIuTc(8-G;+i`*QQb%j}5MGpPMkI5A9j;oukZr|!_f=NV?*4}Z2L5=|*7ue~O zpo{;&cvuX@Eqj5TL8nx=E)=?EXKV+_E)LWUg+EylObh>~tTCM1EYT8BUK(#SC6Rz= ziPIoBU|H+8<@X6XGs}+3z=T2fHa+?>MtzClTuW$5eSg!>>B6KR_;uB43FY<$<0^5f z1w6=)f&`9y0I_# zh+L54MAcr^9L|h2)aH#shk8eOt`Hr}!zA{X+CVMMS>sy#L66}dQ)}~M(H?%EBrPwi zMW~^J7JqSQNyUVU@4yAnfdj8mUC|H+3?c_%#3-|e=t9ATxEHljnH2&aX9efa zL6veWn7W!#hxiILHFxBQ{%<#kqnILzC~MI9Og*{osT2lbs#dFbXY9)+p56TgD&8&S ztRp?vPu9*d>Mgt^VL?t6Gzh2we0@6oCvs`N*nfsO5nT1L0P8JTscSHOlt(VqLV-1u zRK1_LNs=%JXA8F^`7?;^=yT%*u3@K~j5F8y+4d!im6kS1{qKhZ-OP6Z9efi}@VD}n z(foD!f z2io3VzaEXrwUEME_u4ql_BhU%baE3E<8V1l* zM5vXr1|1q@1$ydgPtAzn6a`6T=u_G4j(@!Evak+eG4OW2t0i5Eh~bN-g9A9Z$OTt& zPa%b-_rumWix%Zk^c>l&3T#_S$(yD3dm?>iJnqkYs@>=sM`Ta#K`R7X_K6N!EIh!> zvWM=6;}ELfI)j08=_X!$B(!pQ)m^W??B#aZ7bHAV`&U$pv~I;%BJ^0qB!F=DX@4-! zAh^Rv7l9wp&23|ZB(Rn zhmjW@UW8M6dV~LvpUK4Y$c3x&pnnxwE4~ZJ!V>@lzS0Y>@dQP)JiSX{8e=b4i)g$Vy}EZ$VR-_061tpg+z}oWQf-TLPYRj zW~lBln4~;WriYHut3u5utcd+PFS%@<*kWTiOd_xprd-D_D8%x-)z#5k zvk=7yT0XeefElFtsRo7!`?q_kJ7VBPK%JgppyrwE6!u)PTYt-h3|-6DC`!9vjT0sw z?uS-ISZLe)9xs{rW8+@e#$x<9X&07~2_BHIOqV%pZL$`+%oDZqjt4e}=1|tmnhwV_ z-MqLuPiF{t9ZZ2Ol-Lp``ZajDNds&#Ma0j(`kIu=^?kS_>h zWXgYUgnrhSGXSLKCkjkx_`ppCoAA_^t(}9e1NrF?W&}xH)bTDMfpx|KzjKWsNORs^ zQ3XcO;pCc+yQ!RZD#(lcytnR{G<B&Htp+N3j>S&`^Ln3^fx-8( z&cb43v`C?v7JoVI%%7hb=zuhpe_vb!*ai>$k3D;gagf3bs&+M@vSDeePBXJqWiHqy zA%)6JgcCZ_=}L+r6j?d>-s>bbJbiHtylJ|gapjlhNEI&hq6-J)(&^iA z$L?7v`xH7CJ1i2Wwckt_)w}4^se)j{7~0pVpo1!zfskvP-(#R{y$k~uP{)gjp1Rk-Gx zRj}^lz$X-E#_3JHK7!-o`yDG&tLPXZN!m7=NN5`0dVv>Ww`=jn!mCy_hpDVP-LmM( z$4xnk_kXjrQM>Q4o)`#vew1Cdn|@^#0<@L3atAVqZJXo_uc$emHSqxW%I`q_LYb58 z92D15xI2l`y7j5(g73&1Ivc(o0Mw>yeJ!8)j{_ULsTW)}amc~=l*P}RFH{FSt6P7e zbjRnjFbty1@BjwB3?kPeURH9-I(Q3d)xG-(s(%20Zp(mKk#~je35HLGhs`2;uAxPv z&Gr=+ZqI91S&S1m*FPf1#kq=)Ur^zmTLReY_aqWblQ; z#U+8ESq`SwkJsOcr#iatjLirv$xUA8qlho|9<7EoS?;03cB)Z=p8~UPsdUO61Oam` z%p`_?i-wk3^Q|WiSZfwyBy3x!`mVJ7-fu!oFTsc7ZG{bSXdd_y5cH?d%><~+% zMln)W81W=Yc5r+BQvz*pYZp9PW~8=^D`B47+-DdYnuw zb?STDiHjPpX1eX4WY)~#jJh&y3Fum>29hzL3S6^|0oe8a_mB0Pmz3b+fUStna(@Al zxV0?7>QMHlmm@U{%^(w6f9~YvnMlQYcWG?1EcYI)@xXQE36Z9-H{7_l{_oHidShz; zvx6R%E>&rnjs;#iQ8Z)(+e|oih9=0iF!x7vr43$mCG}oPWFYpZ#=f9gdR}quIc4eU z`gE!!8@oP<_R%#WE;89-3Y>c>&VOwFJ5!yde>k|-ycXXsKrb1U^IXrwbE*i8PhF{* z$xEzBy$G>vzRFaaGs73!rYVpti?QO&p0vsGqK~q;{|(eKduf^dmb$5O!%?tA1c1yF z`AcNz1V1dO&@Af_Feqf?s-A-m^Ed#$DjK;?XeJVl#R%{=Ymme;k)qs`0)NORwrjVk zY;RoERODZv$B_aIx#%whn@lb^f1p0DYvhZ~L^L`#dF2*^?1+ZBrvVH9CBz0Xus2uU zOXIyL9f1va`8aB@3-OuM6AlEEA+7>%h?JG*dNdxf1FgB!k0VQ(L|DC??3~g?lCq%X zL3`4OxMW^Ho(6UXwc&JD7=J+oG?Evk0V~Ii4S3$}z%JT`B|ch5O8KHMH=GdScS6e{ zo9a&ld|$r{6mc>IupQM^#vb>fge~^5{0O&F|1p~vzPb83M$#E0citvlFK)@pV-6DG zibJ24@J9ODyVG1R;MVaAd1*LObV9fVy>42gZ-2pww^@UxFF!8hNq!S zw2o;la#F&T9Z&kRt+i<1>_EBty%?ZA@9m_ikLZe3yX&mo)F88N#tlwJ0p^}M-QEqI z<4gIbbY&228v4WrGo<~v;qvAX#5)S}bMT**?dEA)WuE$#abB5Y;Yt?bLAZdIu>9&< zElgAE^|4IJM@Y74oPUJEM(6e2D5}3WJtx~d&@M{f=|I^gZB%7hLYI1faRFgEj1XJBdU3}G=WJ?7Gwiy$s+u`0B918HyJb!!~y>NBB^%pWJa-npn z=Prz3oXqhhTLg$@o>uHOZ2nP>>>afSQ6deKuIatp`A1at zS;o2~EGT7=eSg=VH^5d_7>&x~RR^9E1z=4XuCs zw_LK@tICLyu=*~#j&JBkHjC2ib z0QrjCwsZsYQB$n@Y*s9|793{c4%+eGIAYFUnaGwl=T1N8W$xPBawr)qn0SaJO2?`gtd9O-M&f!pMk~oN z=E|%bN0~$OH=}x>ygGn;%$diLNjzq> z-o!Q&GUVwuHi(V682<00IActt6tFTh`o)gs0P$aqRroC%@u*27PNx9~l2ReCwGTre zO(0~lbJu2;KJhLC{rYE7gL)R>x3oAxL&^<;kf1ojD4mU?p#38#VS{Op1GI_6ZXvkH zvwu>K=INxMlqoGuVQL7*{fi(q6a_;|Zc(}P4>GZZs(1a8_hZ;B6y}@-j}t|&Y~Jjr zwZ#|mHmQ{vU^cuJmuFb;Td;dR9ZSul%728qAQ1HJ}jv;E-)e;T1CGLQ}Ey z=+3`)zL`rNn8*gImt2h~f-Le+eg=b(eSaCXafiECQn`F|j?+7$EFHUa)+&S@)3m7S zFfW5LEpESXywW>pRva1go{|WH{c;tQ$Z+2y4uDN_?--gfcpPRkLT&ql6Ypz|!? zwwU#Y5>UJDrDl#O@8;d`RMu{>1m1ztLL!^Xe{q*AG;;R9{vwd% zq8s$)EeE${H{(!^3T19&b98cLVQmU!Ze(v_Y6>|qlM$*Dm(3{y4FxeXH90nyPznJR z1T--@G?yXd0VjWLxdU)z-4-nz+jdTDc5Jg_nRygOHYPS^Rz855l&S(7J1Z-ImH8V26_vO% z(8LwwU@u|f3giQ50nGtwKt})@JK!G(8v+$T+`-Yy8DxKHqV+bz~K#0kqPJ8USga zJm{?D>C`JZL_KkI*4 zXV3pw%m{330CSL;E5H>S-(fzAL02XmmaJwVmL&cuKIzbF$skgeDMFYf;$WL-`E(LvPS z@*m|`{}TeaNP#?o=E@+~f26iBvHeG)f5)|e|JfG>pgG9R?mzXwfAsigN6j7VZN2{Q zlK-^v?*&<8wAAHQlo|dv0RK))+M79;gX}E)(efc6~8inZ!b+} zK!cH~`-ueHW2i=(u?j7`G!=f{U4;nG58gq#qQW<_Dy;b7co430$4T45yS>oLbS-~- zYuD!S3TRRhq}4l&i2uo7ZB2NKN+zTofa&a^ct>ne&s}Zo#AMv@8m#qw@Hxsx%AM1? zgK45oHcrf08bsllsxubBb^B4Fz(Ye?I2P@(44(#V%yK3QXJp~pT!}mwG5TwwGXdL} zbn}b|HuJP|Nx2YQ8qpurB zRP%?>u0+eKP9tn1HgXr5#9c@7TYgfh&o`LV!@lO29qByyCKUi@>p%n)gK4^|+&n zqxVJL&|MEN{}Vpg=f{|(dLgldc70aUbC!U)DTxcQ_R)sT>Xe5yJk}h{KfW$C-%~R` z2czJ&&#cPh{V_u6Kylw4=y=VL1#RepK}niq)``Bk431qHcY`@wioF!qHmfj2YWw`u ze2~~59+O~ngddZqAb$10wkm(|U-;LgLMIRc{NmUKi_7V3b>pp}iJXm~o^guDc?Khr zx;lU-l}*IW1RF+xXOz@Ns#0EnkQ)SlQdIYhb46o4Ztw7?xb+~B6m|wnMRn^BZ`bZm z9=T6Bo`BL6>sqxp59E`S#WSY0Bh)9P&dA;Sod7&tPegh{R0iuJqS${(X+&SG;_cBE ze3Rl)mmIK8T#@0{5yTC+rUx(8PLcJtiJ!Kx_IW1N7?GSw{BunE9IqmLO_G@! z%VV~p?y1A+CI=c*F|AY(sBR3>f$Exdc)O<*jya4COxrSnGekgB94nFP^ker(2tS~! zuP^VqH=o%Z&GdgUO}>Agc5yj<@|H!hNb_k#d$n#fg&3)<}nG4d%b2Yt5+klA7fe{}uh17Dxj_V~;9 z@=D387e;?+bMkbCB*hNC!^IEsYxob*Dx*0HVh9=`Yr5fLIn@8!uamZA2Lsgb6~YvuF324 zfqoGv9STH@+v7RJ>^Bfd47bcXNATUu}vzA=ZHOqC1o8e2tXlluO6m=WfP~m^M*k`v|t2) zthBR}Vc7M<>W#UAPC;q6zbLLN!|doBYC2<3kuN_OC~s#`Racp6BcpJ!AxwCWb44@t zypeyveZScFFH&V4wkzON_MapO<@7PeTc`qqnYLf}OT(r`enw-S1<44Hd|7P(XhXkj zWO*@r+h=uCiY>;5IXmoGydVP9u0PCw$As=6n*=XKz2OMS$8~hzFYhxIX_5EaH@2$- zNuFoj7|_NSbrvhrof<+5$Xu2-d}wLNgKmHDVe$P}{lRw48*ZQc3N4tr@JR*&hO&Cl zI)AexCFLm^)L;4;u?kE{aa+U*ckQ!Lco(krdqNuU5NV6fGy=c5Y>W7Q&_D*4`%IN_ zpE;Uw`gOR{`Oc#z)Kb4o7LC3t4Y$CQ;KN!S~2Z;qeO7o5EM{>IlfM|KmaHBW2RvlA+KOfs%n7jlP zuXdR?qm62w)mG`p0*JqgI4)oJd?tSkX{<h8btASYfJOpa}ddnms^9=<{ z5jIKtD;IXslr;ejXeaDG-y}Ch13bi=5Gx`s0BdtBl|Et$ip&^+i**8;m^m_otnt{&z{{2yVHef%fh_e7Y5tQX3&05JXqwTRoNI3j-sK^Ax> zD)aO0p_`!!TTIN<{X^Gu;xOJ~Y6^;_HNNqGfUAEqat0q`e*S>5rP8?l6zbqnZ)vQU@Y$yGw@`jCKr8hkqsJc@vuhwmYR($zD*z z1ZGjtSkgBc=nacv5tZJa21tLXhh-EMuXt?R8Prmp2f*Vnx}Hav^68+alz3Z|Xp_KU zS$q=)ok@QKXH(`CT065eOj{R&uES_3B8fB^yD|@CiB;5(E3fP7i)T5wH(a%p3FTmW zs5-|MZ1Utns6I6z46yK2ppVFDD!Q=U3YC7-pn)RHlP2fIbxU+y0o$M*~FA4cAs(iVcx)|Rpkb2vc{pwQ#^f**o7-z=Tq zMSU~dtO=Hyv@h$XiQh*TyBC}?vQ_)J!LrSNoPs205kac^m8; z>^WgNb3lx%yW4;6mQNLNNKOxngG@WXLzdLJl|PaB*)j4xqN?*~0IPz$&n^zz46IeseIC!eUo9lM_ zhTWEXFyk{EQx+C%(2iJ?ZgkQ+6j-Z!HNd*yZlwn0Q8IrmUpB86Z8(RJ5p|^?1X}jr z9yEC{gw&{H^9e}Aggup9@bG$p8wP-(Zm@sF`*8?;;>4Gu!)uf7);1R~Y|r=C zf$3j%tUM`tQG1U8AID@WGa-taINn%r*;o}L&3$HxN?Bvc{>yeP!}%_z?5IsglB`<= z>$HGIeioDX0`sd#vBuKX-idnHl;FX0#~+eT6eYh6lYgD8GkHf|zgDRSS$spE0@@d0 zxVwKP`(acp8|sdI5>kTmJH?3}6IoO1GN@pyeRmRrhW&vX9=P;P+VR);vgTGXJ8X~H zcyd<{nv$I{2`3khlMr6c+P}vW^1jcmsfLJ*(r&M0AQU-rR zjt{O#32DD(;mF82fQy^$WKAu_0_P`%A2&EfA~dbQ3931HZ0{Q_93gY}Z~V71CZKi^rX!0T;Xc1M(YWVRf!+9Wxa8>9Hhg{6SjLu2g>?tLPZI zV1&*))4jhG-W`(O7w2=q8!{y#K4_}cI6FJ*C$F5MufFj-pXKn}N!kO$Ad&4?Ty>Qm zcyH}N-K1{Yf=~^}VfNv?0eGtGv^P-J`R8g&<)X z*(*x)wU{mz+8z9-t65I4VRyHwTO)QrN>DWJrRQxy5$50CGsDJK$J^EG`@{lE>4c|l zPx0mah^;sZ&MR!253;YeGbj9oC8!BeRvVogBGBc+&_oFnzGlLx+h0$A&mJwly1}w+!kv}mK8xsj8j(gg&L*`g^7jkxvU-=H7eZ|?{|eSy z;%jL3c*k{!E4ebXbtdQLg8^e&!mxGbUaVL>1&j#ey*^eZ{)lGUcP^Cw^X0 z#!;+8&zK{B(HiKm$|qNca+eLLYrIN=B7)#CjB^1J$Spnxopz7&R*h# zzVv9QKBkN&BR$?yivRNvubdA)hK9sNi;;-`AQDNXwwt@$66Ja?qpD*M!MP~Y;6|1l z;ERfKS*CRHM&*Cx4Qt|RO^utJTHvN%V|mcL5qKI1Y1Z}UlC-!LmlsVq8J7soxSu1S zxDfjg))zBZ0BB~fGE3a5=cWVKni#|Gd?zXaK;CUE!rrjC_a&4Q#AS#+qH4^$Jp$bO zt9COFe|;$AvO z7~tEK2(d}J4S^18RRnPivfQ3VEgQN_%@)RPct=}?xJumdtD6pQGIk{`Ez!i_i{Ln< zwNeAS=?;G_jk&Y)#kXOB<9FyY-ACx4ZP8!LXboD6Llzi0I1VSZCgRpu`v?KD7}tO? z`##@J*XL))CrKCFKq(iQp&m4)%2s`T6ZzoWx9cUBv5!T(QSAoz1n_piI&b>%moQ z&HnDgUEcIjW-WwhS@Fme{+q(y>Dvv`3q!IH)1ScT+U^D`p6L5J&GHp&!_9~vMP^ne zpem_gk?QHNf*4sVmjuk{YSVRGlyW}jsd9eEJrB?Yb0f%_*UOVs_}5$1I*!e7e*T9< z0BnDx5_!Nxtg*;)*>D83)v#(*a=sTk}-cgQY?zNmefUT{<-p&vgTbL(S14HhzAPV zUnIks(lJU!Q9}9Ncr%e^@ty_8zuzjSnh_>`O?MQG<+$s{WbP4yrluF#U)1L76|MJe zWK84!%qzYMbKA;Tm&p04mAbl`nHBSOcE3L8Vli$~eGg9H`*6txVi2m02>E0Z7$$!? zGCXa7bTY0 zzLkGmaDKi{l;B%-)q4=2w3;A*FT zQ`Z|$=;PtSc^4nD!vH`3X-mc$k!^p*q>rt`lzE4soCat$*ExUH`!*dYcR($G!T|& zwy)0qyz09?%EJuTEB5JS=hoaVfkUF^ZXQ)&Ab}LG+4Ra4oT@h|Ryu^eRPBG82}LZu zD~a479fVzn=4E9nMT@0^42m7f8%ZA}g2(;Vq4uIZma$#5ND7>4WVWYi&J??k=8yZT z)5LHxGaD7o<+07Rg~_e><#&r=9oCb5s_M@j7L@mCKKa=Q~V9z zqG4WwxvNBZ0XwYXJIoIOzKZTT7=9S|U){@b{R1zO5a0QS@8XoOdo^DBkl^)naqCQe zv&YU%k~7FD`8D94veVQAQFybB8dyo87SJ&eX?Dl4?a!G8>ME@>@Fy^8z5BGEv`$Z z%q)XesZWMg^_&jb`$gU)UQ3qB3%NE>WCYX`ecb@mlsrSiTir+88sX{YQ*G1P!;pg7y32qB zl~VYSbXM+$z%DkV0kYq>WTOlE%@R_R zyIK4~Zbhxfb049`8>VjIE}!jlU3e(RTdZ z;uyGdr+!$16aJ^C{>SUCvq;vN^Q-r+{PmY~AVrfq{ONUR=UY=*IX=S6SP{C{XLeNPWq&209o>zA2QbrvvpyKNMfwJUCu z*W?=z(o(nk{~G<(GzOF`>ni^&3V-_k7CDwdzZLFp;P-^y|1IHc2=)oeZ#U7hpW_Qo z2A-@u^kPy5+*M)l+ky+5iRaX9Y}4j#ANkZOItL4gQCff1U28UDa^%k(x0XRY1|u-1 z@01=wAPvwQ6z)28pt)^&7`}?vIh;xN;8Ow<(|580_okBvhYlf3KFMIx_hjqFCBIyp zpy<288lOH$Qx;M`(9+l+J3&~M%|UtSz@Voi5!cf5BeE|4T+2cXkL2OAz1#*`9d-rt zAus_+jJ|)NR(0nzq|VSfj&#|kA4XdjD@s)p@8kPGb0)B;DXDP)&m`9&diVB)LbO7r z{CSfTFKF!)(a5n3j z8!@HC9x)oGoh(oFb4d%f;=$6BV_wXisj#nBzZg6}@lU6i+#;HncxV+R)k=cHuvoeWIgMbR<75+w!}qH=Fb*X z+f#qY56~ScQt2gKrqU)5yuuMz#GCjuBu=~}C7lJCb*buYF^zC+VV}LHpUafmsx0xJ zk8l5OTqu#qV^;u#T%i5r4raLswbpVxWa(B21W!UH$>j*E$G z5#HEIS3%`#i$w-V!_zlQMue}sSO2$@go=L~Dx)Cjq>%&lSE!@SlmvG+B#|)p(N6MZ zN~Ac`j8bZ-_DBxK-V>VsM6%u01_n>Xcb9kVq6EQ^Ksjodu5NL;Gc_GMiWMT$>hzQO z$=ZFb^j5eBIN$CV06xQJv;BpJhtVkTWwZvV&O46Ze#vuW_R=cc4qarSr(;9kUN3)8 z@q<3LOT(LeO4REb*gznQj>~`5C_>)Dpg|*ssi4<7s2OtjO!P`6OD_qJOY+gBqu{+( z6gD*nOrM8y(UGw z4dAo#?VO|ZwQpKti$o~5Vkm#4sK1Mv|J>cDBcPMTTGtDmvgq1IdH-CDL|k_5eQ*T#4pR`&Gt^T%yyB^z^#KOJTUBTSCHULY@wNc3MBPBjA|na zF*~8V|-TxH_cZkycR!;4D+$yQVU{`*^_^O+%LSehKQ7-wb5_{ ztJ!&f@;te=Bo3_pWV6#|^iJMBER#191$g$$)--fE>}&Tnp&G`)QeR=dMdVlGv=6-# zfquH?^V_VxLwMsa;E@)t#WoZ@XQEx1FFvxG%yD9A_<^uc2#63@5UNPD`k0E3-PB(C z9OzEQk41-@kj#HdVdBgZcF}^ml-}p@9iPYM70;|r?dmkrEQ3>b@G-b11GaVtg55Qp7G5eBAoDS_5;vJd)EuEW>t}Bn-Sv&bw zeH0l6iL4&Qgm_iC~rw=W)Uk~B}as?mIXKBVFjbn^!nVeVV zL&~~k!U;V9UqGP03=Smaaq)V)i$dEkJzU>z7lroh!vpRiP@D7gbsP*F?nTz8dVTZ) zRb%IW$Ofm{s+|5@92F!nT)A3Rj+eD5YmhrZpyX}(W*MGE*Oh`Q5+%t*^5CJ53nEp1 zm{`pxZWCLH&cJ@TZB^VmG2SRmK>KTLmsO3&-ha6Lg0(8b-o*&jVxt5Ciyi9d) z%o-XzWk(3p0?9vPC(qAM9Zeg^JI!5q@;BUnR65VBSaIxy)>q z=EO_tCMwEEqm#~rRI&)7J*|2@|A3=XU{0gq(x;iG<$Q)Q&@W3(%@^5oyYG0kyx7FY zMuAJBoLppKGc>ncbQAO~wfPlL+%mtf>OEsihd7y=nV90uO)4znQGOMO=Ho=Wg6Z9V zCXm=ko_(sq)$x@f%R~rg=l~K_eg8m*R;6)0gb0N=$lg8+3l+Hw9eNyHVVdcRfIZ(o z;`4sREXkdYJTt4edD_*L6n1k&x;T6-rsQF!s!YSF;Z8;*!#jH~3q!QE?81_Idn_UF z4>i6uiA%UNd*kXb-%*nXRQoAkjNC7O#HHXQD@2)bJR8;iMjUx5vP?n<#O|SJR11>4 z?IBE~*aizRTtJaio@I)inu}!ZA*84Rzw>b{C3+E@S>CD^_x+tpB)cXqH%hj5Tg5;g zqnz6&0|wEmpJ1>5*i@>q(G|rWiJcJOCJwULkCh>~V3Agzjy2Bv=jjzJ2iSrW7)24c`wQ+6Mgg> z7WU4xTo5BV;7UCm+3O5{CGZ7G(;wOmw;2SlnCz%Cb&$9|I^_lWjK_`7hlYM?`o&|s14BrZ zbn0$H8R|_e-sq2>JuxnsWfN3+El~aic}9-E`4(LGT9F{*u}1E&3egu*P04`!Z8( zGT4HwBv?cKei{~>J%%Y)JN#FG_XXPJFqf)r05$%ds^^hRZok4MJnvj(QaKs10g@s_ zHyIaHyfd{EOH%89zWM~Vy2@isOO^x}EKb{WZ~-(SK8GuLYg|+glGlf|om>g|cp`Z7 z;t18M9Po#5N&j?mu#J_hETSSmoj~ z3Q2-ru10@<k0(8& z=RCAV*NVPkiT)~TTFv#CROHs_bdt3ZJk|k!`n8t7)z=*xxErrZR4&S}6@tv+bzTm< zuvHFG+V88@GbIxPdh#|QC%yF^EDJ2zPn_M#RA8RfuUJM?*#>?@QzXh~V0L6(p`oG8 zn!TcQqoR98#%|7R?xo+zzq3oM-_XlYuNzz)RF96SFLBLq8r@=HG~f`fdS`v(syo+z zuIJ}E=S~SI_x8}VG=?L|&B4+A#z5~^T$o50SjG2P%r?@H3G}7Wrpz*0kD<8buN0_rbpJNCNyJ zqCGg|d9=zrYAXE3N7Nb3*@C_FB}Q+5*6KUZ=JDV+L)28HBOt3(5;(}UWzacz@ZnWG zZC?=|IV;EM*#M0gn1RcS+;rmcC*&>P1rEzF=fIgxmuH#qH`_Zgk4F(mXj7MdP^vL#q!GY=) z7DSKg+2Wrufm^LSDtd&DbT@du45fj;EML)t0V)`R+ipoN^cdyx?Ep{lR<%7}znsQ? z5?rV6D@42R#xI8#C73^2v8;p;$me!3kM4c zzBNk5A!f1iHNr5UZ#+?(gFXv?P^*f3o%j8SzL6Z?-7C#7r75<#88yM#k0}eaM2#~O zkSv7u1HBVrM+tGHUJpaie`{XjqcnX%=Y#6-yT(Qztjc|5J^2@s9#X{TizHuHISQX$ zTMMEiU@Bt;)|`BkLTa5kBqLD{=lzIz15_6aiT>727ZD|%_TIFvTDGo#avil8)uNe@ zIF!QLP&i=Pj<%A3&SnR;a0TVoX6g>RsywZT*;g9uq)SJu&*aR`2U9VrHWoD2d8~6z z9I#kuZnW&Jbi+Lv@33?@pJQSszP0WU=H_)3QIah%tO79epOwgF%g{waLsgBymj!-& zzvx*EXaYL-=Mw%6jlk-EZqVtZ$Uq(iONufW6++;z?InCiB|pX zx$C#9F+Ze;D=&@L^HRq-J}}vOMNJp86DDl6Ah+JQIi+Bs-T~!*c|KJ@BF#!339NqH z5>6NfsaFBy{@sw6!u{IW_f))D1nbh*pzNjOL5>n%BwSr!Zdo-bu-zBDQ$!&A?zlo8 zVzF=gY*&z1fXOHBcOsH*kKON0VTc7ABbREm`pNwKsNiLY^1zqt)& z_W)NWIv-X&Xu*VkyY~%Ox9AlC`O^=A{uW5f^ZC~*TUr|%QtuE7fLhEuSiYkBIP&=c za1OdPYvp5ha?9wOIn-r>;YY~*jvi6)I=GgS z42!9SlAF(wX`h<5VKc4z#1Q1KbE~SZA5dP;4#Py!k{W@3w2V$Tb)I_m9g@XVow+*b zHO6?9+#@fywR4a&!dX!HY+MErQ*}h5@Mq^st3&il9ipRtdyi9u1gnGJvOABh5sM>> z+et72smv6gTAGkLj7qEDzxS}Le&f2gx)l8LQY?RzK`mtCsn%3}1N`>9i40M3Y=~p8 zDVmE_=~3u^LyIgMLlQ?)1Y?~Dd8%D{A_w&wuI%8i)>}bOA{;_W6X9mD{Z4>|Sl=sU zJLkwtYS%yjqqsDl#N8_9aE(%dd~X}G5}}Es9d8~|B)+WtnmA6aDud>@k{;7O1fpb!jxYLO? z!d`k){g5i1l;)`su|xGQJmwFY!%*W;ff(ws^Vqfu1i@_hNsS7F(dy;5vMoa6PG1l3 zW(Tf+$3K=TWl%k_!fR|EM6FwmuLFfy5vEhW{#?h(3xuOAgNjdC@oEc27!ui5uREV2 z%5cc729IIs{Dx|^6jeuR46P?kUH8HQY0}4C1}9tZxP?=$kVm6ysvkIdm!l-OQFeM< zo(d!$+o4o?SCY5mp(#W;Q!2rBKhpYO6&hD zoH5Q<+8r%=&`G`QHG!kg$kbRL6W?*Mot%brp77gkv_+YM9{XFukxR9~S0t2nLF|Xw z_zVjtrvt7czc#2hBk#V(oNK9KU^p1jJ?o?3ROsIA;CXEf9uq4pH+Xab;ef;9fa2tT zPnXC-O5DuJOwr>N(dqsbaw|)wZg8%3i5g170KI5arB*Xh5p8TJMh|1vC%9|SXslzn z6NAGdc~|$>Oj*0H8ol^z056edzC>_3JD5|(|DDVjk2Eg(Z*Ux0mNCKInnSOyjiS?f zN4y9Q)R@1Gc$04!94b%MC&(>wxt8sJO^N>o)dAzWi%Dz^)|PV(U{&v@xeBI1lLbjE zVLm_?#v4Y=Gv;|I&)ziKp(|N+J1P((Q>vCZn>K&`m!I}K@$_B{pr-kCY|M1JrGL}S z-xCgp25-=yW^|NtlRhF{+{RVNVlJX|z^Vme{=i^tRPusRj;11>9IB;l!+H{bMd+@~ zKz8$kDyw#bSfm^$?hKi* z^zpz^KKgk{Zl4Uo9mIMnBio6CM_BssR6*kan)RIy41wutHX^?clDmW3SM%Q7=$p`r zm9Z;cBvT9MYrJ2vn{Of3;c4A}BU}~E;c!1!j(Yt+Q;mgfQnRU{98Q!zN_ME`@-*U) z7pO05tQL1ambF{XRnIk_K&rK}7394|IXvX|v;Gm!bP-&>gi6yJR5vFlSlF=q-}T-a z({I?b>!3=SA&Fbf@FS11DghdQK>U$e<|i;8 zsQRmy$7a4JW3zly5qI(8nWSzQ9C?5IzqJtz5g4Q}N(=$uYyRV^;n(Z8@7k(~#nc(& z61j^E;-!M?$sg-mw{hQ%q%Zp~hsBU? zUUi!k^87bB8AbMOAm)5N?_8OOB{kx0T5pl!yuFBbYRWoSdb^lN`d{)190)T{g?FT4 zuTE!g{W}&gliRYnUiAn{@=2det@I<%I1$}Q+GE#rPLqIMd+-l`&{*|YVrf@}j0>zV zBR3RirbfwjUO;j+c%RDgHiBi7^Cl;Jz9lRp84vpNHguVx0}j_;wE-;g`?67La0On5 z()E#&;FN-NUj|Gz{9w)4c9RR|k1YnFRlV&0+#Q^$w@=RukCR+HN*{9}y zWear!kgzTruEAn|X2EQ-O!?^z5p(%ZKG@}il{?{3N*}hD)MJ!mB7Y}*$Vk|Y>*u9! zC!|hSmKsX3dM%d*O;ESUJ1PS|(6imh)Stxe_Ks2tyevYx)Ge3j9^x+s1H*IzIE7K` zkdR=HhxPSX9m9Fd05X_151`b}qAgH`nxNek@c>^wn24)?sq9_qj=C=>=MvAglsmiM z#zljECu=3i=(*7MXe!_mKI^7WA0P3WT68VO&SVsBDnW9Z3j<3dj=()gt_atWxP2XO zc7`|Y*-+24YIU%V%C2q`C5BGJZ2F9_;R_h3#Fl3i2FCGlT2NzmE>EtL++nKX9Xs{W znedhkDC5&50}aUT-{1TQ8wQGfXPiyLFB)&!Snt6FlrZpHf^;eK*R$9-v_FLZp!x;A z!?t(?s0&&j@j*W*w{s!F)OPAQ6jAk>gXtO-4os(ii#^S#izC4_Qm`xVh|WJoBTF z`Gu(q0|K*8@e_bP>Hh<#Z9jDiWo~41baG{3Z3<;>WN%_>3OO?%Fd%PYY6?6&3NK8P z9jXVn%_#%869PFklM$*DmzzBU4g@kcGC7w}3IP-aGBYwUF_$6a0VjWKx?_-FO|~^$ zt}ffQZQHhO+qP}nHoMEVZQIt{Gjs3Uc)s}J{MlHUx%bL_A|pXUAZlmptn6WL!a&17 zOV5d~B&saIK+nN~PfyDPNkSszXky@OVP`9B;B3N)uV!M5uViA6&%lV!NKelINrEqA zXYb)?VP@`(Pi{oVg z|55Ob>}-uK{uPrG?Y{%Cbv1Ex{u`L7qn!=DjEJ&;sGO`azKDMiow5+VfvqvVwD{lV zw$4tRf6*pJ&KCd5jvC+jzmm1Veu*3#f8)a^|H~l-zOjkvU$l$0wXA`S2|l@yosGSVvxy_VjGeKG zqb|08)DS-X|8@6oo#B7~bQuF@M+{tv#+eB) z_ z3zVmvWX{Sxua$Ht<3SK(h}JLf>;r}0j$d7Pv=yV!Aw$g6{DwB!r>cRUH4iDgHspKV zTLTKq588#kA;HiyFRTc#KMd1&V4)EEEeu6=^B{kZe4IriiOXw^(DLU_4?8Qt^v{Y@ zZ`sSFd^)w;rmy?Gyb$koo#51M^5yg1;MI5o~`4r5T750xA8F-e-!C4cUV4a}c>u$e<*v zb#0o7u~K<`?=b4_UP|%2ft}}T6Ra?b`k38yg&S$Ow|xH&xqa8rn@?fakNbrEo^YGf z=Nu_qfv5I!j}los3*Ew)!XJC*{on9x3^(L0S_4#=#lq>v1ig>bn)GgLPFSZD z)>x4@59oz`Pb%+6sll@xE}o);4>Ew5$goG~D9E>7oMl}RUlLW6B9Jnz9xgx*wSaKG zY7Gh?7=}Z5)8L5^m-aAm9Th(^JoSHfHIs&S_HdgrnBz)3s<;J_Ht=U6#MG%I#F7EK zNu>>NqqCqSj#5T@#-C=2CYLQ5D#2?0_!V&Fv}`W>HQCkt5v`MOMOu7X)EGt;4^nX- zjE`g^jjW@byO{l+ZYmy7a8(jdk8lon6NII)tE?5AeU{MNICUsrgw*|%6)S&VT_xm! zgusM65~p0=m_~zW)Z3fWinUuaNoHzDB+aP6}`U=$@H5B7Boinf2No~?z@5+K-r zOwu5h`Bi(vFHxItvSuvp^^1$0BK8Z{k18$}j#XJES?Bs>)uu6Y1?4cxW*Dp`C(3T0NM2D#%7;&>8f*2Gij?Rjr{zBcP<+v1J zc2k)7^7e0$PgI9W!#3iTw1QJY#VB)jIk)dVAEOi5Y)9smSu{Yo2qGC+$Ek zV6H+9kqN<3o)iS|vV;=JhPyS%cNbL++TxAUGrbsJf#_T^wc^~YR{U@^rTaO%EW6eM zFKR||i$_X2_)vy`ojC%hC%U|7{303-#7la!Y=Ba^AB|=j-Cx~j2mPLh2Iq)~5>x3h7P;QI1UTW?N`bAJK1?}ItM84n-kH0=OYzZY9-p(4my#9IF-0|bc3bD*; zhf5eVQ-VHq0g1HPGlccTM!v?yFjLDu>)oGy%&xLu|Mq{9l&1=0o(L4Y3n6u(lx#m@ zq%D@$;yUOKmkk?Pf{nTwm%!%DBwG}Pc>~WyPJ}^3Rb?W@LhvGVHBa0ZB%12G1kdH= zX00f>G0zsH4)VjUo+Kl)o)}o6dIoC~Hu45W@lM`xHUoihyv$gI+Jj4PSuK8J=f|bL zlrc){NK=2udAOnoS&tH19?xk@jUmFtui$n#BjSC~KPXW%1B4;LMQHxfFOhYzZ@|cS z7-|IWH#TcM)gcH4sz^>H$PCfV|uJb(>w1Az~(S3 zg8~P1cWlI{DVhBTID7HyJt(e3%dXS^RKb%Fxh#J>prs`C1;ONj!!Cy&<0Pvt5Dnmf zcMYiD*e_Bm!3}U=9s4shtRuKo`4>JZ>Nb#A-6`2lg$q_O0S^hE=wI{;YdgJMLD{5TJ;v7Xv z4fKDg4+Re5%+5Srh>pHQNn98sfQ<{VQDt zm}p|6D-k3yRffDmTF2fYit1})c(G=7$J>8;m;13q@hvu%=8j;7u)+aRoc(ZF=6!QL zZhHk8Yr7c2+{I5)K^3DK6;4GsQqzFq2XB{o8m}^qgL|_F;(Y-sYxg9Z$rdRh@0|BHHhI_pO!il%ggXZP$MVY66=2qHACfX{{TgT+0`Z1$!d@U?no&X%Jb(`z8Dol4S3Xxi!eZ>ra2>07Gv= z`<*ARAj;Yl8QARnPQ6$f;@XBgZ0N&W2rB_ictzhyedvWkbSHAE^ryjq{WYO48I~P& zD*pRZ1;h9)G5u}Jvuh$MJQ@`&WSs1o!HCJ$aFFOjcZ?#IF<7#&)oUNc5qF$v*;oC8 z!LWGT*+{WZVP){7MHoS;2lju4Toqpzix(9AlHC3WgWE*6QBilrVN_3n&EM!Lk$Os9 zXK|tzMHHgYPr201elq^?ne>f~KB3|k-$sV0!%Z!Q@UrVw9d5sJ#RJS1OkckWcCGtN z!T|EL@~3;RmHfigSfVv8sa|ul9C7QY2Y5nYrX>fKv?UV29NZUy>zZHG&#)2tcFiR?+Yc{`8F4~qHYja>$S>SQOwW#!24!8w^Q1N=d6P_a0qZz$I3d zy3SY15nrBfyc%`Th>)u5HF;BJ_UY$I0EX6n{aW!v#M$mnsC$1hxePE}1@LX-tr7Cc z8>cmSmJQN5Rn^BYS<#e_E(&{*{)iZ5&#kt`HeDc-iRZct@gPox+lZ#+IyoO`HXa2cte3TkLfGnKNbcTNjONVk`H0?M=lL$8Z!0ai zEHs|WGYl|+Z8ihoe-H$RY;1HcE+tt#h_}}S)N(KqsZ4(yDHZw0r$UDFc8ni~4bgId zlCLX$%^M#?=M?nq0`tWRB(?Ij1Cma z{g=*}UNI#3%66j{Sf*H7Cc2Z4cu*eVm3nbyPO5iB3}q~f8?Kb-?=rkCXn87EaEL$` z%#-9x-NS$G)n>y@Vr%q%?1vzKM`$O2y_KPZWmLRpQc)~utuyV*D^T4_R=(ANVBt)M zPmA~OH7J^kU_}*G7t>CD6{Zq|1kbR;EVJyQ{T=HFN?wkq-u~Ca%q(5g+tHRdW03d6 zuCFFw)#BzL7>Qwy&%J?@6I0Q1ctoccA1~)`?LB{Igjl6B7NiYrqJ>(}KksfmRdMb2M@j-dHb_h{fL@QEZ2?hOe_D zMEyv(!Ef)*AZ6!^uxpP2^>*hZg9yhXygYA%Df}6eic1EFC?$1toXKf={F{mSX}HHkMV5YaCUT-P zPO`)^hndShB*ilb^Cur8bidwQYBE2QzZ1!=R&Enabm@!iiOFY%an$RmG8Zw2VE?C9 z`1lq%P50$mqq=TmbfdI0i^?Q_vJ74cKIMPx(*YC6U=KRj%|F)l3ah%>qFIM{Ub3zj?JF$`I>K=?9R?R*JV(0)5yEboe!d8=Y)v|n~8lb-{4 zvz6|wUXr?Xj5<3ihkiz6vL~Yo=Kb(mFNsn_^62&7(Qo8xj_V$DFQEj7=v^nRmN0)f z9~SkrjE8x6N1!XO6kOK>NZ>ZOpFnYTV=s(Ijtty3WTAy8>t0bNIEjs{+ zBk2Wp=IPXX-|=;lF5l3K+Y&ppd}?JKvaVw5z;hQIOhh=DU`j4WR25%8QyO$>QA^X* zR{&BE&@mNlBYXGlLM}Ih*!Prju)u$~i5UB}vLnpl`ensv)@`qyu|4|{x1-}rt_lMn z-xbGXx|wryPb@h(s=-ISQGM`iuEyQ?7OKvK4ka{yy6Ak}_HiIJTc7MwPCvM@%xpZD zP|Pa}NWk zw|bMm?FzY6F_~|CipOIE5lnyIk4Kj4mLZ)M2QKMEUP3v$mLTHrb>k+daMAFZD4S}+ zq1y~CAvfevzNZ1dLJX8MEHwWlX#9?Q%ypqxWWHSVO!oZpn?>n$_8K4aMS8s=O;}x` zwyk1t&j?&HMUISx_`9$4p|wcB%>&LxG;91EY7q{#JWC~QNYH{iiwb`XD_G77G`?}E zcbvU5Qmdsj>lkf5d-qN)S{$pNC9R_%)WYj@a-zIHQH zq+#;c52Vbky7^Ot@*jT|1~8P=S~(?1n-A%-A*K{xE(7`+ZxL$VVojgz z)y2*qHE9HX*RiO9t|Zrid%NYvK3++bY)lv1(8FFSu3RH0$8qENa^irS0>j99s5}I$ zqxdhOfXwe4F@%3-;qlLzoo8qvGDhcah3P2A8>{ljDiWWYVx_=9o~1@BtFlC80g;dY z?iIsb_5M9?IQ72_#%qwFlhSEJHnatL2YXRf%mI7u{mmj?)Ued(|^MeM^NC zpRJf!y6=U&?e6=W`sWgl$43phJoPF3kPS@Kc#6AP*DDEvi?fSp9SqV=(f6{$%ZMZk zuzjA0)itGOWMt398Q-u`h)h12?|B8egy}wfATfV_Me&Hf9f1MqAs5k{aiK1>3x)&x zM@76?7A$#J)C ztB-$q;szdGzZ7FVzSsR#RlLEeY5YLQA$7!J2Uv!W>aGC}N95KLa}&L&PivI#W|QkZ zXZ(#I8kZt2RQ9~jy5dP(s?>)*ocbW|#q+l6>6xfY?!1X##{IrUXI{oz2qjYCkYSD| zJ1lFh$of*q;5&e*H#Dq?Nxcd!oQ>@g+Op?; zv>1a{!YEW@Sjmv&0>^+LO8>UGpg7)LBm;ku z=2|>zRpgAQfd~=yGj{4i)ft)>Iw8>XaeK{X$f(02oH1r_xM{j*K6qUalYg2x_ix+I zVY3%%;Va6L5Kt_^IlGY3B}DM>bwFs`I_EFSwSAGa{+0}n+YlM(92vE~>Imv;VB{ep zFi*#E=MW)r8EJYH#)hlO0!%8;hfseAh!Z~!QU!-P*5;O7UfZC^$}IZbt#{64h+V@r zY&Kq0u$jOlb7i*>C-05Yxy7)jC2hwpZCY#qI!6#$<@ZfP93cXzn{(Z9K_Za-M2OK7 zq{T)91J@tF7H9^<^3OFsAGdlM zQV{=l88$?6L2k{~${u81V>C?N+@zvi^-!2-4GY3+MlD5Z5T3vd(VEQk(5zx%I8rZECB&E5O50sQzFM6& z293r~w?hAcxm>->WLhawQ2Cm;=T}=EpIXocW$~9POk-2-X?khAhCF|dkrYY))Q*@s z*PjRp6Ik7@jcXsc#&DgIa%nR+X{BS@kVp9faEH;9sFd`&6!gb&0?M<6hEouQ08y-SHh=-lJBfi%4~{HiYKTd# zR~hkF_%j$iBVHx zaK%y|0(nsSNI!o^mLnR(y_wc6F4@OUQ5-cDhe$hqu0f_HS>6W?bk3|fV%Ep& zp)(_l^z%Ki)<7~35Doj2EnXXiIm~Y zp$y;zrOo8J;hItF46R<9G4w0{5fE6iXr^f*a#0H+W-_g^rvI=HK6DTUyRPjF)NjeK zvg7FTC_i@RsgF0-9lRGHQ0I!n1N5dTcIWH<2#+&E{1vW7@AvF&OnB?LEyy>hL)(4? zh`gV1AVGiAAVtwIP*KtIZOvKGx*Elh&s55ztKt3+otuDD=+)19+uX-mux$~J&o=$ydCd_`an12Lli;gINLdusF?qIS%&x@ z@XUl+I>9Firw!QM69Ow6Jy5+a zZ&!*{do}n)L~A6GQh3ltj~$Lk!Vkia^MCUPKNOj3-flcurF;!e8gF_Hq~78ffkD^i ztP6j#ebNASjw5H^)dW}jqQt)M2^0g#z+mNKh}95*aS547M=%pqQc=yf zqk}|4*w2UTd-eiN^biJ@N#Lm! zjahFJhaJ>WD1q(-4L9ISq9n;3Af`4+0^v||CJKrGelC*`>c$KLI60G_y+oZHI^b3c zJqRv2OFH|jqV>qoHotNHQ)nw_RPlc)GK5roFEOoC^~Xyc8TV!|C5ZeYY-zE^(~-9i z9JQb9c81l8fE*b{pPgga(1-LOP*sHtScDJsp_JGMrWP=fz{R)m1(rdvu~1(|mLC03 zt`3`Z{=FVnSh1Hr{=jxe?y)_1cSdV8Y;sJN4=%50A2`TTLocUkK4G%Ohb@0j@jm-^ zTsq*CGR$0d2YHu>kJeYArMN$br0y!&^=%`(Pbe|A6gy^*(#C+P=m8q6T!Wo6npxo1&#izRdts0-Uh;PCyxr{G;o$*x2~nnSmYs6* zkvbDh3AUYM4e(no;_s<$F5`{c2u_qQA573j;E}zjOM4+;BrjFP7OY4m&_!=YmPe&P zD7F();&Y^w-{N9XmRS1kxahn}Yjzq~%26QMQ*cxwoW-ovvCy0hFvx$HW%FCJ=QYl7 zBhc_=8k&6DPi2t;hwb;7m2H~(~PaF&m9m{ zk!Jq1`t=h~28^&G@V|jBiUX!dy+q5!T6W!5fS38?s0_trArAGxaE__+4Wx>^9<_9_ z5C#W(K9SA}-Vp@l3TJR{)nm?xEsg*#vNsztH)EOF*ocu5$tb(?8b&67e(qm8+ zR4A&o+8qlCQ^q=TM!|-+{&b^Pkx{4$3@w2w&D!WX(z7<+hRlC{7m@8eA(1y%M_m?` z4Y4L6oY^L$DjX1uW84zu0B(ZXYe4b{U;UbJd}-_$)>y%o0}s6u)(S>SkyE~4v&xeP zZ)c(J`2!NYCwS%yh}R|G##DHFVy)58z`9cg=1W^do;(s`2;6jenHq0CB>tBX9>|}2 z1Y}1{s-M{|0PTNmVi9p>`}@deJ&K861`#c)zw^$62TgBlW?!^Fq(yL8;k#`48=yXs zK$1$g#v_y<#%sz~>OnK+{FlBdaRmueC5F^szxI%j`uM_xfn;xp4f21gyK{?%I0 zX1zb~M;1KlGR*Q1jW;QuGQqxYlX*HlQ1-kPVvQ6-T|TK#KApiTg@h~s1$MrW)lq8C znF4%h3IQQUT>gRxO#$^av3ygB8`a9-j42wpps>B&3v?Vz#%$Rf??BOa?O5p;W4^a= zkkO)!|HFSsTgVm$Vv%UiI0_nOsZ`d3J+Oy^VG(&*=InCCqTurLw2Re1$K$sH%=L92 zY|B$aO`g6dd%6Xy6qH%fA_wtZH8pRi=96|e9DewIAax}iwxY}BhFE3|hS(^&-&Q{W z#)+ky>tlRb)w<*%mZ>J4cM>{jf!Dq(b_sgPqZ5D04NyVE%bQiw*?k{hM`18~j4F)2 zDAF(<%yHcmW+J8OK6_EWQ8dejhGPt-pP(RM11k?O@SN#Y0X|m4(o>wJ%=ksY-DbnH zISnLnQr$*$934oSp%?*E)yS1&q)V@Zi*2%;gEMuiL<$)%2Dkq{Lklrcvc13yF^nRz z&ZB=mBkh#>)e<`w_Ys-ldSbW-Xm>@wt6IYmy`eEJowQaE@|8GYA95hv)v;wUBp0O{G#_o1G9|o_vn8E-Y$ZzJZ-RFRyOGwdKmW!CHYCh=B+NA z+qo`K`W*{EM!;H5z}vV$=UZT}`7cVe!(Q&Yy@TW-g>Cd4SC-BAiN7Z!YR=Wx8TdJ zv!^0ti=tqt5DX#p-T4fF>MdRHm=V9qV90+qaroM18C}U;Wzeohyk)Nu&AL!?IM4M#!rL~1 zflI4GBRcsU^0UdUOx1muhHhw9TeCpV?w_ z#+t|csa0ohB3XZ|s|&0O@z&p0Zo#jnyK_7$p_f^O;TIoz(S3L5+7t2-NiU;B4G&O{##+GZV732bMeQ*TLrq z8b8DCubfd%b9AsiBg&Py;2OxN7nBd#z=$QIZ_^M_ReZgQ!8~fI8g2qyW}~iYEbDG_u_j+y^jH zkFnM5U_=&ca-O^27Kq$e%#Jem{o6ti;%~URp}KdTaF#I3!OcP}gb5uive$Yl93O;2 zw;+LecwC{9Z)JVc4X?qbV%IT-vna0+ez`L|n&Ag4HEWTRfb;5&=B0lZHO{*6A^!BE zM{du~X**E(oyX78A(UxJW9&Tl*M_E-7~Jg!dnet8I6{-^+=8fwRNySf6QPvoslW)g zaguV8wJ7XkO%V=bNi-A!W9(|Tc(bJ_65x;BNIr%~0${r&b4Nl1$_3jVR zHLoGZId|PptJa!Y`>9eERYK5J;uj(;noBup_l7wtF-nCspCW&4b#XT_%CM@fKUnH4 z@@-^?ozZOS!YB>SuZ#s%X$99cTrpEV0;J0n;fNc&{IIQNijm-H#h3raoyHl(7K{fG zu}PxlSUz7Xr9DO)g2O$2etfk2i8(8JYFSl^AXf6$_28Ye61^&3M)O=lV@{~7&Ko+x zTHnOg{1e^m`v!mMr)c*sND#E%6kb8;rRVghfMJ2%Y9BGiZ`%aSaD67F%Wyn-X^qTj z8l6-;eyQDA{u9neaZG$)b*tPypw;eE*rFCs%rS8ep0JRA4XK3s_V{Z6;-3p&sTv1G z63iq)8HhUHcOrs`j|{a9Zj-4AmCbcl;!zwGQ;p5mcr<@$L*95N$9@R-`Wlc!U@)3V zRAJhFtH?o3^d*>bZgPo*1(@hBOnZ`Z)sq>;HjaiXSUj-I9kGw}=zaRAamt^8o4B4# zXD;YAz>czG9Jx0IR-gn1(}&X}iFyZ!MlUFKt`%&LD%rFYi1NrB4<3f(^GPCCYUW3B z)f#D?xF3I|0O+!$NTY=;M?G>iriz|`s`l(t!OP86cLy)8yHYr*Gb+hje9%-FwKw_2 z{UJT$^K&aI;%o~&-1sA*gWJwKw1uRBp$2glM*#rY%`t?Su(*V3tPJS=d0UcF#V^pk zt{u=sKJL z*O=3HV|*8TZ5;&O=;}@_Uu0bPmyCN$6K5Q5- z!v=pBpPOnMEhz!wba4n?Y9GD%X>iSa@;yJWfLC<$z!`bU#d>Ng-bBCk7l84gR+4bI z?jRStd#@a7dGfHTK9)b&BD920-l|~;ZR|%?Py=B-LvWj;E@qgnbK7&zUx*Bdd!p@{ z^7BLglEp}qa$Ddn$FqzaYLa<aC zPrAT`YgQ+_;1gXCpDE#>xDD|Eln7#4>G~s#P+g)lM7Z1Lsyz3rbrMc4$X4g=L;=b@ zc7T=NA3~}c~30t=GCTC#FtOPNgRfr;OeZ8 z<*cyn^Tql89-6bh(y;77(QU)Kwv^5&z8jq@XlePfI}stYBi_dDxF@Y!SK|*R>ez~! z*eiSjl$$()z8Tm+P^-U)BkzuSliDV88f)!;9NSMlcfw^!Lsjg&Kn-24)#sRRm$G|7 z6Fo@z<~<~RP>KbDc9ty5Q(+_R__$(S!0V5L$6oQ`L;hCUAa8Y8hoysaWFTd#7=ieD zvp%xn(qaEhWSG-d<`E<7;ua$m?^fK@OXV8@qkXQk;M?)-K0;Gp?`}K^xk5zuU2zQAT21SQ&4Vy$&3hn;XgN;*qCJ_1=26wPPiF%Lf8!9#P6ydm!i?zD;7tbb1lYtGF16jeSQ1~ zV6I%;&vY^9arpk()(}I*;Rvtyh$&v4J`)vYlRW^(9nWiaNovD08=Wc z(uaL3$H1Mz3|M%CYBhYqrC+kOcB%77f|X-SKTl|d=!RTx4fbR|zWGiCvG*iG2=CIv zHw?^8Y(1rg_Tetg2M`u@gVsuaw=EhwImjR-o{n9&fD-YGavo5rG|bk-ErJa|x64|S z40tzJrKxVJ>LVDJ;pyi~(SSRu7qC%-Nao)*IDTyJZVU1GH9sFExDweylWghfpe%ZI z{gS<*WiJ7O?q4ygl|1(Yo}Q~O5K$x61<#2Ezj>?pvT(828H0KSr4ZhK{hY-%%M%D^ zVbCGWYf#3f0KPR2@Wdv~aG|fi<_FRX-2v)S;Z&nr${qUSYlzFCdPs*0K5A}?!{>~7 zv7n#7P4SmARY?0z?!TAdv_IaeRR>a%4=!rjf zF|>K7{&cWvn;FS%6+Mh@bXb&xzdW&!*F!=j6n!7X1Q_{I2tYc_=Mz((hzcB6@G zL+O)iEw7m8ks53TKg&Sfr+E1{wANYRsQy#c9&zCyQoWd|1xvy+Z03f`X5T4Wcl@nf z-hu+&>fD3Lj8D#>uE153cz7fzz1cLse5(+3r+zoYsF1`t0LeOXF;gADxzL4R@NB_D0H^^FoS zYp?|^sJb>OlHo;33av+VBsQCWbN2#-Z= zad;U1yh&r|i0S?rFe`81MSD(g9Qw|G{$fQ?ziG;j*d-2Jn&x&Vi)7;t;8Nl4U&Y*A z*UjS(y~LLyLI{d;zpyzo@1Qi{smcp*Pqt-}1;J$Nv){YdoEm@>H)G+{Oh=9^g5FDg zn$2j|hszXy-gzjiVqep6F`87b;=;2TYV6=~Fhd5TDu=Aydj>lNLR{t74wu5V?PO{J zC!?pq=RZ_Cy{mI6!-AJtR^RHTT+-5a8SN_0%Y6)I6K}lNfBlJTP(J~S`{xrO!?GmD z{LDO)#oCwHcY);BrodGK!|1X?z|@dY;#k*|9Yke+s9E^=~Oq~D&@&{m^FMLx3$N=v271|pN?nHgQBihinOMK`vy>8O2|R9ZlziK=XCD%c2kh-*BIT8cBi~T= zmv|F@c`&_l*jPAD%dv!pSfKVGw_NYNS9s0@0`V5rI0*dvQ^muH112DZqeXRPmz@uK z<1Tf6G!nU$zxu$?7dH4QQ5)9*G$4HE4?WXJE(8LTxc%rdd^1S;YfC}v^ybkC8W>|H zC3%Y3Xy>VurJv1pX+-segSZ7@h|t8QOg966jc1i!owKrVWL}|VV#kHhmxFND`|)^H z%aC^;Xw(HQk8aO`>CMfUr|+@}edM`}17`eSCEOegu3+IzpS2TtRlNvxon)cn3x$?y zT5v&MY@dk9c3bG19?-1(f#;=q%J$dv3Rd~F*X-X2k)@9zIENCmv#$etV}6mOB=7lu z59@kLSs*T*n(sPU4b=n`dFl^+F~bUhbon1u3vB5%AF)~MTfulV9-#I?1;`jH>!l?I zmdL8#N%UVgCchLFA)0N!IH{-k2jjVbl?=x{>7*hUoJmTsqOw_cJLBQKa}GwcqPRqi zLRU6S0x3DcKf$cauLw46F$-*R;1J<|GXuft|MQhqFldV&e_)r@mz@2D`UOXe*=rUM z8ljin&Nc1;ZT|oR8H>*iDYf^~AG<+lj}d=^c3xmDsi$LS!3$L!X`I1pc|VV$aw-%X zkRRKSVeODQ=&2a3KxrG*aJ*Qjbg>1|b*rQsE~Sr4;I_to)-IEOqmB2Bj^VTZ$o{jft?xZyk-4aKI)`oX~h7byJRsvw{)b=Oy z&TK+sQQa7f#lcW(f10W2H*jBH%&x(cVX5+GKbdeC{q>$yU0Y?cOritu<%g^9ysX3I zyEJw3SV#IDbwpQ?KH%|K3(x6)AA4`@I&wQ9LcT}Rff*cI0|i=nUG9|0ir`H?|liqKY*b5Z9z_TM?!fTi^C~>z~^Pcabx9fcwq7lNw)~I!eQ+j193!E%hLJnu1P5* zhF8-2?W;$+m${;K(w+JTNYwW1?YvY+Vex(kch~ZU_lgB3e7-nevk{Pg;=T4oerg#t zjr|6*F5ndEKyH}po`<8kP%di|tPE7`nC*Kl>n1&2^g;Sn^0Ge5007F9GFT@nr_;Fd zts#Xj13ly+gg!Q&-142MhmwO^pIeSIy$P)0a-^ebWG=Jp)DY+#aqy^Gut)8uR{BlJxDrqy<4j^1 zlh9i$scJnfl2`EH99^B?6B#e@;e9;TvG9cVS!8Y<=fQ4@9!p9|jtuwr?%y$OQAkq* zsjWgch$lyN#K7bUU@3({0|Uy|MTgsDrfG7q#_4Pi_C`=HucPySAxK6{m+FlW3 za?c+vNphPV2>SO1r`#~)3R(}b5rj*ZDX z%BcvRz^0yZ`dE3MgI}2Xj`R3F;`WHMBm}Wnb+Ja>R!(O}sJWLF$bI$HqHOM`=1!{> zjs(YUI?Q=GD8Z3`fUuG?5QqwJS;>ZB8OMJ-i!0D8R4-lMC16)Q+|~w~Q<3028N0FA zh0JJ=MjC~ByK3f0NeBkVbejhA3Aj{HZUDeyxL2IY(R#!%o-ChV!v5xMJ+D}?MhhxgbfR~K*-%L zlNcmGd6Y2;jXo93Swi^*c)1;kFHi>_W+&GQApyob(gqu9hd46C8P(#mma2us`Z|f` z1aYUD&~rqvjZ;jT_RjXalNTs^*bjv&*ye*6WDr~v^?Uz_Ko1ROQtl|GEknPN^B4Bb z8l@B_sSnV9t#7!AErdhJL0F;q{dGft9Qiguf|J!`6=Nmp&r?qD`RrjrjO+EZa>4xjc-*6^R80ya9VZ zp3vvar-us4`@)y1p`XUS914ca-a*-dI_iUCBSF|`D zB)5q5Bas99Zw1Xb^d;HS6m%;m0iwjcNpITS>uuCaS9=ufE9mDhnQ?P@N*wb;xblh= zU0ZB&DAg!fE0lPjU{x^oH9a2n7+dhWeLKJit4$xS9xh`XNSxg#rEeU5lY|JyRE>dZ z;F-dIOdJU zN0bAY!)X=ESh+6F7P6Rxp1#bn%Uw%T>yK&NuEk@3>4(R;WjvA)YNSyZPcr zYsRdI5#8+EbX!{Hy+!i0;&bhK^4)vK{jQp?I~II? zK;rj?$Q>wB-$uT5{f;SGk4s6Gt9;Jz1YBX#{MG(P?9LiGDr}{sNC&G#yNF~&{8K1@ zKZ9$i3G__P_;7sGbi;nS<=Dl(O@M6U!cE9h1NNwFZoS9-3bPx<**dAWdx?(u1%!)X z0ix`?V(c_{_KKwp4*(%C^i|_eJ>g9sM?Mm;2k=-h|F$Mr>yGb@gT+`EPrd;m-Y$cu zji;ib7g-1EH#jlN=z%j_z3WmSA;eaHwXSOvD7C$q98NmjSe~e^_PmgA9oHYU(ZMb%&RPpuK66L`9C>x0ix;tGb?KgmE z=HJ5TM{Z(+E8{PfJlKGc{DnLDl~keSfv}sMOH|PuSc#6M%1OZUK(%ia4EN_Cm;~+S zvuslUtdnC19>&7XRhQ7nA7 z=E+cvBMh^e-TJ`7GPY#it{s8QNuBKg>sdr7vf?v7)jSs&v*NzV7wQ-CNZIa9TZ z>(}m^@Y?bQ?gD(A_5E=(E5i|}HVJU5TWpJR0L~%K;MpFa-%2unUgZrxaPj;RU9q_( zFElQ77680$x@Z$Kcc}Rtt#Er^3n#26nwNdTu6%w=uTRA) z7TRz%-meCTy4{L@I>5q$VouCW`AsYgCVS=jdt4`sDd@9znSuZFG>slhf|@R7+^>AA z(eoXXYe7$@8V=JAcIt{uQdJ*OgR(4ITSN>Qa|z58`@`|z;F~=l(5Rc_h4Ym4%grAKG|JM0uz<9{p}4lz8h@ly9GZz|vbGilPZJV14-juK7Id zJcpR<9_IQ;>~uhQRr&71KkY;E!UL9=~={Kkt}W zN!9e^{r*#bhuY=_KN1ELQ&}=Z93Py+i=7AP1}zXK=2q$q<-!}uaH};WfX0K0i;gts zT}=&}9r1TcjbR7U8OQ)BSOGd)aNML#d5=jM+qdzQ8lcrmtazyw*u~;N>xCqqaSE0J zzBOHuHJMF2^G<+RIznbZOZvSPSsy+r-&f@N)hFeD=)xYD>at^eP!okgG?#z#6&KXy zsoxT|R#eIkh2<((UfLM3n~YEf4jtJ2h;+dCZqeCy zMI&YJ+&}Mg+#7pa53I&d;qp_WVFCQCKAvbnoxMDc*#+U!J+*6#gW`7?6>G7!l8y&O ziw^I9j(c}TlG8wV`j!&U_$^nrre(h555iWdEAu38e&v-!h=Y$Lu(Xr@&@_%|*CKn9{D# z9&l`^POT=~!;{8l!s3UhFO&x+{1z}Bi1Jx~58r1Uw?LJg*nkqQUROlQEu3tqs&gpP z;rwAgo7zz$CgFF=pj&1OSgt>ZBs5#SCkCPQ=(cww>Env@8W!be?y^}-0wedsT%^HSKNx@|0f z30zcu6TjW0MOt)-0l7*cqs6{~ja;2)#8BQ$ctr~WE@c(E%PUXVZOt7ldgPO=`Y4jA z48Tt%Ka)wKqg%CEUOl)@Oce7q7P-{opDds}vd!x=KSn@5P?TNpU#8Qn4U&-che^Z_ zK_2#miBm#sgqZ^>Kj?+A;>p292QqViX(p5*Po~eq*}+pWf9`4l<(w4BjAz8f#Eu8v zY1Awqt*?w%z1>!M0W4)Z^20x^K^0MWij?>!PgTZlIgNU53=LK4ROwM^b+!$$U7i8| z!*LnIuXR`A|c_W`CiMdF2JeeJO~{UQR|fKselh59 z0s|p!E#p`QL&EP(YE`wbp~HKB9cGF-S1^I;xkSL!wZT}%VQJX1TPa+}vu!g0hZY#} z1&b_8y@}!MFtiBvhnHUjrprNVzb@`U>N+YY!(HwO93oIDj;q$4o<* zGpABh=W`<*=a=>mcHchb#MVT=8s;;=oh#2_mL*xhvR92GV``Mj5ECYUn&jPOAeIL0 zu=l%(%P}z{TyPxQVtVhuI4h}g-=Yg+VLhy-3-<@cX09r98SliEgDC5V)zqzeaz4Qg zHMlkxmIaGD0L};}qDz@?l`p+^)JV=Pjj_*e;4sT021HP-N`y4N z)&0bO)Z8>vF`D0M4IXr!aYH3lvn{}#eDhq`mcgx&&_f*+(dJ};FN|zD$`2d-^Xi>0 zr-h9*iiM=ULP;Z`mj6OAmrY^xA2^{u3;u1HNdZcxi^2KRsZl=V*!LJHRKs=CkZI(coOt?P}nwKe^B@a3wNV3|H-HX+2bYRAwz+g&1A* z_(U-B<$#_A)}G3L`(&f!@3CT_p>n#Kyq6mNxOQttUiFoNh|Y-a528RXigie!`rhTd zXa<~ptkQF}3&MK%>lmb57HzsLm52T+a$=b-z}7CAPJ3IXe+pgc+M*pJ;g6f4pWm~3 z%ON}mFR!=nlI~;tdypG9;lw>7aPAhOOzMv%>3dx&Jcv<$wG+cqg&S1K{o1_u5;Wq4 z=iN@h0x#ZGXg{`<{-|!a;Yvar}A_leaUhcZZ z=b20v#&@&=`MadSDKa+tD16MzNhe%s?W8atTe<_2){0Srax+-Sg95hjP0vpTag6Dy zRsuNoMe=fgxcg#CLy89xMOis&%;Y?++(-|A(feb@xQUP%)tOD@mELFEx4qA2wVfkJq-p zx94+zwYty#Ik;H?nN#FhcgHmyh89HoVA>vkmbeGz?7&R)m*^xI^H;^P)d3gu@40FP zXD=l1LZrc1ZRg(-;UZp$0hNjKl!-oosit-H58gBNK+_Ma*ZjI13PUBDd#CKi0`R%S zo>qTO$PWymyQTje7u{;C6ds~d#TN~0M?^1wdC2O_@>o@g|5$-a3kEDlU(|wEmblB1 zw9AEQ7;HL{5o=kUaO&$UpeD`6d^q~9LAY!tM}QL|^xT2Pvas#1ZjxmGZCr?EuUL5* zc5|dO%~5N5|CW~+chE?3bSUdDUM>LPcZ^e8IJ{f2qj2b|RNAE})63eT>}Xds$5I7< zprebgHeD3FCB0o18#t)1(G_iVcbzLM-he>5hbplYUM>v#I?wHN5M^Pr6pfG3LrGLi zV1mmL-GD?duuM@f14?IyJyfY`_UET>TA&>cINe3;#%lzo8OBIhJulTT6T-5Zpb&D) zKq&E3t!q{IuO$6{q|B;% zD#Q6;uMGOQ>p^>_Y$rrp)+^?6=){(IQ1bB;Qc$Z30%f=pVA~#47Q5?~F&bFwG3mDO z|F64Pmk&@3IM|jV{x#U6k`O?OpN`S!Z%F*kEOd_64jD>uc~L*}{Y~qzm*LheKGzz< z$+mmOI;T_L`sMDgI+`P%4|fEAeka<-CA&A2`)A-*i2FRKBfx+~Yktk^_IXr|S~Z!i z&P{Zjlrax7_S3PHu(P9)W)Mk4GD>HAeS~qeQ^X9!|i! zUO}3k{|Zr^lt=>qEPJHfQtST->}45Af_!#=f+3hkTa|`|xwL3k_zui1k0zp{!V(X` zO!NrSxkiV@H`iABa(}YD7d9+OpOYE83JO7}Mfvv)O&J;rbUWW#LD6#H86kDbUM`>E z91;A6CoB5e9uy_AF~Qb~ZhDuF;LQq-#I60eM@4NmH(F4edgTI= zOc(ig9(NotKp*#eb`)wMc-SH)9Ct{)3C#vR>zE3CFB<`#q~P|I^pD~PG^AEs>u*qr zG`6&p`t9d`A%!EU+EkVY$Ex>s3Ud_-W^5DvYu6cSpODZAp{PoK3yG4-I9dPXyI>kE zc6J&1`kN9*n-Z)!a=XRnfz$EE3c&({42PbY5ajG*fMFZ73yAu(7}*F3^tZj*DWkil zJaG_}!S9|i+s6O|ezQ86l(6iSse@w~Ns+TQBSc^t2N7drT_P+is=?7{i#3k?nwuj4gr>U~0{eIBYGw+CJ zs<*^ob!qK-JX#!YJkc;UkKEwGOkg04Pab(n{cA;8sLd}H6?q~8X}oVlxX5>Ryd(VY zS!lWm{bGeRlScsw!=}2oF0O6cik#ZN2uM4SW7g4dA#$95ID52(CB{m774S6R@rf#G zlGHLRC5gZJ)>EnEp0*r_J|cjK z^r!mN4MH(~O9#~sfNWuJ2pUwby_>fM6;nvF-d0V(X+@R4ot@GrXve=~+%_5Yq7$kr zt;1pD)c|vU_D>8r* zK+EUw*TJ=N1>rYWI#H7DHQ(3_TXQA1RCy^N)$MYB%3|*edQiKO*v%%zCya+g$VSr- z5Mu3CFB>kazVj$xIvktn?eUYt=@mJH(X5Wk%DTPCinr~L1Q6~}w<9s}Qy50VDXxb# z?_N9i<4`1hs%M@`sR9Kt2}@cCrsKy7Aw572rwP_ zgmZKo;AxSfV3**8jVJKX2~4L_)}fh+xLXPkNqgKY)b4ym{0*j#pFsgr>UWI4FParJ zB-l1I=s|oo`Y&&>2dK(552$Ykq6JZZKr#W;k#LT!y9JfU7z(dDwo+}j`ojU|*`|baT4@bm! z)Foq!=7s|x6t=M8VuZ)Kfu%YS*=$NtLb<4M!e2G?9=+&4Fi_v|=VcH~p#0B&VwPRm zluIAEjRr!ylCZ#tBpbm7$~w3M=NIYjOpKA8d3s9C0~AUy*4EgdBe%^*es0`9_C zKgd}BHg~;(%l*oj*qiOx4nLJigC0GBp0 zPM#Rzhp}(<8nW1nRyVpJ_wQ4GP%>b>VQ4Rkr#)tV?Tu2&aIu<>3^u0zWm%O7IjTMI zJ)=+zLW2VI8YI*1|q%;TumK%`e!IXpu^? zwWe80*k0p&kgg{amx405r&sfQQM@#IIu4jTzTEB6_n>KJpWX$7xjMvu6FV0+QBzSJ z{Xth{M?8wEz45D8>qK131G6M?d-|OS<@9(6MffYfa_wMmu5n;H@pijEq`Q7Z#Xs;T zJoM?`v4YpWk7QN{aoc!qJ4JLA|8UDu*?bSh%a|vm`!8#HK=rEfDE69ikP>DU;b%#L zHoOd2*H_*EA@?}<6ky_iYQrH=SB7bw;A4jFB4_Wq=(H+;a%w24IbZFm6vuN7%L`qq zrZ$_P5E_3boqKBQ+xo#5un(`PZ zq)yOR(@g5o?t~uL_mFR$`g$2JGY8n+7r)C#J`LNe^L+gepmw&6qFX(Ey}{AfopZ0; zgUVcO#Ta@mFQ{67vhB@{lQq*=%a~zl)0+-^uyhzJP|@bL{B9BG(i3I`bh)rLx%Urb zd^@3BTqT>IvQ$5?UvnYdCj*6G1bLe2=@_gtl5k_G2J# z+-GWtAPtVMuY6SI&j+$>93wiPzl3~O%^&1O^0Yv`i0%Y;_|1|INW2P6pt6EO&F@Aa zn#P$ij(Cs9ORqP7+^B|RQROC)lvjWYQ35`Qdjhqb$`q%wb6Jfj6M_at!s^=R#b{b(VDBf{ zFdV~`N=$OL*d1c%Z#qo2zmD;u@>Ee#NsbT})N`$rWqBS8#((x74y_;ExNdZfsvSOW zS15ZifvDKaIk}4#L2-CD1q3PZ8n1)#g_aYujcw$AJU^L~nJ+@*Qyr*sH#|k`gF*Fi z<5F)<%f%XnZEh|@7d=7p6~+-;qdcE#U#lP{w3gZwwBtC%;-fm^nSoVD7jH7VVC)M{ zmc2A;<2?%T4}w)kFTqXm?i1wG1*Wyd@ zRX(IOq?rCs0|U|lhD9%vRs~(L z`JXFHXczM@96iNj`+#K;mT%q=8E@0O_d|C~8yNAw>7kA-;iuRV+Ce)3JR|nRL#sKG za!DLSFi~dOFQb-{s9l270@PW8#Dv|Q)v23*>;A4D4HKa|#w<1ig=*)X7={uWvgolq z&z@_8Tuc!J91}b!mvBg-bRfZElNrLi#rY#5D83P8Tt7>wSd+Z`4PSl5H1w`N*3zXW zZ>J?`1|U58$8@HuK-PU9jzw_1> zLqO;S>qE zlnr2FC9jT^eNb+fD8B`ZcE2#=M~?@8;$YCyWXBI99mC#gDD%iD2G-it1G}Pa#2bB< zSAp`@?(7TR=8IyDBEcF8oxl&cXQyz4 z^Dy@D)#U4YlYpKit?>-nsK4(r>XC(pq)qOw@{;nUro1NyKiF+-P4}zcf>k0&IS*%% zctJwL=z}6N(vo)>$oOb>5VZdKk=k|mZ8D4D!l5{5U2~**J7gaUpI(WFB zO+h@A`*dx*)0uApK=o-9HXg%Z_hK^mugkdR}4;}V!5*9VS5*7Wq$VI z(*T&NC}v@40!No5zDwBt&9(>hpo)U4<_aa7m~HPWsG@QjXVF)@b)255kgLACe90E4 z-TwF0KKh#wQaiBjegeQCI`ZYleQuOc-$RMm{S|_3U+z1>k6Qm zbL7+`noFHG+|9(wV@Kns?&q)-C zX|uD;$VW;8=0;BNU5Lm#T*oNXU+3I~3Cy|=zKFC;; zBBfsTJTDl=ahzY7D`8CCn3Br%s==^$7*TS}qzQs-Z4nKluFH-yw1uv_i-3W-VuOe0 zfDqg^Gxcja29L{sT~Hb$+p4B@BGG=><}!FXQKub^IYfF zr*oEKw%GY)JJT+6j6?G1%;5y;y5V!VDb1H0X+9`5M)kE1py&XMl9;K#3wuDQwxPzn z`zC(xKsw%FoDj|?qN)yaq;uUK{~-$ z)YbQ+lkWnw&7Z4%SEhyIgLmCH!@D9oXIUaXEF`6}aZt~lm9wR2{DtOmc;)4I9amRL ziLN-I(JMn)y*)Uu{p$<$a?1tZ3d+XQBA>7nyWduS>YpJjw6^GmWc2EZc(efh7wt@L z*`odKshXK(!+3HB=-YZ6^6vO{u5(XlZ;~THZ_@&RTkU)@?kcCO?PCOSJ8=H0E1x(q-PM16Cw&TL`BN2|$B|T7?QglGRVj z>1$ViPAv*!>^@QTGPaZT)HT>9^JDbStJgh~qF)vQi$}_L${C<5r%P=mz2g=8S`<^S zt=+R$k*Q{hSpQxNZmGLu+p*Xm80GKBGysV$UTOuG$KLZ8(7rJ9Q?Uh^iZhx}?E{f9 z9${8U8j;@5xSTQwJ}L`eWuVib_cJQT0H@x6z6WlJZ^J9A;ijUgImsm!-cQn7{Cg2; z4Yo^z5gkp(G+yjM%3fxdE&EU%*QeI7N*@!XHC9x8!(#qkDxHmst`vSX)2Hjsg2aq% zu3?Ue5K1?1%-Tc+ye;NmtDS~CEA>c)c?pT670>9bQgWKd*b6sZ<{evcCw~0lu<|5- zJ!3sHS@xK)e7htU!wgv%hO7LkDrH(yRTM(iI_k&sWcWpoe}=E>nuF;2hYhZ=W8CYJ!H5@A2+}yWTgR#I1>YU=nhrg$VNwrl1cQ8OIVDeM{*+@NRFI?122W_ z@AP}_jev?izl|+v(VvY`ZJsqb&B&yGl?KOW3r+cpw_`qs%#f~|C{gh9O<8y#ViE$F zW33P~scxeJRTkFobf9f?QmTn+iE#WfZbP?sbRZa~?6@&Cs;6G|{sMPpz{$d##79D> zW}Y7CqB^Q*ubOP^CKSWc(sJ@^Dr;|~h`k_xP9dN8HL&^9$-B|`yF$C3N3zJ zoWm=#$v*+PE8mQ~4manu@)&pix(L)2$%E$$ ze3jSJqG(r1Q&#wym@}c^2tjnCFjfD6NPqx0-ji`n%4)el4ji2dWo~41baG{3Z3<;> zWN%_>3OP9-Fd%PYY6?6&3NKKXg`NWz0Wg=Go&zZdF)=bSIWjVr%$@@r2Qe`+GC49b zm+zhfO*$l313NJ=!a&vSbH90m4FHB`_XLM*FG&eXimobI`D1Xgc zTT>fJvVP}R^y4`(VY=>@h>4Bx4UauG;{m+Bg&$-PptFD&5Mz6P{mJ~YTB=qfj0}$5 z2ve%A%Fe9(@={qP%QULdP0Ed?&)}Ne81EY68fU3%8*f!(auZE#Olp!&jWtB8Y-2Tj zX18H|qmB2Cb&a+zG&VKb>)hB#41cw59MQ*U8b|brBoK*FE;o)i8XFpyNSr6S%%6F~ zlfW2#Lqk@RXm5xW@%JP$23irZFq)n{vB;_MfrjWM9~+-Yu1`&HK{uXOO>#DZY9g;A zu$s;_!8F+!->|Y#>=%91~C{)AGm&+N;cu)G?Y7rj8|O4R>7Nar)<3G!sX~C{rg{y`j02NiXIZRE`Z% z1w(JsJHaLbls-Kzn3k$Th<~;*WVDc&6%7W$t)ZEy2s1~ki^O+>*yu=>Y%))gz8k;( zy3y`^J0Cag>(SA8qkTL*n~l$AmyIQ7+u3M$#+TEpi~aE>c^(E{jSnWHN7Jv(M@0jH z))}+;v_Y?5(0e43ss8Z~Fy10&&9A>U?G~Zoc!s;=23pN9xwJGIW{)U+3wxHnVgnX(wn|5z*`CrT1M1ZE z4O^!46}wF7J2qY68Q2Bx0EzL-kQn=uF{yR0G3j9iufGPL8k1{r=wn5R%f!3jW7Pnk z^k0Tgt#6H050h(g`+reP2C;7Se+ZMFzPG^V&hcWyKzDbiM7PklmlJN0Lst2G50kn7 zFU8ax@*l+^4{(UL!ojI~Nv5kD;x@r>=cM2U0pRq{P`=&`)&-)MHLs0;zIRY*<=ibm z`A8MRrfsf?<$rOZ1QXtB=P&Gc#GV>T=``ar9UR`UvM;t`WKQT(Y* zE|!(1H=|*m$ws23x{SEgtv1BUbRS+P=;Y{iDl+*EpNVg9hBc!KJSat@LGfHPjFNMn zWO}Ws4S@wa#eaROyDbxi%r9tWP}oFf;Ug>PliTDHIY2E^cT>}6!jet)tQh*9l(g6M zZ_{cOAQrE!`|_<=mygvmwe0>(@74ZTaBLuHZ+OX&mzgp|*m(k<3e8)zhMY~8R>7G# zoGkI-@QD;1fer<(*p6y*7}$tQ6KzZ$?xk2Y&vx|Q@PCR!VkgFtg%;1RB1R}e=@0AX zUcy)cQ}QeFq68tVEFHh1&ImrkVW12jw>CLF$fwI0Pl`i}C2LF6HnBLDnW@9LH36>9 zo=9gA>Ki)7n8a=>)bvbk41sYm98eOr!q+8sf2O3fA$f0Pgp*~SXkFy6k=9y_dxQh6 zGIec^9DiD9qh++E^#-%jRy^xAde!?QXdD~`A2Dl=FtqhsbWCE@25nNjwqdIc7Fs@% zMnaL6&ba(X*5oL@u}ujwZqXL{!h0?Q5~WSRQfoX2yaH?)(q2ApdQx~H11Vu4TvxSp zpar&qLSNhsANiWMlu{kL;YjT>Js+sr3Rm*D$bZQhu^riO?$BE0u-U+Sf`aESTA?W; zmir-NTcNEYHPK-^i^u@9IWPy_L50#L&Kuq+#sGEap76dI?pLm+ImE2>hT&G88@D@MnbNW71l@=&YI;q#T%hDywiDW z=6@UlHqSztwAd1UBHki>E)JG^w`t*1zWm+(wOcSnbNy&1Z!uC4FP`gIzLwNPUno~( z5af2rrD%l$s-jdWZM8^|7Bfm1-{o`ipQz!Ppd@<{m&^rDa@e!b2H_L1BXib%AD8(KL6SVT`Tjew)*l#zBswK;vA7Jxl6*k5gMlZVbGqyNo!HQa+hE z2XT&&&EWjf{}>{DzX+{5Cwgci?vdm`?73=55w&w zc!!fp=F^ea3h5ZTB<#-FDZ)Sa0FRTAMm=TW4-Vm^QF&R1u#vh{PEU-QO%_{{$EASO zdN{~(J;;@)jyU?eQvJ}O-+xBD9k9mCX~VOo9{yO)B?=m4SEzkd%$+{jEtJ9KqRF$p0)jqUdn}8%pAp@)vz#M~iC7X^&uLs*_6?RB;Y%9hda2J9qlb@6p=3)d zH1({NlRx@0dzZHGM1Lz%>ek!57zrGgNz-Z!PP-gY4w*?)Udq^x5zWq^a!q_YmNIg5 z3b+(WY#MA^y^txM0(P))S)}b znso?04FSS3)B+emEs)l2?_I2<1~v{{x`KKM?i%5`ZnXWluAJ*RT=7qF#vPqoH2 z<68~uO2D{l!mJK}f^6MZvpo(Agv%d=Wrs5yIat4p(|?LKN!aPs!@X_=g<&h!s-1jQ zOZ#P9j;^U7-^y1zQy>vYnKk()V7V&FbsJOvF-8l?cIT4`O93-D?d zm*&!!*}JsDM_Q3mw+Cj|*L;%1WhAI9_B@Ymf!@ZcIkGR5 zdEv-zbFv|Q(!9t6^t@fs|d6~@lubW`kgsh>tk)28B}-pD&~@X`0#A|m&dQ3zSD{( zPDV$UjT4GT_$K^;am@ph1K;F(-V6B)@rRfD@`d|k;JFtJy&?U z{r3IdLvn>z&sVvEHRKBNg&eN#7M>8Yt6d=^TRDT~$=VqnXxF(zG%MZVVf(0k+&*o$ z+Gp)=?eq3k`$zk_-D!8*z4o8&yLQxmZuh4IMtjg6j8A5x_OLx_k48N5ulB5+wtv&p z@zJOSnzPC12+N2v&0;@wi{(bpDxIg z)XNv`{^(+Q*6vR(_ODJ4Pbi!0PfuvzU^*M^v;214j{mwEowVbx`zNE*_Hgp|xILSk zjoT^xRoSLWHSPJy6$Q!h#dzG#zD(P%6eAbY8rrDWf%e&>$2;$K7}~JHsed|Tb+-3{ zER(H3cA&~yneyfPH`~u1u_`O#!-mdDqPiDVVz`Bqh>2m*Ti9~|!CD#b`SY#k+b;-$ z-S;c&hTJ?r*`PHaBK!gbLgdGi1lJoYlf>x!{9^i5Kp0(IOuvZQ^U9&B3|bmE<+wPV zoDnFeS0}T{`N_8)9BZY_-G3La-#vZ|I99m?d3W}nf11Ew&gT0-W3^LE&JHJMli9bM z6kIDY{`v5aXD^=q^7PHttCjXn?DP@;1%*yAx^{Zq(~ut*8m4?3r;onYughMvjbBc_ zidWalrL|JipHKGQK7RJgtKCN{l_QlNILc7QI@@GZMYIb`5uF#xt$(b6Yd;RQ=f^!Y z)=EpS-n@GI;^i;9TaT!g&whoKOl%%l{&7m=ABNaoZt6Q?R=3JczE;M$eg*fqeS!+^ zdHa&;x9xfT_J%4r)NkEZMJ7FLsXRNJ(9V8Ld;3XyiW=^`{j0q|xpqZ+`)Ov42hlpy2sR(Em(;b_f7g{ESuXDYjPn`F;DvA6pMev7J||Ew2+R zhMz7u&p))P6l14d;lsC8%&KL}FDmyJ?eE3@T)}tte@j)}2YA8i!lt-KSLRb4Bl-L6 zV03w0Jce8b|EQ)poL*hPe~!PM0ks55`yY?bN{J}0R5AwdkJHN&etmyc;Ug!6zuLd9 zrnB+E=MxZg4?@Epc{%=@L~#BQcC%`C6<__@erx|d*lE*RnfJH1d%yqrT5M~ST4h_` z*_N80Zrdkh*}) zHAWt>Hw-4#GJ>T}ONq_WC%U-r^LwJ$oUn?$?3fIF`*d3b+1SrR^g+{B)rRiKw&FLv8T z<9@*LhKGTr^?Wbf{Q{0~59=A$@cs4VVG0Py99k7 z_8QcFOY0dVi>Owu$K1nuhDF-adItXNR{FEO4}6wxXqLQrU@fm#c(YeOAbjZtWl6ZZ zF_ieBlWkIlviaA$m;CeHE3R$lKgP}F2g|=t4yaU=-^6P9nXHjt!W#L>yp=f%Oh4Vg z+pOSi|VHl8EI00kG)FzL%f)0U&==d2nSQFIZA# zW(qG!Ze(S6AX_jXF)%S*3NKS>dSxInFfj@*S0Gz4ATuB_T?#K!Z*O!UIXECNAW{l1 zNp5CuAUQc8Fd$M2FG)loTRbpBIWj~-HZnIbLpd@yHZ?RcMmaY)IWjddI6^f=MMXX! zJTOB!GDJc)GB+?oIWi(RHZ?RcMmaY)IWjddI6^f=MMXYc3NK7$ZfA68ATl>IAeS+Q z0VsbZ(7Q5&Q5c2cwf-M*N+Qn3I40s8BF-WR8fi75Z~6x`O&%EEaXZD`i0Pq_C5eg89Lsb+TqQLN|;9W_CA|ROcZcWUK1+gp^#fsPz+af2n z#Hy$kRYWZ6Tb4v#L_`hIb>)LPQA=dbJvM)cdLn=AF)A8~;*-Z65f?FH|Hr#^F(;Zt zLNtpO(JIiML{jvN0pj4&ZwwM=AFd(d@zym=yuP_cNM5*72mk_oC9SkxxGdD2`B_%~qMhe49R$%}D diff --git a/doc/refs.bib b/doc/refs.bib index 414773483..97960d853 100644 --- a/doc/refs.bib +++ b/doc/refs.bib @@ -1,26 +1,52 @@ +%% This BibTeX bibliography file was created using BibDesk. +%% https://bibdesk.sourceforge.io/ + +%% Created for Varun Agrawal at 2021-09-27 17:39:09 -0400 + + +%% Saved with string encoding Unicode (UTF-8) + + + +@article{Lupton12tro, + author = {Lupton, Todd and Sukkarieh, Salah}, + date-added = {2021-09-27 17:38:56 -0400}, + date-modified = {2021-09-27 17:39:09 -0400}, + doi = {10.1109/TRO.2011.2170332}, + journal = {IEEE Transactions on Robotics}, + number = {1}, + pages = {61-76}, + title = {Visual-Inertial-Aided Navigation for High-Dynamic Motion in Built Environments Without Initial Conditions}, + volume = {28}, + year = {2012}, + Bdsk-Url-1 = {https://doi.org/10.1109/TRO.2011.2170332}} + +@inproceedings{Forster15rss, + author = {Christian Forster and Luca Carlone and Frank Dellaert and Davide Scaramuzza}, + booktitle = {Robotics: Science and Systems}, + date-added = {2021-09-26 20:44:41 -0400}, + date-modified = {2021-09-26 20:45:03 -0400}, + title = {IMU Preintegration on Manifold for Efficient Visual-Inertial Maximum-a-Posteriori Estimation}, + year = {2015}} + @article{Iserles00an, - title = {Lie-group methods}, - author = {Iserles, Arieh and Munthe-Kaas, Hans Z and - N{\o}rsett, Syvert P and Zanna, Antonella}, - journal = {Acta Numerica 2000}, - volume = {9}, - pages = {215--365}, - year = {2000}, - publisher = {Cambridge Univ Press} -} + author = {Iserles, Arieh and Munthe-Kaas, Hans Z and N{\o}rsett, Syvert P and Zanna, Antonella}, + journal = {Acta Numerica 2000}, + pages = {215--365}, + publisher = {Cambridge Univ Press}, + title = {Lie-group methods}, + volume = {9}, + year = {2000}} @book{Murray94book, - title = {A mathematical introduction to robotic manipulation}, - author = {Murray, Richard M and Li, Zexiang and Sastry, S - Shankar and Sastry, S Shankara}, - year = {1994}, - publisher = {CRC press} -} + author = {Murray, Richard M and Li, Zexiang and Sastry, S Shankar and Sastry, S Shankara}, + publisher = {CRC press}, + title = {A mathematical introduction to robotic manipulation}, + year = {1994}} @book{Spivak65book, - title = {Calculus on manifolds}, - author = {Spivak, Michael}, - volume = {1}, - year = {1965}, - publisher = {WA Benjamin New York} -} \ No newline at end of file + author = {Spivak, Michael}, + publisher = {WA Benjamin New York}, + title = {Calculus on manifolds}, + volume = {1}, + year = {1965}} From 0968c6005e9a74a56588ab55dec44c4c304cb834 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 28 Sep 2021 18:26:03 -0400 Subject: [PATCH 0022/1686] added details about covariance discretization with references --- doc/ImuFactor.lyx | 105 +++++++++++++++++++++++++++++++++++++--------- doc/ImuFactor.pdf | Bin 243257 -> 248399 bytes doc/refs.bib | 20 +++++++++ 3 files changed, 106 insertions(+), 19 deletions(-) diff --git a/doc/ImuFactor.lyx b/doc/ImuFactor.lyx index 4b71a29ed..f76ede023 100644 --- a/doc/ImuFactor.lyx +++ b/doc/ImuFactor.lyx @@ -1433,7 +1433,7 @@ Given the above solutions to the differential equations, we add noise modeling \begin_layout Standard \begin_inset Formula \begin{eqnarray} -\theta_{k+1} & = & \theta_{k}+H(\theta_{k})^{-1}\,(\omega_{k}^{b}+\epsilon_{k}^{\omega} -b_{k}^{\omega}-\epsilon_{init}^{\omega})\Delta_{t}\nonumber \\ +\theta_{k+1} & = & \theta_{k}+H(\theta_{k})^{-1}\,(\omega_{k}^{b}+\epsilon_{k}^{\omega}-b_{k}^{\omega}-\epsilon_{init}^{\omega})\Delta_{t}\nonumber \\ p_{k+1} & = & p_{k}+v_{k}\Delta_{t}+R_{k}(a_{k}^{b}+\epsilon_{k}^{a}-b_{k}^{a}-\epsilon_{init}^{a})\frac{\Delta_{t}^{2}}{2}+\epsilon_{k}^{int}\label{eq:preintegration}\\ v_{k+1} & = & v_{k}+R_{k}(a_{k}^{b}+\epsilon_{k}^{a}-b_{k}^{a}-\epsilon_{init}^{a})\Delta_{t}\nonumber \\ b_{k+1}^{a} & = & b_{k}^{a}+\epsilon_{k}^{b^{a}}\nonumber \\ @@ -1908,13 +1908,13 @@ G_{k}Q_{k}G_{k}^{T}=\left[\begin{array}{ccccccc} 0 & 0 & 0 & \Sigma^{b^{\omega}} & 0 & 0 & 0 \end{array}\right]\\ \left[\begin{array}{ccccc} -\deriv{\theta}{\epsilon^{\omega}} & 0 & 0 & 0 & 0\\ -0 & \deriv p{\epsilon^{a}} & \deriv v{\epsilon^{a}} & 0 & 0\\ +\deriv{\theta}{\epsilon^{\omega}}^{T} & 0 & 0 & 0 & 0\\ +0 & \deriv p{\epsilon^{a}}^{T} & \deriv v{\epsilon^{a}}^{T} & 0 & 0\\ 0 & 0 & 0 & I_{3\times3} & 0\\ 0 & 0 & 0 & 0 & I_{3\times3}\\ -0 & \deriv p{\epsilon^{int}} & 0 & 0 & 0\\ -0 & \deriv p{\eta_{init}^{b^{a}}} & \deriv v{\eta_{init}^{b^{a}}} & 0 & 0\\ -\deriv{\theta}{\eta_{init}^{b^{\omega}}} & 0 & 0 & 0 & 0 +0 & \deriv p{\epsilon^{int}}^{T} & 0 & 0 & 0\\ +0 & \deriv p{\eta_{init}^{b^{a}}}^{T} & \deriv v{\eta_{init}^{b^{a}}}^{T} & 0 & 0\\ +\deriv{\theta}{\eta_{init}^{b^{\omega}}}^{T} & 0 & 0 & 0 & 0 \end{array}\right] \end{multline*} @@ -1928,10 +1928,10 @@ G_{k}Q_{k}G_{k}^{T}=\left[\begin{array}{ccccccc} \begin{multline*} =\\ \left[\begin{array}{ccccc} -\deriv{\theta}{\epsilon^{\omega}}\Sigma^{\omega}\deriv{\theta}{\epsilon^{\omega}}+\deriv{\theta}{\eta_{init}^{b^{\omega}}}\Sigma^{init_{22}}\deriv{\theta}{\eta_{init}^{b^{\omega}}} & \deriv{\theta}{\eta_{init}^{b^{\omega}}}\Sigma^{init_{21}}\deriv p{\eta_{init}^{b^{a}}} & \deriv{\theta}{\eta_{init}^{b^{\omega}}}\Sigma^{init_{21}}\deriv v{\eta_{init}^{b^{a}}} & 0 & 0\\ -\deriv p{\eta_{init}^{b^{a}}}\Sigma^{init_{12}}\deriv{\theta}{\eta_{init}^{b^{\omega}}} & \deriv p{\epsilon^{a}}\Sigma^{a}\deriv p{\epsilon^{a}}+\deriv p{\epsilon^{int}}\Sigma^{int}\deriv p{\epsilon^{int}}\\ - & +\deriv p{\eta_{init}^{b^{a}}}\Sigma^{init_{11}}\deriv p{\eta_{init}^{b^{a}}} & \deriv p{\epsilon^{a}}\Sigma^{a}\deriv v{\epsilon^{a}}+\deriv p{\eta_{init}^{b^{a}}}\Sigma^{init_{11}}\deriv v{\eta_{init}^{b^{a}}} & 0 & 0\\ -\deriv v{\eta_{init}^{b^{a}}}\Sigma^{init_{12}}\deriv{\theta}{\eta_{init}^{b^{\omega}}} & \deriv v{\epsilon^{a}}\Sigma^{a}\deriv p{\epsilon^{a}}+\deriv v{\eta_{init}^{b^{a}}}\Sigma^{init_{11}}\deriv p{\eta_{init}^{b^{a}}} & \deriv v{\epsilon^{a}}\Sigma^{a}\deriv v{\epsilon^{a}}+\deriv v{\eta_{init}^{b^{a}}}\Sigma^{init_{11}}\deriv v{\eta_{init}^{b^{a}}} & 0 & 0\\ +\deriv{\theta}{\epsilon^{\omega}}\Sigma^{\omega}\deriv{\theta}{\epsilon^{\omega}}^{T}+\deriv{\theta}{\eta_{init}^{b^{\omega}}}\Sigma^{init_{22}}\deriv{\theta}{\eta_{init}^{b^{\omega}}}^{T} & \deriv{\theta}{\eta_{init}^{b^{\omega}}}\Sigma^{init_{21}}\deriv p{\eta_{init}^{b^{a}}}^{T} & \deriv{\theta}{\eta_{init}^{b^{\omega}}}\Sigma^{init_{21}}\deriv v{\eta_{init}^{b^{a}}}^{T} & 0 & 0\\ +\deriv p{\eta_{init}^{b^{a}}}\Sigma^{init_{12}}\deriv{\theta}{\eta_{init}^{b^{\omega}}}^{T} & \deriv p{\epsilon^{a}}\Sigma^{a}\deriv p{\epsilon^{a}}^{T}+\deriv p{\epsilon^{int}}\Sigma^{int}\deriv p{\epsilon^{int}}^{T}\\ + & +\deriv p{\eta_{init}^{b^{a}}}\Sigma^{init_{11}}\deriv p{\eta_{init}^{b^{a}}}^{T} & \deriv p{\epsilon^{a}}\Sigma^{a}\deriv v{\epsilon^{a}}^{T}+\deriv p{\eta_{init}^{b^{a}}}\Sigma^{init_{11}}\deriv v{\eta_{init}^{b^{a}}}^{T} & 0 & 0\\ +\deriv v{\eta_{init}^{b^{a}}}\Sigma^{init_{12}}\deriv{\theta}{\eta_{init}^{b^{\omega}}}^{T} & \deriv v{\epsilon^{a}}\Sigma^{a}\deriv p{\epsilon^{a}}^{T}+\deriv v{\eta_{init}^{b^{a}}}\Sigma^{init_{11}}\deriv p{\eta_{init}^{b^{a}}}^{T} & \deriv v{\epsilon^{a}}\Sigma^{a}\deriv v{\epsilon^{a}}^{T}+\deriv v{\eta_{init}^{b^{a}}}\Sigma^{init_{11}}\deriv v{\eta_{init}^{b^{a}}}^{T} & 0 & 0\\ 0 & 0 & 0 & \Sigma^{b^{a}} & 0\\ 0 & 0 & 0 & 0 & \Sigma^{b^{\omega}} \end{array}\right] @@ -1952,23 +1952,23 @@ which we can break into 3 matrices for clarity, representing the main diagonal \begin{multline*} =\\ \left[\begin{array}{ccccc} -\deriv{\theta}{\epsilon^{\omega}}\Sigma^{\omega}\deriv{\theta}{\epsilon^{\omega}} & 0 & 0 & 0 & 0\\ -0 & \deriv p{\epsilon^{a}}\Sigma^{a}\deriv p{\epsilon^{a}} & 0 & 0 & 0\\ -0 & 0 & \deriv v{\epsilon^{a}}\Sigma^{a}\deriv v{\epsilon^{a}} & 0 & 0\\ +\deriv{\theta}{\epsilon^{\omega}}\Sigma^{\omega}\deriv{\theta}{\epsilon^{\omega}}^{T} & 0 & 0 & 0 & 0\\ +0 & \deriv p{\epsilon^{a}}\Sigma^{a}\deriv p{\epsilon^{a}}^{T} & 0 & 0 & 0\\ +0 & 0 & \deriv v{\epsilon^{a}}\Sigma^{a}\deriv v{\epsilon^{a}}^{T} & 0 & 0\\ 0 & 0 & 0 & \Sigma^{b^{a}} & 0\\ 0 & 0 & 0 & 0 & \Sigma^{b^{\omega}} \end{array}\right]+\\ \left[\begin{array}{ccccc} -\deriv{\theta}{\eta_{init}^{b^{\omega}}}\Sigma^{init_{22}}\deriv{\theta}{\eta_{init}^{b^{\omega}}} & 0 & 0 & 0 & 0\\ -0 & \deriv p{\epsilon^{int}}\Sigma^{int}\deriv p{\epsilon^{int}}+\deriv p{\eta_{init}^{b^{a}}}\Sigma^{init_{11}}\deriv p{\eta_{init}^{b^{a}}} & 0 & 0 & 0\\ -0 & 0 & \deriv v{\eta_{init}^{b^{a}}}\Sigma^{init_{11}}\deriv v{\eta_{init}^{b^{a}}} & 0 & 0\\ +\deriv{\theta}{\eta_{init}^{b^{\omega}}}\Sigma^{init_{22}}\deriv{\theta}{\eta_{init}^{b^{\omega}}}^{T} & 0 & 0 & 0 & 0\\ +0 & \deriv p{\epsilon^{int}}\Sigma^{int}\deriv p{\epsilon^{int}}^{T}+\deriv p{\eta_{init}^{b^{a}}}\Sigma^{init_{11}}\deriv p{\eta_{init}^{b^{a}}}^{T} & 0 & 0 & 0\\ +0 & 0 & \deriv v{\eta_{init}^{b^{a}}}\Sigma^{init_{11}}\deriv v{\eta_{init}^{b^{a}}}^{T} & 0 & 0\\ 0 & 0 & 0 & 0 & 0\\ 0 & 0 & 0 & 0 & 0 \end{array}\right]+\\ \left[\begin{array}{ccccc} -0 & \deriv{\theta}{\eta_{init}^{b^{\omega}}}\Sigma^{init_{21}}\deriv p{\eta_{init}^{b^{a}}} & \deriv{\theta}{\eta_{init}^{b^{\omega}}}\Sigma^{init_{21}}\deriv v{\eta_{init}^{b^{a}}} & 0 & 0\\ -\deriv p{\eta_{init}^{b^{a}}}\Sigma^{init_{12}}\deriv{\theta}{\eta_{init}^{b^{\omega}}} & 0 & \deriv p{\epsilon^{a}}\Sigma^{a}\deriv v{\epsilon^{a}}+\deriv p{\eta_{init}^{b^{a}}}\Sigma^{init_{11}}\deriv v{\eta_{init}^{b^{a}}} & 0 & 0\\ -\deriv v{\eta_{init}^{b^{a}}}\Sigma^{init_{12}}\deriv{\theta}{\eta_{init}^{b^{\omega}}} & \deriv v{\epsilon^{a}}\Sigma^{a}\deriv p{\epsilon^{a}}+\deriv v{\eta_{init}^{b^{a}}}\Sigma^{init_{11}}\deriv p{\eta_{init}^{b^{a}}} & 0 & 0 & 0\\ +0 & \deriv{\theta}{\eta_{init}^{b^{\omega}}}\Sigma^{init_{21}}\deriv p{\eta_{init}^{b^{a}}}^{T} & \deriv{\theta}{\eta_{init}^{b^{\omega}}}\Sigma^{init_{21}}\deriv v{\eta_{init}^{b^{a}}}^{T} & 0 & 0\\ +\deriv p{\eta_{init}^{b^{a}}}\Sigma^{init_{12}}\deriv{\theta}{\eta_{init}^{b^{\omega}}}^{T} & 0 & \deriv p{\epsilon^{a}}\Sigma^{a}\deriv v{\epsilon^{a}}^{T}+\deriv p{\eta_{init}^{b^{a}}}\Sigma^{init_{11}}\deriv v{\eta_{init}^{b^{a}}}^{T} & 0 & 0\\ +\deriv v{\eta_{init}^{b^{a}}}\Sigma^{init_{12}}\deriv{\theta}{\eta_{init}^{b^{\omega}}}^{T} & \deriv v{\epsilon^{a}}\Sigma^{a}\deriv p{\epsilon^{a}}^{T}+\deriv v{\eta_{init}^{b^{a}}}\Sigma^{init_{11}}\deriv p{\eta_{init}^{b^{a}}}^{T} & 0 & 0 & 0\\ 0 & 0 & 0 & 0 & 0\\ 0 & 0 & 0 & 0 & 0 \end{array}\right] @@ -1979,6 +1979,73 @@ which we can break into 3 matrices for clarity, representing the main diagonal \end_layout +\begin_layout Subsubsection* +Covariance Discretization +\end_layout + +\begin_layout Standard +So far, all the covariances are assumed to be continuous since the state + and measurement models are considered to be continuous-time stochastic + processes. + However, we sample measurements in a discrete-time fashion, necessitating + the need to convert the covariances to their discrete time equivalents. +\end_layout + +\begin_layout Standard +The IMU is modeled as a first order Gauss-Markov process, with a measurement + noise and a process noise. + Following +\begin_inset CommandInset citation +LatexCommand cite +after "Alg. 1 Page 57" +key "Nikolic16thesis" +literal "false" + +\end_inset + + and +\begin_inset CommandInset citation +LatexCommand cite +after "Eqns 129-130" +key "Trawny05report_IndirectKF" +literal "false" + +\end_inset + +, the measurement noises +\begin_inset Formula $[\epsilon^{a},\epsilon^{\omega},\epsilon_{init}]$ +\end_inset + + are simply scaled by +\begin_inset Formula $\frac{1}{\Delta t}$ +\end_inset + +, and the process noises +\begin_inset Formula $[\epsilon^{int},\epsilon^{b^{a}},\epsilon^{b^{\omega}}]$ +\end_inset + + are scaled by +\begin_inset Formula $\Delta t$ +\end_inset + + where +\begin_inset Formula $\Delta t$ +\end_inset + + is the time interval between 2 consecutive samples. + For a thorough explanation of the discretization process, please refer + to +\begin_inset CommandInset citation +LatexCommand cite +after "Section 8.1" +key "Simon06book" +literal "false" + +\end_inset + +. +\end_layout + \begin_layout Standard \begin_inset CommandInset bibtex LatexCommand bibtex diff --git a/doc/ImuFactor.pdf b/doc/ImuFactor.pdf index 041d8bf1a2d3e93d115dcfee3a9b001f5a6ea52d..a4ec57fb7baa660508d5c6872185270e178b1d0f 100644 GIT binary patch delta 103379 zcmV(@K-Ryx><-VA50E4RFd&yPh5;ylEso7f1TheV@ADLWk_1dlcm9vcI-uam=tVq4 zjS9}rE@5O}-^A>ty9=tns+%-j&Ex^SB(w(7Cy+*|B7w6cb%gW*FD!i*E;MSkmeV-y z9-hWAb01iK-wu_(ruzm9fGDH2)L|k@3I>E$jemyCJP@mS{b>O5Y*&^gm%4RP<=Dko z&paT@^>-ce`m1K%yr(|$(vv_Ni7iZ!X*JzIKbGTG_TBWxMVqCLe+ri)j1=Lyrvp?n zs))U(@lvz}xBuAgOrAvVw}p*-**ER>m%AUod#|(U z)_Akiv9f=K;azu+0d|>0wi_KCcq>gl`i>_xe}CFqIJ&L;X{+<7@7^MZO=6VE;n+kO zCznaoc4y-_`r(L#m-pM;$dz_!l0?-ui8>y7{D~vGdqPUT)h_zXQ-^Uw9Nlksun>A& zCc+R-ywc+XaByzJr>ePh@&z06sOehL+2!$Is7ryBkLmY58H#pm7Y%L{lfwXs5I@qJs&a@UH0}k5}WzQ2&k5!2~g=sjItY!NkJA7RWXMUR* zo?@aSa%sbkUK7uNIEKls^$V6j$^^IMgY|z@N`P2j9YfcLGp~7|dr<*Ll!rYGaFVIQ zxVgH6>u6=SZ-uX~yN0JUPcZa|AE7_Mmqg8BxIrZ|W$iohC_8+1CRM3KgV&xWNAJnD-;fd=$}ks%*Lt0#RCEQ*+gX~W2)-I znv371u>+5c_LQh15l{bAp*f^+3aZ?(Gb7c-nZA)<@_sOwIMbLP=m5ba8Vo(vIwBOO zn}kg48)uFvE7->3f{Ci{LVW;9W*L9@EaA>dgQKfJCU!9B+eAD%*CZYd;SSjo2v$!) zuuj3t1osgd}rl2q)@ddpAIxrF>K{z@Gjvq;(Tt17V9B^Lr z7ba10`py0VmW$#QKEr*{X8`JG3lm-+MyD~4oncJ~E(O=8SA~#}5aNF?3&BCuFykvm zSCCH9g=y+#U}v_-y{N26Ek*#c3TvXn&*JKT7ic=A$t0rySD(&qV^Zv{y=MvLT-w6Q)Yi zu;-ch4KF;QTd2t0Jj#C-$>|;{wkkORimoJjyA~G`SE!V*hK$14-!443MR>4_@SqF3 znb7@yjUOZ%HnCsFQ22psoH_xO$8O3FUKp=lEQ7dZHsI^5Q2uM}Vmqr+jj`oQ_myzW zqova-&$9UiZJfZLK@M)7j_F**8Su}c?iQi_p*e1;ggJ#hm+gPwQon=l@^(nJ59lVP zq{G~s3xIH`9mCV~ICR4tVzr1@wII6}+jo%QGE$=fFCwe zQN}yTBMChsh&da2R7xx0x{{_1`vPsVg#?vwySPg9HsL&o|^e9tkN7%TiP|l=qnYo^Ob;6iRLa8SC z)4&qTLEh3;$ErqD+xqj`lcW>2sB6EX6Gj)!+2F4sg4L3*p^Jq^SV{9q>?TU>|yGPEdTFNLAV64yL> zJwOk3)x%WB`&pKCjp}2I==;^)Lw8}HG^TPx<4}Xc?tN9y1a)ncOA8JpC-HOi8gLys z;5dIEOFJ)J5CK-Fh4cZzE#;X*y9+?XULLQG%{nLt+%ii7>CU{;&pL@;=mg|YH%Sin zr_XKEmCbn!?*<+2{2^sn%?0Be3c)e^{Od}(1q7IsO_~nBTdfG8EGwq1iML#e+|HvX zUk+3N!vHAGLIq$Ap*k$Oo)6atf;?Bz12unuaw^kvXY)GzzDM?D37Jsa90T=02txEj zoR2YzsIxBtsV!82`jtRRI_k@E^>T2OVCi0gC8}1rhUL5fWv?@R1^*-u&_I&Hn(O-Z}k~y9y@*GcY!nF@^ys zlMM?Fe+3f<0nn~I#ECaY#VIGA+PG@hmEuU88G0phOj5g^{Q7jG!2=XDnpv+M`$Zx_ zu+fd~{`vsFxccbR7nxb{l;vs8S64T1$(fRBrE|^FRIILct5?Zu!PE73SAYBTh0x(- zW{q8?H0#d~ZPRU=`}Ibcq+D;LRmm4s(czU$fBx94VfgJj(@D`*MZGPFqOt)+shAYm zK=Pk7N2V*oa+A6#mT93@8_ou8qG2h><|$qK32K$W1fy|+1WIxxm@qWw z<1;d*S+?4wOyzz%K3i`xrIV|>l0@5rXck4wM$z1O(RB@MhE29r(U&_Kd{^~%v^V{l zekxLp1i}oE%t91Nf4@ZizFU_t`6_<^Q?nrRLhN7GgK z`iIvvkS+EkFL|xfS@LDqR|hcON%IRskEtE3H8bY9YOmsY&p{G-qIZsZhn$< z1AXqzK!s)?3}Bjsf6HX%LF*sI8ttsQ9hkQ~`KE{Uy4bd-@N&wsT++*bFMD`H<;f9w z$Wq+K;Mb*-li)8QY`5oP~WDlRv zUCD0QC-ermj~n{Sf8A~)6y?$o{fx-}dkx5r3vdLH*Qr#szau@uMTc-t>V-RJe>U^S z1ORu{cJBv@ewfjqoe$(H+De=-{P%s;A9p2kD^iCN)}aKv2AX!m1B#3b?FT1-NgixK z0tOx+4FW}k^24zpBL?t5zHrQG2QLB($APxI0aQgr;T=Ms zn?Jlqe_*GGG0rq&=pvM07Gj}Cf0u6~=#n!FhAUZ~dF|IE3;4aOl9MYe?Ur9Km2^%!4wW!?17 zb&VZD4218HRm*avhd1hC2G+U7OdU=)tK^7c{FB0RB9L(Ty zm~n<%h|D~<6B%HxS;OY;e;%H|FGMcb@!@5_oebdT#oCI*1p?Tkt~%WBE0+pk@P;Q| zsxgR~JlVCFGUF98>0uJ?s(M##OP@W9%$&yYYtr;A0`M_r0oDTy7p)H%?U2505s4`h zl|S~;(3^%q_vJdzl5*QSp&;PCsLK7$6-22=WElKY1p!0C()AiMf5NJORrd7gO8{83 zfTzUhF$U#2sY@3Q;R=H@@IVEE&x3H>C7$rVbK3^y?l;6gbzup4e~T|R`=gI0^w>qO zfw&GKn8SpDf-^NqL(_lt?FT&SxEP&oNsnOvhIK>Ok1V4$)TvL zn`XZ|TZ@>{xxR`ze=OFNa_&TC3g@_=ItRP)d#F8d;6>9yl&;Y_+C#CQvUlKV3(D(T zmxvly@pb+c4;f%7bJr9A)tWCN!NS!cZ4W#rQ|LL8JV#SLrY{Fl$gv<$+C21&Z=)Ln z6Zptg>2%cW-?~}}9b=(xOkb-Z-*T4cueXJ-ir%#@J@L-AeWk9IqP=7$$vK{!dhX#iZgGY)ocD;RA}8O^g8qbNU!D#UL*k0W(GhqTHMc z$70To2}5YBmKi&O`HL7e%QDHI$CMAmQ5j)HZAHLd%nV>}QynZThPkkv0s}JDo=C z4sa1Jt`*aK)Yo8Y3pHgf*SUx&VvZ<^2Z$mm|3#4sx;+&4_ujE`iaimW;L@-(mkXR& zq@5|7M28$!L}h?WeE}6AgEHe*P{RVSuc&WJUtK%(f6E*kNrYfRkboQRWVF6GJ4sJd zrj%J^^dS?06JnW?i{uY6jYC9~>6n#xE)kI6oiv@BKrHPMkVTDoc$`^~PbvN=vzXWB zq2;PDkSJfisi6XN&)bU3x%W|!#$B+*7ySITK+I3RcTzk&wyy%KH~x%`MFY*mkT-%$ zbHg&bf5>%j8lM>X7KK>GaTvi!3?Ax&v2SNoL-(TEdl zgw#;~%!T~=3^ktr`hzj%EQe};Gn@9s&>eLz+pGxg!D_X6GRx$T@Acn$3D* zWrso272v@0U3umtBLnE4I(KIi@m~NofAbI&r?m52R+q{A|FpYkp4jRbOH$b3^2g!; zaoulxbwi^*^~sX1$DT*;@5cIaYz4qzv2R>b46hZwt)n<-$Arm=E4Pc$;KP%(u;1t+4e-Wd( zjP4wJiqov$ovTr%*zq#59$2$hPZL4Rm+KeJ=|Bdo?xHe;DmWn;?LvbJfk~CSzC@88uPGI z_Y%W(v9H{*flOT6e{7Y>p;gw=9i0Ox>i^4=KE7Ji|2WfS!!Wn=M{F(%wg{lJ|k={eAz1L}PM1)`)*j_zr+8rU3863Sid z3y0xLqM)k+QNwMs4-w5Gf7on~ZCjp6mclJPO^Ps_sYOtJ&uaUb=}^R`11g_I59_67 zN|McIzm;QwMFWhE1?C-sbL}rl-7kKr`(*<;KT!7z974ze&-ycEPHOa1xBC6HJkSHLLyk99qp8Y6Kr4I z)SFu<5by)uSuGsde^C>Bj1qjg8tdm+#`UyZWS8(@TYunPdM|fgWJ5|CrcEC7yIeYw z8XqWA>w~KQNce#sy3ZP2FHTM0UclTp_4rK*%tH447bNiPD+st4kln6ZH7DD=A^4|t z-PeC}4x+gOOlYE+uT++4tsec30J}C~>?2VU1O%rf2yXD4V7_;*m%0sPI*UljjcdhK~vTv#RmyI9Hw|xBvVR+8g zvLc_F^-C|rkIA%avWp>Yai!}=UtWFmKXXP1*^?0^6O;TG6#_XkmobI`D1Y5sTaVku z6@K4ep}uiZYdZJgB*;V4CP<7HL7PPoz;O$%mTM7~L{*~gxWB&V%nUC>4JGbIhTFba zq;x!&Gw1T1Z_a*wck_pDxn3|zEVXQL_qfOvp~5b-)r3;MxO-T<%08^iLwWo9?j;DT zp|D^?GO?gu?3EXhc_aeEwSNM?P|j1sC?dIRg^^#Xyp$Rt1le+jh!homv&j!1UeP6&3Ig3!;(In1T6tD_R|ImqO%Ovo7($X2-X; zJkQDx%j3uGwrmd7$_s1@c>dKtuj<30JnnCoAX)Dos@2<)n14L`%F8Mm9d=Gk4&!se!VcD{AwfzkmX-*`&+QWwYw~EHe@~Al zw3)Nd&L)0_Er{&P+a=Q`y=mA8H7eTmr9s1RKP86~-~{?fYn*u&myYzy)G&q^o-YP^ zP3xbN+}KF}KTVt_ocUAiY^MJ8=}u#F^MekotxB(t`b!PToM)?I1D`p|{)F!=s}F!sil#iK zCZ-ThDNz7V+z>zPn`&GAyJ)IHS3C!!><@V}+z-P+-22)6Sbs{4?SLS;1x4}f+uK}Zhhr>FNk?aHYYsqyzkf)hbAmE&mIr;)-SLKTd8(cQ#n<_OL>HSfew>v zRTgj#8-Mw|paWOKiQ_;?Qwx*;tN1WV0<4uxWgi?A^(%QO5s2=>TMJE)V>u9O zYF{1{UctOhxb($O13?Pj4#E3heyrJ-&QQdMLQ4Le&UP zxKN+%RLtB{F%t$GjmtTa=*pr$#w3P=_j*L)d0XzZ-g#57D-n@EE7Z32`OIVDA zJ$-PZ+l3|6#lFqr$D6<1e2rA%i24g-NdQn<@@VyA-=sXQ?J$slj3F`?7uZGiEPq=N zV_QH^lCg$|=L(<}N;%3-j3rJb8bLRvZEbsVp{n)d0mz2=a@KlowL&jidq;Z&SeXi~ zW|-%%nEE=nw<NUb(1xS$WdxlZ};z-G9>J3=fzi>`q+L4JJ}My zZw*C~ksf^oU%zum-qIe0ZT$PH4u8M^W{zyiVNa#9BIy@7b==5K#pnj6TksibmZBcD?0odj%Cm-#el99= z#)*X)CGr9?V26h$m7_R>cnYu&>dZdyG3gu{;vpa^sncJpS<)wA80{UxER`anNFo=4 zVBM$xiByM|2d?_bH9u$0aDR@B!PufzL&|5thOLfopUwkJ^E@bX$w=5Igfk~5#|^j^ z2+lA$!-$b*O-@h^8=YfulDQJ||JUL$fa;kU;(S5YW(YI$@^y9$da8NFfnRWlq|%or z751p ziM6`~o|Iq~cpSdF3JdanqOZY4zV)Z=OgHFo;!c)9}$As>F`A6~s9&?ZI_wf12 z_C~aq(!{d4tQQBUK5u$HG5wf97gUbTSx%etu}n9tFl$e5H{*e#;z3Ms8mZQev0LQI z#*|(k)mw7=m>}+b67YW!^ctt1XDaY)NIKJ=pa79~@Q=%h?koerb_tV2Au3Gdm_%lg z3EOE!rF#ezgrDV5fz5;~f#L*qVnG}@snDC2^VQ2C_mP+|hcZF3L|__GFnNz~90h~3 zU`+NzQ#)-PXn|t)Ch*GsiwldBx*;G@-r6sbMyXqVoa+Q^^FL-qbv3s@n1 zI?m7C_B*f)pN^>$IZd|%^w;P9%fA+TNVNOVMR=h*pu0yGysZu3VdK%Rp9dczU<9KF zIg=|QB7e9IY_U7Coqrfq5AaqbLoXmiVMci_PP&GeVT)Xv)4;O3*Fy4A+7j9+{AIDK z@2euIED0FOc0+xa&fr$bCw0BezXzQ-;Vy}{gel%5a8O=MsBgm!Iux@kYj5z@A==_` zh;kJos`G5Tk`JtXwObv^Z3w!~>yY5b+GUNwIDg4rQHYj95W@6C1neo=F2WD)6(e77 zD^t@KL0_a1JJ*m7pL`XbU(w0c6`UNFChZeC<_20GLx0T@?QV9mg%ZqxO^`tYj{kp8 zqo-jLtV+yaV@1?bIqCZ9Nv(-bbp5kIWX8#Vg8qY0Lb{KEH4Fg?xT4lrJd?Im7zoP9 zASD2C1AJPSxQ$G|}&{rNaS zJ_~hiqBr6P!|GZc4clhmHL$JjIS|=+nU3GS+Z6u$j`?((tNlrEsL1T-=C#8BeG3l{ zEj%W)@BsF%Ko>>d1o3eCwJ}27Q=s6a7BaU!F0JF;Jbm=M&l;eRR(^qTJfS(9+FQlKI<- zO-j>aqb29u@6~q*;RO>M_M8@>Ct-$9+act8_b|V4#@6PgCEAQ;#)c7|!N zqTsQz_1OOavSX|PB9jp%DVMRI11W#y8`+ZExbc0yLV2Sq78W-^r~I;8>%?1oB?AJ|2!ddDqwj8hdwKEAb7^Lbl9Z-wc6l|k zicpcxbgBuZe0I5-y-I%G-{e)X%r^6duq=78oeQ2c`E`{wMY;8pMfm@*gnxgQ92S3v z*E}h!Rk6*Qyq>?g{NbDDT=(BeXA4e=N`-&ji*3Cts(b|xYMs2DbCZ1X<7S=v!7kg) z7u+U!<*#2;PJb-I%|BP=e&>fj<;}WuD_1qFVe^HQDQ;=~mL_>o!yYWz0A%huZ~T+l zhRhdA>f{xF^8}`hN>66%QIt4HdfJ=!<12_CD2HyhkF&55|7-jvsUt=3uK*RK*i*0`<36}?4o7gr3 z$Q^zQZfx=_wi~m=Slcds9*0Vavw-?_zOc!k<_m^Q89fF=m{J1>C-yv?6>MjPh?5P( zL)t#VlpevFTX;fs@VX^}&J0Nn4M=k<;An{!+OMKfE|H)KU}0|^zTdPs%@z{gMYWS* z%B5fO0fhqOfu{y^!Pb8dnkoaC*w$Alwm4BV;RecR>Ldp*S3R+@UToa$PEg##TR-cR z0#1mYl9J{AUQ-tK z6{5#VTobL0<0U(UQLq^(BxAJGCPbi)V1!XK zPnRjJy5I^x*K&Ad9aG_%3%OnSu@?>C!;iZvuj|0vG`T9Ps9NESNYGWBSd-qRjycd6 zMY3D>*z}3fX0U(F6T~!4mQ@aZL7;~JLp`xjD*1Q5Y)Z7wpJFh9hoY42UddF{f)TFH zLl1V+aYAv;j$vqsWcom;b=G){c3EAchvBeWBTD7|dL6||5o`HKZ$FZxAH(Oslp`Ib z2@^-j2j(U{kT0l{xWUn&Fh)$0fxLKI1J<1Bbm%~V?md6FU{Nh9I1!Y6DNPZlt5t_Z z*{0lHkIcpjJm96X8xwzO+9}I&@p*CiT8&`<9UBX?{>R%pnO2_-Z~n=qV5WVW9*?BWijKZ1w`X~I#>bD z;SpIHY$U+Kj74d%i6FG^FtpSf69VZViQwsR7F9z!{3WWaNqV+^I*rqP`~|Y-+~vo& z1!oG>aS#4{)*SiXLJ7j~R0ODJ&`_Q4oxLl(jpct}V}0P~%xqp2@8{raLSPBA?|Tv5 zl(z#eIFsxYcZZ+i?qKH29$c(8ZbsP3w@p?=?f=3kVmP7+w4v#-yo`Ckyv*53bkcx= zTv!xe5#U-)8F^J9OwB6r+OQm;jqqd*b{#Zhy9X4#62wsk6MnQ%yTdsDM;Q4GM|Dn zlIdMC56na)yzexbhei5vMP5I)$Pb*rN$X=jgE#ytwhx4q=D>iDAb9`19^0G17gI}%uwqzQn{ep3WyCV`VA-Mjc*VC9Bz%-0899K=B3l4y;UM_eo&!2Hi}EGH zrxAO5(o5%uwcJgkeuc6JmSOQ+2j~z`kwT2Un6Wn?uvlP;73Pa2eFsLu@6w~eWgKn| z_ZPiolciO5me}08wmPK0$D&78H~@b(!4_(G0Kh;pswp7oGNW?s6te-4sh0AJHKk?T- zO$~$hPCdIajl0I$R=!z9WnDp}tL0Zxh`*JNKWym?5};C*P1d+B6f8oQBgB9Em1SIT zRb@B1s|(XE!2s(DXO%pesya-%x{xC=wy_wvlQrHrp=JkBhmdAa;b@H{*3WmlP2s@m z8O>|gw$j-|vGAFU1V9wv|ER}?9&mPtW!MaR>Vknp&1IY zNgcNUPl7WOB8gw~rpjCq>6EsspGz#m3Ti^#(vQN_z7B)(YIG<6=v%SMZNFUu@7!RM z77m=l2LA(@fos=|VGg}vho^Sn9@gQ}@V_ksMCIE}agEaQ3A1|0*bIOCJkRahSa+3s zxugML7%WQ-PRSGKWxM5Iwp?HK;+YPUsZR@p|TG9gM2TPP+)%^v0Mzh zV&DdH>rF{m_J@C{b2MjXEceG$$&e zAqqpfVbsQEy;WD!AwzhZQ}|39hix?D#FeYQ(DwX6U?!YZ<`O1hVJ!V32!(^`qtQ#h zjCh<{IU6jDXHt>RSud(VRNnVt98!o$SHutNuO}RvPWgX5i*7Q=2_C2M-6eqgHYeQX zUUMqOyd3CkT;-N8C3(JUQv&L|+2 zAS;-n9yCw-B%vI41_qC7mDkIvchLl%bIoY-?m}KJFa!%YQJTe zg(zv0hu43#KBJ57{G1O9T_7x-{dcqF&U<}j?II@`I(_jUwqECvHsW=@DMDki0N^lE zTl)(%l=;e!%YEYq?MDl4fp2-{6V5j-0q+tWScow%+r_Puhe=X55n@E=4=%Eqvh}FT7jb5+L3ey@DHEt4 z&;*{ZMD8+y^6qjq7a*tr5;I5#dspd7Qdiu%t8}FVJOR{$*xs0c=c&n9E+&whUEzHX`fNt-PCS`=(IP+mL;y;yYApA2VufL z7?*#+C>ZJ9!eD!1ID*zJ=Um?-Y2BOJy(^j4FU`E-V9rE(&DRjk_2tLE)@ zXT8kWp`q3XFt~oZ+Am}Itr4T7AW-~l2ju>$qx=XI!a+!^B6mDiJj$gW!Ppu#-dBDII^C_QK9!{Y3J!|4#2^6TUV;6S*y}%1y8{ zg=^23$rfFK#*Z_9%O!?zaP7Y=#NnoR=PQ#je;){HxqZM;eDtN>LQv*&JqSwot(8nL z;p>g6bQzaom;f8Cr0N(*W@4304LSzffY=@wP8ZRC}XD;OggP# z{_n%RQ=>icxY3@tmw|Wm2$=jmvNI(IPb=;_d|jAi6Ctai>h6%0QR+TbglLZ#7Q9>4 zdg{Le;HI7z-a_uqGc1tpROCE6$3mrkBUflF|)*pJ@=3x0WV_W9RbC5#eFElVyg z6C()~Hc?g)N_ldzNM5Jk6jgEl_TszGzs^jTmS;pulTf63Lpen%E_*$H5=D1JU!2dl zHtFkFcPt|^Q!V9Z=QE+w<}c?nrc`>{`KQyoiM=SJgk`*a{%s)XjZPA6cW)?bU`C2G zcRyKbXSe6vq{X~hS1+JR+4OzcTq8|Y)El_+w@aj3eh81RuC~j(eFUl2b=j2bRcOms z3nUE>u074XY~0@u`1bjK`sSRqPp^uVyVcah4I-IYL5xghOn`taGJkPhfJg*O8+gAX z*J*1q>=K67u?Wc=(b?ZF&VD;%&`cASa1L@1JW)~+E|U4p z+3UA7S-`#T5=t_mlJ}nS#woO$on`XV*+0*|bhbLQKM(=W5|x3m23uW(sg|@ysfeIi z!Ug=WmN}Mr?V`zlOo3j>c(a;BJ(wT?ssIzD3C%JjY$D1f2;F;+FQVcEmmp9%jN2hJWSB#h9t;!R?4h0wF^oN+=R9sLTIquhd&aGQA=YNeOi)mlpiSPPdgq5; zkb}or->j?6by?rwop#$auG2fFjg(^eGYn8!j2U>j3-CyBF=F zHUY|M_wO2iHLQtNtdCf+=*Fd^FAJa}$~Fj^Pqk$|)t2?WY*|mTINi17=0MjRv_ekn zxhKXr{IWz-b(^@JFSaDj>C@SYS)> z-+bP9;0LsMjg7(8Tms@+SD~L~jrSHsJ+I0@flc0L`OZ92TQ9dbD%Z5W?9u4-$K3IA z`%?pB!CU1D?|2lcap3O%9RKeIPTFwYMUCHsLj)?8ZXNHMrZ+gkMX|*H_+lWa_k2OK z=S#DH_BKry@*3NEBffAOgML)1Kl z0{zqX1zyJ?TvUm{H)TEe=D~)?96Ihkz?~b`O@erwy^Lp%z}~T5g7t5r9*q*w73?@u z;uuqVe}0H7G2rTUge%D(gR7`Z(uC_>KQAzU+sXt$4v4AVastrxnP5Bx7JH{QSvlz) z-HPT_qBjW0CI#i_0Bja)5iZ(%(i@=7hMoW$FRT0}T;{8}Gumr#R*TRQ%?~;CfqU?ch0mhbOU!d?oHK49JZF7pmj~>B zr}6586CVRXK&BlTt>lDi_86n}^QHr6g$YDBirj4LaDhk`?$#e}+t!5@LHJTE z;&arf&v_B+2Y{y9>E&jm57SpbJ&J1~+1XjbZ5$$7wL=IlLb`#Mt3^5YYKmfTS`Y+M z2a)7e(bD>55sw6l1-8NEbx{Q^5SAE!Zu)8fU9K=E7zC{{2lZQG{s1ux`!1W(#m-rl z@$_fE{DXN$-n>A{-R!~jHAZJ_iHHQ0k}9|20qiKz)2tzOGB$e*PaIrK1gJwMr_G6$ zS+ZCfa%Y)EcC(O^uCkmcnjVoD@8Z|Xkti=aJu(`RDrS>islJR#RcLcus)}TPkU&oq zt9T}mG6o48{-8rl@Q+vu1Q1K|SUE!KyS zb38R-f)b`>$KlAhli>1xW(_@mskrR9;&+8Mgw#gvBpc#6jAxVAHJ~*=#OAtMZ?B?& z+5#eHLm2kJV96h%0e1$oLoAo;YGhlZvx_n&IaLp!?&o2n>u;8X(J>CeH-zX_+&#M7an_}KoS5H#XAfgO%b-Et zS&JROd+C;>`wV_$=)XSzE0j)S;c#8kT4Z!c%%{p{X&h>N$*`FJ9kOP57 zyE8%E ztJrXNyyMBP;=2o-HLZz%Fz|P+R8NZ&Tcr}3Pf@CmW9|u+iVu`(=-FIq+jUp#=zeX+ z8PU>hgldSQYPesU|5~oDS`Zj2SQbT9-kt;0&D+u%BpAb6!V<~F6u`yffUD24+X~u) zyzcVO`dyQk(a=BBf>0l%6k(Phie|2Y!38r{DRmewiAP@m>dVo85^LN(w+M_a#y}=G z3M=@@G6;60J_eu-lOho|1H7OQ70B?mRA{_J#uXcJo(PkXOzZtXqv0DwA^}uAUzyCF zv7YD5fI>Z>QYJP;=0RcCkgwwomU+O@p?euOGoc=1x90WH$o5U#j_kejp=sC>b9&{a zJPE?;$q-haJ`%)#>Jyyw_~cq6`O&pTcgjFrQnjZVm7FlogBB<5T8;{VO%Vdq6NKQ( z`tWWkJ-NX zDBFKEQtayJo?(eHaCH^s3jFTA@MHRN&eQ1C(V^uLwZc;JXH~2FxrPCDg8YP4iyQ1#eLPJa0?`>wJ&yoKMDcRuCfUld_@iX)=eJjs(kBpS%+@QOYG)-3zXox z_Jvf4q+}>Obr)@|4D_@sms#Q?ZGmTvlq1VD0+5tGU0tO3_`SSdHzV~>_8Aw0?{dq# zl~+y=Mk=pBXPA1%a5!886xzS8TR>TF=T6P8+qJ)ccnvv|Zjspd`fO#gPkfhXW|@eu ztqD$)d{!Vn2yduOJ-@F|gV^ zry9j-^e_f@BzO^-)EV{XO=f^`+GR}|-;* z%vxW6lR7~`o-yV4bQR<(jteQX_Xn4Qy}|+8v9gK|+vcE~G0Yc9YW4Iv@fcQB&+Z-X z9yG!!mET{F9R3$@d29xaKQ(EN%%Ge&gMtXo9_xV5(JH5LuFBrak5b&HjK`_x3wHgMz2aKH$yW8I*SQ z*ENPOE4WV<)Ktlzp#4NBWHL^N~*7ngbXnh7wp zPy6A|f#zNA)qI zKdaT}X1=Ye@O6|vdv3{NghR$PG4?2bhyAl%(RCW|(f#72aHtCz#G-GiFf;9X0h|z} z(wic$w^eb|e&EHm>a<+V&|mJpSD@YZ3J7RQrh=xx!+AIq*7Zp4@fuU>;wI45TU@)T z@o$i#`)&?4Y^wFUWpU%wLQ9D78KhF(K zZXpYwy$(d>s>Ee4*E;s`9-s@6!(vdxQUNrcpFS)gDo( z;vY(a$A#Z&=}p}e2BN8f{Wh9y_!YH|DPE0X?B4ffPKry~BJfGIl6Tl4@5hcj&c3z! zWb98_T_v7ZAela)Y50gRK}KrDZX_J4_D zNOBq_lp}$)`}5z9lIu2QLXf07!j9zHkuVl1WE8F_1fp73bWAy_4(BdZ4Ph|VohlwgE4j}nEb zrL#ZeAqE=$C?nuvc5Ob9610CrKuZz{HmGm4pT5(uzKxMzgTC{wzH9Zo3-5|h(6&-? zcvEa>QxHAvT@5Xh292SlZ11L5YA}9_Y(ir=8ZR{@R0^bFWiP(ZKW4Lp8WV5Ui>oqU zuk4eK->(bzx@>-bgBdS2rF+OeU8N1N0b`MPQ?HUQFBe}zo1j=jYLb7CJ!w#-!%j>z zQd$o=v9e1F9ZnjU@Eu7*A_?m=goSK2pD?+V+q0#CgdrMP&@ADM#Ao?3U!(23;Ah9)RXzzj}X0{A3L#h;r->7Hu2<*5rX9`JW z0AN6$zra@*62cK*UAp3Cy>aD#zLp=0EVEx>=V?)H!h5q8)NUzm9%6@Mo$fLiGh7=N zGtzUeE>i}TrbRVr%upJC9~569q2!SG+7o{ur8Zi$SP((tK2>6 z?#U_xIN<@4#$AEJ!Cqy7g7LeHHc;@rhF}8TAjdQrqk{Q?lijp#GteW+#@_e%7C9bvmVDxD|_y0^+p7$RCfa!56aDa0YBP)GwAyud2dM={)D zW!orTb!;{6ro#JG>>_uaTh^Bi ze*NuF_vU?iQMzBD!P{)9R;Tr=x>>UQ;ni}P7GHj>6i%!of*ceHQfrbxt0^#!&j3Wu z8s06I>tdd-U;+0u&msRX$YU#;lFB><1`972t$OgMLylCzpPl-g|-<`+Cl5O z{+chdAnfJ>No+d8dfKT}?19ODLehfGrD*%=spI?^g!pKCjF6)N7iq?gy3N6k2JnKC z`x@ZGM>Y5+@xONL{W`c!TgCX8!YU>ytiEf#4U|>ToANsZsH;JE2w&}dubrt%=Vj?) zapPMX_hvsOF=APOEgLSd&fVsuG!j~86!aZNOXF!q`+O5*EMt=?oHV_lK z%IY*IbOOY{r(t^ls4?H}kK(Y_h0=#;y&EIUgo8wMgQT0#eOC%P5a3fy^t~aok>M_O zhWn^P%%31oqza#Uz*ol9qm-X^*#Sb;; zK6-Y49Ei2vVH-X8D8ggqd}&ma=zYWFj=h|k%7%9U8-dc`IJPtXcj3zrgjN&6#7-!A z?fI+*cQ1=v@sqSQ3>#@8}{aj`4cL!-%M#ZDVv zC=L#8s!rWTp@FmjRCJq#!!3xkmlDlh*UgRw(ABt@QJvZ34rIl^RxW&QZP;Jk9oQy5 zDZ#-xWaT9-do)%fo;_G~p$HLNiyLGsA!_aI0A=KU2AQ@`o!B7ZWX*6F`n?R5BLKsH z)fI;p`|w^h7H#gmHG(u;2M*-aC=jT|WF$4Ny6u$Qo@)s3OTEVtmL7y?d*J@v@i&!dW7jfkhZc1u$~%)_0(ioPmRNRYJaTvDjZytuqlJ< z#zdoFpBmL1spI$sF&?{P-Kl3&CEp%@*SL)!S>(?QdT-RigUyBjB25#tFV@wNkJ_oA z9qX0NL;d!$2A3qx=I+fPu$1jLeL)+vwQT~&G_H+srfRx4%pp#Zhin)+mq+td1Jyv(!kDY%=k?XG)w*Y^dKeCEY5s!4N38j2=I~%=;{yd%t%c9@r%lk#@uU~H#Xo}m?rKfi#F@>PU1hWE5gMS;kf=3A4bA|@RUnir<^fPq&1Fy%dMyX zE#=$~7Gh*bY^WQn2;*!tVZ<2Ye+T}j97SuRB+;A$N8Et#SjjHcSX2@r<56v*KZR){ zim7UbJWwRX?f0m6U67F13 zHajc2%WB1+Llea$R>OFI8sQ=Km$T`HMR3XCucERVM`^%vG*MuQC1or`JB(1HNo}U< z0P%(}+gR?-srrNx0kcdDsm#1YV2rkF_EVs+ClMGJ+wI@tXnVvALkLm4Q zb<5$T!}MbPdo;Z+o|)q$#W{q=pYO+@pT_a(o%zFF?fF~$8 zPN-qW3a;ULU{)GSya9}C?X<}e2#O4oqlt!?N$yi@;F=6Tk=@u|^@%_Eg{(XzriNF! z2~mW`W_!gLFUs`;f6xbn* zNs;kHOBwx~VQ$4|XCB7fL}~71sG`EpLXpOO+{_uRi$8 z^m8&T{9|*UbxJ?v+e{OSviD`0>SMXgf73jhWckdelUVdITgPrSQ&eS7uk3K>C1@Vv$a%}7a3f2`D_>GJB$J35-dmq0BzdOdn{ zLzjqHEyn<1G5YQ5A6GwO5vWPKFw|v8l;BU{1`k@G0DoYRQfWoa0>vH+)Wo6zGFZYq zLn_4?AU~W+K?5|GNu?Y#zyn%r_G@utb6+tmW}sG}7CXRLhJbM`DDlA91zC?Smh{)N z^eq)~f0fQ!fmxmvwYY7W6#4vfSmI!u@o_R}vdI!O^}2$An%gQRqxYm_fd8gXxWIdb z>n!e*lVQD+GBTW$*@L1b$=34?O81 ztTmhYi&eQJ_f}AzwtiHD|4&^nyo%RjFpO#e4cIARpERC z?8&ET`PoAgfG~NU08Q7fD%b0 z949qOuDj7R7GCPkT^iXs1nFTq?t(;USn3&xIEEQj*Ux-4FFHz7QZt}M$EQ?L+F>D= z5Ee=o7wTuIZ6D=<22u2FS4_jOOkXCVe?6FYJnVhWirp^acVvywAPr56-=X0&x5J;2 zhGSSkSr4z%b~^5P%wk$tM%bP(J3a`rbvMk86``EO0tqDB@z z3_)`pR-aJ?=c}UI5E{|8iHWtksR01kRClKYM3Gkh0qR3r^TLZ z;KTrWizanOOSH#{2DH5_tQCIsBYLXayj1FbQ z{>1z%-=23Dgkh?Yx_R7_7HCy$jcv4~zp8owgUTEeZcN|&L%Z`%4O>U=q)zF{~$8dE~6HfYCR=dPD(6U})o!ty!OD}f}aiCjj0n~jdV(fs2hnomBY{$%4 z7%R`&#s6}4e8yK<`Zl9uLF-kxOIDf|NbOyz=|AcI2=NGWU`L&thf(8M%yW4ce{>lj`ju4REyT zEfG7tC4X=9l*0|z8ewVl*I)kSZ~QclRRmbsw_zM;IC;J8H<4Cie`k`r65EClyiV5Z z%`){PHmhlt=jkFDv#7vUCA?WSis0CAdpPHcD9a9&*4a*b_|BV1L|~v>8!2C#|? z-D{mPpEgO^u2al?e@_gH9_Nci*_RJDqBs89NY9C%2prDoZz^s=_XlC z%SYBlzL^%T^CsQCO5ol~m?q^fPO#dKSU5#W>L)Dk92TN zqx(fNP1nS~{ayWJh#Q(Yj{8P2f6FNjUSP|ZS1tThdzIt{mzB{XE&Ny5Mun?X{e!{A zJYZQZHOOhu{Tg$8bKsi}UG2rc%CL{fBB(ZkeILBF7o#8a45ZGh~0a3+CTeTbf59o%kZj%U9 zDFHZ_F@^ysf9+gLbK^D=zWY~bZgOpe;QgqrRP83UlSkEVC0TFnVUhz!qHS#~$&u(d z`S;rmfD}Q26eVk%OjRyp4n={DM)%iWHyZl<=IYb8Tu&G!jyg8Ext&-=sBjbQG@+DF zZWfbw)0_KpeLWL`O{@D7FZgu5S?>H8F6 zy#2O;fBD(mXsKA;(fS3GL{S;-2Ool|%nadnKvYL4cM}ey>!`u3X8dKXna{HVa3e3O z8P}dpv1rYQHfFmVj zY^!DQ5F}fa+vP9UN==LEnoZ%7n`s$7+T3PWR}t0d>NfW>2WZ;J{Jedva>H;%B(;Zu zeOOFiI7yh;yb5=! zO^3Fu%3}8fD%h5baO3BvVvVC!%W7Hff3mA1HDRKWw8$)vA_k@+h*MG6_qhqfA__pH z)?!6+ zU_`={m8FCMs?S$f?|!6{1$+n*f0{@z`e*;>YQhbX3dzI6j@H2|#>Zt2%%x0Ef3dvAq-diN zXpQ!0t-(>27v6xNZN%zBKX!nA$oK>d)1`c=%?k=_S@SVAuPhPN4B5O8_)2}M&Aa2O z2Y+J#LM@vIowCe;kTN-z*mRXcR^U6pUwx{}h;t%3Neq*7z^`H*uHQ$R;IV6Wzd_u3 zUf1wfRN;f$%{JWHt%`?-e>|)~yfgA_OYCq36SMpH)bn*MB=-Por)@@)N;0z&V9xrf zTkZbzv)Ax5rUBX@BT-<<_|g~o84N@qE1M`-8f#zVW+{^e|Ah#Yc$r{GDQru(9nWM0 z*bKZ&*p`AjfmJHv7#lTth^s1{d*^-iSgpDHDZ?^rlmjEUzxytme~}U@jx)(t_B^=8 z*-}6&d;T$FwO)cYK($f^-6>EQ%G)s$`ElS-<$9j=ZN-5ywie@6c#{wUR4>OY?{VHF z1VFf!m$2=Rf;Q<6ZAu*yX_J|x#*%eI&zxjy<@fQiTSKDzM6^0wObH4wVwA74=uEx7 zDw*%X!09hpnYgv1WMZQ?G%}QDU6zYZWh1IsM-}&R zAq8tCA}Kqr>cfMXIkf3^h42mBMFxweBuf}^wB z2|%((s|$iHa7N>?b~My}pD!$0ae4**U6$LlBL5ymJDYUiLh5*B>i}=)g`q}wp{6S) zN0vsJKG$G7HsxSMXUEtSbHq|MXj9IGosP>J66xH1gCVJnBNOCFYUR_yKHt+F-|K2l z=!V8z)TO$1WA^WP8L{I)60|1?)bC5Dxmd$EZi{(Uf8Q#q1I8Ekn|x`WP3Q4TzBJz+ zWxJ`u_Cbzs2{0AO&cn8Y0+MOFRnI2cTMWN@R&-qP$Pw+nJA6bSDs{s5cB}Z8>f_6 zKj1_uhB+^E2|W zTTZB%2(5`5F5Y9pO*>H`5sX`~VDK2B;mLaUe}(4}95G%1zVa6r+VaIzK92YZA~-vX z_#A952$?XS+{%T@%CeLhfn(kqBhR@H+b%?Ar7u z+UzK%qnYtxGh;nO;*em=b}{eO2=*xp(b{b37@M${!Y#qD+%gdg3rO-sxFvw2;H!m% ze^i&Yamxdh3Z+Jt;MpO`0hP=&(e-XvUo=r4Y_~ikQerBvUx@CMa{UfjYUC&FzjomS z!VE>>kpS?IE>|B>wmUauvC+x8{3w$39zy}DD?}Qft88`*(4v3e*nC*@W=U*5f)+<4 zQfEli;nEt+1|po@1D(imX_c>=0GqY|f5J22U`1qe!XX}Jh@E1PMl{{613MUyscd65 zw_C0rAp^;#Z_f8z%mmO@G2B+FjvHM!<@oGazF~6thEDR0jtv@L?t!2s|1f+EX2P+3 z@&r0IumhusfC*}!0lYjbQI1&9AU6n!`ekW}<^*QU4fQR*o#?KQM|W&gH_G|qe+_5$ z;=J|LIM^{uxP+0wb-6OfT{pLtJA*9PMGgG*dS->lwoIeXjp;5t*_%$z-Z5=g635`? zD>1!!Ucrfn?KwLU5aq= zep&3o)ndE6jh}AzZG-W#YPrIeaI7#oH?6<2jDP2w)oQb@U$!gDD8+KUfBziY!?*Lm z8sOI5wpf&nrd!2MP(o}xXUGXmPbFO9*rJkiX=I#B(6$4*5O{ zbSi+@_`^0}fy?#$;b~EJOg6e8-YU1N zc-dI?qVzTVvOb?ei8h_{Dd8-W1jdaAclJplXf%e~k?;wGYb$oU;;-z$P$P{`^!^soq~LU<#(EwQv2P&i#RZx8QA7 zBFfZ-kC~qwl;7r0l8eki@-U%e@e9oo%kih|>G2cx z60WT}IAd>HXY8r+&8V1*2&s>qv1ddWam>K+m$X@vRZ(r1zXtJc169SEG$4DoGX|;g zc2@-zZnle1f1ozgr}ezt)~zo7^fSbu-@<1h*5J853??KCMJB{NIt(BxTO;hM-LZC& zu%`37Aam?^Y9zk)HG+=Bc{^qt!n0^syjb4Y?EW_(Fgz<$*Yx4_o5$Hhd0X}T+=1Sk zsmr&zIHty|zf^-io#6mx8*TT^mPp1%2G5}tnMpj3e@(fsLm9){-oU5$108h}+OAlY zDc9(1ywUcVhtqzCNDoDsPwH+sG=!(!VOLkIwX{!oHU}V@KEwYN^9`hy>-zf<#ad5b z;#nUz@m3JK$zl)Q91p+xvQhZ?fN;1q)@Fnx7OQlC6V{s6+TsSl{{bji4YmqpZe(+G za%Ev{lRIJ_0XLVip93j>?OjWABexO0>sL@Wsw#x>epD(|DZ8?Xb91b!9M(S25_gxe zUeRl7|9w7S21CveGXRG}Nm=iS4}lGIqw#&+4Gi@C`N?Snz{_4XQXmyh@B3#bvqN!y+cO)ONOWk>z~nnrgfX|>q4yF-=bt~Vq4U*$sRmm5a=yM?RnFzx zJ^FWbi|c5p@F}`OGjp>A$3%s>RaK9TdvN9(T|aooy{f$Uft)R*u=Ddz-o>6C{OGut ze-3~2@9F$vc~kv%wR~7#eW~8xT|IqV1fM~R$`SExHOW^`Rd00u;r{lz>9_vj{pxvr z`&2i0SY5z>C2IMPx7F*%b>;rmr>Ec%n2DCVR`LX!|3ZblSzh@Me15-rc)EH_&8MbB zSxlGWL|RtKc$b`2%4#<iYh>C+r8!Dqq}$LfB6tW7|-Od#QZ*uex^)V+$jm2S1-LdNy+3m`Hf zNe7$LmXNj`4eaQbW78ER(S#(%38M;~inxr>u(mjcq0kUuUCp1uG@}PsOAPLC^0)Jo z|DJdN!Suioju@e4S_onopIuy^y#JNXF7ZbgG9bj~(Dd4mRia}$yPExc^3%!po+(-* z_gYRyw399BIB z(E%gX0VDroEUT)~uZfBEBVeuR-^^}X8dMfiZqHt7>J*V`I(O0?cj}CY5^defj>rs; zND-}A$%y3fmRy@l9Y$ofNA!=>z#Uv{t20G^Q?f83DK?EbPk5~NIhI1yglo1CRk5@U zWXu110Hb9Gmg*2NC$M7LqF6!!NBl3gCnw1;3$A^r=%=xosL=FZ=}^Ur{Vno71)$q_ zu`xw^WQcjJij9`ZDKgsZf(othgbj}oyyg*w7a@x2I&XWVKyOE zEMj3NqbLL{0$OTjh?VRxiqe8e$k2#Jgxcn)KuSSZDOiiUI+%g@1vWv1p|vZD9L&*S z%nzyMD}5uu`i&Do&mza_6+)z< zhPFt+nA5KtLU)ox7E;x%z7ER~)!`!od#Tol`j(O`n!>sqW5xx29rW>%-c-V|;LNjq z4L(e~R?^WiJ0)DHZ>i#-p92bP$->hwWFn!6rTUw5e{=4yu@189-7imc?P4*1Y-F{V zX=FBrZMEwbi%p^kY!b!dOuMF7tWx_H3!x0c9bk>n2;1tWKd-OXSIhgb3n1A1L)`u8 z6x%u6uZg*SO0u=)Nw#ha>IPhYPK|Us@ckS&4g{ZnT&3$YKo041SxhaJ!$Va0fTFt- z@RxyY0Ex!z_`3j8x9jdIbRt-P4)j9?Cz0}OvP+$;U0dU}lZ(@&Jh&V48(4-YYWEYk zObV2tK@iAHR-oNUe>zFBfMbXmCzkO{uMP9vES^iK2w6jE`~wU4{~C)$kZ>@+?A{t84*RNkEBCkky-^sxB?H>o4%& zP(Fv*>#6?h*+RLd0@SX5X(G^px@;yX3?b!UO;ZrVU8knm>bjOCoDAV?t8-=&;BG^y zA3SRMH+})>9A7A6tS!(-38K(Pi9Udt5GwcTQ_C8!PpZ-gUSU`YrTQ3n9s=>aO+q6RF>=U1{f4*yeqowaWGiOa9*AJT1?%a+(SlhOR1j$A{OqmGy1(^xszc0-ZvghVA;`{`E`bSZFsedfWunEF=9v}>@ z0*FmQ7z&Qx?m6eq+6^-XXS+fA^8jNMXj9A>CmNk42ySc`5KWj{2fGBD&{Z(3jvE#EX*2vO^B-*##A&%dY z!%$%wn$3Xa0J}&NDrJ+fiv+khF%`S`I=8gDcsyEV(1!H1QKT{ryRlgc8n1E+of%fT z6BDW&xurnmVxE$e810VCQ?P_`d>6vUTB0GK0!tKsliB2!IPJ+~wVBWok);YOQOtN) z2GrRJDbEld()SMKjaE8xSzhUKUc~hC;vgdw!j z)0G!}VbKQKIcsu%ZiT%rYf6}BBx|1bv*zJOijwxS(L|)#IpzT)DKWEK zhdXm8eblR*{@FRz(>^Oj0XQNYc#Z}4!BZ`Nc!@`U-og>g+!+=F>`*d1OqSn))m6X3 znZUb;Wc(XhaCy!5Sj^q1W#=@Zl>Q7-lT*{P1*cMnS8iN*MdT1(mEg@W@wQkQdl9_5-9j44kq;LZ_6WKM)}e^M5I zI_S=+`cAdfgjCxJmfMnX9O~KdT&4q(98$&K$ntlt$OGcQjt@a?VY@!WjZG@Au(*{e zQeHx7=~$8Sxd31zixX2K{05-xr_P5ApZm z!a#pRUwuCtzPtU9zEun7H55^HnZ8)G$M z&9s=skg$>f;N0=Uj!V^|guf(JOdD64-MG^A=UKK$b*>S0`JzpM?%6_rYm_DYgL?K= z@+|H!N?tUVS+{Rw2^IAEgXCG!h5aM&YLdmke0_$!$YO{n+LL6lA`3JVpEW_b4>7+9 z!Tv}|)^vBh>Cz<2yoDs|1@+d_j!Uwt9E-h`y@qy%RbTj|t2qdpg|Wt zPHw-B3mU|0T+qNvFKF0*Z!W&w&+zSjhPQe@!?>N?Hqli8j5y0WmMhv66)rk88$}ty z8GolA1%SmQ|NpIA_m*+f|q zt|awj+vBi8E5|tKA|-!4zi!`f?t?U`L$Jn>SNm5%ElpQ`1ZG`-7FT{0T-_%NdF$p& zKT(#ygQRQS7u{n=j37-be>ond}5zEZ>UlB{kUc)62< z$g9!L2PfGFfNQw)l}4r~L0$}5jXT|*L0*1rLf{t-q9dQr2F67 z+P7xWlh1hlBTieR@N0D;Ee-n$$eLx`PjK=79r$f*yEE`6%afe-DZnT|mWsWvyGE}pt}c6fqG%67N>aLX$u&fN1=+ojk)mokhPR)KxP)H2gH`}_Hp)8>V?ZP(BK zadGzFGXp4$v@xDB8;uW6CFbVUyR%<^)6Hvqe}{)Da=!V}wtUwZr-DuR__q1a*)L~5 zi7CyW+(Y@G$ou)DP3XHynAX&CE|ce2roj5twf-(QQQ!dI8%4==tzKyDGXoDQhSbO~ zme6ca4xQXi+UfJHC2!^e+3!QgD-b#fhbLo8s|T16Ze*d4LF2Vpz( ze_E5FH(?rrSomNtGjDTG-r8uDj+i8in{IHN z{U@q$!uzH+lOtDr(X4I80Hw z{kDMU8{`{?fR=WJl2I_%DJd6UT+Oa|og@L5Pf&c#0r8bCKm|ftVSdod3d9dkf6tWn zx%8TK>9vU#wb!HFUU2exL3x@d||BBkX5b$ZQVlLwQyr4Miq?Rj=EU4ta zRmCxJKi>O%SaB*4KSDiE-j7opq_~O0=q>P)K22hGus28(^{hKDGo(3WiVmd3VQhzd zHnEkIHv}{7h4|{0qGq`wMW)Vof17QJNc*L>0GcOmK6HG{^T?V*127sgt6ljB+(NqP zTw6bAM_|Y9py$;0oCnp}sXK5~+WICC9?%cn?H3+Grce+v1%*oO#=--4Y#Z(>FW~hq z>Rzjl_(!Rke2sRCbs5+)Y&}7Z_EaTTIdH683Ju4gEW4BHGIv;zw4sW1f3L#K3>F*& zv@||WDsLJ4$LbAkeBe88w8^*L7-Cy(vG_1JFhTCcVT>%hOL-=8adK^Lw3-M6a46#o zLflEA&Isi(E;1*CI`c#iGbmg_7N%89Bs&N{WXaIRudaYmA^EK_$PudkAmggR*r-BE zyA}frNrQzL>0atJp3DcjfFH59%VWPTd=$@K+M(Oz<3xifEACRr-W4*a8J3}2(&JS*8-dk7lrB?v`I z<=HN5_9C=^{YYd112pNmrZel?$J_)d{ilNMVQS;)=#c8lwoDD? zN30smyL^y+e^3(+1cE#1M+DV6mwy~M!@^?NwhB8V)-$zBS7etOeJt5flB7?DS%diz zt2*-!l>9M56MWi9{tg~f*%EogGCr65eaOW~PJuo`DlBexQWVfZxdaB{gA!Y8(dNOn zNDqbpp)>?AQ6fZJhx#6?KKJ*}x&2gXy+r(Nfiujxf61Mm3h;7xW&ttlry+VQhd3a_ zqr&!3bQt2u&EU?Iqtb9pIX1P*MM_wsVjV7etmC+#eJ-*a3G>~O0~ySuruu!}ffCvm z6-pfgvdl&-ou5aVLH2Qlj>?85y{*cqr8?v;bGG5+DjfddvJ7FBjA6ZtX0{G&XGPE0F$tN_6@{4JgbIwq}<5QeG{ zKR`VK?`1g!1w^%GKh@10%*1Fp6&d9EF7bdBsNJ!D8mIoGf#a#Y>aA!EQg znT&gEnafHSi)wW)6zLX4^by;gkU5zzsPAq&J6w;TV0X(yGZomHqGu&Q%kXREhCzZl``-fEmX zgYPj0Yf5-o&$I?CCZ!+b4E}?sozjZxkTGDLOvc0Iol$w;y{fSmr#N}-F;(%N0qUC& zf3D>eVl7m55m>Q~XpLB3pZBs9!X%8b^q}bw_g8S#5$h3EYcYoir8z_mG6t-NQLW+} z!dFqPG48M6KO@%j)UD%E2r5k>DiA+nJsIID&mepzgOI~ua4wc}ig>7=WEo_G?LHW4 zkKqM&`q1=}6aiB_`W2zomz?bE95_)Ie>rt;GsT6@M(x7ddrd^>2?X)jH?zLW9zoP9 zGRZ%W8H=^g?*QW7!9qVP8M8%r%a|Talh=LIFK@12o!hv1bG{|Zn=kVDNl3#Qw>u$cg{B(Q$>gr?n*YEFd``^F4yoGz%u=(G4beq57S}ujn z?bV0dtB+S5&h^b79nz;aR|D4dP50^b_2nP$Z!X_Rtb=kKKW4!;l#{Y2y%9n5l+|F8v=c_SRmLF=7*wp?VVoGcq-kF;ppk zR`jyZbXSrvdXBY1>?{X$ZW~|7iLCIBiIr_`ln~QHg z{YtaVhSufW@@$MEqeN^dsA0xX=<`&6WSSzAYh`-M^n=@Zm-ah+SO zGi7rwW2?WOjkO=WW+II8*~^P(KRx5Hgjr?W`P^uk8Le{9Z8n)byL`j4D^#MhTuGCC z2u)`hm$?-lx6|zW**~6rP7ro`Zfq%+D`C5xbDPGhGL0v!p(k7}waP@^H2x%iw&^Ym zFt8cVl~0p?&6w$#x6PgPnasWR8^$u9YmLd~Qrg342rM6&8v>2i)=6mS`)G8m1~5QC z<6@hOKE$NUop!_&V-uqoI%bT~RVt(C%Du6;5=djiL3%vFP40wf9=YGW5;^BS13Hp# z&gixWOASYIE;ASn^J*`aB6rSz?!&UR#dE{-DOj4shN2HBxQcLrTk6fjf|7#*__3owVNBdBF_$$3ky4NAF&Qd|(HOyCrE8#LrX_i~Ff zku#-0F5x?~`uRSdk`p0pX3&Xe?ooKQwh%cL_fJAD7s%x{$%O_+-w#}WePAde#4uPS zQ;&wCms#ewKP>~_S%eaQxf>|l%>$b;M=VK* zMkMcrfe?)los~KQc<3XClsg3Sjj8`W^xbhpX)DJz(-U_TlYD&Plv~stU^co%@?#IX-$Gidp#`{b; ziLk96ClMN37E;0L0iE@e-=RbhkCO-jfJ=;a5a1hIg9AU1M#vn1W`YbsMIUCRbo64$ z3<6GT>krCGaTF_$PTop}(|{q6Z*Bd4Xt_UmD+jfIE_NpGEvsY2z$}b^48z3k{SMC= zggll>88|DJ@o{HX$(Gi4FJAw+g7mm` zQcC)x&J{>QDoQwq;XM4FrLl#p+lKS$UTEIEb20~anhHG7!+_D)ItdIl%v+~){Io%n zM;fxfZz1li_(z>|;Og!kof z!Qv+$%&G&(wz*e{kf{dA;}R*w%KxoA?uO3e>V!N#1o(}u!NDIWk7o#Z8Z#QxM;V7$ z=?(hV#{hFM3AMJQ3H~-@Mz$wqWY_L)#?tZ8m(_Aom#ga6VpT2XY5B~iITpTO&`s1nU!0ARtVi#P z`Z?~b7!}hg73tCHri^uy#hGyEOzWnzWvnRb)S_4}*R%2}{#YfGZ_hx1QEOvPMpjk0 ztQYHL>||NZCucmi+URn*Dprl{d9piyD~sj2E@x%5)b|o)wg`P*l~dS657O{BNNE@i zVOd?3HI0*g(>Uqcjx#md8s~Ub%~IuZ741)`?xt9-s!6Q4ty4w0T$a>z4hP2XuYsH$ zeW2#$&vZ+b1hh0R6(`HZ>~>nl0nZ4JV%#^s&G|2>M-OkNtAn?PpI4Cp<#+{uD`DVN z`mR{sfDg~<6GA(hmo&}_5Lak4zm9DJ_H;9+{t2W|x`tV-8Zjh)Br&8Q34zUFMnEBFlj)_GIYKIvO!GIM@F`5kkqia{ zEiBO@a1=E~swv{n*G#H2Cf}?XMjxx^iwZ1BUw+=rBL#-Qcj+`)kxq5E6)WQNd<2piCPrVK zIXPNPr;%&Tl2XG`kf*Yfn{2cxD*$viHktXh>(!KD4_`A<%W2KrHg6#fDJp>}zu++`W^ZZA(aQ$VB6f zW`9OXF?N?#qzNS5?SH=5wn{tslZ`@;nC3WYpB6IM58SnU(-+feYb+XkV!V@xp%r4v zN4l4z<)jGQr}DS7NFURP$S}Fqt5NkXY%d7{92z z2nqxuHvT@J6m>BRLiN{Qi=47D)K4skEpF?wp~H2ZG$m;cwzU!wAmP=hxz37t^=>hZ zZbb#}Xw~VagjzC_s!8^t?B{B^E~evZj!{=cxoF~-Dh_5gF2=WE{T75qwWzCP3vkT> zOK9}gk6xusi#FZ=f6fx&U&9jle>~Hm+uJh@u?7vk{4DKsQ>)I*&S|6*dVoM9hX`om z=KLeZGV5JmPah1crn|&90W27jK~ipX!iQiq7CaZtKMh`r#Do`hRgxHFa`b9h*6<$^ ziGq*5E=W&N`M=}kyLH6zrX2shD4J&HAMa!~wfZ4mzJDz(f2)_}YL(i>%@Jx|L@S^a zsFOM<=5r#2(Q5Q6_K z_N5ZR80$qAUHcBOeB?h9T)$>W-bOcAP{(aa|&=OHpL)pJJ=u7)1+!ye&tN6sc2wR)#x=3*Z27@cGrsybFJ@sgh^pD*ke?|N_ic22yRN3R$d-l8VccR>^Z-c{; ztM#oZ*HD65-mPj_H%0%p=Y3~yBiw7I8OI;~nc=kL)+7=L#zorOc?Zpa2Zg`;j|1Mm zKll$#VL(I*Wo~41baG{3Z3<;>WN%_>3N|nxFd%PYY6?6&3NK7$ZfA68AT=~GARr(h zARr(LmpFz2A%AU?%Wm5+5JmU?3attfh!{RZN$j#sg2V;dpcYV|X%>tuTSR2i5a|^D z`;rS!;O1NJU?DM2_txg$6)3Wgs0n|NBp zLwzjRCw~`$qub^l)Zd5Ev?B=aQq9**W_m z?n)9Nic>*9_QC8D6kc=WgAN@mJD>FA>2oZZQ}j&_JDqrQRiS&>Wb7X*3Twh~)~7zC zjCFR1z^6WqAnE;noWMbMqw$Yu2~kCR@{E^Y9DglcZ^3@-4Uv*v_UD%wx+9SK1SnU| z`geBpon0B<`5#?5qnjo*PR*cwJQ#%r*8+_?iGOYSJ%SDIV1r%_9?fOvjNhhV~C-9ZG+$tP1MPv<;R z+aKmhi|!@3XR0P8S6MElB&?dhTqaU-aoa5Z0ohRj{F5W-D6`6gMkbdj3IP?fC8`lV zmnb;_6|+m|-XWK4X#o|tJ_-TpE|>C!0T#DCIRP#(m%F9`7Po=z_;{g@7(WU`qAeXoA0Ts7P#{rfcm$CQ(7Pt1}0l*8F{aykVx6AJV=m?kng#s3r z$@l>cmmr1$7z8#lFf*4SnWrJQpN@;+{tw2S3HrVNA2AMe1nlSxzP9)}K{B`nO^&!= zPJ)XQdtRbh9Genj3wx`$(J!#{ZfpnBvwxSz{7uiJ*$J9Havr!9x2uK2O^BR^+#pU_ z@5T#=Ime;6eZ%5z;~htzAKDRZhkr-XY)C%N^}#J20YEx#Uf0``o`MW>_Cx0Y+^>A~ zO!%e0A550Vp3fuI!;l_J8fESUtGGS|ZgjU#FEndCHUz?kDjPdSSrAvk13(`g6BP<^ zoY0uL$}^gaR<^c{_>77+od1&R{XDc$uDJe&Nro-I{bn2kniYuAAv4%%7JuVWN`+t) zl(L?js9PqRWaG=)DC?m0P$mS|tVecSNUneUH~k*N;<3T&aeo%6Ha-e`e5;)n*ar#3 zYiHdXkYJKoAS(lZVM1n52x+VF1@~sc>*{d$5v*x zzaJ#pn9wL{XuU>mPU4;$=*1!YeSqejRkH;V#p#3+E5ae}q_@DLSbue+n52W9d$25H zRMlcsYLP>dB?ftNeK_Q zffT#dPbemp2n;PtFP|xHas9~nr3^?;MeZTW%YA(E`t#*OC|?<3Uc}~ zq&CIaIkSMWq-wkdha zC6HjtM^xKHFj>Twx10Ch9hCRgLYnkeOP2PdrHH$U^?%(fq5_)w2CYLl239gx_*EnA zhAj3hqngtjpIOQL39*1!uBt57a^rpeJF>Agy3apvA0baO&1>lol`Av%e6%dguD3m_ z>IwU%E6h`sa4Y>oClKqNlpsbQ2OC$BU7VL7V~rR~lLP7Iv81RBI+$pxl3m`QJ+Ola zS|dss#D9Hm2M#X$y23vqDXz&JO^2k@5L&^vsh~rV8^P5}K$r7*PCe{ro}`Mj@!0jU z5nrFhyxxri9RxLhNyc~SpYW8kTo$6+42kOM`^aHXORkJ?hMysAy?ezwXR&`1GGzs>_%csG!&CH|h;cJzsZp z&I5Vs9j^wZRkhXrq2Y;H<@A4en6XJP&>iC7ic&oc3@;|xQ5>!ap%p#+3odltUWX8r zm46s@r(1bKBA{>zpEkw2M6Y(zy#NyL@J7kQ_TB0%uLat5MI5s?sjS$jWDGSp%c7?t zaak&X8|k3HxWc~_mn$L@VeR+`!6PuOwY#e z_e%c1qnM~*`1aK*6HQfizY-tnYA&7VKYs?-g;e33EtIxP9mXymMdYW`fOpYzw)=k3 zf9BdMSWU-GaO|K=^icHh_(xx31-_Cv_KL@LGP@kl#gi!gd<|kobdiz_j_Q7JZGXY{ zaLReh=2@_($;L_}(V9bG+k=H3P1ORgd!DDBpqA0YB~N1q{_Usr|^zjT0@GIO%t*IUTi$K zvd}@id))w=WjNo^ zxFhc(-{!c5U1B9pc8H0n2Y(U1pv1%be0@<|8`!27ufjSK2+sLl$u@eY2A3-By2kka z_OX7K$-(*ksQ_-8A~r#gfy>OqM2AF6B2Yu+0uB1N%w#YCthSvm@aC-BAEG@eiJ(HY zto67LuHo|{w7=QQLTKQ5R>#B0)49^AHwcWU&-LPHtLH6YJcZ&MNq=A=h#5?AFp~!l zf3Um}0O3IC4;zNL_#Mn5l4XJbpEgPmrLkZ&^+#}5^?p2Kr1`V$SoQ36e< zEwc)TO>)BFOn)w$k;;kMzCT=v*=*vaeEh(Z8{i;qbAXT3e}TtgMsE$!!6=2~vXtbo z`i_fYkR!qyyjAFQA;0XAm&Lx0Yeq6@nL%N?^6D(!K2X;XdN;Akd(`1nJAXvHdv)S8 zKGTJ;7IJoh(Fbg@6(t@@CJ@+KpvR8t8{kc>79q^iLVx#LV4>K8Mm0hs?$3>I!H2qP ziHpGE!Es*ut=5*0Gq2_Snh-9tj42R8WP3n_TAG55aN{cH9x=(G|Jjm$kzv>sZvLC0 zLSW?=tp48BgcjElsQPKtWBeW)`cq%~1Z`QIDXd_#g2D}fQtgBmC3yvX==1Q z6Fj`T>^;PVD%uo&^u*#5JE7iH^Yq=Bx;Xo@Lh?5l(iOIPzuIx1DH^k#vYliatL1%| zijfE&{V?g-7|w9VOoYSh6-2!Iovf+xSAG0ZO zcf+Lw*OFb(D<71MAUr~Pbk|-y*(t}#J4;QUjR1Qw$pN?GA*y4+yx_v=hzTX$ zLE?FQZ6faJgGSQm0vE}9I=5Qqcep6IFN?pnkLO4^&ib#gc4O*8bE*#BD>xkTivcvg zEq})AT=>>_c~PP>I{BqyI^!D8T8D!cj3Z(_>kI=|cZ%W0SoK+Q(qHQmg^4^z!)Su| zH!%e4qJrXmKi27`-Qn*=qU91?#>;t51=F~VqrJVR);Gnkr9Lv+CUizV=t7u=+?MN9 zS%tkoiSxTu^_(x>{=XUnkDI@_Zn;qGYk#kMyr+&(u$ch7f6RvwNay3;>HQ2r`@wP% z!$7p^J>h!)Y@5)@8I`8uAQBqafH2?f^9)@Afj`UT38Vchp|S+%Z9sDu=7o)_@asu1 zU%c_WGp}#6ZHWN8Sp&=>o(Jzr4yz-OAxezVIP$R zo7;rC-=0q_X;Q0&P||2C$RXY2sDBUNkwg)V!Yur@lC|hP?m*Mu5YIn|syVZ4SgX!p zaEXyInE5H2iCvtyom3M$JH?iBm(Dci6q&HilF$S@;B?nn90mDN2`=c1rYh!nAz)zOFnt$&KoPmA|L zz>AASMgCGE(D6Ru%lKzZ0QD09q0U>iOEh7O(*x0=tny+O4&0Yr-GlLO+E_uif~f1b zwF%gr&`KpL?3`iT7e*^=Q8Ce~3DT0Abobxf&O!+|qH8^J;%IaF-o!6rZheh!xiNus ztGl`cONYmI$@k*bPrv6a%70H#ny{ps=ubwuKb`WyacR^40bhEarTU!J=J95NOvDFZzI0iEvCV4!H;E?St@4FrgN#%QmnQObR_JEv&vJbuM?rJhcPen|GL-d$ z+1lAn|jI} z_^y^5+^@IrdH{L}ZqMh+vDsS=5V&U}G_;?EboOj>gTH|bF2t6ZxBS_Zvb;WTxL<)l zYO4ln!F%G$**dc;&;Y;q`EW3e3hkril^|qL9N!(x_LkcXPJf>s%8A*c=r#-T$<=J!bM-KQg*V(i_ z*RZ#$NNywR9L?*DzM_jFW;OYXE;?3<-)1 zAEX&%vmWhjLw|4pq1>#|jJn+Kf)=uvWX!`1z_(-Vs>f%c0J-zyvx=AX6CQ;fb3i-0 z;5NFey&hKL5HN5Na6MlOV6r(JE$8zOJkw%JKZ=Pg1-;PPbqlen6CI|JHQa3ueBF{j zb<~*b;#zIMQRxEs=v1J{vMHox0*>m|2Y9USARpRuS{jb$^Yuni z>h;?GhBzE%Aek4Kw7er7apAqEi6Oy~pCMpz3 z{iN^Df~mZzb(l3h*lwFX5yqy|O#9J5kJ>C?-MSJj>e&g{D@a%IGE+2&e5*W7h2(=8 zd{jD>7=P8XSASFNuCi*y<;L|6;mx?gz7h;FYS)rPXLSlJNp|AML{1Ct{YrZ0^;;ZK znsDFK6)173;00$$J(~IGzQv@z-RK%MvD-HAbzWCyu@bPF(~t%V0<7f6X`r7)BL;*+ z;KQzY2eu&>c&a32oV=(f?C4zj;NShnWbH>1Ie&^m$X}}KKnWS9`B6H#L?FyE%y7qY z!6;$-K1G%+!OmzCh_tyqu{fn4eyt+BD-N(0 z^XsIhiZIE09L^7lhmXmfq-3vMKfKaML z@PCO2klfZ4&&(epLpq{ zh_?`sJ4mL$QV;R9fFV%6;{XC$OD9WCIsAa~_C!EuomsBA@~^@OuP*m=3V_rM%kXN% zz-(8+)ZAb+ruo`8Mgn+2E|g|v<<0UcUVl#->c*LSvAE_A7&yaXNLTjWl(J~7P7bA` z>3fuZN<9`*?6&HNqLF>=S~4g%P&eXNUTicF9w%O`q*j+q8@f3DSIt~L7cZr+>5yKy zYrq1t{IY*rpKYlC9zhYRAxm6(xq1+C;KzzM>y6n4ig7d&{pd$F?c`e>{}c$9tba)0IXMW}1#6G-%Z6(mA1z0P;xP(>+gLt*v+ zPtAh+(GDsD&4+1UABg;jU?C9$?|&P^)H8lJIu*Z``e)Y0h4j9ey&0fRooomlWt28j z3dYN3<$2&u*Y9O#P9VLo!&Ohvg|7~Fn;7YEFvp7+x!UYAI0SU#mK(0EVRqWyZRZ3^ zD85%+S{v!b#-Zp{-+>@@cI+&@ON&spK^+;W`vGi3>Q#da_`h_Ti z>93OzVVU3X)**iLnv_!g2}fL_JVLC@RIqz9ePnbjtAiv;_WX&YuIa%Mf_e`#t#JTy z|B)#MU(?q?4@M>ghmPHs#eY_YM`%TXw#ZK!1^LfkXoK>?^|{uM64UvrL*X*qyTHB; zE6}5?Ij>Rj7ozA&u2u!o6ogbMB9x}Gq%G6Z5OuV5gpAbzZY*~BeOL$_9bak)(vUVV z-RU7uw7lE(%{7~^cVNEwg=UyU)I5H^4U?t&o3k6kKZp?YN`h>}!GEGh`s09~lZ~f6 zJ@hIbV_vJ z3;8Y`KbFhha8@jryAq7~7b}mej!N9wlM;v@NftYd^ctmYnl#CCI9L)JNnw5w{r?hN zRh%y7K5`Mxxl7I^FLb(EVh`4BN7P_MqC&X9@^UX<90nN&sM9JAxM%)YV@N?6QW_)UB#cktX^k^6UpE5lJNQy^%Frou^$W-X_|!O_qexI8cy)!0ws?mXy-7e z8l{Nkx$;Pf0)H|kmlK}0w)(cY#Z%CbXqP~`5(UqkBfH4`J9oY%J?Bzp;vMghNlC12 zvFV?SrlcyZ$Et`94t6-UvCv|PFyi9(Vs-QxxAA!Yr5)`bOnV^Z1|)6sX|18f7IQ2K z1E6l3hKBu?5P>=WhLXLrbufcY@1|pyNXKtTtpLmkcYnM=$2(cKJ*j>nxOkakB+Ct4 z#x~hh?uBY?cQ)_La0irs$!fdrYc9VCx)li#TZqMpHqVqBr$KVM;NGUfIM2b*iiSh& zj~L;@&*A9M?WYiysMmkj$?@M$?=poLp2i|>15*y&AK-&P9JIE;qs8_2=P-)Q zNgRhZPJd1JxJ&H&PXP)0elI!^@^Qhdo+rY+2dA(rMJ&b;^FMrY?u>x%yaY}q1v_+$ffdmIaH-X4a zq29-;sI4c`*7zGPJMlYOf>mMwK?-G|mmV;iF=eIZvPXHY(r=gHh2Lt-wBr&^zMZ7! zeI7OQeVoY#q@U9C^EoY=4V6yDpS7wIZ(qyYx=2;+xZ!>K&tYTCrEM4*6` zu7Av2P>juz&=mZYXi3g1ly>bOLN9j9*QBtWd?O#@6)&5`U1&HFhyG%&23PJ|HoXMo z&0N?~hd5GI9qE4w2jeYn=_WU*uigb}p~{bnpYki+S45bv*2-yCW6Bt3`87eW(d9K_iog#H*D^}IgO?20FXMSr5E>QD4yM}Yx1 z5LnqN4TqeI;Y)Xz=j01}V>x*0Od8BWE;*+d%qARF!aE(X#`UA5G3s}kqQ_6AwSS-l zihSNKwx$RCG`h^93=Jk@YOINV3xV)|#`OgjeM60Yjb2(`#d-qszxZcSm;yxRoTtJj zKI+OutEYxDUT9ia?ehwhS(ah4K-BgzUfC>J$xa!z6DL zkIlrByI)@B%8A$@l>aw;*2v-6og0DFYz{GB+|cm*J)X6$LUkI59MrA>;uke{6bVaAw`s zZEV}N-LY-k$rIa7I<{?_9ox2T8y)k$-#Pc3TVK_!{byp#T4Rnicde?uHaW4ly`77y zrvreQo|%D(n@B}mS&o^Bi=Bvxffa_FT*L`rx3PD#G_fG!b#rqQbaQrPaB}5m z_@_t(03dR)01%m3+5m_|6cn|j(akBlN?&yeI{%hG7{ns-7ul3)olgGa;1{h{$B2!Bf7b0VTxuqQp z}?%fT>wr* za`vVGCp#i#ds`#BfB&G2Y%Og(|G&8Zi;!|L`bP&LJM({(WBPZ<(plWn17NCX>GF@% zW=1yuNc69`2H@ZOA_p+FbhZ6=J>VZb{@GDedpjG?|GVTrZTxFNMm1p-30WE1{|>;v z(qeWd_NJD0=0qwk|7dCCWcuI0ztW0Emj9lf|B(65G!ZfXe?MQ&$i>OhgGh&o;eW=1 z>3^R8SbF~tB`j?3;Z4uX$w@@d%ECm%%*Mt}#Kp$q`@iU#xH>rj>|FjO_&>e;$N$$L z0RSEV6PWcCdlQ~utF)HT3O});xk_-_xfw$>+7)Kt)#;vF9c0TP3sZxmYn%sFoP2jU z{Mp~ee0x{Be^L+4Bt~%nxRc4LXyS0a6`a=+(n@o`+U<9xg13fn{TncKY+Dm~u-k}x zmyC_|Kt-Aq|^IktgCVa0EUqcE+%>{M-ByG!l#e|M5(Ng?zo;M|^Iy>@6a$>C{; zByiNZ0pTWQW^^cSCvA!46H+}TD!T;MpV2}G^IcGuYa{7_rT4bjF?pNz_a?j~{@}KNw2m<0E~auc zjQNQoe^mph12q{c4%&>?+)rUDY?5|yu*#07mx{K7^O|QX0{7SV8smrawR2QXYm>hk83mUG({Xv3?kgn5&nE(-@aP z6{vr{1eqLwdF|+f@ry&vRsi`^ZG4^=PQoa>e=2P_fs~lqR}G1GL;I=A+P%#so};Ux zJDP_@g@FqgzLfcL+829ZXNM6cKGF2-be(8skE<21{`jS=Tq_srrEF_Zr4>1_o>lDA z1ZT9}fBdnz2jE}KeZg?E;0&pkC94FZqSv5L7G}rB{Y!9_88h0w%RH`puN1u`8}T|L zfA?9|WXENyyU3J?GDyOf4pv5ytZ*_<$0TO6zd{O4d1ffxv!eRwYiWP;^`A1u;?g095^nI7q=X}-s!LTPCG!ILkR4>1|>M#IaIF_1tnvaN@k zfh{G@bj!jZqm++`)FK!>8`=hTuHRrH3<;w(jSWCGi#`P6g=|^I2Vt@1q8a@m$sE5O zf;4Jjh%^vggQfb`dGJqLz^Cb{L(rW<0~elK@PqP5uXy;kRuf!byJ;n^7(o7xe=;U~ zt7PcamX%FltTMY{Z|T}>{+)J&qe$wPle?u|_m@wKO6DiS?yozkBT)BfN4>w6u;WV! zJyJm9zYCuoQ+`{A@2R9an2DSf_Md}bp2F)tWc4^NrnP9}_4(_uMW&Z?#U|dE=T=Fy zd0s9CG(_(9i@-V{M3g7u)+Ohce?+%wFH3**Xg|B$pWUpH&+RLUOC4_fnMIQrVP^4F zeRU+2-^f_zwDxh6Dz$V(uM}fOlI#PUlM(xmHYXL>zB!5V*VXJZ;{+c_+Y;*#JJ!ObTmo8v4fLsxW9YHyQ#xYerssr&98<+ zl47jNUc^kWDj2eH$AXCvpe`+zZq>rVtoz){je=(I+^k<8;3Gx%1E$Ea@*+g2pb+3M zJ&Q7b-BslrKfR)EI){!yXITRpt~ONvou+)R_Mz^f1P@Z@5mtB(;-27 zg7y>k4cL=E{4v?(ysll=J@D*w_?WWYjKVmXVz{O-;CyMpTVA?BU&0e~{B4tws#o{? zbGIdpbeezc{5eT_xx~#nDwJ;G}e>4I@NKJ<$c|F4X{WdNEi}>u@E2X~QpsApmhxz%OpXv5HX}INx zb}B0Kc??sOuIppK=&SIj1fK2;BaLzk#aBq)oKhKj=H z^Mfn+%~QVwuvF(xpKXE>lmm*{%o9H-tP zlY~_cbnY)Hf9BX4(JY~?3^ed@jRaCs;vUgE^%D~lsl<> zsL~BL9$iDL3ipE57>vu$abt8|^t1-)<+$U*9qtTIYB3d$A|^rv^@l@a zQQY036~D(|P4_`_RvRTo@{|r0LLBowkW3YHe?Q=;M#r~xEt7pn(EhJQ)s}by+l2ob zZK*u%fyQ9V`~l|4OZq2kg|SrP*Sac7DZ%ujM_~Y$|9Ch|#u!No2&%a6kABYp`dVI;w7V~0On?1C&!bZ<~xTOCV4 z^8u@>_0;4R_?Ix1zXkM;IyitJeB7L5e~dffkg30d=N=17Ha{HjSciwr?9m;Lx##Np z&U8~x8s_rT=PpuJ%q)q$C9?BH5CeQs$2_;Qx12P}nb)(fb45h5OfQ|1n%*}pz9*u} zBujbiqHy>W{V#%lV>cGXnFX(MV1_dgFOj2~7A-IM1r7Z5toN|Iz`Nr;4%d6Mf7_1L z$3f81TXMo+8a!0C)ivFaT@z^og5jcTBRWjFMiPw6p5PdL&dU2(gdNM#7R{!yk@)PU z(N@{O;r__y4;B7EhS$^pp<`%{30 zFNmeObg)K7rCu_{T}yt3LH>8aZWf?h>oP%vLoK*owd6Yfp|a=Tq7`+xbLamk0 zalx(PP(Ca9q&F3|NmbJkmVFO*BV`@$h8W?v;demt@|Lc2Id zR3f{8-`_{*@M-S!Pr6kHTtQclX0vW!q!_;UWR$~J!|tr3Bn^28G^({Bf_bbg{>SHg z9{`2Owe~Sp+~(w^2THXUe;35pf0kdr(oEEG(s_`%UBkB-A#2$#T4C24yO#H=%Q{t? znDwF1S7^WE-zXt-xH^I2!~%254^%SIv; z>H`9XX1zCH1|X>rnX8SfmPRuVFCURhT*hM8OmI&kNh#FM#_yzSf7~theR&x|gND%h zY}q6WBph}y;k&;xK3NyN=$mD!S4;12bI||*or`Pt4M1uJf8`K=DGsR?x3s^RFju7a zLF1?L``G>(G#2&rcNJp+upa2d`Ovbbss^sZ#d?brc+=4v^-d(fw@R4R-aTwCPx(3o zv~&YXjHiUz+rfLm^!>GwI|`*`Sral5HHc7e@9pG-aU zLwfY~%ojQM9}CAHqbqJ|9kEbtutE$N4Te^Rl)XfIV@*wzToTSg;pF-(bPV}I;hTCq z7Ws=aj?0qlS-IgDJ(F%^QfiLJ+IF|n1X(3PNtbep()vomf4<}9#M?(bCZM764l(sO zj=STv1svncP$&q0ni`kt<6B>DTX6ZJ>iL<=SgHVC@z0nfPPPD0H=g5+P^ohh+GGkQcNMc`}?wz5U)=Bf*RmwT-^g z9*F2nHvsqGHT40iK-IQ;dR8nfWI0ey3qaqe@8IWX* zGe(&(Q4AD~dNrxc2HMjvfQaiaoWFk3opo{+MT_d%`7<#t*PUdZI@a9$X(v1_F$vwe z(b)Qfe{fygGZF^9)XMLn&AWSLtKY0$AY7B6+<1nZFD6+c4>Y9??x5uj4nT9>|#JK<;8% z%Aycp_b)!7QgYJlE^Wg1x^irR#bcuXU4aad&O~KY@IW>JX9KJCPE#^;HoEjo7(}G@({PdNLkiM>}$icHz2>%9o#dKg%apx@i&<7b372g3PRq<-g`a0YBZRFkj)(PFOEYhBp}= z@Erv?Ch4W`$FE`Tnrvb%9f}o1u68$FGRMy<*B7 zfh}Mdy>5~W-b?aGGBz}c_RbZamW6#LhB;OKp)SlxhHO-m%L(fi^u)i&UkdHL3BG0N zGidRIGm@0@UZ zyaoAlqTG|8TnZ;=k z5R9qp&*d^xZ_`L2KSF}Aw=Sodg4x&;BfY~g>Ybun6>b?6+a6_sdQ6?3r__K5CbqTY zxd4+Y{d>cJ;JMd`F(9NeY>7S+}POt@@FVremK6}5SI zK_$5?te!?N1w6WLe$mL-tNTb7x-6+_=bEMf7=MB&7{l+IU)}~*;kMKGS?jd|jl;1J zyNSf~qW zNiNQd!HAw|`0E3223~^Q6W3mkjBPh6P?Sm#!EI+=gm+RuR&G09TmJ7-%hpsDHmfdy zG+<5{C*wmRkKl4Ge_lssFa;X#vc_tswNJQN3<5bf>!1w7lN%A;eyA{Z_|8A92O}k) zTwTnfvdxjLMr5MNh^J8Wh~4HIEI_!e-;15Gh|3!vcQwjMc4VzIe^YH=N@nHZhZ=0d z6Lg=bL$fqzwBlajKD3skfAtF1D9eKu( zsg3auXN&rsHY%e>D*%v5W0J1HP%eW!$^4!pJ?f1raW{F&c$)cAwzOME$}hMn#d zx;4>0j`(ob^kzDN&X+sVd^(C}c}5JZ0)({DBJH)Tc{9xNIXCc(V;TV|s|ZJHwX2Vb zQ2)AKbn-yPIR8AX|Mn6JGNo z{t~q`7B59zJ85#osl^H*|S++O^i|dGj34AB_W}C(5RKvA|llcU~$If34S;=d2fHTsr zTP0eattj_yPuzC}lOfLlOl~Z#QE{2Pyuv&T_CLcxAVi;;Q9rG2eQ@v~%hH5STC~fO%D>m#HJmUW?1X`AtRwEGoB0Y{Sw5#onS)P4ao|Rrbeu z?B&a)gOmPPRl*Y}PYO-<*f9xzt ztv5s$c1ash*%A2`&N;4*VDjZ*xIr)j1Agmfi*cgQdno{_3F@&>UCHEK;f)T_q}-X^nn1(W12P-R6p=D9oak25Y&)kjY}tY<$~iPX|Rz=(w|?UBxNP@ z87?H8jg3@4eA8{znRJN#dgbdDe`~kS3Hw?(I%9fX>@q)nt2OA>M+5uix9cU_lg7WB z5*>*+!JQ-_>mARi;&7gvX>@y{L6GHpUXW}QAJoJ89}KyXV+4aK4EhAI{sAbZG)PK`=Ke_T&_$527( z$k1OVO(Y!cBoP^h`OkKv9YtDX2ODxbL7472E*O2L8UScGYnlASl31I zm`YL&HICFBpPFw~h|%?ys&|!JDh2^Hb*E-1Y3$B6bt8e_YEPxw~1f(34%V z$!WsXT~wh5qeMA@*#mR3dkZ$?PPa8FP;i~!ix_d4o$*)?w)V`)j6~xr^YiL4jTrtz zdx`*C7n~yM3MBpvO4tuFd7iRat~T{n7-#P3S)h6xw#yee*rK|wZ^PR43?n8X2KpYA zl(zUcJJUsN%Syqh*zZxX4gyJ76@8ft<=Jc#!gI8;ZUeDkAEOd{=H@ljrT$;2Lm4l z%FqbNad2k(ZBF^`lDX|a4##HZ&t*n%x z>4)NHEen9{p4{ltP!aq#FyZpBL`O4C=m2E@ja)2Er4P%n ziP4FIc<5l}J_$iZw7DG_*!;c-=$jyU(pzST7arbq*!78xm*0b?+@e z)(u?p2@i0E2pcoWn(4@)=uN zptHIqnAy&lm8-GmRG#S>d>S9>3BM%hID1~09zS-GOruPz660h7N-8XpN{dWRba7KZ z=|8qAGW%*_Z&{z!!Y6ttYDO=8GQSAAOSdby{#jgOs6{cxM(GD_F=@r*eN=j-b^>HP$5!yV#)zGYY!iP zWN#o3$!R|5Du(b8QHC52iOISCq7&+Pb*o=Ly#ux32~?efZtE=?N#q+tDqEP3h-fiK zaf&&#0G3QckmjZm&Ix9WI9G4Q}8(y-+2|`Px^7a zhG1U~lT;C&kOLd;L7kFU45j#C{Y~8!U}>flz*sDg`<*f-6$AkUoRMy!WN<#=`>TF|E9&M zSo%v{cb$L9LV2n9KwE;4{wkF_2xCMuXgMitkADMBVgC84^4V@|RX|M61aEemAIqSEm%b z)|SGI7Ew=&6mCn*E9vUpUVn?)r%af+uD#zEC)zN@vP8LGLQ&WkBJ z&6NzJz{2}q8|!T;3~z-8cCtarX2z^P;(%lDXKcb{kGT6ho=lO>JhvGx3~DSNDH&BODK3ec2^&yh#YCGH`}Ibw zFB6&kTB0;pM=1S*Ll73RRi%sVg@@nP-(t>KY>KGT=?kH=)%doynug9I$KAo%-=Nu1 ze8rzTtd+(vC4W9IrQ&)j>ufb|Viev5XjNq^bjf`tl#J%iLeAQ#EIxDJ0T za964(GmpuHTkf@0vZdxK+~gqL^$-h~`v?R!EA`nWH7n4L5Of+|ON)0q7;r?B628Q1$)l?q_TIum z@HLKM`G45Og`Gf8=UNtUD!b7l^dM!u(F%%?*Bb@hnMbtyri7#4L^RBW?6V{2bq!}c z%dm|0>XOU8A|Cnmg0(w2Jh0@eC#+l~fZY#QzJv(^IU=)|YQMiyQ(TLAXxRzpfLN7j z4|UZK+Pkq5?#%ek)hgLo_4?S4a-unbj}CzN*ndzC>{<8bkpH%;WYo%{RR%FRlv?n~ z;`zqPZzJ;*!8LU2bdbX<;VtsY*t`eNX))^wBen-t(FBH8G5EuKc+OfpQwKkiXax{P z!rz*J^qUk>ut*=^OCh;0gpp1HdFMLO>tzxvXM!46(#}_cm--_M@=c!sF=O|GbUUNl zb$_iB%h5>-?){#o2-IWFVh!ac*D8|gT{)lZEkaR!A zNYDNqM|S1|*I~o%(ysb~Vu7nuti)oVw{Zh!2S)-<8yNlXBE0{Vj{4*K=00U_>?e^TOh zn?z{7(i2IWrD=sbh~U3(pO(4nJ03#0{X3qGL{7e^Pcc3fm8>Zg7NJPR?4(BHj1jVo6IXonVm>~ZAcx@%Zq3Sq;WEWnpZG3>i*ongBRG2(v(+Rqu2d$%?x<_7St66Hkfq9V zNempp^25yNzToN1(8}aXb%@zX^pRQTvoump6LZhEmRUm-Nq$b+Qt4Mo5WS<`|2!O& zByDpka!J~f)q)_>|MckOQZv`ri>G>C*U{Qw#3PJ&sk{y_KYbbEz};kgTi z0+(Kk^boMpo&6@LMuCW3Y((%lB4L@J;0iqc^XGRJOp`4O{-sxao$*B8*w+lbv$s`$ zetcPFMY5Yfu<=y(+~1;ZKE$LL0qXK!_Wt1`ZN`|}<5qUqi5dbdSAW*Bq@8xR)KFM~ zrCnid$0t(Ty%9;gw))#VDb8{~5WolM^|TV29xSDwrPd z@4#8&$y!|{?+;?OZx|P*_1fH$cEza{hdVG%JNOfb(>i$hUw`j@6avdvE5u5g@b7^` zzEmqh4OIo$9J;)gA$FXl78zIIN}-KnZg$|fgVCyn$vaS!#xYhb{Zxv1-aYSLf;8nO zN7|7V*yvD8LkVt8wD*eoeFAZQmcYCR(fqH}&r&z7LU$Ki5OH8(s>_^(Np9p%EG$ZC zXQNw6dE{%p8h_eDmPB9AJ{R#+>cVkTUlywbQ-0=Nf9Y{5r-xTdPG!_bZLhFt-=i3OAw7o@8QJdfktDw51!2@!u(0)*5d02W{A(N505L~B^Y`D}n$pd2(M6`vpdvC4kK%15 zg1RB1OnvJw-A(8j4JQZr(TWvm|CauQKb}@@PJdPJYxyU8s?35p0Eg@2z63_UqY4wx zakXQA&Jq+rLY&hf1Mm_MNmEtEXMQ0U>*AA6g<@a>igHI=5DSJT_~)!w?rKhc!Kf4cF8mE z06)WRDJ#r8CY?BC*wqK&a4ip=o(RCWWPe5nWuN-HkHM=|@o7gK((W|g0xn?k3&|&U*b6MdT z@p-ooqZPKo_r=HcVhvi%pf;6FS=j(D0LAB`M^l1DbjJOVW%U<722lR4;a91aXMeiN zImCoGKK;ly^;#-Sz@=l^%P%h=MFhHiZl?n2OE_$>$`Uw&dV(Lkpk;6na$Z0s4NGyb z&NVyGNVg-~7yg?sh;A;#27J&ko_iYOOaU9yj%f$=zdr^Dy1v(uS0FLvJm7FV2fZC~ zi9~%-Nd_choZb!L-0b2PXZ${0FMov$S{LARw2`lfUOe_tNWia8EC5*62kF8HG)&Az zaKLJOxMV2%r`L0zG!Jwo9$)NX+TIjtCip|3@IRI0Z6zgivl4OR=x@e%qGel@NVn`w zBN*tLq|!yiA~Lx~Tjf+GKJaU_NM{1c36pNgm^Zg(6;4zUQ44RCnk{9>w{+jm zTd>y4VaI)P&S{Mo=!Wn8@;+T~l@^j;zT2kz&UavLI{XEy9R%5f9wtoNq!t2LgOr0J4!Iw*Wg zjZ4E{mlUVg@T)ZB9T@NC!Kkw54RbN>3=6`$7EIUfwuMndCH(6fq<>HwZwWr5PUBC= z+$eA#kYPv%DAg+*+S$t}$pW%PE$<({Wu3%tCdzJ;c8Fh#c|>shIq7IcIjx~|-gy52 zHMW-6+hg}9yw8A*UJA}IZU|Vm7c)={hoFl#e-4kz>C`zYCiX2tF3M7m^H-!phoXmk zGjfR|FJ1~3el^JX7=MV`xO<{l%F?~M`l*N+rqhm$zo-n`3#f)ZUpA)INei?<~OyI8 zk;*#FxTd<(ALgZq*h%oR4#e^!8hd#)^KVX2fP5`IK!{vhV1L0@-AZ`H3<53XB<>Zj zGRZ+Ffp1KeI*yBledFj%5KIuwN&@Z)qWh^Vdw9$D^5^5GbWpF@izNS%c719l!I)61 z4yVlQFZMJII?`vT50-yhu? zfNr7FLJW*RKw@hhphGILMxS%#aSSs_)qsy`C$5G|Cx7ddNwsh}hv4wBwj68%yPA{_ z-gt(u4*DC?sePro#eQu3Q{;1aheZryZn2;nNp9Ck8`mx+A!SL$kjpFKzN*7b4* zGCoHhlAv^(72b5ug%`ph8b#@!NG= zwV>J)V}DqjUUF||BFclp9g|h0wZ&_Y)oiJJu>HLkP+Og~!0uCx{m76w!XW1P0DMt! zo%ptN#zoIM6XVRT~S_*@AAoxYN)rM-W=%E&P(Ch;z#UmVYH}k9)%NbK7^txgCm6Q&QYdJ+DQO z!B`Y)ZQ1>oQ;_5taCwf5xb>pBM1<5Bdbt;)w7`@7ggK2<*%7i|(LilWpyE2pxwv+x zsgv71L}A^wI25P)AH&UQEj?B(pz5cPCj)4>dd!_Ju`TdEJM)>(O8lHhkU4}a1Wm!q z(|@dARU5w^S){HjsSAJehaoB~-^E)+N|y2$s7PaLMf#2>Uh5i}ZtOgdx=e zMjxE)gQ_kS6~Pzty7JMu62es7T@$T_N?vOLgD|=W^UpR^`-Mh6a7#22B|yCtY-M;P zbNtGxx%(L`%%`g(v@xSyfSmK|Y)0B4M)`vg$%oglv()ZTb$c^7?kjcbGKWBklT7WCt2hu+hf53mRz`I9rgkC@`i@z<+lK9CXtU zasHeRnf1X0RjCX0vWc$#X_t267K_P*LGsL3B1127`8L_0PUPGv>{&jKPbju9UR)zp zD%HuZbyiZak!iMmlu0SZ&>+@k^$gtti#EFs0;8Fz@J;G?W7V&{E37(K{e&~g0iC4K zYnQFKMr;CpLgpfDL;jsMhJWzXpmH?Ri+BLXzFJwxH-S*s8&h2Ofp1P-j)URWUK4if z&JRamU30A(GF34fOQIjkjvB$8$H!>3=t73*_Kr2%k<4>K5h&aYM%v^(5Lu|R(BLUW zE&h=fH70>0zC+8Q=!{5(iF499=!LeXr&1!aZ>QTn+v<_q$@r^J+JEY}0Y75V-1!3M zluIeqR^0J(5n8@R*244S_rW-cq!nXs0%YuFVFlQK|KB4ztT8H{S|56-<#G>QJSHHr zGrjt_R(nr6@#Hi|{H=5n!IjVtd}x{pUqsraN0u$8fK)(%#$MkstShtG^Ti{*pdoU+ zmGcH9pVBJjD$K_OS$~)xV7tM5M^Cw#42>f!@O~@Fs z*KT5)>zk@=lG)G!QMXJvtyHGUQ~YO)q{Ayfvp@>~uaV>m#eV?bjBeBI6LnRMs!rU7 zNy0JrA&<$pqWPJ^=@G;8+2^sfi`@USqRB9p&&SZwAm8kxIY+YXAVYu}n{GJ*JawlF z-B%|f=}dw5ZV}(VIi>|e!k|HLVN@=L&}oYz3EE(>dr40FdlEGm0l2@XKZZ;it|(5M zqJIK*uSh^1DSyb!su21TVUghiNH-orInrM>ajE`Zvzj0r9p2D@_qR^+l(=j_(g#nptsN#w{!dGakm2FPu(KiG&B`3*~E2vtY~)h zcZN<^0(;&wW$kx&RM@EZb*&#`C<^OUwB;C3Jc@l~@_**-0)iw%-j&ykbPp^F9RY@S z&|`wmVZrb)rIAlJXiL1t=zJuB!KRKtOliOI4+iev${s~R z-NZ&({a-(kEGkh{Xa&XKtP?}#@_$Vuhwq`f zvkwc#Lw`QvuMgSjaIzDyJS#%Z!z5*7bvV=S-sJWvjHQz0#d_k#NT-F8-$!8 zq4N-t0#W5MAKst#23$Oxd)@2JpuULGyp7yN^?%PL*BO*whGbx&Zu7&!Wn!8-K01Kz zu^wcCXglOgMJV(imEE_s%-o&0Il(4=8j|Wrj`3bZm?v-s1s{S@-(I6$M%>%>&<7_w z^uAj$zHN@$OuwPw3}L1@P%eZXLwknk$gJ4hQJ;aH{zz_PP-6y zxPM%zw6#Qsc)Aeo(C(oZqm{-%4%@A1?)!w%G(=tp1*t3bq&+a~V1DE1H^v9oBg>eF zkv1CkjDt`6J8O@ja5{CRz_z2q)IW3fCj6MRjS1wG`>2p?XZ7YZl@iVFs&38Pu1R6b z6+gwEr{>P`gFply8a}V%UddM*#@$ie&42R2VLS)~3xxaMAi*{v=wCY2SGHk{tZ8Fj zv)sIOazgUZ-r%rcA7Dx2Ru3Y6k=QqI(dX4*EV}7|w3}b~A z2_8lDTO9Ll9mZYX?Jpp!Sa)pB`Oy>_`)(7cQa|n=zAqCl8p&D@Jlj~fEH2?4rhh>- zAPH=8C?fnF!MZ!exga(?s!l&<8zl1k?dXrHp-m@(7GO>%LNyuN+l89?dg3f-nJB;B zUhl2~5`1ymLmN)p?dVybV`&60X>SMUcXsy?!7XHe*3&O;#R|KZkhT>0`PB4N_zC^^ zsDZGhKFxpME+2r9+wrsRuq!kc6n~u$>r#Y1m74|jso9iURPmkLnK|=-7T*rldi@Ca z3(c{&H>zk<#|mA4CrRZ}?cgyYj-JDVGWhJr=C`g9s(FbO`|7oXZ+~SzGnwVR z)s=v<-4>dNNM=}Hb;l{4?e5`qs8wE&wmMtq(22eNxKjXIBRgazg_!8O$Xbo=WK0lU z7>$t%`+Y~wpF5lchRL#W^t3wV1n#9rQD><f@8SD{waP=e}38Bt7}%uS=K3xH8k-DXKIt z{Ks~7ZB{hJo%ripLEez{`o?Hv*b8R~@K`f8CKfOKsWOInFf?(ho$zZ_*wAAw}eMaQO^uk>hU9$XFff!2kTxnfM_@%d!L_F{0rponeG z^MDI%kMJQVnZm;kSbs|!PT-kW3wC+a{WJ()?kxmOTM`|L!UT$4Wz4d^PwnfhMGQR! zwhAi?ispx|U#)Le(75MDnLu$3hawO}U0`v76k<|NKgw#&n+#l@feTaJCEI5c23fky z7w5r)744YM5ua1?@fjYGe1URzwC9O;BO@Ea-(CXfOwJ*MngOYwL z=c2w$>edUd+xjebdkJMJgp23xW)^DU;RQj6rr5w9EnBgrYfXfkT2>qG7re!HnE;_` zvKy%#m5xTwCQh1JXU#(MxQ8F9`j-3dRP8$4s8iT0uYd>h413^Dw zJTLe&lq6eJ1@ngbFu$6zQYp|3-4~;C(xt7}D*z~yQ-2aE#cR-lIQVfKDOw=vew*SP z*u8^85)JObX%9UhB|KJ)`p(V|S6NZ=M-i;CX5tsh;50PxV^2ay#9Oia@sMfH?WKB} z$g(Am&VgUb(vomXc!-ixlvv%&1)muTa|X-;afi?jssonqi{Cx23cWGnY3Qhw+p_lcF+qlRU>> zCeoD7mU)qtpLq4O5z#$0i5-?mk~B!np}G&KV6T~Ai$-@{I(Shlg#1YM6tHCLF@Ld4 ztArsnINxL*Iuf%SKG@^pPn;*__+5cpfRdBYWq&#>fO|AfgvZ~ET?9MsEHbVY4;Dc# zXi!PLG?w{G&#_IdrKb0U&MaWga-N*!bAUk52uLFnp4vKk*o?Q&<3TN?#Wxw!&)^Ru zBoyEhA$=jQ#z`FgdG^+-x>uL2T(%ix6xpKuNUgpdorrNl){-?th;mXW(z?@M}$-4!D?J<9v|K`%AuV_`?k_ z_vD}s@BCO|HNHYlB(40sg2f8Get$<9E1wMK_VuHZr%Tkg#~@XD)N10|%#Eh4dp`iT*C8Mqxqr22 z2)Slyfnw&h`F+O8f(y^Zey3G3V-;EDyV1L{?AQMZ{3`?0tu6tG7f|YfN0e8XY#c`~ zkmwg9%?>5Nw)QzCq@3z$4!# z@^$0&cX4@IX)@JH=cohZryl=k&VSTty~nnyu%y>e{45lL7K zLG4qxRs*mc5K5F(eqE1>>uUDByxh+vHS!6v~B-d-yEz# z^U#$?TD$vS26*!4s`AJ%i{j$uQ8E52V#V<16H@`$@F^N#pG}$+NqRPq8Gr6_n#GAyig+byBQyxg97NTCxgocm|Eq+P zQX9N=sKqgKESdGl7+0v`m-IO!J{EIUUC4w*A?fw-hZyMnQQt${#y{jduYh`egb3_+Jft(92_2hId+vh*9gi2 z7oM;zQA=tulQS!&*z`!S%sRG<=w~i%s#?E;Z_9$j)^4(sI{KWIeJ`0smvXI{onGri zvA#G1X`e{8d(P*1K-b98zEstY$T%$m3<#GaXa3d|sWV}B+>H7S#Afl~V^ zSf%Y^X~Be9PpmYAQz?~d7qZrW=U7qP z9Hk`6U(xl{=)&lPf`6rY4dM{Tfb6}_@R(;49$&fZs(Guq4~%4?RFi1ntSAVfL_Zrn zVee#nQqX`v51G}`1O`AaL5qC!Mn>Nw(MmzPdAV|)aEUHdZ)Hg&X}ACAt+mv&=l|f8 zfS6H5u8P@Um(9ISiTKn`>@o8(3T#(B{J?+l2@~P<{-e%S`bWH51AAD*s@qZ>9<4hbGM$%c z_;i$}0l{MKIDgz3B}-u+s@aq}m1prc%1TW<3eMa4LOUo8DXp=xkTx^-Z!-x^1HZ6? z%}Xuk<^9wT;+84XU>9DsCtMmmFG($=`EXW0AO0=R!4@OAig<6#hPyR(r%qQMv`o1= z4?0z)Dkq}YYV99g3zm~-&#+2^(d8J%BlA!dVk_bc&3`L+4;CnH%rDxn4inzKbIz-N z3X6UQ&l8R$DUIS0c8=!&Fa^h2BxX`VnkNphAGAGQt33^%nQFRUn_dO)p7rry^VjGA zPV)PzMEm0lgCn7|2ymnJadxelri@4d4c_PEgY}zTEVP(_({yRoQ>6zyrH17*k|xoD zIQ4QKSAV=%Cwz6;J9{&XKGEvfa4w8(E_b6haq<#?v zsHWI`G~64aBolcJAmfzJ-i!jk1BA6z(b0M^QVjfc1YKZUzTj=KoP#o9923U}Z{3yn zXZD`N#LLsi1mdE!I2=20vYLXHJs;^rpEG1EG=C%|mA-k=+U-N;dpp=snqy69pr<40 zG%sT&7~}5wIL;!HKCs%y4f?Lc!J{iqsh(I0*6nlL+xgQ6DC2!$*9qD?{w}in&w44B zgwbT1vrr(kMaimUC&^_on#asTs^>Q<#8dc^!zT2q>2xdG4v(2 zz<-_{sv;njNla}y1J~XdfR4KXz~YrWbYP9XTx+7Y97jG(DFqt- z18N&%x#CZ4s&KWXNlCP1`WaP17kmsx8iokl(XFNNm(fQ=WpNp{MBXlX7dJ1eM=m-2 z0DP1FntGc9)S21w$nfh*mwGfJBsCTE@sqNN1R%73K- zZjk2pFZRQS4K>(WDs~rd{Zebxo)PluqZfz^Cg6%FK-lKn_B=13#+?8tTbO!oQ~rJ? z&HeDC|966|9YStj(YrE{N;is&BHTmzc15n(47Z>ql+9h4+ZpGdgvZ?OMSv~)4g^u* zqDP;lc=PpmS@73QPidmKtBt;hfPY92#mOyv)zIcC`Nd`FH?@^jN#HjS1FuJ4upEp| zWyq#WJ4SAnWqFq?Qpf8g!$wwp2x~XL7)o=zr#SB_W4}XDetp{>wq4oVNDd9QvKr8j zB4@QLqiUT&b_2-+d%|sJt?#o$V8}~Pr-h|dW^T3^?qRGn_Pju3*Hg5PxQ|^XKsbb>LEDZ;jJ+^ z)zyf|tooRx&8Z5cuNByVp4i8anfiDP_4Z7&AM|VM!^ep9F<5uy=}6mEUp{gzhvl-1 z0EOOvnW7s9HuFu)l-ut^+kcqz@Bwrr%F;^|rhVHfDfm=iXrV8|l02w)y|I&;McziE zx5=s5y+^(#QrLh^eok`@0M@Cpl3>SU3taEwp5VpYZ9`>rG+w-GBuO_KK+<#xm>D9H!jAkOx z#q`u(7#A9(iT=+7qVl`S`*uThxmoH`cyv%p9UvH+PZisTa}Z|$2KTa-e<_yycxL*M z{l!A6+yY9BB@7YJuz^mJyLfX1u`=tm0~G-q=EY(&phBptQHgAAjyyqni*t?5oP z7qgNdzaWO0Cj5n0B!B7!D$nu&=GgnYy3@r7CHSU>Y1xfr+Ops6goKT55Ow78z^sT% z3{ZuwKh8>8P0^1n_^EKGxiKgcmNeA_GWhB#9 zcC42!QYcn;?forIeu+KXs7NXD$u9*dczN1O;uM!B83sG%B!66xW7KKO)mswZtOC%X`^~OT0_?jFC>T33yQMIYY%S-piiJyYVP8Io<9CsN_Nu~MX7`@Jo zMpJj4$B$_RN`Lru2NY8Frf#D#kNY4Ox6te@u(Rl7ge`7LIoS(gn_SoDi?Kp8=7yQN zkwMs<0w2!wy`vb~ms^-&pAVGIl@O6D=rQ30$5fYa_=lIZ!9z&&n4|wpK}Bg>wlk7F znlq=kHHu;1rm*+I_wslf1fOxyS^x1P7xCbWV=~eW9SJ7cSROxJiRk7Vm@o zWT`tuW>8ntbi;r9!UXTXwTmGZGv8ZrXy6ux;uciynV&vlN>12sG!l@NTgBaDhtWG< z1D{t=3`~GE5LrB{^3di`oj_YUJ3-gBKD(P&Xuus1>%^-NZT~RoQ3-*0TPir`Rg6JR z>>vZq9DiyZ@J;U2Vl5HOGAb*9z@caL(Pj$fgvF=u@{D*@z$@bYAO=UDZik!mb=gh@ zK%?9EC?8b;ifr1tv1KSRxr;E?381}v?o9)I_NS!phq`?_Dl|Tim3h>Qrh->TE3@k` zm-9f}5p*QvFC?({>=D{T`a=Fj?&Xq|Lv;kd2<2bt#D~eR+S+b z3;UkcMg5Y)*P!yXrhBrjIq*A@1)`k(9KjV&W=xbcol05aQ!%g;c*7yVQ5Mb?jWM0 zLlY^XxJ-8C(%}hlxt`~itO5+NP(XtL0*t_9K;CUJich%bLYahVA?YK1qTC~jS-#X6 zvo*{iq9dJPuT-tN4cPEShTn(=x{Z2$s(1Bh&=@n&vI3?mBCgVSjO) z>>WlMqt_ff8BPUhO|T48&e##qj2f5aNrjrMW6{BB0tIQl`gzK$BTVujipIozM%^xn z0!X&e3@wqRNo0GS9Emi6klTuUY6fSmm^@c&pU@NGpfKa>KYL|3#)Rv)NoYeU@jOK;crQ)aN|6&Mupxw zJg!IXtdNyn23lu$@FZCm8rnhK>n99%n-ljMU73*PYL{!Kd19JONV{mh7k}q)u<#}z z5Df$Zze{qJG(-6l-yDWGy%3T>0D@IR(=u^qy=>jNA5=&moBa=s`IqOrRGih#;VZQH zK^%pN-tT3a0Eqf};P6ny`gWC>Fi5ozlc+DjR>bUB>cw$d&rd5t{$HE@ymSyOc*+Bz z=_mu7PFAJ(M-z&fv=v-o*nc%nQbED?mUZ&tBl#W;grWZdzl~_a%6)n;vPjq$(89;d z2i>(7W0Lb}9wjQgvbvMs?Nv_>QN#usP;jCQOVM>-lC0`)zxw#px+_634wRgvTU+2< zC>?_M@it4uTxt)HUqgq>ts#*@XQF*m2R#2HAK%s%NNu7FCsFcS#XC4~O8wO_w=)F|XFQG!{U&FZzq${p~ z^THGkj}UFm|A6Q-34e>UvsVwt-WSJXtx<`p2YE8qUS?YaJ=k~PbC&j&U4wy6&6O7Jsr8W<^q83yjs2%7703 zPJWI(+S>2D(uAwY(@H<3*pX#_nDCKPWT5bp>LEOgSx}8){*>^5_@>*Qtn48;J5Gdi zhYp|)OQvT%t_}l&R-sO9-0YVN6LTs_g#L28>%2tSJdy&OaHKR|xU~ST5>oZ3vZ9)~ zEBqie#3bKw&VTFxHkSEZM>nB$lYD0>9n_Z)0E^;?K;1Y8DoF&s?Z6ISYYk916k{yZ zYF()w$a1yf0W8i4;s<|p)gBDng#k(UKD(PQQ^s@DCd%P8frB8~zwOQ=nWk5OvNn`| zwwtXgUg#-DO0J1fvNO^C47Y2%RxvpcP4`^C+?Kt;6Mwf(`NVMx5rAm)*QYF*?dBP{ zeImr6cogY)A#IIAdJ{MyT|iSF`bW1V!JvlZoykF$ks=?}qf%hPN{o?tJIWYkg|=5} zU(T1`v(bGMSI#oYlq`YXf2$4E_0uIS(&dJT>}nA`00JDz3r3)29^XVSu={sRgPbcm z^VxmzLw`p!gO`7PqX#sT+DLtojj4a9JNV6A>WolBP;))d$JU7N$?*%C3qy8olGPs{ z;ymU~kcGH&E{y4JGlx}2?zdw#KI{S=Hs1QQ!|tQmINHMrwEOk* zhUSa=NEG|}Z`*x7Lo;i@=~FjcCty~X<|Kz^^M8r|iK2=*MFv{wkc)uQys(Z+gJ*q% zu?A!?yoJ`2q~)UB0dp;ASzpC{E=;cub>m?(*!-Lmw_0sIFn!=EM2QbFX8x8W;-rDY zzy{cn$?#YtCGD3kVo}sr~UlOw7AR*{H}5 zgMZ-4pKDVKa13ne&Um+{A64dM^tbx%sGOKP-eJy{&miss)ayM&*J z&a)kNRIGG=H%6r<$oM@U-u4P>J{U5UF}ab-fq}SS22I!Sf<)I*j2Es zMOQO zK!M?)!3Ph2Z6?=$x|7&5CXM4m7a8`)gZ5|Sb^CU1+V}{Hq?`egPhs3`k;}dN1GRg@ zVb@)JNi|CI+srx#^>y^j9AYP4g0#ChMRW3c0!75 zRvyO}pYSzqugID(4|Lha4}WOfmyS9`@)L8Bm2T`6rG?@SF~4Tg>XwhVz7ZflLveNE zL9@4Hwt!NBC;lzUTx{%5B?VIj(>}vAwk60}w@qA16@{Z;(Mrj{N?X>UniIRguHmR0 zL*mBx;=&53<=%kzihyX$NVmc~Ft=MU4lrambK>t<1>z7sj&VQ*vLcwMEYpQIN zXpT!ED}jN=NbVwiKOoB;XFAK3dQ2eeHsx5xZGS_<5mGJ)dY^kj68sWfV|)~bGx zU()gs!+Ut+@KJEShtNO=oX>~)#=G~xqqnoW>}l32F#f(v#Vh)ubf?<_B0n+vqkw{S z&e1@d(@1)X6{4L}abp_^(SmGly?&BGdW^3fQ}OQHe&q0fPk&4=`@s2W?05|?ufZuF z=3H*N&gD5K?GayB^h1ZntbP^UUi!4tc|p~u1Zc=b$!`L+fd#~ojLa~F@* zB@r!&Mh_z^?wD?vF(`vHc21iWl37affR!#`n8gY9_p--qV)oDEU+5tsZZ(La(pmv^ z80enqyvN#2tbd@JhtISj7EUp&%IP9=9vX`^0lRa&-A52aOJ1j@eQ}GKsAVR9L6AbEKBYm-=knn!0h&(2LnDFDB}-$8Ib>dN_n%8T7h zp4q4JX5_);^lW=E#gSgi(*!-dB!Qzm6$DiUag|X!RxV+k4$pmcaf4#A2!OS&PBJmb z2DtFq)_)rV5Ys2%@k;rI4X@r-II_koj)p12Ey_NCu2ueL8UX(9RUrNlr&D8yq^)35 zeR%9NyIs;CxzN@Bx-tRPMYMun_tOLI5b{5*U$0xYBEnJ7^>m2a2zktZ`01bVNDQL( zXWW*Jn6uOj2jcm}<~Nzo(xnGtK=Pn-$zm%!BY!aZeTr)ATv+K6gNfbB5(S8Iwx4%g-EXiZ7x8)#v90qm=wv^d!EB zK6C8B0>hsHJ(VW}@M8_xrC;CjPd5dEtppiU){^p*+it`4vEHq*^A9`&U5cv3Bo$Tc z$YonBu}~0JR0lgVS`;j8AFbNq}?q~^X$@bl4ulgFiu6261snPzH~hh1cxTDeGGGpfc)m#h0U2KB^`rU z>t$Qw!TbtvyTR~RfD{IS$(b{;{tnk1kl9p#vOMr=)CS*zPC0V~-aIYamW7g#ynmex z7O=!g*>`aB@?cskUI9-AVqN5F4ltCmw?~#U`$c-04aiOt_sJHW?;MBTAHDgrKZXe< zPIeUJZhq=l%RtoT9$zJx4leXwP0ae?yxS}c_YgQg)1i2U)LHWEO0#@&qixJ!daRj7=LFRqn6NvOB^9Fb=yL2K=lVY(?oa!j&V_Dm@QfdqTyFvsZxffCf^du}#>B&1xCL&fvUlc6RdA zvtP7O)2}i6PbA1BSSl5ZYfu_jolM11kzUq^Q@PIGEh^78F>+FJmmaXw^?z|&ksffN zq?wMb<(zwmG9_Wdw%!ll{PF!;DmB>>0%*tFHcO)+ZBhU74uBS|GRaIxQvr{GTs+I> zr)8SSXIznGXH@pvy-p2paHak`i7LzGX5`7o5!G(S;*clZdTKPE_ZY}F>Blr3^uf3o z7?HLP_%acPkbVbOyiT{7EPq$cUn=g=A4=)Ew1%@Bt|7x3{@kl2QhRV~)Q$Jv&{kr} zF$*1GrJRu0y^G&t*L7MEfY0Y*niG4!S+2a`&YZ;XG^RdA|2L)l3NymRI!OUq&C3Vk z^Z(}}`)h}x%vddD_6X+r1vEI(pV75+oB8s_Mxrf7P#amGC*=Hw+>lB z%6XKA95?9MQ$Khhm;^Jq8nZbNsPweTvRniN%~rgxgACtl6i}?@cSZnFK(4I5@1?`6epX4sb!FgoRJS9ib9r<@v?NpXb}D zX30-ry`UlvxdC(P&5x{CvsQnjW`iqtPxJ>>gosC+d!#&s?f23VsRVqn;ijM7$YT9* ziFAhm5B?ijZnGv&xSigB#RhE&e%xe8j41A*QD+~q`$KHo@LSAeL$?_ss(Y<(j?YW7As|Z`OJbpr?-Cl^`#KY`*60|~E9^!1z5SP4Ra%X>40e1^D_ShtN zR_iehJI2JXh5PaUc+TW~9Qb?se|=LicviFnK+s7BCf7j4GqLgu27{xrhNJ^7>+t=1 z+5->s`^30~aav%68e|a|jEMyw7dd&M!oo+OZQ*~+s zX;Fz-OE9?Rsp!=$*P(m~Q-?d@NV85^w=thb@()#lD@Dts!@JplJ5MaUMFqz-RcHX$4 zV9qJb0UN~xwr16qQl?BB*F{|KQB&uk!``3h39*^Y4_#hBvGsq#H0}&OV9NBkQ*i{@ z%_O|L=^#@>#40)&fFGJE?x+8aZ-}Q+GcH8hOBX;-`%3zIY)_ z+OdKL)=PQJWn{Bkuo~X#arnN~HEGl%V`!ez6#8|goU%wc^OTp+d2sY z2GGW?{bq`2_J~jr4#QhDz}=`K+&||_&ZZJctDCi=VbGKx0((hEVqSNm+%Fph>ACPy z8s3UzwOM~7a1=pb;C%20LaTNL5L|!Me?>xUv#Yh^K`BBm#rX>()48${J(#pBZ+e9j zZlo02HbHb=sNFE}PyZgP`TqT~wtM+H#W{Zw^WxNStLuYs;y~=~69$ZGNoc1W0kzjv?57{g$s=~yO;WPr!LBP<9$;Ptf{sR}x6g6>XAMc45F2*6bTuX&7SzhHYFI-oz5s%pQY05u*C6>$P00e9bY@uDAmm32J{5A7j0M`pJ7s7++R3_p>-Fq^Ghm1=>W_SK02Q`Xj zSPV!OPqne7yv@b&{`T~<3cyct+{W>?9j07^wE0*cUf9V~qu^H9u)(B#$H@#D9)omR z$vGTT)2b$q$I}#QVu8vXLdW5t5p2~=WHx{K)dC6Sl@zFNe$wMwoYWp2MU&h5(N z+Bp$c$X2iqun-+65Bby%4Y8=Whx1wzBP-SUfiDQVbd%-yyagZXk{U@*qBDOq{`*nR zPl0(8N={=839%US@QG_ik5ODX2B713(8#>y;EtK5;5(hU3eW!8X;8exu36rdL{NV^ z0eWABmbTMOBLY_>1A#&21?tW|Y0Y4!0M%u#^C~^4bJ1)uZxM>1zV9vU%Q+uV&^4?J z)T2NcZid6a>LPbtx6_T@Kd*Cd?>dBX}654<MJVc4BB zOSPH3l83GIgGKU7fKN&%iig&@k$m|`nWu$8@2YxQ7gJgVHd&58>)7O3##u4VQjf*( zkcVVDuYr@FQ*CR=JCCJ_7liNhUK_ZSi6q3D920rQX5IrD8jl(U+S6Fuen$dEAkeD` zOz}M1xMc`raWl9L+%Vq;HMoEM1`-Xa=;x#vMhy4;p9-$gA^45qY=Z8T6;^^P!n@1Ijp^&?Ch%c+}?X+Aa=4I>GzZT3gzJIQJh z5bwZW3IUOg(wOP(^t@rBrh&+pHX)J1Q19Yi-4y|TKrILK_4>0@KbwD==_Ia%N<^Fo zSlA8nN?hJMiXx!74srTzne(HO2?PdH4$kmFzToTmbEq?c1~4Q4va=krISphZc#11Y zfB8Al6tUqpTg?zX3lj+TSQTq13n|+BGVJw%z{}T%8YeXP#5CorlmBr_Rgb-7Cwa9! z2-r$hC}#H#PDTinc7%V~sTC0}=P$^!LHMB9Q9+&}ddog~5iP%CuPcnDkI0^Nc|G02 z5%$S*;%-)`kYoNbQbe#g%s@6_5G3o4MyfvmN4}37;$A_Q&G=f|EjP;3TJ{Vfn|WO; zoh6dz_T(+1uCkA3-1IPW9{|}4f9W`Lf%&RHGkjxo^VDt|vW}+-2 zs4Uo6r9A9uCUp;-O|ZoRfSZfHeRpJ6!OWhQp6>$o@E+G!B2D9Ej*Ho61d4`&GY@Xo z&n~8rKC*}lF4cdFimZqp>HTb0x}F8yJXIA0DAL_HLH%>1msnEE3Y9y2l&#sRg%i$b z{ypI_{KX2|8tKv8USHIxO;fwtj6Vly4jG2(p_2?q5s`GdVK3CYIBG^ltH-04B}q-C zXy<{;JAYK>>Bpt!*+p`=Oc>44Wxt1;AMDNu9AmB)Zq$E(5*SsbNgX&gF9g4|95*~e zRe6jiyqZg7*Ww(0y2yO~`2Zv8hv+G^Kr$#h3&3CO0<9#YMw-4`3PU3IbdV6SIK8jW zkgzu0mc{#S=g`d4M<^%;x}ASI!bi(|#NkWryx~8wGumu{#V^>A20XlM&RV*x{9YNl zk&;Bt=PrLdH7JERku&XX{LS&O+nzw&f%9f)Qk8w6vzT&H{dmh8z#?=SwXxraugnEB z3RGqh`*c2Jx{h$k3MKcxk&<%a1RdtZ2G*1HMX7T;sut+!W5DO$0ab@-a$WZvuDNRm zz~gOVA|J2$u&_fo;U2nP686kj+(6aSey>j2QpJDqBp6ydK$b-#<7C}*M^bKkQjoW| z>I^7j0j4H1AgP;~5)E8awx-8S8&@oZ54!Q+h)?xApc_F`(UGoj7OA4u%wt>V1v;T9 z>k3w@C*iH?V}#rqSM)AeId+q-(y2SSTMQ6!sc3!f!citFEX5X3;`C}h4)m$g(XgcV zd|rQ$3A6UcD<^wDBmaC{#a?e<886=RHk*=NZ)0Hu5;+bjHUY@v;%Bpp?Ui6-mGdu< zqaWxV6`$M)m*Rvfu~o;^|C@i) zf8|(t_Vv3DBhfS~3U`$Sf9&XzfA@NDLNG4G^A=(6H!qk_H1W{Q@V%vFj>HD z{*m(L1%o!`$LX>tUcoDgprFhj62IaO_a&mMo(mRi`FjIh}VjWiD!CB&+xEmL+k$7<@%<#0k~ zmeao2GLP;+%k1sTKBJpHWNCVu*0k?`2WelQLAhe>JO~vaYXH`hTB@H|Rmk6>&Gw$o z>a`Pn(V+H!v&l&cyvVBgWoN%(otj*Nq>!_XBpE5;`*YS80)vug_KR3kxg>wBvWd>^DEPG8q>)ySu97Pv zn?ukKu`$au&^Ros@u?yQXbXQRepG%Q$KGg|d;=n=c6^?QPCtXblP_?x=NuPPZo-aRvIG0%Bco0ekz03ZQ@U zrUL_BjoiO~=RrU0Wn_O2_tdT=5%mVtLS2G+#;;LVk2D9h?HFSBCN)VbRgxQE_1kM~ zGe%S`{E;XMZ5;l0Dd8hdATSCd6+&2-!?Q9r4CmXKOSI5Fd&xI6K^l43TyY~V#%4F* zZQ)^SwcATXVPJHDaq~4yt*!#d|DF8Gdy;?o_BYTSnY>9NNfi~6 zbbn1DOCdx1%Bhkhug{%pKKT*6AL@hiig-hXx+FGetr$xfxGSBG$pQxX4gy_QZUjql z;z$XiawPJJL}~HnOKmGP{Onmg_uc15QJ)FOE|7_;hm4OnQ!MV5CuI`#I(-8QuNOHc z&QY#-O!Mo0^#OkrX#m*d&ji&u=!R{QvJh>k-ZyEs{>Vf|XIf{%FoP>4TOXF{6TG3D zeeQyKZMc0J6$KrITsoc~4UuG&q_264*v5915I-~PEk60p?I7EQ>H4S?5gov!-Otw} zu%po~_8;_Eq<1BaQRLnJHM%^)xXA7W=isY}-^S*?Wa@vAu_O&jB8%8ibr8+a^c5n4 z6wysWIR0=c&be*U8Zc&ED>)(mb;;*jCfUkql{cpjrP2if@q}Bhe*p40Rb}XZP51X-xnXav-<*L3XUFFMtsw`*3Pn$`u3NNR=${^2?2uvp(*tY?p zNY{@EBnp>wJp(D1&nW{7x7qLl-#7v>GLsRi6SvJN1G*EJc%B0clN_oDmzzBU4g@wf zF))`<3IP-aGB+_eGnXOc0VjWKyJK)J-?lv*+jgGVwr$(mv2EMNj(2R^wrxAvv7PsK z&bjye>sGzhUnWMcHRf2ey1Q0)lM#vA+qtNEI+!xiG0`(}160ISrI;AG*Z_?5EHGqb zB2K18E|&IoqDC&J+yD(z6M%}T1AvJcz|6?V1VaW8v3KxvvNX4F0Z@M$Q~f&#P`5EM zv9z^x0;t>D*t=O8TL5_7+}s4+oL%XiT>0t$IZ4IT6yRcE3NW*@F$IVyC~8T`O8_V( zV;o!^8wIu{3r8{4zDSw1Z*zmu^yaX7&K~|Ab9k9sW1<4)`5Q>I9IpH!*dx14y|T{ZoJ0|H6!HEp0sie}Vsl z_zzsj&io(g=$KgP8Cm}mw{#Y_^e{D1v~>ALa5E#De}wvXT*LG~t0QM>V(Du8pFvFj zQRSa?HL_7dt;sutKThQ<$hv?a~0q; zb2El&G%HNNtJ6I?qo7A6KqS2*{oIC<`H__Kk(`1XG;cct!|iH+h-;Z7!}Vu&L2 zR&ZX6Nh-|!YPR2%^55zs^sm9xv2Bgz!EPe&TrxJ+gA}Q!ShI33YNQ=Y`H&@;VhqbV z`oWQQ64n+U?Ifu5C{QxBzu`;|XsVIsEJ6#ee+j(quY-i=1@FP#kYO8G6qE-#9EEE= zuu(~Li^6|W+&n0von+BT6Y$$0H}~8b;AJJ6^{hJgmA*_VrqjA_`FY$citu083Qymr zTt4q#z9v6^pJe8}>gnB`UhJ&Kf1=w_VNkwKd4Szo|61&bNM^6H+T3ql0SlPIrLxbO z_`Soj)!?~u+rgLVUchg30ioLr6w#G7v6<#ywhVu26RI|gJ0Nr3TwLAe1;=3rlj2=6 z<1~l~Ovmwh3f_dPo_JU5Qn8=H$@?A43ygdlUZ44&eS^G&)E z6C8iOAVFxSHV1P?CTAQr_)HbCrC9WP4yF_d9g=3ZsrhYcqEc4ZH-fRZpIWqFWbgIb zh#-otIc|Sl?oJ-zqd2fj>Cid+=3CJD<1y*5FWTz-IZuw5@1^_Pt3uJn#;`c9)Z^fC z(2c~wbVJ#!Gf0C|B${qQ)b}`}&FIeIjC+4ZHBoaMAI$&(0qzEV_J{pw2cuDf%rl>4|VtjdZvAfq*mE*uJWogHoKkWtj{wBmk@7Bb86?^8?= zcs?e|I~SFHV6Vr9Z(6s(IXr?ks{Tc$Kioq*dfQ1p?%FI#IK! zn3BbRkj+ikM|}kMS+T)gQ@w)UYJ6RyJ8_cqyJ$7R>rEx3=^w}Mo7D%0 zs%UBc9VBAw?RZQtgjQipg@}JN9=V^lWvtW5Q)&k+D0fS8oKA~{qBFg@jL&K=T51Tz zx*F~_W~RmWXT7Ce!V|s&wUs9>b6Z_&KUF1-P10Fcaw_wy#gA{FfCBvJCJ0r2h#V3^cmWOEK68H}D)p6>cqhn} zaMUq=Bs==gf&fX6*|=OSP{V2H*{5V4KQhO1J|$j-D&gY2sv?NPCST&$ zPh-I2ygT>jqt$&>n1V71B#rFUMcFXZj&<6o(k)t!Qfu34Zd1}~FE6=M(TAtKmKs56 zN~9jd78u7~TJoI5Q38MI20uSYR%Nmi-fXiv*c0h;3E?0LHCylbN17mz2W@k2tjrNC zxZGjq#&N*1X>x- z4G&-ApoPqz0^-=FPES5K6rFh2fx6G|NRmo{F)!rUJ$5>`I*Ic)ILPIDmn>6#A$M^b zWOn=D-^VjP0IYwKB4*GUX2{<*JLwI;OgC3kJAo@!GeQ{3OpCqeCF`#k!+W~{QNWef zSZA%a-kM^#v^xZ4%D`8_-`FtE8~h+i6NwL8gOS!(^(JS?uDe)xM3a?h$3b8xL~o71XEO1KGw6C+j;DDd^&XBg>e~MOkf}JfVAW|ADBC5{H_FaM6cw0ZP+lEB8T*H-(G~ zGz#9)+nYg3`Yi$23@_F?|INC&BPl-*QyoxbNB}!!y3n& zf6zj(j=DR)m&f#1yv5jn$2UBz)K0|Td4?VTQLX#z7jhD0- zTC|T1I&kxG+J`NEMSx@c@B0Adm|~tyu`i12fE47=7KRj^_=5{KXVff^D=b|Dl0^7| z4kV0243(cSis%3V-QjUM+C1Bij zja)QrYlopJPdHbcpblrOWIAhE>h95sSAu zw16le6kUXw$m#nH>Z5SvQtCy>nL_SBm5evw$vh)olH=Z<#3J!$d@r>e-P@}qe10jg zQ*<^61H5v1g0gX~ZwU-I2yuV79F0vNOIbXvs9YTvEjtG#SUK&pfsJy>^}4Vtx^FY2 zuo3h_W5GTzE?M`)0N1imnf@k)5*r}H+Hm4ucssirO;Ti# zo1Y|5IQ){`MeSt1@gCq5f}Cn@gpre4=9IAgq{07Ui|CQ$(w~$mc~pNBC5(%?VaGpK zC`g|M!sG!arYjh-hwKny@g}4bjvao-l9qKoAIcf$L=<*Cgjr!F$yuK?2SgX2!z+4Y zakQ6-K(6ID&SbDQRA_m`2V0{gi&BO1Mel<&=ATko4I6Ve2NwNq58S&f#>c$oQ3YEG zBt4?yD_m-qt*h&b)kc2>4i}7T23K$t&GFi6MMWOXCVs2tV)=l5QC|ZkX?l24CDl>6 zu+zM`QiWsiW=b-hmmIF5K~Qx09tg&J6%FqN=NjqR+)Z)=8p>U7>eaE%%TFq$m>1&= z_X<4RA>L;$VchD@q6BiA5%{GDlpqZ7p@|jhuMPn@MM3t6!kvFqhtu9BvdnQw34QG3 zP)Aqr`y0)PGh{_@SpEq_hNiEYg7XE7L~HN1iJ{Z2@G%Yd(YMmcR7$C_N#$lt6FVBR zF|$6}ba**-(K7S*mO;xWRt6Ce?`IJ5XL}Yp4dldZJ4#;<0?$UL>~)(BD`*WWol^+T+sT4ETNkL9OxPe$E4%sku`b=< zT9k6-U!1y&yWS#jp|Dq47?N)Ir(h|TcL$LLWxo2MurtMAvhmCt*h6FG*R9Nl0CSOY zM-G=V>cD@@BOrQv(ob36Z3JMvLOtc2DQ}(9!rBN@3Bt2T5^gP8Xm}n?8G*#W1hXEN z_K^p_h(k*mFB1^e2oHX4Iyzv?p!!ezOT1!Np`RuHK6!#z^AYSxa-g+?=W||R#>w)H z^0!?tQsxIAFt}yAPS7g!9rE0vm6M)SEVVqy^pStNfPHXoJqp@|&FGK;uZ!8h#8dX9 zl9Hxhbt8#RHK<|BfiXc&p2si^oVf-^ z-{uwi;Zc6g`6QV2GWee^Pv%NLtph))iVbZ!QiPYg_VHV2eVvs{2%HQ{S2bx_{JU2< z9U^~V`n7C_NC~ZkT~OLw*lOCsq77N)d%;k|z)BMhe}G!;7#S%l##4Er_8iSJl93r( zB(E#81gLxhDJ0);#fl^UE_e;SgOY~Qf1dokN>IQ>2IAy?$#(s@xb_JPQM`c%UbpcZ zeDLviBW7cwo(;;j`l|Dcn{D z_7|cQo^-QO8FHv<=HM{A);P#8RZ;|JRaYrDkQV088);wy?>#sT&drQz%BA#H@#e%c>0e=ncM*i4>5Zn9^VMW#xpn5j#zhxUgk&1u( zW9^t(_d0EP0*tE=Di`#1W(YVBco{~PAD4PYIxgL%ijE;Khlgfm6?N(9A@l?X$q)ly z(<(?dM>KBuu>{^1e^YKSF*q1?l2dV*SswLh!Jw22Lm z(rPSMtbTLdM~&UI;B}$CAIp5D4Y$cxtu{Q{$W}*|7V9rqA_?au`yVg7ehZ@mj&OQ+mzXfMZ@mY0e&__!4OA755zZJ$N@K!bl76WMX9K{_G7#K1>9 z3itZV$3dPI`~L8sCLbKxj0AXW5vV{=8u_{DGhR}qbjmC$akjMM*(3CB8H?%;rL17( zmVg`0K1P$u8bPZDw%?CP51I}GfWvqoNCMfZN^6>mzu>q=J&yVZi6@d^ z$kDf5n@H_aw=r8B6bp ztR$E&)=eRI(|fmeA2Eun)Iy zrfz}jwnJC`76rP~^QjGUgJvauRA_=#@^#1Puh)N|H6ssaU3co(2p#YBBP^d`WT8Qn zy%^dc@P4*hv3XB_1?S(o_xJUOqTjVfJg0xIgYctpr2=*Y)X2@ZA(}350Evr;2WyEYG#NP^eb* zJpMVOx%6A!{?+dtJVq~PC{(_1wu(;h#^&QfOKeqZLy9__2~}=CA%`}S!WbQ~La%>s z2op2?rjfp}eVoefzd^VQeO!s=uIZpr5?i_n_A)d;UL|k4y-<#11Dn9*m9IxV^S@7} zEL;x1Wt@_~*xn~W2pU;$(BK0eOeQ;O z4^FLr(?@BvKBJxF+&BMXEU6@0P_%!d?bbR##et%`<`Fp5b#T_+j~_BwD-(*@WhP0) zxOm~@Jd?DwaTn6j>qZZ7#h|Qa92bI}>e4}z20D!`89%FRErI5=Qaw~xLtk*iPyAxw zvdVX`WzLa;aq}nrofhb!@)OA;bs+Vc;PnOEWK4v(f^q5QfR1+s_xvR{VWEG>0DCdj z{9DXKrKGOBdD-c1;uy2Moe|6ca@z2{tc3wVZ?`=fNCT8W1nEd={Q#PlDJ?pUUG{0V zpV?!s{aiVcpFKJxDZAb(sN@2`LA6(9&SzZ~c?%#@b9a96oN>xz#uThQot){A5W^r> z6beBoxgH5L#;P5s(?|M*LJoh^wbmZU3!Mfg-{6J!C!kbH z%dvORwL^xaJ)WdgTb@%0**{6LjHsre4JIV;JT0GaJ3S|B!F*|c9h}{?Yx(n~BD=84 z1zbHXQ68qo!)|t*#jRTG5WbTlXYtBIB+`tWGt%FVVu;~<RD-vYAWIk?=GZR1xW z>fu4YrQ4gdvhWkD?g{R3J39uhaQtff8h++oObh$ZHS*3w_BiV3Ump}Ebfv=~>hRg~ zc_t+sQM<-2&w-^x!%2V9s9#x@H#gpd+GSPHE_?((Oo7cw1&dAN1Dh& zLyq#EpYzvH%^*-5p!oiyk)n;V^2u}aRyO8S8T~Q#^f8I=;89Vkc05g{SK=R+ zXI>0s{k78U;L&oJLoUL+DRdb1t<7ZZYPf1W!GoA$nU!B%&_jQU%CZjq37BRj60V`m z-T?ewP05QnlC846jU0LE*%dqUTkFSqjC>Q)~+%~gMAJgzhU-r#vn!H2B)5_Pmz z^B^WVW^P=z3sGz-79k|`GN!2HYjlk1bW_deU%q?OYO`t6Y5>#TAg%~Z9z)~ zd~;Tz7YvXrW39puc5<{PnzwrRhx)=7*l?Y;yZ;a1b7^03M&I&q+wQSGfy#(v5#)(+yP^|&2=+o)g8pX>nXPt&mNsS7G`!M z-h$X@?ZS|dZcj0XF!m#Jlq`JWa4Aaq#&iIFPDae2`HT}f3+1*77TNx36MQ;=i-6d4 zAB=zN9EsZ$6|TpS39rBK9dW>O^2q25Rol@@DquLSrrXvbe%xYx$q4X~f0VqnrQ_b~8785VH23&>GlGzfVB$_UCXRpY4EOsKx!5b_KU#^?xw4nN(6BxLJGPzQs61S>V-D?y>cU?P*+K>O`w3dG@ z49&{xbtc|3Jo|f%S!lSNa6*OhQ!nW{5Qf84#FeeofXk$2K6|W4tYWR54C82~>8j!AdTN?36>$ZkK6gpO zyxdZM`8F@eiE;K%MRA`6uHRkclm#$@F29+WS0MglNd|O-n zjm|8`-ND)4A_IsQOpfJ};u4!--`>_^_O@28Y=5AqHAA)QV4dDm+kU`@*23tIs!8xHEc)5IzbF ztiTkjS-~?bZ&9L|U-N&qB?p?Oc0!VUzk#J+uTo#qdoC|}M}*OBbZQ492e3FWLZG3! zpZ6Ov%{t=STp>Y?YcN9Rg~UXNl)w+x371<@bWakk5Sp4XcO*#T-LVCNeV@jj z&-%=XfKoRKP|$zMFweD?2?S3Z6TXq&H@?;6qR7@YBmi{~QqBP+DPzYekhEf?>{-&i zv=US*g53}3)(L&k6Mj%tLi+k-!3vdU=da(Rv=D!~;uKY)2)oit#VK98!XNedHBBEs zH?NUR#p^Igam8xHS@oL(G4xQH%D!pOT@{XyY7vZfTd;qt?uJ{Pt5?PS4dRY2)f{NyKFC5G$j%v>hw!R-1v)K4jVMvN2TvJwZqOu@@dW-QI{zG@ z*NGBbVTtxfmfp?Ro{|fPDsalY`cKZNy>HwREmwaUxhx+1x!2!$;XPb!rdsw-qVcDT zY$)4Sg61*|LWRl^D-g$g#<=>wJHduLmXH`<3h;XG_(Ba}TTf`9L#&jLI{jaDzKeub z=rVt*3ELY)_*Knzg*iYM(C0`T4{%Rb*_ql?RN&(q@JAUw+CI-787ZNo9;2hV=}WJM z^WSnhHL<>DwfDS#ho0V2=1_Auu1i?P0QXuWLi2{Nv`KP2HF3UFGfWJ=P{S(=65X#n z5cTtBp2J5Bjm@AP{x0FO^1UFG9JugO&!m6J4t}46aJRjEbK6H8QgR6OJc{gumobno zV$*FNFo}+@d0qIK9Tj=Z6IM3%5!Rn=L(7bnXJdnWfq?5IF~|M7+{gM6u6$1H#G*;} zNkAgq$r0rpys?pLq@W@7UWFIExXWesr027@>!G4HvKHK1Y%p(iW%$=P#!4MMeQFg_M^ zV7%#CaTvL|SOc zZ<0iF_R=Hx7fUSKWyv^xz(x0&%+nK_5MmIUF0}@k-z2>HBh1?0Z{>nyaUi7)t=07+ zxnZ_DiW7@r>M>Udrf>_*R1kmBDfwfCe$;Frxt^dldtKcS{T^*3rDOg2-R;kjZPd55 zFogvlR6qIUe=Y|&@Ua503hD%Wyi%@6-vKOm&`3|yfP_CIGWXIZ6jJ+ zg$J@aWCK|l6^+BHQu_!-Emd{Q&Fpv-VgrZ2yokl<3Lxgre;s0E zb5z6y>4JM9VR^Vij7h{-_)iqsUxt>1JS80 z!wyYA(jXbdHh!>UMQU%JJBG`HFxc8-_>gp|J^tz&^z^9UFRXv(n|%oiZ5PVMnjo`e zFRlhyeqQxb^`Go6kV>4xl?gcZsNb}7au5@`c44s6zgc$#o*N?yVlNz!hMLZ#&wkF- zFNM9NN>%EG)Z~KJ$|c*ngZo3UFFVU3K-=R0!%0cd3YS&{{`JiG^ps9svb?<)3poL> z4sE0nungU)w7-9`5T5HCNA8=a8yHO>@G~knc+``U6WJ~0!_FoHldx{0imtDY@~5$- zBO-Ldf|>Za>3mBG9~tg3(eY}L(O{$-sS?uWI#?Vbxq4`dS3P(f_R{OEvrxyJu|jIr zYz@elaJqG}*r)^q>!&BaREPxL>_p|apreQf5UE*dCAoiP1~2#j3V*s(gA{P{_PLdZ zQhNGAP4^45c@*!jm|V>xT{x~p#H*#l&W+vIo0WC>hk-9|Vh|7LmQja4pL*~38W|q| zDi-&qF!nuTsc)LHm{f?c^(2`KaZ;-{Os0_=j3wp~P0nbYOIXqD5?{|%bQ1?|S92b= zACrmGw;O+}j_uXai`xmKaE6PlS}%{6Th=e|_u!|; z6^tSbkF$;ZHitl=gj|;0q8a%(m#R%rHye>&Y;b{xsz6L)R^hX>OE@TMCdM$5km77$ zbd7&alyr`t$a7(@_&g~1Q!Uyl^oM`d)(n4nD-kpmZY$pfO^j1$EgxK4x++|a{Q>r^ zMbe9YE4$>D?_M1k`1PV^+y>h-KdOBMGzh}8d(bg}O)8@&Whu~Z4>mDDdQnUWV*(Ws z6EEivQgC<2Cax(#$V`76<9rhz@74;U>#a#S zz7&E3@n@u;aUBJ5B%-P8k^SEEjGh0yDKPVv^vZdfwZ1sA)eWY-kl!pyoSO9O-&I|m zBwK+PEb#<*^Yv%yi68#oZ6PLPtV0UkzC3@=V>NNX z&AU}8oz$@N~ z`>J9^s#gZEa`?7{_%P!wG76*Zx@-iv$jFrfPDL@^_k;_e3jyQRjd?zK_Akak((gys z2RI%99rC*TX=;|OmTn#EvGRW)6-^uBXwIYyV%vHHxJ{ezl6lV4bBB;LW8mp#-vF3b z(e_ot`OCGQL8NZ+#R<4nh6s9@Jwpg>N^0qXSIlt8HK6eI1GT388JA~i;1BDoU3&X_ ze<}TSySyCAObzD)f=gS~iB4#Jd0xJR>513{yOIVS2=ABRS7z`Fjf8*iQTmBNIJPg$ zfbf9s|NDaLvtZv$z*5kT17rzJhx%1$J?|$0Tz$9mv1T-a#tY5~t5vg;9&c_juM-Ss z(zN~LM6LFqWT`Zv>lf~ItRVI2CXIpKi!pY9w~~qIE}b%&XStig_rCV-cf0@_;@Fi$ znT(_Z*mk6@wpw)4^kRQ;vpLwlx&AoZhb;!>c3WTzr7?#|1YBznkVV(T4K8-5kCaHwpci4gg;8HCMyFsD`Gb6J`Tm4 za?9m4NKktBdGp^2a6%a2Oa;EH8v*Zbjy7^;O$yHyq9)_$)Tw_hvZiAMp-p(kb|IGA z_t6fn9I;k%b2O80XtpveCeMv>5cTNRVGfZ|;EZBkA@Bl1{Ai{Grb5duDl9|rwzbop z*zyf6JpjpJu||KfdY@eP-f%sK@DYZ=_}KCba_29$&xI-IQ|)1N0GiIodGm7K>c!;G z#Ic~^lZV6>uGB^XI<8sH7#+D2?FCgN0i1~;098P$ziB$-2W~h|Ll}LM$u)dD^z0-S z%(TUROjt^hGD&dH1uEPok=1^&IZh65*U5PUpmo!b0N&p5uEBzTbFKMV0GIkUeO6Xm zjTD51+^(5AFXJdYuoF9}zlY0^){vh7=^@h<=oauDPbzC46-m-L>d7592>Y*ZV963< zsXla(@%)gi+TQtH@HZKkdeYq_qu$fgg(@U9Ghsr%J_bTI(=|gvRmjrXQpCTHZ~i0bw<@38cGg-1AnTNgN&dV?gu2 z3W0EQs<%yf zVBC{sYL)n5Ay;M^K9MBPNY`A!A9N*-FXOi(KWCFsu;^^e2S zRuh9AiN!(WH?VR@g{XZm(^vb!b>@QNjN;~VQM^j%&$NyeTZ&hcpv{rG zhZr>+;!N*d7O19a#EbXDeeuhzZ{wigCicg2T_AQz^;7&IsBDO!Q99e1hGn5Uq#kj7 zyg5CtDjj?bQxw8!t?NcB%XEArV*G(vPEjU*iU1;~G1F9vDSyu!Y>MuRRD)aJp_HJ# z2~wHX7t`Y=u&0jVA(+1mG|;q+9I_53XL>ZM0P`q;c1j#$ha1}{>(Kg1{>2z6n_a-n z^lrttmuL1jICf#Z$qvtp$CG!$t%CbBHyM zHXn-Cx;WxAj@>|`>4*=>51zd?Ul{p+$5lG0IAoJBli{a~vWR={uMT8W?4J4a!nROT zg3DRVVS&!uH>!G@Ze0W!9?x@oTH)S$9U&T_I9R9$qH%XTg43AP8gZ7hW!S~GyMXUa z7}r_HNHvqc$9`srF?$llfiV-R_%l8g0`S1Z&M8Ct`7AW@$qI8NMlS)QRqc^~ru4X! zqX2H-LAFNQdG|D|WZVpDIE5dkwmgkrfILTGptG+i;kX4Zs1w#un!o&W`L2bpxDgjqN8BbL5eC#Vx`)tFyn*w2huYiKf2qqGR)m;@uyn zk_)0{9KHBg?rO7M#U8lcI*rkPXRFYOk|o5BaL=#(x+^vW&C9aEhh@pUqxmP@m362^ z-w|#>sQ2I8oAPA~k>0;5DS{s7W_*~6>n}{oI0mF@e_K0*K5&k|?`*GV*09CA+Xv%X zlOn?7M#3?*0F_{2ksAvSqb*?_)mm90%wJFnXkLw{MAR4Fh+V=|rb17Dt(E$57CF)9 z&WS@X3rf!hn`;hMo|c)AJfLZiVu`&OoFKxIeB9-93dC~s=c1He^pqT5G%x-M@4!(~ zuwSXx9K?X2WiZAY5gfpura<>W^)9v?j*De&2~?N5DNyQsnT#{94v_7B+Dt`K-6e>! z_+r8hPRkz9FD+rzawSB6T{O4RX?uOEpXtFGfv?KrOS|v*JY>pZX>)6~G3sugbH7`C zp0&CI4*Cl$xS0L8iNwUM^0vNp1QhcQjWcl0ab5~1g-Z2rPm zh&aVtSI(Lb)qZ+^pynDI`MjNOteN}?qoAi$EJ&57{22zJ9j(2I>*4_yhi)RzT3g@r z0g_E_-wTN$BRAM@4|;FE*1nBTcMvFfO8zkk{O3q|J<93_$O;0r2;Z?GNiGJl;pT2x&H z(DQ{2z(de~U?Cvs8Lkq?a95|*+TYY(nG8a*!WSepB{wpP{#t&zn&dfjZmc=*}FU`nzETyI-vP&<@R zOr$!LuofiXvPN_uOi^fftQ~=_W0cNwAHc;lkl(fMQL|@W=dLXgby|4?hxds85|IJt z;0xBe_57cwL_!RUo&DBQTL2LH>vmkmObf|>g7-Ye&GMm~bhF}ncmkSoTwvXt^mR5Hq(yo_7^l3`C1dxdUNI-3hp+4diXBDC;+K85LIn5y+lohh;@g&CdUd_ zd`>F_eah%F@MJ{>YqI9CzqithuE>vn5TA!{%J`>FzhuS_`A6vedy4^Cv!4tJMn|~d z2&foX6Rs*vUUl4{Z>q8b=0QCiW%g4T9BU7ScvWGIafMqL>Wrd%VDfJLjlkzakCw|n zS?aJlhHQ{S32!{aa(C&9odRM@{Nvf;q)BEc{&|_>4 z-uW7nUXG>08wTQZ2(&n@8@O$6&NZB_-UF^yosfcGFU}JYAXh5@5bb3B%MDg3z;>Rz~IX^&uvS;LNXdyBm9Xg&` z#RjM&h)tcfi|JRcMSB%qS%^0O8Vr}OW-3y(2EJVGbS?_AY+Nv2@MMUs%o_>q3`D7s z&}ts?;_{zdmLe%aqLhHuX=a}W9CAt1L(G`dIL0qLW6`Zn|1J0^%6*d;fMRw>Z;S#w zm^P$GY5r!FM&4I{3{Evn>W zd5M76ee$690x+e?dQI}0GP2Y=o#{JdCyY?0M{1*N>S7#?FEn>1liz{})m2bW3&_So6XqF4DUy zTK*PD{j>rmv*Tn!KXDn#czHH&h!-{q^At6WG2UZ1-lGC&P{)yDwgLasE38Lm!2A z06qWqE~vR`?KG?F5695s$#tYBz4M7U%*WY()%5%J`@?d&o8EyMlrb_i+~LGGI=F@R z1U{?y16KtKF_bIqq{bTF_bz*uF}F_+e52TjW-FFc9fi&Znel~gyOP&?xl)k_?5Sq3 zmL|5zE^=5PZZmfKcf8vZ+~oS*Ih@#XqI|vG(++fh zIV9}$KsgcHzJtCiKci2d<|m2CC zc^*^CiwO+fFgXf{4f~-3S&)I2xW> z{ag1@lp`9?6s!OL3w|kq)=5e7%@mkUbN#Mip$Re1(em{vjm9vEB%UY8rG6={Mv)x( z!U`o!B21uYi)@pjU?v-2I}Yn;81U4bE5b4e?Mx49xU4ps&1s){>xSHz>VMOJ)hvsf z0a0v;%#rKX!&BCg*KxlvU!$EF_ZJ3~cx|1i3>{;$Z`c<{Sk#X-WP@i!JQ^~9o_7cY$`IoU8 zS0BiLn+D*5W0eo+t(hvvSn^Kxsl)KAbqGTPUPA&_^jDwL1rOXzT`b9Ji56SBxtj*9 z1F_3_+&$*P68q2s!NgN|m3Te_102~O9F~5$zV#+_?#z(yljwJ7$Un+|-!|0~YNcvD zImnGjvB8Z7HWl!qMFXu5$UFk*K*jba-wFgFjm{ro)<$gsFcBe>gdPcsORpx|Qx;GP*amFJro?*hSH3bJ$R;N-z*pDN$rLb_Gr zv)mr94;|0@Vuwj1?&}PHlL|x6H}qAJ-@~>}RARPXegw9+g!U-bF~wQ7%#G5ISPj>T z&~3rxOx=om0)o&-_^Di-!F?w{gp4}^z(?+p?b~)LFpp&W+*dsSR8N#YP^w&iUqm%r zm}yZ5qSDDpi`DwY!R`2bz=mA47;`bRbTB7LB1^j~HBhXUO{!#DHSvS5hzz{kffKV38#rL=flkMUHux3z4zQhj-#@X33p>tyAYj zjXzj6Z4SAnCJb$HasIdIKfRlnOAWfA+U0})K<&^XOXO33eW3bv!y0vKS{m!O&|&rq zmb3FBC1=dZq=uTR9}RAf7Ke{e_xa;g6Ij8+t4Jcazl|eHvfi0GwHa=XLdp=A)J@KK z{VA3KNd*WGiO)k@g3*$tuII3;#o^K74RSvV6u@GAeQ=LL!mg8uzS3-Pb_zsPJ+6$ zN)U)#BX1#&be}M>ez}ASOI8#rFFk2ohItZT=TK@_w<>qzH_c>HQG}8kx)zccmv8vB zlU$6vIG>!tj8ty0$3td8*_aO$czp+8-KJ)yT%gu}?i(|^`uT-jePK>)6S|d3v3%xv zDL7F!EsIZQlvP)>)7-c#d*_CjIJ(7NN(I6I= zUQRl*@;frQBCPGye3+@vu3Jy)lE>N#ce(yYvo985bvV;!lVzr4={3`3B+3^~nf=lM zm&IFuuXDam{sz<&Npa5ls($X?m)m#@F5cMeVd7!D=InZu&!Z8;0q%&1wp{%faw=7! zR1A?$Dzf1_B6=2dg^+k$Ha*Vo#-PkZ*a#Dj(BCvJ>O?o_==DW)U-w(9Qvcxvp`9CD z^npU5X=w1{|Ft54n4!E1nin+`Z=mm*EcTy&)7nih$C@Drldvt{Q{2n43nb-jyLBp5 z@ohr~&Q~@_u7T=7DAGiMhYGhlV63z=qZ~FZxAfmWPx!Sf9HGQ**|d{+L{Q39HU#2k zz<>Zt(=Z~oLcMeLU&_<-{y>pL#C`oX84u6yW*V&=)+%2qM|rw$O4~DEnf1(R8$%9JksBQg zD655I9N-4-tTsRIW)aZC762+A-+@bDO8!t4{}q4J>>3ltCNNvsm17} zyjy5IQDJP+3?)wv=!Bw^A`A=`2{b^t0j&1$YP-va@)GI>zhkqm7&}`FwamZQ=yHqw><5q z7}-n@f0_~zXA_v>Roj(O2696@1lzVfGS#0c*C*NxtE-k_WZY#1(2)+gnslO#5$a08 zS2g&;=I^R3!>Ha&erfbC7zAs78Fr*hvn4$K{71p^hQBM(_Lo`Fb*&sg6@JZc2NY=G z_2$|sRe_zapQtb2f}5dUT07?e$l#c*8H((?YoxOMXkfd|de{q~u^b;wdR2yp-!rRp zpQ>)t*q-1K2Br+SQPYh6$c+cR&khwgzOTz?rs$b}cVJr_SIZqp)s&@wB|Eo8XNPh; zBkP8COUS^XD70~6A%Xo68QMT#pcqXhD$azySm2NByq*5$Djdb9{X_0B!e|eYF~Q{} zn6qqrep)KNM4jf?OT70$i2X`#ynWBfEwAYIvTZ>1#r_Z8jj`6v7D7}TIbX~r}K2(YQd7swqR zI{(C(!NBoK(cI;XiJESpV@Fz2(7q(?6z7NVO>bhkpM7SWM2o|JW-hAi|KG3Y5W)1k z+FjEK#_bDN=~us#MuK4|;I6wTH`VZbdOwqRs?M$3>}#E`&gGa!*qhV^b^(I=boWj+jrku)!HxIYRxc zB&P4&D1SXIS;_N7YWFQc9MLD2T(&w|b<&+4`=ED*6-CN_&!jf%=IdA9-+A%~RG|<> z9$QTeLB2wk5F{S@C1n^zX-m&?gp&7=u(h!6&mlw1*k%lPnQ$7dGVCKBKqWm)Kx^-z5nAV&uCLa2BPax9;h6I zW%)KzaO=%~?uTx<`XAA*8u9soWlVmVGkAcHG$-hp1k=v(8#%R@ehP-KRD01Fd)Dp5 zTaSYU=)r+j;^6zD(mcrrE`1)a$}w72Hj_qO`H%R=G~6e$a1|f!tLfp@x9fo%CF)x> zp3en@4ogVt*+}Obo-!4 zGN+s0ZMjAK1hBl5zFZgA6)ZdOY?LKwQiN!O_Y`jiX);Lz-k>LO>L>~Ibeh=7UTA72 z*yW=t#ROP(la(!*C`OKD<+0#vQiBB!TtiIjxA*8#wa_3>ux}J{`Ig8Z!e!SWz;`OV z+x!uKs-Cvhi&v{1P2rqNv1MXjxd$-df8meW{m((9)H0t4(K=#*kP+~&(L1*&U_=^D zp@pD?VACW>E`bb!HPW4z^CSABCtXyXiSb_4mZUFAsFd?T-dr<0n=1DiJpf(y%pZF6 zc!aY8U6b_+*X>86V}qpl^^QZpV9VORoxI_$fQY1qmZKKKqK3mfeOC8%}$sv8e_ z-45xz%s!3|qp^#G=tjHH$oX;`_n=N`nT`~DFiXzwX zsv$Z$IAUX%PPs`|Gql85C(+r#>o}rirc8|C%`w;K+mE`2JwphXcc$*5Oz-T7MiW$j zMOT|Gk%>dbReU}r%m#8Y*c^oxmVd*AEzf#jHzU9SKS{EZ@ zc3)M;$VH}b23f|ZEDPORXBcWw=$0Z2IKX*xBNmE?pjLQG3&V&Rl;53FFf;*CUO+RJ zX8+XkN$hk~+v*HvvpX>s6qVj-@1B@{zM#@5`C`^!5}^F-$`*?5B9} zHo+(%U;J~FO#jWP76wz@O%#5DdBtm7Q)Hj>xoV3NraXs5t}s67X?+caUI40p>xa54 zNwKNm&I9@;Q6s~jp_s6pVN!gh0`$PYV<9!PO?S@f^{0)#k>pfDg=Yiml7rWmO0cn9 zc)@1rNHPr03NT4?cm*M<;ZAIAcUXaRO$!Ujx>piR9airfxU|CFi^ZPur@5{KtH3d2 z7oCRu9~tS1p5WXxHf5o#xY-0Vxn9A3v#z?3)Lh6P+Z&LvE#hTCGLB90dCv=?S( zIfAcJhVtvPG6{0r%}dO7aaC#%Uf(x*GX?t2V~W7GNk@1rECjDerExYgDP_z|wuT)t z<9-T3fo7!bhzvvU0c}Tkz+^?_U3qi*-^7=zZoZc}GfbD6=RXi7jECrdm9tIt7?oCz zDeGb6Q@tzrjIlBZczCz2!=()DVK+$EhgdE8V`s2(F3;@|NeR}6y^fYGf@q>Vgt3_@ za*TtaKJESzEt;8AV93}_wT@3|70pJf!ed&nrFqI>i8=tGp0CrRZo~{2_ zeA;U-UnRUNu)PoG(3;SH&Kc-+$CC4Msl^~8^i__oaPB`6?Fo0>qx>n~Ih>C>;-#@sSk7RZ5zYk@r|9$Fp{See)w**OG2M5o?7} z9fTs!43}t!>ZdKISMoMm`DS@(TV)Em1lwO!0Tgh^o3U5cm@wbc%CP4BqOy%Lxv{Nx z5~A;9U9asJ8bLusp+Wu!MXeFXUB8}5UNVs9%XzB)1^)c%z#m(T)>th7=URrYFa8!XR$6gG4_{kxNwm}1#+$LsCCfY?X`a# z2&&-f2wRon)wZA!OyiFk9fn`g z-hb4c8MKxWL%Xm3)Bnm=%L4VRGH+lMj(=8utJq`TIU0(c0vSnfQWL0NI@0JU(cH3x z-Pt3=dj%o*uILqb7`4(d)M#hgd#V)7{bP0)p22UWO$n&iT2uQN|CzxWGplid0gF!! zK+m8oI3sy~cD$O)SleB}CBfJ1zvWkxsaDPiFrh@MRu+k1Q#t~3_)$=-@(Ntq*qu$$ zM?*}uLOszJ76qwq_6KEgJS)Wsm*p=8%JLEfbT(l3R>lra0-I5P+82#2^6>8RxN1E% z)y&)+VneUCDUUEf+~@&oYj-L%xm;f7jW8f1cT;bFMOV0v(kHPJEF`hJW>0R^{d!{~ zSa-s$T|}YH=lJoRW;Dizm% z_Y=l{k=rRHk83ouwc6yV3j%D!G}3G>Y@8e9;eeAp@f#QhMs}zM5c(~o@^MdlF@nCp zlxlm#k*qW{^@{_k3Re9SQwd%<%WC@e0H|*WOb7$CaoTDKI*UP19NVkmyoDPWmoCt| zZllUvv8ddACah!p_z51)eeNBdHCKm06UH2W>g9u6pqZDICbd&8Ky#*(>>ae{)}tIQ zjSIP#^-RHe)p(dpr)UVI2t&l;6}I+Cwa)_aPT)+mIl^WXXp0pF0Kz7Wcjg{rgPIA6 zE9Eel8;fLSEtGFwlkX%!plbu!Ywl4$qx6?7g`U$wg)`(WzkavZ-f90b;LVcr`cbui z#9PvzV{zA;6HCdgUMwK!GsHqF+Lp2{IUg~bRet9Ahg5$p!P-WodN<;H!*hFU;ksf_OQa$%H{mG?^?N?lZib+d8Hryl zoHY9JyJzCY^>ubx0bCk^2%e)(25JzdpbVtikOLISdYF`ewrc?EfgMx9&019~9Nr_p zml}^wdn`#-f#WIP;IQlN7W3K0Cj@0UlqY{>rKwcq1;nJTTU}QM^M19cB5`MbC~kd> zZMMO8r30(@lW#hPJsMee29@&yP`|iufr#l=K0F`>BXcaFMrozH41{>s01gSE{dU4N z8fzJO`yrP$fm4fCdIXuC*%{ynmI-q-yjz`X@TbTBqa1EUZjcA!@^UTgp~BQ2=zH#p zb}#w9FA(0jA|=gGztBt6P6$YUlc~1R6Ygi}+k*BO#0;LgX6KA-Tt>{tg3uo$PX4ac zHs?lSegE%a8cy)#6b8T$!!*)kYiwYbhLcM6fKFm(nD6=(wDfGBPB~ry>{Mm1bsiRr z+~xV>(hrdI4YWQ2vgHV&R@E!?AuTM^9^&q@_V+%j^yLEK@y=& zcJiq9(SixSZHXTp4%_QD6jriA*uQ+&g9r_@G_OCNG562csKN3C~E78%|FwzmG zVSRImdN0MPU0G>fsPmwIlNles2U)V_N?7QlMGOOlk=&qv#a~@mBHrewHwN{Mz3iYH z8f2JS?^{yLMa!T6#-hKVJRKy0&Me@@eUI*Vq03u9ipc-!e*q@Rpg-EYstm&E!2$hP zx=bCMHuv_Gmf-;IWy@j5$$mj{et_wzBvl;Lkof$sU-68fcby-9-ZjUjNpOpXB7=3w zMoJz|AI$5uqIGQRn>t38SC_`rX}_tWAr$b0b#%i8{wYU_1m#2lpL{XUKi(AxY#Vn< zQpy@)bXHK$7#CGK3g)I8lz3$Vk>kU$YZyF|}>! zRHDw0fWV{uGY~zlVEBmOj=(}dFC9wy_eQhxTTtRwryda$OT0YhNUQ(%Xk&aOHt`s1 z%Gth@Y~S`MM-0hA`oDor5~hTR-fkU)$I#^$8iD54hcFE2}E`zw5DyJ zi0Qm*ow7t2H_Ww$$C3GOf?`9eM(5<;{=#7^?;n%Fv()1HSz z7eKcc5kGr5)r%@@NFYJp35!}p)5+&O%EB{Cn9{KzX(%Ufa(C zGOD+3;)w@;jDKZAYkqW(SN)6(Lp6VNqJjpRcw*m;06di~$AEoGHNC z(TQriU)AqZT*O33(9(ZyheRABWS2W1%By7F_oim3$(+NDpIpmb)yC3bDCrveDGU@$ zfqLtI@SnW+Ic=-~(}EMQ!?nYrbxO*N{pehz8#dzZy+!HFk%=SHseM$v$tFFREQ7_@ zl5!4_{JP<&Fm>r0UFYDOm<1$UytBG1E&AWo_@%P(+3xYUuHhxp(4!OMc4WhuoOxTrDPl6TdWT&j}g(vtmaSvzlSZ0@3E z&Fzmzk6R?37h}jQTz$Vy;?&bXmp1?2knt9mj=|ez%+qgt8{fj|>`WyW67sLkznXWiR*ptMpUaSGU^fkDD zjm7FRi|D*d!B(UijR6xAf=Z&AH(h{c7n?m?XkOY;oINvsj$gLhzjS2Z!L=lr(@;z+ zR*kwGFOjVKTmDQrFz>P7p!JtZ?!6H94w)v}bms8I4I`t*vx?mM$)Fw)Aw%U8*#m}% zdP`feE2K9PA|zpgtaltWH^&VBWMnXZNvyra-QwA5u3Wv6c{P#GP`A?L81T-?D!S}4 z$RBT8(;6?zG#7pYV~JyDAvOKApuT*0ixh^xLn61s{>R@+224pQXsMN8=IEMv!xX3g zH1R((y^(%)@-&ue5|MtNps?$v0UKdR^HtxLiX(uGB2Qoi^!xHsWQopLEeVW&&jSye zdrXqeh}!wRS<4N5dbd4U9ThfwIJz4(&GySIZr(+9u~tyB{`-nvwI#ZTIS{qSI}saF zbi_ukg$rn@eQ~ruZ-$(4<$U3VjsYyq5jrj4rq71e6p{z9Uzehej~$PF;Uj>XTBV&i z_I~;#lL!4`b5REInjLSqF>ycZQ4=27^gv1Ib~a_1S@FcTWm`=>s6vvAPLI zQkVqt0d(1KHAdIM0Tey*cmJDY==h=UN?^XMIO;x@(E(EthGr}>E)V?gP>w=gM9<9Q zV+P|75(akiJV|(wjka6#70OzMc#)J!n3c2tF<3V;Ee3kmFdUT^AYt`}BnbP_(F(l- zV}qbK7hAlo>P)VA&aCx+3*Zh?=praqP~zOv5`<$z>|q^Totv?A{yXvz#ooOg5kbLR zgY~dRJp`%e1~{>Nhm$LZ^fIR(vlN!br0 zm?$%jAZU2&v={V*2i4C==J|^JhB{`}Sug(io=<1>O2k1JNOcUqE_f9tt2Ff(a&Nml zwQ-?51NT%CIV#ZUI?gf^42!+QMJU)n41+0u(g#bJ{+VggnJW<9F2Fv?!Hr?y=i97o z2IFf0fOF_A0m2M_?PmndXEwtE^)P?~#^VRb*7Yx~&M(Dm%^@=z>KyhKr4cAW8mi)q z{*cWjInD1QIHN8W~M` z{})l#!V+o+ntbVE;z%_sU!5>Rf)ai!0>~96v$>_8S-19oz3_Fk^D$MyL>q=;0K?5= zm*XXO0%PtLfq<*utR1Ya*2bbf0t*+Yt^IP9+cT1{O${X1wyZ{x28ROlrI!} zwn_(zH4m^M+_D5C>jx^`S}~Tq0A~JiqIyLi);?etckqU#R$Z?JF*+DSsWBkwS02?M zDmPAQ_fU?1vU`-~DC1Rat%S*Tu6S;!Qb0)y}3NpISFT+EM&5 zB>{d3a{k*63lDPDr&Dtkc-OyuFG{$wxOW)UY~5#AEPB+Al%nSk?uYwfr4JG)0f5SX#*NFeQn`4I5s zC?j{b?l~xebyXXst6nRh@1BMFXhMZ@LeoVG0mDvQm{!2Y zIf0Z|eTH}45@@7CDsamxgKs1i&IjHqXYlHOS#MPf+uvgD5R6ymJ=hi)EX-}UOhK*M z$nd#L$O=|cFCPXZ(&j*T?bsxJ5x!F{{#tJ&YV6>X+oGUwCNE2LY63c1mgg3WLQoK8 zM_j@rex0NRmEjJrX0a-Fqum?M>wzr`Qg~=D8VF*A%TpV2fn`m**+{ghBSBx|gf%gL z;#r>OGyibh9-qz4T_hR9UVjhOOZP`5KsENXofQptf--AaFfz+T)iqx=#CsxvhatDO zKf2~d;H_vqxm)bf0^&;qXutDp#0^~aq41cFYTSoF@d~d>zFte*=eD-N_^A#(9{a^x{c+Ln zc0GQ~Q|a2=y<2CFhc% zkB3zpX=7D&`ZP%2lBLIm_aF@w;TO*izirQ4l~yRC)w*L%V8!VBe8B+YvvD?=>b|mS zr82Y|ngu7GQ=kuX@SzDVD0rO~;AEn0F4?t4>u!|S5mIhT@_^W z!e<}IBh{;;&u6FZh6a7B6J^rg$e*4fkD)QWw<_U`xzLMi-b;K zFvTprdidf1Os5F4T>9^%(T<$k1|oiz#=#uqq$10XkkLrD_5B$um5izcppG15q1z>85oG6!JoWcp-4ZjtQpPr?!T z|5EvyTGSPOlQ8IRjm>zBfk>xP2KpwCUwlmjj6e;0{f@~T$*qM8!zOCd!7qn`cnCl% z$cz*|HnTc7-vb0-Pd0h^mvA-y`QL{t8iTri49!WI9#c4faY4#tIVNj(B_9tE+IMqg z$meT|rK1t!u%hXhb;GLrxUI-{lw-VjDaYh=wMwg$I3uKLi34ujtPhP&Ng%6WMdbnrjzAOKLI%Cxq6wFsNRU;oG~?qeS&8!w!>Gb1a*48;8@x3VJ0^K3_@;ntWF zlcP6VPK{%K$64Kyg=J6Q8N>DO_>j5VPr zKklc>?VD}Tdko*T@U@GWt+63$_~2i$31k7QUk*}#Ub+$CKeVb5o%7pwy~a0?YhhiZ zdWXqkD?B_;u`cmoiGx9Vhfs*EB@=se!1I~_**NbA4?8c#ztnRAYA6 z@Hz15UI-HJ2LjL8wI%P_O>BHtZT6s*da21B2FiJH2olTShz~sc3>>4%2qaKg^EQwP z>s|eS6gkhoz%FNcVugGYe*B0sJ6@#=uVGx!#sXTjC}FSr5#n_l0%;2@?{{QUj8_GL zoP2g3MSJ1;XR&~IeI1JKbZylW^yXaiPm|s?_B_4f;F#HQgbhd>@uhevHr!zt@vl77 zKf8ivF%b@n!F;g0s+Edi5RWmmIH!wd997eQm-yuoJ0gMIU;L49F(-E3MtdWV%O;(6 zAj~r9i8&{!#BYeH22#8mk+a2cY28Lo5t$e$UEsN{8tb{W%%LUSjO0AQ*Ld1_BihMsumsXlb_RgUq z7Qy-$Q?JB)fZk9@skvz!@{(q>kR_x8{XVu)$>qz0VV_n6f*=2xnL_#>o1+rD4&=Df zqbz`5wOv30SpH%`(5+tCVCh*;U=m?}T5UNZfU2CidkSj_6jEX9!!w?MNA2;sy@)YnuxvPEHCr za;DT_F^7mdi#bpWrzH4h~f_)N*lxJA@Yub{yFftFfMcg1#kLgZn{+ zDu=ae^onaxTvTxVk@jF{;jb*?j?NaFGh1w~{iW?Q%Z;@#OH0u^FKlkFfjyPbSA7nw z#|m$&gUt_>fWAYL5b|eI$2a=*i0=2hqTL+5{Hz~>*X}c=(vm+ERZ2>3(6`%^wCO6Yx+`*ghXEQ>2&SgA0k(GFjnSzOQAK_zuy zjyxPQuks*ZZLIOL7t7(Kc}JE@vE6+p+|xR~5Hb0GWq@r)&IY0*h;fFX zUCx<@;pOYm?{QBimzEipu1)H0?ZKW^5p%RBwysm!00Ad4+IZ6n;6+;ni0yS})z8vz za^OGkufbGb?20M{Lp_Zz{pVim^I2XZN6Ys+d3{D=)a@WN%_>3NbM_mwBE8A^|X$oSp+K1voM_ zGdP#bo&z2QI5IUeIG69915G+DGA=ePF)lPPE;2A6C{$%wAWUg?Wgs#zF*z?pWnyVz zZYdyZaA9<4b7f&5c4cyNX>V>IHZC(RF_&%*rp9$|_0ds;N{JQ>EzL+bUJsS$b90sY=_*SzYN=1%8TE zq$gu&tVxy8l~ShJGQLtqxyrao*~VAYrCd^#i9|4(f6CJMXl+GPRieSxSGq}o7*tvj zV@oWJYbqOwpVeEA777_9rM5h=@+wrGSw&w3VwIAu0+DbbR6$o>(V_#9vcxRd%EyL9rgxebXo@AKG&D9g zY!R#Ie-k~YDrwJ+gokgMDk=h`p^}6qWN00<3Z-JC387M&qy^C05;O#m(n0Gg(O}c~ zw3TSE(L{}~QO41Vh>0?h71JojmJx1fxYdq^G>o@Jjb1ib)*-!YqD7J5qy_66UJ2EL zaa)Q&CCyN;CslZ0#yawZq^2o8koJ^?)*8|Ye^rv>DU~8U@LH&%X#s|42ct=kL?>7q zw>0qyju0jhRq!kmcSTksQ4Wa~LbM|RTHNzFn40&)O+^80~7Twm5KW^3UznxF3`t9Usx>fJa&lc0O#bss4*xzl{ zfA6N3^Q()4=_Oe{8eUHiXOo@zb@gXM4W8B>lK!+s(=TWqapzJ0`WFcA5wYsWAFFzg zFtgmlRWi%A>Pb?r()jxA#r$A@x~Tr7r99cI>i5&@MfIsAb>kY9>Mt_gXOWgIufH^^ zva#hl`IKq}Vdrioacm`R-LiV}7*$D z#I1v~;wbYSJG`$g8QaIl=zqZ1N_M`k@gvg+=RR0>}jN-6M|aTI}R1>9YQA2^BC_Y!^$FBucQV>Kg@ zrWAe!&|QTec!PBhrTI+-9(DiH9d6u`?kKz)n7w^4v+v{$BS4JqA0zHi3g5Am`?`P| z}IK)-n=~A#vXvf7A_c;V1D(`d7+BdIf$#$t zaO=5%-^2xOU)-N`2;HW$DIE-gx7&2!q!>gev~8Tf9XH@XN+0w#f!DZgI%(OoopN2; zqjTG~)5~OSjN1`4N5@!We9Gmob9J8f6}zX)k#cSVv%~6dnX#0X8=& zCvUesHJFfql#mdrW2Lf!f31a`XE5AR+s3u1(L2HFL>JxatX_77C|P1-BSDmiUjAzI z9xZBEM32>35+z!6B18zHMDM-q>v`w-_|Cj@zMM02ow;Z3nR7n;=AP>+7(;r0w{EpF z*LaaRKyIy#u8CZ_JdzNw2JiW`Jnlefvo? zDl5Rrr{aTmGDCJfGN;}lj2pi=osRkR{ma#m$N4#HzQ;o@Y!=7FzAW+QIQfqUh4x7d zhQ)`!HW?DoK*t`ihvEa85CefXu|_7`AA5i5$0M4?x39;=IezkZWfyK2u07V=udT$X z9BS!#;V4}rof1bb)Fb<9di z1aE4xwNGkp()Zyy30nl;(B39z4>>QTgjw$FGK%>~>DZ)+?6re|tZ|qR(myRdG^3tJ zz)Bjk{hRYX>b+XmotZQD-SiiOz)@!5Pr0@##i?D>bf;7r46)mHI~LJC8(t$3&jqW? z22Z`_j_)-mrB!Nl--fG1zL@Dt_?$d__nS3xbMdf0S#@+kW8u(bkT{AIJAka!Sz@5M z9`p?dpDt3($nstT_r9&I(D=ja8K9kAl;c~1hEdy^da~O#P+0@eLG>MXmyU=?>7L-( zb~gx4FJ((FC^LXs*!3OnKlJJLK5fNAKNuxKLh?QC@%y)}vLy@)>y450yW2bWw^i*< zg*jx|$GxU9HyO-C|CIar(KBDtR8tTv=|tetX(w{H24ywpc?Ju zTp$F8x)+buCKw_>7BQs7y0%pyxWvT`EvdKCwV~9~o>SAmG&An- zN={U>X&+U}^M}|)*q2l;!vF|>k5xNru{Lcbxqj)u#+I;MvWsGC>wP)y6mr`dIJ80? z&G{G)0Bv)VS-)N%r8gl2U9(Vvgd4wm79exNPD@wC<`0BW&Pg)+2j6|B$(1HUB24MC zy*FOk3;mQ2NNz`5k+S$#XapD1L6)Odbvgz8x*jvhvoUQ%czTEw-VM(z8}Io193r+f zzNST+8N~z?)si2S=`Xz2^HGnp8<~+bwD*#c0HCp6MM^0wjj+<%oe0e&_n!CT$M^rZ zgt_(e3x0HZ9{T6dN_bVUUsFEkNJf{L%(9x$c+@<8Sg~^izi6O8D<{n4L(J0*YoGcj z;B0QR`f|_gXLWXh8mf9WG%Eb_p1h;Qp_dVy*YO|kJ#L2>6p{HtIF2*jmgcA4D-W%s7{>v*Dw`U*gpNyD+6{`K^laV#RF>=9Jc$c6%SCX4?b22 z1RI8UPedu42D*JD30T%5EXy`p=0!5fI_c1exl^{3Iq;2i+0e{=G9_Q;p~3k#?~^{P z*W>ZonD>?9b|=@?hjaM}g;nV)8=<@39V@9ndL zXW5+$W|%EuME*nke+g-Lv$ajvhNm`iPr6kFHj(U1B;bo>6&d7cZH!;9Ur(xSX)BCVj+JeE9qL6J~&S z8gg1q@FgK$?P*eOj_bQ-F}b)@0wu(gct2ln&c0`mo=!(4zrfQG^wW=sSg2u4eC z+trn)73uZElgEl`EEeE~wNm|udfeUJV*^mLovJaz>b?%h8gH} zW_H>4dn`Dk#~FXFtPf`=>(&b7>KYdHoXWL4s?>|h9Hp< zbnUY#%_Fi2%_I9!F|fncs1e>i!PAi7=8~~$KTqXM`5tTe#LTDvdB-}U!L7#&r9)Cs z(hT%lzA7v59yN5_QEK;AuGM-wpunU2kxwmPYd zp>|&UEoOu3E9YyP61^n={jdh7ILA(p4kfz7YeUgAs{WzwdS*I#mMNRcaw;VdLa>85 zs<(*EJN%8n#C^OUt^fNddTr1KV&Divu-VHJTAEtEfjD|ZJCQ4hNl3qG{%6;8feQ0^ zEiSntxfvcuxK2BiHV#`C_)``6Ed6wC$P$=HUpyYG~gO)%mvnBxt@;v9n>T98Sa zL8jNAxzwm%*4<^bLX-LV(;<2CNLf(T5}fp^atznd_E1Eeh=@6orm3N1vgeg6BVn1o zKS}2C3+Z3z-f|&-vIxhv$Daj0NrgExF{P%ZJ^T78qg^;^3T0od;gKXQw5Lde7p^>o z$D}5bl#X-|HHYB=tb}}U)%mbC&1T_??xL}B?`TBdr%DVs1#?>VeugIi2kGp^J1_?_DBx0xAUZ?S(Y-5vSs`^;nvdL-MU4AJdH1Q@=q~uZ#tg$(m zQYawI1Dx+uEV`p!yNzr$j~G&ORCrhT1X3i@vbs%0uB<)H%XZ9~m@B--3y(3X$b${rQC1N=2Z@a5p{%5~|+_CFu!IR2xh1nsvbbLIJBeEfA`eGc0Ern|pw z4UB=}M?K~@)_HdETzGw{WVbe**r_`W(PZjI#kL7NL0v7LDNBtDY2^n1nR(oUH5q&WwNarLe7?*^b@wf&EYKcaa&I@?n>OBRzqGtDy}<;*u}{BL0cC%F zT%BB9{=97Rg8|i)YXsVX792*#45@y8LGp@O`DK23l(w5imoK~KvDKrSzDg>&?1qlP zZJCBf6b`l>Q|tCZN8Oibo2l66dB@&?N)=d*28t9fS{_?$Yg5}9S<OVgUr9 zEK{f6neEmVg^W9`vyIa2dEZ=V_;8y95!!G|_55Nax7HG3nh#0##iLtbAKko}rCx&d z)EL#5QSvb!)m=XGa(4qfFIU461hJAyzXMMj+f;q{kp4^4I+A)0uY9Ei;QQDmb%j&1*#MXr z4R$85WXO(SiK>TU0#B|YWk zOcweKdp5q!ZI+l6us`}q-7Q0;2A>0PltW_Wa&xH#N}uq@&Rz^OQ9NM%HhshB3e3&l zd+?l3%{;*tQ`Y~dREIL8w;4J#(lIphBG$Euq!}7~y?QV@Y6HGm+K6obS#+7;e0+WY z!j3`HAT6$B+pnU#$DtEM?7^Hv}l=&SJM5 zR)OCo6=*F@OrJefs6w$C7VB%AmOSr=%gc}&xSrVpK9{$VH|=Z+v^=tf{A}gg?|@%S zQqc&7@iM2FGD{(a78r|DTh^k>4MEo8(Ix$Ah^qkQd*OZj)sUUFM8nwkm&GL_H{at< zub=-qG2S%g0oG4!PwpLJgn;d%KbzRM62AoA+#GIiT-`W?CO159tVHzoD|W!&VtF8Y z#Q5nqamCwujZmt~&vn@CANncV^IPsa75yo%0{;Ghj){$gKiBSh!Io_B2#f<3Ou!M_ z%$UUq+Rgl`J&211X=LWWlmU5pMV?fqVQ*#I+#CZ&{nS@=kij=R20k!WHaeKPY> zqGX=fQ3ct|)IrnH-wjJ6fp3^M50>B_LB3s+eG^>rF4tyQPib2NN|pR)s#l=rGkRjB z04-U9p1KQky9M#(r*mi6%@b+Xdn@a0{%vAG^vJCeX46KeG(#=zSz=Res1y9r?$$NQ zD}N3bxT9(P)aJjJ(EtWjz<8gk;6fo>^EJb_KN#S2mokLsUvi+uz3+K!LP%$j&V&ld z0Q*RX^FP}2bBSf<*y{$NbqF+Q{h%#lG(Rb4FF*0h7hSc+dh4j&T#>2O;a;)3+B}+f zOQS5xZbNvU)+GA;dV=H0M;p9$i=H2|oR;IA*9g6!qaDJdW`J{FMM*J}V`L;jhfjgS zXdv(+LmGGp#Qrh2TAhJzfUHfBEEJq+(L&ZG@T=Z2)dMhD#_B6qzC|o%bG1c79e0_U zi?)jZ@0|}(A@yQ8=E{bys&JPOrjP{{7AfQx?4VVxSRpm3phJgh3Zl2F)&IJ!Yps;m z$IF`sSyB1}e?3-irKH>?t1Cvyz;C#b?-WzN3kFR|H7{@b5McT5Ut2l4dbzheGp+1j zwKaT`i&fOVarbJL>sZ15axe0q?`;E0r~mF;V$wFm6ZO|RT}Lq9f#6a{D1cCDCHmVNf;Y%&hOe0#}1cXo>pB8J0Na{m5A9~GNO zlty-CvI6avy{TG&cYC$$nUp`S&Z#J7`Gi0Cp|}~{bCpwQ~DbE zuEoU_P;;bWG4K|%$TDzdS4V~!)O{&X>meSV37x_hewj&g=Z+$^NulmXuh*p^{0Xp~ zYAOin%3+b%c((hs-8+AB-NnW8lZ9OK4c48*^pY~qD)P<*hrCqt*6xBAi@uJTyjtDs zNgGsY0OS=>QU*aiqS_B{`JH`IIiguFUSm3eb7OB#m+&Ndb@QM|m*Q~}hxHC^cs$g5 zqs`P%(frmphWovW$$jm{v&$f3c5q5|2=7f ztijT9(o!-I$wyMsau7`oNr;4`gc?LcUR*<5R#sk4MqL^7|4Z)b{g;hCl9U2vNW8-p z0C-1r#qe>NdJoRBK5E34S2ff$i2azZj%yI9Y7kxK;Y^luJH4kl5gxk-S`McC812UA z?&jukx5~hKPlGPL7*AxCMd>V1)v6M3+1M5LKePVC@k z#IW`tC-Zu?knTNuzU_Tb-IS0 za96p3>ubf)oWTCh1PgAENum zRjY!tqm)_p@7o$LFE8-&n*B>>@mOXdLOaBDcX`}#(T&p=U`l0-6<=8_nQZ+4=?Wi1(O~DDFHB(fj}seZ~+8=+sGAu&#zG5D8OQd zGaL>Xpbwj(E_MMIy?B8IcDKct8re)FQ6;Ik`S(3HQY1}f9c0lLYk1~zX1;Sjet-Yw z?X6X-M8$TE(_7yzBmdDZnn1$abTn9d9M#lW&=*`TNt_!qH9Tk87PrUHc9>tP&HO9F9$5 zj_Ywe=XOxg__RP?akz(nY9 znihs|IA-DoCO9t(HFHDCgd5I?IFjh0@@-5kH$6|S zV`X#ZsjmTz5(7$w0tEJ+f6NqSBn|S0@dLpU2$c)Wcn;qbmRw-QufKX+_359T@50S& z<@8PPGhQrzw*nyMXj*>Q3uqieGt$%%G}^`58PUOnPk3Kc@QU7K)_Tgdhrz=C5xgtBA8^HWvgPGK63C2QF>$PT~X3uk_t z>7Qbv19EA?hF+s4Kpev8*7}MikTSt7`CvVk5+K%pRfo`a;ly(u)?HP=0p)%V1Ds@W zVcb;R!F4pU+c(13@7tP5nh6X&;z#KB@Fh{b>u*pArQG{gJjw>2@0MN4oj+E)dXM&e zk(Xn6t?}OV@!fipr4BCG`x%fg+azA3g%wO=`G=D%=^9T0{K%hpLn1%HuE68!Sc)Qm zMEstAi4(nMmz$4WZmLY2qz>dt5BWu@gqPW5ysU_EAd7zD6((D`xNxdpfPOZKGa%Ed z>cf(Y-=xZcM@D-};vx}G|6HLtq$&kfZrPcU>LR79<(Ir43`WjW@dF(om_)syr&>pZ z;&_uR6Z=NW0c8c-SX@A;x;E^0AjvEPpC#OXS!r-|5y;36dVL#-N9UTvqaoZOdq&fa zL9i}{mkXNzkQHu(ri*h|tV~>3IlmCdi_xNVBs9HnNEX{X>(^vU!f-Jv@`%k3zN{b6 z80hx!iUp0aS)3)=|4m_FXu!Hh>z?B#?qZa)W%(lF>~D#7PgaW$DCINK1!xMo|%|PfeD8|ppuM*pG4K}hI+wLi-9Um{@*x0e*!#U`yd&4i}cDRbe z{b2HTYVuZe%CX5?F?l<?!NXivVBx#|eu z`7NTBX?YpZ<<~DMzg9YSE_JM(0wLiiz8ZeE|6byk<+0I&+0vsE@)O1s6h=2j{@?BPn8+PvR&C zoU8uAB(X}r* zykc+#=_p+or(OnjX0zOj%8Jxt1R$%hCfc2kWyf}CCAb3B^XHK3!A?^sL%|8uSyDosf9(H3xomd!i24IEVMI{vE32soTF1uF#E!`UR0 z4_x+c!=7G-7ApsO{%pg^H*8Dz)k&F5cH!F&EMy`1J2g_WV=mrOkzWw(=e9aN@~7vY z_e1^as5nAIAr%?A33;@C<3SOH|N6seA5e0b)TYvo05;9JtSG<7b0xjubQxyJUR}g3 zh+M$KmC`*ZFn^wwk&A^L)qJD+PG<&i6J}VVApt!m{=(Vl&T#mEb&aPDsW_wkImiLN z-$+Fn?<9{T>k&cB+0dg>S^?LUG_7A=$x#j5us+_PeEMROCr}!Hs87{4ED6gWq4Xv- z$*?TN7K=QJNff`bzR8h|dQLDNm(jqgXG=$g<{+adA)y^%^}b$u7&MOSO+ zq22T-4$Mc5vT2X(Ydc|I0Gc#kqslvu`H5qLcTqY;8cCP_3XYolNO|# z-c*NwKvcT(T~n2zeML+fya}X( zat){EF0mrVVsaH#9WNlugdNpE)THVB@K(n)B_C9u{3AcuNyirFA-@a_%GgU`D6+&k zk6sVZgI)Wc)bf6o<$jOqV~gm!#oj}EW}h^qa(&}agTwB8wVw#;(kPb}97s;$=ioKq zIFN0xSfp4%V-td2A31A=SHGy8TIfQY?3o*kNXZ*Ma-&yqm86R-4(PSll7Kn``2 zF|feiV(`OV%(Z|$EC>K zGqFck3*vcRnXVeGq5Cm_>Un&{t@ zi3RakZd9BW`XZEE_nG}m*Fk;*8!2tuM{UY5iO5}E+{Uu8BiU^FRvXkqxt=<>UOSV% z008MW5KHO;aU{+Ry%ISgsa;QgeY(-$0SX$;tT!9`MIu44 z(T(o@`T)PW`sDK$I$Nzrxgjkt0H<_DaQ_baS!%_oF6MI?4{6syQXwpoXfzq{~U{(qy7>yGIP!cPiazk@I zJtJeL)M}HZGWXl@#d@QpPOk1s5^W2jSrko;qPg*+>l)Y$n{2D1FLyNfuIle-Z~8S$ zfA0J~-A4BA8ut!30$DY%YEfvBDwz`(ZBg%<156bxd53#j?BAp$L8#J=SJQ?wcw0V4 zrGKtbvc9}+i@s{=^+swvY0`-cLY!45lVD3H%G5DsY8ZC2s=ANzrBkiVYBmwHU>FB2 zR2}g({P(!2Qk&!me6@X1kr4RvKo54uf6`BF=>I@^+LimNzNMkEZJTzWT+@3oK@xGIcZPb0osFwrf1gvm zUic(X*wHw-q z+j~8i<5r)cNB_)I+3$fq^JbtzGvEd=O~AiRh4P^Fw_=TUR^1NFTb6v+!+Kq8+cS7M zOI0rD<-e9aydm@Ch&-qaxAAx=e`&0sp|0$YAnZNey}K)0|NN#c4rNEz9{pef$a*^v zsCSp#+Ipa%{^(S))Vro=7oJzHhxQ%dT_yiVvL`p#XEWbrBYn z-;o~SqC>bR^}?MqoB3k`fV*nD_X9;g%xKWg2XYl{B~BRr`@ZUryArwOnL`QdPy${9 zO}pU%MaG5pgA>3c4>lk{3LYQ~2DWbSfk9T4TH(WOf7h144(ECD?_)tm4B&x$;h577 zUIZ4718sQ&sEUfhJA^(re}8z7{=iNVW1MNm(1lB$T8M=nUA~W?OP*RVT#@F=YriI8 z0PqxGHaLe3lY)7A0ZVa^7+@z;%k%=?o4Z+-8V2y7Q)WHZ{?>EM!!VdCHb%jlm{2N} zYMk+pC}0YReld|U%nMFLT9P-M!P{U6H0#SXXx1d(Mpgo=jxR-0e_UG1q)f$@dKq6z zi`Y^;l{~ssu&*}FbgU2+iu%d_kB!0KmyRW zv?09IX9BDqRPrOuP5H)$SYcXZUD`e8cB-~Z?uG*G9d*;fV#_?;?^eh6fF=heQ z0}L0f4;bx`zHJeSDH4@G_0iCqg+ce_I#)@#?VV5%a9>pAe}3l*qRb;Q4E~{lfFWS% zdW{)jRlq8Hdh|5_ELy-*V)Ph;a-Gzr3x{xp!5Mg<0>S4&IPMZp_}{s019SHq;-9*( zguK7S7n}XjM-zJNqSruNhmcJZC{J|00bI;8D^=O~GuBgk_!c;f7e;V>FXL=Aehs~ zh{+W4k`XXtWFX4TsW2?&?3gfwwrW#jM=*a8qh?bj*z=h3fjBB7tf(yy*o&C~>}{rl zW%)1{f3}ljK&IMr=#&tmMpzRJLOfrJ7_P=45gVseuJ|G2mKoW@q1^ad^Z`vV0>@Uk zy3x~kixtp-#t=!+vC9E2!o{^rH5>IcI%}vV<#L^ih{ETHB3Xbag7RM!si50Kaewa} zE2r2K!3iczn&o1F6N|JnODEAGhviWj;8I^ee?`ck%(xZQumJ2U>f6#+*G~N+2S?%| zm=Gl3hC3OpFV0TV(=3(JEHe6#iNFc5Ov!ojyO_oyB8qIxN<5bcNbpXU%}pSd_Hf9e z#ymXEEXXG%dz4wsYxB@@Wf(}LFW=-)0lMdHMdsZ5C`jWj*y0O*ep?{sCqFtV9v<6Q ze~#4~d&b71fhs=ajo{MEq{=RG-J8ZIM!rSCmvJ0MFcO1@x?t?v8P(9esP-Plug7NR zg!(a##>O0c*w6v6h`; z?IZNQJQD&kzM3(APDl;)&s@lF&roCee=ko+$lSTPEF^b1(Ok%vXAHyIk07Ktr3c2# zvY}BNuV$G=_?*of5Zf$aJsbJ!nkZvg%5*F}FlPl7F**VA&*Tdjr^ftgoKed-ljX~J zWrEWhRG|c;mH|i0#d4_jH?wJvt;jAdXd?@T__z@q3I}UkUB{%E=QSIV&3d|Ue|_xy zMF$xwO<>7&TWm3fed8v&9wy9iaTNYte;A5Yg3gS95TDQDs~ebNsq4~lUq<0#_r=y< zx>x~g77k+{C*v83hmNq;IveHGBFahM=WsDj4aHJ~zBZ|tT<0p%9MY*U${i8dFgp(k zLC$H_YBuYMl^q66SAYZ0cjcLre+&iCKXvZTCgL9fQFsW7Q`&hht5YKXKkY7>C$>7q zk`#8h{HZuVT=yGa-O#8{eN@u**z@T9-B@3atpFG-_Ki!5;kClIbtD7rm@qkU<#sU| ze0Z`J_Pc$)5oS}-<19c^X5(e@$FCImNu_8nwwC3xwH%(Ob1QY5wM1jWWfKmyz|rnzekI2z;!;_ePx<|ZWl(}g?S>05z#x!j7oZQ)F=^GW2>O1e5j_!##APTF znS|7sg`K*W7_N(b<&F(R;@bXWt4s{7vX1WP96(b4U!3&u<)Z$_f0-^DhPjtpW+?mS7)f%Y6w?*k|hC3$jmPoveq z=5Ufw?qXj!3||rje_a)b8g83?h-enUW_xVg@=UT6Zs}=KgyBpsg7SM-+s{mgA~qdR z`67B)FLWve*}VGI91DoZvB11TaIXC&sQbk(b-!#N=LhP3fkSXH;8}mB%*l*?N_U9Q zqsIh~3vxl1|7lg&)3T1A*|V}w>{;0l>P0_e|HUcMNaJeRe+NKnDr{XLqat!Pq}(UB zZpwGZ`{9d5gd?t|Rti@>U~rk-dZ?`FcKR40{A?K#2+rm7HNwUnOK$KW5#ifl+_*jN z-J!k_{u}^-4q*_04*udm$9bAf)yJpN?~Ji?hhMRTU#l!LCWf7>*|h&HB!U&%(M~Bi z!S>Zny}5+~e*r(>oz=pT9W}wnD8ZMjv3`zCnVy!5>=GVq>kqt3@8!;mY)A@|YLf^3 zE|-pE#s|vG`k?AR5`LhE?z2YMi<8s07clotJ$_RHvygrN1qnR+1_CYyWVh>9&dD}! z2>xkZ_x0bLgJ|vm6Pjq|E2K@emXCf%fL$9t_K_$Fe*%J25(GDRPTxD%%iM`oEU+@0 zrxL#myIe#*BjkJp$h&X=Zp8P8QO&y=wYv&M%xmLEi>|1jFW#b3)Enok^ z;GC^xMLsp_mtKe;lWEsv=R?}!O4m=mzWU_9L8}Nr3T19&b98cLVQmU!Ze(v_Y6>$j zATS_rlMNUU0ysF6fj}sK-CJ9e+qM;c-(R7=QBw=W9YivDXxd~FPdk}5JDJQlZilPo zS{zH_R-)~=zrN=H-~|*YaX0d~?TbZ9Sm5B`T)y++`0Lx7KYYvWf>C0rWsBQ~MXm@H zcA>2%l=8*x{o+;jVN)K;PL`m!CDSs{24Gw47`z1G7xo+x%fB%IFS#I6@9MzD}sun~pR-6$7J96{=Gqu5$ zBm&NH#bI3T$Nij|&XU~9;TfeSlVB6w=`=}0CRW(NGz`vv!Q|OjVKxyRc1}zVf6WOC zJJ_VAgi&I#vP39;Zl9o7lSljfdwMpZ&76I9Ht{oTL1bSpS4^AqreP!0sA$)hCJod5 zl$=h06X++&IP)wn9qE^;X$&#&#XzrV{d1BV8|nY2iPMBLe~O*W)W1&bRGdyau(m2K zAImxTX+JD~ZM%#prV_RrZ$uHM;@Pfbl=BWenMe%brkm$?AxY>#k}ysMk|?VDpu5y! zk}!_Zr5klcxl^gji|taEK1p4p4bogK1_Q6-Y!?Hce4?*8q245g0%y{lm;8Pr@xo&} z%*e_XD zJ=EL#qyOemZmTjpuMh9mRk7WEjQ_}C7596Mf4wdrn=s%ZwJV;3QTB(t9qxzWB<}s} zek>(_#&$rEEJ0B``*xX&3~>)G4UlN}xGi4<)MU^(MU0vNL&FAy1$5{2;Srv-S&iWE zy+eox|BZ)ZF!WG2PHo4eE5R~CclrCr>Bew(g3@q>o#`6TJ!sLI6}BhRf-`^^tHH3Q_T@q0HM}pYHygC~J74V_Hh2mq^Jj7I$9CR4N*@T+ zX4^cUTfHgO<^66#{#cJbrQ-)_D}Dse>pg}EdEC@py;{n$4t zk83*&BwWD`WiBqTi|kpppvSg&XL< z4eRBs_1tQWUbOL!_5iRl6mu&ccvzTVcy_B+_gj`)3RD3Xly=qvd8twZvb_9$%Y-`8~j2C#B}gv-ZZKsrQs zfdtK=6zK*Php=XKtatU{5jF4L5uK;EFxp99f)U^ z?dv9(Rgxr3g-WpLT6+@~ffp89+!A8Kd%91VyZ=Q5GbO^Kr!=2W5nP zhMNV{okT$HI}?;8Ufbm7qB3WkSXfaaFCYVUxNlN9ibIH}0Q;cM>;oT@&Y>Y50-};S z{k57k`Xmgay+fF#QbZI<hSWw*<-HxIdg_{WDMqi7OfgmJ_|N%b$t7D z9$=d1L77WN!agCKIWakIz_noD43jgA746nEe->yo|z%e7i4XQ zFf%V-XUCwYnpYh71&2r~eQAPm*Ny%TuNvL`qY31el$ludc{QD|!0+UU@gKn#cobbe zYO~+b&tLeD`|1FHOE~TkU+V||iIvTvz$EXb*oL3OFqATNej0*>zB1(oxXyOk-xYgD zhz4!ly=%fYJV(-Q?pXWJDwY??TjQ=oFVS2r#zHlCj1|D=q1cr^PY-A`_~8!K^f68D zVQC?sXVoXTM+~hxfJdeB)}hDT6R(ia(# zlEsJlP4Y1Hyn~F$`!4{pQP%O2C|$2mlqy2K@V4G6w&Mol%sW&W5^pirFp2#xb&1`J^-7j z)xv-5ipR%)$|3s+VvR$&Yo1B0-6rs)1Y7uYyjuFq72)Q2yxMKTXAu#r=fNIyS_TlF z;srb=boa|Yk{9rpdxXD-&rh~DqP>(Rmd$0oI6(Dz%kzol#|*lla%|3K+MJJNx?zP` zo4DOHlf{FW;51UL8)LV~m5nLAKB~9m_A%Z2B;aq8Iw2YX1(Q`FDon;PiOeDsw$qAA z_Yf!uKdYevn+aC}#R=@hf;ezep*Jn(t5-wrBe7r(WrAdhz%-&@@*d$h3I%DK;FbLs7lf0`As|tn?3YNR)Ga^HAuIr*!IN)o`ydcV{HB!o}L`MKME z2bST}F?AxR>2`qr`rLo{*WwWp?PKU7ywDxc-J=WM)&}sf^=Q|xgAWlfg4x43lRP3K ze^>^#*d5v4KMbk|cq@{j7Z9Q_qdXTUT|>;UMJ~;0VAr@C@&_|ci{#didmMmH+Y*6ZSgonxegK4 zc{X0j2iCsYuMg!e1YPHKNbqCrvcX`Se`K#HM9U!vVR|A0_7rUw;RpAMk*~Lvsp*TL zFVcveYe&fW6~?T$XW=NnOO?PO@_<|)bi?ZhUf>9Ns@bME)*JB09p2@ZQsi_nuW!>8>K z^1XYQ-?(xAzcAGS)HUK1+hg5czpO%ovxCUV&KtblX`63&XuerV$+PdnbdO)y&b@{J za!7hNxE0hA@@Wu=ULcw|+G;oF_euZ3f_aEgL_)n_FG8MHf+MCx<>qW1nEQL$eyO4v zQC@e&F0fZ{RWNScht zPVypwAPAxxeSGL{etUWG&2!CWoW&_i`Rwv)W_8SDI!n?dW=za3SF=~q&-0Zak%kzOuitx`vC{@cD~BybM?iA9?CS)|ig zCK8^cCtkwRZ1jugrR@*oI!={n2fk*SN%-L*w!<1y*lIuYNocktg=HF8E{jd-rQu(p z^(}xNV__d-qpchFYiL3Xe`J{c>OzyLSf~T7O=z0I%89;(FgAJ?nvL7oSlbSM9$uA} zXD#a2`NBqjnlCsCWpEoz%(Wh@aAMBGUcq!$$}rnNJ(TSe%-9jCg@q?{w_X||<;=vX zVV-DVC2Vb+$i$6eK`BvS31DDv9KPSQG|d(Y-o+BqVJ4It@&T0sfAm4525iCBHJT~| zo!Hh_sJ7TqH2wzaXiA!cm#d!ISf@60yHgZ;cOx_shP^s|l&dgBa>~N6@m`1Q9sXk6k&(sMKnoY+Fg!19}GG$d4Lc`J%HQcgJsBq7v z+OAyNsRqd5$6b}zwHIy{U6obPtOy<}uvH?qCcVoX3*a%Te`GiAvH26?&0v}*NNE}^ zs~m8F=Z5=3JF(C@`ggu;O7za3LTdtqqP6W_$#u|!#X_G)9?X=486^^aj6xGDo*Wpp z&KgJ2E~{%q7)0F~NhmXG+wpNVn_9JQfF?tR{IkHhn%;iz`fxAf$?DOU%>~In= z7$YIcKwq4%e*tgKlXM86!1f*>SkQ_}5lhCul%)vs)#}5bY*TKpM{Z*U2zW_;Bk+n; z#i`)`6IS49aN!nK4ikZp#6s9Fr{Slf%Fn5%Ngw(DF}N0Loat47=rf5P#5##12w!Szi)$f85~c9QH5 zx5ml-h~MpWVqkp0@ZQ=Q$%Al(!#4KF42qZ`ZUNJTm_Dq4eR> zaaSame`m>i*gJbyI3Fv($GU?bx!Jrb-p>JR!od=H-}g>*Q)mYuI9L1>xFb%1I~e)0 z2Z+_4n{jRB+a@c5{(oU~Yy^@CykY6FxQuzgxXjr`bkc!>URcyl>DRTIa`0e9QYk(k zhQIj!^5VA(>}E5VG6hQno?RtiF2Lw7Z!TWFe_^u~-27q2Vg)AW0}Z{I39uCg4a#Qr z^5Sn7-%>PnL?n0)V7$_(cf2DsDCocv&D2atLaQwystrMa!BINgot!lKmc2|Qh=z%o zQe(Ca?52Vd2MK)^JhP+0R3z6n5v|Y%wI>EPz>dmx&8zS}ImSMk-%tCS*L&QBjhX{I(q0S3%8!2es2|AyGF;eMWIuF7WD|p{&IuC=A z$5r{{u~mKm0w=wX{S0XMRcIbKQksJRK7!)?_ae48UNF*u)kW?t2H5~6!eA^>F`y-& zz$LF}^mpaWE~|1pgb~Bc+615z zmdBQx2a68f2NmBAkcd%$WCQ@YMX>PWwolGxN8@thQ@m`&y=R2Ys_usn^jQP zHJo%4^_3*zZ-wIzQ<6ghQmV4ae;TSn!6bA!BD|kj#sODVc9T-?Ljt0c>aWgrgZ}9BY}-8)e+NqdZPA;G zihL;FpS8t9z@4kAya`t82#P)(p~;frIX5E~`xmmIBAb+?1!NMyj6X^Inm1KONu*QC zu6`~t4J(=Pc}v&wUHjTM%B#_x{G%(yD!2V|4ZL%MMOxS(zy|*Voq=nr#xRH4u)|Y3 zfQPkz)ct8G`1hCY-*FNeJwj=D znID){d9X?>s|#1|rrlid4+}tpuy4rn7!|$UQ~8<#0Tpd6n+6tOe=XX6nfs^LzEOk8 z@?F{Xx?3%D4D5P>;nAQCNNvmxj{7pGYtraYk6<>ySEf z11F!Z`l`BH549!ge-HY-&{BhY#DbB^y(Ryc-Rw4QliAccCgrh8l3|J9_d%DKoK_wP zPO-D^px$mR5SjA;3R{X;Bg+`odURTal&osHK$6iJbO3KVgFwP0t~ZREkY7J z-gmB({=T13GBQ;jtbz(N;ko^&J47dq6P}JGXLKM{peq=n9u!ZyAfXyp271J`%IjrS zymcQ0csP~0@tb0sXO(O3vS#h^+t&9u;93`y`z?Jhf1Hvwxqn@Y8R>NA`rNUQ4#JB3 zKlPS7hx*EzPEN{K`rxj=Pyx>`t3R9F%>$On5@ z>Pj(6Zrzo-(h{D4J%h8oF`mv<6AG`1gmOrfxDx+KhH7H;bgo*Sn5aD?Yem2!=(=Gz zuK2XiDDEz5H&XWPWbk$9-aF3{w(ebZ@DxCpf4~RhG#CRX-5cnAPl!gaT6_dMCY^yC zI)jPiembIITtjb@IOQ&!VOp)62wxSe_VcQF``uYDGIl7abq5$6zg_K@q4?HFP*PAR zaW(+Czv<{cd-y!2HwI;C|4zeu4HgHh~2SM zf55R*k(l<5o!nY%@SA#7Z`FAK4` zDc-rvWC-sAL#?n6coZLfske}fyI2n{rTf-OMHujPPE}FFXhUC5(B&$p4^KQPp0weq z9C(-j{=&RYpNIZC24x}-vJlc_U0l0%e>dymrr2Z^MoRFKKI&3FQiu)GKx|A^))^KH z{W;kt64k;xS{Z(NLaAuH@^Ky)lUxEOZ0R}>;NoT28bpGzBlBYqkP_h>27I0dPv;i> z>xrlHAvF0%@PLyh`hg8hzqDb(z-VKq4UCvJF#q?*y;Dzn@^Mdl@?H*}_~9w}D0^UL z0Z1#19lkC~vWX+BVfyYPD`$*8RfN-CY`90ax<%^00|-f-!;^n9C;~M&lYu}ef9+iB zliRit|9*dk@{KpO5Il%iJNeLL>Pa$5+B#RKGq$HgOT0TKI!Pg^bN%0UfdwU!0wvyA z_ejT|M1f0ivDn9Nfd#+5IQ#M?w-ZK*rIt-DE+<=O)Q#^{RXUP0A)8iuxL9 z%Dh^`mA_pe-Qr_-e0jB5WX&T;wW^A`SS>?awwxnrcyQ%uW<~A(e#E!We^xi=ta*Bw zFWs%WB5n|qsTIV?$&?8YkVWP%u5%EHU`Y+{cjP*$vEkNT=QHRH2I89dR$e`MQ%$7a zisRo%Bg8}#tEnfkpbQ3HOq9?_MPp($M94{t2qYVOpCSyNn{o!PMZ$TYv<&bt{oXb7j1stg4>O~41{UYHcP=5#zqN_!f9A!n0=M*4HMn$p`Hyf zjNPN>EN(4Y>4Oe?f6A>P)~1uGpr9^6o4iBy&JVpH2amJ5S(WSSqPoF5@6lU(7yH4x zU2u}fsO+i?1U%W-8SqcLF>7M9g_*K4cpDq{fsBE>X^}ZDV^Nb4YPXK$B4R#ZtXkg1 zzv+WB(fGG86FTW z1<(;?8wAbA+Oi&N%lb~XtVda#ZrgHwplc3VA;rXv}R%lkg_mv38Ma z(0#CW4tmsh{O^|MVBvLsRb~!U!LSTVitzgbfGM~;%NFiGO}@eZt8!i}vpTP0d_WB2 zlt?SE|6k6He@MWOaKKH=6*>&~qmp$QkXoM4u_ga+Hmg1G1KO;@#^7o$0dcL$&`-U> zd-J@Sl|`VyChxO+XCA4o78@LuYg%1)Xms*Z=J>h&xrVXetzwCHJc`sfaQALOdft zlmEWSc27Dq#XS)6H@(cI-%(hhv{V8de$ z9d{q#&JAlPK|Ic0%F_p6?^rLv`qxp9Mu}((c9Rn#SE z!u7VFe;1f-r2-%a#8huN0qFWnFrEU7ol_gFoODmOqIs3*3<9!AK{+}An+98iizc7+ z258g1C&0$bGP?dKL_8OekJhVjfLr(qp$EAnrKzg_b2FW=HnI=E2T$1X!k}#aC zZU*Kvb9dEq556(?S@ddwd2WSs#tnq$wCn7$e}MfoUVU`pV;~5~v?HUHoKVdkVzhqV zbO5a|fe1&Dn@tri5Xr*b>f?>Ok0E2Vh(j?5Uy4P1jve$lFJk=w&{SK!To3eNx(cWV zaV;b}TT8f&Lu9MA2*E{2H}GOPFJ@j%Q4CHCf4MUfKZKnI^_2{E>F(>0P?(z%TsClaG;eBc5@ZQj~wz; z)@H{vodJ-9ESAc~|EJw-Q~0bkM5bApV+eGM^&#XOPmP$MglXAwI5O@exV)QLe?w0y zE_<%{zR>!R+Q_YBLp+D^th1^DwC0CcUze-RRTNNLK;*0s!|oX@`F%8CZ!lZLa=9u8 zwl!M2C_|zH8?dam3l?P@U?1QlXP#VnyE)C=iZOG`hOq-1#tsiTNe-cIyBXnr?m0RU z86D#gd_#y{#@(aK9j9%&hl%-JfA%ouvlJTS-db!A-b=S6-DU6-L;u|YDCanF6J}xj z9MFmrhNt*X+yMNJ-Lysb=v3Ke zN@zYtsXmRlM^q}_S1Pfe+P2-*D!N~raz?at8=)GasOs<6X1^87s|Eyy3YK|Z7PsdB zb+e|l1__4nmas%}F$Qq)IN<8C?6!h-Ag{f=vwB}=MKttJwII|7DMgs&hoYIQU~s|A zRZ1O(OX9&7fVy(D#F`ZBe^Ug;=0hM89EBD9WEliIQXd1*hJo@4n*v_YhYDnPQz|rE zBIAmUIG+fUl2q&6K%?OsL?QuHJzbg1jY#>^PzFr5_5Xxr92A4>d_EZo<0)9>JyywfB5KHBl*d-MtfzT zE~(m44N6X!r$LJ&cP$5nz{UuH=@CM3WqtZ-&`rc;pe);-pooTkkxHUn!kGf83jXt( z)y+C9L(t#u@3?)G*5*oxx4ZgVyz!QbG+)f|rW<7HSbTvuqx&#A37EncYJ}3T)}|4b zkHCGu6BNZcoJi%ee{cvwI{oY*KRd|J4)RnElAqK;nrG!8Mbts|$7Wd9WBi{(v@fD- zq0Df29e8sjdLQ2|cEy&{7TF0EdC2y~C)xh%fnrxj_XJCnfvc-1SKxPdg&*UWa~?;p zjt(u0s1=ryKdD;X%{BC}6Xd6ya(6*Qv!L*Icc@4x?yDw+e_J3~u6(fz{80#iwv|oL z;45n2x2m&HSLIu;iz;+eTw*sL8lVK%l`o`1Bqc-Psk>-uWuT{Rxy%9|X$m|mq#RhL z5rCxh>FOfIr|;!;x*4d4vQM}eyw5FfS6(?i7^u7gonh(;!(o37P-y?Ub^&FznK?DP zZr1+dHRMdXe??;B>$8@G@6j*JZQjKCYdKiOS61<2^>XiEPCR4yT&9Wwq?@3DP zs>zfM3#G548X~aX@A#&Xy5pwNqkFE&)LLJYIzmC7e=y~Ez6x>`$Ay&HyMxQ#USW^z zSXo7jZFA7g80L#4wR-%VcnGViC-;u~M=g!py5rq)#C#V36MLfCjhC zXBzCT#NS>I< zg&aS?`kmX$FPb38vo!#Nz9tijE@BQk#5q}`c2f~uP% zsL>;Ek{G^sPE7SqPU+5M{~C8Vs*4%@S*`wy8PXECNsN zOz(C4U|`B!odiFDJpEZq>3lXL0CGdIe=X>yk2VI6QG;vV9iWEB-@+m7CEhE-@2Z?T zODgeS^JM$GI{C5+=OK-gL1--fd2VQO3t9N=bs#F11ulEJ)}fF009}Y27K0+5sx-+} ziK^L!{&EyfQ*Rn{^`y32bYmVb?Z{#SdSiM9o&B(_%T_%)BE5nsru&;i6Ic zi*PPbORrw-1*vQ{%NIGAMqcM-b3~zxe<%qa7k;ayGj)#`h{gu?+i14oSJYajcr}Ev zJKvW%DK2S>z(>_e?y=vE9a)@x8*BB+*dMdVnG&kq7PbXkACec1-lUG0} z0ysF6fk18niIea^EPv|ue~Ds9avCL+BZ0O1^WTnAkTzvPkc9tYM{?~*n2Z!M3Re^Y zQLQUFrX1CW5KE3U;Zcj~4Hh`Wks}I{)eOtfQVbd15Wp&AmKeg~pF@i=ilo@C_D4W` zjhNJtRRecK=awi+Fv6Ngi9*!U*&p%{0}X$a5pXfPHlIidT7M#-C5Z$Z)VJDC-)UIi z#>lTh-+5QxwR+x#cSR^@TPZobDK@kzh@SSYhL%Z##!ynWchf617{5g}p)nkdml_f( z1=3vm@qPX=nHbdq zdvK*8Zb?I^Yl2_J8alLWYz3pjAWs6>08!6RK?Wps2ZC3+elaj)u9_n8peB)x5N)d> zF+h{`L+AKf#Y;&Ow;vWcgX0I#9wTPgpe5+n4JQQpEfjCrI1c6%a?WL$M|KdA z3=#B{G88@R$?2w*jtY4?T;;m`Hpye`Pa_fca92Fp>|Oe?Hc#f(jP0c5jP0Ugh1@TE ztj~&EYp{l8>?>`bfSZJ^EBwn0(hjYn8vtf=S>;SzWv)lVZ~$fgJyEPmMxGRjHB=OD zY!6biP%x?yi+)q`uF9<1Md-IUbze@tA0H_Rd7L!FT@XS6DHBCek`(r2@~V>yM>ui5 z6pl;6r<+7)OaYsk&He!yAOG9ukql?v1Ltr*EX`${+}{W7=(DRD66xG}goCE-T3|DR zu_=1X!%@eG>-DKkXgmAmOyVpc6w0Z&R5y2}{@il>Ib3VfLf7xDQI)4L4#riPLb_H4 zthTJ5M-Uu^*Ur05yDr+N_ZQ^W;*aougCy~__Of&j7&r{w`Yq>w^3hNu217O)({X8Z zv^S7ztk+nhPp6a2X%|~2xVqo2>sdXJR3;C*rHcz z5&K1eW=}%pp1N$K{1+l3NNMmHMA@u&n|Roy7QPgD-j`c40~R{+8cK${@S_gHout1! z>+er7OY%X38-y2?@C+f50%=Uar@;D{N-0{Qt1)1kyszM0Z-WfTF(Ok~`K4&!l=(ox<-A9&<(T*Zm3~PP z9jjuEf6Bqv#a5$1fc6Dp>wIuL*$>T`bV-TG9d7ySwaLm#dvE9lR2sxMGyX#WyB9&k znv+!iG9+m=Z`RiNrD^QsO=6u_);m#m&eLC07Xw?BImkcLVfi1uwbGQ|=kp`+NX915 zvWJMkcKj|76P51LUERvSgPYKaM@scfQzkxEP*U2+GHSb6e;ORv3~A!^yCPv8ySu{pQ7?2p@(X9-FLGa z{5rqx=em=DMVcX{XSP`{Zp3@J{8I%l5wWMcMWP3*V&?=+L;k`(*5ZFY1O-cN7uGd* zV^Ki>ic?ny@U*Ojzf?6^yWP~HmhAI6laxya33F1BSGp`alpj6oiv=2;3&b@%l87Jj zli&r13OCp)3g1M`@hlnI(5H)pY!McQim)t`%R~QaNfiiuTB4~bryBINC0J4WFzeCU z-zy4Hz}4rb!h`%+syLA*9A%EUTO+(s6v(D~d+vY&x~AvzaUXXoLZPz}LB+GEtc_}_ zNr``}iSVz`XNSLESs*gW@XcNZwMR8C`yGbB8d+j-1x1p= zs^79jpRGV{5Z0;@^>tM}iaS20)YoWET#A9(R&qX#6Sb8;&3k8B?N5#q*kVv6$Kp`) zeBCaHPTRB_nvxNHj9bmlWVEs4V|6ACbP?v&od_Hn+xL#(Tf=P=EX-b1n^k+9%^*b# zNVB6+Do5Zi{OThT3x=INQIag??8sBl2mR9rk6oc?x9Rwk>}j>0JG!O9akeZ*l6cXA&)@5# z?FImf%6N(MhA_xYGV;$ot8`KZgKx+9jDE;h#;JZc=AdN^8_hPiWi+-(Yk3N1Qo;j5 zp{)5_GMUHpz+ofn9|jk0nHC)_FSKtT1N50Zn6``A%fYl;;vdJqIB2Ou$m&vyjnuBr zfN0vM;LIEva|};2NU{`p(_bm70ee7|N)5moMJ_|@JcRffr+&FmE5U0@fb+^RpFhw- zDk3hhtX;GrM@PZqRQH-o$VrM|qWz1kHm2|U28EJU0z&S?iT^q>=UEiYWg_1ii-&_) zDy7+18Fvj+4C?V=ukP|BJNwtum|l#GvE&*pIPaenv}#;D<#ajE;!GWgv2sglA zX8p3}FVh7kfTUoafO_Z+;O&z>Yc*%4NhmAs*Y|f5g}d~-QlJ?}Vp>p$^T(hhx3eyK z1bT-?I5K*jstb%n{9$Mm{hj%81v{iY@p&G-sIQSMnyU8q~TkScIJ!X)J$vfRt z=^;@Ilvy3!%s;++m&GMxl%n7Pz4^Za=tc**NzpRIRjVd*Zf?NB`5_VW+PlHSODbKw~a1Tc%NAqA>Q8wMD0fUTC?TW1$Pi950!}hVmapHHpyFCabqX zXqraKpoejoC!WCP{pf zXjuv{Jm{1^iZxDiB+>vzrImu3lmECG?|GO{1arlU;@?br4Y&+So=udsyag%9V}jgW zUKzl3V9|LdrS+UGrJPZE=gy7aNORf~_sD99VkVu=lJE7929jjVikgp<9}5Cy^7F)S zy~1)OUst{!zcr970P~#EXEI*rfeH6`X3?LC1R5yzXa``-y8H{^!mp4VU&0kGjvhiF zQX{ly(m|eiH(NM!kgoHi>;2y_ zCPvfcB`BEaaVM?s_V;`!rv%NGKV?5=4MSc>zI z$u$(^>Zi5tT&vq@loyhSUq)OP2`XBeuOwNViRAWEa&1#nIma+1sBQ^wY19HDJZ*SG zLRY)8pqRr44KhbmkyDo`UYNx_8|u}c?n9Fsz)kbg6SZ#;KLpCgTJIkcVtEJQdkhD` zAe=mucW&LH%j_mYS(rrz5lr*6NCxAFNh>PMpdzj@G$_eCM}`9e2+H*y7kQ0Hnm^93 z6RH})VmQm{rd<@>`BpY*yY&?i5c{G&HLxP->F>Z7<^zOv3E4w{XRv+|H%|b9e1z)` zkZo^}F!9C0BC?rAWI}E@LAUV}^r(l`;3{&3UyF$eQ3K;KA_gHnjQy-wOD$i|vp22* z>A~GMuYe@}lYikP9JUH>(H@+Zrx&(*Xuc-sF5-y?<_J&6F<`n$nDX|5`P}__t8H$P z%8_+E`C+cf)T>T;_N1`OkF-G~W~J~2Ak;@x{=sZ~5sAWaQd?RLFz1Yn6_gxhGX+e) zQk`bI;0IXdWw(D^%fP$SwaT{XE*LEf1d3R2MbL3_e9v8VqaUs$^4sJa78ef2gx#7c z4jYq-vJFAnS>8ol)@$RQ`1;MPd4FGGk@5e&uJft5%athJ7=_N1q@inrR4;=96xJ1! z9XUCy2chbiYzM}bC(qN?Bz0HhYMQf2FaI9Lk;b{p5e9ZLOW5=8?eBAmB5ty(;Emk7 zdEWKq5a!=$q!mv8Z7q1B+oGJ*fG$C*TSCZp2SU6d z*+SjKdQ3)GVW?sdz&{2M>0#-B={zdE{fk2!7cnXGd?f{r95o9jP`0jHSvan-V?K(i zeqsZth=5}}Pr?-z!~lniutxU%!(8jU{DXhbS6?hpW#H;lAV0<9qda`&D!}4adMNG7 z+m3E(^IY5ab;&v6zTPMM{>A2(Ns0%i`s0rTg(a_U2B6n9o%ruE5BzRmKV z5!1G5*b<%6WfXJ{)k!@%oKgR|uAZG`Aq1Z&kmWY>wS)VJO5*=zM2)x?HNw}F8aV~4n$uh z%csf}RDWNjWZp!Q&YQIY+UovqELscK;ABtCVm0>~`dFm^`h)CAmrm z&n=@Xmt%{Ymj1rRaw_lbd@^0`Au;x)`bj^(N2IbaZjF4!TE5ePH0*4N%nstS0yL?Y zX!EqXMBtBr`jN@g~58aZ|?}=8Gb&d0{KgMQ6 z4K;~)B|LuvQu%s$ZxxVT(ew#6Z#fW9cf(b<%+50dKN?zx2?PNqGWZ9D zoj_H8UGI3())NLSR`O*P+5O=myIN`2mD?nR=X~wx#M2bBa6qADF+^3cLq~o`!RdPP z=}8`jtM*#XZ*TF*vV(rGYx@0tG}}qgzgn9u9w65rhec%nC(Mgj9Fm7~fbbMd!73?l ziSV_?a$C+LOHs^m`XmpSn25`ACJ+6Ys*NOS%N{+btC%n-Xj&V-Sr3sl&B&W-CqWpC zFHy}UT}H9fCt1#st-4B}E6Hx5dS@6F8i_Ei$~(WojbboKJEf6bRSUU$wgvxa?pRlC z0y>+Y(5WJe*d~yXe$`GP?0W{POVJR}hp&4a8K<#-HJ(hJ>VUN;VjsuYIhAX-Jd5Es z?lVZ$l8eHwC3{*%7*DbjWUCaF;Qrx)MBtBgFf!-14ID!rY2{ZI7Z8Z`nrh&>=^eXQ z1f}HNDf~g)#59cPo#wFeDU4|W^<`m#1&o{c%m+oBez@wLz+k0l|B0t%oV@3eFd2Zf zWA}k&8L7Po$>Bvu(r+j-T$9-F{ux1~d9$B!-%X+8Ep2s%R^}co8$aBti-jE2B++5; z`h97R@WX77Cy?bVRw8=3Z*qTAeN!hm+FnTB0%rWDGI9awNFi=JOyJrn zaL_&lN_;;n)-$7ThHZ!^_QJ*l&G?shxj+=W4~)~eJl^fN`}}m-#0Dn|u@(9ss&(jl7CSVBvFs z=vN%8?f-WaX%1OH5OmSqpjZ6_64FWMft9VE0d)ysyc?yxL{Q^o+hrxVmldQiZ3@9!l=ZG1vRL`zG%<7#y>HuG>_pgvvz^_B!pP{K&$uWyu4(8cF^w-2iA5o z?NYM1MwM*nuBwF|ua)Xk+pBFS+&CR_LhC=Dn_lY?DatNe$$-7YY_L_10%S|kDKWe1 z1+6u>I=#7bE<|Wyw*&jU5R#yJN1m03o{KZCUickdKr#xLHuEUKjZ2>lOrSF(GwCLA z=w=DOqgqwMU#?6UItCri$Gl|w+ zi}J!}I1U!0OF-%;>yif*NP8`$%n{1>O3{7YmH)^I ztDQlq05>_{?Ncy9VavkewD*|Kps=-}!qGU7jfb0VWsnxFXi46rErs>+CJHwrE1D8* zqmce8x_jCHMKfJaAMOM>LM_AA21ckS3mzwP+eoP_2o&TSPyZ%#r{JOM$_1hL+0sd} z_G{Mq$4Xq-#?3>d1ij*Hf8XRg7vp4~)cg!3VMPL8-a21DzOPBeyg|iT()hewv3x## z17W5sOL4QAc@(cHEq)5^>43uMaVQ+oTfXX3VF}!2k4ExJfBk)=efd)9FA>j~t1MHW z2l%3K3?S_H9z^Dm@^?S0g@cyL zF&Ry4hw+?pUAH@OaWAH=vREvMD*R0zEFC*e(gct1uOG0re%fp0KRb(m8qC0Mx3gkv zRMu@}eDX27UGnh2Zt%k{?aGxmY9G36VLem@XaMTaL`L0C_mw_exueW)OMXAouFBw6 zp?LwhzzS(kqEe55xB(0g$(~=8FLs(51ZZQ-{8J_kMzL5fYfkTJx_U>!}{jurXpVol|$Gh8afcCHat* zAw=pM*1a;q>I9S#Mrju7m^qfFUjKa`2tXQ$ zagc1NI=S5K<=i;vi)UG6ozviZP2{_A+c9nunu^b-xI1;~h0~ZSsnFTiZ+L2BOB%Fz zB#`gFrcbCgU2Y0k_=Gi+@nqUJs2I*3q0(1wsj+dOx{o(@*~rN|42{!La|bXI=LAvW z)a$Y$n<3laxnpk&botz%P8(n_vp`5NdZI$On7w60sws*j$8s$=Hx5dry%|TFUL6rB z*m#)J%&PtrM0>4idyP6FcBkXm-Fl<<;L!nM?hrm9E{EVYxTM^d$v@UL*wOoO^sUAq zd>jP`d*u(9y<-Hj{-Wwi z@na*R*wEY>ShTl2i+y9-^#hFA0ohA|gVCkmaw3dY#>!f&+8XWpANY2!j~Bofwco$z zjUe7!t!#%GMYVY2s@8M`k4}xnj(Uv{XqJx2aMO#20Ibt2r#w+kz#Fv+V}Jj%X)UyT z*wY7JX!~*!>afAKV<5?SiiMB6wy!A$IL%(RZLY)KOtmO6?bre0faCp5pIf}W*GnEkY-8U5Rkj7Dh|xn0#A#+fyPNKGu_+Fp;yl- zld&P+9td`;tvf$Mgvo>o9_+@jNd%CuOs@39g>Rja6dFg(l9~6?tIp^? z7?whwVcV15ojcN6q)ioW<`-|;?FPvS}w^l$@*kFAK7jz&}Xop zMh*_SZm?lGIGo_B*0Ik*$7+}x(f1uWe~S~^X#EzYNQp%X$rmcIZ=E~pM)I(HOa4lK z2b_koD)~2e7-|Ysk#cG#sFey4BswWl-WL!QikV}bZ;W&NsKsFX2nSq3zz z1Z3Y(U}s9+Hx!yZqy5w@{m}^jJ-HL`oXq`b;7K=qe5U5l+dG*@bkmT2YriZK-{bJK zrgj{y!it5eN_^31C641F-~U(vhDeSC&+-2Al2mmANMB<~mFqA|(^@y1o_}rk8p%AT z1<~xpO?KcyTsq0VX#6~p_7Zq+-k`jCa`^~Cb?s!zZ+7Dc%mj-LcUrT2Lg#usmJ5c| z^Gh+Xc~toiq^B#$9mqUpeB)bqlQmQv()*z99fPZ*cx{BA9W4+#M>Y*GwcFR3M1O6_ z=dU~fu6pU6uh&)$B7LE=ziR*V3UW|Uz)MiA{oq3&q01(}Y}#)0Olt5v^$I%CzFSiE zyK;jdjCydL;>oa@pYd+&Zdm_x5-#x3ESotSyw4t87xU43`nMId6J0r(-pNxolGCRi zER?$sVu|nga+M}MB8fL!h@L59KU%hRS{SnrI5_O7{R@iggmKWSnOIu=tKU8EIXh_6 zCw3H8GezyeNdPync->G%f1(_zg~Age3OAgh9!Arr2Oy{})nE&M}1p z{tJQ{JR=_}mFlIJ6I3(PjaC2UKw&xk>_)?RJG*cH-Vp@J98yb=BrzGCn@Hp!MEBx5 z|7}Es$E)>m?winj7fqj&x64cNo%;zrcJ>|hn8@|@;mg5)UD+3E`zK1}12bBy7t6Hy zMvEWele6WDGvDr=2~*R=0ebWJyx+3`8sdyofDUv0&4rVr;6k;xqwCMk{u`%jt*4jC zi|F?c>T@d(pJ1V`x3~8o!GO9=zs@fI3Vcr0Ap(J|`fGetuh_rG$J@3(^Z)+-J2`*8 zGx2bFe^?i?f_J22W;C=YO|AFPGg6bo3@MuDzVR3(O487b#I42$fT!25rK~sL{@?yd zo#PH?z9yy^vcg03^7i|g`o-J5i9dQwSlunG)6GSjmUow5yI#InY^T>wE}|OmNO8B* z1=qq9165=wRUMk9Sm}hWR@=J(CyN&CKl@_L%pdc`fxU(!NPTkd*7N-*{7aap0nK9f zXfr4I0eWJmlNxqUvrk=?UrT;~e`8f{^oGD(SJ|)zhx#kVc42PEx~Or{z}9)^=!yVD zxun+1QG5Dt>|L#Lc*^a6m)x$6qd)O-6CRZI;~(>;XVX`ooU|rCo{mr7Kd+7t>!bJB ztyTERdTXiQ?i;UTr-gR5^?!eI33clU)H)GmL%meHwTqK~@0SI9dKh#8z~>pOH-u%; zVcqW^g%LtbSSxn78>l_g5>?I9U5T0T3EAO2=w z9VTFqqexUNO=lWhwSMJ5Y64wdd_G7btPIs!jz@_5m9>eKZk&Tw!Vp?gdj-$pU-c1- zkg(X{Aa*=N(3PiuHuCJgx3NQeNYns7|Jw~LC``5s&VZKYd1hi$lm669y`td1DNF2E zas*tI12t=32{Vnq8PiNwLV5q3?-^MotjtBD;54}hG({s~X`xVn_PR-HN6Wu+9JPWa zC(>Zt#lt(4pUK7CIzHR&i_A}1R;iELPdMVpG5W|ce@C@7J&NY6Kik(N zt+GnZ|NGw%7!li2)&8+Wu{EhCn4rW; z_l&CqrMM@M_=I=)W(2)TSVytM+({$`3-HCvC-C*Mage#Spq7G^UL528Xe9R*oo9N< zzV{qR+S#KlTPImt2=6Lu(MGwwqt!>ZD@BvMI?6JrCTCsN_t0k_e3SB0pfI*JC+Iv( zjURi3WD!9HP%m+Hkx+wt4#im-#u|M~Qz|P8>CsqDrZ2+gdMFaZ)jf*q2VKSeUnBYr zJK2j0OG~248fZt?K7aKRy(g4#r#dr0P`5huhfl7`^7&d?rOv(ERq>pk27+ld-A=)0 zN}o@#J}h_i@x7#LL$5zyYmxA+Hz%^YS|+S(_s-V=MhvZyWDN=!(d<_nrj3eMdJHA4 zFkXS23ncb-SzqnFx<*Vl15ANO5AiN9Gf`3-gMZ* zz~qBPI;~L`SdCFIL@{TvPd5{=E!W=Psov~4v} z(qhtwfQ_nbPlm+9C5F3z#DkrnkUFhRlz5178$1_sa29xN|XJ^~Wx>qgQxh(QM2ky}l1 zV3;aU)@H_uwo{jDiXNv#W*8O7vjUg3Qz(G6QJFl%KQN1^@j+FQ|H{+?CGgPj=8~gW z*YNHPWpR}r1P4e=lkPFbMg?Z9F4|R{544fN{2R7jTc=Br()n8DIh+GK-982@%6Y;f z)mwg&Ir+lhG`7@F@e;U9A~=8&d5DQSNTUpl*x+54!0FcdtIG(AAHOt!XA%SE5QS?7 zI6&>C{F#kviDWS!htNqm(kgdklw(xa+)16#YK#7CMBM+-Eut&{ zlfy_}KT7lFP8i4IF9aybGQ7}L^J>MVcYmg|wJju0-pi&xkd+x>)PI`Y zl7WHGn*YLn;Z!s4hOJqO+8CCWB2z*qU zqoJA^M`TsbEx4a{4~sBQ=N4ym8bFcEKAVVE*LDx$8m6F=s+z3QpUL_)Q+vB=p#b@C zIi7VBrt{!TE+NCeZcVmuN%#<$cpJOPvz5tzR%~?qIJ;7rcdbJU)t|WE@5ay`pJ)3= z?#KHBR-Ez4Oaq{89Im-<()16hrt%|o2Wm%v;t)uKOy@QYAKr@BZB<04ldwwI$jQoO zf>5LChPxP~Ckwx=Dz%P}^g=AAtFQQys>$Yz(WE2bW@15DDP1t@-&>r&+Btmj6%r{Srq*=2q2SklZx)=TUL_rK*&xWCJj~-%5+YR-O$#WfMp^N}&5{ zX6SU2AVh(F_JgsNTYVulF;Ml19jQO^hnD$Ml$%HnL(<)tY!=c%qq!7)Pq5k#a!e(`5c^GCj= zfOSc=Y&S6GOTw@$L+;JjYGfYldH%pf<3)ZHp%~eAEjiWJAgd9U7VE2oW7g8!lXH1o zuYTSUT+xoUOg;4IlW{5&^BT{836UiQd+e{IK1sSU8syly)DAN0g5|)p^IE%cMv3mu5UP?Wmgw3hsmrBX>LxKQ4cxP{&SgPJ+BsYoSBxxv3P(aHXsWY2+xef&$JwoI(Ao+fZ+}Hdac!cTBGiP{PrJAfuUUcGuRl zIyc>r1)nePPc5r5WV>^j+%SmEkufkjzMbwO66_ZXk0*WxiP$wgy!wILyEA*Mc>`Fj zIZ?OCxpRV$&$#BDMsZ1mMjK8`vd1}xT|b(EG-Moo_oY@#yZ!z-PDMZ(fh>9TTjYzX z-aCR4-%hR$rQcUfdgwRIC<^(fC@GRn@pU3Vv*auS71lp2?# zcE^tvDs&_Fkj|Ri0{j*zgGZ6l_*sBMC!*zFugD1fNvL?B3C(! zt7z};w2#vf@acOrK)*6TI~J(#JpF+#Fk4&}>*O-R)KO)N3A~nPVzH?6T>~b5F+Lf# zl^}>88>@|4V~3Tw=G(1Re9<)4Y4da>HcAgoc1uh&rYrV4U4?X;U;U+QNJlnyiV&}M z~1#(6F;)36u%5kCokml2L*VM1C-$>T@ zn+}NG)AuQRVsOq-2^OxW7mmr}WhsSzC>(oN&MdCWG5Y0RP&{cu!AvjnJ0Pb{rA4Xr z>hsOYY+tVbLKJ%S7X>zl1+cPSnjyCX(4ePu#Dl*x@cz4%n6Q*J-kdj?46DI+KY@ z^F8=6^J6AKJ)phg{h8X1u2^GfUY#4zoTsa;bS1zj<)5vRiq5b9Zhw2)%wN+ml&HV( z6w$e$5)?_AzhsAkR42&)nSig&3B3C7Qq!+%mv*lu!k%EZzcF!mG~Oa8@>^rRnc zCF}1hTlR7w_FkL7v52jOz@}E(t=X%1lyf4<)Ay&k+7>SXRasuEUdPA#W(zKbeg-lNMoiS zoKPE@#a_PA>NEIE(6{+_f;HhoITLH-;J2v}ZxYLSYID0*MoNO6y<((*h{4mp8=Ewy zP(7;K1v}USC#X3dV`hDXS)4p6!tdWh;X-Ag;7)3w108z-(G??t%|jr;uf!y0W(w6M zE^E&-;23{Q0JB+`J_XSOpbqXOhkG$SmUxnC9#Iabx`5}Qkvrpu#Iic9**kJOmD6w( z4WW0QAmnn9>4~R_NbT#)yP!c7>!n{I;vFQag(XwN%(^iPTd0M+Bb^7aDVd$voKMTa zmALnlpgOu@^L#j28cfC)B;v9?`2r!*V$5juD@9#j70(H9e~58`A|kn>0~A4VKTS1H zG5N(uvaY~Myo+B4rfk#1e7hIN;(XF1*Uk5{Dnfen6lhao% z-*}kr3-@z~D!tz;fq(Ij@Z$p0IK*U_GagcoqM7R~S9@lX0+*?2dQSph%b0{A{c=ot z7bn4nyp)ksUK$^PET6Md8mZr_h1-U%_tz26WLMa&7A@(qQ3rxjR{}}5Hsu5ABQMtx z2UE#e_5Yns#C$2Gi-Y}m+vysNQVV<~Iybow$T}z(id}h`|3zanNihliGnh>!zVpHS z7l&l&7zv|$D`C{SHEnA5PPPfNY7G;mb#@(1Vrk^IEiU*3@YT`^k_BzD?DnR;dvBG8J9RFS?=$nreRac zEJc~+PuBWnU_!F8e5ZENw8_zoX30eANDSL^tDW{hR)TX8Mg%V$xCBEylS3K7-clSHEpqWd|j<6=2>AlZx?g})`LSTh7x;U$?=frK=` z?m3KvKWqTub#KogH|SO|lFiB(8w5QJ4er z$k8}&`)uYCVo8`!_8tY4fA3u>hBQhj{>p2dEC7!bEZ@#Tb9dJcJ+po$f%5YcIEDg! z`aQj!#u-u6f}CjbTr>BqT>-`O&TQ`HY_)5Ii|zVi0sD#I-2m|>umU+o>@mbifAg^p z%!4BRAPOzV+AkR7iv)jZBuHQoj`!Hk+Q;Ys``*J0<9JDN>ttckeiVeUeVIL zK0{3bQbtDbsEw@td7q(Hq@`*8^Iy_X49($t`yUD@>a z$vvz{B*Zvu)haDXkHMVoMPJUy(e5+`sN8^nADD376-h1oT8hL=JeAiq|7`|UHnY^< zEYWnCze|48xDd49ohWeM-X;~7ZjGc&yRs%n5&stUn;>^QfgDT1iU0_Lnymc1#4BzR#8u`yZ-APgey z(<#3IGmM^bjybzM)H(A-4z11z7lb90UFE$X!ELT@TZ6mp4ebPWM#K3KVZ40UQKXbH z*`{XKKphfs78BmYU0|-*9cB%mLsv z`rl?Z#d&2sME@+Bd*q%popV$JciOleyP~-R-5)TnN)3=O)TuVT>pk}-agB8?2Z0@{ zs)=l|Jq6nP-;*sH4N`G?hK4{sgpw=vpbZ%7wlQ#b8E58AZP#$xF* zWKnH!XTg2S_#C|RyqW*O#Nz2P&UA`>CFK$`k78S!W1^l(b zhlb8^eZ>-Jy%7nGgNtmSmWrL^jl1$@4p*ZF@9pCb_|2Hf3v>*cPWkoxHPa3c7weW!tJRy!(I-aLn^p=elUnhd4^09!SLX?Y zxyw6(BlcJq*ca(nT{|4RNae*LXShv@sG)@@lrC?`^mX{X$!b5TAlTSA{-4$JO4q<` zvmMj_rM_UdVjT^B?|_{>*Tyqje$mmZ)lP{R?=&beBLh9sm2!RavVIr*R|#cwQ$u-FxAmUsW;|7#Mps6B&HjOMUJn&x?CxGe@JuT1q5pr7<-j5;Sx@qXYa<}$%j zk2C+Fy%~fJBI%3Z{@qFe4D}A`cBhW^I}hck9tO^z;b9}FP8p|mm7I}B@5R9m=|KhX z*WbXFQQla@rpxz}44cyvPWNm=N3~mRoefDl%V$x8E}x+xp%=7g92(U5myEq{W842wv2K#Ur0Ti)5~0d};Y4ot(52j9F~R5E zxFNJxQZoMO8&2+Oa8vLxCnmj5g@X~=d)AB%BV!pd5*s=`*h$E43%x{rn#;3=8H6QD zMH8~I2C9HM#7j^O)P`phN6XV@g4qzCMe=Dxa6awL7lpIu(Pl(k*BY2AFeuCDh6=Zc zI&pL3wj;<6B2OPoR&71{VEr~KOwi#`%t>3l=1kgXLRUFL1XCdS(nA{SRR*n%g{Kv- z1RV<}k?7)ry3egTl^{}J4a(9R3qK+YDbMgQ&voclHYiF0uwd!b_u8v@*6MA-dn3;S zuB@Yf*`Dn&IY1;$ANtn@n-PPzE`~bapOl!I=~cY*!fkpN$kKRHyS8Y;s5<(|vuKo=ys3hBfI?C>aahpoQl>{%xEj&Qhewu$hcQ;w4$s~u;{^Bg*+K_P& zC6IRb8%OaD%#pVzi%MA!(X@MY=HYwQ3>%wsH*c4r9E(GwykH$Zrh{j9FYy2M8c@HwmEt-px-u77K$r*)Vv@wl$)aDT7?_ zmP?4@`TDEALamhzF}fa~n{c7b1Z2XXaqm&jm|f+yUD0aBMPTf_8B*bToTmvdp8=x$ z?r@P9@ijHwk{9QBnq_(hGdoT{<44kPQS?rYl9sHERo#p<%a0e&Tf`wr97jNVmp#yK z4=H{F2G^t@u}Is$Pr*iT`zF)MK=Ep`8AH*a|%`i2J_=ng=|D#Zz z5H5c@7vRnGT^1(2_g~gr{}KP8j4?qFsrAQ#aARVHT1APE$yx&!WdCb2t1mg;b||qJ z56@Y>xDkuP&dhkX3XkwZZ81a&p3JjjBUu>}I0W$?3(Fp36#yv$rT(XaYIQ;?tmL=8 z57m3=tmL~MBx*c&6B{I6ZmZ8QV8`4MJB&W7OJnX*JQ@+NxQufr^4S5KM<~GC;exEU zk$X1Jhu7)i@ZUq#Jkah>gnHSp7>gBGEtWdX0zG~!h4*9;l*ie&M=gF|{N3Z@gL=&c z>KgwD2|3J?I(+{76p$kR=&o2i0|AM{3jb-4gsV8KN<;j~JU;(|w(n00=7qp=?GXz< zGAC<;fXFv6Y#5H~Bo!I>)8HHZ>@>2TlBX~fkNRf!!q;){r|;{OcO_A`WvV1=waqt8 zI{I=GNTU1q(Fu*#o0{cS?y>Hl7B5&?;5XUJQ_k`Amk2}*c(P0=x59n`mVbncbI7j? zi{ks!1F=TBDw{^ffBS8#u)j0JV=wjYkV^J`e17?A)NxxFDzFW#uA)nwx&Ge4sNM}l zP5yG`pFVWjJ*|FgqC0oNr_}O!qWyXuH5HtVUM|Z_)oQl=1lU0M5qd6@<3(@0~NtAF-vbJMS73qdE1f7LM~3{5|}{uC&rgU0@+v%xnAv`Y*x zhrXy)+Equa_q?T|HmQcVp65kpTmX(gB2Ug-)f88mvz%>9JT*O08FIs5K{;yiIb7WC za9bICKQ9=`|LYY%awo`BHtdNupD-itD{v*5gmDyYwg=GTQ+4a74nI+dtw`_IL@#%1 zi^;scEa%_b5{`bOG6OxaJciioM)%#AU9W!Fl0lX!@3e*i-DHzm7pBcNN5J`Th>@Wr zV*y6R;t!JgD&eSGq2I(4WFPIiJ39pC{Y7i~%y!t*D>bvwqpY%1_~#JFJf%BL^aAVhr-QpcJh*))QFPFHKyv&_O8TPbu_?8 z)I12Iym!Pky?6|TYG1fj&4qkLUT^F2Gv%!M^8Eb3EOgh>cMC$k8;IC*v%|xZj=N?) zIGMlQgUuWoiEfiIbjOd~1^JrY_}{Pt95+w%W|S@!C`&U}Bc)*SMigeV^UV%vGG`-Z zn;9zT8B?xlHw{Xq@mK>MhtpOId9qR$V3zu5X0T#FO_5tSzmk8?t6qoM*0S^N;Fgcge zjRF+}HZV3glOPx;wLk*U0S7OuDyuFfL$?LRo)%ryh6QqJ($G{eU8f; zXDHMXZFFgxGPcO-+zkcP}s8IaSW4Ko5$Fpeno)VK>6li)rbnLKY~Pkwli7_Mnp$L zzz)C)#;?jL5q6z>D0DGAY>a^ykjg@07H{Wp_`(Q0MLUY0X2BA!F3h8UQD<+%b>M0yCUP|eh%f`uY zNi6?;0idVw0Ds7d&6d~y@vp1J$&+&lpIqqxsx~V6tn{5eq{u zn0Yfs%xC@>-MZHosrU43xG<*PO%s}}CWq45PFk%xo`1kD2(F6$Jpy|)b|J?c+ljN< z0^^^!_U7N;XKIb=i!@0qfc6pfdi_Slf4(gTKXUlORFM`y!cMrY-WP_j3;k|lx|j~9 zfHmd%SLXlowJ=md*_Eh^I!ti_)2~I$!Vw~r$IWYo=NJv{hFAIN_W&m=lh$0W5&>i) z*2zwl`F|?#5(Tk_r$CPWUI}WV0!QI8IkiDYPz}eFw(!q+St=Zq?*fe^%b00T%A}a5 zySBmc=D$^jyMea#T8V)R@pz5-D_T3jN{ckTvi61sy3pBHF$X{GqTHiVJmhaboS+@$ zm3WcZNTG9F>a7f7t8{0T3G^DUb!o1W2+VqPo_}MK!1H0q+kdx|cK&y2yT?~YD1VO& zqlq35NP!J3p{k9zM2U~{5BH&`43C>rT8d z_ukF1{dfs(jJQ6Nd>P=D1Y%$Ev3pw{Re!X>-{ocA!M4H1WTEhm|Fg_M{l+5E0)pis zd!#v7eRL4v#9yFg4F(9G1UWzPJOo-2-%L)!6mCS~w}>Al}P zXsZf|qptg0Bg2qCb5b0}`Vs~ABrYdsL-m;A&cuS1PsC`iRC8kTE*d@uT0HJGELCpC z<1)WpMqiUpcofYg2o>Z_z%o6q1b=t}?I@LVQVMGy`4dwS(Wf|2GsdPf;Z@(UE3~)? zp=omf{&fO6=L2Yy2Ap50Mf&xb2{-Dg)S%g(J|z4H%X^z`0Su-kso9YWFRG(J*ht$)qcp8JBS z?whNe=-HWb$J`rtc7%vqpEH|u6y@pCB=tb56GK>bu zVsm@R;JJm~(xB#Z`h%^m>ObaYCxOpuxhM36(I4+5B~%HtuxTUVa{d#}x^zpjo+RTR znPn(FDGTuDc^G=HbMGGS3+YFB$eI82eDW*OE+OHuLaT*1RQpB?aP*^dlY zt~M!IcGV0bOxbyeaxz#Ges&Ob zVI#iJ0YPUtd51f9;ue5*3>(n~)kG+(p?}U_Xbv6bQzV7EE7e7Mi+{B|Dj2%&Xh-i( z9C+p-IUqUoONR&yFw|WMI!Pgslvf*WARPwsZ-mq!%g)FC1Z)0%)1&@IP{!R<4u8HY9K`sw+|6Ylq~p07c-2gFd!y+voi%D5^4i$s*q{`gEwBdS z!-f=YoTP1cPow14pxr~Ix;019mxq>Em24d}Pnx_0R|j@#^lVOxhIwzf#&(liQ>I)Z zYmE=1i7_#M-sHGjuqo`J(r*>yKSdK4n^Kxam*2|5741Y`_TGpTSLp>f=kqkkj0@X6x>K^Y%`?(#1p^RaX*$BoB1{eIt@)aZ* zQOPvB*44gCi`C?#;rD6EJdu8&#p%2HfuIUKFysTiyUxu4Dw~oVK2PS#D3CR65Bp_C+Z|-V3ZDr-m?HWb5&rtErUe1;* z&zLCm@qD)oJNe-5l~y;Q%*xMNg+pO-6|uzS?|(X-uDc4h>_H#08Rkn$htaT4f4x>s zKrX`#Lw-A;c;uMjLy6+`gTw;n5C24$Be_-2AKPk2%LNEv`_Uncw$^q|FPlqq1P`5~ z9YtNH7~YNxGn$hpnz2dD^P)hFHN}vSmq1z|9>d@#u(a7k=mW^1+{61UiHXmw>~K4> z{(oyE8RHV4lfX7Xf^ZW99b^FnmXbr>eg`u%BR&RnUrMGbB2&f`hQTu`eE6pbgc`#= z(~1!aE~p?*(iYijZnF*Lx;yK)Odhl#Z;I27jUFw3r*MRn7^I>nko=NYvS@2QI`zaE ze<47jtiBhkCG6Mu1@e@a*XbkL0soE(NPqcWIROZ8!+tfre%j6ufd;{{;dxR#4$4mQ zas<J$WN|wr?e46pH@PT1D|njlOk-G$|pTJK~-#O z=1A%s@#>0JJ|2$RLPYW7%6nx6jTu#GJYQkEotKf<+f2}>8%6|WKH@;m`oBDbbAQ)C zzbQ9)MjS`K7CCC^kXn&Jz9!nSwesG2)}hH$o&H;hx;EU?|!&u)Og0X5r88P*odkt4?0O|MnZk zyd_7Dm-5CM8LzZaySft&XWDT>wi+ILaTCw zA5J5-P;F&M`01Z)4zJ5251xO9C`5Z4zvFK@c#YDcw!q1YZ^~0SM0IE19$MNMaH#)l zaQxB&L26d4rdYZjQ}1MZNS*j1hK>XnY(U7}E8(;S_EI0-V@;kcsS z*Hwkfw@8|m^WROrh za5LJs-Eh%!xkqAjG&mV}-FUDfwqUrqkdoO{N%*~dIe-)KEvVqR4TS6;Cw>z|xMh7E zLp7eOdX`rbB*A*Ofq%oV$}?)(lfZDPFI!$;M?h%XOEYt&a+@L6p?{~eJtXifmY6^O zx?QGAVGJFPf_aKXM5~JG{UF=8k1&BTO6~5(TOS zhDQ5+$4zPy{C~$_O{Q31R59Z%ED6_9t|<+b&1jwndOEQ!%5=-9st<#P;++tOp%1So z44cL+-^tU1t+P>Y!hcFz3jQ3ge}4g#XP~QKnV%@@=n@fz+cRgd?ge1W#R*f+a}88( z1uv?_7~i0L*qMI1+HxQ#hQUzFv48ZrVJT$6%sKT{KadCy z2;BK%_!(6@0V@9&-;>$HzPx;8P(e6^Rve4$Sisa2BUvn{-D)cUW37u~>^k!=R8lO{W6*!pPHit@L)63p_TYrcG_!CIOrNK_@Y z92k$J>CPC2+kYMrnb5)LA5hczq`|M{I78(So#tR(tPDInRWc~u>0k<>mjN@@}I*@`>9gd&x z4+be?XnzE}-)JH|;B99cQ396-7mf5KU!;~USy`8QeIZ+ntJxZa2tZZZ`$202;W|9o z!mpKnZ&eQ8Cvu7EcoC;@?~6#r>y=o0{M#oiCYQbe-_Dj$r3#(YVwy(3saX*nRcdWO zkOldh+YiZX+t3w%pvem5Wjgs8i_=ZA=mu| z$0^ber{R`cTj%vZHbT|j?Gx@Y`;>3|iO>dcep;Yt!MTiR3dG~TjWy8lcVO^?y>n7$ zwSTy}(5-;`pQsRoYRtef35H`B5BN9F=2K$OJOp24`sYKS3iR+#)<9b;s9KrBRvctD z7$1=lrlzoII7jb3VNWxJ*%X_9!?uU~#FK!%IDAtU_MI7ZM&RP@8b|eC>MjeWrf<>x zYiq!;cZ6wrOpSIs8uX(7IiCruzJw*b_J3f7E3t<)p_H0Hx4dpbRg;kl%dVfSA z*b>jgf`5h>Ic;&!(*oN=Xy0D?)4hwJr?k;7UfhHh&xTN?)J&678yZASZVc02-Shlw$lse!i?W7ChnI%gackUgcq?*mnX9?U zY$h=#HW8cvY&s5y9R7_9f1@gx~AD zw=x%ouFb)ga^tZ2flC3i9xv4;Xti!6sQ;=Ozvx0U6F0G(PG4y(Khw0FOHlp+>U~g{ z$)7i{XS1gCq4rEcqPTS>-|GW=HJxI|2rlaq{d4dVG8r%CJi7#Bj7vMkf`86!=w)(G zf{LoB+Yb|E_lJbhc$UzGD1TnMAqluuG7J7lghBp6Wm^vBe-$g8O2j5#}IXUqvWnuhO*%l zj87}@>oN-|bLA0;58lL=MIt4fOgTVkG%5{@1#if~GQev_`kO>OP=5oC5SvR89@H95 z($UYr&Q^mATh5`3pzLiI$+)dRTB(5g(ezEBQ9wfa@Mu#AeKnI(1T2(x_$4G$!WO*m zIt>$A|MdX9+F*wb!Ya>CR-Bx`eagMtyJN{|>z?DfXLb(ETdssN?l?;O@|RG*FqV8D zaWs_8rTl>-X|`jOE|B*k?_$+Sq6~ct$Tyb5oHsO%{ry3_x zb2>=l{hU}Csh}K|6STj1YeC>N|CyH#3bn=w+%V@BV>#+CN1$${ zi9Og1eGJw%Z&pbySz;$ozJ4ke5D^8P_`jO`vJ)c}396IXD6);Tw@CSyd{fo>r^6UU zR9C5%f%;CpbrW$}_td)9rdz8wh47^-rKg6CzEG3>6SVCE6~kE7(!d3kR_QMv?u1<= z5F!@?sDHV+Kl0{fAmDG4XVR^F{X5^ak}3cloo*q|8Z|jg6(nK7#xA8aTCsK% zaWJSG$ppc9Oi>bwi@5hxfw z9~BXSSzjPvk#FJd!?o$=Ay|JYDo00xgz~aArs!AB5oQE&XZ!EF2D+Z;9-=rD&JP7$ zP--Lm1CiTOijl~;ByGYuq=XxIPXF&YQZeFf{3AqQuFui0SUVopO3aCt?HT;D08H_7 zvw!K&Pe&PWKHk`jKEg%834+z;0rmE-sg^^>#Pnm@MFW3S&H9Pmhare5kvbJNLu!`9 z*ihz`g0Xw2iyQ-eho%5FdYk*F-sVldQ-4)B; zZ6BJ?qp)p9Wm#^I?k((?Jg2@*b|Q&d@PBLc28UDTB^TOrn>rc|OR^Q*xLNhz4=w%= zxzJM8H90Sn?1lI~`y+?(w4w3gKV!#55-(KT;nvuHH|p=PtGn;awcw7aCt|FIarggT zI{W+%G5?D>rOHb^zxcBLz#-Ec+8_tseMf9g9p_?V=c_lB>?{=~~J&`~)2X@AD9 z@1iUMc({KbzFMWZW+60K)0b{0wm^af5r1v+C4x>8QeH2kYB*~s&9#HkvQcC6s-khyzzYksN3%%nR z(dXe$qq-_sxV1D*A2&mLh1HSQ%Z$@O(g`1f+|fDq zz8LY}PwFL!fuV3>E|0&!s!jyxWt29Q{~nDwz@@Dw)?p102Dp~$ZZCf~SHP!mbvTNd z1DbEQDdO5xZR&$(fkzW<3xD2S2ub$zxiAJ?vf9TSRF~ASmb2fFNh=?g;nHRc={I<0 zbix?TGv{i2O9W2fahV_?d%(dF^bdDVUi%GDJl&?#+d0%TQOi4w&wO^2cEeO&C}6kcCSm{5j#Gt)N$EYt-9|9`AV_Z#+u2-a-h zj7c>dt4r5pjTcgsgVdfWg6oHI>lJk4TfS)eavDDThcK`Ayz8iU;SI^WNhzi2CsCI} zNBGEehShp~xQ)%V$>ah?n`OVE#RP7jL$>%tgP+enAbQW>=(JsjngP0li1h0Ah9xAP zc6uge$@9LdfKd18Eq}Mq|CnZjoaB?ync`~)HyXV>Wa*?yjt9PmE(_>aM;L*H;#s3t zzod7agO(OEeE5W*E&Rt4|3MDUCjs+m(c#a(76MH$u+)eLH64aw- z5woM&a|PFxnFGKm60S`wQyE8^z$)H{Ch*^P4x&EN)rbZVkQ~_Ia=n*vT4b9b%_KTW zO1)5-{xa(n>$uqgqT!dy_5moD?*9P|x6Wn)-6ogX{{a@4;4=dY1u`}^G&GmdjRF<} zGB7ifAQ&fqYs|5kO63V(UO;^`8Nek*$rf`M)?hGW?r>jSIlR=^tVy4z|`rG9t=< zMCD|Em5D@z7?p*H3~Y>vq{aV9w{ddh`Ued#a;!NilCd=gIM@&=+FBcb*!&k|U~O*Y{{O}OUxb8{!9P0uu`&He zIi~-(%pFC|-2le&=1%`eZDL^ck3|3Ws{#JAE;0aPb7$-SQpJW8maq?nb1=#PF~7VEWhdUrXozp#%kO-8|`;IXH;uSy`BfnAzCai8$F;Q?vc9 zkpEU6rh5aXifwHq3w9fR@07l=9w1LM#g>_KQ6p(z%8M+<9Hn2@(GQNa6SubbXd_0g zLy3~1`3(m+pshxlGYc-bG30;UUk3@z3*3XdCCAn?D=7E3I||kK%TCqCxx3VVPJbs( zmKaQr0?y?Q)@y?%l@ykWNCHQl;}>RRVnT=Ff`Z^6M*Aud(0(&Y{Q~4OJzOR~7KU_T znq7H@i3TJKSm)Tt=zhpb%22!oxh@kyHzL(hpt6Z){TVH=Gu;Jcxi*j-SbA@Z8I!eY ze{aG||!cI!^{0GyrX_tSP-y);Z2z*qj|9hc6JzUx*B) z%DHl}Uc$BpRZ^Y}>t4w|O>jor-QbJOH30u&>J5gQ38zoJEM6%P8MOv|vM@U~?putj z$e7;lS?YG>eI@T9-iX(K8L`i@COs}y)kUU2lui=5bg(jtWPy`$Iwm%o^%Y!T%soTt zni<(gUqkE9+keUwgI7xem|lJ1G4LEk-u?w-6MuuRAR!nbQB@NCMnHF;mGFiL*f_lI z`C*$#xlEMkqqx&+muP}l3IKg1P!ODganBVwX9cxf*+Vmdd1DR zwHojI+D$8V#Q^euca$;yTPa(lml)_T$c)>&GRx5pdoUX-vpL^!NT0(w@%rAzs0(Zds+IcM*G=i8g?^B zKDVzZF15JuXBLg31(`)xbyXD%+IjaFKiSbq)IMNiVnt@QA*|yaeX#8hc|LGBV(>Zi>;>A%hlFabOxof_447%$PKU1C6 zVuikcEX1L==#C7+H4PH9CvZQ0UynWM!xxiX#^c&)-3`x1iXu$eF2x1R`-l010*KV@PR~T+p%v1djds< zFxGoil=gS`k7<5D^iU(np-wH}tjofKUIP<`6q;lY2x?ykhSWLoO$GQp_OX@M$7dsd zZ5xDQpm1rrCaf+8Mk9WfrIm$ng2V_c7>)?Cip@HnyJ{DS9saVN?|Whv#zvRluPheT z-O27vecvx1Gx$Ck8xw5w)dX#x}8bC~$Rwc^1D*SSOY+&)1~f}3D+BesoFf60l(REs4vrMyf@M~fCp;euKzSQ&t z%q}V+j%?$S=^&&(W_i`1VFcJ-6Ysas6;dobM@&gE6ETtAsr%?(y~GF*)ekzuhFsAG z8S}zAC34}vfJ7H=Rx9P|QrYb0M1Zegt#LGmEoW$sBMoFsVsNZs3DAI&Z|Q_St5~sn z#Xk1Vlu#Eqaw@j9yes~MSs}xJWBm#tvEa7ow|KmQrv&z#KHuxFgJN^^DJ~i7f{$5o z{uMj;y|WMM*9{WM={!Jlllt8f}Rz?Sa~0%lrZ6$xGTNYq_CB!q>VoN(sUAqFaF`~`Jl5f16I*nl`7WOyf(3#HRO6v+s$>Qt=WVn@Aj9dEbj5f9%G>Sd*aDUzlMG#7pF;#)ZoZK7j*& z-Rs=UFYxYoj>B|+9&NT`ba4>0be0@2m6dLu3jSiWlo`$o*Sj74^1T%p2oJqG0V?wG0@=NPeB>~PwXtsdSd3x2Aaq}# zg>m}nwJft5G-RHkg*7TXFRK}sC94f*)aIWkN`Q8HexYa^M~ftNi+P+X#Y15UMqoe& zN%&i4Ssu3XTj_x0g#F3S%p1g9RWe8|y+S96;;tnxT`%uDe>W4*t#KJI^h+hEPPzCx z?xCXR;Gz|Oc9SbcVM3*q*M7q|iEU(ek8gjQ!)>thn7Roz<0i1aCpN(OJ7d;UaW8~Z zvirg=FnV7pEN(oaDqOQDT39SApU>Cp&*9VDX+xSt2V8zvk9xCqK!gas=VYYaR{id* zy*LedFf^*AK7whCH2%ludmjLW$hqb*Mbzr#r3XrXxfd72+jo{vx57l&e$sJ}xn0e> z86k7oCQ5GC6T61zs>?D(lZz%@t(6BY8>FT13x6ahcQkW8D6OV4U_eSVkF^}df#cog zd}z35Gvirn^h#g#iqlFg1nL6@LtM&Y(@bzrB2M|I zosG|bLEErfT&ITK*Xp7k06G`j?(K)v z4F38{^ra}cO4Qu;X2MjS-V2S7%I9PIYtT^G-Pc)!1;Bcs73)RIo}wJE4j1Dol+cRHi=X)#|cZ@E-sd2?7OXE(p(HC+cGzqgQ@BnMCkk`l;YeufC6_f}$eLpze3xqts zeaM~RJo3$dYmEdmLfAU$N^>B*GffYF_=`swh;bW#zfyO5xKv4>C2o+A*FmX(;i9G4 za7%yYE#H($;x+*&>T-U%#xZ8+o<(^;7)bMNzo7QB1-0Yqefx2G4mSWcgVf8KLJ4d< z^X19n_=f*yuvgS}!)nQ3?`Inm=97%oqFQ>l1WbdpGE-QOmxzin(+GHSR!2U65=O?- z_&16Zn8IT>xI-T3CEp++*Mu6>JXPc@z5MUN-|LhN{d8?uWHJ@}k>cLj7|` z{UxtXCF2xCCynx0#HB#u(T*6Uf<)0!G^$mkQX6PbzX3wdzj6NhNOsoBm=!LnYUa&E zJ6(5@xocT+@ui+{w?xNxYe!*!>kh(oam|S7^-?Rohd?hJ!uXifapUje?azq>M>0z- zZ%R(9vLD*6PeVvgnLlnM)kG>#%PS!Mqee5N%LWWFAHVy_GkVs*lxq5 z1-L~ub-a$>oVp=nq64{#XebIpfZe}%g-FOqvOCHAlndCfzq@?aZ^^EIpIJ9ZFV*0q zz}CnL%@iPZXMW9%3*qU43d8cm)bXF{|Ewr^BhHL(C-sWr!dN?|bGj+j(@ccek-=3> z^ftExE@dHZgOD;Uk=WU+R~0D|;wuj6=)paQIV&F8FT9D4F^Q+c1D`o7e(%C{8j#s-Q`Ir#)nH zvA!Yl_SU%7n5Me7xSh-QkxbM}3q_};19k$tM+#6hNTGr#g|Ix`zj(Jba4lO+fWB7$ z+IGF2w?b~y-?`I|_y%e+x%fHA`HO%K9a!^_XFAzlO-^(31GSO6k-!!(3|==$2JgkW#To0HgnQ=-PD?{S6G9y-8mJ4hlOP*a zWU@oM1>Es3@|Hq+Z-Q=F`t(}d;S9tjJlCly6}D{o=*G6!bzJ5Vl6U$dP$BTis?D3& zwP6_zMMy*##btNTw&NW3FK?3Q0YR9GzMM`obykfOvLhr2d+Rdl$(W5j(ULn1qn^pym0{+A zG3}9NsK?Z4xeE1&U?N*f?h7y}lKzvFSjdCMl3X-w^VG(+l7umzo@jgz!+$?4FZ}!hg^9B#60jP@c_pyk`L<~52P!V9$VGd;oote2@8v9hKEo%pRj@v zvCJ~;t6p^^D-iobU@5`!AxVsI6lZk@pfAqBkNNq3PFW1$ggn^LRfA7H@{*~)e{mW6 znN?Z(G2yZyiKIremDl9r1s3P9u(}(-xR-P&H zADw+;pePj}0^5!}2=Amm ztXwuc)_mV3=B+6#Y!+SoslXgk4u*$BZb4;#8a(#QU~)8`rHxe%YoBnl7z8pdmVxQ| zCpSXc{ZOIo@SP2;2P4IwoL$Vq(#;XA24uoXh^J8Wh~1`YEI_!e-;13wh|3!vch!oC zHe{_de^abqif3ivhw81v;433Hz*s1P^HQ#sg}7ARgEsa_)!OHy4on<4Kg=w{<68; z>nHASg$?&0AWL;P177_i?h>^vfRDwZ`7B%DzHW_losl^1*}Yj;MTAa&@{vZkr+~mN zQWtsV)~c=vNg{;+E7kwYf!|5?2>cN$&Yo9PbTXbR?GGe0>|d$z3490FW~;^L6#cdM zllgeU$Ijn&nMrGNfHTsrTLoI~tw`5ycieY5qak-cOfD>qQBkSf+=5&T_J-j=5TehF z$e&i1J~()gWo%$FOjI3z)Ag#34mtn!Fhhf=(du=~3bGyNz$xmP1K z(9tuh5nI#!K9d_7NIjOS)SjGMp8&_q956i$e~KJ3B+nVkb1Mdq1N!-0kttnMObF*m z;)jywk(TU8_>s-+cad?%uR%2UtD^K)Sf!&r)orEM1GOVU#)774j+_bQhAn&{1R|9+Aq=Okd&oYo$W<@ic z-#aFhi!Cvz4@u&GF|#B!o)BHw#ce>PN90>L=eSw|NtcIVdO-{f_^q2Qh6!HpB><=< zsK)|T1*3N%e=!1|rmnE}fcjkN1zf7`d(oun1AdstR81zRe&A<1vUlzws3H4mr%tYl z1^Y$PAOoYshTkD1rN#5rW$R{tYqyT^`x@C=V>%w}Qa^pG z)##Q-1N&vS>&4rXhWs-gW4`drA- zdi4kZ)+_*pO3+1`saRV~{ruc}q>5DM3e-H%;tc$9Aff_%B~)uyIe7bq{7`p&B?}FZ zEo6D8T7^D;uDh&#h=627$Zw-2l3(p4;pvC_opA(~I7yS1-m_Z2WUFVAJ%P}f4&F{W zhn4mCV8Baf-nStB&gQa2FyfsmtRxw9d!*oe{`T%*kNF+Px1slTO)IZYb`}hd-&6IY z(uV*FGz>{x&Oo1r8xlE&8^bIUD(_2p3{twTxORAdk;y5Y(&%+#Wn)IogasdK&vW4k zhPz*lN@X0XAF?p8u8rb0m8cwI7@<8rHQy>1t?emM=Pa{S1OjU8O3h$@cBr&`N~@!l zP}-W+Wf;?p;FzZTNNUAm<{InL)Htra5~rX=b~Oh~yZ)h*rwa-o@p7-h6f?Nf&1#q; zb`dgvU&|P|yIC*SkzTUOZo<`GRH6r?L^*-k19Px>3)1IGvo^|?bDrM|A90$Uaa#|v zbkEL+K;td-@#rxQA8w#MMS!ghN)~no5`6|G><5`VPu?t3nR+XTHFbB-S3VBi<&79@ zQC`=zV(of{5fKvseUD5`UHqGs;h|fW!lh7u?A`?gt3MbTGBv@BEq1pQDrb_oa?k$z z_a8y6Z4h+mvYRJP&{t@`=s2PL)wHbB0A615fd#+}+~}r1@zZsI;$0uTr>U|_U5hj2 z92{A#_o~9I!d>deQ0~U#Gm?=uBB(ekT62r_6ZNXAt~2Ll?);xo<%^I|-|qG_SvIGC z@*x#TC`-Q!z~(yPFH=$|4zSU;QbjFt!}!VL^VN#wAVeO|9OAVJPPi|$%gjdl9gZ-0 zhem&ip8n#g)1q>+%w=lLxWCN3?Y4*D?PU-{+2}OTS_N5)0Bi_i-%kWF^Ru+P=S#5m zSD$fE@mUS1qS(TtWvOocb-6zSw8~01K|OW*pxE z$odF$V96`Y&lw`@*DyRTLzf^>@F$}ZOyEv!D+zQ(_3aaX|AnACH{GiG zclGBSF7lGs*wO->#Vx_icKWPLwJnF@OwZuc_)t&SB|*p8^TPD_v6FZzWoo4e2NO_Y zL7_xyL{fs2i|R@Lu|=WDR||W~`m6>%(L-S~ddZXNMc`eUP5$-gV$-1V@#%>wjcmW5 z{#N1+Z>x-vaX9~_^V*Pu2wyqy9+BhFJX*Cb4`X? z`GFHm4{|#3kIo{^ie9${v^(v5;GK4HYHa3ImJx_kE;f@Xj>e0fXn8hCHK4VZrQ2RI zR)TM-)OGhIu(cKSkw7h;=^l$fPzE(%O#ch|sK5Ev^QnV>G+n?ZBUUY#9QG9| zSOQN((eGyM;iEzN2J(=c=7X+$2ph;q*P#Ye9 zo*|^7ndyj-26H5bh+SJ={%&1c*XZor(4oP;h$&~#3d~F52A&*o&X*1x<74M0qnF5E zBmOjFaD}RGr&{)Zdh8Nh^TRKLYjp0Bls`H6$YxZ`)Vw2|i?8~9zN`ezIV8cDAQ?l|Q6hEx~)b+xPu`m`CaCHMcyxOCpMO0&> ztq38uD5Jw%k{m)k1h(h%@!sd%+P)5p zZ(eti-Ob{`V5Q=u)#Fvh-o0QJcPvjC%^_`of{2m4L+(Em%B3O7x!>y0cvbR>5O4n9 zdo@mh{Xl|$Dci2pyx?AHjr1AJd=y3YZOchuY0D|~v5g=NtOY>uZB6%v zihZhsFr4=QozDBEr@l)<&y@r+_Da4bnIk5U#1`ekk}{`*hFl+^|!1 zB;zH$p2zn-T_19YnW59c6P_muPqC7;JG2dp@R$t2+LHqINyyoldpGiGEvHw8~VArNmBlnr&JrX`qHNH}W1W$$htx*)- zD)hhK4JzQ(DLId|rBH)K)YC$_+hWrSx;mGC*TVKGBWBKP&-cZNHcXLBVXl`D6!rzN z`F_-b!V7w>R~LO#1^q~{u>RM^I%^93Tfu>yERfQfG0TrQO=?4Yl*3zD;3e5F3|^vn ze&xI8&ms0qH-(N@lY@bmzs3m*fC3pMKXyj52E8e)5rYo&Mjq4`h9y`_m>DNbbxt`7w$w>~v*2kLTlXt-Yvn7FWON)Y$NcHQd4Mo5yfCEZA%nHTRVn)ZCM}$Gl|N3qz?7Xe`O0Qpz^{*Skh?>FL3}G# ztCFa!K8>jb$UnqbkKk#gQ|i z14^uzXwxFU--vakB9dN<73OLQC0}p|Lc_NzwXr?$@Z0)ZOc{%e5tTZUyqzVq+cgKFyo`gstxJ|2w*v2FzYOwfhg$o+7iil;=LA-vI zsfLkzz)ak7_gIx-T%4O)E_2&bvf*n8;C(zjb|^K>y{GY8-Z160XvP?SmHy3NC@0v{ zOW6Z*62FV>@WldmrfM>A06Rd$znhG|p6j4@Y3LP@P>;u>kD|MyKI1H+#2% z0Y@|{=1sU3Kf1bM?=2_*U;8yIe;c#7uoK|!Si=HNWiwic9;m1@T22xCdLySj^N4oe z6o2GTM8jObK0AV5TYtvA49jS%D!%M3vh*6q$Q&s+;y&Eg$%82V+t(1;Yt&906Bbwv?=m3b0e+^~Bo^@{y z`EEOlN3JYdq!W`vsRW%Yo^P!98<-{wtf5<`fgD~5Zjo2SBu`l|!dZjyz;BD{bv|HynHjC2ynI@StbFOyg}5>z{rcD@q4 z)E$|TZ+Z=g7`h&$*%;iee`}nWk4~C#?e{b-_b`$#LC4R#nZl1;wa1dK$^L}zt}NJw zpI|~jF=n*&hi^-Pr1{84xcBeavojw!51Ypk5F+jRvX(?b%-ANGe3yMm>06zinX{v`>w^>a{h2wF)$eh@yUOR$!e`B^ZrU}JQqW!?* z(I3=t(63+h2yuse6BD-E#6t2Eo=Dovjmup@1pagSw9Hl4@eso0+wp85bn-oYit#D0 zU`Zjz$OE~Wg0p6U7&x8ie4<+GUVvGM{_g2+Sh3b=Be>^5u5{r`)hF<_!w?w^M zlYjhvAE+g4u=|i6OW9@Y22z~)0N1o3*Gd(gO`BA~8f8#@Kv@F6Fpxs-5#nHx9lt@| zr%gT)QwiSALoshm5Z!G!V)B%yA`yPVTA;BqVmT(8D9}<#Uc8Hze?0?OH|nQGLL(A5 zqDb-krwrC+e<#C<*)?T-GU3z2V(}__MZHc=`2GB8yPdu<6GH8`Z<=+x#R?gdx!hRd zb1ri$k&WlrFJk9h;{pQl2~(?#JYKj(#|+|KA9W*_p(hkE<}Kbxv{ccjrbyX?ST)M_ zuOdjBjfc=%HrJZFR*;$L?`s@g4zHi}oO42-8jWvje|46*b~S(6CXV_uh=elz02$*- zf?1~eK=wpkS=< zSI*V#?v2n}zDqJsPwg4yB}iZx zQV&fv59E=i6FGmcfE#BrQPqtVY*n6&>5Qc*f7XH~CD76N>TcJd3>vo8u+bm(faA?6 zGm9mYo?iOz9wSbv@=S$51rs@)QRwo9PgEXPv8}Rrk~w%RXtQec@o7*Pp*k(vU?u{a zTZiMMgkOoUL-0Q3Ob_^X;4E=utrJ8)bN1lf?MMr3bf_gE1h+<-dxia80XRQPV4j0$zE`SeDVr7{yNfM| zIIu8PrH+CmH?k*YW+k+wi-J z-nNN3&87+6gw+xvi_sEZE;?>$ijdePWQ~+lTO@Kwko|*d=q-w&FjnU>WMADUB^H-o zGf45*p>pD35!*s|l_2_6e{8Qif12v^Nh`#s|Fs)HXH04lC;yE?>xwn!-3XJoy+u%7 z6YmWxr`ACVd1YUu(uEE5ZV?2PdSsHx!`qt)VbGYru=N-p^bT6|dmB~{FzB5B2!3UA(@+7(Y69X?GRChuH~2ZCiIM&gPrVX`HG}(OMiTWyM>EGf93mH-pQUa zvp_b$?)tbdp3+{k@g<=B^_7zGd?>u|^byaYtjRGI#nSHQ`-_@q@XACQj_1J)x- z;+upz>@-@V4O=z0{H zZ)SPes($))zWAe7?1-Srm+%9U%Rn?~Wg>wwITGzkTtq+ERMFmqfObM%-)iNY&Gn%R zxz+ZT$U_2mFkaX$S>_$!XSgjzxtYhr6Nhx0xsutdh6UJ@Q|~86sfKP7laNw(?W- zO6-Zw=}Z@Nn0ua_7I+4{p6$bE1+DOXak0HvgJv_RO{G&7R=^8DaXIKwlwjeVu|H&) z{Y8&{l>XIxN>#EQn|K?^ZpL+@WtkOAw(LzK=;<1z(QQ?7p8gv1hOlC6V6SBCeLOFJJXHndq?VRfA#GaB zfvC4grHC#vfA7ghItTJCw;x0%);#b&;}m-$GP*`v{3E-3w@vq*XU9Yn|3gZ; zK{`dS!h<*TOWe=qN}}Xo2=%Hn1I*$F`XnBA65z~Te{#^dECONdL$!)KPQEFWf|EbM z(D{PT66rkkyi*5q^azxw<}D2L?zrxDVt*RAH`gUk*bh8n=CAmyuFTfXtlxK(?eeFy z&XdZg#&BYirc1)%px`YfHWhzeT$EbPr$V1+V7!|fqtccq)XA_jG!XAvAWgH|8b%(K z@UM5Ee_TzRIrxk!jV~c{Bmcc$x;`DCM5kbAXD_`t6UZ91tbhELbrQdsD637J{>k{DJb2r-f!7fL{B~pf-cJRIV>`}Q|qXR z*t-z9FjF?ulY4Q~T=br#yO?PBS9zq9Sz9 zuL}Bn*^pK%HNXt9L{{ZvZKJa|1xEh`t>k9P;;{nUqz7bnn zr^!Wv=GAv7UU!1bH~xl2BJ(u;n(9t>n1>>KC*H#{0LzDH?B&(Ow>e%8^0njuA!2QT ze+654EB+NT5VVAYxL35&C>xywzA;7OI5r0M?N?{KK)i5fB5+S2-A_g7!&{z*FE1CR zooe}B1o@Ao^HVbk#)L{$7-dF}$)aL=juoLq>Dj!QBes(4BP^nLSbJ-5Mm2cw$2Q?+ z*4Z!4o2{-~HcGOUOC)H091=L+1zAude@~H|wJr6!9qb{DIeut)L@t1Rk$uE&ZlXPr z8SveNI*EY|ByphEd2}7ZB${?sRV%zSgpv2Us|0fS@cA~sGjZ3M?d`4T;5GlgwSXh0 z=wrS~RAN_=H{d+u{n4c!=oUIPSkC|iB&Nm=I=BLB^f^ZsM?Zs91^B3D;%c~Lf3jAQ zR0Ee|2o4`>%g!pGt4Z^{ZNhYaagD8xK3fHxAZ6W^N7u<*GpNMMkzUV00429%G$=glt!=ONJyT3X(h>F4vwBw@x^Rh>#jXC+A|67I?CsFuQRo zD_r_33aD)fR8&hb2iN8_WpcZRD74!ehvHQCW4JlBrN^QLRP_|{WB?6Uhq==!rUl+> zXFlUufsf+|GMjLPpebm1f135Ha^v?Si^O#Wb%8%$D5Bi*U7SUPcnM#DQoAv`B?XZm zr_6r7pii@`P(PSjC{hhz^ufV4u<}w~9(*ykD-Vq`K2+J&Il*G6__YQw2%~*4|7=CI zUtr(`w?rdW4Ae`(R*FY5$ET>Av!Bkwe7ZV98$UJFJXe6fT6pJne`f2Iv*Gva$ARxU z{ZN12msK66MozE(6EjX?Pg#lXlKu=4>oNE@jF7f&>nQ5R3n+5S>PO4J=_K?&T)G(AgMOqNrO_oOL_OHWX2)^5Dsl5ie0-_PDK)R>@O(cK{>b zQH9^8kzeXW(KMy=scFin9YdiWRV*b`uUUrYxR^cp`onLo>H=2P!@tSv#}!+LUF!Pj zmwkSn#Yj8ED0?s>{&^RY8Eq{tuhu*A1A>O}gHkf!!GbVpf3QQJ1_!a8d~p4;_S4s} z`3En7dX`}F=}8R=65~3d=B(pNLfG}EiTg~9n7##GQSj#yvszq11jZuMm{mJc=b24j zObM7eXMs9}!B4A9th8NpaZ_uLkS!vpP1o*KR@Vmk4wGhkq+J(^>_80)Hp*~!K`r$H zXA6=R1;*F`fB5d;7v1zjtS^UMMqLm=Wy(UGbb_;Q>ZQ%N*dm8 z136bRd#2ap6N)vA2j@toQdN?3t%U?^M5?t9Wn!`+G>D~19YZ(&qSdY)|7Zp(e3L5P zSk-Iq3ai#tKjBQ0UneQ_+GQ)Q0UN*1A5$T=A>U3be|>mrP#K!(MLd9gUyU^68-IxN zjWMq4z&D5XuY=*%UL$tP&JTNFZBvbEGG!4fbD|&fj%tCO$Hyp@r~-zl_Kr2{k&JUf zAt>B*M%tu35NW8hkf14f4Ze{U6(;^8-b3@DsPqWAiF499=!LeXrxGHvZ-?7H>#C94 z$+)Xef7+_p0Uu)FocVmm)`Iin_rX}P#1%s>0%YuFK{?p}-0u+{ zRvQ&fsS7#OaJq*s8sit*nO=QdtGOqgcygE{{#G~%=Zx zW3THN)|T4r`QnybP!l@d%6UKN7UX4ue=NxJv)*97qo>?Vg2s`V%T+JV+GNqQ z-zN~Q&qKSuoq|qZ)i~5D&OO-OzGj-{3fR!9TFn?;;!UoetNTWt>Qa}qU2822C(0bf zrUv$;pxFo60)b<{CS(lWYd5ma@lMe+%Bb&vs9mOG1GV&({FJt0g)^ ze=)!}qg!=*MP5~*suH(hlKh(cki}$NQU6TlaEs>t>~q`NMehGuQD+#-<7Mcmmu>b^ zpCj3}lOjNkNi!b-p1RY9?yD6Nccj33H;e1v9MgcI;}gxF_1FXkafy?60s3n(oJDmW zQ=(?Le!jZ#wS#gG7iID1E%4RS0U}0Cf8TcJd_)${LU*eJ+OVfx;&O@F%rBBO=<^yr zZA6)cJhwp_>Ql@r*vkBg3jp2Fb9ZYRE(CPk}Pkr?1 z6RKrR)k!JUd0||sA5Z|)N76TIHk63WH_n4lHbhCQqd&_r;kVE!kCJXv{t*VPe@-qE z9=rJ~=MBP*N}_Tv!bQNcv)VUeRT6tlF^xNxWYA>~Ri8WqW2yK_7fJ(pc;@PH(R|xG zCApixm#j#l>&+2lp`eJUb7;3uFhXsRMIh9Gm~(OyPl0*h3D4|E#WRnC4Mk9Q$nskimfn`?VA>dM00RV$LJlM7wk}f2%4|UOJ?o z_vor72rKM&FY@aCdx4{)uSdEeN}n_=I$lK4C}Bjc1J9#n$vD>Vr8Lfz7ik(b=5CVa zWGAr(n{hJKkCBGd*&rTEm@mJV>L96*01G2F!CMFxQD;&FX(~lv63;p;q^8G;OH$t+uI*+4Oid^iv zrS5-=>;rTEb>lmB$3bTbS8kr7aNItzDnYVEQ`?#%$Jm}^$KQMdfA3;1O6(5;Z~cRZ z*E0qMtt}Fi8Df$&&aCSAQ3ZScJ5Z;2e^xHHHvS#}PC(m_PG4-H*{UO+KjfE`s6Yqr z(bn4Xv72*p^4och%jO+od@DN+T5o$AG`Q_NcrtlZ0EPW>ta#fJ>TPb8W-EzVvDkdg zPZFQq27$Htxct)oe{*C~odRyPe@HS~9I4MytaHLIv+kBYAsAWLV{Z@JvFn$)9XA3o z2x5pA**o;V$M@E?y>Bb@4MIm!{9VjJh>eWB(b$yNjCU(l#lt|FJ6NiNn`DK%XQ@Rp zGoGk(Quar1v#*<0_|)gOTF-; z=?+B7w#o<7&c?%5wWfp|Z?Hkv$s~zl)B#WFGVcB>;1f+-b?$8?j98x~#HaLx%Ae=IrSjE8M-g&D-aN|s zV1fCpN8EP;H6nO7W@a6>m=qrhWQvufFFnkw}`Nth%v?_cV#O%!gYBkG;}u^J;!!Q+t`QVt5;(ZHfcPl_s> z^hhb$w>EL(Kzxm6mQr@qKi3DQ_`ei5y_*wuO)N;v`bRU?1s_{yDk$-?_qdQ-n8YdD zCY)_2f6O#wRdWoRzvqxXL6+1RYp@Kd^ObwTogW94UPGr9KsDzy%7??MX))bQg{bZq zf&x=x<3F3^V=-}|KD@{fDP@IC;grC3O+{S>Q(F z?{`@C6QOx|G;w-byx?lR(0xOykuop;%OI@6e_Ffoc925kt;x0CzMIUs6}#32<@&nM0Gn8vukvD%B^tFiqvCI>IYYIFEFt^79_iX7HZj&_oLDkkMV|qL{brV zkb79v-)hLRz72%Z+i@%Oqc|5O*lEZHqS=_)_xCqo*lu>Y$B;+cmQL(_Pv!fqb01H* z5$mAH(-bEm5ePrxCEe}wC%e4&1p}PCfAUCrday4Trxs>ZJs=mRoBjKa)kcF7mH2Z> z8ER+2cVLuJ@NdZtu(^K}t2`h!?6YvsDi;PQQrWFTx4^`eW(F3MLP^7_WCE>)9P-zA zcYqgg)vU-C2NTL1S~J$>^5oaoIQFWUy`|Oq9|WC!ebpw{?mUBjp2d2h30HdMe@Jah zqsSBG2htQbH3RgPepd_T5xf*CGz}HESIW4gRz#;BQoQ4f>V>%-kGZQf?6%f1GLwy@nQ6@*~zwG`PId&je1SYs*jYPp$xNkRK<` zS?B|v9G_A&3aemBW$x=E!pg)9XoYQq3Hk{mTe-^e(7>7(+h(WAWp$c%_x3(!Ityj; z6Fusbp1fVl0ysr#;9(ii+M)pZx5Q1PUKnWhO$5li_Fx?7J~jh_6DkYwf4jl{n2y`C z{-+RjnHt8v@7nsr5g&y9lZAN18hSNImle;OrWiIBcXfE)+mI&NKNsSaYh^RSv>O2P z(2036g1yy>Hz`W222msi#|k7A>-d$ z>%y1U5!8@-_ZY$$V?6Fqm&dzpa3wVZ{yH43RQ5yv^ z%gUWMU==+S7%$AJe*z`e{PaXIAvwE&e2c#fsn(h`Y>(5y=k#*ly zgT~_``Uxl_8ODebn$1~kx6`01$JiI}vsCohr?M^f^4H_Ue*%LZs32g(8_5VynTMVzf%5s6ALX3x*!nvHjH9MBg2ei0s`gg9#d>bf6i4{ z``4uY_dXppC`Yf$W%JT`>HU;5R4*sitS=|6=h4#rFMXgdQb?8`bS|8Q+=M=!Kcv|* zUV6?cAZXI?f6HMKkEY*em}r>|WV{KVq2Ko;jrtqPl~<=Xgsl~qHmsN^v~aL1#Iu&O z$QcPVwH|})h*VLdxv%BQD$tU12Ay*o#@0B}y>P6{;d*t|i2IgnNmvfyUn{%aM?RI0 zCSBAxu1eM}mWPaY4o`|T2Nx+9ltI;3RjzON)4f~pf2My`f2jSEk29mK;f|TZJASrs zBJqDZTewm?NEZgL{3q(5xyoHu^*tisK3jsFl>Xl%L-(;OIoc|r>b6zbHzIl(mZx|4 zJI=%+PPsVFRFg}yK+iS$?ipxhfb~6Pf}qKLZ~kXhe75IXB!Ad<*HwOjY(Cq5@W9w- zyb5I9e>rYcILhF2-HNS^gTf{nX;(l!pLwta^7P|?6#clvMT&k2>$*^*LU)u{KP>_9 z^1FB~$sCB^C<-QMQ$%y<(Yc6Drcz$-vt8ZR=5kiQZhQwS1UZ&vXaI%!6b$c zWMo`quu7hl&Gf2)NeOaH!0`I=N_jAC_1QPbG;jn@1QSQgNyw`3uM?*f~$ z=S?G{Ro5eOBj$a4?wrd98JqRJlcA(ge`iYYJ)b4zqOoyS|5RExV(lP31ao>RF1@mS z@WdEHR1++XbS_`e@IlqBH1c3q6?WsxV=Wk(B z=vdK0 z-qZ8R;3TF~j}OZO(2zKDhIB`pgY{H3$Otrpp)k;elK80$!m~9UX^U71vL*J{EBp+P zjBuRP5f(5sBX1zq6^lW#+McDCf20dn0x-7wp^>idXYwG#nb_~Fwx7UFwR<>b1tn z+w+tw#{Z=2pHJHv$$XFDz0XkYKUH}h3CG~WS_RX~M6Nf78}2ohlhx?Ie+-nful8_Z zh=Y7s&*W{K5*r=1VgH1o+f!eFDI(CpY(3f3yz0=ZdV1q8TT_~9FR^LStUxCHSY9xI!=66_Q%fv zPwVRUzEUO#i?S~La`cWge=(VE;)VRPvotTcwfLmpoXl6Tx~^GsPOs`SKS(x*vzs}> zh$q9N#Y(aIeZwt{qy^FMBHs|!aXRqL_5t!%o9*EPB$f_^-hN6G z!{P(})OR^|fwtB&%HZh_HPW~}ZS7e(Zp*PwfZhy(0xlS-`tqz9f7%LdVvzFEt$T6M zhyDVa;gOl$ADP;3W47gGWrRF?u5;>|wd7ln*J%?t31P=7r?YgN;Lo-a z6I(m3TY)>^P#Tg z`ryTGX(L8RoxV($v9f692C{!BHK$^^2*}wg*aod`CU>WQ}oL zg$OEXRwQ}K+YGz4!}WeJeDVHQtcfLbNE2fQCgX)=_xYl00kPXf(v)?DFPN-^gAM(3 zD`QHygfaVO02NNVK2({V%`s;?BSqWH%(IjufneZTe+vON>lxJ9HWNwMYlUeLsi!jf zlRL!A7zvAGYGC2|Y`5e7qGw_E73RRkZz=*XpgRyjRW!{Sa7yjvh5(_B!?NeyVE9(2 z3VOMDD3TB6x^i9Sgv=OcKa`Mi9f}m?eccYZ-&Dc5F=8oplk7prfq0J25uoXtY;tTl z`2!>tfBQt8*92Ax4{TERJN`o8U}n3!2L~U-vxz5wEmMgFcmg$gO<;3K#xD@Bst(u# z-k7Pa@xeU(sobg!XdjB`$=#!d6^WT7=EL#i0SSl0Z#iqjd)W=vEn~N}R-|k*#PW%# zOMOgpoy$1yjy>(>cpKt6;FUE9|8(cqOVCB?f1*!|Rwp--eEfeORQaKU_w~i{`k zLep*(SdlHarA=l-45gM7GQBlR7Wk&n)r8l~>cFdR!LE~?*4o(X+bewh1Q>~nL0xV3 zFO9B*lk5%#Uw1@rSJD6<^Ef{9yOPQikjL4Fv&*~19kJ=i)(t^Xn4!f5)ow=u)vbLH ze;9cb`KO8d2~8H>d{0r9NeJT_v)Q#1NI|rGWIbc(2u%|6f?i86Cu%9(GnnYN3Wma~ z+QB_^spv|=XC}o0FQu?2Nf+3idRapn+=9zTzSb8jGjx9?bXkoadOrIJY72>l@XGzE zc2X8iJpijpIpaPT$az-sdXaWA@+5n{e-4u~3c`(tbNnej&>5o&Dq`sjJUe@JJ&aeR z2{|v<{_Qc|Qw~8#S>_4M$d7Ed-ufMBw) zSA{mDC#RSA%!|EV4pGbQ<1N@#s%We_yH-C&dRg*ZsFBy0Fn&YJMrhZW(swlFe?Hg` zhY`IRz<+D?EB_;i)cUII@|XnI;1TsdPg)a2rXt;_86CN&4x`7xMd`%$OqHH`cOMB9 z9xaCRz%hL7vwc8n5ghZb7THozwdVFo8}!$Y#9ZqACP)+_dED!<6-^rti+a8uF{=4Z zxeb8jQ{Y5WYU$1p!Ea2QtkccEe`utFPUlo{AZJcS<^nZ<4E%ub0TR?4tF&OJ@BiXH z6G2<{I2-`q)rdz&GX_v5P+fBDXp&$*@yQl{*H>T00fAK8_&wF=1HTR&e=dfk!_NWCW~nN71t-}BFO2u5+_he**|`2MnsUT< zm$!k>Gv}JKu^#6{jv@#;pV(7G&6%!Q*y2^Nfqv;Vkw%Z1i|Y#Aw;%+ncM?r$J^a{2 zG9-050Wj}`cM~xlQ07+0e-t`GA}Gu;UbeUwWI)DOD7&{#+IM{u=6Avyo1W#f4;4G4 zMl;>hPfy81PXVs$*CC|yR_~r?w;L3+O9|IR*b>Q9VYHzF1xUs^t@c|k%0^mbccs+c zi3J_*r-T%{5K6X>->5B4Le;m*bw!bi+0?YO; zeufYEs<83T?s#)6jK?{WeD#Irj4B9_TAc` zy<*gN!W}uBpb%hkNq;)E{>q_4f{ntP;@ed#c~P!ZZFkqm7Uo0zmb^TsH+*D>Zf2g$2JioE_?WzrUikdX#(x!NiIqk2DpQWb2?u!zy-J)8{7@%0e z!oP6~@V{uLtgpL7Dgr!zn>KXG^3@m?0C+Ct(-0xO$7uqT9FSEL+rMhjp#Oc8YgU$K zj1W$YK2h0_)k#HEu^47td^2r(>u4B4yN9V{`h_u1 zfl#&ZKWezJg4J&}ooG9NO|hhzbJ&q-`!6Z8OPd)D-QmYooQW5N+xI((+FssmZFd;8 zRNQ$~ELrR5PN50u0D*h#67zUm5tsBqy(y(6$B9f2=#j(nnbLT@u@jW{Zz4XA$iqoO zv7E54Udmu7f21C@BAE_|4sM#j74;EtvmW#VF zhe}h$YuY|mFJZqUiY7*kabC=uQaZj-D#~u3J(0-#EWa$|iQw99nE;2EwRZb?NGYDY zx=(tiS;84y{Ow_(HVCMnOpn+xA?)zGI>wsSatSFtf9vjv6eznorhIMnt=}S*q2PD5f;Wf zA!ewH9#KfV@RcM8AR4kh)=EBmVuojfK{-Zt1?-+*J7#uEkz~E+d3KJX#dz>Z>3hLD z_s@j=f6>3Ff6GVEjj#R6(AT-j_A@EM^-HBECd#*Ux&#Uf#~SMJ9;I2TgN^-MCWV0o zl;wl_M=9at(|H5^@Gz!eC1sK&LL ze{}W@pNushOj_BItncH-!e*S3$q&HS!(AA%G%f_6lqZ=hf09^RR7CWDSEZ0OK;l?F z&N0ck;O4E-4`mkphY_jykrT0CrS8yj(1UPnjTE7rYs#6xB39an;q?$f_Pu4)BQ#;!r!-m_rI8k?dHtFshkZnlI0dar;Ll}C zC$0Mlms2v^+)yH2FSHYQgyq{#_q3{7-Rll0aqQI5Koi9X7E4O$9N3$@E#Yp2f9rs< zm?ATgR|MDUQctcsywp?*qmkc_k)!rOrC=|%N_%I=1lzd_ChG54-4xfh5cFzHn~;D#TWe*9nq_&mTi(c^)Y?$Y&9)d zHfVArUIPQg@0DGd8T>mqfB1%?kymR(Qo>bZsdw8$p_K+)Iee+CUr6NCIh58E`3yN2-76f661uND}#{-+M>)-R3MXTzmi-?e8fVv_?E$xVfN1J=Ls?X|{6_ zS=u6Q1?6HukDSR+&kN`9ow>DKMH>?ZbeB|RFo{=kxf$55By@M2*>q}Dh8whMavj&% zZ=gquY*1X$<-PD1>YhhRbweo@oh>L3t30jF{&yN$+tfUtfBTsLB}@BAp;umpIuF#7 z$4KJVWF2%Ag_L8%YWnx7im?s_Wrp3KhxU;Ds~{n|e;dM;z~J>X6@CXW#eQ#3Y0s6J zH~b|pZhz>6#w~jc2@QFFomS|9Kva@`uJiUzhVHnB+PaO^zI+qR5H_b~*l;DA)tj&Q z0SO3?)aD{!e-|#h>#PP9qYCshcD7&(|J=}RXLY{3e$U%=`zY~xiL>(#w%2nGDV$0K zAI0LU<@PZlp3F8{VU%OG%TvQYS`%-^=|o==kR(p{Rpvlnu2|g&^2se9C@~+uw~iz z44}f0JRlTHJ5tXB##rL6<8YEtB=nFqqoYh#lzO5kO@#7GlnK{O3wj|fM7?}HJeSZW z+!F~I(VLnZjg=t=H}PtOiyJ#uLF7hm=MI<+e>?P+cXx7Zn+nTj()q1%ER+%PIDa;| z!|&mKt3i{D9JAhk!dOl5iA_!yJ_07r7*Vr^>YV!2K0e4LwYRhO>RYKTW5M zy-{6ha{kDqWPX4Y<{5)*`!(X#;*r1N2%O;d@g~B6m3+P>qcx`6t<|6ywM{~{>gndO z@Gej|7I0f3kD`4Rs&#P7Xr}>`&Z1W*e|r;5L6YC(q!A7&eIuz5M_SJY_8(xbf}2DA zT3QSsg~9`g6wF3s5n7p!Ybh6zx%K8+v!#7gP1`VU3P+P#fGdbd$ttq=aJU}Xg2I>H zz~6gas;IE~cf4+F6`AB+tkTE(Nfmha3YEE!>FJOV>q+)ee#XsIPOjd)3PyY8e~6Q( zR@6#Yr43)k8@7EqnDyd`fU!`t-V{%|AI-D*k!olr5pCX9a)ajItDCVaPlmTIlI1l2 z>_I3jh_8*Q{!_Z8#Jo+XJM254wwQA2NOxjuMiyZcoFO7+p7y=rCQM384d zu)X3Q$J0`bqjBUL@QdR^?xh^@f57}T5jcj1Y$9YstKrjAx>r!M=&&f8P|<2EEMCq# zGD}O#+iklN3--moBNNW}+0S|@t1g*I!HcjA^98MsQCrkxSU}@`UeiD+M%9K;cQ9ZW zXBcP*xepgT)%0sOq`r#;_p1~=rPj|)j#Hrdz2FVFCgExkU3z1V&ged^e<7Fleo;#; zVyAJp%g!}6w6E=e#r9p0vbA&C8?A?zeg)p+yfu9|RRbIStH`Qd95tu+@`1974Do^) z4jRcHtaYao&%`wTdzcd(FQx55>2K-2>W79)rBv(V22tbmWjc2gG3|L%3T=a-kupDW zMv}OPvkg#bpzrT(!0C`~i37h94z>=V&`Y`70+mrGuQ%}=WFPL2xY)*5d zbGD}h8Ien9MB&7se4>92mH9V&*creTJGH|-2xTVZ?#9=(j7_{eLUu_TAN5GshIeE01F6ftPg(Jt7BG$T5eRgveg3U ztpgCk7p)~$B_BL$UT-&DgL+wfk!8ahw%c{L6kRg}z#^L>e_NCeV_R*cDwDvvQ(zrx zlJ-o)`G#NtnOwsEvP@6q$Pj_2URNrc>GW;-y6D|u)w%%}tn7v>Se9r+KyaSW)WAxo zg$fk=b2MKIJyrHqBSQSMA>1Y;jy3t__)cezPMUZ~5r*J74@o8u>69J~gU&zL`1uOx z#}ralM6Q3)f0-LE$Y}%1dhJO>j}7>a=+jCxR1UY2MJg;afS7tpi4r~_*CY|7TXU$h zbgR(ZaX8A@NF<$maYqMVY=u0RQEWZhQC>d+^Sr0#+8;d1j#$$2ZMs{sm}3bX_Ckwe z?e%G3P?vNxTufV5Rk4-6>8g=sZ}2GJlo~FKrjiFiBi@)^9xL-}Wyi_L9;5;1P(cF^ zdWFKAe`#qh{DVB2lQy)O?Im&#zsqm)rDwzT>vtM6{m)*^J+oCiDTIo;Jumg^MAkYT z?8ARQL~ZGPb$(4YeoS7G`zD0mjOUlZ)}QHjW7NcuF(66z+CQoafK{?9q)!jw z8f=utIB>UXrX69qn<^);UgrwIt+Fg7`Lyovoak0XMmuSG-837lp!UPK@3fxae`^F~ z!=reYqGD|4xRAKjC~peM&E4ygb>?8Up}yH6`9SYb`mz!V>2CPN7t@do$Ey5`erzMT z9s~cNIkR)}CdC=mR4WzN;va~$tGO6zhD(oy*7HN%TYKF#UJ_Nv0lt`dB(R^$ST8TQ zGzWqZbV!@~jlWxEVRbGRr^cWqe>O0gvz3WP2`DSGE%fs{@HR>CrFB>z=PZ0*;cn=D zK*ltm(tSi;sQZKoSpDf^DJlJ@j}>S0HxFC<b2p+qc;tT>63=M@5!qpoH z`dI_ZJJgl-yUe+CmUn&4p2NC9G(aG0dUG0C&b$j$5N=IiLh9JOb(rGY%q zHvO?T?O?vt!@5XiuP6<5FcFXgt7?V|)$Q^b9O;HUiI0Bfqi(?++Efoi_ojDoPU_@e z{paU0d~Gi?mijbli-RI^J7r+j?-vYE;3k6Fqy`r6=z9-%9y8DJ4> z9MxF314pty z-k{jCY3K0N&PqqAmzPgAMVcQ)czcmFv3z@!Sn-cB)N=AqJ?NjsGT%6Xly9TCBdOL8 zY%IrMIC(PzTWX?b+DCh&QyYSF_Eal>vEw*vpX{K?e@$NBA@WGyU%Vdn!dK;D6+(j9 zq?a#GvqFuLUmjqHHUTmw`&4EDN9o+7)!mzu@1hAAp*ffGmL1?H$EfXEJ^$PXh)a)2 zlEy&4g<_De#5LDB3EvmdN5Jdp{;m7Z&5SuYbX6vi!GO?LY##oL=3;=c(qjrp)S*oCnHMVnr4i!tX*GLfGyQW+Y z*uzdr0e3IVeAUcOF7$Gf1K#-e0!C{8agMc>a{OH~8Kb{(6*RTqYdCdUkq6mDY!)tR zE^QTFs>Y6o@YrHI_>Gif5cAVCDZip8T@+Fe2b9mejZiBcv4*$ z^=yaO0S)0W(#|!1_&n+Oo0YOwb60jw&$qojaZLU3X!A$~^%($M+2FH}O{UwM_ zf4T!K4!Fgdc?Pa+>8eGk=1HA-rpfZYfSrm~zcpD|ZVNR?=V;GdQI-aimiQ3 z2{14CZTkVSl${RGU`$R05{R&vT4*b{6&40(B{Z!j%xp4TP{vfnRHACEoA=0=+nMy= zp7{HHR*NaG;`xFg;t`q))|nht!5>HLjqGofXa=E*WCWVZy%KuQQns+4MNZ8^xLW=gxZ{fR47eP0kuu*zns zrXW#2A`cYvjt~!7j5;q%hpUC#d49fm92aoAv;CH}%-3Ha)m;9CY2@``boiU8BzdRU56+~r+)>S)9?n$%pQP)=*tRrG=s{@4o=jI#NvhH zwXxYh@)?s;7lgF6OyMELaR@y|@2AI>2Gai@e@Q|Fd06=Q-oR)qzPBFYi^DEWSgkC? z*$T7|FxY#K1+Th+K*cqt$J7Iq5@?BnSWxBVy(0ZSqxEt+;D3^^qCDDW-LV)t-+vK= z!+4%Qb)_Hi(9e{K4)Tgt5fKa<_xST0cGlaaT-v>^(%9MSQ&^Y~4M6f-vDi^&rfo_x z$4_j33R4W{k9c(Hq_(z$#ulbqbgz<=XV+cvs)<3rGZv7Hexu7PAU4?xseGkf(8XdQnz6omw#;wm{K=h;*RSBP5VZ_p%AGSwIn@jb~%yq4V9^5 z9e5%bBB>y^v&vt|Av$zpZA=hQ&866lqAThcR!FLnr^FRK* zdud43d+=2WweJmmttGEkXB{rM63>OZXiOnVpqslJyWC)dv6d(-X{TyB;(tk{OS=OM zn_v!ny4sK-K-^yR40BOYCn6<^lJXSD7#Bt=M8>j{)-op%1ZBi?2*N4AKLOa|`XtKj zL)cmvOtkT}Iuao$6fHJ4?{gzMs_}b!@d-cYC_%FHj`^)+;bKXIXmpBoX$AVbToZrt zgR$K2YbK?IXz`ht(lbVk%YWDPD8kH!D>6E8N-6a#FV}e(zk_6mL@FL~x~~Io10UO+7P0`@aHC%siNUf6dGK@)grVZ|iBOt$VZMF?;#od$grGN$1TxCBztN?0 zxjxuIbu9}&^b?iJ9CUxX2fU~rJWEqB#n;A^p&Rx;cPKxT5t}86-hU3~RUO=1G*hrR z2#LVZ>Ctz35i`yXQhBXtx8sDHh3@5_)+hS(-R3M!uFiqCWR2It^=(;r1`fof+RHGE zng0AG6YuF`WYgfCl#d!iF`7}bIaq|2{7y@3!D?TQ)!Pz{`G_#@amJMyhG=Heu}6YZ zMCW`?6;>C#oU)N^Yk#RTypN!O)9c*Sp)`ZDdWb_N>_$Az`{t+!k;w+BzI7@)MAXeY z)Nv_?x9>)*ri30;^2jWqys6fuFMd>B3 zSg7P(l4AIiR@w>?%RJqLD-C8_g=*fH>kjfU{H z!?3#2?-}JJ34eWp)D0sylN_`ni9@arGkGmPZx%!ZVSYcOTW2+QQi7DACalME)jO%5 zNpug2zHR!k0=IK22}W>XuhqElY4xRODS zi!&^$VJ5+m5zl0aF^rX1abmZ?NfDd1Pk{Jt43tN68eT2zG_+a{eW3{k0>}%XN2I3# zywsmOyBE-vf?FRe>bD4ZFsusTQeWwAzt{i~440W^0xFl_GXo2^>iPoTIG3u80wTBT zGXt#?m&y797MHF^0}KN+F*KLaW&#xjGBh?hHsy$cLrXZ2Dw{ubVbO5q2urM<7 z0@NhcWmuSbH~`FyY;Y75VopF~7b|-^abp)CFF*@u22cY!09aT7tjx?Ta1;PBdk0S^ zD+@~(0DrY9&A);GO&en~D_bikfTq2Ty_=P(C4k?}%}v){j$(iwA1nk^^PA>ltGk3DL1t>_Ui%2Rds(%9{#F*5@0LFG^0D0+uUbk~`=KTi^ zGV@e-ZzNi`ZHGBOL<^J0mmuzvEWUl2#r-Gi586e*`x-w)sb>f5o+c z|2`cBpqZ7c?Y|cR{-er2=W1qeXXE*Q_x-1sf9=YoE+Qr+sYv&qHuzUs!p_v*%*xIJ zpyu+AqQ*{U{|Wpnt!!-d?;Zj$|Ic#&@_$+W$5$|RakBCN=rS|@SCcUR*Yn?&{{Nsv zMeRMj8F<(M3~a2-02cOt06c75zWh;TYJ9ZeFhzl!%-LRM+vSG)7BQt;LgZg2ykiEC@B2yq*6?~<{(5u{8z&7PHe zQ7h|MCV(o%5^Yr8IRJ^W8^6BvXeULZPlcAL^A`blNLPb0Zy8c}VSy&P1a2%%nhl56{M;xB&_J5Bu#%UIVERmoMYD@3EAwgDxdGDHYf7#2layq^H zwx7p?vY6mao#@P6^40Uf)oar8-_y+eSAG5avy0uexKB(w8Z7G9X%C3IpC(J4;Ypm; z)>{W{s}KRx_%!xelWDtb+l`*9cbx*6?uCNJ7f^aFAmQDqlUu3&2Pwsi#`a#XO-SOHKPK#ND%>fKNl#G3%vB6 z`_!n~Ihd9vRC*m;4tr3zSZ=9Xbcg8hipA5-NctaVb(r0`obk_TCVy*B;-Z+Kpdj5K z&+|Bscd=Thln+NGxY)kE@>6{^V%sfQS)R@HfxIW(q1D#>0U2$f3}GsaHfqfpEzNtNizY&pi&Q z7cCf5m-J31eh$Ah^M9t-vYvxEtES7=@lrV9{P~atcrQaPwJ9n4P04H+d^+Br5(s#1>zWpP203@iJk8c)4}K(kDd6- z8~(l%UE(m+3g^`Et4ig3WV{`S4n3gBVK&+c%Ut(H$*Sbe-hVH9E+�(B&#Avb)fX z%|bY+(1$ycyW*Ul%0TB^qwYq@&-G`c-@!XfLq8oaAx4|Cx8UJ}{p!(Ez|7XxU@Agv zr~s>uTOP@mz)Y}dlqb@ENFC&hI~9t&YU+eBuTghXQNW{H!f*exHNkMf-PN=hiU=b81oT6V8?}YP4NnTQ>+RJ14nh4X8s0yPa`08I*T8? zs&c619{x1~)`R$EWN2%Ejv2(IroYuw`3aIPH1(C0uWHM^@XQ`y()7B_aOx!OchP1> z(3e6?H!wliKW6|5Q`y>*79?it?Rdf{f>CKogN!l}aet7%ZK~VFS7rw)tZ+wml1`6< zraQB>Ldb3*USUuJ)Qa0>L+kO zL}M|jNX`#pk;b!-^H1q~K~%1l0&0Rv zb>gK5b!9MzErEou@1}sq1$W-hN9%{kP$g9|Xgc}ni}Dec-JhvrDt8z;DsAm+xy^}d zef*S8#UGyb+8RV<$r1Wc+Yns)sY&ye$MNKwf`5WwSyf3+1amE#5KrVQrNl#Mv>biE zKT?H3Jm_2cV&snDAr+3gHctXJzB@;f?1@lBW*%A-iwLs^4b0(D;ud>b8v5Ita;0&& zg4q?OQV-RZ+QTF_vYYs-%Wesj;$FLOByah-#JwYCd!TOBq4p%rilAg(8sa6Ud+M$E!vWo{_dh9<15Qlt)S&Kdl! z!TPPk@66KrD1}kZcgrWxG-N54S4bMu+~p~NfTkPgI#~Z17C}}eH135Ov(L%kRxkDY z4FP)P!6gf5AmT1*gUV?ioOUwn1HdUQW`6~*Wra?&*-dW*Wx2hc-VI!}o)y7TWm)R` zUApm#HL|}K5D8lK6X(3m*87J9KK(9Hxhm*&@LycG=S@Md#L0v|JVOybuN%zHQC;_N z2uP-?FiwIXPD$Rzvgb*ro&#O{7tN>8JZ1{Wk-&K`5aZjke(Q3Rn9F{FR!TmSa-HF_AATCf4jWZhh3Xeo5A-VzCDaCLA|cB z=?`~F&xKm+JY)Em2#~k+hNjdsm49q9m6Y-RQ2V82`u@7MDAty;65EGL9lf(38_Y*- z)d;f za$N#DESZsdA=%Wa=>bTt7T`~r+1(@b$N6>&onrx9P#E5U&<47k*WeFHIW-o!2J33N3wn9Xe8pLg4|@DXgxCHP;{DP5#F?#)*;a%erNh(n z!MNvZEMbs}LiqVD9N^tuJ;BTZ3c{aMD%{xmlUC|RKxnOM@))X^BY)Yf42KqtG}VBq zB>$U{R%x->in!KGRsti+#|9I$Lwr=HKdg(SvT(R z!p#{y3+x(4&yXwuv9J>bt1_D&U07n^A>Qy{-*bmn{Q%gA5=*|gMXJaNkA!IpDU4eh z5B2505HyzxdGSi==70P$e8?h$G2l$AF8O2&6+^a(DSJU7yyir)mvD+q{8yU5r^4yn zB8R({D3v+ADjVh(4eFLO|I8#vVPPYJg7e}$JfgrINsBVe;njf^Z0-H-&pkZr39(kT z=aV|Siqp#F2L5m#u8aCa}TrlgF09y zWpHitL$(SWFMlD^?iXULLyPc*a_Uef5Cl}j$O*Uh`Ey~9cYpW20dA4B};SMI}+KX z@+S6EDlomhO2ZbG1G~iMg0LW~Rwk*N*87(sK!cD+Dt|CIgtAm6Q;RD!@iDS<(1KM{ zKN~rymtAj)x}*BHeib!=e`qb*=f@`Lof_g>6{#}bCR5`Ajv3{h6gL?&uLPaAl+1<2G7Mt$@PQOr7ER3;oQp%m;cb>EaUu=;*5?uxo zGo_DfBY#Elu{Z4m$BTp+Q^8m~ASCpJf9<0>{IYx#(G9~5yJt(y`n?ds9qU9AdNYh& zX)Vp&kT?&*5SPO*ertKWpNT}N?Kr_=xISEDbu0j1t0Iq9jrPUpgEH=)TvY=feLoKo z^==Q^w<00Hy6#a8Uj-sNs^%+NW|ys}=Ze!#1AmDSjBk!mcpSy`+GkBe8O0%ar{QAt z2lt|(7DgI)bXqObS+%&^vb9=`XZQvro5@cKQ_~_UzIqRY;J=PS^g?ir@NDTJy9E#7 zZ2)?8Ztx3|%P8kZJ0rY;j&w@)TS%Fc5!K9D*0VTapMhJ6CG82f>2->s3+rn!K2XIyKQ0V_9%VKAbj+% zcCnOEYi-fEnbO6K{o0(}7;8Sd8oy|ry}V=6_KA^02E_Rp{>s~#gG~iHHQ$Le(1#+h z(Jg=7;lK%6he_vF0lT8dG`uK{eZQ;}cV5bv@0sYU2vqII{_ClxH z6McRw56vHoYTAI~F+FatD^D8NH&kIWC%AmvB^0s53S!FQdt9`B@HDpCz%qJDu6m`a zikB(A!-$0kb0QPg^P!JPEOseMKiNT(1oAExhTSE*UF{Yh>`}cce_I9m*QGTXlYg)j zHX&>m#j290OdYi1Qr{X2e->8so+UqTe!B5b?+;du{hj6BWbGM<`}2f8<}g)rk3rVd zZL2B(6&K=eCMj0gC7tzXccV?s9<6&x-ll@pMUAKH-bq1|aU-Q~cf|AYC|ww>#dG*b#$NlSfKt4DajjPb2@nY7`*52PEB+Yz~vs)$$*2 zB}`(GY`=yMmox!EkY*VolHr#OcLOg&iwEiY17-b0yo^wW<72RV?gUJUrlgp)X1Y=L6T$O`E8OQMjuUmLqY4+B}JSp>Qip7Q)Vi zJPG5Q*qw!qR`syLj+e9D0WD$RmEK`o#@57d9s+s?7ZzHxjHuVmWu2@kep#91-p#g8 zBth6BWS6GQi7ZxVTdlED)ygUfx8*_0T?KpV1zdc_eo&~07sP&*?0?2r8PSiYhQ8(S zD}!66C5WvkEAV2o@?~*hOP)v|@|izv-tYaewHl=-Hh)TW6z`7KI5!myJ$qjfQ(t)# zv^>JB#`Ad{{k_iGu8|rHs&P^W7u8+I^jHTY$k`YMMD6BCxatL8UWG84+ZV#oC1;61 zkHfOXAu%#_L6ZN45q~A6q?FF+r2ldbn!!;z7Knk5AwoobRCDet?zsu4Fgi4sd8tQ% z)qnF6a`m$!c;zqHb0Ff^m;HJ1D#ov{b%VPkgfV>`_rlwZz|8oSZp-mDWhtS4LN~sx z?W9tv5KTqkMV*1Ni(NQ zr66wJ4w%X~>!N(6cr9{>E1oXIF21(=q#`q+{o0sY&%G4E`y4srV9$j`^&xEe>_~wt zhg+>aHu@soA21IXd_1JqSM|#rPwx-GJ8oX;tYo$JaMGj*eS;*;6%YM&ps0iWZQO$5 zUFU4Vf~J$Irhhbp(m_Ytf#zNNaHAC_>n!1*>(JxQB%S-oWY@SDUuFoZqAaHPkc6Vt z)s+6tmrz*eifJ5qrMVpGIt69ydb!sf&Dh{YYwx}10nTP;HH8zkMvPT?!RjI< z!!H}F`uKq&Gc=(D%GAXYcguMnf?&rIz?1*@6^fED5|IDtyVUsGZ8Es># zQR=(2aDSRa1+SDrFDOkKjLh#H&@;I^e;Q@`-W+Ee5LrZ(mXE?;(qwOxFDoYai}z&N z0zG;I^<^Aqk4RuD&wBiU%Eo>*AtltPP`o(1M6r$OhlW)>5rqSOZAG<#FFC9V|9iT} z;wM7ku?01_Y6`z7_>$On9%z;$MNQ91M{g`>Dz8=>`rU@Wnl+PMvd0v? z-T+;WwRi7PA^^2Q?N621L4$1oIfZ}Ci$54@@Tna<$RrQEB-brd5jDE=31KO(osS39 znb^x~Dig*f{*A}bxOx2nxItoKa|dnI60a&zC1;UwhY!3TP@Y?%0pvJrd4`R{^datR zzkdM|x%24+Q7FJ{RsKM)t7$h#DH+(EP?&8EdW}o46EB1YG2frXz{w9wXMc{PP+|)V zOn0cVzKzQ*iq_A@8Z4zsoI^wxy>aXd40+RDe$G!|!T!t^FXA$beCM#%d(ag`YVP-% z1#Q5%|44w5;pOAi=4IkrF}R=cA-m}M@_)y}zHF`mFR>H26lt~x7V4#vHhWZyu-x(r zLqOVj%U}M8-L8=8Dd-JHk&?6qw}~BI%kY^-?rz9f1PiG|UgEQa?k|<37J^Agg1xRf2o38FdfpPev%%pxuC&L_B zF5GPM$baFcC$ZLbWV4k2`!~xkP^Wn+EeNI~K4~kJqs`tdl-D3-g4vL>5}^Hn<+<2dbW$ zqo#~mTQA$mI4L25?;Vj;x_{TCQXwOdt#mM&b~5S%Z2V0!hO?{ixkb!Zc}%!T6PZ8C z^qYZnhmnIqcYGrKzg&isALXVJ4b)lsnr2TlqQ5yt05m?7+y+0P73dv~)0qIPEtT|P(Ckfn zVv3v3?F%?{?eoakaet!*N2>%A-th_`xZ8~(ogly}BKxw}`zBVek|_SC$~q zKsxP+lO+9B>o~n*QYpZnQI3B!3oQKW@C!&5R@Ta+7hP zpWG&>Veb2Fb9LmUeDPryL?NkM3u=ii45ql3PKcwtAEX@D2t!9=e0ulAlXCHGWL{b5PK4&G23-l|+ng}3|j$xO55r+CUtId5YeEin1o}+!$$`DH}vTzG+-e2G=CuH;p?7r_mnzFSORKD;@K(+d4h}Z zUYFiua!tCu;ZKZ}U~z~<(i~pESs8jG&76m4PUM$v-cB&5rr-S;@z`s3z8{N|Lldr8@v9sLC1aO7)jBzScca|9nSA}bYnuN857`W6 z&|M~O&K<7Jcdh+f4M>EH1RwO-_v)gL0)J-PMFfH2RqZfG{f=5T^fzHPL_>pA>q=+` z=dh&9*XBV*GcNR$Fkfu>kc`}rCMd>t;s=U9V?qjnT)}LS;b&oACMMoPc@_VQBI}2O zTIt%58d>s}Ese=k!oU%YbsdM8 zb|agdEhv^#{ZrQ9t;R=M<(AJ|8@awT=MusVniuL2WhGo)c)@c^hJ%`J_SdTjtu(vr3!hcY*SUt19 zv@2ZYYceiPguJ-k!Cj|%Pbhzq@5fS)k<)a)t>*f%`Eam`Ta4L zn-hqo%&}I0cOQMEOnQdX?0>6?aO~U7l*TXJ5b5>pS#19!QaS1WlhqNXT~{n7H2Zw) zwcdSj>mDs0s+g*!`s9Mw0Z;>osd}h4G}2lU#S2GjXF1U zknbl4X3B3#_OZO6;+4r+eb#t*BK^~!YD-YDeMxIt{lS?hXPtmBIe$K0=nMfty%amK z(V^ICgBMj_h~^nMaK|xmDie`smDxjE_<~}E#+ds0QoJ7Elkxi1BpjolKH39`Zw^;< z|E8W#RMHVxJFoWmPM-tYxx8QT0dugL)mQm`(C=0M9zwyrSJn?zRUssc#9_RqK}Rk_ zvh`UX)x-vAWMAg%4}a^=ckd*f=DUwg{3qg)d1z|Jt~5E^n7|(;R^kt(&km}8IV{qN zDeGivfXM6i2mPYzizBS* zDH{a$VS1yh2!BX_%BSOJ^r_yD%Gox!>8iQzg2@~=o#=HWRnElpfI54wkCwmlE!k6@ ze~T9C#FW&BWw9|Vy>mGTt3X%I`{@3N`L3iFbXxN^{&OGPM+1mE598$ z5~^9kz?ZX?Q<#>=NAre4Ub@wYR7-z92hs#63wU|jI-0yQb!!A4uug%JexK;bFl|K| zJqK<>pXr0GPqwe%ZTI))Yj&*fAn_T<7%)5h-F50JHx_tIsSo?k<)hani7tDeb0RTj1Dkvc|2pX z;+PilbToCf%HQu}su`L#F#{NAa7(ii^OtYdOU^Bl3qNV> zx7sxfs(nqc3%Q4E-n??w`AYfTc5wKo-hT~Il{dMf#Kngx@LqHlo{8of!uiBSoRKzu z9=Bo6-k*uOt(p@=+l&3RsX++pFPF+`l3jNMvkRtSV1X;6K55a%%u z@^x6(Tv~lwKq7D%r>Hw`q4t?t6iW=i$1;uti*72rusPox4iOSjSb#hirhWIy{(n5A zabC(1(mzj$e_fN#h6aU`eTeR_Qi!vh=NbfNJc z!wK^%yHg8I%wg(Q-5JPPpG@6t27gXd!l5nOFm&oQwJnRE$EcNFpiyU%BFp}2x8ppA za-|eeZ)Edk$y$(prHaq9HAclmDAf)E#+;yQu5EB|Kw+X+P{V z-jcQSJm6S?G$)bieG&8Pf8SG4!K+)!IvCL{1=7h>aFXI?wE-l{VTsWl>wooso(0`{ z)6=@COZ%KoOh9*_Vd=}F(q(r-Mp<~A<{ev&T=0dHuj7~E21?oW?YPa^?`hl&$U{1n zp-DkCYGPlSCZI;1Oj_!E?yf=PkZ~>@Ux(TLz-upP?8L_Ab%&(nW7;YG_7Rl?XeD1RY+XJdu{OCRpw zZ-@#0Dgw*M!{ZU`8w+vGV;vgQXMaQEI%ATaw-_AaLoln?-%h0kCWiv!{%~8c-Vua; zqHcFw&&77_2ftQKDxERf&kJi+^55{>fqRZ|&U=NutqzJzD!kx&8OF3Hn*mar7GwBQ z;sr-=RGplCMS~d^@zv6VPA{tBuYN$M}*VaBx>;1Y4`dS$g2)ESu!az=JFHHD;WJt3g-uTMu50$%LauCFoArV%sO`P|G!E|%I&OeYd)TQ zRn8i%l!9arn90p_6npZ9zULcdr+hQdHtm=X%Bx9?RXk~BjBJ*X-HmlG%Njj&X5FQ7 z^^}THNFTZhPf*)JWr?O(LXTssjF1q^X z3q{}8Oa?7py;Xal1!nz5idCVC)f+j)bAw#Yfbi?*n}ZZr@^(Qs7i}6FWw_jN0I|$( zFRh!({(q0{D;%_j`B$b_mMnh{%rM{I%}WQ7kY_mao*zipMK>=<&3j0R3&o#Q5NA_) zkBg1wy4&}s*BybX_4fB|g~*D@sxjN%ZN4(s;Z|7!z3r-!-~oT0{T@2|VH&}K93^#I zcv7YUg9(n+2whI9(Ms>sLty(bj4a; z1ao#~>9`(lKQg(9FUzeXeQ^^aeEoFYN##*^VEaj!TcAFq*nHDfTdG5TWLVJoZLsP^ z^<0Rozo)uZlW@@*144Fiu2ynqTME6-5uTFf6&V`r^AVvMozwTUfA`6B&@dPpp-hD$<{N zKia(UbelO6*qs>I1j{`O%;2x0JN{UGEY?aKlC54WBW1#@i>}2l7G0>2rjZ& zo=lo1^vTVm$8dCdB#nZ98DKKT%mSsAB6D@{HPUDo5EWy#JCxx{O>Eu?>0|PkO#WPy zq3rb59$yMYYlBTN=lAsc`N?Y9jjaaJ+;ec2bL3&d>57U|< zDKQ%R^SN^AJ*_loOHTF}!Tabce*{n_1wuJCJ7Uy09#tkfaWD53A}aubIgEH}J95$C z9MaNl!IVnXI}TD5O57PcQL~cj)1!KFg-V#HY8V5GK@_juSQsFd`G2C#+VxyAJiw;p zGU6=CZJ7wmv=d}T42c_fheWQvhAq%*hWmrz3W7~!(bc1r;;85*9mD4F`)vQWh4Ah1*HGmQH!op z1UE$>#>lS1!?d$YJAVW-nd`iJ@#w@d1-js>G%gR{Wr=Y%+9%Ha6+$cwFO#cLoJV7$ z5BaOM>xy4C%&vP>R-hl{^&$q0W6V^vq6|GB(#7cG2tt{m2A)K|K%Pn{hox3n`skR( zSqod+mX1lZhW;2*FvKS)e~sWJ*@i2bg! z8j{732x{Vm?O}i6F?$Lq+nlW6&|kyRv^tAShmu^VY%nxQE02`nq1u4kOg{kn|NQAg z2yWqv?%>z?w0}R>Ur0P^fpYzar@7UeGg&@WBHokT1NuoDCy)eMjJPTxB9vCExT!;> zX=*w5F?Oc*Jk>1tflx)&d!5kGCzl48Z9OZ_l?_fH#4=L%MXW@5V4`nRU-VP5p}2BT zSfAKNSJ#Rki}O*_mA*)&U291-KXHy5ekh1xTV$VXHGdmH@-QPqIgA)Egm*+7ty*iO zgPh7c#=-`A$Se<#B02ZGv<+D>!(pr^P$OnO7I%+_kYWKnu>h+Nh|)oc#ENJZcykPVG;-Nd2$`5pdw7zJiE-o4Od=ju9K$c62TD+d}+r_ zWEe#!K7UG?k2rmij(}{@gK;eX`zCEj zwu)YR^-)@uj)4EyUR424YW9_n?)EgzW2W?Q(Xa&OXfQK-Xy4CD2XL|+hX~Fbdzn51+Cm^KAH!;1k$DK0Q4sXg}Q{QCqDuSVZw2)`)))|FL zG2bkRH*X=J{aQBHU0k7V^Bn#8mcnN@a-Q_(tzotoXB4qIUm*3N^Yak&#}_JviGLhL zubGyjdMY9sa)75FHjFK=yWHuuxCCqvg|l0P^eVZ^T6sj zD;&+H8`TM07a*1grhQKoKIcNu&{Ux7C1(iF$$z|F(7ht- zB_D#N$D(7x=GM_4{lUYS<2k~8qq$Uhss};D7L|?WCr1RYlV2@pFX9&E}zbcr&nDyyqa zgm%1rXBePHuohEZ;OjY4Uua(zrggF~8QB|#X0)a$?!9G&`mOVsOOVL9q8Ta1OW+v# z)Je7N8h7OEjF13T&kH!`k6kLJ_8z*=;dPuvph%*Lkf00{z4^NwFMpfUNU~aJ9~=}4 zUM7Ojyyx#QQrTm2c22Ufzlygi&3jdA-&>(v!QwZvmgMbB=gyD3Mw^aU_t?Mn9Uz^K zVXwihQ7T$swOL;>vmFYuX{5s=CFV>RV7PA&6NRcxO==Em)xT4M<|u2SRVQp|H;}67 zg^G|ZVY|jmQK>~4NPlfE8;4G5Mlw(Zz!&>gy{WKQe07!W9d<;ZOd3#7xTV|hS4@gZ zf;l~}XM;Gy+A++Z_eD9uHEbCp3Ve0u2oO{>Y!d`P2On+?tP#2yd&68^AfjY4w zB)pDo7TdUL)$6+@=)d`g41W};tkO9}U#cy4fDuX~9o076m;Yf zS7$VP{wAjvWPbx{>JgcxNME^K{Qhl&XKA8)#N{DsVQwE$fE_=yX#Ye)OEQVV_hw-z zPn<4^iHQge@%kb?xJq5SXQ__fT-i^F*`z?$&ps{-tm?J|7lPkNbF;V~dWv29E8>if zcs4}!E(8|!1#~YVb9X_d??)||Vo~iJrkjg^BkduBdw-%22MnLu2dt7Jm83w}fx9-0 zE-cutBy2z~yO}d=NF~nLbFLzuQ6`xN=y7RRf5+Jl;oro0_|amY`W0eXih{Le-=C1H(_v~MyCC;%WY%jBxaNIC_*=_7M|NCOnfrIZ9 z8npP_N`DxfM|Q<0xVWUg{?mNxpF9r{P@_Ml=Zw_6v>UBVIE zPimu1ZRdjACN$Kjw}K!l&S8=6Kkoq7eSc;WFnjUtbx?;0vU~A97#?NQLRw@8*+3a%fo2vdHXkm2|emn=fUNNY*S9E-)_l zM0OsR2oD@P48zhV?Il^#PfO-7jPAmEP0?Paa?@I}gMOeOIxqAo$gPjZ&&MbIs~v(v zw|`?%ac7`?tplxbm7UtMf$(L@USzK`c{lB%+lfve;C^ipB5!1XU2(9hz{^O;bwc9& zqGwXBwpV-d2O*ndM+#QhcBNN_{YFi83Fy61;`{2yf&~*5rUfIpJCiFz#Q`=v)9ofB zJv@;IxFfIAhAyVwgH_LL*;?g2E|U1mP} z(#HE8SIQq+8_h`h++#xc9h3}naQS*0UNFT|7RE^_&DJt=A=TC=ufP()M}X$sHr_}m zuV2@#*f)RrZC~X}Eu0BfQY*J~M_D$@exrHj_*ib5Ea(Sn=ww29uY)aQZhuxaSxp}v z$H!DEy<(}iSx0{d2ieBG!aRod7ygZQBXv1Myxxc2o!@|{_2wi`5G3sCu9*oaJb`rK zzP6wgoz@bUl73IzXkZ3785ZB()9m@@+w4$Uaq}*$Af`OQCcW@&;sG4==NoZ2%v7aR z+u_%b;)sLkSCp=`+o<611y-z?1MO_r5ihfEG%i8f!`yZ5}WsHzR3vGZcZ&0@u1M3FYQQ76u+_#mh=&=kv!nZ= zhhmanQ(^1=N`^omi7RP`Y3gCNSj=Gn$Tmn=nRzL)X71F}=m7 zM`xbVbMHC7pJ!|WeScXCG?j=(pV~9v`O1H2HK16elAQeNm695hMxpl}{8UT*dvMu@ zX$n)HiYk%YXKbn3Cp;VKROG#Wml5M4X5Q#K5!>~oj9R0GV#Mh(1-t14^`l0&Blo0v zeAx-zZT1}PoIp6HS(#n-?`Rw++h)T*V?ftXOuFU;6>+?PKYxXBhY#-J5i5M1#UznF`#Qh13ti za0Xf!sbziuu)ET<@9iVlsTI_Z2_E~}_RS=5E%)|`a$jZfBc=qDYu0DD6U`{5)QA1c zqdfrlM(annN~yoq6p_+jq+h~sXQ`)(k#bweFLHNfAf|EJ&M;Z|)j)&g#`Ot;wHgWe zpinzMtE0`zF|UwQ2P8aM}Q1HrG$K*3V0C(B)oz_L{?{Pn_#Ud+s4@@3NnF@ zJ;%J599WTaRg(-P>*S*VJ;mc`Vz_jm#?5Xd{G*srHbe#L!+MC<&1UMIIf4HD$gUV#}yF40p_K{`iLDd=xTV*b1l`&Pv zDVx#{dq(CJdXOZ^8Y`@%;|E`~ARyA5o2_}$3Z1$4_IEBE)*C{q*OgM;emlUBs?LZB zkUUdma}_?km%SFZY*Vemhj1OiHUVW|s%rA04HPv3O%u_T3TJ++=7`Xh_ylgoExC{c z0A7qlPS;pZ@eb>`rahuaPp*(}=*CVIYk^Y6ADjt%?M=?8|5P<}mddk9v4O*L-e-?M zbCsL_9*#b)wYkpSm&o9W5RtzStW)`UvCtg;Krj=56ed0}U^49sLhI9})JXTP+=Ke! z=V==d)fq^x?TdfU2140uyzcUT6JkE%9{|()>Glx@iF=*aVBk_ zMQi911&4cm)?%k(pe&4~8E@CVZ&-h+RG#n68%V3*W$na#vEkObe&TktVWi*#@PPtE znBaDld|-vy;bhQm3*&q6!*>6S>-SKD3p;4D>cd%f8VEGVJ$dnXFlJeB(!Gx7h+pbj-QwCPah!~DH$j(#OOYeKx9B>3A|G#85Wjc>ql}UwQ+c3qskP%0-QX zE{P+L1s{3fttN_`*7=J7fN*s)7|aY<8~dAW)dD6ityq=B6IQ&TfY?qFsu)fukCUcO z4<~sYS{wYCpk>{`Smp#4&Suo)nhyTxxJ#BYlMAyQLUb4yfs!@OkImoW=k-@Xuyxi% zL(c+1SiSe1Xc1-R_o@g-0-LDH3j>h{svdII*5O~Lh9eE>%4|evm&X42 z)`h2;Ov5w1cJuiOV1vQe;`K1C2k+NpowGcYeZw!%-xgDg-3e^6afW;k4-84`E0^j; zy6ZsXQ;B*TDj-%ppd=k%#Q zbk~u2)*_nOzTe7yEzCV2TU~>3Gw)3|En=*IbzRpeBmFo7Z1(_9e8?0#(7xX!q~?6B z243EhDd&0^3lGZjODZN_p<%!Y#RJv-9j^G0%D0RmoNMBw(;Cs4y__*}(V~1C&%2bI zd}2Unz0J1ojF$W-i7(~)Cx~ByOJ5~Zxt0efM+$wW>?S0qtz(mZX!pRB+~sLlcNR6h z2JYez0Y`@vFa#miQ4hkf&<&#HTU|GscKyL;Jj@)EhH)nOa)A4Jt6?;o7Pfg_t65wk z#lWmN6CvAr%sqNQO`KgBy@~Z4nt^VL+&}tLDx2Zq`>?zqKkE+cw{UUN`3t2e{oXg_A zD3@6Da{9DenAj6nvZutR`bpCoCuH9xH+|@7>ykz`Vfn`l7uW7n@rX6CH}1<|=UzoS zlNkuF_aO~dbaas~(Yj+|#C0p2to2YjN2#~JLMS%_PZn}EW7-8iR`PN%t5~UTQs*7wyk#!E&Eca!t@)Yc*u_a zSuFtGyVUTc()F;JF~(`XI=aOGIPPrDfr3&Rxasp>CC-gKPkv7D)H=MQM6b1cHJNs@r`_kbQ^FM;0XUDZcuP^(~uujEntW0dJ}QT3@>z_ zv!;{Vj@tz}O|fb%4w_t|HW2`O+Jq`|Jnnbc*~))DZM(LN5JM(`+cr`Z3h$PM5IKJA z-mVjowUe{V0J1~g9&`U;hT_^{T_22%xS>&H>%4M4J14PodlX#C4(&nMtw@-1ZJp8u zXx>45fBdqBe_b#MqBs=el`w=z>`Hz<PQB$Im$~jz#-}{?~%RkM?2l*RevF=%bV+1#YLWv=G!W4G~@kslsf)Z)*rRv_F@tL>nsb10Nu0fM(4cxi1wf`&{BsMU+e z%cMp2u5~tIM$t-9R+vI+rzLhvk9d!wC2i{$2 zu3W5i_(JfZQwJ`DZFs?o&~QNkuvpU>Qbm>3d{G<9iG`_xXd1jV( z&29cg+}_N$a;Vb~wM}|Uth9i6GEb1*?*OEiGc!7ohn2F^AQPuC;JKGT%1yv5)i^>- zp`2_E2xGut&>dd!dt&WV|8Nlr-iyRe+xRlD{k}$UjgXD%Z4jU0r-wlVNa;3SO*<2B zRj*)%Neq0~kSx{TkrDpbvTE2OIX51%Duj#!$j5L6X5r`IuKL6w!0{p0ztt#k?K@vH zq%d_45e0D-Ex+zW8Ic(6>_k3VbUTYWwo@sSJ$KCIy?S%vniN~IeN#7F#A-1*Dr8I&( z{P89+a&YiOeCc}L3fb;3Q5y0gLPhJ5Drlr&O+_h#yQPx9TAe zenKH-J7RVq%xM8~g;i1#`Uc$Ypk6mZ$Nu|Q&(d0GG<>Gb#@4p%5A0tB=cK7;L84m! zEKB7=_j7%xCrwWQkg9w^E=6zhk^8e4$rlC)C2pCQU$AXcVf&aN>$8aI(}cn_q{k3>_sr1yL>l zi3iH`)W{;mF;iyi*HzTtcp#c%xc@Bu_!*(S7LpZdP3D*Ydk($5!@~v8!+&Hx6M%B4 zEY^Jpd>Co*Kf*dtvC}AQU{aq#B23mHDDyTaI7$ndK)St9_4M&`VUSTlLpD>>m6FW#l_7 z^nl3$#QX)U7}8mDfy1M#IdMUgM;nU4fCj{@wpI+ZRjcN4W?nxaoT3E`a}-1N!6ak} zUpj#txwn{J`8@r=tK86KqZ<8GImR?e!$=s$%^N;BH(=C~Y2)GS`s+4WyurN8i#e|j zO^tP07GnNfp&pWdwPG+&3~c`DLV>0DrfiY`RE1d{;oSV)k*(nO!m$+W6w0ccB~^#e zgtCCh6|bld+s-9V4(7zao2T0-9JEKsw|u3#h;a)$VT<#QYM$l`jZ94SuYwLbwgA^R zfKgjsIEZbgQXHWvf|gr)om=<^XLg9os;8v50e@ovN}lZe^re>PEYm%han%l5;QMq3 zU_Q9WHSK;|ueZ-4PF6dpRhz}f3%ox*qAF%CNbvn52y-}sgCn2!X(E<68lxGo*rBHe zZO-g7!^mtBqtS*@Q6k^Dzg8s|1-5n}L^2t^TSKkgem|sz^B6mWyDZpTRoMQH$FKn> zO(TNX1U@mz{M+rM{CMeB!_4yt?}T~7p2BLNkV}<%A;fI~S@qBDU3db?NE6V7Nnaul3{e(?3IMPXf$1N| zSE=FxZQ$wfW2SV0_bL?PVUw8C>1ftLLYaOti-1AG(wvh*GZl|4%w1_u%nY&^_Te_m zILsW29+w2%R54!=pzBxb)FFkr_fPM_KYMXaXvxz*eEke)${(MvNo|==a zlwiG;pE}*=&+{&kM&ZG@$k`yr@@&wE^{IKyhyHpZLw?M)<|(=q@M6DKXI}AokAcC0 zd`d?xzt^~QsuD&OLZtia7JlrrTSjK6;_kjBp&t=}eL>GV@bVeFEC69~vRl{T3llLN zBMI&68iFmm;F0SNJRnL5P!gW{EKX1}3jKFs@OtNOP7Yr=qo4gV3vM&Z&wZ`D=T~K4|Hm6PjDCBfcqBC z{DnDz1S^@gk+&AKKm=WNcs61SG9BxcBAlaJMn)~Pd=dvaxsFwWZ{2O@{Dh-Y1uLAO zOdlzOjwr!NrLs^RPoAn|%G!hbm7mJ|FL&z+gnz`3!|PK3LP+#)jp%%ARhb5cFLL1N z8tDfre<}D7I}F||;4KhTeVhuAgVv?BNuAHB*YbV#qjLSiXNSgtu@LM#@kHS0tvNA` z2=?13bpOK=vq$!qLtBfz(A^!@`{j>Hq&=7U@RNw_uZcfeGvQ6N=%f~8dQD5Ls+Z&AzoR54R|T31agq9yxWz!QOp0Np-QhT{^hqD{O5H)wU> ze!$9B`wU_vHiD!ME?eAo<;S<&_Y*xvT+4FFauPPnk)i#6q&mzDX}XeD(=o?I*6T<9 zNs1>pIQ@p7i7E-Rb7?plcxsj|q=I~#@M<30Ux4SOHRp>3s*#z+C=$=)i8w{>&z9hL zH+zO=vUYBf19akjIiZ5O={wg&NOg7hV5hh21lXtS09^egZ#w%j&mUiaT;q?Yaej4K2KkIQeb}_!BX8Hcar7P1$=kOnEr~ShM~-f?b<_YAE6?d zb9J(t+4f}#GXCR+z4bx#@?vHozb~3L;C4#jGYN-|`*J8cKx-P5(-uxHht|Juq=m{i zuZGjhC95&k>hW&daF*_8%?LZj&!kSmpN+)zYOoxbSWg4#5_BG^!HW=>NF5YZEeE;( z$(OSF2*^_U^zLg^rgPiPYAP`y}0ms$L>&G->8srq}{2bBuny6Sjgmh7uJ#)&Wtc>8b*3QfT#T@muY0oC=F zmMKXB-Qc2@K`G}IzJ50j!|p=LC_c)x|Jim416;jy+5)8jJhQ*%R^ zjR{3!kG*sJi`X-~%<4Zq=PY~q2mAD#+=)umWfrxPJ{VZnZA*!ag=h1@wxDamL_NMw zH2c)Wd;NZTXSQ=S$KJ6gJkcI<1j1S>jsQ=qp}N;#)%>31oYt=`>D@wPA}{g-M1m9Q z`TQJ}f{n%F#oV?K{4!Gy6$0|DxZ#J$#q13KR%%;BUeX04lfTPLupi>^D&3gi`?J(6 zxpiY4EmG8-bEZOkU6+#hP38M~{yBI@1uBu7Y3We$5Cgq;_(7Hh9|)uc1+H@vk$@b_ z-`PCR2p?n?Amsmjl3jPs*>a5YGxJnS;WdePkPY7op3YK5J`1`I7fx}g3^CIBAdolW z@YREDBjJD2)d7m4+39Dp(v;yC>y?bZxbLRG_kh8ls<#6mKhQxt4oG3U%Bu!OI0O0Tn;w@Z*C2y{Y`TgI37jWzvHo+)LyMICWTB~{( z$G5boP8*58L?r9_Y})8Ev-j=Ro_r)0JIh`-GF%bJhGPz@7ujlUoUK&?4?0ZI`wIXQ zt&LpC?4_}W=m>dj${8HLx?K|K*}zb0>mP>AhdwElEVpL$G__9bg=R`<0Wa>)1#HTa zol~C?CGSQU@O>_feB}tVBTjgY3hS{))pZ5sa-|!n$s}dM-@G1w*uF$v6jG)19-s*Fu<21fYb?V6aXoj*?qngBX?ZUtXGq}hl)*Yt{ax$ zBItthx&E8%7K#i-W(*TUW0<_JK`m|vP|zNooN&(cnd{f>UL+&dQ@Mig4x|J-fXfO#754-T058h2C{1Pr_oFb( zyVt~ux>_X!cn|j~ZyXs|K_Q;8_|6r=00({Y_%qR3lc9%#$8VxRHK~jOI{0|7H){U5 zQ-V)vPo4-wV)vhfOJu{VPl!=23?QkKR0)sYf>?;eb0u?7mX0@6HVpl z598lu=aWICBM9KH7R$%CF3U8?`x@`{i@|>`mdiBa#+MgYYr{F2x>lvM!`G#Xzx!HO zv86}vATX^M2??$+zD8JbIZe|)>~|bdFd$OD_{14DT|6nJ00Qo>g5&38T&}IZ;dG3D zj904y1s;wAKv~d?n*(n^f7)K&*uFgN8G23RhKqXAWF&iZsiEHDWDTCmkzLF18MBD# zP_3N8l9!3946r60R7*x+N)k^~yH@EG1C>DgW{|kw9LHvW4b-z87m6wySB?iy9y2%F z?HydW#xH*Oo2ukM1z@w2Dn81meMn2rnJI?j)h5*!FP#p0xp?nr_f0eOq9wd)h##?c zRBGAEFhVm@q5L^i?1ADI#-IGWj~WXzIUF?E3Xd$-Hb;=_c1qx5^dy|JAP z_1#+Dz`q=BI(FC};tqiIXf-LAu?jGPSVuNox2CkwZE-^W6iH=K$)jqP!wt;IU%cM@q$ zbLOA_A0yTketo<;A?cd5h2B8Pbv_M9e7QVm4ldh;iG{^Jztq@E_)OLj!**UVv%dDt z!@}uUb_G(zWJ(nSLQd&luIKdm)J_GLYt7VsO@h$Y`&wA?!v#}bDEI98n0cP%lQeIP zo=}gfmi?B2&&ycju^I|1?C_td&RsYgK#kTP08Dplq=|b4l_GDi@#%q3Sl^$nzcRMdJ%ZCb`v;bc|*s&(d!g|-Qj_I^4Z?%oeC*#~bdWux&vhW0K8JeYL z+SEL|Q(hHu?yRt2l9M}+VC!j#lY9qx`hLfpQc)o_vu1!|L zDj$E=PjAg6x_24;11zA`Kg>5SPqgClhGxrP5h6S4gQcl^KI$(7vePxPjVPT!5+r86 zkIKiu<~QLcdxvyY1Y(b?%ia;s2FHL zge_&qdr0%N+phRK|5qulDD3PFvkZ=NaGLlEsTw9ey`J|TuUges!J0+M;M3ltiRj7U z!rTB)Xftj}l(k>T*YEEm7z7thC}6jy59VtCd_9u?e6>!{@nQdHmCVR6E}2CZntc=6 zw>*<|GEo4VWfS#cq2^lE4GgRcRs1e{e_Z53N9U2OgXV6uD{2yc9Ih6oET8~^zR^b^ zZ1idQ6{QV!vm?y9pvio4$RoVAXdPUV5bwOV@mH13=myvBq&~}I#jOv(fgO>2|I?4LXbdS*LW0#HZVN*#QGI9mV?snP1#a>x(NW)IG3YE!5APB%bW zDg;Nna8u^&MJ7D5=jyU47EtZENwt2U;>>`7tH##Q_4)@7`Et&=&w0Q~W)-}=Nlv-v zhRm&fo_U4J?U-KtpZcOV$YLej47kY-7bv)0Ds;%c20E;NuCh+A108nnWgO}mU$G+- zmcu=RPJ^A?aXL+(e()Kz)G-%!bFB~34<<|Az?q4{VCO4rx}H}Y79d00b@Sw5ViipT zVR?Il!S9E*#}((e;P%nQX)i9D!`2IGC!=(B3;);EZzl;5P@xZZUKVyaTA_ozrQ*<9 z%P7y8y5a7%9=P_K9?#R;Vp$V5iU<}NMG7yt@^)pd6SCDNnqBY062zqE)i!ZV80F&L z#dbiBj`g8-nC^>D8vq{I+Sz3GFQmZf&za!pr}IHl)=f6NJbsfNMF_{&YNp$*8lOtS zLTRf1ip9&_=Y{1H!ZzyPe$OtYjAt4Td@I(`ZCL)@&cPfL@Z#QddoFwwUM#XC#&${J zeu%Fxe4j@#jMOVr^0v8s^A&fh)_%9~nGi(P0F3a>8t|T;TdKJNp%obM_4hiy4EI~~h+zd05Ep3={ z;Y**RKzC~S7yt@&rs$it4PF3Byc%6OU!f5 zaxz>7>=p%QObctLUxC4P^q7Jg9SSl(dnWnDd87#@XWt!IVfw)ZGqG|6X?oK@KF1@h z7-IVt8u2-7HmCljaIK*fO`{3)>XgluzugB-RoGEiR$iyYmm_Wi{Z~t+K3}Pd;L+i8{kUcoHq?UItJpGKuD{UuJaOt1# zvG|d0NX$H1*kBvT)FAx^;UiOemoqLWbo;d;7oaKXoNbiBg>q#}a9>(#>_W~F?<#l+=BN>93^yNx32@#?T)^Z=v zh5I`j3(~oJs+i+Yaa}jNxkmTPCBy?n;K39r%mOow?0}cJ?Ie!~Ar;I0tujw0BMPfv z4)7D9-Gplmgq_038Z2r)uLiZm>uR(`s6N^7YU#is3M9nIO^{aj?_zW`|JK@5*(0#<617H%1R=_fTkrZw`wR;x{mtgSnsoiO zD3<_Ae>Y7yebMzBoz@pl1ChI03y*_&I3_L6oBaT%BTk~r2ZCCRjc`Kh6p)m4r;NEU zGWiNh7sVx1CFmMCZ(kNvhfy^m{FGbXPnD-5?NrzY57_4K(^4Foy49(P)$ZV=MDh5} zluvae8~b%ngPbcXN}a|+d+*2o^cM@)q;M|x#lN&WRWN{|!xdoR z<>F?+{CHE^OFR@1FZA1Ng6_jgm%mFm!o{Ct0WjtGaDEt3kB<=h42YsdHy1elXf3@A zmlC1{9NU)xL}|zoQz?h=lv&oWQhQ2W&|jMh;vXL|u*P6P+@)JA#6`U+{j0n9>v7Rq z9>NIE?79egiqbeV^mXzhr$*Bjpbn>QC(=7+FR?xALt&DUtb}l#-j!cN;gQ?>H*DVM z&{@Z@T5-U&d4z2@03@Ucz^UDa#vA`w3zRAJF5`?=d2_R4}5(T>(7_=|#nbtYZN^2nUd>zWuz#mG{}&qP`0+B z5#`$^vLb6n3m4b^$$pPh_(&^T*^&%_4_SRzW5QOR5<|)?2jmY7QiG8vlOIlZJ@Da> z6zV}gSghvu8bV1CHoE09E(0Ir z?z|*tcZRn(nj+o~R8|eMMG=0i&uNSNs}8Kiq=r*6o=F+KSM{{JTKwjRo;c)`TY@-Q z82*ZiH83w|b~W+XhQ<9D3lvO-1COlf zF^j6~oOgxzHMcgaF&UQ{ED1`K`l|sH6PP8{xB--wikXd#nVX)8jgpCpk{X6l&fY}K z(8ZL9N{okviG`Von}v({|4LF@8bIaPSm{|9IOv%f*q9htScs@pOf`sPE!|9s{##2; zWbI(+V&QCRNaSYf=TLiCg20K+J2YG>|ZLB!6? zmgp};4d~L@P{M0(@I9eDzs*WxQvLf28I`wxc-T1h)+3718CtL@AKsT^7LLuhv&YZ8 zM#Z(Vf@%|fGMvdOxoBLarjtr}c3D-qoTfx(uJlI?)71E&tXWE9OKa|0tc?CbtrnjX zmETOEDxofuZZ`2EgMCDEKx2xlKbPbrtxAE?2e6>|^{=oQy{iI+zNLF!4rVZKJ_1YI z$WljnP3og++i7qXmH!wkLy=nxGrQJ9I~;@CXiH4}HKYZ}g+8mje8(89k zHXz{8)SHzSTob2hE`HZBU*7NTe;w{7$0Ib$Sq*a`vEbW{T2YKow@N?Wt}K0BJXyvcKMQjm zCx4b)&SY(+ATG|07z^2_Wu#tD-g6jr?b}L^kVk5ms^FK#Qb%y(5%v{Lg2dn8Cdt(0 z6?=wb$oB>DM@rkHGdtCuOg+X51^RN_=Q0&Q;+a4u*+OA*SM_hs28`nCRX;7^ykoxU zH@o+$PB-{}<@gF!Et@MQv*AQm*gp(J%=6f1n%x->BZKBjZBT85QKM(w^rB z(MK}rt;_b#x;8BbrPYF#S#22f(Z2&^Xp5SgXtTAAndEs7m1t*U08W`8Q!=TlRVZ@>t#NqGb}Qd4w`DW4X;<7|8)3nL`-#TU>g)ig zVMV+2&%ch3#xHAYBys0^iwS#nB|1I+RO091;*2b1wHPojd6B#LP&G9nl@|rONI96+ zxLx&W(!+Yl(B5w9Jw_@H%GA|=1rP_JNeARCEH(I&Y64)c+lJvLB~@v)wp?Pk*+|b1 z34xLtGqh(nd(N$JLZ(f)Pb-$Hpk)(WO3w>ZB0kmDAtbrfRfZewUN{ATErX^g0cLDYRp)pzqk4`>VA0Og#2Sh`!~(W! z*4(=C9_SMC&4`}{JDZVMkwh}3?MFb!tRf${RLODNPJ#Ql(WC*iM6XTMd(dCgS&lyG zqZc+t1sDes-eg!d#qtMGFyTZ8r{tAq*xg$YgK?EO`PRmPJ9m0?M{uJs+)a1!;%lIq zfEoye4-$At%fM_%iNttTZo<4IWKYW28>`wE+n5*_X*lx|7;flJky*D<4HS{OlQP4x z4escqviwxEsKaMz#HzA)W?2M+Cq=@0HArc)!tew*o|s7HyaX7Z3x~-@CS)E>q;EQt zls6`dSW);fY6v=+FbE;YfngeP+aRZ9Km^Dt+KWo$=>Z%BrdL3vf{F9rGcw_MH^)Ym zR9;3$M9%_qis^nml#McF_S<}%On-&5=zyGRi;9- zxTbpsZsL>$u)SafyeC)mxTkeIed;}SV0-TiX2&Ksy7D0YW18jwv9aT&Byd(&z?(_e z4c0G;HClOFvX$*yx?FWxY`tW(hoP9sYus>nDJ*YkcpTj#x0=!9<=43#Y1nMT*c7X5 z)T}&*Jz#AZihd$E7|htR0*95jIDvYB!ol^??d08+dgd@#r-XZ3#2N5V*91Drtcu@^ z*T_X=reb(i%f`#**K`}`G#EcTZBZfM~k>5&Eh*Ag>6j3 zC1g|Nxv;vLVIu8>`)uQu#|ulF^rA)}-8&fp=iiYhD$JVUyGqY)Kdl8Qg%PK%VY+J@Ey9>G$H0ZVjTM@`(SNvYK;ucHbSCv~!wG};z-b!9quKtreA=na#L z5=Vpvfv_ap0C8VXhKH`2G%;m6e$7M!j0xPe*|}3XcrWYck!iACgS%~gJxbFKEfG-t z-Iv(gpC_jExpKX^up_xmr{*fAHhR{&s;W364sDd@*C#}ESc2cbwYtk@+mE=01dxzc z(1ulOXT%dkJCoOY57m~F0F4q(zz?QR0=6aLYHdl?td{KiuTfzUZiSABBXe8(Nh-l6 zAURx`RT6e6uPG!Hhp@=cEOLiTWRV5N*8Q#wk0dd;Au))$U|dCV{VLQtct`ko$v7oq z!fz~k`$rC_bVb|~v9^Ti(e=>r;`D3gVocMN3X#pH)IHi&sq9I_0LMsP&N&_Ki7;tI zdd(=|Zk3j-$o0*ArvMuA644qAemag7uCPT2T2Z?~`B78F^j%#|df%AqEk7u;c8RiI zwAMV0tJ>0+0@bteKkKK@{qDxkf5_-ZlAc%|D#fCd8)f@lfA=S+ikacqCIl3hY59is z531U!e+lC&Mp{r1ph`57S9t+@Ke!b(=)trTOxCOs$9BzlDY@~FNV6`D2AWESFb7=K z*tiUn?!$y8hM3np%St}?Xb$@Km^Lx7(5WcBKk_1o<(k{}ki3k+KyMLjnYTkKR4V;9 z3}w@~Zow)u4Xq%-neMxaj17t(yorq)mUmEQGD2KD{f1EsK-BP$!xwR@jpLJ(`_&s) zbkpz6nD2}F-Yy&PKZdmHG|@g)#hdgGUDieD;I!l`6xMC**PUVopVV7jaFqCj?b!`r zAx||+w2Dfj@mz~C)`dxfLv-U7XA>8`TKS~a4%FI_pwzK9wV-E6AfxcvrW~WXlzuaP zm?mvr12jRbfSEmwyw>=q8~v0JK1Q_HEm>UEqQ*4ql*-uzx2-#2t(tZhNRYD$59pLh z7(;7COHAKvhYB=n7CbC>sTUKn0-mXBjDMzbl}xecgsx7^zd-g{%P4keNuCA_NXjh1 z&^NQhYNSc$6*N&5f8F~2v3!T-M9l!z1aqwt%~Z@!0+2H7szY=OgU>YAJecZGr8LT} zRK#&hDU2vij$1{MxBBpk1??Q4CmKvQfX{*H?ZzDyQB=yr!in+m2+9{_f5~;VSeLsGUWpNN;&1WZg9*?N zaiFdS04w*mB@Zu;p2|b7tj9ibvW50zSEYFp#itv~+f6!kn3lKg}?sK(TY)Q@Rp) zwzhW^74W4$w{;c8gqSV3@t#Bd(eQk)aP2mR_M{h;9yn+6qm=?F>rzV*I&!gu5y>?w>LJ5+~4px1u~`Z+y5PXmq59o~g+F*Xmt z03*rfIGSiZSF*#AZF91Jn~d#w+%}Po3+tMm{jLut)CDiD1@a?^+L7tc6!}>` z;JfprQ5M4GbVX&SwCcx_`!zPEK;6$vM?v)$YpGy;hgL+3`>H z&0O{g7t#Srxg?LgwciztaYwp)fTU|I=Imiy>bKWM_xBlaV(XC$jiIPGcb~@7FX`ZI z6cD;s?1|N6n?j%m!|UhNo=&o{?W^d2dg3Xv2ln##;Qj>!c(jn2u3{`xOs@c~qHo53 zxs7k_a28A7@eMtK24ID+Qzw;)iDyQZWVR_%n$cpnjRRvxjxD$>cprsufRl-ja}YI` zkIN4auM|`%<}y6am!vHHoST2fmT^g#fF*$L6z0Of45h}bz$i}3#KhUoU|?ZfoHm+y zmBxkZXZ6?2ZfCKKO(Ceex%8Ua2iT2xIuT z$=etx%|j;|YL@2aP&}o%0gPBgLidjlQXH@wwLAQP_fR2}htc-RKvVl;MxIrnxFP^b zg6`s9n{CvWM`jYN$d6{)6A8!9t%K~7j#}wycgA5~-Ziy*_-|y%w#qbdKgY@|^0J=k zJs+&`b{lKZwqX0Yx1}{=&GEhuBbn}7TMLl$5dW`>3j;qcUfu#Jeci)BM5KnY{1LB42+Dr3SSO@7b(HjvO5mgu@ z(LPYdc*nK4WW`w|YJv#a(GePXB$V{{CD<5EJIErt@zPCfE>;r}=h=*7+@m?{>+=MlDzm?Df@> zLToGUsO_)qznWvdkh9+EwEWwKy+2amwJg`?^ZXG{1IrdR0DJ5HMJ6xQRy*;jll(bH zy078BJ5sxT>azyoWEJ(E-DE`TPL_Ku)K$G(YkiC55chUpH)OIxD)+ZO9sd=N3!LpA zuTlMS8&JY;b2?mm3k{10PPSRGMf_0r3HbI0AY7bf$WM6qLVre%B3tCoO;8()w3#PP zHYoTKZ;UEg0L4qF;u=xrg}nt5vj}TT{>{%BCB9wo)UMW0w9)H=gCTG3Li~_~rxWGK zkxyp`liu!Z{Ksc%?)#x?>{H*d_i6LqH;XVk&jbKb{89an?n8S&eMgX<4}w;u*Kdy( zPd6#)G@lV27PBwJ-Wy{5ZjQTTThN&o7tDPLC{1EPlcV=7HHd5nw=3_(WV^93_uZq& z(=JXo3KhU)Y|G)&k$}Y%0Jz@4<{ZY<&cxZp$<)yHzen~)Rxr%W?5PN&pu_-X4qX^V zWlJwpB4%a|7)Es>ZDt}?BIch-C3}09pGj6CCL$#mMrk`U`=1fp|3+d&+I%dWVjRq( z;vC#!?83ratm5n<>}<@e>>@0}ESyYC!Xg4h|9=U>&yD`q+hqN@cw&GM6@YwBno-mc zYv|VbO1#{Yj=j>#IwvBdJpY*3hW=u3d|2cn!w%`9Q zRZ!u|cjr(KXq3l476eQtUkja{tMkXxD-Km|5^eK=- zEdpkr$&6#IeF&!ORElv> S0$3IfE>0M7a&ZL-nEwFqjx=5X diff --git a/doc/refs.bib b/doc/refs.bib index 97960d853..ec42fb032 100644 --- a/doc/refs.bib +++ b/doc/refs.bib @@ -50,3 +50,23 @@ title = {Calculus on manifolds}, volume = {1}, year = {1965}} + +@phdthesis{Nikolic16thesis, + title={Characterisation, calibration, and design of visual-inertial sensor systems for robot navigation}, + author={Nikolic, Janosch}, + year={2016}, + school={ETH Zurich} +} + +@book{Simon06book, + title={Optimal state estimation: Kalman, H infinity, and nonlinear approaches}, + author={Simon, Dan}, + year={2006}, + publisher={John Wiley \& Sons} +} + +@inproceedings{Trawny05report_IndirectKF, + title={Indirect Kalman Filter for 3 D Attitude Estimation}, + author={Nikolas Trawny and Stergios I. Roumeliotis}, + year={2005} +} From 6bc9b50a46ac7cfdae0d1ec82c61779d25c3a6cf Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 30 Sep 2021 09:05:02 -0400 Subject: [PATCH 0023/1686] add test for MC based covariance estimation --- .../tests/testCombinedImuFactor.cpp | 397 +++++++++--------- 1 file changed, 202 insertions(+), 195 deletions(-) diff --git a/gtsam/navigation/tests/testCombinedImuFactor.cpp b/gtsam/navigation/tests/testCombinedImuFactor.cpp index a8c039144..2f12983c3 100644 --- a/gtsam/navigation/tests/testCombinedImuFactor.cpp +++ b/gtsam/navigation/tests/testCombinedImuFactor.cpp @@ -16,6 +16,7 @@ * @author Frank Dellaert * @author Richard Roberts * @author Stephen Williams + * @author Varun Agrawal */ #include @@ -40,237 +41,218 @@ static boost::shared_ptr Params() { p->gyroscopeCovariance = kGyroSigma * kGyroSigma * I_3x3; p->accelerometerCovariance = kAccelSigma * kAccelSigma * I_3x3; p->integrationCovariance = 0.0001 * I_3x3; + p->biasAccCovariance = Z_3x3; + p->biasOmegaCovariance = Z_3x3; + p->biasAccOmegaInit = Z_6x6; return p; } +} // namespace testing + +/* ************************************************************************* */ +TEST(CombinedImuFactor, PreintegratedMeasurements ) { + // Linearization point + Bias bias(Vector3(0, 0, 0), Vector3(0, 0, 0)); ///< Current estimate of acceleration and angular rate biases + + // Measurements + Vector3 measuredAcc(0.1, 0.0, 0.0); + Vector3 measuredOmega(M_PI / 100.0, 0.0, 0.0); + double deltaT = 0.5; + double tol = 1e-6; + + auto p = testing::Params(); + + // Actual preintegrated values + PreintegratedImuMeasurements expected1(p, bias); + expected1.integrateMeasurement(measuredAcc, measuredOmega, deltaT); + + PreintegratedCombinedMeasurements actual1(p, bias); + + actual1.integrateMeasurement(measuredAcc, measuredOmega, deltaT); + + EXPECT(assert_equal(Vector(expected1.deltaPij()), actual1.deltaPij(), tol)); + EXPECT(assert_equal(Vector(expected1.deltaVij()), actual1.deltaVij(), tol)); + EXPECT(assert_equal(expected1.deltaRij(), actual1.deltaRij(), tol)); + DOUBLES_EQUAL(expected1.deltaTij(), actual1.deltaTij(), tol); } -// /* ************************************************************************* */ -// TEST(CombinedImuFactor, PreintegratedMeasurements ) { -// // Linearization point -// Bias bias(Vector3(0, 0, 0), Vector3(0, 0, 0)); ///< Current estimate of acceleration and angular rate biases -// // Measurements -// Vector3 measuredAcc(0.1, 0.0, 0.0); -// Vector3 measuredOmega(M_PI / 100.0, 0.0, 0.0); -// double deltaT = 0.5; -// double tol = 1e-6; +/* ************************************************************************* */ +TEST(CombinedImuFactor, ErrorWithBiases ) { + Bias bias(Vector3(0.2, 0, 0), Vector3(0, 0, 0.3)); // Biases (acc, rot) + Bias bias2(Vector3(0.2, 0.2, 0), Vector3(1, 0, 0.3)); // Biases (acc, rot) + Pose3 x1(Rot3::Expmap(Vector3(0, 0, M_PI / 4.0)), Point3(5.0, 1.0, -50.0)); + Vector3 v1(0.5, 0.0, 0.0); + Pose3 x2(Rot3::Expmap(Vector3(0, 0, M_PI / 4.0 + M_PI / 10.0)), + Point3(5.5, 1.0, -50.0)); + Vector3 v2(0.5, 0.0, 0.0); -// auto p = testing::Params(); + auto p = testing::Params(); + p->omegaCoriolis = Vector3(0,0.1,0.1); + PreintegratedImuMeasurements pim( + p, Bias(Vector3(0.2, 0.0, 0.0), Vector3(0.0, 0.0, 0.0))); -// // Actual preintegrated values -// PreintegratedImuMeasurements expected1(p, bias); -// expected1.integrateMeasurement(measuredAcc, measuredOmega, deltaT); + // Measurements + Vector3 measuredOmega; + measuredOmega << 0, 0, M_PI / 10.0 + 0.3; + Vector3 measuredAcc = + x1.rotation().unrotate(-p->n_gravity) + Vector3(0.2, 0.0, 0.0); + double deltaT = 1.0; + double tol = 1e-6; -// PreintegratedCombinedMeasurements actual1(p, bias); + pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT); -// actual1.integrateMeasurement(measuredAcc, measuredOmega, deltaT); + PreintegratedCombinedMeasurements combined_pim(p, + Bias(Vector3(0.2, 0.0, 0.0), Vector3(0.0, 0.0, 0.0))); -// EXPECT(assert_equal(Vector(expected1.deltaPij()), actual1.deltaPij(), tol)); -// EXPECT(assert_equal(Vector(expected1.deltaVij()), actual1.deltaVij(), tol)); -// EXPECT(assert_equal(expected1.deltaRij(), actual1.deltaRij(), tol)); -// DOUBLES_EQUAL(expected1.deltaTij(), actual1.deltaTij(), tol); -// } + combined_pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT); -// /* ************************************************************************* */ -// TEST(CombinedImuFactor, Accelerating) { -// const double a = 0.2, v = 50; + // Create factor + ImuFactor imuFactor(X(1), V(1), X(2), V(2), B(1), pim); -// // Set up body pointing towards y axis, and start at 10,20,0 with velocity -// // going in X The body itself has Z axis pointing down -// const Rot3 nRb(Point3(0, 1, 0), Point3(1, 0, 0), Point3(0, 0, -1)); -// const Point3 initial_position(10, 20, 0); -// const Vector3 initial_velocity(v, 0, 0); + noiseModel::Gaussian::shared_ptr Combinedmodel = + noiseModel::Gaussian::Covariance(combined_pim.preintMeasCov()); + CombinedImuFactor combinedfactor(X(1), V(1), X(2), V(2), B(1), B(2), + combined_pim); -// const AcceleratingScenario scenario(nRb, initial_position, initial_velocity, -// Vector3(a, 0, 0)); + Vector errorExpected = imuFactor.evaluateError(x1, v1, x2, v2, bias); + Vector errorActual = combinedfactor.evaluateError(x1, v1, x2, v2, bias, + bias2); + EXPECT(assert_equal(errorExpected, errorActual.head(9), tol)); -// const double T = 3.0; // seconds -// CombinedScenarioRunner runner(scenario, testing::Params(), T / 10); + // Expected Jacobians + Matrix H1e, H2e, H3e, H4e, H5e; + (void) imuFactor.evaluateError(x1, v1, x2, v2, bias, H1e, H2e, H3e, H4e, H5e); -// PreintegratedCombinedMeasurements pim = runner.integrate(T); -// EXPECT(assert_equal(scenario.pose(T), runner.predict(pim).pose(), 1e-9)); + // Actual Jacobians + Matrix H1a, H2a, H3a, H4a, H5a, H6a; + (void) combinedfactor.evaluateError(x1, v1, x2, v2, bias, bias2, H1a, H2a, + H3a, H4a, H5a, H6a); -// auto estimatedCov = runner.estimateCovariance(T, 100); -// Eigen::Matrix expected = pim.preintMeasCov(); -// EXPECT(assert_equal(estimatedCov, expected, 0.1)); -// } + EXPECT(assert_equal(H1e, H1a.topRows(9))); + EXPECT(assert_equal(H2e, H2a.topRows(9))); + EXPECT(assert_equal(H3e, H3a.topRows(9))); + EXPECT(assert_equal(H4e, H4a.topRows(9))); + EXPECT(assert_equal(H5e, H5a.topRows(9))); +} -// /* ************************************************************************* */ -// TEST(CombinedImuFactor, ErrorWithBiases ) { -// Bias bias(Vector3(0.2, 0, 0), Vector3(0, 0, 0.3)); // Biases (acc, rot) -// Bias bias2(Vector3(0.2, 0.2, 0), Vector3(1, 0, 0.3)); // Biases (acc, rot) -// Pose3 x1(Rot3::Expmap(Vector3(0, 0, M_PI / 4.0)), Point3(5.0, 1.0, -50.0)); -// Vector3 v1(0.5, 0.0, 0.0); -// Pose3 x2(Rot3::Expmap(Vector3(0, 0, M_PI / 4.0 + M_PI / 10.0)), -// Point3(5.5, 1.0, -50.0)); -// Vector3 v2(0.5, 0.0, 0.0); +/* ************************************************************************* */ +#ifdef GTSAM_TANGENT_PREINTEGRATION +TEST(CombinedImuFactor, FirstOrderPreIntegratedMeasurements) { + auto p = testing::Params(); + testing::SomeMeasurements measurements; -// auto p = testing::Params(); -// p->omegaCoriolis = Vector3(0,0.1,0.1); -// PreintegratedImuMeasurements pim( -// p, Bias(Vector3(0.2, 0.0, 0.0), Vector3(0.0, 0.0, 0.0))); + auto preintegrated = [=](const Vector3& a, const Vector3& w) { + PreintegratedImuMeasurements pim(p, Bias(a, w)); + testing::integrateMeasurements(measurements, &pim); + return pim.preintegrated(); + }; -// // Measurements -// Vector3 measuredOmega; -// measuredOmega << 0, 0, M_PI / 10.0 + 0.3; -// Vector3 measuredAcc = -// x1.rotation().unrotate(-p->n_gravity) + Vector3(0.2, 0.0, 0.0); -// double deltaT = 1.0; -// double tol = 1e-6; + // Actual pre-integrated values + PreintegratedCombinedMeasurements pim(p); + testing::integrateMeasurements(measurements, &pim); -// pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT); + EXPECT(assert_equal(numericalDerivative21(preintegrated, Z_3x1, Z_3x1), + pim.preintegrated_H_biasAcc())); + EXPECT(assert_equal(numericalDerivative22(preintegrated, Z_3x1, Z_3x1), + pim.preintegrated_H_biasOmega(), 1e-3)); +} +#endif -// PreintegratedCombinedMeasurements combined_pim(p, -// Bias(Vector3(0.2, 0.0, 0.0), Vector3(0.0, 0.0, 0.0))); +/* ************************************************************************* */ +TEST(CombinedImuFactor, PredictPositionAndVelocity) { + const Bias bias(Vector3(0, 0.1, 0), Vector3(0, 0.1, 0)); // Biases (acc, rot) -// combined_pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT); + auto p = testing::Params(); -// // Create factor -// ImuFactor imuFactor(X(1), V(1), X(2), V(2), B(1), pim); + // Measurements + const Vector3 measuredOmega(0, 0.1, 0); // M_PI/10.0+0.3; + const Vector3 measuredAcc(0, 1.1, -kGravity); + const double deltaT = 0.01; -// noiseModel::Gaussian::shared_ptr Combinedmodel = -// noiseModel::Gaussian::Covariance(combined_pim.preintMeasCov()); -// CombinedImuFactor combinedfactor(X(1), V(1), X(2), V(2), B(1), B(2), -// combined_pim); + PreintegratedCombinedMeasurements pim(p, bias); -// Vector errorExpected = imuFactor.evaluateError(x1, v1, x2, v2, bias); -// Vector errorActual = combinedfactor.evaluateError(x1, v1, x2, v2, bias, -// bias2); -// EXPECT(assert_equal(errorExpected, errorActual.head(9), tol)); + for (int i = 0; i < 100; ++i) + pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT); -// // Expected Jacobians -// Matrix H1e, H2e, H3e, H4e, H5e; -// (void) imuFactor.evaluateError(x1, v1, x2, v2, bias, H1e, H2e, H3e, H4e, H5e); + // Create factor + const noiseModel::Gaussian::shared_ptr combinedmodel = + noiseModel::Gaussian::Covariance(pim.preintMeasCov()); + const CombinedImuFactor Combinedfactor(X(1), V(1), X(2), V(2), B(1), B(2), pim); -// // Actual Jacobians -// Matrix H1a, H2a, H3a, H4a, H5a, H6a; -// (void) combinedfactor.evaluateError(x1, v1, x2, v2, bias, bias2, H1a, H2a, -// H3a, H4a, H5a, H6a); + // Predict + const NavState actual = pim.predict(NavState(), bias); + const Pose3 expectedPose(Rot3(), Point3(0, 0.5, 0)); + const Vector3 expectedVelocity(0, 1, 0); + EXPECT(assert_equal(expectedPose, actual.pose())); + EXPECT(assert_equal(Vector(expectedVelocity), Vector(actual.velocity()))); +} -// EXPECT(assert_equal(H1e, H1a.topRows(9))); -// EXPECT(assert_equal(H2e, H2a.topRows(9))); -// EXPECT(assert_equal(H3e, H3a.topRows(9))); -// EXPECT(assert_equal(H4e, H4a.topRows(9))); -// EXPECT(assert_equal(H5e, H5a.topRows(9))); -// } +/* ************************************************************************* */ +TEST(CombinedImuFactor, PredictRotation) { + const Bias bias(Vector3(0, 0, 0), Vector3(0, 0, 0)); // Biases (acc, rot) + auto p = testing::Params(); + PreintegratedCombinedMeasurements pim(p, bias); + const Vector3 measuredAcc = - kGravityAlongNavZDown; + const Vector3 measuredOmega(0, 0, M_PI / 10.0); + const double deltaT = 0.01; + const double tol = 1e-4; + for (int i = 0; i < 100; ++i) + pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT); + const CombinedImuFactor Combinedfactor(X(1), V(1), X(2), V(2), B(1), B(2), pim); -// /* ************************************************************************* */ -// #ifdef GTSAM_TANGENT_PREINTEGRATION -// TEST(CombinedImuFactor, FirstOrderPreIntegratedMeasurements) { -// auto p = testing::Params(); -// testing::SomeMeasurements measurements; + // Predict + const Pose3 x(Rot3::Ypr(0, 0, 0), Point3(0, 0, 0)), x2; + const Vector3 v(0, 0, 0), v2; + const NavState actual = pim.predict(NavState(x, v), bias); + const Pose3 expectedPose(Rot3::Ypr(M_PI / 10, 0, 0), Point3(0, 0, 0)); + EXPECT(assert_equal(expectedPose, actual.pose(), tol)); +} -// auto preintegrated = [=](const Vector3& a, const Vector3& w) { -// PreintegratedImuMeasurements pim(p, Bias(a, w)); -// testing::integrateMeasurements(measurements, &pim); -// return pim.preintegrated(); -// }; +/* ************************************************************************* */ +// Testing covariance to check if all the jacobians are accounted for. +TEST(CombinedImuFactor, CheckCovariance) { + auto params = PreintegrationCombinedParams::MakeSharedU(9.81); -// // Actual pre-integrated values -// PreintegratedCombinedMeasurements pim(p); -// testing::integrateMeasurements(measurements, &pim); + params->setAccelerometerCovariance(pow(0.01, 2) * I_3x3); + params->setGyroscopeCovariance(pow(1.75e-4, 2) * I_3x3); + params->setIntegrationCovariance(pow(0.0, 2) * I_3x3); + params->setOmegaCoriolis(Vector3::Zero()); -// EXPECT(assert_equal(numericalDerivative21(preintegrated, Z_3x1, Z_3x1), -// pim.preintegrated_H_biasAcc())); -// EXPECT(assert_equal(numericalDerivative22(preintegrated, Z_3x1, Z_3x1), -// pim.preintegrated_H_biasOmega(), 1e-3)); -// } -// #endif + imuBias::ConstantBias currentBias; -// /* ************************************************************************* */ -// TEST(CombinedImuFactor, PredictPositionAndVelocity) { -// const Bias bias(Vector3(0, 0.1, 0), Vector3(0, 0.1, 0)); // Biases (acc, rot) + PreintegratedCombinedMeasurements actual(params, currentBias); -// auto p = testing::Params(); + // Measurements + Vector3 measuredAcc(0.1577, -0.8251, 9.6111); + Vector3 measuredOmega(-0.0210, 0.0311, 0.0145); + double deltaT = 0.01; -// // Measurements -// const Vector3 measuredOmega(0, 0.1, 0); // M_PI/10.0+0.3; -// const Vector3 measuredAcc(0, 1.1, -kGravity); -// const double deltaT = 0.01; + actual.integrateMeasurement(measuredAcc, measuredOmega, deltaT); -// PreintegratedCombinedMeasurements pim(p, bias); + Eigen::Matrix expected; + expected << 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // + 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // + 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // + 0, 0, 0, 2.50025e-07, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // + 0, 0, 0, 0, 2.50025e-07, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // + 0, 0, 0, 0, 0, 2.50025e-07, 0, 0, 0, 0, 0, 0, 0, 0, 0, // + 0, 0, 0, 0, 0, 0, 0.010001, 0, 0, 0, 0, 0, 0, 0, 0, // + 0, 0, 0, 0, 0, 0, 0, 0.010001, 0, 0, 0, 0, 0, 0, 0, // + 0, 0, 0, 0, 0, 0, 0, 0, 0.010001, 0, 0, 0, 0, 0, 0, // + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, // + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, // + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, // + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, // + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, // + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01; -// for (int i = 0; i < 100; ++i) -// pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT); + // regression + EXPECT(assert_equal(expected, actual.preintMeasCov())); +} -// // Create factor -// const noiseModel::Gaussian::shared_ptr combinedmodel = -// noiseModel::Gaussian::Covariance(pim.preintMeasCov()); -// const CombinedImuFactor Combinedfactor(X(1), V(1), X(2), V(2), B(1), B(2), pim); - -// // Predict -// const NavState actual = pim.predict(NavState(), bias); -// const Pose3 expectedPose(Rot3(), Point3(0, 0.5, 0)); -// const Vector3 expectedVelocity(0, 1, 0); -// EXPECT(assert_equal(expectedPose, actual.pose())); -// EXPECT(assert_equal(Vector(expectedVelocity), Vector(actual.velocity()))); -// } - -// /* ************************************************************************* */ -// TEST(CombinedImuFactor, PredictRotation) { -// const Bias bias(Vector3(0, 0, 0), Vector3(0, 0, 0)); // Biases (acc, rot) -// auto p = testing::Params(); -// PreintegratedCombinedMeasurements pim(p, bias); -// const Vector3 measuredAcc = - kGravityAlongNavZDown; -// const Vector3 measuredOmega(0, 0, M_PI / 10.0); -// const double deltaT = 0.01; -// const double tol = 1e-4; -// for (int i = 0; i < 100; ++i) -// pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT); -// const CombinedImuFactor Combinedfactor(X(1), V(1), X(2), V(2), B(1), B(2), pim); - -// // Predict -// const Pose3 x(Rot3::Ypr(0, 0, 0), Point3(0, 0, 0)), x2; -// const Vector3 v(0, 0, 0), v2; -// const NavState actual = pim.predict(NavState(x, v), bias); -// const Pose3 expectedPose(Rot3::Ypr(M_PI / 10, 0, 0), Point3(0, 0, 0)); -// EXPECT(assert_equal(expectedPose, actual.pose(), tol)); -// } - -// /* ************************************************************************* */ -// // Testing covariance to check if all the jacobians are accounted for. -// TEST(CombinedImuFactor, CheckCovariance) { -// auto params = PreintegrationCombinedParams::MakeSharedU(9.81); - -// params->setAccelerometerCovariance(pow(0.01, 2) * I_3x3); -// params->setGyroscopeCovariance(pow(1.75e-4, 2) * I_3x3); -// params->setIntegrationCovariance(pow(0.0, 2) * I_3x3); -// params->setOmegaCoriolis(Vector3::Zero()); - -// imuBias::ConstantBias currentBias; - -// PreintegratedCombinedMeasurements actual(params, currentBias); - -// // Measurements -// Vector3 measuredAcc(0.1577, -0.8251, 9.6111); -// Vector3 measuredOmega(-0.0210, 0.0311, 0.0145); -// double deltaT = 0.01; - -// actual.integrateMeasurement(measuredAcc, measuredOmega, deltaT); - -// Eigen::Matrix expected; -// expected << 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // -// 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // -// 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // -// 0, 0, 0, 2.50025e-07, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // -// 0, 0, 0, 0, 2.50025e-07, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // -// 0, 0, 0, 0, 0, 2.50025e-07, 0, 0, 0, 0, 0, 0, 0, 0, 0, // -// 0, 0, 0, 0, 0, 0, 0.010001, 0, 0, 0, 0, 0, 0, 0, 0, // -// 0, 0, 0, 0, 0, 0, 0, 0.010001, 0, 0, 0, 0, 0, 0, 0, // -// 0, 0, 0, 0, 0, 0, 0, 0, 0.010001, 0, 0, 0, 0, 0, 0, // -// 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, // -// 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, // -// 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, // -// 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, // -// 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, // -// 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01; - -// // regression -// EXPECT(assert_equal(expected, actual.preintMeasCov())); -// } -// Test that the covariance values for the ImuFactor and the CombinedImuFactor (top-left 9x9) are the same +// Test that the covariance values for the ImuFactor and the CombinedImuFactor +// (top-left 9x9) are the same TEST(CombinedImuFactor, SameCovariance) { - // IMU measurements and time delta Vector3 accMeas(0.1577, -0.8251, 9.6111); Vector3 omegaMeas(-0.0210, 0.0311, 0.0145); @@ -278,7 +260,7 @@ TEST(CombinedImuFactor, SameCovariance) { // Assume zero bias imuBias::ConstantBias currentBias; - + // Define params for ImuFactor auto params = PreintegrationParams::MakeSharedU(); params->setAccelerometerCovariance(pow(0.01, 2) * I_3x3); @@ -303,10 +285,35 @@ TEST(CombinedImuFactor, SameCovariance) { PreintegratedCombinedMeasurements cpim(combined_params, currentBias); cpim.integrateMeasurement(accMeas, omegaMeas, deltaT); - // Assert if the noise covariance - EXPECT(assert_equal(pim.preintMeasCov(), cpim.preintMeasCov().block(0, 0, 9, 9))); + // Assert if the noise covariance + EXPECT(assert_equal(pim.preintMeasCov(), + cpim.preintMeasCov().block(0, 0, 9, 9))); } +/* ************************************************************************* */ +TEST(CombinedImuFactor, Accelerating) { + const double a = 0.2, v = 50; + + // Set up body pointing towards y axis, and start at 10,20,0 with velocity + // going in X The body itself has Z axis pointing down + const Rot3 nRb(Point3(0, 1, 0), Point3(1, 0, 0), Point3(0, 0, -1)); + const Point3 initial_position(10, 20, 0); + const Vector3 initial_velocity(v, 0, 0); + + const AcceleratingScenario scenario(nRb, initial_position, initial_velocity, + Vector3(a, 0, 0)); + + const double T = 3.0; // seconds + + CombinedScenarioRunner runner(scenario, testing::Params(), T / 10); + + PreintegratedCombinedMeasurements pim = runner.integrate(T); + EXPECT(assert_equal(scenario.pose(T), runner.predict(pim).pose(), 1e-9)); + + auto estimatedCov = runner.estimateCovariance(T, 100); + Eigen::Matrix expected = pim.preintMeasCov(); + EXPECT(assert_equal(estimatedCov, expected, 0.1)); +} /* ************************************************************************* */ int main() { From af714cdb5a756a744dd0000a89782a55fb14d66c Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 28 Sep 2021 13:43:04 -0400 Subject: [PATCH 0024/1686] undo name change from 984a90 --- examples/CombinedImuFactorsExample.cpp | 4 ++-- examples/ImuFactorsExample.cpp | 4 ++-- gtsam/navigation/CombinedImuFactor.cpp | 10 +++++----- gtsam/navigation/CombinedImuFactor.h | 12 ++++++------ .../examples/ISAM2_SmartFactorStereo_IMU.cpp | 2 +- tests/testImuPreintegration.cpp | 4 ++-- 6 files changed, 18 insertions(+), 18 deletions(-) diff --git a/examples/CombinedImuFactorsExample.cpp b/examples/CombinedImuFactorsExample.cpp index 49cdb6835..35ed387c4 100644 --- a/examples/CombinedImuFactorsExample.cpp +++ b/examples/CombinedImuFactorsExample.cpp @@ -107,7 +107,7 @@ boost::shared_ptr imuParams() { I_3x3 * 1e-8; // error committed in integrating position from velocities Matrix33 bias_acc_cov = I_3x3 * pow(accel_bias_rw_sigma, 2); Matrix33 bias_omega_cov = I_3x3 * pow(gyro_bias_rw_sigma, 2); - Matrix66 bias_acc_omega_int = + Matrix66 bias_acc_omega_init = I_6x6 * 1e-5; // error in the bias used for preintegration auto p = PreintegratedCombinedMeasurements::Params::MakeSharedD(0.0); @@ -123,7 +123,7 @@ boost::shared_ptr imuParams() { // PreintegrationCombinedMeasurements params: p->biasAccCovariance = bias_acc_cov; // acc bias in continuous p->biasOmegaCovariance = bias_omega_cov; // gyro bias in continuous - p->biasAccOmegaInt = bias_acc_omega_int; + p->biasAccOmegaInit = bias_acc_omega_init; return p; } diff --git a/examples/ImuFactorsExample.cpp b/examples/ImuFactorsExample.cpp index 38ee4c7c7..12167a19d 100644 --- a/examples/ImuFactorsExample.cpp +++ b/examples/ImuFactorsExample.cpp @@ -94,7 +94,7 @@ boost::shared_ptr imuParams() { I_3x3 * 1e-8; // error committed in integrating position from velocities Matrix33 bias_acc_cov = I_3x3 * pow(accel_bias_rw_sigma, 2); Matrix33 bias_omega_cov = I_3x3 * pow(gyro_bias_rw_sigma, 2); - Matrix66 bias_acc_omega_int = + Matrix66 bias_acc_omega_init = I_6x6 * 1e-5; // error in the bias used for preintegration auto p = PreintegratedCombinedMeasurements::Params::MakeSharedD(0.0); @@ -110,7 +110,7 @@ boost::shared_ptr imuParams() { // PreintegrationCombinedMeasurements params: p->biasAccCovariance = bias_acc_cov; // acc bias in continuous p->biasOmegaCovariance = bias_omega_cov; // gyro bias in continuous - p->biasAccOmegaInt = bias_acc_omega_int; + p->biasAccOmegaInit = bias_acc_omega_init; return p; } diff --git a/gtsam/navigation/CombinedImuFactor.cpp b/gtsam/navigation/CombinedImuFactor.cpp index de4d3f66d..5d49e4c0b 100644 --- a/gtsam/navigation/CombinedImuFactor.cpp +++ b/gtsam/navigation/CombinedImuFactor.cpp @@ -39,7 +39,7 @@ void PreintegrationCombinedParams::print(const string& s) const { << endl; cout << "biasOmegaCovariance:\n[\n" << biasOmegaCovariance << "\n]" << endl; - cout << "biasAccOmegaInt:\n[\n" << biasAccOmegaInt << "\n]" + cout << "biasAccOmegaInit:\n[\n" << biasAccOmegaInit << "\n]" << endl; } @@ -52,7 +52,7 @@ bool PreintegrationCombinedParams::equals(const PreintegratedRotationParams& oth tol) && equal_with_abs_tol(biasOmegaCovariance, e->biasOmegaCovariance, tol) && - equal_with_abs_tol(biasAccOmegaInt, e->biasAccOmegaInt, tol); + equal_with_abs_tol(biasAccOmegaInit, e->biasAccOmegaInit, tol); } //------------------------------------------------------------------------------ @@ -137,8 +137,8 @@ void PreintegratedCombinedMeasurements::integrateMeasurement( Eigen::Matrix G_measCov_Gt; G_measCov_Gt.setZero(15, 15); - Matrix3 aCov_updated = aCov + p().biasAccOmegaInt.block<3, 3>(0, 0); - Matrix3 wCov_updated = wCov + p().biasAccOmegaInt.block<3, 3>(3, 3); + Matrix3 aCov_updated = aCov + p().biasAccOmegaInit.block<3, 3>(0, 0); + Matrix3 wCov_updated = wCov + p().biasAccOmegaInit.block<3, 3>(3, 3); // BLOCK DIAGONAL TERMS D_t_t(&G_measCov_Gt) = (pos_H_biasAcc // @@ -156,7 +156,7 @@ void PreintegratedCombinedMeasurements::integrateMeasurement( D_g_g(&G_measCov_Gt) = dt * p().biasOmegaCovariance; // OFF BLOCK DIAGONAL TERMS - Matrix3 temp = vel_H_biasAcc * p().biasAccOmegaInt.block<3, 3>(3, 0) + Matrix3 temp = vel_H_biasAcc * p().biasAccOmegaInit.block<3, 3>(3, 0) * theta_H_biasOmega.transpose(); D_v_R(&G_measCov_Gt) = temp; D_v_t(&G_measCov_Gt) = vel_H_biasAcc * (aCov / dt) * pos_H_biasAcc.transpose(); diff --git a/gtsam/navigation/CombinedImuFactor.h b/gtsam/navigation/CombinedImuFactor.h index ce169c1d0..5849f6f24 100644 --- a/gtsam/navigation/CombinedImuFactor.h +++ b/gtsam/navigation/CombinedImuFactor.h @@ -62,19 +62,19 @@ typedef ManifoldPreintegration PreintegrationType; struct GTSAM_EXPORT PreintegrationCombinedParams : PreintegrationParams { Matrix3 biasAccCovariance; ///< continuous-time "Covariance" describing accelerometer bias random walk Matrix3 biasOmegaCovariance; ///< continuous-time "Covariance" describing gyroscope bias random walk - Matrix6 biasAccOmegaInt; ///< covariance of bias used for pre-integration + Matrix6 biasAccOmegaInit; ///< covariance of bias used as initial estimate. /// Default constructor makes uninitialized params struct. /// Used for serialization. PreintegrationCombinedParams() : biasAccCovariance(I_3x3), biasOmegaCovariance(I_3x3), - biasAccOmegaInt(I_6x6) {} + biasAccOmegaInit(I_6x6) {} /// See two named constructors below for good values of n_gravity in body frame PreintegrationCombinedParams(const Vector3& n_gravity) : PreintegrationParams(n_gravity), biasAccCovariance(I_3x3), - biasOmegaCovariance(I_3x3), biasAccOmegaInt(I_6x6) { + biasOmegaCovariance(I_3x3), biasAccOmegaInit(I_6x6) { } @@ -93,11 +93,11 @@ struct GTSAM_EXPORT PreintegrationCombinedParams : PreintegrationParams { void setBiasAccCovariance(const Matrix3& cov) { biasAccCovariance=cov; } void setBiasOmegaCovariance(const Matrix3& cov) { biasOmegaCovariance=cov; } - void setBiasAccOmegaInt(const Matrix6& cov) { biasAccOmegaInt=cov; } + void setBiasAccOmegaInt(const Matrix6& cov) { biasAccOmegaInit=cov; } const Matrix3& getBiasAccCovariance() const { return biasAccCovariance; } const Matrix3& getBiasOmegaCovariance() const { return biasOmegaCovariance; } - const Matrix6& getBiasAccOmegaInt() const { return biasAccOmegaInt; } + const Matrix6& getBiasAccOmegaInt() const { return biasAccOmegaInit; } private: @@ -109,7 +109,7 @@ private: ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegrationParams); ar & BOOST_SERIALIZATION_NVP(biasAccCovariance); ar & BOOST_SERIALIZATION_NVP(biasOmegaCovariance); - ar & BOOST_SERIALIZATION_NVP(biasAccOmegaInt); + ar & BOOST_SERIALIZATION_NVP(biasAccOmegaInit); } public: diff --git a/gtsam_unstable/examples/ISAM2_SmartFactorStereo_IMU.cpp b/gtsam_unstable/examples/ISAM2_SmartFactorStereo_IMU.cpp index c0a102d11..27d87d217 100644 --- a/gtsam_unstable/examples/ISAM2_SmartFactorStereo_IMU.cpp +++ b/gtsam_unstable/examples/ISAM2_SmartFactorStereo_IMU.cpp @@ -57,7 +57,7 @@ struct IMUHelper { p->biasAccCovariance = I_3x3 * pow(0.00002, 2.0); // acc bias in continuous p->biasOmegaCovariance = I_3x3 * pow(0.001, 2.0); // gyro bias in continuous - p->biasAccOmegaInt = Matrix::Identity(6, 6) * 1e-5; + p->biasAccOmegaInit = Matrix::Identity(6, 6) * 1e-5; // body to IMU rotation Rot3 iRb(0.036129, -0.998727, 0.035207, diff --git a/tests/testImuPreintegration.cpp b/tests/testImuPreintegration.cpp index 1f584be0e..94e6fb89f 100644 --- a/tests/testImuPreintegration.cpp +++ b/tests/testImuPreintegration.cpp @@ -43,7 +43,7 @@ TEST(TestImuPreintegration, LoadedSimulationData) { double gyrNoiseSigma = 0.000208; double gyrBiasRwSigma = 0.000004; double integrationCovariance = 1e-8; - double biasAccOmegaInt = 1e-5; + double biasAccOmegaInit = 1e-5; double gravity = 9.81; double rate = 400.0; // Hz @@ -76,7 +76,7 @@ TEST(TestImuPreintegration, LoadedSimulationData) { imuPreintegratedParams->gyroscopeCovariance = I_3x3 * pow(gyrNoiseSigma, 2); imuPreintegratedParams->biasOmegaCovariance = I_3x3 * pow(gyrBiasRwSigma, 2); imuPreintegratedParams->integrationCovariance = I_3x3 * integrationCovariance; - imuPreintegratedParams->biasAccOmegaInt = I_6x6 * biasAccOmegaInt; + imuPreintegratedParams->biasAccOmegaInit = I_6x6 * biasAccOmegaInit; // Initial state Pose3 priorPose; From e38ea502d7df488fdbec8072284715c977547e32 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 28 Sep 2021 18:22:15 -0400 Subject: [PATCH 0025/1686] detailed implementation of CombinedImuFactor noise propagation --- gtsam/navigation/CombinedImuFactor.cpp | 68 +++++++++++++++++--------- 1 file changed, 44 insertions(+), 24 deletions(-) diff --git a/gtsam/navigation/CombinedImuFactor.cpp b/gtsam/navigation/CombinedImuFactor.cpp index 5d49e4c0b..2dfaae2fd 100644 --- a/gtsam/navigation/CombinedImuFactor.cpp +++ b/gtsam/navigation/CombinedImuFactor.cpp @@ -110,17 +110,22 @@ void PreintegratedCombinedMeasurements::integrateMeasurement( // and preintegrated measurements // Single Jacobians to propagate covariance - Matrix3 theta_H_biasOmega = C.topRows<3>(); - Matrix3 pos_H_biasAcc = B.middleRows<3>(3); - Matrix3 vel_H_biasAcc = B.bottomRows<3>(); + Matrix3 theta_H_omega = C.topRows<3>(); + Matrix3 pos_H_acc = B.middleRows<3>(3); + Matrix3 vel_H_acc = B.bottomRows<3>(); + + Matrix3 theta_H_biasOmegaInit = -theta_H_omega; + Matrix3 pos_H_biasAccInit = -pos_H_acc; + Matrix3 vel_H_biasAcc = -vel_H_acc; + Matrix3 vel_H_biasAccInit = -vel_H_acc; // overall Jacobian wrt preintegrated measurements (df/dx) Eigen::Matrix F; F.setZero(); F.block<9, 9>(0, 0) = A; - F.block<3, 3>(0, 12) = theta_H_biasOmega; - F.block<3, 3>(3, 9) = pos_H_biasAcc; - F.block<3, 3>(6, 9) = vel_H_biasAcc; + F.block<3, 3>(0, 12) = theta_H_omega; + F.block<3, 3>(3, 9) = pos_H_acc; + F.block<3, 3>(6, 9) = vel_H_acc; F.block<6, 6>(9, 9) = I_6x6; // Update the uncertainty on the state (matrix F in [4]). @@ -131,37 +136,52 @@ void PreintegratedCombinedMeasurements::integrateMeasurement( const Matrix3& aCov = p().accelerometerCovariance; const Matrix3& wCov = p().gyroscopeCovariance; const Matrix3& iCov = p().integrationCovariance; + const Matrix6& bInitCov = p().biasAccOmegaInit; // first order uncertainty propagation // Optimized matrix mult: (1/dt) * G * measurementCovariance * G.transpose() Eigen::Matrix G_measCov_Gt; G_measCov_Gt.setZero(15, 15); - Matrix3 aCov_updated = aCov + p().biasAccOmegaInit.block<3, 3>(0, 0); - Matrix3 wCov_updated = wCov + p().biasAccOmegaInit.block<3, 3>(3, 3); - // BLOCK DIAGONAL TERMS - D_t_t(&G_measCov_Gt) = (pos_H_biasAcc // - * (aCov_updated / dt) // - * pos_H_biasAcc.transpose()) + (dt * iCov); - D_v_v(&G_measCov_Gt) = vel_H_biasAcc // - * (aCov_updated / dt) // - * (vel_H_biasAcc.transpose()); + D_R_R(&G_measCov_Gt) = + (theta_H_omega * (wCov / dt) * theta_H_omega.transpose()) + // + (theta_H_biasOmegaInit * (bInitCov.block<3, 3>(3, 3) / dt) * + theta_H_biasOmegaInit.transpose()); - D_R_R(&G_measCov_Gt) = theta_H_biasOmega // - * (wCov_updated / dt) // - * (theta_H_biasOmega.transpose()); + D_t_t(&G_measCov_Gt) = + (pos_H_acc * (aCov / dt) * pos_H_acc.transpose()) // + + (pos_H_biasAccInit * (bInitCov.block<3, 3>(0, 0) / dt) * + pos_H_biasAccInit.transpose()) // + + (dt * iCov); + + D_v_v(&G_measCov_Gt) = + (vel_H_acc * (aCov / dt) * vel_H_acc.transpose()) // + + (vel_H_biasAccInit * (bInitCov.block<3, 3>(0, 0) / dt) * + vel_H_biasAccInit.transpose()); D_a_a(&G_measCov_Gt) = dt * p().biasAccCovariance; D_g_g(&G_measCov_Gt) = dt * p().biasOmegaCovariance; // OFF BLOCK DIAGONAL TERMS - Matrix3 temp = vel_H_biasAcc * p().biasAccOmegaInit.block<3, 3>(3, 0) - * theta_H_biasOmega.transpose(); - D_v_R(&G_measCov_Gt) = temp; - D_v_t(&G_measCov_Gt) = vel_H_biasAcc * (aCov / dt) * pos_H_biasAcc.transpose(); - D_R_v(&G_measCov_Gt) = temp.transpose(); - D_t_v(&G_measCov_Gt) = pos_H_biasAcc * (aCov / dt) * vel_H_biasAcc.transpose(); + D_R_t(&G_measCov_Gt) = theta_H_biasOmegaInit * + (bInitCov.block<3, 3>(3, 0) / dt) * + pos_H_biasAccInit.transpose(); + D_R_v(&G_measCov_Gt) = theta_H_biasOmegaInit * + (bInitCov.block<3, 3>(3, 0) / dt) * + vel_H_biasAccInit.transpose(); + D_t_R(&G_measCov_Gt) = pos_H_biasAccInit * (bInitCov.block<3, 3>(0, 3) / dt) * + theta_H_biasOmegaInit.transpose(); + D_t_v(&G_measCov_Gt) = + (pos_H_acc * (aCov / dt) * vel_H_acc.transpose()) + + (pos_H_biasAccInit * (bInitCov.block<3, 3>(0, 0) / dt) * + vel_H_biasAccInit.transpose()); + D_v_R(&G_measCov_Gt) = vel_H_biasAccInit * (bInitCov.block<3, 3>(0, 3) / dt) * + theta_H_biasOmegaInit.transpose(); + D_v_t(&G_measCov_Gt) = + (vel_H_acc * (aCov / dt) * pos_H_acc.transpose()) + + (vel_H_biasAccInit * (bInitCov.block<3, 3>(0, 0) / dt) * + pos_H_biasAccInit.transpose()); preintMeasCov_.noalias() += G_measCov_Gt; } From 3cee1b71ec55d157e7a4654c984fb9d40ae15550 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 30 Sep 2021 09:01:23 -0400 Subject: [PATCH 0026/1686] test passes --- gtsam/navigation/CombinedImuFactor.cpp | 6 +++--- gtsam/navigation/ScenarioRunner.cpp | 3 ++- 2 files changed, 5 insertions(+), 4 deletions(-) diff --git a/gtsam/navigation/CombinedImuFactor.cpp b/gtsam/navigation/CombinedImuFactor.cpp index 2dfaae2fd..64d555e2e 100644 --- a/gtsam/navigation/CombinedImuFactor.cpp +++ b/gtsam/navigation/CombinedImuFactor.cpp @@ -145,9 +145,9 @@ void PreintegratedCombinedMeasurements::integrateMeasurement( // BLOCK DIAGONAL TERMS D_R_R(&G_measCov_Gt) = - (theta_H_omega * (wCov / dt) * theta_H_omega.transpose()) + // - (theta_H_biasOmegaInit * (bInitCov.block<3, 3>(3, 3) / dt) * - theta_H_biasOmegaInit.transpose()); + (theta_H_omega * (wCov / dt) * theta_H_omega.transpose()) // + + (theta_H_biasOmegaInit * (bInitCov.block<3, 3>(3, 3) / dt) * + theta_H_biasOmegaInit.transpose()); D_t_t(&G_measCov_Gt) = (pos_H_acc * (aCov / dt) * pos_H_acc.transpose()) // diff --git a/gtsam/navigation/ScenarioRunner.cpp b/gtsam/navigation/ScenarioRunner.cpp index 3a447dcab..9d3e258de 100644 --- a/gtsam/navigation/ScenarioRunner.cpp +++ b/gtsam/navigation/ScenarioRunner.cpp @@ -145,7 +145,8 @@ Eigen::Matrix CombinedScenarioRunner::estimateCovariance( auto pim = integrate(T, estimatedBias, true); NavState sampled = predict(pim); Vector15 xi = Vector15::Zero(); - xi << sampled.localCoordinates(prediction), estimatedBias_.vector(); + xi << sampled.localCoordinates(prediction), + (estimatedBias_.vector() - estimatedBias.vector()); samples.col(i) = xi; sum += xi; } From dfa32e50207a3b69be71ad3b17df9093ae98d8c9 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sat, 9 Oct 2021 22:51:48 -0400 Subject: [PATCH 0027/1686] lyx update --- doc/ImuFactor.lyx | 80 ++++++++++++++++++++++++++++++++++++++--------- 1 file changed, 66 insertions(+), 14 deletions(-) diff --git a/doc/ImuFactor.lyx b/doc/ImuFactor.lyx index f76ede023..80c160e6e 100644 --- a/doc/ImuFactor.lyx +++ b/doc/ImuFactor.lyx @@ -227,16 +227,62 @@ preintegrated_ \begin_layout Standard The main function of a factor is to calculate an error. - The easiest case to look at is the NavState variant in ImuFactor2, which - is given as: + This is done exactly the same in both variants: \begin_inset Formula \begin{equation} -\Delta X_{ij}=X_{j}-\hat{X_{ij}}\label{eq:imu-factor-error} +e(X_{i},X_{j})=X_{j}\ominus\widehat{X_{j}}\label{eq:imu-factor-error} \end{equation} \end_inset +where the predicted NavState +\begin_inset Formula $\widehat{X_{j}}$ +\end_inset + at time +\begin_inset Formula $t_{j}$ +\end_inset + + is a function of the NavState +\begin_inset Formula $X_{i}$ +\end_inset + + at time +\begin_inset Formula $t_{i}$ +\end_inset + + and the preintegrated measurements +\begin_inset Formula $PIM$ +\end_inset + +: +\begin_inset Formula +\[ +\widehat{X_{j}}=f(X_{i},PIM) +\] + +\end_inset + +The noise model associated with this factor is assumed to be zero-mean Gaussian + with a +\begin_inset Formula $9\times9$ +\end_inset + + covariance matrix +\begin_inset Formula $\Sigma_{ij}$ +\end_inset + +, which is defined in the tangent space +\begin_inset Formula $T_{X_{j}}\mathcal{N}$ +\end_inset + + of the NavState manifold at the NavState +\begin_inset Formula $X_{j}$ +\end_inset + +. + This covariance matrix is computed in the preintegrated measurement class, + of which there are two variants as discussed above. \end_layout \begin_layout Subsubsection* @@ -282,6 +328,14 @@ Gyroscope Covariance : Measurement uncertainty of the gyroscope. \end_layout +\begin_layout Itemize +Gyroscope Bias Covariance +\begin_inset Formula $Q_{\Delta b^{\omega}}$ +\end_inset + + : The covariance associated with the gyroscope bias random walk. +\end_layout + \begin_layout Itemize Accelerometer Covariance \begin_inset Formula $Q_{acc}$ @@ -298,14 +352,6 @@ Accelerometer Bias Covariance : The covariance associated with the accelerometer bias random walk. \end_layout -\begin_layout Itemize -Gyroscope Bias Covariance -\begin_inset Formula $Q_{\Delta b^{\omega}}$ -\end_inset - - : The covariance associated with the gyroscope bias random walk. -\end_layout - \begin_layout Itemize Integration Covariance \begin_inset Formula $Q_{int}$ @@ -1469,7 +1515,12 @@ Noise Propagation in IMU Factor \end_layout \begin_layout Standard -Even when we assume uncorrelated noise on +We wish to compute the ImuFactor covariance matrix +\begin_inset Formula $\Sigma_{ij}$ +\end_inset + +. + Even when we assume uncorrelated noise on \begin_inset Formula $\omega^{b}$ \end_inset @@ -1487,11 +1538,12 @@ Even when we assume uncorrelated noise on \end_inset appear in multiple places. - To model the noise propagation, let us define + To model the noise propagation, let us define the preintegrated navigation + state \begin_inset Formula $\zeta_{k}=[\theta_{k},p_{k},v_{k}]$ \end_inset - and rewrite Eqns. +, as a 9D vector on tangent space at and rewrite Eqns. ( \begin_inset CommandInset ref LatexCommand ref From d5918dcb810982a41659a35b71427869b3f16edd Mon Sep 17 00:00:00 2001 From: John Lambert Date: Sat, 6 Nov 2021 15:31:33 -0400 Subject: [PATCH 0028/1686] Create Similarity2.h --- gtsam/geometry/Similarity2.h | 189 +++++++++++++++++++++++++++++++++++ 1 file changed, 189 insertions(+) create mode 100644 gtsam/geometry/Similarity2.h diff --git a/gtsam/geometry/Similarity2.h b/gtsam/geometry/Similarity2.h new file mode 100644 index 000000000..120e6690a --- /dev/null +++ b/gtsam/geometry/Similarity2.h @@ -0,0 +1,189 @@ +/* ---------------------------------------------------------------------------- + + * 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 Similarity2.h + * @brief Implementation of Similarity2 transform + * @author John Lambert + */ + +#pragma once + +#include +#include +#include +#include +#include +#include + + +namespace gtsam { + +// Forward declarations +class Pose2; + +/** + * 2D similarity transform + */ +class Similarity2: public LieGroup { + + /// @name Pose Concept + /// @{ + typedef Rot2 Rotation; + typedef Point2 Translation; + /// @} + +private: + Rot2 R_; + Point2 t_; + double s_; + +public: + + /// @name Constructors + /// @{ + + /// Default constructor + GTSAM_EXPORT Similarity2(); + + /// Construct pure scaling + GTSAM_EXPORT Similarity2(double s); + + /// Construct from GTSAM types + GTSAM_EXPORT Similarity2(const Rot2& R, const Point2& t, double s); + + /// Construct from Eigen types + GTSAM_EXPORT Similarity2(const Matrix2& R, const Vector2& t, double s); + + /// Construct from matrix [R t; 0 s^-1] + GTSAM_EXPORT Similarity2(const Matrix3& T); + + /// @} + /// @name Testable + /// @{ + + /// Compare with tolerance + GTSAM_EXPORT bool equals(const Similarity2& sim, double tol) const; + + /// Exact equality + GTSAM_EXPORT bool operator==(const Similarity2& other) const; + + /// Print with optional string + GTSAM_EXPORT void print(const std::string& s) const; + + GTSAM_EXPORT friend std::ostream &operator<<(std::ostream &os, const Similarity2& p); + + /// @} + /// @name Group + /// @{ + + /// Return an identity transform + GTSAM_EXPORT static Similarity2 identity(); + + /// Composition + GTSAM_EXPORT Similarity2 operator*(const Similarity2& S) const; + + /// Return the inverse + GTSAM_EXPORT Similarity2 inverse() const; + + /// @} + /// @name Group action on Point2 + /// @{ + + /// Action on a point p is s*(R*p+t) + GTSAM_EXPORT Point2 transformFrom(const Point2& p) const; + + /** + * Action on a pose T. + * |Rs ts| |R t| |Rs*R Rs*t+ts| + * |0 1/s| * |0 1| = | 0 1/s |, the result is still a Sim2 object. + * To retrieve a Pose2, we normalized the scale value into 1. + * |Rs*R Rs*t+ts| |Rs*R s(Rs*t+ts)| + * | 0 1/s | = | 0 1 | + * + * This group action satisfies the compatibility condition. + * For more details, refer to: https://en.wikipedia.org/wiki/Group_action + */ + GTSAM_EXPORT Pose2 transformFrom(const Pose2& T) const; + + /** syntactic sugar for transformFrom */ + GTSAM_EXPORT Point2 operator*(const Point2& p) const; + + /** + * Create Similarity2 by aligning at least two point pairs + */ + GTSAM_EXPORT static Similarity2 Align(const std::vector& abPointPairs); + + /** + * Create the Similarity2 object that aligns at least two pose pairs. + * Each pair is of the form (aTi, bTi). + * Given a list of pairs in frame a, and a list of pairs in frame b, Align() + * will compute the best-fit Similarity2 aSb transformation to align them. + * First, the rotation aRb will be computed as the average (Karcher mean) of + * many estimates aRb (from each pair). Afterwards, the scale factor will be computed + * using the algorithm described here: + * http://www5.informatik.uni-erlangen.de/Forschung/Publikationen/2005/Zinsser05-PSR.pdf + */ + GTSAM_EXPORT static Similarity2 Align(const std::vector& abPosePairs); + + /// @} + /// @name Lie Group + /// @{ + + using LieGroup::inverse; + + /// @} + /// @name Standard interface + /// @{ + + /// Calculate 4*4 matrix group equivalent + GTSAM_EXPORT const Matrix3 matrix() const; + + /// Return a GTSAM rotation + const Rot2& rotation() const { + return R_; + } + + /// Return a GTSAM translation + const Point2& translation() const { + return t_; + } + + /// Return the scale + double scale() const { + return s_; + } + + /// Convert to a rigid body pose (R, s*t) + /// TODO(frank): why is this here? Red flag! Definitely don't have it as a cast. + GTSAM_EXPORT operator Pose2() const; + + /// Dimensionality of tangent space = 4 DOF - used to autodetect sizes + inline static size_t Dim() { + return 4; + } + + /// Dimensionality of tangent space = 4 DOF + inline size_t dim() const { + return 4; + } + + /// @} +}; + + +template<> +struct traits : public internal::LieGroup {}; + +template<> +struct traits : public internal::LieGroup {}; + +} // namespace gtsam From 6b7b31a9121385890efcc395e6fb48a443a214c4 Mon Sep 17 00:00:00 2001 From: John Lambert Date: Sat, 6 Nov 2021 15:32:52 -0400 Subject: [PATCH 0029/1686] Create Similarity2.cpp --- gtsam/geometry/Similarity2.cpp | 203 +++++++++++++++++++++++++++++++++ 1 file changed, 203 insertions(+) create mode 100644 gtsam/geometry/Similarity2.cpp diff --git a/gtsam/geometry/Similarity2.cpp b/gtsam/geometry/Similarity2.cpp new file mode 100644 index 000000000..7970b3190 --- /dev/null +++ b/gtsam/geometry/Similarity2.cpp @@ -0,0 +1,203 @@ +/* ---------------------------------------------------------------------------- + + * 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 Similarity2.cpp + * @brief Implementation of Similarity2 transform + * @author John Lambert + */ + +#include + +#include +#include +#include + +namespace gtsam { + +using std::vector; + +namespace { +/// Subtract centroids from point pairs. +static Point2Pairs subtractCentroids(const Point2Pairs &abPointPairs, + const Point2Pair ¢roids) { + Point2Pairs d_abPointPairs; + for (const Point2Pair& abPair : abPointPairs) { + Point2 da = abPair.first - centroids.first; + Point2 db = abPair.second - centroids.second; + d_abPointPairs.emplace_back(da, db); + } + return d_abPointPairs; +} + +/// Form inner products x and y and calculate scale. +static const double calculateScale(const Point2Pairs &d_abPointPairs, + const Rot2 &aRb) { + double x = 0, y = 0; + Point2 da, db; + for (const Point2Pair& d_abPair : d_abPointPairs) { + std::tie(da, db) = d_abPair; + const Vector2 da_prime = aRb * db; + y += da.transpose() * da_prime; + x += da_prime.transpose() * da_prime; + } + const double s = y / x; + return s; +} + +/// Form outer product H. +static Matrix2 calculateH(const Point2Pairs &d_abPointPairs) { + Matrix2 H = Z_2x2; + for (const Point2Pair& d_abPair : d_abPointPairs) { + H += d_abPair.first * d_abPair.second.transpose(); + } + return H; +} + +/// This method estimates the similarity transform from differences point pairs, +// given a known or estimated rotation and point centroids. +static Similarity2 align(const Point2Pairs &d_abPointPairs, const Rot2 &aRb, + const Point2Pair ¢roids) { + const double s = calculateScale(d_abPointPairs, aRb); + // dividing aTb by s is required because the registration cost function + // minimizes ||a - sRb - t||, whereas Sim(2) computes s(Rb + t) + const Point2 aTb = (centroids.first - s * (aRb * centroids.second)) / s; + return Similarity2(aRb, aTb, s); +} + +/// This method estimates the similarity transform from point pairs, given a known or estimated rotation. +// Refer to: http://www5.informatik.uni-erlangen.de/Forschung/Publikationen/2005/Zinsser05-PSR.pdf Chapter 3 +static Similarity2 alignGivenR(const Point2Pairs &abPointPairs, + const Rot2 &aRb) { + auto centroids = means(abPointPairs); + auto d_abPointPairs = subtractCentroids(abPointPairs, centroids); + return align(d_abPointPairs, aRb, centroids); +} +} // namespace + +Similarity2::Similarity2() : + t_(0,0), s_(1) { +} + +Similarity2::Similarity2(double s) : + t_(0,0), s_(s) { +} + +Similarity2::Similarity2(const Rot2& R, const Point2& t, double s) : + R_(R), t_(t), s_(s) { +} + +Similarity2::Similarity2(const Matrix2& R, const Vector2& t, double s) : + R_(R), t_(t), s_(s) { +} + +Similarity2::Similarity2(const Matrix3& T) : + R_(T.topLeftCorner<2, 2>()), t_(T.topRightCorner<2, 1>()), s_(1.0 / T(2, 2)) { +} + +bool Similarity2::equals(const Similarity2& other, double tol) const { + return R_.equals(other.R_, tol) && traits::Equals(t_, other.t_, tol) + && s_ < (other.s_ + tol) && s_ > (other.s_ - tol); +} + +bool Similarity2::operator==(const Similarity2& other) const { + return R_.matrix() == other.R_.matrix() && t_ == other.t_ && s_ == other.s_; +} + +void Similarity2::print(const std::string& s) const { + std::cout << std::endl; + std::cout << s; + rotation().print("\nR:\n"); + std::cout << "t: " << translation().transpose() << " s: " << scale() << std::endl; +} + +Similarity2 Similarity2::identity() { + return Similarity2(); +} +Similarity2 Similarity2::operator*(const Similarity2& S) const { + return Similarity2(R_ * S.R_, ((1.0 / S.s_) * t_) + R_ * S.t_, s_ * S.s_); +} + +Similarity2 Similarity2::inverse() const { + const Rot2 Rt = R_.inverse(); + const Point2 sRt = Rt * (-s_ * t_); + return Similarity2(Rt, sRt, 1.0 / s_); +} + +Point3 Similarity2::transformFrom(const Point2& p) const { + const Point2 q = R_ * p + t_; + return s_ * q; +} + +Pose2 Similarity2::transformFrom(const Pose2& T) const { + Rot2 R = R_.compose(T.rotation()); + Point2 t = Point2(s_ * (R_ * T.translation() + t_)); + return Pose2(R, t); +} + +Point2 Similarity2::operator*(const Point2& p) const { + return transformFrom(p); +} + +Similarity2 Similarity2::Align(const Point2Pairs &abPointPairs) { + // Refer to Chapter 3 of + // http://www5.informatik.uni-erlangen.de/Forschung/Publikationen/2005/Zinsser05-PSR.pdf + if (abPointPairs.size() < 2) + throw std::runtime_error("input should have at least 2 pairs of points"); + auto centroids = means(abPointPairs); + auto d_abPointPairs = subtractCentroids(abPointPairs, centroids); + Matrix3 H = calculateH(d_abPointPairs); + // ClosestTo finds rotation matrix closest to H in Frobenius sense + Rot2 aRb = Rot2::ClosestTo(H); + return align(d_abPointPairs, aRb, centroids); +} + +Similarity2 Similarity2::Align(const vector &abPosePairs) { + const size_t n = abPosePairs.size(); + if (n < 2) + throw std::runtime_error("input should have at least 2 pairs of poses"); + + // calculate rotation + vector rotations; + Point2Pairs abPointPairs; + rotations.reserve(n); + abPointPairs.reserve(n); + // Below denotes the pose of the i'th object/camera/etc in frame "a" or frame "b" + Pose2 aTi, bTi; + for (const Pose2Pair &abPair : abPosePairs) { + std::tie(aTi, bTi) = abPair; + const Rot2 aRb = aTi.rotation().compose(bTi.rotation().inverse()); + rotations.emplace_back(aRb); + abPointPairs.emplace_back(aTi.translation(), bTi.translation()); + } + const Rot2 aRb_estimate = FindKarcherMean(rotations); + + return alignGivenR(abPointPairs, aRb_estimate); +} + +std::ostream &operator<<(std::ostream &os, const Similarity2& p) { + os << "[" << p.rotation().xyz().transpose() << " " + << p.translation().transpose() << " " << p.scale() << "]\';"; + return os; +} + +const Matrix3 Similarity2::matrix() const { + Matrix3 T; + T.topRows<2>() << R_.matrix(), t_; + T.bottomRows<1>() << 0, 0, 1.0 / s_; + return T; +} + +Similarity2::operator Pose2() const { + return Pose2(R_, s_ * t_); +} + +} // namespace gtsam From e48704d7855e111da019861dbbdb8b9224d5e522 Mon Sep 17 00:00:00 2001 From: John Lambert Date: Sat, 6 Nov 2021 15:44:40 -0400 Subject: [PATCH 0030/1686] add basic Python interface to .i file --- gtsam/geometry/geometry.i | 22 ++++++++++++++++++++++ 1 file changed, 22 insertions(+) diff --git a/gtsam/geometry/geometry.i b/gtsam/geometry/geometry.i index 9baa49e8e..151c42155 100644 --- a/gtsam/geometry/geometry.i +++ b/gtsam/geometry/geometry.i @@ -890,6 +890,28 @@ class PinholeCamera { // enable pickling in python void pickle() const; }; + +#include +class Similarity2 { + // Standard Constructors + Similarity2(); + Similarity2(double s); + Similarity2(const gtsam::Rot2& R, const gtsam::Point2& t, double s); + Similarity2(const Matrix& R, const Vector& t, double s); + Similarity2(const Matrix& T); + + gtsam::Point2 transformFrom(const gtsam::Point2& p) const; + gtsam::Pose2 transformFrom(const gtsam::Pose2& T); + + static gtsam::Similarity2 Align(const gtsam::Point2Pairs& abPointPairs); + static gtsam::Similarity2 Align(const gtsam::Pose2Pairs& abPosePairs); + + // Standard Interface + const Matrix matrix() const; + const gtsam::Rot2& rotation(); + const gtsam::Point2& translation(); + double scale() const; +}; #include class Similarity3 { From 60053906a6016f0ec9e079c41a5c76cf18b70675 Mon Sep 17 00:00:00 2001 From: John Lambert Date: Sat, 6 Nov 2021 16:15:20 -0400 Subject: [PATCH 0031/1686] add python unit tests --- python/gtsam/tests/test_Sim2.py | 196 ++++++++++++++++++++++++++++++++ 1 file changed, 196 insertions(+) create mode 100644 python/gtsam/tests/test_Sim2.py diff --git a/python/gtsam/tests/test_Sim2.py b/python/gtsam/tests/test_Sim2.py new file mode 100644 index 000000000..67bc770d2 --- /dev/null +++ b/python/gtsam/tests/test_Sim2.py @@ -0,0 +1,196 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +Sim3 unit tests. +Author: John Lambert +""" +# pylint: disable=no-name-in-module +import unittest + +import numpy as np + +import gtsam +from gtsam import Point2, Pose2, Pose2Pairs, Rot2, Similarity2 +from gtsam.utils.test_case import GtsamTestCase + + +class TestSim2(GtsamTestCase): + """Test selected Sim2 methods.""" + + def test_align_poses_along_straight_line(self) -> None: + """Test Align Pose2Pairs method. + + Scenario: + 3 object poses + same scale (no gauge ambiguity) + world frame has poses rotated about x-axis (90 degree roll) + world and egovehicle frame translated by 15 meters w.r.t. each other + """ + Rx90 = Rot2.fromDegrees(90) + + # Create source poses (three objects o1, o2, o3 living in the egovehicle "e" frame) + # Suppose they are 3d cuboids detected by an onboard sensor in the egovehicle frame + eTo0 = Pose2(Rot2(), np.array([5, 0])) + eTo1 = Pose2(Rot2(), np.array([10, 0])) + eTo2 = Pose2(Rot2(), np.array([15, 0])) + + eToi_list = [eTo0, eTo1, eTo2] + + # Create destination poses + # (same three objects, but instead living in the world/city "w" frame) + wTo0 = Pose2(Rx90, np.array([-10, 0])) + wTo1 = Pose2(Rx90, np.array([-5, 0])) + wTo2 = Pose2(Rx90, np.array([0, 0])) + + wToi_list = [wTo0, wTo1, wTo2] + + we_pairs = Pose2Pairs(list(zip(wToi_list, eToi_list))) + + # Recover the transformation wSe (i.e. world_S_egovehicle) + wSe = Similarity2.Align(we_pairs) + + for wToi, eToi in zip(wToi_list, eToi_list): + self.gtsamAssertEquals(wToi, wSe.transformFrom(eToi)) + + def test_align_poses_along_straight_line_gauge(self): + """Test if Align Pose3Pairs method can account for gauge ambiguity. + + Scenario: + 3 object poses + with gauge ambiguity (2x scale) + world frame has poses rotated about z-axis (90 degree yaw) + world and egovehicle frame translated by 11 meters w.r.t. each other + """ + Rz90 = Rot3.Rz(np.deg2rad(90)) + + # Create source poses (three objects o1, o2, o3 living in the egovehicle "e" frame) + # Suppose they are 3d cuboids detected by an onboard sensor in the egovehicle frame + eTo0 = Pose2(Rot2(), np.array([1, 0])) + eTo1 = Pose2(Rot2(), np.array([2, 0])) + eTo2 = Pose2(Rot2(), np.array([4, 0])) + + eToi_list = [eTo0, eTo1, eTo2] + + # Create destination poses + # (same three objects, but instead living in the world/city "w" frame) + wTo0 = Pose2(Rz90, np.array([0, 12])) + wTo1 = Pose2(Rz90, np.array([0, 14])) + wTo2 = Pose2(Rz90, np.array([0, 18])) + + wToi_list = [wTo0, wTo1, wTo2] + + we_pairs = Pose2Pairs(list(zip(wToi_list, eToi_list))) + + # Recover the transformation wSe (i.e. world_S_egovehicle) + wSe = Similarity2.Align(we_pairs) + + for wToi, eToi in zip(wToi_list, eToi_list): + self.gtsamAssertEquals(wToi, wSe.transformFrom(eToi)) + + def test_align_poses_scaled_squares(self): + """Test if Align Pose2Pairs method can account for gauge ambiguity. + + Make sure a big and small square can be aligned. + The u's represent a big square (10x10), and v's represents a small square (4x4). + + Scenario: + 4 object poses + with gauge ambiguity (2.5x scale) + """ + # 0, 90, 180, and 270 degrees yaw + R0 = Rot2.fromDegrees(0) + R90 = Rot2.fromDegrees(90) + R180 = Rot2.fromDegrees(180) + R270 = Rot2.fromDegrees(270) + + aTi0 = Pose3(R0, np.array([2, 3])) + aTi1 = Pose3(R90, np.array([12, 3])) + aTi2 = Pose3(R180, np.array([12, 13])) + aTi3 = Pose3(R270, np.array([2, 13])) + + aTi_list = [aTi0, aTi1, aTi2, aTi3] + + bTi0 = Pose2(R0, np.array([4, 3])) + bTi1 = Pose2(R90, np.array([8, 3])) + bTi2 = Pose2(R180, np.array([8, 7])) + bTi3 = Pose2(R270, np.array([4, 7])) + + bTi_list = [bTi0, bTi1, bTi2, bTi3] + + ab_pairs = Pose2Pairs(list(zip(aTi_list, bTi_list))) + + # Recover the transformation wSe (i.e. world_S_egovehicle) + aSb = Similarity2.Align(ab_pairs) + + for aTi, bTi in zip(aTi_list, bTi_list): + self.gtsamAssertEquals(aTi, aSb.transformFrom(bTi)) + + def test_constructor(self) -> None: + """Sim(2) to perform p_b = bSa * p_a""" + bRa = Rot2() + bta = np.array([1, 2]) + bsa = 3.0 + bSa = Similarity2(R=bRa, t=bta, s=bsa) + assert isinstance(bSa, Similarity2) + assert np.allclose(bSa.rotation().matrix(), bRa.matrix()) + assert np.allclose(bSa.translation(), bta) + assert np.allclose(bSa.scale(), bsa) + + def test_is_eq(self) -> None: + """Ensure object equality works properly (are equal).""" + bSa = Similarity2(R=Rot2(), t=np.array([1, 2]), s=3.0) + bSa_ = Similarity2(R=Rot2(), t=np.array([1.0, 2.0]), s=3) + assert bSa == bSa_ + + def test_not_eq_translation(self) -> None: + """Ensure object equality works properly (not equal translation).""" + bSa = Similarity2(R=Rot2(), t=np.array([2, 1]), s=3.0) + bSa_ = Similarity2(R=Rot2(), t=np.array([1.0, 2.0]), s=3) + assert bSa != bSa_ + + def test_not_eq_rotation(self) -> None: + """Ensure object equality works properly (not equal rotation).""" + bSa = Similarity2(R=Rot2(), t=np.array([2, 1]), s=3.0) + bSa_ = Similarity2(R=Rot2.fromDegrees(180), t=np.array([2.0, 1.0]), s=3) + assert bSa != bSa_ + + def test_not_eq_scale(self) -> None: + """Ensure object equality works properly (not equal scale).""" + bSa = Similarity2(R=Rot2(), t=np.array([2, 1]), s=3.0) + bSa_ = Similarity2(R=Rot2(), t=np.array([2.0, 1.0]), s=1.0) + assert bSa != bSa_ + + def test_rotation(self) -> None: + """Ensure rotation component is returned properly.""" + R = Rot2.fromDegrees(90) + t = np.array([1, 2]) + bSa = Similarity2(R=R, t=t, s=3.0) + + # evaluates to [[0, -1], [1, 0]] + expected_R = Rot2.fromDegrees(90) + assert np.allclose(expected_R.matrix(), bSa.rotation().matrix()) + + def test_translation(self) -> None: + """Ensure translation component is returned properly.""" + R = Rot2.fromDegrees(90) + t = np.array([1, 2]) + bSa = Similarity2(R=R, t=t, s=3.0) + + expected_t = np.array([1, 2]) + assert np.allclose(expected_t, bSa.translation()) + + def test_scale(self) -> None: + """Ensure the scale factor is returned properly.""" + bRa = Rot2() + bta = np.array([1, 2]) + bsa = 3.0 + bSa = Similarity2(R=bRa, t=bta, s=bsa) + assert bSa.scale() == 3.0 + + +if __name__ == "__main__": + unittest.main() From 8e9815b2705ed1acb945e46c943426618d92c16f Mon Sep 17 00:00:00 2001 From: John Lambert Date: Sat, 6 Nov 2021 17:35:07 -0400 Subject: [PATCH 0032/1686] fix typo --- gtsam/geometry/Similarity2.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/geometry/Similarity2.cpp b/gtsam/geometry/Similarity2.cpp index 7970b3190..ed6635233 100644 --- a/gtsam/geometry/Similarity2.cpp +++ b/gtsam/geometry/Similarity2.cpp @@ -184,7 +184,7 @@ Similarity2 Similarity2::Align(const vector &abPosePairs) { } std::ostream &operator<<(std::ostream &os, const Similarity2& p) { - os << "[" << p.rotation().xyz().transpose() << " " + os << "[" << p.rotation().theta() << " " << p.translation().transpose() << " " << p.scale() << "]\';"; return os; } From 9fd745156ed761bf6f9a034a2fc9d2967d5093f9 Mon Sep 17 00:00:00 2001 From: John Lambert Date: Sat, 6 Nov 2021 17:37:58 -0400 Subject: [PATCH 0033/1686] add Pose2Pair typedef --- gtsam/geometry/Pose2.h | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/gtsam/geometry/Pose2.h b/gtsam/geometry/Pose2.h index a54951728..12087a34c 100644 --- a/gtsam/geometry/Pose2.h +++ b/gtsam/geometry/Pose2.h @@ -322,6 +322,10 @@ inline Matrix wedge(const Vector& xi) { typedef std::pair Point2Pair; GTSAM_EXPORT boost::optional align(const std::vector& pairs); +// Convenience typedef +using Pose2Pair = std::pair; +using Pose2Pairs = std::vector >; + template <> struct traits : public internal::LieGroup {}; From 7082b67bc3081547a0fb475e2bbdc1b9c008f44d Mon Sep 17 00:00:00 2001 From: John Lambert Date: Sat, 6 Nov 2021 20:38:22 -0400 Subject: [PATCH 0034/1686] fix typo in types --- gtsam/geometry/Similarity2.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/gtsam/geometry/Similarity2.cpp b/gtsam/geometry/Similarity2.cpp index ed6635233..9c051a313 100644 --- a/gtsam/geometry/Similarity2.cpp +++ b/gtsam/geometry/Similarity2.cpp @@ -104,7 +104,7 @@ Similarity2::Similarity2(const Matrix3& T) : } bool Similarity2::equals(const Similarity2& other, double tol) const { - return R_.equals(other.R_, tol) && traits::Equals(t_, other.t_, tol) + return R_.equals(other.R_, tol) && traits::Equals(t_, other.t_, tol) && s_ < (other.s_ + tol) && s_ > (other.s_ - tol); } @@ -132,7 +132,7 @@ Similarity2 Similarity2::inverse() const { return Similarity2(Rt, sRt, 1.0 / s_); } -Point3 Similarity2::transformFrom(const Point2& p) const { +Point2 Similarity2::transformFrom(const Point2& p) const { const Point2 q = R_ * p + t_; return s_ * q; } @@ -160,7 +160,7 @@ Similarity2 Similarity2::Align(const Point2Pairs &abPointPairs) { return align(d_abPointPairs, aRb, centroids); } -Similarity2 Similarity2::Align(const vector &abPosePairs) { +Similarity2 Similarity2::Align(const vector &abPosePairs) { const size_t n = abPosePairs.size(); if (n < 2) throw std::runtime_error("input should have at least 2 pairs of poses"); From 4372ed82f2627b38916a86a5abf375ee13cefac9 Mon Sep 17 00:00:00 2001 From: John Lambert Date: Sat, 6 Nov 2021 20:49:04 -0400 Subject: [PATCH 0035/1686] add means() function to Point2.h --- gtsam/geometry/Point2.h | 3 +++ 1 file changed, 3 insertions(+) diff --git a/gtsam/geometry/Point2.h b/gtsam/geometry/Point2.h index cdb9f4480..d8b6daca8 100644 --- a/gtsam/geometry/Point2.h +++ b/gtsam/geometry/Point2.h @@ -71,6 +71,9 @@ GTSAM_EXPORT boost::optional circleCircleIntersection(double R_d, double * @return list of solutions (0,1, or 2). Identical circles will return empty list, as well. */ GTSAM_EXPORT std::list circleCircleIntersection(Point2 c1, Point2 c2, boost::optional fh); + +/// Calculate the two means of a set of Point2 pairs +GTSAM_EXPORT Point2Pair means(const std::vector &abPointPairs); /** * @brief Intersect 2 circles From 1dd20a39fc59ed248244295da148d585e69b301a Mon Sep 17 00:00:00 2001 From: John Lambert Date: Sat, 6 Nov 2021 21:40:42 -0400 Subject: [PATCH 0036/1686] add missing `means()` function for Point2 --- gtsam/geometry/Point2.cpp | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/gtsam/geometry/Point2.cpp b/gtsam/geometry/Point2.cpp index d8060cfcf..06568e37c 100644 --- a/gtsam/geometry/Point2.cpp +++ b/gtsam/geometry/Point2.cpp @@ -113,6 +113,18 @@ list circleCircleIntersection(Point2 c1, double r1, Point2 c2, return circleCircleIntersection(c1, c2, fh); } +Point2Pair means(const std::vector &abPointPairs) { + const size_t n = abPointPairs.size(); + if (n == 0) throw std::invalid_argument("Point2::mean input Point2Pair vector is empty"); + Point2 aSum(0, 0, 0), bSum(0, 0, 0); + for (const Point2Pair &abPair : abPointPairs) { + aSum += abPair.first; + bSum += abPair.second; + } + const double f = 1.0 / n; + return {aSum * f, bSum * f}; +} + /* ************************************************************************* */ ostream &operator<<(ostream &os, const gtsam::Point2Pair &p) { os << p.first << " <-> " << p.second; From 2252d5ee0d666308ab5cc7dc5407bc25bfcb2cfe Mon Sep 17 00:00:00 2001 From: John Lambert Date: Mon, 8 Nov 2021 13:23:57 -0500 Subject: [PATCH 0037/1686] fix typo in size of mean vector for Point2Pair means() --- gtsam/geometry/Point2.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/geometry/Point2.cpp b/gtsam/geometry/Point2.cpp index 06568e37c..06c32526b 100644 --- a/gtsam/geometry/Point2.cpp +++ b/gtsam/geometry/Point2.cpp @@ -116,7 +116,7 @@ list circleCircleIntersection(Point2 c1, double r1, Point2 c2, Point2Pair means(const std::vector &abPointPairs) { const size_t n = abPointPairs.size(); if (n == 0) throw std::invalid_argument("Point2::mean input Point2Pair vector is empty"); - Point2 aSum(0, 0, 0), bSum(0, 0, 0); + Point2 aSum(0, 0), bSum(0, 0); for (const Point2Pair &abPair : abPointPairs) { aSum += abPair.first; bSum += abPair.second; From 81f1d9315840e0638da10c1397a73cec90b0744e Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Wed, 1 Dec 2021 16:04:49 -0500 Subject: [PATCH 0038/1686] NoiseModelFactorN - fixed-number of variables >6 --- gtsam/mainpage.dox | 2 +- gtsam/nonlinear/NonlinearFactor.h | 106 ++++++++++++++++++++++++++++++ tests/testNonlinearFactor.cpp | 44 +++++++++++++ 3 files changed, 151 insertions(+), 1 deletion(-) diff --git a/gtsam/mainpage.dox b/gtsam/mainpage.dox index ee7bd9924..e07f45f07 100644 --- a/gtsam/mainpage.dox +++ b/gtsam/mainpage.dox @@ -16,7 +16,7 @@ To use GTSAM to solve your own problems, you will often have to create new facto -# The number of variables your factor involves is unknown at compile time - derive from NoiseModelFactor and implement NoiseModelFactor::unwhitenedError() - This is a factor expressing the sum-of-squares error between a measurement \f$ z \f$ and a measurement prediction function \f$ h(x) \f$, on which the errors are expected to follow some distribution specified by a noise model (see noiseModel). --# The number of variables your factor involves is known at compile time and is between 1 and 6 - derive from NoiseModelFactor1, NoiseModelFactor2, NoiseModelFactor3, NoiseModelFactor4, NoiseModelFactor5, or NoiseModelFactor6, and implement \c evaluateError() +-# The number of variables your factor involves is known at compile time and is between 1 and 6 - derive from NoiseModelFactor1, NoiseModelFactor2, NoiseModelFactor3, NoiseModelFactor4, NoiseModelFactor5, or NoiseModelFactor6, and implement \c evaluateError(). If the number of variables is greater than 6, derive from NoiseModelFactorN. - This factor expresses the same sum-of-squares error with a noise model, but makes the implementation task slightly easier than with %NoiseModelFactor. -# Derive from NonlinearFactor - This is more advanced and allows creating factors without an explicit noise model, or that linearize to HessianFactor instead of JacobianFactor. diff --git a/gtsam/nonlinear/NonlinearFactor.h b/gtsam/nonlinear/NonlinearFactor.h index 7fafd95df..503ae7d58 100644 --- a/gtsam/nonlinear/NonlinearFactor.h +++ b/gtsam/nonlinear/NonlinearFactor.h @@ -28,6 +28,7 @@ #include #include +#include namespace gtsam { @@ -770,5 +771,110 @@ private: }; // \class NoiseModelFactor6 /* ************************************************************************* */ +/** A convenient base class for creating your own NoiseModelFactor with N + * variables. To derive from this class, implement evaluateError(). */ +template +class NoiseModelFactorN: public NoiseModelFactor { + +protected: + + typedef NoiseModelFactor Base; + typedef NoiseModelFactorN This; + + /* "Dummy templated" alias is used to expand fixed-type parameter packs with + * same length as VALUES. This ignores the template parameter. */ + template + using optional_matrix_type = boost::optional; + + /* "Dummy templated" alias is used to expand fixed-type parameter packs with + * same length as VALUES. This ignores the template parameter. */ + template + using key_type = Key; + +public: + + /** + * Default Constructor for I/O + */ + NoiseModelFactorN() {} + + /** + * Constructor. + * Example usage: NoiseModelFactorN(noise, key1, key2, ..., keyN) + * @param noiseModel shared pointer to noise model + * @param keys... keys for the variables in this factor + */ + NoiseModelFactorN(const SharedNoiseModel& noiseModel, + key_type... keys) + : Base(noiseModel, std::array{keys...}) {} + + /** + * Constructor. + * @param noiseModel shared pointer to noise model + * @param keys a container of keys for the variables in this factor + */ + template + NoiseModelFactorN(const SharedNoiseModel& noiseModel, CONTAINER keys) + : Base(noiseModel, keys) { + assert(std::size(keys) == sizeof...(VALUES)); + } + + ~NoiseModelFactorN() override {} + + /** Method to retrieve keys */ + template + inline Key key() const { return keys_[N]; } + + /** Calls the n-key specific version of evaluateError, which is pure virtual + * so must be implemented in the derived class. */ + Vector unwhitenedError( + const Values& x, + boost::optional&> H = boost::none) const override { + return unwhitenedError(boost::mp11::index_sequence_for{}, x, H); + } + + /** + * Override this method to finish implementing an n-way factor. + * If any of the optional Matrix reference arguments are specified, it should + * compute both the function evaluation and its derivative(s) in the requested + * variables. + */ + virtual Vector evaluateError( + const VALUES& ... x, + optional_matrix_type ... H) const = 0; + + /** No-jacobians requested function overload (since parameter packs can't have + * default args) */ + Vector evaluateError(const VALUES&... x) const { + return evaluateError(x..., optional_matrix_type()...); + } + + private: + + /** Pack expansion with index_sequence template pattern */ + template + Vector unwhitenedError( + boost::mp11::index_sequence, // + const Values& x, + boost::optional&> H = boost::none) const { + if (this->active(x)) { + if (H) { + return evaluateError(x.at(keys_[Inds])..., (*H)[Inds]...); + } else { + return evaluateError(x.at(keys_[Inds])...); + } + } else { + return Vector::Zero(this->dim()); + } + } + + /** Serialization function */ + friend class boost::serialization::access; + template + void serialize(ARCHIVE & ar, const unsigned int /*version*/) { + ar & boost::serialization::make_nvp("NoiseModelFactor", + boost::serialization::base_object(*this)); + } +}; // \class NoiseModelFactorN } // \namespace gtsam diff --git a/tests/testNonlinearFactor.cpp b/tests/testNonlinearFactor.cpp index 84bba850b..eb35bf55d 100644 --- a/tests/testNonlinearFactor.cpp +++ b/tests/testNonlinearFactor.cpp @@ -406,6 +406,50 @@ TEST(NonlinearFactor, NoiseModelFactor6) { } +/* ************************************************************************* */ +class TestFactorN : public NoiseModelFactorN { +public: + typedef NoiseModelFactorN Base; + TestFactorN() : Base(noiseModel::Diagonal::Sigmas((Vector(1) << 2.0).finished()), X(1), X(2), X(3), X(4)) {} + + Vector + evaluateError(const double& x1, const double& x2, const double& x3, const double& x4, + boost::optional H1 = boost::none, + boost::optional H2 = boost::none, + boost::optional H3 = boost::none, + boost::optional H4 = boost::none) const override { + if (H1) { + *H1 = (Matrix(1, 1) << 1.0).finished(); + *H2 = (Matrix(1, 1) << 2.0).finished(); + *H3 = (Matrix(1, 1) << 3.0).finished(); + *H4 = (Matrix(1, 1) << 4.0).finished(); + } + return (Vector(1) << x1 + x2 + x3 + x4).finished(); + } +}; + +/* ************************************ */ +TEST(NonlinearFactor, NoiseModelFactorN) { + TestFactorN tf; + Values tv; + tv.insert(X(1), double((1.0))); + tv.insert(X(2), double((2.0))); + tv.insert(X(3), double((3.0))); + tv.insert(X(4), double((4.0))); + EXPECT(assert_equal((Vector(1) << 10.0).finished(), tf.unwhitenedError(tv))); + DOUBLES_EQUAL(25.0/2.0, tf.error(tv), 1e-9); + JacobianFactor jf(*boost::dynamic_pointer_cast(tf.linearize(tv))); + LONGS_EQUAL((long)X(1), (long)jf.keys()[0]); + LONGS_EQUAL((long)X(2), (long)jf.keys()[1]); + LONGS_EQUAL((long)X(3), (long)jf.keys()[2]); + LONGS_EQUAL((long)X(4), (long)jf.keys()[3]); + EXPECT(assert_equal((Matrix)(Matrix(1, 1) << 0.5).finished(), jf.getA(jf.begin()))); + EXPECT(assert_equal((Matrix)(Matrix(1, 1) << 1.0).finished(), jf.getA(jf.begin()+1))); + EXPECT(assert_equal((Matrix)(Matrix(1, 1) << 1.5).finished(), jf.getA(jf.begin()+2))); + EXPECT(assert_equal((Matrix)(Matrix(1, 1) << 2.0).finished(), jf.getA(jf.begin()+3))); + EXPECT(assert_equal((Vector)(Vector(1) << -5.0).finished(), jf.getb())); +} + /* ************************************************************************* */ TEST( NonlinearFactor, clone_rekey ) { From e037fa1bdbf49a7c07aeb226caaca11e43fa4be5 Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Wed, 1 Dec 2021 16:20:51 -0500 Subject: [PATCH 0039/1686] c++11 doesn't support std::size so use obj.size() instead --- gtsam/nonlinear/NonlinearFactor.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/nonlinear/NonlinearFactor.h b/gtsam/nonlinear/NonlinearFactor.h index 503ae7d58..b87d1bfaa 100644 --- a/gtsam/nonlinear/NonlinearFactor.h +++ b/gtsam/nonlinear/NonlinearFactor.h @@ -816,7 +816,7 @@ public: template NoiseModelFactorN(const SharedNoiseModel& noiseModel, CONTAINER keys) : Base(noiseModel, keys) { - assert(std::size(keys) == sizeof...(VALUES)); + assert(keys.size() == sizeof...(VALUES)); } ~NoiseModelFactorN() override {} From d9c8ce2721c076805b541746d268e69a99e71bd9 Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Thu, 2 Dec 2021 23:26:34 -0500 Subject: [PATCH 0040/1686] alternate make_index_sequence impl if no boost::mp11 --- gtsam/nonlinear/NonlinearFactor.h | 34 +++++++++++++++++++++++++++++++ 1 file changed, 34 insertions(+) diff --git a/gtsam/nonlinear/NonlinearFactor.h b/gtsam/nonlinear/NonlinearFactor.h index b87d1bfaa..249891397 100644 --- a/gtsam/nonlinear/NonlinearFactor.h +++ b/gtsam/nonlinear/NonlinearFactor.h @@ -28,7 +28,41 @@ #include #include + +#if BOOST_VERSION >= 106600 #include +#else +namespace boost { +namespace mp11 { +// Adapted from https://stackoverflow.com/a/32223343/9151520 +template +struct index_sequence { + using type = index_sequence; + using value_type = size_t; + static constexpr std::size_t size() noexcept { return sizeof...(Ints); } +}; +namespace detail { +template +struct _merge_and_renumber; + +template +struct _merge_and_renumber, index_sequence > + : index_sequence {}; +} // namespace detail +template +struct make_index_sequence + : detail::_merge_and_renumber< + typename make_index_sequence::type, + typename make_index_sequence::type> {}; +template <> +struct make_index_sequence<0> : index_sequence<> {}; +template <> +struct make_index_sequence<1> : index_sequence<0> {}; +template +using index_sequence_for = make_index_sequence; +} // namespace mp11 +} // namespace boost +#endif namespace gtsam { From 2aecaf325805f14e690fcfb83a4a20b579527467 Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Fri, 3 Dec 2021 00:39:10 -0500 Subject: [PATCH 0041/1686] optional jacobian overloads backwards compatibility --- gtsam/nonlinear/NonlinearFactor.h | 17 ++++++++++++-- tests/testNonlinearFactor.cpp | 37 ++++++++++++++++++++++++++----- 2 files changed, 46 insertions(+), 8 deletions(-) diff --git a/gtsam/nonlinear/NonlinearFactor.h b/gtsam/nonlinear/NonlinearFactor.h index 249891397..542c4d5f1 100644 --- a/gtsam/nonlinear/NonlinearFactor.h +++ b/gtsam/nonlinear/NonlinearFactor.h @@ -878,11 +878,24 @@ public: optional_matrix_type ... H) const = 0; /** No-jacobians requested function overload (since parameter packs can't have - * default args) */ - Vector evaluateError(const VALUES&... x) const { + * default args). This specializes the version below to avoid recursive calls + * since this is commonly used. */ + inline Vector evaluateError(const VALUES&... x) const { return evaluateError(x..., optional_matrix_type()...); } + /** Some optional jacobians omitted function overload */ + template 0) && + (sizeof...(OptionalJacArgs) < + sizeof...(VALUES)), + bool>::type = true> + inline Vector evaluateError(const VALUES&... x, + OptionalJacArgs&&... H) const { + return evaluateError(x..., std::forward(H)..., + boost::none); + } + private: /** Pack expansion with index_sequence template pattern */ diff --git a/tests/testNonlinearFactor.cpp b/tests/testNonlinearFactor.cpp index eb35bf55d..8ecbbc397 100644 --- a/tests/testNonlinearFactor.cpp +++ b/tests/testNonlinearFactor.cpp @@ -418,12 +418,10 @@ public: boost::optional H2 = boost::none, boost::optional H3 = boost::none, boost::optional H4 = boost::none) const override { - if (H1) { - *H1 = (Matrix(1, 1) << 1.0).finished(); - *H2 = (Matrix(1, 1) << 2.0).finished(); - *H3 = (Matrix(1, 1) << 3.0).finished(); - *H4 = (Matrix(1, 1) << 4.0).finished(); - } + if (H1) *H1 = (Matrix(1, 1) << 1.0).finished(); + if (H2) *H2 = (Matrix(1, 1) << 2.0).finished(); + if (H3) *H3 = (Matrix(1, 1) << 3.0).finished(); + if (H4) *H4 = (Matrix(1, 1) << 4.0).finished(); return (Vector(1) << x1 + x2 + x3 + x4).finished(); } }; @@ -448,6 +446,33 @@ TEST(NonlinearFactor, NoiseModelFactorN) { EXPECT(assert_equal((Matrix)(Matrix(1, 1) << 1.5).finished(), jf.getA(jf.begin()+2))); EXPECT(assert_equal((Matrix)(Matrix(1, 1) << 2.0).finished(), jf.getA(jf.begin()+3))); EXPECT(assert_equal((Vector)(Vector(1) << -5.0).finished(), jf.getb())); + + // Test all evaluateError argument overloads to ensure backward compatibility + Matrix H1_expected, H2_expected, H3_expected, H4_expected; + Vector e_expected = tf.evaluateError(9, 8, 7, 6, H1_expected, H2_expected, + H3_expected, H4_expected); + + std::unique_ptr> base_ptr( + new TestFactorN(tf)); + Matrix H1, H2, H3, H4; + EXPECT(assert_equal(e_expected, base_ptr->evaluateError(9, 8, 7, 6))); + EXPECT(assert_equal(e_expected, base_ptr->evaluateError(9, 8, 7, 6, H1))); + EXPECT(assert_equal(H1_expected, H1)); + EXPECT(assert_equal(e_expected, // + base_ptr->evaluateError(9, 8, 7, 6, H1, H2))); + EXPECT(assert_equal(H1_expected, H1)); + EXPECT(assert_equal(H2_expected, H2)); + EXPECT(assert_equal(e_expected, + base_ptr->evaluateError(9, 8, 7, 6, H1, H2, H3))); + EXPECT(assert_equal(H1_expected, H1)); + EXPECT(assert_equal(H2_expected, H2)); + EXPECT(assert_equal(H3_expected, H3)); + EXPECT(assert_equal(e_expected, + base_ptr->evaluateError(9, 8, 7, 6, H1, H2, H3, H4))); + EXPECT(assert_equal(H1_expected, H1)); + EXPECT(assert_equal(H2_expected, H2)); + EXPECT(assert_equal(H3_expected, H3)); + EXPECT(assert_equal(H4_expected, H4)); } /* ************************************************************************* */ From 8fe7e48258d69f4cb131c6af7e15504806ebbd4b Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Fri, 3 Dec 2021 00:46:23 -0500 Subject: [PATCH 0042/1686] backward compatibility unit tests for NoiseModelFactor4 --- tests/testNonlinearFactor.cpp | 24 +++++++++++++++++++++++- 1 file changed, 23 insertions(+), 1 deletion(-) diff --git a/tests/testNonlinearFactor.cpp b/tests/testNonlinearFactor.cpp index 8ecbbc397..fda65d56a 100644 --- a/tests/testNonlinearFactor.cpp +++ b/tests/testNonlinearFactor.cpp @@ -255,7 +255,13 @@ TEST( NonlinearFactor, cloneWithNewNoiseModel ) /* ************************************************************************* */ class TestFactor4 : public NoiseModelFactor4 { -public: + static_assert(std::is_same::value, "Base type wrong"); + static_assert( + std::is_same>::value, + "This type wrong"); + + public: typedef NoiseModelFactor4 Base; TestFactor4() : Base(noiseModel::Diagonal::Sigmas((Vector(1) << 2.0).finished()), X(1), X(2), X(3), X(4)) {} @@ -299,6 +305,22 @@ TEST(NonlinearFactor, NoiseModelFactor4) { EXPECT(assert_equal((Matrix)(Matrix(1, 1) << 1.5).finished(), jf.getA(jf.begin()+2))); EXPECT(assert_equal((Matrix)(Matrix(1, 1) << 2.0).finished(), jf.getA(jf.begin()+3))); EXPECT(assert_equal((Vector)(Vector(1) << -5.0).finished(), jf.getb())); + + // Test all functions/types for backwards compatibility + static_assert(std::is_same::value, + "X1 type incorrect"); + static_assert(std::is_same::value, + "X2 type incorrect"); + static_assert(std::is_same::value, + "X3 type incorrect"); + static_assert(std::is_same::value, + "X4 type incorrect"); + EXPECT(assert_equal(tf.key1(), X(1))); + EXPECT(assert_equal(tf.key2(), X(2))); + EXPECT(assert_equal(tf.key3(), X(3))); + EXPECT(assert_equal(tf.key4(), X(4))); + std::vector H = {Matrix(), Matrix(), Matrix(), Matrix()}; + EXPECT(assert_equal(Vector1(10.0), tf.unwhitenedError(tv, H))); } /* ************************************************************************* */ From bee4eeefdd358d07fb7ed02911a58dd5ec3eba33 Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Fri, 3 Dec 2021 02:25:11 -0500 Subject: [PATCH 0043/1686] NoiseModelFactor4 implemented as derived class of NoiseModelFactorN --- gtsam/nonlinear/NonlinearFactor.h | 341 +++++++++++++----------------- 1 file changed, 151 insertions(+), 190 deletions(-) diff --git a/gtsam/nonlinear/NonlinearFactor.h b/gtsam/nonlinear/NonlinearFactor.h index 542c4d5f1..e024a41a0 100644 --- a/gtsam/nonlinear/NonlinearFactor.h +++ b/gtsam/nonlinear/NonlinearFactor.h @@ -309,13 +309,137 @@ public: /* ************************************************************************* */ /** - * A convenient base class for creating your own NoiseModelFactor with 1 - * variable. To derive from this class, implement evaluateError(). + * A convenient base class for creating your own NoiseModelFactor with n + * variables. To derive from this class, implement evaluateError(). * * Templated on a values structure type. The values structures are typically * more general than just vectors, e.g., Rot3 or Pose3, * which are objects in non-linear manifolds (Lie groups). */ +template +class NoiseModelFactorN: public NoiseModelFactor { + public: + /** The type of the N'th template param can be obtained with VALUE */ + template + using VALUE = typename std::tuple_element>::type; + + protected: + typedef NoiseModelFactor Base; + typedef NoiseModelFactorN This; + + /* "Dummy templated" alias is used to expand fixed-type parameter packs with + * same length as VALUES. This ignores the template parameter. */ + template + using optional_matrix_type = boost::optional; + + /* "Dummy templated" alias is used to expand fixed-type parameter packs with + * same length as VALUES. This ignores the template parameter. */ + template + using key_type = Key; + + public: + /** + * Default Constructor for I/O + */ + NoiseModelFactorN() {} + + /** + * Constructor. + * Example usage: NoiseModelFactorN(noise, key1, key2, ..., keyN) + * @param noiseModel shared pointer to noise model + * @param keys... keys for the variables in this factor + */ + NoiseModelFactorN(const SharedNoiseModel& noiseModel, + key_type... keys) + : Base(noiseModel, std::array{keys...}) {} + + /** + * Constructor. + * @param noiseModel shared pointer to noise model + * @param keys a container of keys for the variables in this factor + */ + template + NoiseModelFactorN(const SharedNoiseModel& noiseModel, CONTAINER keys) + : Base(noiseModel, keys) { + assert(keys.size() == sizeof...(VALUES)); + } + + ~NoiseModelFactorN() override {} + + // /** Method to retrieve keys */ + // template + // inline Key key() const { return keys_[N]; } + + /** Calls the n-key specific version of evaluateError, which is pure virtual + * so must be implemented in the derived class. */ + Vector unwhitenedError( + const Values& x, + boost::optional&> H = boost::none) const override { + return unwhitenedError(boost::mp11::index_sequence_for{}, x, H); + } + + /** + * Override this method to finish implementing an n-way factor. + * If any of the optional Matrix reference arguments are specified, it should + * compute both the function evaluation and its derivative(s) in the requested + * variables. + */ + virtual Vector evaluateError( + const VALUES& ... x, + optional_matrix_type ... H) const = 0; + + /** No-jacobians requested function overload (since parameter packs can't have + * default args). This specializes the version below to avoid recursive calls + * since this is commonly used. */ + inline Vector evaluateError(const VALUES&... x) const { + return evaluateError(x..., optional_matrix_type()...); + } + + /** Some optional jacobians omitted function overload */ + template 0) && + (sizeof...(OptionalJacArgs) < + sizeof...(VALUES)), + bool>::type = true> + inline Vector evaluateError(const VALUES&... x, + OptionalJacArgs&&... H) const { + return evaluateError(x..., std::forward(H)..., + boost::none); + } + + private: + + /** Pack expansion with index_sequence template pattern */ + template + Vector unwhitenedError( + boost::mp11::index_sequence, // + const Values& x, + boost::optional&> H = boost::none) const { + if (this->active(x)) { + if (H) { + return evaluateError(x.at(keys_[Inds])..., (*H)[Inds]...); + } else { + return evaluateError(x.at(keys_[Inds])...); + } + } else { + return Vector::Zero(this->dim()); + } + } + + /** Serialization function */ + friend class boost::serialization::access; + template + void serialize(ARCHIVE & ar, const unsigned int /*version*/) { + ar & boost::serialization::make_nvp("NoiseModelFactor", + boost::serialization::base_object(*this)); + } +}; // \class NoiseModelFactorN + + + +/* ************************************************************************* */ +/** A convenient base class for creating your own NoiseModelFactor with 1 + * variable. To derive from this class, implement evaluateError(). */ template class NoiseModelFactor1: public NoiseModelFactor { @@ -552,83 +676,40 @@ private: /* ************************************************************************* */ /** A convenient base class for creating your own NoiseModelFactor with 4 * variables. To derive from this class, implement evaluateError(). */ -template -class NoiseModelFactor4: public NoiseModelFactor { +template +class NoiseModelFactor4 + : public NoiseModelFactorN { + public: + // aliases for value types pulled from keys + using X1 = VALUE1; + using X2 = VALUE2; + using X3 = VALUE3; + using X4 = VALUE4; -public: - - // typedefs for value types pulled from keys - typedef VALUE1 X1; - typedef VALUE2 X2; - typedef VALUE3 X3; - typedef VALUE4 X4; - -protected: - - typedef NoiseModelFactor Base; - typedef NoiseModelFactor4 This; - -public: - - /** - * Default Constructor for I/O - */ - NoiseModelFactor4() {} - - /** - * Constructor - * @param noiseModel shared pointer to noise model - * @param j1 key of the first variable - * @param j2 key of the second variable - * @param j3 key of the third variable - * @param j4 key of the fourth variable - */ - NoiseModelFactor4(const SharedNoiseModel& noiseModel, Key j1, Key j2, Key j3, Key j4) : - Base(noiseModel, cref_list_of<4>(j1)(j2)(j3)(j4)) {} + protected: + using Base = NoiseModelFactor; // grandparent, for backwards compatibility + using This = NoiseModelFactor4; + public: + // inherit NoiseModelFactorN's constructors + using NoiseModelFactorN::NoiseModelFactorN; ~NoiseModelFactor4() override {} /** methods to retrieve keys */ - inline Key key1() const { return keys_[0]; } - inline Key key2() const { return keys_[1]; } - inline Key key3() const { return keys_[2]; } - inline Key key4() const { return keys_[3]; } - - /** Calls the 4-key specific version of evaluateError, which is pure virtual - * so must be implemented in the derived class. */ - Vector unwhitenedError(const Values& x, boost::optional&> H = boost::none) const override { - if(this->active(x)) { - if(H) - return evaluateError(x.at(keys_[0]), x.at(keys_[1]), x.at(keys_[2]), x.at(keys_[3]), (*H)[0], (*H)[1], (*H)[2], (*H)[3]); - else - return evaluateError(x.at(keys_[0]), x.at(keys_[1]), x.at(keys_[2]), x.at(keys_[3])); - } else { - return Vector::Zero(this->dim()); - } - } - - /** - * Override this method to finish implementing a 4-way factor. - * If any of the optional Matrix reference arguments are specified, it should compute - * both the function evaluation and its derivative(s) in X1 (and/or X2, X3). - */ - virtual Vector - evaluateError(const X1&, const X2&, const X3&, const X4&, - boost::optional H1 = boost::none, - boost::optional H2 = boost::none, - boost::optional H3 = boost::none, - boost::optional H4 = boost::none) const = 0; - -private: + inline Key key1() const { return this->keys_[0]; } + inline Key key2() const { return this->keys_[1]; } + inline Key key3() const { return this->keys_[2]; } + inline Key key4() const { return this->keys_[3]; } + private: /** Serialization function */ friend class boost::serialization::access; - template - void serialize(ARCHIVE & ar, const unsigned int /*version*/) { - ar & boost::serialization::make_nvp("NoiseModelFactor", - boost::serialization::base_object(*this)); + template + void serialize(ARCHIVE& ar, const unsigned int /*version*/) { + ar& boost::serialization::make_nvp( + "NoiseModelFactor", boost::serialization::base_object(*this)); } -}; // \class NoiseModelFactor4 +}; // \class NoiseModelFactor4 /* ************************************************************************* */ /** A convenient base class for creating your own NoiseModelFactor with 5 @@ -804,124 +885,4 @@ private: } }; // \class NoiseModelFactor6 -/* ************************************************************************* */ -/** A convenient base class for creating your own NoiseModelFactor with N - * variables. To derive from this class, implement evaluateError(). */ -template -class NoiseModelFactorN: public NoiseModelFactor { - -protected: - - typedef NoiseModelFactor Base; - typedef NoiseModelFactorN This; - - /* "Dummy templated" alias is used to expand fixed-type parameter packs with - * same length as VALUES. This ignores the template parameter. */ - template - using optional_matrix_type = boost::optional; - - /* "Dummy templated" alias is used to expand fixed-type parameter packs with - * same length as VALUES. This ignores the template parameter. */ - template - using key_type = Key; - -public: - - /** - * Default Constructor for I/O - */ - NoiseModelFactorN() {} - - /** - * Constructor. - * Example usage: NoiseModelFactorN(noise, key1, key2, ..., keyN) - * @param noiseModel shared pointer to noise model - * @param keys... keys for the variables in this factor - */ - NoiseModelFactorN(const SharedNoiseModel& noiseModel, - key_type... keys) - : Base(noiseModel, std::array{keys...}) {} - - /** - * Constructor. - * @param noiseModel shared pointer to noise model - * @param keys a container of keys for the variables in this factor - */ - template - NoiseModelFactorN(const SharedNoiseModel& noiseModel, CONTAINER keys) - : Base(noiseModel, keys) { - assert(keys.size() == sizeof...(VALUES)); - } - - ~NoiseModelFactorN() override {} - - /** Method to retrieve keys */ - template - inline Key key() const { return keys_[N]; } - - /** Calls the n-key specific version of evaluateError, which is pure virtual - * so must be implemented in the derived class. */ - Vector unwhitenedError( - const Values& x, - boost::optional&> H = boost::none) const override { - return unwhitenedError(boost::mp11::index_sequence_for{}, x, H); - } - - /** - * Override this method to finish implementing an n-way factor. - * If any of the optional Matrix reference arguments are specified, it should - * compute both the function evaluation and its derivative(s) in the requested - * variables. - */ - virtual Vector evaluateError( - const VALUES& ... x, - optional_matrix_type ... H) const = 0; - - /** No-jacobians requested function overload (since parameter packs can't have - * default args). This specializes the version below to avoid recursive calls - * since this is commonly used. */ - inline Vector evaluateError(const VALUES&... x) const { - return evaluateError(x..., optional_matrix_type()...); - } - - /** Some optional jacobians omitted function overload */ - template 0) && - (sizeof...(OptionalJacArgs) < - sizeof...(VALUES)), - bool>::type = true> - inline Vector evaluateError(const VALUES&... x, - OptionalJacArgs&&... H) const { - return evaluateError(x..., std::forward(H)..., - boost::none); - } - - private: - - /** Pack expansion with index_sequence template pattern */ - template - Vector unwhitenedError( - boost::mp11::index_sequence, // - const Values& x, - boost::optional&> H = boost::none) const { - if (this->active(x)) { - if (H) { - return evaluateError(x.at(keys_[Inds])..., (*H)[Inds]...); - } else { - return evaluateError(x.at(keys_[Inds])...); - } - } else { - return Vector::Zero(this->dim()); - } - } - - /** Serialization function */ - friend class boost::serialization::access; - template - void serialize(ARCHIVE & ar, const unsigned int /*version*/) { - ar & boost::serialization::make_nvp("NoiseModelFactor", - boost::serialization::base_object(*this)); - } -}; // \class NoiseModelFactorN - } // \namespace gtsam From ed07edbfe4ab40fa1d583fe47bfd762818a97ae1 Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Fri, 3 Dec 2021 03:00:47 -0500 Subject: [PATCH 0044/1686] converted all NoiseModelFactorX to inherit from NoiseModelFactorN --- gtsam/nonlinear/NonlinearFactor.h | 502 ++++++++---------------------- 1 file changed, 137 insertions(+), 365 deletions(-) diff --git a/gtsam/nonlinear/NonlinearFactor.h b/gtsam/nonlinear/NonlinearFactor.h index e024a41a0..64ef96b85 100644 --- a/gtsam/nonlinear/NonlinearFactor.h +++ b/gtsam/nonlinear/NonlinearFactor.h @@ -316,16 +316,16 @@ public: * more general than just vectors, e.g., Rot3 or Pose3, * which are objects in non-linear manifolds (Lie groups). */ -template -class NoiseModelFactorN: public NoiseModelFactor { +template +class NoiseModelFactorN : public NoiseModelFactor { public: /** The type of the N'th template param can be obtained with VALUE */ template using VALUE = typename std::tuple_element>::type; protected: - typedef NoiseModelFactor Base; - typedef NoiseModelFactorN This; + using Base = NoiseModelFactor; + using This = NoiseModelFactorN; /* "Dummy templated" alias is used to expand fixed-type parameter packs with * same length as VALUES. This ignores the template parameter. */ @@ -366,9 +366,11 @@ class NoiseModelFactorN: public NoiseModelFactor { ~NoiseModelFactorN() override {} - // /** Method to retrieve keys */ - // template - // inline Key key() const { return keys_[N]; } + /** Method to retrieve keys */ + template + inline Key key() const { + return keys_[N]; + } /** Calls the n-key specific version of evaluateError, which is pure virtual * so must be implemented in the derived class. */ @@ -384,9 +386,8 @@ class NoiseModelFactorN: public NoiseModelFactor { * compute both the function evaluation and its derivative(s) in the requested * variables. */ - virtual Vector evaluateError( - const VALUES& ... x, - optional_matrix_type ... H) const = 0; + virtual Vector evaluateError(const VALUES&... x, + optional_matrix_type... H) const = 0; /** No-jacobians requested function overload (since parameter packs can't have * default args). This specializes the version below to avoid recursive calls @@ -408,7 +409,6 @@ class NoiseModelFactorN: public NoiseModelFactor { } private: - /** Pack expansion with index_sequence template pattern */ template Vector unwhitenedError( @@ -428,250 +428,110 @@ class NoiseModelFactorN: public NoiseModelFactor { /** Serialization function */ friend class boost::serialization::access; - template - void serialize(ARCHIVE & ar, const unsigned int /*version*/) { - ar & boost::serialization::make_nvp("NoiseModelFactor", - boost::serialization::base_object(*this)); + template + void serialize(ARCHIVE& ar, const unsigned int /*version*/) { + ar& boost::serialization::make_nvp( + "NoiseModelFactor", boost::serialization::base_object(*this)); } -}; // \class NoiseModelFactorN - - +}; // \class NoiseModelFactorN /* ************************************************************************* */ /** A convenient base class for creating your own NoiseModelFactor with 1 * variable. To derive from this class, implement evaluateError(). */ -template -class NoiseModelFactor1: public NoiseModelFactor { +template +class NoiseModelFactor1 : public NoiseModelFactorN { + public: + // aliases for value types pulled from keys + using X = VALUE; -public: - - // typedefs for value types pulled from keys - typedef VALUE X; - -protected: - - typedef NoiseModelFactor Base; - typedef NoiseModelFactor1 This; - -public: - /// @name Constructors - /// @{ - - /** Default constructor for I/O only */ - NoiseModelFactor1() {} + protected: + using Base = NoiseModelFactor; // grandparent, for backwards compatibility + using This = NoiseModelFactor1; + public: + // inherit NoiseModelFactorN's constructors + using NoiseModelFactorN::NoiseModelFactorN; ~NoiseModelFactor1() override {} - inline Key key() const { return keys_[0]; } + inline Key key() const { return this->keys_[0]; } - /** - * Constructor - * @param noiseModel shared pointer to noise model - * @param key1 by which to look up X value in Values - */ - NoiseModelFactor1(const SharedNoiseModel &noiseModel, Key key1) - : Base(noiseModel, cref_list_of<1>(key1)) {} - - /// @} - /// @name NoiseModelFactor methods - /// @{ - - /** - * Calls the 1-key specific version of evaluateError below, which is pure - * virtual so must be implemented in the derived class. - */ - Vector unwhitenedError( - const Values &x, - boost::optional &> H = boost::none) const override { - if (this->active(x)) { - const X &x1 = x.at(keys_[0]); - if (H) { - return evaluateError(x1, (*H)[0]); - } else { - return evaluateError(x1); - } - } else { - return Vector::Zero(this->dim()); - } - } - - /// @} - /// @name Virtual methods - /// @{ - - /** - * Override this method to finish implementing a unary factor. - * If the optional Matrix reference argument is specified, it should compute - * both the function evaluation and its derivative in X. - */ - virtual Vector - evaluateError(const X &x, - boost::optional H = boost::none) const = 0; - - /// @} - -private: + private: /** Serialization function */ friend class boost::serialization::access; - template - void serialize(ARCHIVE & ar, const unsigned int /*version*/) { - ar & boost::serialization::make_nvp("NoiseModelFactor", - boost::serialization::base_object(*this)); + template + void serialize(ARCHIVE& ar, const unsigned int /*version*/) { + ar& boost::serialization::make_nvp( + "NoiseModelFactor", boost::serialization::base_object(*this)); } -};// \class NoiseModelFactor1 - +}; // \class NoiseModelFactor1 /* ************************************************************************* */ /** A convenient base class for creating your own NoiseModelFactor with 2 * variables. To derive from this class, implement evaluateError(). */ -template -class NoiseModelFactor2: public NoiseModelFactor { +template +class NoiseModelFactor2 : public NoiseModelFactorN { + public: + // aliases for value types pulled from keys + using X1 = VALUE1; + using X2 = VALUE2; -public: - - // typedefs for value types pulled from keys - typedef VALUE1 X1; - typedef VALUE2 X2; - -protected: - - typedef NoiseModelFactor Base; - typedef NoiseModelFactor2 This; - -public: - - /** - * Default Constructor for I/O - */ - NoiseModelFactor2() {} - - /** - * Constructor - * @param noiseModel shared pointer to noise model - * @param j1 key of the first variable - * @param j2 key of the second variable - */ - NoiseModelFactor2(const SharedNoiseModel& noiseModel, Key j1, Key j2) : - Base(noiseModel, cref_list_of<2>(j1)(j2)) {} + protected: + using Base = NoiseModelFactor; + using This = NoiseModelFactor2; + public: + // inherit NoiseModelFactorN's constructors + using NoiseModelFactorN::NoiseModelFactorN; ~NoiseModelFactor2() override {} /** methods to retrieve both keys */ - inline Key key1() const { return keys_[0]; } - inline Key key2() const { return keys_[1]; } - - /** Calls the 2-key specific version of evaluateError, which is pure virtual - * so must be implemented in the derived class. */ - Vector unwhitenedError(const Values& x, boost::optional&> H = boost::none) const override { - if(this->active(x)) { - const X1& x1 = x.at(keys_[0]); - const X2& x2 = x.at(keys_[1]); - if(H) { - return evaluateError(x1, x2, (*H)[0], (*H)[1]); - } else { - return evaluateError(x1, x2); - } - } else { - return Vector::Zero(this->dim()); - } - } - - /** - * Override this method to finish implementing a binary factor. - * If any of the optional Matrix reference arguments are specified, it should compute - * both the function evaluation and its derivative(s) in X1 (and/or X2). - */ - virtual Vector - evaluateError(const X1&, const X2&, boost::optional H1 = - boost::none, boost::optional H2 = boost::none) const = 0; - -private: + inline Key key1() const { return this->keys_[0]; } + inline Key key2() const { return this->keys_[1]; } + private: /** Serialization function */ friend class boost::serialization::access; - template - void serialize(ARCHIVE & ar, const unsigned int /*version*/) { - ar & boost::serialization::make_nvp("NoiseModelFactor", - boost::serialization::base_object(*this)); + template + void serialize(ARCHIVE& ar, const unsigned int /*version*/) { + ar& boost::serialization::make_nvp( + "NoiseModelFactor", boost::serialization::base_object(*this)); } -}; // \class NoiseModelFactor2 +}; // \class NoiseModelFactor2 /* ************************************************************************* */ /** A convenient base class for creating your own NoiseModelFactor with 3 * variables. To derive from this class, implement evaluateError(). */ -template -class NoiseModelFactor3: public NoiseModelFactor { +template +class NoiseModelFactor3 : public NoiseModelFactorN { + public: + // aliases for value types pulled from keys + using X1 = VALUE1; + using X2 = VALUE2; + using X3 = VALUE3; -public: - - // typedefs for value types pulled from keys - typedef VALUE1 X1; - typedef VALUE2 X2; - typedef VALUE3 X3; - -protected: - - typedef NoiseModelFactor Base; - typedef NoiseModelFactor3 This; - -public: - - /** - * Default Constructor for I/O - */ - NoiseModelFactor3() {} - - /** - * Constructor - * @param noiseModel shared pointer to noise model - * @param j1 key of the first variable - * @param j2 key of the second variable - * @param j3 key of the third variable - */ - NoiseModelFactor3(const SharedNoiseModel& noiseModel, Key j1, Key j2, Key j3) : - Base(noiseModel, cref_list_of<3>(j1)(j2)(j3)) {} + protected: + using Base = NoiseModelFactor; + using This = NoiseModelFactor3; + public: + // inherit NoiseModelFactorN's constructors + using NoiseModelFactorN::NoiseModelFactorN; ~NoiseModelFactor3() override {} /** methods to retrieve keys */ - inline Key key1() const { return keys_[0]; } - inline Key key2() const { return keys_[1]; } - inline Key key3() const { return keys_[2]; } - - /** Calls the 3-key specific version of evaluateError, which is pure virtual - * so must be implemented in the derived class. */ - Vector unwhitenedError(const Values& x, boost::optional&> H = boost::none) const override { - if(this->active(x)) { - if(H) - return evaluateError(x.at(keys_[0]), x.at(keys_[1]), x.at(keys_[2]), (*H)[0], (*H)[1], (*H)[2]); - else - return evaluateError(x.at(keys_[0]), x.at(keys_[1]), x.at(keys_[2])); - } else { - return Vector::Zero(this->dim()); - } - } - - /** - * Override this method to finish implementing a trinary factor. - * If any of the optional Matrix reference arguments are specified, it should compute - * both the function evaluation and its derivative(s) in X1 (and/or X2, X3). - */ - virtual Vector - evaluateError(const X1&, const X2&, const X3&, - boost::optional H1 = boost::none, - boost::optional H2 = boost::none, - boost::optional H3 = boost::none) const = 0; - -private: + inline Key key1() const { return this->keys_[0]; } + inline Key key2() const { return this->keys_[1]; } + inline Key key3() const { return this->keys_[2]; } + private: /** Serialization function */ friend class boost::serialization::access; - template - void serialize(ARCHIVE & ar, const unsigned int /*version*/) { - ar & boost::serialization::make_nvp("NoiseModelFactor", - boost::serialization::base_object(*this)); + template + void serialize(ARCHIVE& ar, const unsigned int /*version*/) { + ar& boost::serialization::make_nvp( + "NoiseModelFactor", boost::serialization::base_object(*this)); } -}; // \class NoiseModelFactor3 +}; // \class NoiseModelFactor3 /* ************************************************************************* */ /** A convenient base class for creating your own NoiseModelFactor with 4 @@ -687,7 +547,7 @@ class NoiseModelFactor4 using X4 = VALUE4; protected: - using Base = NoiseModelFactor; // grandparent, for backwards compatibility + using Base = NoiseModelFactor; using This = NoiseModelFactor4; public: @@ -714,175 +574,87 @@ class NoiseModelFactor4 /* ************************************************************************* */ /** A convenient base class for creating your own NoiseModelFactor with 5 * variables. To derive from this class, implement evaluateError(). */ -template -class NoiseModelFactor5: public NoiseModelFactor { +template +class NoiseModelFactor5 + : public NoiseModelFactorN { + public: + // aliases for value types pulled from keys + using X1 = VALUE1; + using X2 = VALUE2; + using X3 = VALUE3; + using X4 = VALUE4; + using X5 = VALUE5; -public: - - // typedefs for value types pulled from keys - typedef VALUE1 X1; - typedef VALUE2 X2; - typedef VALUE3 X3; - typedef VALUE4 X4; - typedef VALUE5 X5; - -protected: - - typedef NoiseModelFactor Base; - typedef NoiseModelFactor5 This; - -public: - - /** - * Default Constructor for I/O - */ - NoiseModelFactor5() {} - - /** - * Constructor - * @param noiseModel shared pointer to noise model - * @param j1 key of the first variable - * @param j2 key of the second variable - * @param j3 key of the third variable - * @param j4 key of the fourth variable - * @param j5 key of the fifth variable - */ - NoiseModelFactor5(const SharedNoiseModel& noiseModel, Key j1, Key j2, Key j3, Key j4, Key j5) : - Base(noiseModel, cref_list_of<5>(j1)(j2)(j3)(j4)(j5)) {} + protected: + using Base = NoiseModelFactor; + using This = NoiseModelFactor5; + public: + // inherit NoiseModelFactorN's constructors + using NoiseModelFactorN::NoiseModelFactorN; ~NoiseModelFactor5() override {} /** methods to retrieve keys */ - inline Key key1() const { return keys_[0]; } - inline Key key2() const { return keys_[1]; } - inline Key key3() const { return keys_[2]; } - inline Key key4() const { return keys_[3]; } - inline Key key5() const { return keys_[4]; } - - /** Calls the 5-key specific version of evaluateError, which is pure virtual - * so must be implemented in the derived class. */ - Vector unwhitenedError(const Values& x, boost::optional&> H = boost::none) const override { - if(this->active(x)) { - if(H) - return evaluateError(x.at(keys_[0]), x.at(keys_[1]), x.at(keys_[2]), x.at(keys_[3]), x.at(keys_[4]), (*H)[0], (*H)[1], (*H)[2], (*H)[3], (*H)[4]); - else - return evaluateError(x.at(keys_[0]), x.at(keys_[1]), x.at(keys_[2]), x.at(keys_[3]), x.at(keys_[4])); - } else { - return Vector::Zero(this->dim()); - } - } - - /** - * Override this method to finish implementing a 5-way factor. - * If any of the optional Matrix reference arguments are specified, it should compute - * both the function evaluation and its derivative(s) in X1 (and/or X2, X3). - */ - virtual Vector - evaluateError(const X1&, const X2&, const X3&, const X4&, const X5&, - boost::optional H1 = boost::none, - boost::optional H2 = boost::none, - boost::optional H3 = boost::none, - boost::optional H4 = boost::none, - boost::optional H5 = boost::none) const = 0; - -private: + inline Key key1() const { return this->keys_[0]; } + inline Key key2() const { return this->keys_[1]; } + inline Key key3() const { return this->keys_[2]; } + inline Key key4() const { return this->keys_[3]; } + inline Key key5() const { return this->keys_[4]; } + private: /** Serialization function */ friend class boost::serialization::access; - template - void serialize(ARCHIVE & ar, const unsigned int /*version*/) { - ar & boost::serialization::make_nvp("NoiseModelFactor", - boost::serialization::base_object(*this)); + template + void serialize(ARCHIVE& ar, const unsigned int /*version*/) { + ar& boost::serialization::make_nvp( + "NoiseModelFactor", boost::serialization::base_object(*this)); } -}; // \class NoiseModelFactor5 +}; // \class NoiseModelFactor5 /* ************************************************************************* */ /** A convenient base class for creating your own NoiseModelFactor with 6 * variables. To derive from this class, implement evaluateError(). */ -template -class NoiseModelFactor6: public NoiseModelFactor { +template +class NoiseModelFactor6 + : public NoiseModelFactorN { + public: + // aliases for value types pulled from keys + using X1 = VALUE1; + using X2 = VALUE2; + using X3 = VALUE3; + using X4 = VALUE4; + using X5 = VALUE5; + using X6 = VALUE6; -public: - - // typedefs for value types pulled from keys - typedef VALUE1 X1; - typedef VALUE2 X2; - typedef VALUE3 X3; - typedef VALUE4 X4; - typedef VALUE5 X5; - typedef VALUE6 X6; - -protected: - - typedef NoiseModelFactor Base; - typedef NoiseModelFactor6 This; - -public: - - /** - * Default Constructor for I/O - */ - NoiseModelFactor6() {} - - /** - * Constructor - * @param noiseModel shared pointer to noise model - * @param j1 key of the first variable - * @param j2 key of the second variable - * @param j3 key of the third variable - * @param j4 key of the fourth variable - * @param j5 key of the fifth variable - * @param j6 key of the fifth variable - */ - NoiseModelFactor6(const SharedNoiseModel& noiseModel, Key j1, Key j2, Key j3, Key j4, Key j5, Key j6) : - Base(noiseModel, cref_list_of<6>(j1)(j2)(j3)(j4)(j5)(j6)) {} + protected: + using Base = NoiseModelFactor; + using This = + NoiseModelFactor6; + public: + // inherit NoiseModelFactorN's constructors + using NoiseModelFactorN::NoiseModelFactorN; ~NoiseModelFactor6() override {} /** methods to retrieve keys */ - inline Key key1() const { return keys_[0]; } - inline Key key2() const { return keys_[1]; } - inline Key key3() const { return keys_[2]; } - inline Key key4() const { return keys_[3]; } - inline Key key5() const { return keys_[4]; } - inline Key key6() const { return keys_[5]; } - - /** Calls the 6-key specific version of evaluateError, which is pure virtual - * so must be implemented in the derived class. */ - Vector unwhitenedError(const Values& x, boost::optional&> H = boost::none) const override { - if(this->active(x)) { - if(H) - return evaluateError(x.at(keys_[0]), x.at(keys_[1]), x.at(keys_[2]), x.at(keys_[3]), x.at(keys_[4]), x.at(keys_[5]), (*H)[0], (*H)[1], (*H)[2], (*H)[3], (*H)[4], (*H)[5]); - else - return evaluateError(x.at(keys_[0]), x.at(keys_[1]), x.at(keys_[2]), x.at(keys_[3]), x.at(keys_[4]), x.at(keys_[5])); - } else { - return Vector::Zero(this->dim()); - } - } - - /** - * Override this method to finish implementing a 6-way factor. - * If any of the optional Matrix reference arguments are specified, it should compute - * both the function evaluation and its derivative(s) in X1 (and/or X2, X3). - */ - virtual Vector - evaluateError(const X1&, const X2&, const X3&, const X4&, const X5&, const X6&, - boost::optional H1 = boost::none, - boost::optional H2 = boost::none, - boost::optional H3 = boost::none, - boost::optional H4 = boost::none, - boost::optional H5 = boost::none, - boost::optional H6 = boost::none) const = 0; - -private: + inline Key key1() const { return this->keys_[0]; } + inline Key key2() const { return this->keys_[1]; } + inline Key key3() const { return this->keys_[2]; } + inline Key key4() const { return this->keys_[3]; } + inline Key key5() const { return this->keys_[4]; } + inline Key key6() const { return this->keys_[5]; } + private: /** Serialization function */ friend class boost::serialization::access; - template - void serialize(ARCHIVE & ar, const unsigned int /*version*/) { - ar & boost::serialization::make_nvp("NoiseModelFactor", - boost::serialization::base_object(*this)); + template + void serialize(ARCHIVE& ar, const unsigned int /*version*/) { + ar& boost::serialization::make_nvp( + "NoiseModelFactor", boost::serialization::base_object(*this)); } -}; // \class NoiseModelFactor6 +}; // \class NoiseModelFactor6 } // \namespace gtsam From ea7d769476e897f786799c5f774846460e880e19 Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Fri, 3 Dec 2021 05:49:36 -0500 Subject: [PATCH 0045/1686] documentation --- gtsam/nonlinear/NonlinearFactor.h | 136 ++++++++++++++++++++++++------ 1 file changed, 109 insertions(+), 27 deletions(-) diff --git a/gtsam/nonlinear/NonlinearFactor.h b/gtsam/nonlinear/NonlinearFactor.h index 64ef96b85..34e891c64 100644 --- a/gtsam/nonlinear/NonlinearFactor.h +++ b/gtsam/nonlinear/NonlinearFactor.h @@ -307,19 +307,39 @@ public: /* ************************************************************************* */ - /** - * A convenient base class for creating your own NoiseModelFactor with n - * variables. To derive from this class, implement evaluateError(). + * A convenient base class for creating your own NoiseModelFactor + * with n variables. To derive from this class, implement evaluateError(). * - * Templated on a values structure type. The values structures are typically - * more general than just vectors, e.g., Rot3 or Pose3, - * which are objects in non-linear manifolds (Lie groups). + * For example, a 2-way factor could be implemented like so: + * + * ~~~~~~~~~~~~~~~~~~~~{.cpp} + * class MyFactor : public NoiseModelFactorN { + * public: + * using Base = NoiseModelFactorN; + * + * MyFactor(Key key1, Key key2, const SharedNoiseModel& noiseModel) + * : Base(noiseModel, key1, key2) {} + * + * Vector evaluateError( + * const double& x1, const double& x2, + * boost::optional H1 = boost::none, + * boost::optional H2 = boost::none) const override { + * if (H1) *H1 = (Matrix(1, 1) << 1.0).finished(); + * if (H2) *H2 = (Matrix(1, 1) << 2.0).finished(); + * return (Vector(1) << x1 + 2 * x2).finished(); + * } + * }; + * ~~~~~~~~~~~~~~~~~~~~ + * + * These factors are templated on a values structure type. The values structures + * are typically more general than just vectors, e.g., Rot3 or Pose3, which are + * objects in non-linear manifolds (Lie groups). */ template class NoiseModelFactorN : public NoiseModelFactor { public: - /** The type of the N'th template param can be obtained with VALUE */ + /** The type of the N'th template param can be obtained as VALUE */ template using VALUE = typename std::tuple_element>::type; @@ -338,6 +358,9 @@ class NoiseModelFactorN : public NoiseModelFactor { using key_type = Key; public: + /// @name Constructors + /// @{ + /** * Default Constructor for I/O */ @@ -346,8 +369,9 @@ class NoiseModelFactorN : public NoiseModelFactor { /** * Constructor. * Example usage: NoiseModelFactorN(noise, key1, key2, ..., keyN) - * @param noiseModel shared pointer to noise model - * @param keys... keys for the variables in this factor + * @param noiseModel Shared pointer to noise model. + * @param keys Keys for the variables in this factor, passed in as separate + * arguments. */ NoiseModelFactorN(const SharedNoiseModel& noiseModel, key_type... keys) @@ -355,8 +379,8 @@ class NoiseModelFactorN : public NoiseModelFactor { /** * Constructor. - * @param noiseModel shared pointer to noise model - * @param keys a container of keys for the variables in this factor + * @param noiseModel Shared pointer to noise model. + * @param keys A container of keys for the variables in this factor. */ template NoiseModelFactorN(const SharedNoiseModel& noiseModel, CONTAINER keys) @@ -364,6 +388,8 @@ class NoiseModelFactorN : public NoiseModelFactor { assert(keys.size() == sizeof...(VALUES)); } + /// @} + ~NoiseModelFactorN() override {} /** Method to retrieve keys */ @@ -372,26 +398,59 @@ class NoiseModelFactorN : public NoiseModelFactor { return keys_[N]; } + /// @name NoiseModelFactor methods + /// @{ + /** Calls the n-key specific version of evaluateError, which is pure virtual - * so must be implemented in the derived class. */ + * so must be implemented in the derived class. + * @param[in] x A Values object containing the values of all the variables + * used in this factor + * @param[out] H A vector of (dynamic) matrices whose size should be equal to + * n. The jacobians w.r.t. each variable will be output in this parameter. + */ Vector unwhitenedError( const Values& x, boost::optional&> H = boost::none) const override { return unwhitenedError(boost::mp11::index_sequence_for{}, x, H); } + /// @} + /// @name Virtual methods + /// @{ /** * Override this method to finish implementing an n-way factor. + * + * Both the `x` and `H` arguments are written here as parameter packs, but + * when overriding this method, you probably want to explicitly write them + * out. For example, for a 2-way factor with variable types Pose3 and double: + * ``` + * Vector evaluateError(const Pose3& x1, const double& x2, + * boost::optional H1 = boost::none, + * boost::optional H2 = boost::none) const + * override {...} + * ``` + * * If any of the optional Matrix reference arguments are specified, it should * compute both the function evaluation and its derivative(s) in the requested * variables. + * + * @param x The values of the variables to evaluate the error for. Passed in + * as separate arguments. + * @param[out] H The Jacobian with respect to each variable (optional). */ virtual Vector evaluateError(const VALUES&... x, optional_matrix_type... H) const = 0; + /// @} + /// @name Convenience method overloads + /// @{ + /** No-jacobians requested function overload (since parameter packs can't have * default args). This specializes the version below to avoid recursive calls - * since this is commonly used. */ + * since this is commonly used. + * + * e.g. `Vector error = factor.evaluateError(x1, x2, x3);` + */ inline Vector evaluateError(const VALUES&... x) const { return evaluateError(x..., optional_matrix_type()...); } @@ -408,10 +467,14 @@ class NoiseModelFactorN : public NoiseModelFactor { boost::none); } + /// @} + private: - /** Pack expansion with index_sequence template pattern */ + /** Pack expansion with index_sequence template pattern, used to index into + * `keys_` and `H` + */ template - Vector unwhitenedError( + inline Vector unwhitenedError( boost::mp11::index_sequence, // const Values& x, boost::optional&> H = boost::none) const { @@ -436,8 +499,11 @@ class NoiseModelFactorN : public NoiseModelFactor { }; // \class NoiseModelFactorN /* ************************************************************************* */ -/** A convenient base class for creating your own NoiseModelFactor with 1 - * variable. To derive from this class, implement evaluateError(). */ +/** @deprecated: use NoiseModelFactorN, replacing .key1() with .key<1> and X1 + * with VALUE<1>. + * A convenient base class for creating your own NoiseModelFactor + * with 1 variable. To derive from this class, implement evaluateError(). + */ template class NoiseModelFactor1 : public NoiseModelFactorN { public: @@ -453,6 +519,7 @@ class NoiseModelFactor1 : public NoiseModelFactorN { using NoiseModelFactorN::NoiseModelFactorN; ~NoiseModelFactor1() override {} + /** method to retrieve key */ inline Key key() const { return this->keys_[0]; } private: @@ -466,8 +533,11 @@ class NoiseModelFactor1 : public NoiseModelFactorN { }; // \class NoiseModelFactor1 /* ************************************************************************* */ -/** A convenient base class for creating your own NoiseModelFactor with 2 - * variables. To derive from this class, implement evaluateError(). */ +/** @deprecated: use NoiseModelFactorN, replacing .key1() with .key<1> and X1 + * with VALUE<1>. + * A convenient base class for creating your own NoiseModelFactor + * with 2 variables. To derive from this class, implement evaluateError(). + */ template class NoiseModelFactor2 : public NoiseModelFactorN { public: @@ -499,8 +569,11 @@ class NoiseModelFactor2 : public NoiseModelFactorN { }; // \class NoiseModelFactor2 /* ************************************************************************* */ -/** A convenient base class for creating your own NoiseModelFactor with 3 - * variables. To derive from this class, implement evaluateError(). */ +/** @deprecated: use NoiseModelFactorN, replacing .key1() with .key<1> and X1 + * with VALUE<1>. + * A convenient base class for creating your own NoiseModelFactor + * with 3 variables. To derive from this class, implement evaluateError(). + */ template class NoiseModelFactor3 : public NoiseModelFactorN { public: @@ -534,8 +607,11 @@ class NoiseModelFactor3 : public NoiseModelFactorN { }; // \class NoiseModelFactor3 /* ************************************************************************* */ -/** A convenient base class for creating your own NoiseModelFactor with 4 - * variables. To derive from this class, implement evaluateError(). */ +/** @deprecated: use NoiseModelFactorN, replacing .key1() with .key<1> and X1 + * with VALUE<1>. + * A convenient base class for creating your own NoiseModelFactor + * with 4 variables. To derive from this class, implement evaluateError(). + */ template class NoiseModelFactor4 : public NoiseModelFactorN { @@ -572,8 +648,11 @@ class NoiseModelFactor4 }; // \class NoiseModelFactor4 /* ************************************************************************* */ -/** A convenient base class for creating your own NoiseModelFactor with 5 - * variables. To derive from this class, implement evaluateError(). */ +/** @deprecated: use NoiseModelFactorN, replacing .key1() with .key<1> and X1 + * with VALUE<1>. + * A convenient base class for creating your own NoiseModelFactor + * with 5 variables. To derive from this class, implement evaluateError(). + */ template class NoiseModelFactor5 : public NoiseModelFactorN { @@ -613,8 +692,11 @@ class NoiseModelFactor5 }; // \class NoiseModelFactor5 /* ************************************************************************* */ -/** A convenient base class for creating your own NoiseModelFactor with 6 - * variables. To derive from this class, implement evaluateError(). */ +/** @deprecated: use NoiseModelFactorN, replacing .key1() with .key<1> and X1 + * with VALUE<1>. + * A convenient base class for creating your own NoiseModelFactor + * with 6 variables. To derive from this class, implement evaluateError(). + */ template class NoiseModelFactor6 From ba3cc85701aaee6277ae5446e98027f9a1267295 Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Fri, 3 Dec 2021 06:17:14 -0500 Subject: [PATCH 0046/1686] avoid inheritance by conditionally defining backwards compatibility types/funcs in NoiseModelFactorN --- gtsam/nonlinear/NonlinearFactor.h | 566 ++++++++++++++++++------------ tests/testNonlinearFactor.cpp | 44 +++ 2 files changed, 385 insertions(+), 225 deletions(-) diff --git a/gtsam/nonlinear/NonlinearFactor.h b/gtsam/nonlinear/NonlinearFactor.h index 34e891c64..764f1fdf9 100644 --- a/gtsam/nonlinear/NonlinearFactor.h +++ b/gtsam/nonlinear/NonlinearFactor.h @@ -306,6 +306,76 @@ public: }; // \class NoiseModelFactor +/* ************************************************************************* */ +/* We need some helper structs to help us with NoiseModelFactorN - specifically + * we need to alias X1, X2, X3, ... in the templated NoiseModelFactorN class to + * maintain backwards compatibility with NoiseModelFactor1, NoiseModelFactor2, + * NoiseModelFactor3, ... + * + * The tricky part is that we want to _conditionally_ alias these only if the + * `sizeof...(VALUES)` is greater than the index we want to alias (e.g. a 3-way + * factor should only have up to X3). + * + * The approach we use is to create structs which use template specialization to + * conditionally typedef X1, X2, ... for us, then inherit from them to inherit + * the aliases. + * + * Usage: + * ``` + * template + * class MyClass : public AliasX3 { ... }; + * ``` + * This will only typedef X3 if VALUES has at least 3 template parameters. So + * then we can do something like: + * ``` + * int main { + * MyClass::X3 a; // variable a will have type double + * // MyClass::X3 b; // this won't compile + * MyClass::X3 c; // variable c will have type char + * } + * ``` + */ + +// convenience macro extracts the type for the i'th VALUE in a parameter pack +#define GET_VALUE_I(VALUES, I) \ + typename std::tuple_element>::type + +namespace detail { + +// First handle `typedef X`. By default, we do not alias X (empty struct). +template +struct AliasX_ {}; +// But if `1 == sizeof...(VALUES)` is true, then we do alias X by specializing +// for when the first template parameter is true. +template +struct AliasX_<(1 == sizeof...(VALUES)), VALUES...> { + using X = GET_VALUE_I(VALUES, 0); +}; +// We'll alias the "true" template version for convenience. +template +using AliasX = AliasX_; + +// Now do the same thing for X1, X2, ... using a macro. +#define ALIAS_HELPER_X(N) \ + template \ + struct AliasX##N##_ {}; \ + template \ + struct AliasX##N##_<(N <= sizeof...(VALUES)), VALUES...> { \ + using X##N = GET_VALUE_I(VALUES, N - 1); \ + }; \ + template \ + using AliasX##N = AliasX##N##_; +ALIAS_HELPER_X(1); +ALIAS_HELPER_X(2); +ALIAS_HELPER_X(3); +ALIAS_HELPER_X(4); +ALIAS_HELPER_X(5); +ALIAS_HELPER_X(6); +#undef ALIAS_HELPER_X +#undef GET_VALUE_I + +} // namespace detail + /* ************************************************************************* */ /** * A convenient base class for creating your own NoiseModelFactor @@ -337,11 +407,21 @@ public: * objects in non-linear manifolds (Lie groups). */ template -class NoiseModelFactorN : public NoiseModelFactor { +class NoiseModelFactorN : public NoiseModelFactor, + public detail::AliasX, + public detail::AliasX1, + public detail::AliasX2, + public detail::AliasX3, + public detail::AliasX4, + public detail::AliasX5, + public detail::AliasX6 { public: - /** The type of the N'th template param can be obtained as VALUE */ - template - using VALUE = typename std::tuple_element>::type; + /// N is the number of variables (N-way factor) + enum { N = sizeof...(VALUES) }; + + /** The type of the i'th template param can be obtained as VALUE */ + template ::type = true> + using VALUE = typename std::tuple_element>::type; protected: using Base = NoiseModelFactor; @@ -375,28 +455,42 @@ class NoiseModelFactorN : public NoiseModelFactor { */ NoiseModelFactorN(const SharedNoiseModel& noiseModel, key_type... keys) - : Base(noiseModel, std::array{keys...}) {} + : Base(noiseModel, std::array{keys...}) {} /** - * Constructor. + * Constructor. Only enabled for n-ary factors where n > 1. * @param noiseModel Shared pointer to noise model. * @param keys A container of keys for the variables in this factor. */ - template + template 1), bool>::type = true> NoiseModelFactorN(const SharedNoiseModel& noiseModel, CONTAINER keys) : Base(noiseModel, keys) { - assert(keys.size() == sizeof...(VALUES)); + assert(keys.size() == N); } /// @} ~NoiseModelFactorN() override {} - /** Method to retrieve keys */ - template - inline Key key() const { - return keys_[N]; + /** Methods to retrieve keys */ +#define SUB(Old, New) template // to delay template deduction +#define KEY_IF_TRUE(Enable) typename std::enable_if<(Enable), Key>::type + // templated version of `key()` + template + inline KEY_IF_TRUE(I < N) key() const { + return keys_[I]; } + // backwards-compatibility functions + SUB(T, N) inline KEY_IF_TRUE(T == 1) key() const { return keys_[0]; } + SUB(T, N) inline KEY_IF_TRUE(T >= 1) key1() const { return keys_[0]; } + SUB(T, N) inline KEY_IF_TRUE(T >= 2) key2() const { return keys_[1]; } + SUB(T, N) inline KEY_IF_TRUE(T >= 3) key3() const { return keys_[2]; } + SUB(T, N) inline KEY_IF_TRUE(T >= 4) key4() const { return keys_[3]; } + SUB(T, N) inline KEY_IF_TRUE(T >= 5) key5() const { return keys_[4]; } + SUB(T, N) inline KEY_IF_TRUE(T >= 6) key6() const { return keys_[5]; } +#undef SUB +#undef KEY_IF_TRUE /// @name NoiseModelFactor methods /// @{ @@ -458,8 +552,7 @@ class NoiseModelFactorN : public NoiseModelFactor { /** Some optional jacobians omitted function overload */ template 0) && - (sizeof...(OptionalJacArgs) < - sizeof...(VALUES)), + (sizeof...(OptionalJacArgs) < N), bool>::type = true> inline Vector evaluateError(const VALUES&... x, OptionalJacArgs&&... H) const { @@ -498,245 +591,268 @@ class NoiseModelFactorN : public NoiseModelFactor { } }; // \class NoiseModelFactorN -/* ************************************************************************* */ -/** @deprecated: use NoiseModelFactorN, replacing .key1() with .key<1> and X1 - * with VALUE<1>. - * A convenient base class for creating your own NoiseModelFactor - * with 1 variable. To derive from this class, implement evaluateError(). - */ -template -class NoiseModelFactor1 : public NoiseModelFactorN { - public: - // aliases for value types pulled from keys - using X = VALUE; +// template +// using NoiseModelFactor1 = NoiseModelFactorN; +// template +// using NoiseModelFactor2 = NoiseModelFactorN; +// template +// using NoiseModelFactor3 = NoiseModelFactorN; +// template +// using NoiseModelFactor4 = NoiseModelFactorN; +// template +// using NoiseModelFactor5 = +// NoiseModelFactorN; +// template +// using NoiseModelFactor6 = +// NoiseModelFactorN; - protected: - using Base = NoiseModelFactor; // grandparent, for backwards compatibility - using This = NoiseModelFactor1; +#define NoiseModelFactor1 NoiseModelFactorN +#define NoiseModelFactor2 NoiseModelFactorN +#define NoiseModelFactor3 NoiseModelFactorN +#define NoiseModelFactor4 NoiseModelFactorN +#define NoiseModelFactor5 NoiseModelFactorN +#define NoiseModelFactor6 NoiseModelFactorN - public: - // inherit NoiseModelFactorN's constructors - using NoiseModelFactorN::NoiseModelFactorN; - ~NoiseModelFactor1() override {} +// /* ************************************************************************* */ +// /** @deprecated: use NoiseModelFactorN, replacing .key1() with .key<1> and X1 +// * with VALUE<1>. +// * A convenient base class for creating your own NoiseModelFactor +// * with 1 variable. To derive from this class, implement evaluateError(). +// */ +// template +// class NoiseModelFactor1 : public NoiseModelFactorN { +// public: +// // aliases for value types pulled from keys +// using X = VALUE; - /** method to retrieve key */ - inline Key key() const { return this->keys_[0]; } +// protected: +// using Base = NoiseModelFactor; // grandparent, for backwards compatibility +// using This = NoiseModelFactor1; - private: - /** Serialization function */ - friend class boost::serialization::access; - template - void serialize(ARCHIVE& ar, const unsigned int /*version*/) { - ar& boost::serialization::make_nvp( - "NoiseModelFactor", boost::serialization::base_object(*this)); - } -}; // \class NoiseModelFactor1 +// public: +// // inherit NoiseModelFactorN's constructors +// using NoiseModelFactorN::NoiseModelFactorN; +// ~NoiseModelFactor1() override {} -/* ************************************************************************* */ -/** @deprecated: use NoiseModelFactorN, replacing .key1() with .key<1> and X1 - * with VALUE<1>. - * A convenient base class for creating your own NoiseModelFactor - * with 2 variables. To derive from this class, implement evaluateError(). - */ -template -class NoiseModelFactor2 : public NoiseModelFactorN { - public: - // aliases for value types pulled from keys - using X1 = VALUE1; - using X2 = VALUE2; +// /** method to retrieve key */ +// inline Key key() const { return this->keys_[0]; } - protected: - using Base = NoiseModelFactor; - using This = NoiseModelFactor2; +// private: +// /** Serialization function */ +// friend class boost::serialization::access; +// template +// void serialize(ARCHIVE& ar, const unsigned int /*version*/) { +// ar& boost::serialization::make_nvp( +// "NoiseModelFactor", boost::serialization::base_object(*this)); +// } +// }; // \class NoiseModelFactor1 - public: - // inherit NoiseModelFactorN's constructors - using NoiseModelFactorN::NoiseModelFactorN; - ~NoiseModelFactor2() override {} +// /* ************************************************************************* */ +// /** @deprecated: use NoiseModelFactorN, replacing .key1() with .key<1> and X1 +// * with VALUE<1>. +// * A convenient base class for creating your own NoiseModelFactor +// * with 2 variables. To derive from this class, implement evaluateError(). +// */ +// template +// class NoiseModelFactor2 : public NoiseModelFactorN { +// public: +// // aliases for value types pulled from keys +// using X1 = VALUE1; +// using X2 = VALUE2; - /** methods to retrieve both keys */ - inline Key key1() const { return this->keys_[0]; } - inline Key key2() const { return this->keys_[1]; } +// protected: +// using Base = NoiseModelFactor; +// using This = NoiseModelFactor2; - private: - /** Serialization function */ - friend class boost::serialization::access; - template - void serialize(ARCHIVE& ar, const unsigned int /*version*/) { - ar& boost::serialization::make_nvp( - "NoiseModelFactor", boost::serialization::base_object(*this)); - } -}; // \class NoiseModelFactor2 +// public: +// // inherit NoiseModelFactorN's constructors +// using NoiseModelFactorN::NoiseModelFactorN; +// ~NoiseModelFactor2() override {} -/* ************************************************************************* */ -/** @deprecated: use NoiseModelFactorN, replacing .key1() with .key<1> and X1 - * with VALUE<1>. - * A convenient base class for creating your own NoiseModelFactor - * with 3 variables. To derive from this class, implement evaluateError(). - */ -template -class NoiseModelFactor3 : public NoiseModelFactorN { - public: - // aliases for value types pulled from keys - using X1 = VALUE1; - using X2 = VALUE2; - using X3 = VALUE3; +// /** methods to retrieve both keys */ +// inline Key key1() const { return this->keys_[0]; } +// inline Key key2() const { return this->keys_[1]; } - protected: - using Base = NoiseModelFactor; - using This = NoiseModelFactor3; +// private: +// /** Serialization function */ +// friend class boost::serialization::access; +// template +// void serialize(ARCHIVE& ar, const unsigned int /*version*/) { +// ar& boost::serialization::make_nvp( +// "NoiseModelFactor", boost::serialization::base_object(*this)); +// } +// }; // \class NoiseModelFactor2 - public: - // inherit NoiseModelFactorN's constructors - using NoiseModelFactorN::NoiseModelFactorN; - ~NoiseModelFactor3() override {} +// /* ************************************************************************* */ +// /** @deprecated: use NoiseModelFactorN, replacing .key1() with .key<1> and X1 +// * with VALUE<1>. +// * A convenient base class for creating your own NoiseModelFactor +// * with 3 variables. To derive from this class, implement evaluateError(). +// */ +// template +// class NoiseModelFactor3 : public NoiseModelFactorN { +// public: +// // aliases for value types pulled from keys +// using X1 = VALUE1; +// using X2 = VALUE2; +// using X3 = VALUE3; - /** methods to retrieve keys */ - inline Key key1() const { return this->keys_[0]; } - inline Key key2() const { return this->keys_[1]; } - inline Key key3() const { return this->keys_[2]; } +// protected: +// using Base = NoiseModelFactor; +// using This = NoiseModelFactor3; - private: - /** Serialization function */ - friend class boost::serialization::access; - template - void serialize(ARCHIVE& ar, const unsigned int /*version*/) { - ar& boost::serialization::make_nvp( - "NoiseModelFactor", boost::serialization::base_object(*this)); - } -}; // \class NoiseModelFactor3 +// public: +// // inherit NoiseModelFactorN's constructors +// using NoiseModelFactorN::NoiseModelFactorN; +// ~NoiseModelFactor3() override {} -/* ************************************************************************* */ -/** @deprecated: use NoiseModelFactorN, replacing .key1() with .key<1> and X1 - * with VALUE<1>. - * A convenient base class for creating your own NoiseModelFactor - * with 4 variables. To derive from this class, implement evaluateError(). - */ -template -class NoiseModelFactor4 - : public NoiseModelFactorN { - public: - // aliases for value types pulled from keys - using X1 = VALUE1; - using X2 = VALUE2; - using X3 = VALUE3; - using X4 = VALUE4; +// /** methods to retrieve keys */ +// inline Key key1() const { return this->keys_[0]; } +// inline Key key2() const { return this->keys_[1]; } +// inline Key key3() const { return this->keys_[2]; } - protected: - using Base = NoiseModelFactor; - using This = NoiseModelFactor4; +// private: +// /** Serialization function */ +// friend class boost::serialization::access; +// template +// void serialize(ARCHIVE& ar, const unsigned int /*version*/) { +// ar& boost::serialization::make_nvp( +// "NoiseModelFactor", boost::serialization::base_object(*this)); +// } +// }; // \class NoiseModelFactor3 - public: - // inherit NoiseModelFactorN's constructors - using NoiseModelFactorN::NoiseModelFactorN; - ~NoiseModelFactor4() override {} +// /* ************************************************************************* */ +// /** @deprecated: use NoiseModelFactorN, replacing .key1() with .key<1> and X1 +// * with VALUE<1>. +// * A convenient base class for creating your own NoiseModelFactor +// * with 4 variables. To derive from this class, implement evaluateError(). +// */ +// template +// class NoiseModelFactor4 +// : public NoiseModelFactorN { +// public: +// // aliases for value types pulled from keys +// using X1 = VALUE1; +// using X2 = VALUE2; +// using X3 = VALUE3; +// using X4 = VALUE4; - /** methods to retrieve keys */ - inline Key key1() const { return this->keys_[0]; } - inline Key key2() const { return this->keys_[1]; } - inline Key key3() const { return this->keys_[2]; } - inline Key key4() const { return this->keys_[3]; } +// protected: +// using Base = NoiseModelFactor; +// using This = NoiseModelFactor4; - private: - /** Serialization function */ - friend class boost::serialization::access; - template - void serialize(ARCHIVE& ar, const unsigned int /*version*/) { - ar& boost::serialization::make_nvp( - "NoiseModelFactor", boost::serialization::base_object(*this)); - } -}; // \class NoiseModelFactor4 +// public: +// // inherit NoiseModelFactorN's constructors +// using NoiseModelFactorN::NoiseModelFactorN; +// ~NoiseModelFactor4() override {} -/* ************************************************************************* */ -/** @deprecated: use NoiseModelFactorN, replacing .key1() with .key<1> and X1 - * with VALUE<1>. - * A convenient base class for creating your own NoiseModelFactor - * with 5 variables. To derive from this class, implement evaluateError(). - */ -template -class NoiseModelFactor5 - : public NoiseModelFactorN { - public: - // aliases for value types pulled from keys - using X1 = VALUE1; - using X2 = VALUE2; - using X3 = VALUE3; - using X4 = VALUE4; - using X5 = VALUE5; +// /** methods to retrieve keys */ +// inline Key key1() const { return this->keys_[0]; } +// inline Key key2() const { return this->keys_[1]; } +// inline Key key3() const { return this->keys_[2]; } +// inline Key key4() const { return this->keys_[3]; } - protected: - using Base = NoiseModelFactor; - using This = NoiseModelFactor5; +// private: +// /** Serialization function */ +// friend class boost::serialization::access; +// template +// void serialize(ARCHIVE& ar, const unsigned int /*version*/) { +// ar& boost::serialization::make_nvp( +// "NoiseModelFactor", boost::serialization::base_object(*this)); +// } +// }; // \class NoiseModelFactor4 - public: - // inherit NoiseModelFactorN's constructors - using NoiseModelFactorN::NoiseModelFactorN; - ~NoiseModelFactor5() override {} +// /* ************************************************************************* */ +// /** @deprecated: use NoiseModelFactorN, replacing .key1() with .key<1> and X1 +// * with VALUE<1>. +// * A convenient base class for creating your own NoiseModelFactor +// * with 5 variables. To derive from this class, implement evaluateError(). +// */ +// template +// class NoiseModelFactor5 +// : public NoiseModelFactorN { +// public: +// // aliases for value types pulled from keys +// using X1 = VALUE1; +// using X2 = VALUE2; +// using X3 = VALUE3; +// using X4 = VALUE4; +// using X5 = VALUE5; - /** methods to retrieve keys */ - inline Key key1() const { return this->keys_[0]; } - inline Key key2() const { return this->keys_[1]; } - inline Key key3() const { return this->keys_[2]; } - inline Key key4() const { return this->keys_[3]; } - inline Key key5() const { return this->keys_[4]; } +// protected: +// using Base = NoiseModelFactor; +// using This = NoiseModelFactor5; - private: - /** Serialization function */ - friend class boost::serialization::access; - template - void serialize(ARCHIVE& ar, const unsigned int /*version*/) { - ar& boost::serialization::make_nvp( - "NoiseModelFactor", boost::serialization::base_object(*this)); - } -}; // \class NoiseModelFactor5 +// public: +// // inherit NoiseModelFactorN's constructors +// using NoiseModelFactorN::NoiseModelFactorN; +// ~NoiseModelFactor5() override {} -/* ************************************************************************* */ -/** @deprecated: use NoiseModelFactorN, replacing .key1() with .key<1> and X1 - * with VALUE<1>. - * A convenient base class for creating your own NoiseModelFactor - * with 6 variables. To derive from this class, implement evaluateError(). - */ -template -class NoiseModelFactor6 - : public NoiseModelFactorN { - public: - // aliases for value types pulled from keys - using X1 = VALUE1; - using X2 = VALUE2; - using X3 = VALUE3; - using X4 = VALUE4; - using X5 = VALUE5; - using X6 = VALUE6; +// /** methods to retrieve keys */ +// inline Key key1() const { return this->keys_[0]; } +// inline Key key2() const { return this->keys_[1]; } +// inline Key key3() const { return this->keys_[2]; } +// inline Key key4() const { return this->keys_[3]; } +// inline Key key5() const { return this->keys_[4]; } - protected: - using Base = NoiseModelFactor; - using This = - NoiseModelFactor6; +// private: +// /** Serialization function */ +// friend class boost::serialization::access; +// template +// void serialize(ARCHIVE& ar, const unsigned int /*version*/) { +// ar& boost::serialization::make_nvp( +// "NoiseModelFactor", boost::serialization::base_object(*this)); +// } +// }; // \class NoiseModelFactor5 - public: - // inherit NoiseModelFactorN's constructors - using NoiseModelFactorN::NoiseModelFactorN; - ~NoiseModelFactor6() override {} +// /* ************************************************************************* */ +// /** @deprecated: use NoiseModelFactorN, replacing .key1() with .key<1> and X1 +// * with VALUE<1>. +// * A convenient base class for creating your own NoiseModelFactor +// * with 6 variables. To derive from this class, implement evaluateError(). +// */ +// template +// class NoiseModelFactor6 +// : public NoiseModelFactorN { +// public: +// // aliases for value types pulled from keys +// using X1 = VALUE1; +// using X2 = VALUE2; +// using X3 = VALUE3; +// using X4 = VALUE4; +// using X5 = VALUE5; +// using X6 = VALUE6; - /** methods to retrieve keys */ - inline Key key1() const { return this->keys_[0]; } - inline Key key2() const { return this->keys_[1]; } - inline Key key3() const { return this->keys_[2]; } - inline Key key4() const { return this->keys_[3]; } - inline Key key5() const { return this->keys_[4]; } - inline Key key6() const { return this->keys_[5]; } +// protected: +// using Base = NoiseModelFactor; +// using This = +// NoiseModelFactor6; - private: - /** Serialization function */ - friend class boost::serialization::access; - template - void serialize(ARCHIVE& ar, const unsigned int /*version*/) { - ar& boost::serialization::make_nvp( - "NoiseModelFactor", boost::serialization::base_object(*this)); - } -}; // \class NoiseModelFactor6 +// public: +// // inherit NoiseModelFactorN's constructors +// using NoiseModelFactorN::NoiseModelFactorN; +// ~NoiseModelFactor6() override {} + +// /** methods to retrieve keys */ +// inline Key key1() const { return this->keys_[0]; } +// inline Key key2() const { return this->keys_[1]; } +// inline Key key3() const { return this->keys_[2]; } +// inline Key key4() const { return this->keys_[3]; } +// inline Key key5() const { return this->keys_[4]; } +// inline Key key6() const { return this->keys_[5]; } + +// private: +// /** Serialization function */ +// friend class boost::serialization::access; +// template +// void serialize(ARCHIVE& ar, const unsigned int /*version*/) { +// ar& boost::serialization::make_nvp( +// "NoiseModelFactor", boost::serialization::base_object(*this)); +// } +// }; // \class NoiseModelFactor6 } // \namespace gtsam diff --git a/tests/testNonlinearFactor.cpp b/tests/testNonlinearFactor.cpp index fda65d56a..fba7949a1 100644 --- a/tests/testNonlinearFactor.cpp +++ b/tests/testNonlinearFactor.cpp @@ -253,6 +253,50 @@ TEST( NonlinearFactor, cloneWithNewNoiseModel ) CHECK(assert_equal(expected, actual)); } +/* ************************************************************************* */ +class TestFactor1 : public NoiseModelFactor1 { + static_assert(std::is_same::value, "Base type wrong"); + static_assert(std::is_same>::value, + "This type wrong"); + + public: + typedef NoiseModelFactor1 Base; + TestFactor1() : Base(noiseModel::Diagonal::Sigmas(Vector1(2.0)), L(1)) {} + + Vector evaluateError(const double& x1, boost::optional H1 = + boost::none) const override { + if (H1) *H1 = (Matrix(1, 1) << 1.0).finished(); + return (Vector(1) << x1).finished(); + } + + gtsam::NonlinearFactor::shared_ptr clone() const override { + return boost::static_pointer_cast( + gtsam::NonlinearFactor::shared_ptr(new TestFactor1(*this))); + } +}; + +/* ************************************ */ +TEST(NonlinearFactor, NoiseModelFactor1) { + TestFactor1 tf; + Values tv; + tv.insert(L(1), double((1.0))); + EXPECT(assert_equal((Vector(1) << 1.0).finished(), tf.unwhitenedError(tv))); + DOUBLES_EQUAL(0.25 / 2.0, tf.error(tv), 1e-9); + JacobianFactor jf( + *boost::dynamic_pointer_cast(tf.linearize(tv))); + LONGS_EQUAL((long)L(1), (long)jf.keys()[0]); + EXPECT(assert_equal((Matrix)(Matrix(1, 1) << 0.5).finished(), + jf.getA(jf.begin()))); + EXPECT(assert_equal((Vector)(Vector(1) << -0.5).finished(), jf.getb())); + + // Test all functions/types for backwards compatibility + static_assert(std::is_same::value, + "X type incorrect"); + EXPECT(assert_equal(tf.key(), L(1))); + std::vector H = {Matrix()}; + EXPECT(assert_equal(Vector1(1.0), tf.unwhitenedError(tv, H))); +} + /* ************************************************************************* */ class TestFactor4 : public NoiseModelFactor4 { static_assert(std::is_same::value, "Base type wrong"); From ddcca4cdae0220bcbfa299837bbbe68099062f15 Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Fri, 3 Dec 2021 06:46:26 -0500 Subject: [PATCH 0047/1686] switch template bool specialization order --- gtsam/nonlinear/NonlinearFactor.h | 31 ++++++++++++++++--------------- 1 file changed, 16 insertions(+), 15 deletions(-) diff --git a/gtsam/nonlinear/NonlinearFactor.h b/gtsam/nonlinear/NonlinearFactor.h index 764f1fdf9..b925916bb 100644 --- a/gtsam/nonlinear/NonlinearFactor.h +++ b/gtsam/nonlinear/NonlinearFactor.h @@ -314,7 +314,8 @@ public: * * The tricky part is that we want to _conditionally_ alias these only if the * `sizeof...(VALUES)` is greater than the index we want to alias (e.g. a 3-way - * factor should only have up to X3). + * factor should only have up to X3). SFINAE doesn't work in this case with + * aliases so we have to come up with a different approach. * * The approach we use is to create structs which use template specialization to * conditionally typedef X1, X2, ... for us, then inherit from them to inherit @@ -345,26 +346,26 @@ namespace detail { // First handle `typedef X`. By default, we do not alias X (empty struct). template struct AliasX_ {}; -// But if `1 == sizeof...(VALUES)` is true, then we do alias X by specializing -// for when the first template parameter is true. +// But if the first template is true, then we do alias X by specializing. template -struct AliasX_<(1 == sizeof...(VALUES)), VALUES...> { +struct AliasX_ { using X = GET_VALUE_I(VALUES, 0); }; -// We'll alias the "true" template version for convenience. +// We'll alias (for convenience) the correct version based on whether or not +// `1 == sizeof...(VALUES)` is true template -using AliasX = AliasX_; +using AliasX = AliasX_<(1 == sizeof...(VALUES)), VALUES...>; // Now do the same thing for X1, X2, ... using a macro. -#define ALIAS_HELPER_X(N) \ - template \ - struct AliasX##N##_ {}; \ - template \ - struct AliasX##N##_<(N <= sizeof...(VALUES)), VALUES...> { \ - using X##N = GET_VALUE_I(VALUES, N - 1); \ - }; \ - template \ - using AliasX##N = AliasX##N##_; +#define ALIAS_HELPER_X(N) \ + template \ + struct AliasX##N##_ {}; \ + template \ + struct AliasX##N##_ { \ + using X##N = GET_VALUE_I(VALUES, N - 1); \ + }; \ + template \ + using AliasX##N = AliasX##N##_<(N <= sizeof...(VALUES)), VALUES...>; ALIAS_HELPER_X(1); ALIAS_HELPER_X(2); ALIAS_HELPER_X(3); From 280acde2fca26ff09df8acd40b10fae0a774cd1c Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Fri, 3 Dec 2021 07:43:42 -0500 Subject: [PATCH 0048/1686] can't get "using NoiseModelFactorX = NoiseModelFactorN" to work --- gtsam/nonlinear/NonlinearFactor.h | 296 +++++------------------------- 1 file changed, 50 insertions(+), 246 deletions(-) diff --git a/gtsam/nonlinear/NonlinearFactor.h b/gtsam/nonlinear/NonlinearFactor.h index b925916bb..b55ec7856 100644 --- a/gtsam/nonlinear/NonlinearFactor.h +++ b/gtsam/nonlinear/NonlinearFactor.h @@ -592,6 +592,7 @@ class NoiseModelFactorN : public NoiseModelFactor, } }; // \class NoiseModelFactorN +// // `using` does not work for some reason // template // using NoiseModelFactor1 = NoiseModelFactorN; // template @@ -608,252 +609,55 @@ class NoiseModelFactorN : public NoiseModelFactor, // using NoiseModelFactor6 = // NoiseModelFactorN; -#define NoiseModelFactor1 NoiseModelFactorN -#define NoiseModelFactor2 NoiseModelFactorN -#define NoiseModelFactor3 NoiseModelFactorN -#define NoiseModelFactor4 NoiseModelFactorN -#define NoiseModelFactor5 NoiseModelFactorN -#define NoiseModelFactor6 NoiseModelFactorN +// this is visually ugly +template +struct NoiseModelFactor1 : NoiseModelFactorN { + using NoiseModelFactorN::NoiseModelFactorN; + using This = NoiseModelFactor1; +}; +template +struct NoiseModelFactor2 : NoiseModelFactorN { + using NoiseModelFactorN::NoiseModelFactorN; + using This = NoiseModelFactor2; +}; +template +struct NoiseModelFactor3 : NoiseModelFactorN { + using NoiseModelFactorN::NoiseModelFactorN; + using This = NoiseModelFactor3; +}; +template +struct NoiseModelFactor4 : NoiseModelFactorN { + using NoiseModelFactorN::NoiseModelFactorN; + using This = NoiseModelFactor4; +}; +template +struct NoiseModelFactor5 + : NoiseModelFactorN { + using NoiseModelFactorN::NoiseModelFactorN; + using This = NoiseModelFactor5; +}; +template +struct NoiseModelFactor6 + : NoiseModelFactorN { + using NoiseModelFactorN::NoiseModelFactorN; + using This = + NoiseModelFactor6; +}; -// /* ************************************************************************* */ -// /** @deprecated: use NoiseModelFactorN, replacing .key1() with .key<1> and X1 -// * with VALUE<1>. -// * A convenient base class for creating your own NoiseModelFactor -// * with 1 variable. To derive from this class, implement evaluateError(). -// */ -// template -// class NoiseModelFactor1 : public NoiseModelFactorN { -// public: -// // aliases for value types pulled from keys -// using X = VALUE; - -// protected: -// using Base = NoiseModelFactor; // grandparent, for backwards compatibility -// using This = NoiseModelFactor1; - -// public: -// // inherit NoiseModelFactorN's constructors -// using NoiseModelFactorN::NoiseModelFactorN; -// ~NoiseModelFactor1() override {} - -// /** method to retrieve key */ -// inline Key key() const { return this->keys_[0]; } - -// private: -// /** Serialization function */ -// friend class boost::serialization::access; -// template -// void serialize(ARCHIVE& ar, const unsigned int /*version*/) { -// ar& boost::serialization::make_nvp( -// "NoiseModelFactor", boost::serialization::base_object(*this)); -// } -// }; // \class NoiseModelFactor1 - -// /* ************************************************************************* */ -// /** @deprecated: use NoiseModelFactorN, replacing .key1() with .key<1> and X1 -// * with VALUE<1>. -// * A convenient base class for creating your own NoiseModelFactor -// * with 2 variables. To derive from this class, implement evaluateError(). -// */ -// template -// class NoiseModelFactor2 : public NoiseModelFactorN { -// public: -// // aliases for value types pulled from keys -// using X1 = VALUE1; -// using X2 = VALUE2; - -// protected: -// using Base = NoiseModelFactor; -// using This = NoiseModelFactor2; - -// public: -// // inherit NoiseModelFactorN's constructors -// using NoiseModelFactorN::NoiseModelFactorN; -// ~NoiseModelFactor2() override {} - -// /** methods to retrieve both keys */ -// inline Key key1() const { return this->keys_[0]; } -// inline Key key2() const { return this->keys_[1]; } - -// private: -// /** Serialization function */ -// friend class boost::serialization::access; -// template -// void serialize(ARCHIVE& ar, const unsigned int /*version*/) { -// ar& boost::serialization::make_nvp( -// "NoiseModelFactor", boost::serialization::base_object(*this)); -// } -// }; // \class NoiseModelFactor2 - -// /* ************************************************************************* */ -// /** @deprecated: use NoiseModelFactorN, replacing .key1() with .key<1> and X1 -// * with VALUE<1>. -// * A convenient base class for creating your own NoiseModelFactor -// * with 3 variables. To derive from this class, implement evaluateError(). -// */ -// template -// class NoiseModelFactor3 : public NoiseModelFactorN { -// public: -// // aliases for value types pulled from keys -// using X1 = VALUE1; -// using X2 = VALUE2; -// using X3 = VALUE3; - -// protected: -// using Base = NoiseModelFactor; -// using This = NoiseModelFactor3; - -// public: -// // inherit NoiseModelFactorN's constructors -// using NoiseModelFactorN::NoiseModelFactorN; -// ~NoiseModelFactor3() override {} - -// /** methods to retrieve keys */ -// inline Key key1() const { return this->keys_[0]; } -// inline Key key2() const { return this->keys_[1]; } -// inline Key key3() const { return this->keys_[2]; } - -// private: -// /** Serialization function */ -// friend class boost::serialization::access; -// template -// void serialize(ARCHIVE& ar, const unsigned int /*version*/) { -// ar& boost::serialization::make_nvp( -// "NoiseModelFactor", boost::serialization::base_object(*this)); -// } -// }; // \class NoiseModelFactor3 - -// /* ************************************************************************* */ -// /** @deprecated: use NoiseModelFactorN, replacing .key1() with .key<1> and X1 -// * with VALUE<1>. -// * A convenient base class for creating your own NoiseModelFactor -// * with 4 variables. To derive from this class, implement evaluateError(). -// */ -// template -// class NoiseModelFactor4 -// : public NoiseModelFactorN { -// public: -// // aliases for value types pulled from keys -// using X1 = VALUE1; -// using X2 = VALUE2; -// using X3 = VALUE3; -// using X4 = VALUE4; - -// protected: -// using Base = NoiseModelFactor; -// using This = NoiseModelFactor4; - -// public: -// // inherit NoiseModelFactorN's constructors -// using NoiseModelFactorN::NoiseModelFactorN; -// ~NoiseModelFactor4() override {} - -// /** methods to retrieve keys */ -// inline Key key1() const { return this->keys_[0]; } -// inline Key key2() const { return this->keys_[1]; } -// inline Key key3() const { return this->keys_[2]; } -// inline Key key4() const { return this->keys_[3]; } - -// private: -// /** Serialization function */ -// friend class boost::serialization::access; -// template -// void serialize(ARCHIVE& ar, const unsigned int /*version*/) { -// ar& boost::serialization::make_nvp( -// "NoiseModelFactor", boost::serialization::base_object(*this)); -// } -// }; // \class NoiseModelFactor4 - -// /* ************************************************************************* */ -// /** @deprecated: use NoiseModelFactorN, replacing .key1() with .key<1> and X1 -// * with VALUE<1>. -// * A convenient base class for creating your own NoiseModelFactor -// * with 5 variables. To derive from this class, implement evaluateError(). -// */ -// template -// class NoiseModelFactor5 -// : public NoiseModelFactorN { -// public: -// // aliases for value types pulled from keys -// using X1 = VALUE1; -// using X2 = VALUE2; -// using X3 = VALUE3; -// using X4 = VALUE4; -// using X5 = VALUE5; - -// protected: -// using Base = NoiseModelFactor; -// using This = NoiseModelFactor5; - -// public: -// // inherit NoiseModelFactorN's constructors -// using NoiseModelFactorN::NoiseModelFactorN; -// ~NoiseModelFactor5() override {} - -// /** methods to retrieve keys */ -// inline Key key1() const { return this->keys_[0]; } -// inline Key key2() const { return this->keys_[1]; } -// inline Key key3() const { return this->keys_[2]; } -// inline Key key4() const { return this->keys_[3]; } -// inline Key key5() const { return this->keys_[4]; } - -// private: -// /** Serialization function */ -// friend class boost::serialization::access; -// template -// void serialize(ARCHIVE& ar, const unsigned int /*version*/) { -// ar& boost::serialization::make_nvp( -// "NoiseModelFactor", boost::serialization::base_object(*this)); -// } -// }; // \class NoiseModelFactor5 - -// /* ************************************************************************* */ -// /** @deprecated: use NoiseModelFactorN, replacing .key1() with .key<1> and X1 -// * with VALUE<1>. -// * A convenient base class for creating your own NoiseModelFactor -// * with 6 variables. To derive from this class, implement evaluateError(). -// */ -// template -// class NoiseModelFactor6 -// : public NoiseModelFactorN { -// public: -// // aliases for value types pulled from keys -// using X1 = VALUE1; -// using X2 = VALUE2; -// using X3 = VALUE3; -// using X4 = VALUE4; -// using X5 = VALUE5; -// using X6 = VALUE6; - -// protected: -// using Base = NoiseModelFactor; -// using This = -// NoiseModelFactor6; - -// public: -// // inherit NoiseModelFactorN's constructors -// using NoiseModelFactorN::NoiseModelFactorN; -// ~NoiseModelFactor6() override {} - -// /** methods to retrieve keys */ -// inline Key key1() const { return this->keys_[0]; } -// inline Key key2() const { return this->keys_[1]; } -// inline Key key3() const { return this->keys_[2]; } -// inline Key key4() const { return this->keys_[3]; } -// inline Key key5() const { return this->keys_[4]; } -// inline Key key6() const { return this->keys_[5]; } - -// private: -// /** Serialization function */ -// friend class boost::serialization::access; -// template -// void serialize(ARCHIVE& ar, const unsigned int /*version*/) { -// ar& boost::serialization::make_nvp( -// "NoiseModelFactor", boost::serialization::base_object(*this)); -// } -// }; // \class NoiseModelFactor6 +/* ************************************************************************* */ +/** @deprecated: use NoiseModelFactorN + * Convenient base classes for creating your own NoiseModelFactors with 1-6 + * variables. To derive from these classes, implement evaluateError(). + */ +// // This has the side-effect that you could e.g. NoiseModelFactor6 +// #define NoiseModelFactor1 NoiseModelFactorN +// #define NoiseModelFactor2 NoiseModelFactorN +// #define NoiseModelFactor3 NoiseModelFactorN +// #define NoiseModelFactor4 NoiseModelFactorN +// #define NoiseModelFactor5 NoiseModelFactorN +// #define NoiseModelFactor6 NoiseModelFactorN } // \namespace gtsam From dfb9497d8162206f2dd419f218e4bf6c435f04d5 Mon Sep 17 00:00:00 2001 From: John Lambert Date: Tue, 7 Dec 2021 11:53:34 -0700 Subject: [PATCH 0049/1686] add Rot2.ClosestTo() --- gtsam/geometry/Rot2.h | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/gtsam/geometry/Rot2.h b/gtsam/geometry/Rot2.h index ec30c6657..42dba3487 100644 --- a/gtsam/geometry/Rot2.h +++ b/gtsam/geometry/Rot2.h @@ -14,6 +14,7 @@ * @brief 2D rotation * @date Dec 9, 2009 * @author Frank Dellaert + * @author John Lambert */ #pragma once @@ -208,6 +209,9 @@ namespace gtsam { /** return 2*2 transpose (inverse) rotation matrix */ Matrix2 transpose() const; + + /** Find closest valid rotation matrix, given a 2x2 matrix */ + static Rot2 ClosestTo(const Matrix2& M); private: /** Serialization function */ From 37af8cfbecf7bf05446976e485f44f0396c2a819 Mon Sep 17 00:00:00 2001 From: John Lambert Date: Tue, 7 Dec 2021 11:59:28 -0700 Subject: [PATCH 0050/1686] finish Rot2.ClosestTo() --- gtsam/geometry/Rot2.cpp | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/gtsam/geometry/Rot2.cpp b/gtsam/geometry/Rot2.cpp index 283147e4c..f8ec9c9e6 100644 --- a/gtsam/geometry/Rot2.cpp +++ b/gtsam/geometry/Rot2.cpp @@ -129,6 +129,14 @@ Rot2 Rot2::relativeBearing(const Point2& d, OptionalJacobian<1, 2> H) { } } +/* ************************************************************************* */ +static Rot2 ClosestTo(const Matrix2& M) { + double theta_rad = atan2(M(0,0), M(1,0)); + double c = cos(theta_rad); + double s = sin(theta_rad); + return Rot2::fromCosSin(c, s); +} + /* ************************************************************************* */ } // gtsam From 68535708af01697ff92ebd0d01b536f4687db728 Mon Sep 17 00:00:00 2001 From: John Lambert Date: Tue, 7 Dec 2021 13:31:39 -0700 Subject: [PATCH 0051/1686] fix typo --- gtsam/geometry/Rot2.cpp | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/gtsam/geometry/Rot2.cpp b/gtsam/geometry/Rot2.cpp index f8ec9c9e6..9f62869e4 100644 --- a/gtsam/geometry/Rot2.cpp +++ b/gtsam/geometry/Rot2.cpp @@ -131,9 +131,11 @@ Rot2 Rot2::relativeBearing(const Point2& d, OptionalJacobian<1, 2> H) { /* ************************************************************************* */ static Rot2 ClosestTo(const Matrix2& M) { - double theta_rad = atan2(M(0,0), M(1,0)); - double c = cos(theta_rad); - double s = sin(theta_rad); + double c = M(0,0); + double s = M(1,0); + double theta_rad = atan2(s, c); + c = cos(theta_rad); + s = sin(theta_rad); return Rot2::fromCosSin(c, s); } From c2040fb910f7fd6e2f012084ccfa8c19facf652d Mon Sep 17 00:00:00 2001 From: John Lambert Date: Tue, 7 Dec 2021 13:34:06 -0700 Subject: [PATCH 0052/1686] use ClosestTo() in initializer list --- gtsam/geometry/Similarity2.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/geometry/Similarity2.cpp b/gtsam/geometry/Similarity2.cpp index 9c051a313..1ed0dd1b0 100644 --- a/gtsam/geometry/Similarity2.cpp +++ b/gtsam/geometry/Similarity2.cpp @@ -96,7 +96,7 @@ Similarity2::Similarity2(const Rot2& R, const Point2& t, double s) : } Similarity2::Similarity2(const Matrix2& R, const Vector2& t, double s) : - R_(R), t_(t), s_(s) { + R_(Rot2.ClosestTo(R)), t_(t), s_(s) { } Similarity2::Similarity2(const Matrix3& T) : From 7ebbe1869eeac0393c5e992944f672d0ac093db5 Mon Sep 17 00:00:00 2001 From: John Lambert Date: Tue, 7 Dec 2021 19:07:50 -0500 Subject: [PATCH 0053/1686] fix Eigen error --- gtsam/geometry/Similarity2.cpp | 83 +++++++++++++++++----------------- gtsam/geometry/Similarity2.h | 54 +++++++++++----------- 2 files changed, 69 insertions(+), 68 deletions(-) diff --git a/gtsam/geometry/Similarity2.cpp b/gtsam/geometry/Similarity2.cpp index 1ed0dd1b0..5a63e70cb 100644 --- a/gtsam/geometry/Similarity2.cpp +++ b/gtsam/geometry/Similarity2.cpp @@ -17,6 +17,7 @@ #include +#include #include #include #include @@ -95,13 +96,13 @@ Similarity2::Similarity2(const Rot2& R, const Point2& t, double s) : R_(R), t_(t), s_(s) { } -Similarity2::Similarity2(const Matrix2& R, const Vector2& t, double s) : - R_(Rot2.ClosestTo(R)), t_(t), s_(s) { -} +// Similarity2::Similarity2(const Matrix2& R, const Vector2& t, double s) : +// R_(Rot2::ClosestTo(R)), t_(t), s_(s) { +// } -Similarity2::Similarity2(const Matrix3& T) : - R_(T.topLeftCorner<2, 2>()), t_(T.topRightCorner<2, 1>()), s_(1.0 / T(2, 2)) { -} +// Similarity2::Similarity2(const Matrix3& T) : +// R_(Rot2::ClosestTo(T.topLeftCorner<2, 2>())), t_(T.topRightCorner<2, 1>()), s_(1.0 / T(2, 2)) { +// } bool Similarity2::equals(const Similarity2& other, double tol) const { return R_.equals(other.R_, tol) && traits::Equals(t_, other.t_, tol) @@ -122,9 +123,9 @@ void Similarity2::print(const std::string& s) const { Similarity2 Similarity2::identity() { return Similarity2(); } -Similarity2 Similarity2::operator*(const Similarity2& S) const { - return Similarity2(R_ * S.R_, ((1.0 / S.s_) * t_) + R_ * S.t_, s_ * S.s_); -} +// Similarity2 Similarity2::operator*(const Similarity2& S) const { +// return Similarity2(R_ * S.R_, ((1.0 / S.s_) * t_) + R_ * S.t_, s_ * S.s_); +// } Similarity2 Similarity2::inverse() const { const Rot2 Rt = R_.inverse(); @@ -147,41 +148,41 @@ Point2 Similarity2::operator*(const Point2& p) const { return transformFrom(p); } -Similarity2 Similarity2::Align(const Point2Pairs &abPointPairs) { - // Refer to Chapter 3 of - // http://www5.informatik.uni-erlangen.de/Forschung/Publikationen/2005/Zinsser05-PSR.pdf - if (abPointPairs.size() < 2) - throw std::runtime_error("input should have at least 2 pairs of points"); - auto centroids = means(abPointPairs); - auto d_abPointPairs = subtractCentroids(abPointPairs, centroids); - Matrix3 H = calculateH(d_abPointPairs); - // ClosestTo finds rotation matrix closest to H in Frobenius sense - Rot2 aRb = Rot2::ClosestTo(H); - return align(d_abPointPairs, aRb, centroids); -} +// Similarity2 Similarity2::Align(const Point2Pairs &abPointPairs) { +// // Refer to Chapter 3 of +// // http://www5.informatik.uni-erlangen.de/Forschung/Publikationen/2005/Zinsser05-PSR.pdf +// if (abPointPairs.size() < 2) +// throw std::runtime_error("input should have at least 2 pairs of points"); +// auto centroids = means(abPointPairs); +// auto d_abPointPairs = subtractCentroids(abPointPairs, centroids); +// Matrix3 H = calculateH(d_abPointPairs); +// // ClosestTo finds rotation matrix closest to H in Frobenius sense +// Rot2 aRb = Rot2::ClosestTo(H); +// return align(d_abPointPairs, aRb, centroids); +// } -Similarity2 Similarity2::Align(const vector &abPosePairs) { - const size_t n = abPosePairs.size(); - if (n < 2) - throw std::runtime_error("input should have at least 2 pairs of poses"); +// Similarity2 Similarity2::Align(const vector &abPosePairs) { +// const size_t n = abPosePairs.size(); +// if (n < 2) +// throw std::runtime_error("input should have at least 2 pairs of poses"); - // calculate rotation - vector rotations; - Point2Pairs abPointPairs; - rotations.reserve(n); - abPointPairs.reserve(n); - // Below denotes the pose of the i'th object/camera/etc in frame "a" or frame "b" - Pose2 aTi, bTi; - for (const Pose2Pair &abPair : abPosePairs) { - std::tie(aTi, bTi) = abPair; - const Rot2 aRb = aTi.rotation().compose(bTi.rotation().inverse()); - rotations.emplace_back(aRb); - abPointPairs.emplace_back(aTi.translation(), bTi.translation()); - } - const Rot2 aRb_estimate = FindKarcherMean(rotations); +// // calculate rotation +// vector rotations; +// Point2Pairs abPointPairs; +// rotations.reserve(n); +// abPointPairs.reserve(n); +// // Below denotes the pose of the i'th object/camera/etc in frame "a" or frame "b" +// Pose2 aTi, bTi; +// for (const Pose2Pair &abPair : abPosePairs) { +// std::tie(aTi, bTi) = abPair; +// const Rot2 aRb = aTi.rotation().compose(bTi.rotation().inverse()); +// rotations.emplace_back(aRb); +// abPointPairs.emplace_back(aTi.translation(), bTi.translation()); +// } +// const Rot2 aRb_estimate = FindKarcherMean(rotations); - return alignGivenR(abPointPairs, aRb_estimate); -} +// return alignGivenR(abPointPairs, aRb_estimate); +// } std::ostream &operator<<(std::ostream &os, const Similarity2& p) { os << "[" << p.rotation().theta() << " " diff --git a/gtsam/geometry/Similarity2.h b/gtsam/geometry/Similarity2.h index 120e6690a..85a6324c5 100644 --- a/gtsam/geometry/Similarity2.h +++ b/gtsam/geometry/Similarity2.h @@ -60,11 +60,11 @@ public: /// Construct from GTSAM types GTSAM_EXPORT Similarity2(const Rot2& R, const Point2& t, double s); - /// Construct from Eigen types - GTSAM_EXPORT Similarity2(const Matrix2& R, const Vector2& t, double s); + // /// Construct from Eigen types + // GTSAM_EXPORT Similarity2(const Matrix2& R, const Vector2& t, double s); - /// Construct from matrix [R t; 0 s^-1] - GTSAM_EXPORT Similarity2(const Matrix3& T); + // /// Construct from matrix [R t; 0 s^-1] + // GTSAM_EXPORT Similarity2(const Matrix3& T); /// @} /// @name Testable @@ -94,9 +94,9 @@ public: /// Return the inverse GTSAM_EXPORT Similarity2 inverse() const; - /// @} - /// @name Group action on Point2 - /// @{ + // /// @} + // /// @name Group action on Point2 + // /// @{ /// Action on a point p is s*(R*p+t) GTSAM_EXPORT Point2 transformFrom(const Point2& p) const; @@ -114,25 +114,25 @@ public: */ GTSAM_EXPORT Pose2 transformFrom(const Pose2& T) const; - /** syntactic sugar for transformFrom */ + /* syntactic sugar for transformFrom */ GTSAM_EXPORT Point2 operator*(const Point2& p) const; - /** - * Create Similarity2 by aligning at least two point pairs - */ - GTSAM_EXPORT static Similarity2 Align(const std::vector& abPointPairs); + // /** + // * Create Similarity2 by aligning at least two point pairs + // */ + // GTSAM_EXPORT static Similarity2 Align(const std::vector& abPointPairs); - /** - * Create the Similarity2 object that aligns at least two pose pairs. - * Each pair is of the form (aTi, bTi). - * Given a list of pairs in frame a, and a list of pairs in frame b, Align() - * will compute the best-fit Similarity2 aSb transformation to align them. - * First, the rotation aRb will be computed as the average (Karcher mean) of - * many estimates aRb (from each pair). Afterwards, the scale factor will be computed - * using the algorithm described here: - * http://www5.informatik.uni-erlangen.de/Forschung/Publikationen/2005/Zinsser05-PSR.pdf - */ - GTSAM_EXPORT static Similarity2 Align(const std::vector& abPosePairs); + // /** + // * Create the Similarity2 object that aligns at least two pose pairs. + // * Each pair is of the form (aTi, bTi). + // * Given a list of pairs in frame a, and a list of pairs in frame b, Align() + // * will compute the best-fit Similarity2 aSb transformation to align them. + // * First, the rotation aRb will be computed as the average (Karcher mean) of + // * many estimates aRb (from each pair). Afterwards, the scale factor will be computed + // * using the algorithm described here: + // * http://www5.informatik.uni-erlangen.de/Forschung/Publikationen/2005/Zinsser05-PSR.pdf + // */ + // GTSAM_EXPORT static Similarity2 Align(const std::vector& abPosePairs); /// @} /// @name Lie Group @@ -180,10 +180,10 @@ public: }; -template<> -struct traits : public internal::LieGroup {}; +// template<> +// struct traits : public internal::LieGroup {}; -template<> -struct traits : public internal::LieGroup {}; +// template<> +// struct traits : public internal::LieGroup {}; } // namespace gtsam From 89b4340530db96c6bfbfe750fbe129c9f9e998fb Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Wed, 8 Dec 2021 18:29:52 -0500 Subject: [PATCH 0054/1686] alternate option for typedef-ing X1, X2, ... --- gtsam/nonlinear/NonlinearFactor.h | 100 ++++++------------------------ 1 file changed, 20 insertions(+), 80 deletions(-) diff --git a/gtsam/nonlinear/NonlinearFactor.h b/gtsam/nonlinear/NonlinearFactor.h index b55ec7856..53a3e664d 100644 --- a/gtsam/nonlinear/NonlinearFactor.h +++ b/gtsam/nonlinear/NonlinearFactor.h @@ -305,78 +305,6 @@ public: }; // \class NoiseModelFactor - -/* ************************************************************************* */ -/* We need some helper structs to help us with NoiseModelFactorN - specifically - * we need to alias X1, X2, X3, ... in the templated NoiseModelFactorN class to - * maintain backwards compatibility with NoiseModelFactor1, NoiseModelFactor2, - * NoiseModelFactor3, ... - * - * The tricky part is that we want to _conditionally_ alias these only if the - * `sizeof...(VALUES)` is greater than the index we want to alias (e.g. a 3-way - * factor should only have up to X3). SFINAE doesn't work in this case with - * aliases so we have to come up with a different approach. - * - * The approach we use is to create structs which use template specialization to - * conditionally typedef X1, X2, ... for us, then inherit from them to inherit - * the aliases. - * - * Usage: - * ``` - * template - * class MyClass : public AliasX3 { ... }; - * ``` - * This will only typedef X3 if VALUES has at least 3 template parameters. So - * then we can do something like: - * ``` - * int main { - * MyClass::X3 a; // variable a will have type double - * // MyClass::X3 b; // this won't compile - * MyClass::X3 c; // variable c will have type char - * } - * ``` - */ - -// convenience macro extracts the type for the i'th VALUE in a parameter pack -#define GET_VALUE_I(VALUES, I) \ - typename std::tuple_element>::type - -namespace detail { - -// First handle `typedef X`. By default, we do not alias X (empty struct). -template -struct AliasX_ {}; -// But if the first template is true, then we do alias X by specializing. -template -struct AliasX_ { - using X = GET_VALUE_I(VALUES, 0); -}; -// We'll alias (for convenience) the correct version based on whether or not -// `1 == sizeof...(VALUES)` is true -template -using AliasX = AliasX_<(1 == sizeof...(VALUES)), VALUES...>; - -// Now do the same thing for X1, X2, ... using a macro. -#define ALIAS_HELPER_X(N) \ - template \ - struct AliasX##N##_ {}; \ - template \ - struct AliasX##N##_ { \ - using X##N = GET_VALUE_I(VALUES, N - 1); \ - }; \ - template \ - using AliasX##N = AliasX##N##_<(N <= sizeof...(VALUES)), VALUES...>; -ALIAS_HELPER_X(1); -ALIAS_HELPER_X(2); -ALIAS_HELPER_X(3); -ALIAS_HELPER_X(4); -ALIAS_HELPER_X(5); -ALIAS_HELPER_X(6); -#undef ALIAS_HELPER_X -#undef GET_VALUE_I - -} // namespace detail - /* ************************************************************************* */ /** * A convenient base class for creating your own NoiseModelFactor @@ -408,14 +336,7 @@ ALIAS_HELPER_X(6); * objects in non-linear manifolds (Lie groups). */ template -class NoiseModelFactorN : public NoiseModelFactor, - public detail::AliasX, - public detail::AliasX1, - public detail::AliasX2, - public detail::AliasX3, - public detail::AliasX4, - public detail::AliasX5, - public detail::AliasX6 { +class NoiseModelFactorN : public NoiseModelFactor { public: /// N is the number of variables (N-way factor) enum { N = sizeof...(VALUES) }; @@ -424,6 +345,25 @@ class NoiseModelFactorN : public NoiseModelFactor, template ::type = true> using VALUE = typename std::tuple_element>::type; + private: + template + struct VALUE_OR_VOID { + using type = void; + }; + template + struct VALUE_OR_VOID::type> { + using type = VALUE; + }; + + public: + using X = typename VALUE_OR_VOID<0>::type; + using X1 = typename VALUE_OR_VOID<0>::type; + using X2 = typename VALUE_OR_VOID<1>::type; + using X3 = typename VALUE_OR_VOID<2>::type; + using X4 = typename VALUE_OR_VOID<3>::type; + using X5 = typename VALUE_OR_VOID<4>::type; + using X6 = typename VALUE_OR_VOID<5>::type; + protected: using Base = NoiseModelFactor; using This = NoiseModelFactorN; From 5004c47944f1e50234aa02c4c879771e272be7d2 Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Wed, 8 Dec 2021 18:56:09 -0500 Subject: [PATCH 0055/1686] revert typedef X1, X2, ... to old version, and clean up a little --- gtsam/nonlinear/NonlinearFactor.h | 94 ++++++++++++++++++++++++------- 1 file changed, 74 insertions(+), 20 deletions(-) diff --git a/gtsam/nonlinear/NonlinearFactor.h b/gtsam/nonlinear/NonlinearFactor.h index 53a3e664d..099f58979 100644 --- a/gtsam/nonlinear/NonlinearFactor.h +++ b/gtsam/nonlinear/NonlinearFactor.h @@ -305,6 +305,70 @@ public: }; // \class NoiseModelFactor + +/* ************************************************************************* */ +/* We need some helper structs to help us with NoiseModelFactorN - specifically + * we need to alias X1, X2, X3, ... in the templated NoiseModelFactorN class to + * maintain backwards compatibility with NoiseModelFactor1, NoiseModelFactor2, + * NoiseModelFactor3, ... + * + * The tricky part is that we want to _conditionally_ alias these only if the + * `sizeof...(VALUES)` is greater than the index we want to alias (e.g. a 3-way + * factor should only have up to X3). SFINAE doesn't work in this case with + * aliases so we have to come up with a different approach. + * + * The approach we use is to inherit from structs that conditionally typedef + * these types for us (using template specialization). Note: std::conditional + * doesn't work because it requires that both types exist at compile time. + * + * Usage: + * ``` + * template + * class MyClass : public AliasX3 { ... }; + * ``` + * This will only typedef X3 if VALUES has at least 3 template parameters. So + * then we can do something like: + * ``` + * int main { + * MyClass::X3 a; // variable a will have type double + * // MyClass::X3 b; // this won't compile + * MyClass::X3 c; // variable c will have type char + * } + * ``` + */ + +namespace detail { + +// By default, we do not alias X (empty struct). +#define ALIAS_FALSE_X(NAME) \ + template \ + struct Alias##NAME##_ {}; +// But if the first template is true, then we do alias X by specializing. +#define ALIAS_TRUE_X(NAME, N) \ + template \ + struct Alias##NAME##_ { \ + using NAME = typename std::tuple_element>::type; \ + }; +// Finally, alias a convenience struct that chooses the right version. +#define ALIAS_X(NAME, N, CONDITION) \ + ALIAS_FALSE_X(NAME) \ + ALIAS_TRUE_X(NAME, N) \ + template \ + using Alias##NAME = Alias##NAME##_<(CONDITION), VALUES...>; + +ALIAS_X(X, 0, 0 == sizeof...(VALUES)); +ALIAS_X(X1, 0, 0 < sizeof...(VALUES)); +ALIAS_X(X2, 1, 1 < sizeof...(VALUES)); +ALIAS_X(X3, 2, 2 < sizeof...(VALUES)); +ALIAS_X(X4, 3, 3 < sizeof...(VALUES)); +ALIAS_X(X5, 4, 4 < sizeof...(VALUES)); +ALIAS_X(X6, 5, 5 < sizeof...(VALUES)); +#undef ALIAS_FALSE_X +#undef ALIAS_TRUE_X +#undef ALIAS_X + +} // namespace detail + /* ************************************************************************* */ /** * A convenient base class for creating your own NoiseModelFactor @@ -336,7 +400,16 @@ public: * objects in non-linear manifolds (Lie groups). */ template -class NoiseModelFactorN : public NoiseModelFactor { +class NoiseModelFactorN + : public NoiseModelFactor, + public detail::AliasX, // using X = VALUE1 + public detail::AliasX1, // using X1 = VALUE1 + public detail::AliasX2, // using X2 = VALUE2 + public detail::AliasX3, // using X3 = VALUE3 + public detail::AliasX4, // using X4 = VALUE4 + public detail::AliasX5, // using X5 = VALUE5 + public detail::AliasX6 // using X6 = VALUE6 +{ public: /// N is the number of variables (N-way factor) enum { N = sizeof...(VALUES) }; @@ -345,25 +418,6 @@ class NoiseModelFactorN : public NoiseModelFactor { template ::type = true> using VALUE = typename std::tuple_element>::type; - private: - template - struct VALUE_OR_VOID { - using type = void; - }; - template - struct VALUE_OR_VOID::type> { - using type = VALUE; - }; - - public: - using X = typename VALUE_OR_VOID<0>::type; - using X1 = typename VALUE_OR_VOID<0>::type; - using X2 = typename VALUE_OR_VOID<1>::type; - using X3 = typename VALUE_OR_VOID<2>::type; - using X4 = typename VALUE_OR_VOID<3>::type; - using X5 = typename VALUE_OR_VOID<4>::type; - using X6 = typename VALUE_OR_VOID<5>::type; - protected: using Base = NoiseModelFactor; using This = NoiseModelFactorN; From 018213ec855db1dcbe0c7a7b754c178e49442379 Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Wed, 8 Dec 2021 19:09:35 -0500 Subject: [PATCH 0056/1686] switch `using NoiseModelFactorX = ...` to `#define ...`. Reasoning is given as comments. --- gtsam/nonlinear/NonlinearFactor.h | 91 ++++++++----------------------- 1 file changed, 23 insertions(+), 68 deletions(-) diff --git a/gtsam/nonlinear/NonlinearFactor.h b/gtsam/nonlinear/NonlinearFactor.h index 099f58979..18822f0ef 100644 --- a/gtsam/nonlinear/NonlinearFactor.h +++ b/gtsam/nonlinear/NonlinearFactor.h @@ -336,7 +336,6 @@ public: * } * ``` */ - namespace detail { // By default, we do not alias X (empty struct). @@ -356,7 +355,7 @@ namespace detail { template \ using Alias##NAME = Alias##NAME##_<(CONDITION), VALUES...>; -ALIAS_X(X, 0, 0 == sizeof...(VALUES)); +ALIAS_X(X, 0, 1 == sizeof...(VALUES)); ALIAS_X(X1, 0, 0 < sizeof...(VALUES)); ALIAS_X(X2, 1, 1 < sizeof...(VALUES)); ALIAS_X(X3, 2, 2 < sizeof...(VALUES)); @@ -422,13 +421,13 @@ class NoiseModelFactorN using Base = NoiseModelFactor; using This = NoiseModelFactorN; - /* "Dummy templated" alias is used to expand fixed-type parameter packs with - * same length as VALUES. This ignores the template parameter. */ + /* Like std::void_t, except produces `boost::optional` instead. Used + * to expand fixed-type parameter-packs with same length as VALUES */ template using optional_matrix_type = boost::optional; - /* "Dummy templated" alias is used to expand fixed-type parameter packs with - * same length as VALUES. This ignores the template parameter. */ + /* Like std::void_t, except produces `Key` instead. Used to expand fixed-type + * parameter-packs with same length as VALUES */ template using key_type = Key; @@ -586,72 +585,28 @@ class NoiseModelFactorN } }; // \class NoiseModelFactorN -// // `using` does not work for some reason -// template -// using NoiseModelFactor1 = NoiseModelFactorN; -// template -// using NoiseModelFactor2 = NoiseModelFactorN; -// template -// using NoiseModelFactor3 = NoiseModelFactorN; -// template -// using NoiseModelFactor4 = NoiseModelFactorN; -// template -// using NoiseModelFactor5 = -// NoiseModelFactorN; -// template -// using NoiseModelFactor6 = -// NoiseModelFactorN; - -// this is visually ugly -template -struct NoiseModelFactor1 : NoiseModelFactorN { - using NoiseModelFactorN::NoiseModelFactorN; - using This = NoiseModelFactor1; -}; -template -struct NoiseModelFactor2 : NoiseModelFactorN { - using NoiseModelFactorN::NoiseModelFactorN; - using This = NoiseModelFactor2; -}; -template -struct NoiseModelFactor3 : NoiseModelFactorN { - using NoiseModelFactorN::NoiseModelFactorN; - using This = NoiseModelFactor3; -}; -template -struct NoiseModelFactor4 : NoiseModelFactorN { - using NoiseModelFactorN::NoiseModelFactorN; - using This = NoiseModelFactor4; -}; -template -struct NoiseModelFactor5 - : NoiseModelFactorN { - using NoiseModelFactorN::NoiseModelFactorN; - using This = NoiseModelFactor5; -}; -template -struct NoiseModelFactor6 - : NoiseModelFactorN { - using NoiseModelFactorN::NoiseModelFactorN; - using This = - NoiseModelFactor6; -}; - /* ************************************************************************* */ /** @deprecated: use NoiseModelFactorN * Convenient base classes for creating your own NoiseModelFactors with 1-6 * variables. To derive from these classes, implement evaluateError(). + * + * Note: we cannot use `using NoiseModelFactor1 = NoiseModelFactorN` due + * to class name injection making backwards compatibility difficult. + * + * Note: This has the side-effect that you could e.g. NoiseModelFactor6. + * That is, there is nothing stopping you from using any number of template + * arguments with any `NoiseModelFactorX`. */ -// // This has the side-effect that you could e.g. NoiseModelFactor6 -// #define NoiseModelFactor1 NoiseModelFactorN -// #define NoiseModelFactor2 NoiseModelFactorN -// #define NoiseModelFactor3 NoiseModelFactorN -// #define NoiseModelFactor4 NoiseModelFactorN -// #define NoiseModelFactor5 NoiseModelFactorN -// #define NoiseModelFactor6 NoiseModelFactorN +#define NoiseModelFactor1 NoiseModelFactorN +/** @deprecated */ +#define NoiseModelFactor2 NoiseModelFactorN +/** @deprecated */ +#define NoiseModelFactor3 NoiseModelFactorN +/** @deprecated */ +#define NoiseModelFactor4 NoiseModelFactorN +/** @deprecated */ +#define NoiseModelFactor5 NoiseModelFactorN +/** @deprecated */ +#define NoiseModelFactor6 NoiseModelFactorN } // \namespace gtsam From 84e873ebb0d14aaf0058d5a3e09d94aa38776847 Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Thu, 9 Dec 2021 00:50:36 -0500 Subject: [PATCH 0057/1686] fix Windows CI issue: VALUE happens to have the same name in PriorFactor --- gtsam/nonlinear/NonlinearFactor.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/gtsam/nonlinear/NonlinearFactor.h b/gtsam/nonlinear/NonlinearFactor.h index 18822f0ef..ca13434a1 100644 --- a/gtsam/nonlinear/NonlinearFactor.h +++ b/gtsam/nonlinear/NonlinearFactor.h @@ -413,9 +413,9 @@ class NoiseModelFactorN /// N is the number of variables (N-way factor) enum { N = sizeof...(VALUES) }; - /** The type of the i'th template param can be obtained as VALUE */ + /** The type of the i'th template param can be obtained as X_ */ template ::type = true> - using VALUE = typename std::tuple_element>::type; + using X_ = typename std::tuple_element>::type; protected: using Base = NoiseModelFactor; From 40e585bb117eb24d3e591a97d06362b9acfa63a3 Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Thu, 9 Dec 2021 02:26:57 -0500 Subject: [PATCH 0058/1686] review comments --- gtsam/nonlinear/NonlinearFactor.h | 46 +++++++++++++++++++++---------- 1 file changed, 31 insertions(+), 15 deletions(-) diff --git a/gtsam/nonlinear/NonlinearFactor.h b/gtsam/nonlinear/NonlinearFactor.h index ca13434a1..3a59a4db3 100644 --- a/gtsam/nonlinear/NonlinearFactor.h +++ b/gtsam/nonlinear/NonlinearFactor.h @@ -29,6 +29,9 @@ #include #include +// boost::index_sequence was introduced in 1.66, so we'll manually define an +// implementation if user has 1.65. boost::index_sequence is used to get array +// indices that align with a parameter pack. #if BOOST_VERSION >= 106600 #include #else @@ -467,24 +470,11 @@ class NoiseModelFactorN ~NoiseModelFactorN() override {} - /** Methods to retrieve keys */ -#define SUB(Old, New) template // to delay template deduction -#define KEY_IF_TRUE(Enable) typename std::enable_if<(Enable), Key>::type - // templated version of `key()` + /** Returns a key. Usage: `key()` returns the I'th key. */ template - inline KEY_IF_TRUE(I < N) key() const { + inline typename std::enable_if<(I < N), Key>::type key() const { return keys_[I]; } - // backwards-compatibility functions - SUB(T, N) inline KEY_IF_TRUE(T == 1) key() const { return keys_[0]; } - SUB(T, N) inline KEY_IF_TRUE(T >= 1) key1() const { return keys_[0]; } - SUB(T, N) inline KEY_IF_TRUE(T >= 2) key2() const { return keys_[1]; } - SUB(T, N) inline KEY_IF_TRUE(T >= 3) key3() const { return keys_[2]; } - SUB(T, N) inline KEY_IF_TRUE(T >= 4) key4() const { return keys_[3]; } - SUB(T, N) inline KEY_IF_TRUE(T >= 5) key5() const { return keys_[4]; } - SUB(T, N) inline KEY_IF_TRUE(T >= 6) key6() const { return keys_[5]; } -#undef SUB -#undef KEY_IF_TRUE /// @name NoiseModelFactor methods /// @{ @@ -583,6 +573,32 @@ class NoiseModelFactorN ar& boost::serialization::make_nvp( "NoiseModelFactor", boost::serialization::base_object(*this)); } + + public: + /** @defgroup deprecated key access + * Functions to retrieve keys (deprecated). Use the templated version: + * `key()` instead. + * @{ + */ +#define SUB(Old, New) template // to delay template deduction +#define KEY_IF_TRUE(Enable) typename std::enable_if<(Enable), Key>::type + /** @deprecated */ + SUB(T, N) inline KEY_IF_TRUE(T == 1) key() const { return keys_[0]; } + /** @deprecated */ + SUB(T, N) inline KEY_IF_TRUE(T >= 1) key1() const { return keys_[0]; } + /** @deprecated */ + SUB(T, N) inline KEY_IF_TRUE(T >= 2) key2() const { return keys_[1]; } + /** @deprecated */ + SUB(T, N) inline KEY_IF_TRUE(T >= 3) key3() const { return keys_[2]; } + /** @deprecated */ + SUB(T, N) inline KEY_IF_TRUE(T >= 4) key4() const { return keys_[3]; } + /** @deprecated */ + SUB(T, N) inline KEY_IF_TRUE(T >= 5) key5() const { return keys_[4]; } + /** @deprecated */ + SUB(T, N) inline KEY_IF_TRUE(T >= 6) key6() const { return keys_[5]; } +#undef SUB +#undef KEY_IF_TRUE + /** @} */ }; // \class NoiseModelFactorN /* ************************************************************************* */ From 11fd8612269690c9d95eba4a80ac5db705906aa1 Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Thu, 9 Dec 2021 02:30:51 -0500 Subject: [PATCH 0059/1686] update doxygen (review comment) --- gtsam/mainpage.dox | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/mainpage.dox b/gtsam/mainpage.dox index e07f45f07..e9c83da8a 100644 --- a/gtsam/mainpage.dox +++ b/gtsam/mainpage.dox @@ -16,7 +16,7 @@ To use GTSAM to solve your own problems, you will often have to create new facto -# The number of variables your factor involves is unknown at compile time - derive from NoiseModelFactor and implement NoiseModelFactor::unwhitenedError() - This is a factor expressing the sum-of-squares error between a measurement \f$ z \f$ and a measurement prediction function \f$ h(x) \f$, on which the errors are expected to follow some distribution specified by a noise model (see noiseModel). --# The number of variables your factor involves is known at compile time and is between 1 and 6 - derive from NoiseModelFactor1, NoiseModelFactor2, NoiseModelFactor3, NoiseModelFactor4, NoiseModelFactor5, or NoiseModelFactor6, and implement \c evaluateError(). If the number of variables is greater than 6, derive from NoiseModelFactorN. +-# The number of variables your factor involves is known at compile time, derive from NoiseModelFactorN (where T1, T2, ... are the types of the variables, e.g. double, Vector, Pose3) and implement \c evaluateError(). - This factor expresses the same sum-of-squares error with a noise model, but makes the implementation task slightly easier than with %NoiseModelFactor. -# Derive from NonlinearFactor - This is more advanced and allows creating factors without an explicit noise model, or that linearize to HessianFactor instead of JacobianFactor. From 39286f667214a4f7fd88c224943bfb850d5e2a32 Mon Sep 17 00:00:00 2001 From: lcarlone Date: Sun, 19 Dec 2021 10:41:07 -0500 Subject: [PATCH 0060/1686] added clone to play well with gnc --- gtsam_unstable/slam/PoseToPointFactor.h | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/gtsam_unstable/slam/PoseToPointFactor.h b/gtsam_unstable/slam/PoseToPointFactor.h index cab48e506..b9b2ad5ce 100644 --- a/gtsam_unstable/slam/PoseToPointFactor.h +++ b/gtsam_unstable/slam/PoseToPointFactor.h @@ -61,6 +61,12 @@ class PoseToPointFactor : public NoiseModelFactor2 { traits::Equals(this->measured_, e->measured_, tol); } + /// @return a deep copy of this factor + gtsam::NonlinearFactor::shared_ptr clone() const override { + return boost::static_pointer_cast( + gtsam::NonlinearFactor::shared_ptr(new This(*this))); + } + /** implement functions needed to derive from Factor */ /** vector of errors From f340e6260ee053d4b47ebfbbb32aa42970b35286 Mon Sep 17 00:00:00 2001 From: Yun Chang Date: Thu, 23 Dec 2021 20:44:03 -0500 Subject: [PATCH 0061/1686] 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 c59fbc825fe2f77c96d2e8a1bd7c509c3bf7189c Mon Sep 17 00:00:00 2001 From: lcarlone Date: Wed, 5 Jan 2022 23:01:57 -0500 Subject: [PATCH 0062/1686] ruled out corner case where weights are outside [0,1] in TLS --- gtsam/nonlinear/GncOptimizer.h | 8 +++----- 1 file changed, 3 insertions(+), 5 deletions(-) diff --git a/gtsam/nonlinear/GncOptimizer.h b/gtsam/nonlinear/GncOptimizer.h index 3025d2468..9601e5f8c 100644 --- a/gtsam/nonlinear/GncOptimizer.h +++ b/gtsam/nonlinear/GncOptimizer.h @@ -439,13 +439,11 @@ class GTSAM_EXPORT GncOptimizer { for (size_t k : unknownWeights) { if (nfg_[k]) { double u2_k = nfg_[k]->error(currentEstimate); // squared (and whitened) residual - if (u2_k >= upperbound) { + weights[k] = std::sqrt(barcSq_[k] * mu * (mu + 1) / u2_k) - mu; + if (u2_k >= upperbound || weights[k] < 0) { weights[k] = 0; - } else if (u2_k <= lowerbound) { + } else if (u2_k <= lowerbound || weights[k] > 1) { weights[k] = 1; - } else { - weights[k] = std::sqrt(barcSq_[k] * mu * (mu + 1) / u2_k) - - mu; } } } From 859e4cb37af125b9351db22dc86837077d5c62f9 Mon Sep 17 00:00:00 2001 From: lcarlone Date: Wed, 12 Jan 2022 21:31:22 -0500 Subject: [PATCH 0063/1686] thresholded mu to avoid case mu = 0 in TLS. improved verbosity handling --- gtsam/nonlinear/GncOptimizer.h | 25 +++++++++++++++++++------ gtsam/nonlinear/GncParams.h | 2 ++ 2 files changed, 21 insertions(+), 6 deletions(-) diff --git a/gtsam/nonlinear/GncOptimizer.h b/gtsam/nonlinear/GncOptimizer.h index 3025d2468..6c8519aac 100644 --- a/gtsam/nonlinear/GncOptimizer.h +++ b/gtsam/nonlinear/GncOptimizer.h @@ -206,9 +206,11 @@ class GTSAM_EXPORT GncOptimizer { std::cout << "GNC Optimizer stopped because all measurements are already known to be inliers or outliers" << std::endl; } + if (params_.verbosity >= GncParameters::Verbosity::MU) { + std::cout << "mu: " << mu << std::endl; + } if (params_.verbosity >= GncParameters::Verbosity::VALUES) { result.print("result\n"); - std::cout << "mu: " << mu << std::endl; } return result; } @@ -217,12 +219,16 @@ class GTSAM_EXPORT GncOptimizer { for (iter = 0; iter < params_.maxIterations; iter++) { // display info - if (params_.verbosity >= GncParameters::Verbosity::VALUES) { + if (params_.verbosity >= GncParameters::Verbosity::MU) { std::cout << "iter: " << iter << std::endl; - result.print("result\n"); std::cout << "mu: " << mu << std::endl; + } + if (params_.verbosity >= GncParameters::Verbosity::WEIGHTS) { std::cout << "weights: " << weights_ << std::endl; } + if (params_.verbosity >= GncParameters::Verbosity::VALUES) { + result.print("result\n"); + } // weights update weights_ = calculateWeights(result, mu); @@ -253,10 +259,12 @@ class GTSAM_EXPORT GncOptimizer { if (params_.verbosity >= GncParameters::Verbosity::SUMMARY) { std::cout << "final iterations: " << iter << std::endl; std::cout << "final mu: " << mu << std::endl; - std::cout << "final weights: " << weights_ << std::endl; std::cout << "previous cost: " << prev_cost << std::endl; std::cout << "current cost: " << cost << std::endl; } + if (params_.verbosity >= GncParameters::Verbosity::WEIGHTS) { + std::cout << "final weights: " << weights_ << std::endl; + } return result; } @@ -291,6 +299,9 @@ class GTSAM_EXPORT GncOptimizer { std::min(mu_init, barcSq_[k] / (2 * rk - barcSq_[k]) ) : mu_init; } } + if (mu_init >= 0 && mu_init < 1e-6) + mu_init = 1e-6; // if mu ~ 0 (but positive), that means we have measurements with large errors, + // i.e., rk > barcSq_[k] and rk very large, hence we threshold to 1e-6 to avoid mu = 0 return mu_init > 0 && !std::isinf(mu_init) ? mu_init : -1; // if mu <= 0 or mu = inf, return -1, // which leads to termination of the main gnc loop. In this case, all residuals are already below the threshold // and there is no need to robustify (TLS = least squares) @@ -338,8 +349,10 @@ class GTSAM_EXPORT GncOptimizer { bool checkCostConvergence(const double cost, const double prev_cost) const { bool costConverged = std::fabs(cost - prev_cost) / std::max(prev_cost, 1e-7) < params_.relativeCostTol; - if (costConverged && params_.verbosity >= GncParameters::Verbosity::SUMMARY) - std::cout << "checkCostConvergence = true " << std::endl; + if (costConverged && params_.verbosity >= GncParameters::Verbosity::SUMMARY){ + std::cout << "checkCostConvergence = true (prev. cost = " << prev_cost + << ", curr. cost = " << cost << ")" << std::endl; + } return costConverged; } diff --git a/gtsam/nonlinear/GncParams.h b/gtsam/nonlinear/GncParams.h index 086f08acc..1f324ae38 100644 --- a/gtsam/nonlinear/GncParams.h +++ b/gtsam/nonlinear/GncParams.h @@ -48,6 +48,8 @@ class GTSAM_EXPORT GncParams { enum Verbosity { SILENT = 0, SUMMARY, + MU, + WEIGHTS, VALUES }; From d9a00ded231ea074cd64bdf5cc87690ea5dc0f0a Mon Sep 17 00:00:00 2001 From: Calvin Date: Tue, 25 Jan 2022 16:39:05 -0600 Subject: [PATCH 0064/1686] Modified the scaling values for plotting uncertainty ellipses to properly display 3 standard deviations for both 2D and 3D cases. --- python/gtsam/utils/plot.py | 42 ++++++++++++++++++++++++-------------- 1 file changed, 27 insertions(+), 15 deletions(-) diff --git a/python/gtsam/utils/plot.py b/python/gtsam/utils/plot.py index a632b852a..8060de2fb 100644 --- a/python/gtsam/utils/plot.py +++ b/python/gtsam/utils/plot.py @@ -75,8 +75,9 @@ def plot_covariance_ellipse_3d(axes, Plots a Gaussian as an uncertainty ellipse Based on Maybeck Vol 1, page 366 - k=2.296 corresponds to 1 std, 68.26% of all probability - k=11.82 corresponds to 3 std, 99.74% of all probability + For the 3D case: + k = 3.527 corresponds to 1 std, 68.26% of all probability + k = 14.157 corresponds to 3 std, 99.74% of all probability Args: axes (matplotlib.axes.Axes): Matplotlib axes. @@ -87,7 +88,7 @@ def plot_covariance_ellipse_3d(axes, n: Defines the granularity of the ellipse. Higher values indicate finer ellipses. alpha: Transparency value for the plotted surface in the range [0, 1]. """ - k = 11.82 + k = np.sqrt(14.157) U, S, _ = np.linalg.svd(P) radii = k * np.sqrt(S) @@ -113,7 +114,14 @@ def plot_point2_on_axes(axes, linespec: str, P: Optional[np.ndarray] = None) -> None: """ - Plot a 2D point on given axis `axes` with given `linespec`. + Plot a 2D point and its corresponding uncertainty ellipse on given axis + `axes` with given `linespec`. + + Based on Stochastic Models, Estimation, and Control Vol 1 by Maybeck, + page 366 + For the 2D case: + k = 2.296 corresponds to 1 std, 68.26% of all probability + k = 11.820 corresponds to 3 std, 99.74% of all probability Args: axes (matplotlib.axes.Axes): Matplotlib axes. @@ -125,16 +133,15 @@ def plot_point2_on_axes(axes, if P is not None: w, v = np.linalg.eig(P) - # "Sigma" value for drawing the uncertainty ellipse. 5 sigma corresponds - # to a 99.9999% confidence, i.e. assuming the estimation has been - # computed properly, there is a 99.999% chance that the true position - # of the point will lie within the uncertainty ellipse. - k = 5.0 + # Scaling value for the uncertainty ellipse, we multiply by 2 because + # matplotlib takes the diameter and not the radius of the major and + # minor axes of the ellipse. + k = 2*np.sqrt(11.820) angle = np.arctan2(v[1, 0], v[0, 0]) e1 = patches.Ellipse(point, - np.sqrt(w[0] * k), - np.sqrt(w[1] * k), + np.sqrt(w[0]) * k, + np.sqrt(w[1]) * k, np.rad2deg(angle), fill=False) axes.add_patch(e1) @@ -178,6 +185,12 @@ def plot_pose2_on_axes(axes, """ Plot a 2D pose on given axis `axes` with given `axis_length`. + Based on Stochastic Models, Estimation, and Control Vol 1 by Maybeck, + page 366 + For the 2D case: + k = 2.296 corresponds to 1 std, 68.26% of all probability + k = 11.820 corresponds to 3 std, 99.74% of all probability + Args: axes (matplotlib.axes.Axes): Matplotlib axes. pose: The pose to be plotted. @@ -205,13 +218,12 @@ def plot_pose2_on_axes(axes, w, v = np.linalg.eig(gPp) - # k = 2.296 - k = 5.0 + k = 2*np.sqrt(11.820) angle = np.arctan2(v[1, 0], v[0, 0]) e1 = patches.Ellipse(origin, - np.sqrt(w[0] * k), - np.sqrt(w[1] * k), + np.sqrt(w[0]) * k, + np.sqrt(w[1]) * k, np.rad2deg(angle), fill=False) axes.add_patch(e1) From 1b817760dd10d2d08579f4021968eeda262f34c1 Mon Sep 17 00:00:00 2001 From: Calvin Date: Fri, 28 Jan 2022 13:31:11 -0600 Subject: [PATCH 0065/1686] Changed all instances of the Sigma value, k, to 5 for plotting the covariance ellipse. --- python/gtsam/utils/plot.py | 30 ++++++++++++++++++++---------- 1 file changed, 20 insertions(+), 10 deletions(-) diff --git a/python/gtsam/utils/plot.py b/python/gtsam/utils/plot.py index 8060de2fb..820cefb7c 100644 --- a/python/gtsam/utils/plot.py +++ b/python/gtsam/utils/plot.py @@ -79,6 +79,8 @@ def plot_covariance_ellipse_3d(axes, k = 3.527 corresponds to 1 std, 68.26% of all probability k = 14.157 corresponds to 3 std, 99.74% of all probability + We choose k = 5 which corresponds to 99.99846% of all probability in 3D + Args: axes (matplotlib.axes.Axes): Matplotlib axes. origin: The origin in the world frame. @@ -88,7 +90,8 @@ def plot_covariance_ellipse_3d(axes, n: Defines the granularity of the ellipse. Higher values indicate finer ellipses. alpha: Transparency value for the plotted surface in the range [0, 1]. """ - k = np.sqrt(14.157) + # Sigma value corresponding to the covariance ellipse + k = 5 U, S, _ = np.linalg.svd(P) radii = k * np.sqrt(S) @@ -123,6 +126,8 @@ def plot_point2_on_axes(axes, k = 2.296 corresponds to 1 std, 68.26% of all probability k = 11.820 corresponds to 3 std, 99.74% of all probability + We choose k = 5 which corresponds to 99.99963% of all probability for 2D. + Args: axes (matplotlib.axes.Axes): Matplotlib axes. point: The point to be plotted. @@ -133,15 +138,15 @@ def plot_point2_on_axes(axes, if P is not None: w, v = np.linalg.eig(P) - # Scaling value for the uncertainty ellipse, we multiply by 2 because - # matplotlib takes the diameter and not the radius of the major and - # minor axes of the ellipse. - k = 2*np.sqrt(11.820) + # Sigma value corresponding to the covariance ellipse + k = 5 angle = np.arctan2(v[1, 0], v[0, 0]) + # We multiply k by 2 since k corresponds to the radius but Ellipse uses + # the diameter. e1 = patches.Ellipse(point, - np.sqrt(w[0]) * k, - np.sqrt(w[1]) * k, + np.sqrt(w[0]) * 2 * k, + np.sqrt(w[1]) * 2 * k, np.rad2deg(angle), fill=False) axes.add_patch(e1) @@ -191,6 +196,8 @@ def plot_pose2_on_axes(axes, k = 2.296 corresponds to 1 std, 68.26% of all probability k = 11.820 corresponds to 3 std, 99.74% of all probability + We choose k = 5 which corresponds to 99.99963% of all probability for 2D. + Args: axes (matplotlib.axes.Axes): Matplotlib axes. pose: The pose to be plotted. @@ -218,12 +225,15 @@ def plot_pose2_on_axes(axes, w, v = np.linalg.eig(gPp) - k = 2*np.sqrt(11.820) + # Sigma value corresponding to the covariance ellipse + k = 5 angle = np.arctan2(v[1, 0], v[0, 0]) + # We multiply k by 2 since k corresponds to the radius but Ellipse uses + # the diameter. e1 = patches.Ellipse(origin, - np.sqrt(w[0]) * k, - np.sqrt(w[1]) * k, + np.sqrt(w[0]) * 2 * k, + np.sqrt(w[1]) * 2 * k, np.rad2deg(angle), fill=False) axes.add_patch(e1) From e524e2806b6a341053a7ab4a425a5fe0a4afe72e Mon Sep 17 00:00:00 2001 From: Calvin Date: Fri, 28 Jan 2022 14:16:30 -0600 Subject: [PATCH 0066/1686] Updated comments to reflect standard deviations instead of variances in the discussions regarding the values for k. --- python/gtsam/utils/plot.py | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/python/gtsam/utils/plot.py b/python/gtsam/utils/plot.py index 820cefb7c..f409968a8 100644 --- a/python/gtsam/utils/plot.py +++ b/python/gtsam/utils/plot.py @@ -76,8 +76,8 @@ def plot_covariance_ellipse_3d(axes, Based on Maybeck Vol 1, page 366 For the 3D case: - k = 3.527 corresponds to 1 std, 68.26% of all probability - k = 14.157 corresponds to 3 std, 99.74% of all probability + k = 1.878 corresponds to 1 std, 68.26% of all probability + k = 3.763 corresponds to 3 std, 99.74% of all probability We choose k = 5 which corresponds to 99.99846% of all probability in 3D @@ -123,8 +123,8 @@ def plot_point2_on_axes(axes, Based on Stochastic Models, Estimation, and Control Vol 1 by Maybeck, page 366 For the 2D case: - k = 2.296 corresponds to 1 std, 68.26% of all probability - k = 11.820 corresponds to 3 std, 99.74% of all probability + k = 1.515 corresponds to 1 std, 68.26% of all probability + k = 3.438 corresponds to 3 std, 99.74% of all probability We choose k = 5 which corresponds to 99.99963% of all probability for 2D. @@ -193,8 +193,8 @@ def plot_pose2_on_axes(axes, Based on Stochastic Models, Estimation, and Control Vol 1 by Maybeck, page 366 For the 2D case: - k = 2.296 corresponds to 1 std, 68.26% of all probability - k = 11.820 corresponds to 3 std, 99.74% of all probability + k = 1.515 corresponds to 1 std, 68.26% of all probability + k = 3.438 corresponds to 3 std, 99.74% of all probability We choose k = 5 which corresponds to 99.99963% of all probability for 2D. From c9dbb6e04085dad6dc7e48c99dbe6b5624a4575f Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Sun, 30 Jan 2022 17:23:02 -0500 Subject: [PATCH 0067/1686] create backwards compatibility unit test for NoiseModelFactor1 --- gtsam/nonlinear/tests/priorFactor.xml | 77 +++++++++++++++++++ .../tests/testSerializationNonlinear.cpp | 53 +++++++++++++ 2 files changed, 130 insertions(+) create mode 100644 gtsam/nonlinear/tests/priorFactor.xml diff --git a/gtsam/nonlinear/tests/priorFactor.xml b/gtsam/nonlinear/tests/priorFactor.xml new file mode 100644 index 000000000..46752262b --- /dev/null +++ b/gtsam/nonlinear/tests/priorFactor.xml @@ -0,0 +1,77 @@ + + + + + + + + + 1 + 0 + 12345 + + + + + + + + + 6 + + + 0 + + + + 6 + + 1.00000000000000000e+00 + 1.00000000000000000e+00 + 1.00000000000000000e+00 + 1.00000000000000000e+00 + 1.00000000000000000e+00 + 1.00000000000000000e+00 + + + + 6 + + 1.00000000000000000e+00 + 1.00000000000000000e+00 + 1.00000000000000000e+00 + 1.00000000000000000e+00 + 1.00000000000000000e+00 + 1.00000000000000000e+00 + + + + 1.00000000000000000e+00 + 1.00000000000000000e+00 + + + + + + + + 4.11982245665682978e-01 + -8.33737651774156818e-01 + -3.67630462924899259e-01 + -5.87266449276209815e-02 + -4.26917621276207360e-01 + 9.02381585483330806e-01 + -9.09297426825681709e-01 + -3.50175488374014632e-01 + -2.24845095366152908e-01 + + + + 4.00000000000000000e+00 + 5.00000000000000000e+00 + 6.00000000000000000e+00 + + + + + diff --git a/gtsam/nonlinear/tests/testSerializationNonlinear.cpp b/gtsam/nonlinear/tests/testSerializationNonlinear.cpp index 4a73cbb0b..f7b524a5c 100644 --- a/gtsam/nonlinear/tests/testSerializationNonlinear.cpp +++ b/gtsam/nonlinear/tests/testSerializationNonlinear.cpp @@ -107,6 +107,59 @@ TEST (Serialization, TemplatedValues) { EXPECT(equalsBinary(values)); } +bool str_assert_equal(const string& expected, const string& actual) { + if (actual == expected) return true; + printf("Not equal:\n"); + std::cout << "expected:\n" << expected << std::endl; + std::cout << "actual:\n" << actual << std::endl; + return false; +} +TEST(Serialization, NoiseModelFactor1_backwards_compatibility) { + PriorFactor factor( + 12345, Pose3(Rot3::RzRyRx(Vector3(1., 2., 3.)), Point3(4., 5., 6.)), + noiseModel::Unit::Create(6)); + + // String + std::string actual_str = serialize(factor); + // Generated from hash 3ba65669113f41d0e56a03b4b314047776bab5c4 (>4.2a4) + std::string expected_str = + "22 serialization::archive 19 1 0\n" + "0 0 0 0 0 0 0 1 0 12345 0 1 6 21 gtsam_noiseModel_Unit 1 0\n" + "1 1 0\n" + "2 1 0\n" + "3 0 0 0 0 6 0 1 0 0 0 6 1.00000000000000000e+00 1.00000000000000000e+00 " + "1.00000000000000000e+00 1.00000000000000000e+00 1.00000000000000000e+00 " + "1.00000000000000000e+00 6 1.00000000000000000e+00 " + "1.00000000000000000e+00 1.00000000000000000e+00 1.00000000000000000e+00 " + "1.00000000000000000e+00 1.00000000000000000e+00 1.00000000000000000e+00 " + "1.00000000000000000e+00 0 0 0 0 4.11982245665682978e-01 " + "-8.33737651774156818e-01 -3.67630462924899259e-01 " + "-5.87266449276209815e-02 -4.26917621276207360e-01 " + "9.02381585483330806e-01 -9.09297426825681709e-01 " + "-3.50175488374014632e-01 -2.24845095366152908e-01 0 0 " + "4.00000000000000000e+00 5.00000000000000000e+00 " + "6.00000000000000000e+00\n"; + EXPECT(str_assert_equal(expected_str, actual_str)); + PriorFactor factor_deserialized_str = PriorFactor(); + deserializeFromString(expected_str, factor_deserialized_str); + EXPECT(assert_equal(factor, factor_deserialized_str)); + + // XML + std::string actual_xml = serializeXML(factor); + std::string expected_xml; + { // read from file + // Generated from hash 3ba65669113f41d0e56a03b4b314047776bab5c4 (>4.2a4) + std::ifstream f("priorFactor.xml"); + std::stringstream buffer; + buffer << f.rdbuf(); + expected_xml = buffer.str(); + } + EXPECT(str_assert_equal(expected_xml, actual_xml)); + PriorFactor factor_deserialized_xml = PriorFactor(); + deserializeFromXMLFile("priorFactor.xml", factor_deserialized_xml); + EXPECT(assert_equal(factor, factor_deserialized_xml)); +} + TEST(Serialization, ISAM2) { gtsam::ISAM2Params parameters; From bb33be58b36ec4aa4f00d56064b6286901710e96 Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Sun, 30 Jan 2022 17:25:20 -0500 Subject: [PATCH 0068/1686] revert some template stuff with inheritance for readability NoiseModelFactor123456 are now minimal classes that inherit from NoiseModelFactorN --- gtsam/nonlinear/NonlinearFactor.h | 362 ++++++++++++++++++++---------- 1 file changed, 241 insertions(+), 121 deletions(-) diff --git a/gtsam/nonlinear/NonlinearFactor.h b/gtsam/nonlinear/NonlinearFactor.h index d7061215e..212364af3 100644 --- a/gtsam/nonlinear/NonlinearFactor.h +++ b/gtsam/nonlinear/NonlinearFactor.h @@ -309,68 +309,6 @@ public: }; // \class NoiseModelFactor -/* ************************************************************************* */ -/* We need some helper structs to help us with NoiseModelFactorN - specifically - * we need to alias X1, X2, X3, ... in the templated NoiseModelFactorN class to - * maintain backwards compatibility with NoiseModelFactor1, NoiseModelFactor2, - * NoiseModelFactor3, ... - * - * The tricky part is that we want to _conditionally_ alias these only if the - * `sizeof...(VALUES)` is greater than the index we want to alias (e.g. a 3-way - * factor should only have up to X3). SFINAE doesn't work in this case with - * aliases so we have to come up with a different approach. - * - * The approach we use is to inherit from structs that conditionally typedef - * these types for us (using template specialization). Note: std::conditional - * doesn't work because it requires that both types exist at compile time. - * - * Usage: - * ``` - * template - * class MyClass : public AliasX3 { ... }; - * ``` - * This will only typedef X3 if VALUES has at least 3 template parameters. So - * then we can do something like: - * ``` - * int main { - * MyClass::X3 a; // variable a will have type double - * // MyClass::X3 b; // this won't compile - * MyClass::X3 c; // variable c will have type char - * } - * ``` - */ -namespace detail { - -// By default, we do not alias X (empty struct). -#define ALIAS_FALSE_X(NAME) \ - template \ - struct Alias##NAME##_ {}; -// But if the first template is true, then we do alias X by specializing. -#define ALIAS_TRUE_X(NAME, N) \ - template \ - struct Alias##NAME##_ { \ - using NAME = typename std::tuple_element>::type; \ - }; -// Finally, alias a convenience struct that chooses the right version. -#define ALIAS_X(NAME, N, CONDITION) \ - ALIAS_FALSE_X(NAME) \ - ALIAS_TRUE_X(NAME, N) \ - template \ - using Alias##NAME = Alias##NAME##_<(CONDITION), VALUES...>; - -ALIAS_X(X, 0, 1 == sizeof...(VALUES)); -ALIAS_X(X1, 0, 0 < sizeof...(VALUES)); -ALIAS_X(X2, 1, 1 < sizeof...(VALUES)); -ALIAS_X(X3, 2, 2 < sizeof...(VALUES)); -ALIAS_X(X4, 3, 3 < sizeof...(VALUES)); -ALIAS_X(X5, 4, 4 < sizeof...(VALUES)); -ALIAS_X(X6, 5, 5 < sizeof...(VALUES)); -#undef ALIAS_FALSE_X -#undef ALIAS_TRUE_X -#undef ALIAS_X - -} // namespace detail - /* ************************************************************************* */ /** * A convenient base class for creating your own NoiseModelFactor @@ -402,23 +340,14 @@ ALIAS_X(X6, 5, 5 < sizeof...(VALUES)); * objects in non-linear manifolds (Lie groups). */ template -class GTSAM_EXPORT NoiseModelFactorN - : public NoiseModelFactor, - public detail::AliasX, // using X = VALUE1 - public detail::AliasX1, // using X1 = VALUE1 - public detail::AliasX2, // using X2 = VALUE2 - public detail::AliasX3, // using X3 = VALUE3 - public detail::AliasX4, // using X4 = VALUE4 - public detail::AliasX5, // using X5 = VALUE5 - public detail::AliasX6 // using X6 = VALUE6 -{ +class GTSAM_EXPORT NoiseModelFactorN : public NoiseModelFactor { public: /// N is the number of variables (N-way factor) enum { N = sizeof...(VALUES) }; - /** The type of the i'th template param can be obtained as X_ */ + /** The type of the i'th template param can be obtained as X */ template ::type = true> - using X_ = typename std::tuple_element>::type; + using X = typename std::tuple_element>::type; protected: using Base = NoiseModelFactor; @@ -573,56 +502,247 @@ class GTSAM_EXPORT NoiseModelFactorN ar& boost::serialization::make_nvp( "NoiseModelFactor", boost::serialization::base_object(*this)); } - - public: - /** @defgroup deprecated key access - * Functions to retrieve keys (deprecated). Use the templated version: - * `key()` instead. - * @{ - */ -#define SUB(Old, New) template // to delay template deduction -#define KEY_IF_TRUE(Enable) typename std::enable_if<(Enable), Key>::type - /** @deprecated */ - SUB(T, N) inline KEY_IF_TRUE(T == 1) key() const { return keys_[0]; } - /** @deprecated */ - SUB(T, N) inline KEY_IF_TRUE(T >= 1) key1() const { return keys_[0]; } - /** @deprecated */ - SUB(T, N) inline KEY_IF_TRUE(T >= 2) key2() const { return keys_[1]; } - /** @deprecated */ - SUB(T, N) inline KEY_IF_TRUE(T >= 3) key3() const { return keys_[2]; } - /** @deprecated */ - SUB(T, N) inline KEY_IF_TRUE(T >= 4) key4() const { return keys_[3]; } - /** @deprecated */ - SUB(T, N) inline KEY_IF_TRUE(T >= 5) key5() const { return keys_[4]; } - /** @deprecated */ - SUB(T, N) inline KEY_IF_TRUE(T >= 6) key6() const { return keys_[5]; } -#undef SUB -#undef KEY_IF_TRUE - /** @} */ }; // \class NoiseModelFactorN /* ************************************************************************* */ -/** @deprecated: use NoiseModelFactorN - * Convenient base classes for creating your own NoiseModelFactors with 1-6 - * variables. To derive from these classes, implement evaluateError(). - * - * Note: we cannot use `using NoiseModelFactor1 = NoiseModelFactorN` due - * to class name injection making backwards compatibility difficult. - * - * Note: This has the side-effect that you could e.g. NoiseModelFactor6. - * That is, there is nothing stopping you from using any number of template - * arguments with any `NoiseModelFactorX`. +/** @deprecated: use NoiseModelFactorN, replacing .key() with .key<1> and X1 + * with X<1>. + * A convenient base class for creating your own NoiseModelFactor + * with 1 variable. To derive from this class, implement evaluateError(). */ -#define NoiseModelFactor1 NoiseModelFactorN -/** @deprecated */ -#define NoiseModelFactor2 NoiseModelFactorN -/** @deprecated */ -#define NoiseModelFactor3 NoiseModelFactorN -/** @deprecated */ -#define NoiseModelFactor4 NoiseModelFactorN -/** @deprecated */ -#define NoiseModelFactor5 NoiseModelFactorN -/** @deprecated */ -#define NoiseModelFactor6 NoiseModelFactorN +template +class NoiseModelFactor1 : public NoiseModelFactorN { + public: + // aliases for value types pulled from keys + using X = VALUE; + + protected: + using Base = NoiseModelFactor; // grandparent, for backwards compatibility + using This = NoiseModelFactor1; + + public: + // inherit NoiseModelFactorN's constructors + using NoiseModelFactorN::NoiseModelFactorN; + ~NoiseModelFactor1() override {} + + /** method to retrieve key */ + inline Key key() const { return this->keys_[0]; } + + private: + /** Serialization function */ + friend class boost::serialization::access; + template + void serialize(ARCHIVE& ar, const unsigned int /*version*/) { + ar& boost::serialization::make_nvp( + "NoiseModelFactor", boost::serialization::base_object(*this)); + } +}; // \class NoiseModelFactor1 + +/* ************************************************************************* */ +/** @deprecated: use NoiseModelFactorN, replacing .key1() with .key<1> and X1 + * with X<1>. + * A convenient base class for creating your own NoiseModelFactor + * with 2 variables. To derive from this class, implement evaluateError(). + */ +template +class NoiseModelFactor2 : public NoiseModelFactorN { + public: + // aliases for value types pulled from keys + using X1 = VALUE1; + using X2 = VALUE2; + + protected: + using Base = NoiseModelFactor; + using This = NoiseModelFactor2; + + public: + // inherit NoiseModelFactorN's constructors + using NoiseModelFactorN::NoiseModelFactorN; + ~NoiseModelFactor2() override {} + + /** methods to retrieve both keys */ + inline Key key1() const { return this->keys_[0]; } + inline Key key2() const { return this->keys_[1]; } + + private: + /** Serialization function */ + friend class boost::serialization::access; + template + void serialize(ARCHIVE& ar, const unsigned int /*version*/) { + ar& boost::serialization::make_nvp( + "NoiseModelFactor", boost::serialization::base_object(*this)); + } +}; // \class NoiseModelFactor2 + +/* ************************************************************************* */ +/** @deprecated: use NoiseModelFactorN, replacing .key1() with .key<1> and X1 + * with X<1>. + * A convenient base class for creating your own NoiseModelFactor + * with 3 variables. To derive from this class, implement evaluateError(). + */ +template +class NoiseModelFactor3 : public NoiseModelFactorN { + public: + // aliases for value types pulled from keys + using X1 = VALUE1; + using X2 = VALUE2; + using X3 = VALUE3; + + protected: + using Base = NoiseModelFactor; + using This = NoiseModelFactor3; + + public: + // inherit NoiseModelFactorN's constructors + using NoiseModelFactorN::NoiseModelFactorN; + ~NoiseModelFactor3() override {} + + /** methods to retrieve keys */ + inline Key key1() const { return this->keys_[0]; } + inline Key key2() const { return this->keys_[1]; } + inline Key key3() const { return this->keys_[2]; } + + private: + /** Serialization function */ + friend class boost::serialization::access; + template + void serialize(ARCHIVE& ar, const unsigned int /*version*/) { + ar& boost::serialization::make_nvp( + "NoiseModelFactor", boost::serialization::base_object(*this)); + } +}; // \class NoiseModelFactor3 + +/* ************************************************************************* */ +/** @deprecated: use NoiseModelFactorN, replacing .key1() with .key<1> and X1 + * with X<1>. + * A convenient base class for creating your own NoiseModelFactor + * with 4 variables. To derive from this class, implement evaluateError(). + */ +template +class NoiseModelFactor4 + : public NoiseModelFactorN { + public: + // aliases for value types pulled from keys + using X1 = VALUE1; + using X2 = VALUE2; + using X3 = VALUE3; + using X4 = VALUE4; + + protected: + using Base = NoiseModelFactor; + using This = NoiseModelFactor4; + + public: + // inherit NoiseModelFactorN's constructors + using NoiseModelFactorN::NoiseModelFactorN; + ~NoiseModelFactor4() override {} + + /** methods to retrieve keys */ + inline Key key1() const { return this->keys_[0]; } + inline Key key2() const { return this->keys_[1]; } + inline Key key3() const { return this->keys_[2]; } + inline Key key4() const { return this->keys_[3]; } + + private: + /** Serialization function */ + friend class boost::serialization::access; + template + void serialize(ARCHIVE& ar, const unsigned int /*version*/) { + ar& boost::serialization::make_nvp( + "NoiseModelFactor", boost::serialization::base_object(*this)); + } +}; // \class NoiseModelFactor4 + +/* ************************************************************************* */ +/** @deprecated: use NoiseModelFactorN, replacing .key1() with .key<1> and X1 + * with X<1>. + * A convenient base class for creating your own NoiseModelFactor + * with 5 variables. To derive from this class, implement evaluateError(). + */ +template +class NoiseModelFactor5 + : public NoiseModelFactorN { + public: + // aliases for value types pulled from keys + using X1 = VALUE1; + using X2 = VALUE2; + using X3 = VALUE3; + using X4 = VALUE4; + using X5 = VALUE5; + + protected: + using Base = NoiseModelFactor; + using This = NoiseModelFactor5; + + public: + // inherit NoiseModelFactorN's constructors + using NoiseModelFactorN::NoiseModelFactorN; + ~NoiseModelFactor5() override {} + + /** methods to retrieve keys */ + inline Key key1() const { return this->keys_[0]; } + inline Key key2() const { return this->keys_[1]; } + inline Key key3() const { return this->keys_[2]; } + inline Key key4() const { return this->keys_[3]; } + inline Key key5() const { return this->keys_[4]; } + + private: + /** Serialization function */ + friend class boost::serialization::access; + template + void serialize(ARCHIVE& ar, const unsigned int /*version*/) { + ar& boost::serialization::make_nvp( + "NoiseModelFactor", boost::serialization::base_object(*this)); + } +}; // \class NoiseModelFactor5 + +/* ************************************************************************* */ +/** @deprecated: use NoiseModelFactorN, replacing .key1() with .key<1> and X1 + * with X<1>. + * A convenient base class for creating your own NoiseModelFactor + * with 6 variables. To derive from this class, implement evaluateError(). + */ +template +class NoiseModelFactor6 + : public NoiseModelFactorN { + public: + // aliases for value types pulled from keys + using X1 = VALUE1; + using X2 = VALUE2; + using X3 = VALUE3; + using X4 = VALUE4; + using X5 = VALUE5; + using X6 = VALUE6; + + protected: + using Base = NoiseModelFactor; + using This = + NoiseModelFactor6; + + public: + // inherit NoiseModelFactorN's constructors + using NoiseModelFactorN::NoiseModelFactorN; + ~NoiseModelFactor6() override {} + + /** methods to retrieve keys */ + inline Key key1() const { return this->keys_[0]; } + inline Key key2() const { return this->keys_[1]; } + inline Key key3() const { return this->keys_[2]; } + inline Key key4() const { return this->keys_[3]; } + inline Key key5() const { return this->keys_[4]; } + inline Key key6() const { return this->keys_[5]; } + + private: + /** Serialization function */ + friend class boost::serialization::access; + template + void serialize(ARCHIVE& ar, const unsigned int /*version*/) { + ar& boost::serialization::make_nvp( + "NoiseModelFactor", boost::serialization::base_object(*this)); + } +}; // \class NoiseModelFactor6 } // \namespace gtsam From 82e0d205190577e7f3fc669829b9ff1b364bcb67 Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Sun, 30 Jan 2022 17:26:54 -0500 Subject: [PATCH 0069/1686] move boost::index_sequence stuff to utilities file --- gtsam/base/utilities.h | 38 ++++++++++++++++++++++++++++++ gtsam/nonlinear/NonlinearFactor.h | 39 +------------------------------ 2 files changed, 39 insertions(+), 38 deletions(-) diff --git a/gtsam/base/utilities.h b/gtsam/base/utilities.h index d9b92b8aa..22e90d275 100644 --- a/gtsam/base/utilities.h +++ b/gtsam/base/utilities.h @@ -27,3 +27,41 @@ private: }; } + +// boost::index_sequence was introduced in 1.66, so we'll manually define an +// implementation if user has 1.65. boost::index_sequence is used to get array +// indices that align with a parameter pack. +#if BOOST_VERSION >= 106600 +#include +#else +namespace boost { +namespace mp11 { +// Adapted from https://stackoverflow.com/a/32223343/9151520 +template +struct index_sequence { + using type = index_sequence; + using value_type = size_t; + static constexpr std::size_t size() noexcept { return sizeof...(Ints); } +}; +namespace detail { +template +struct _merge_and_renumber; + +template +struct _merge_and_renumber, index_sequence > + : index_sequence {}; +} // namespace detail +template +struct make_index_sequence + : detail::_merge_and_renumber< + typename make_index_sequence::type, + typename make_index_sequence::type> {}; +template <> +struct make_index_sequence<0> : index_sequence<> {}; +template <> +struct make_index_sequence<1> : index_sequence<0> {}; +template +using index_sequence_for = make_index_sequence; +} // namespace mp11 +} // namespace boost +#endif diff --git a/gtsam/nonlinear/NonlinearFactor.h b/gtsam/nonlinear/NonlinearFactor.h index 212364af3..4deef0d3a 100644 --- a/gtsam/nonlinear/NonlinearFactor.h +++ b/gtsam/nonlinear/NonlinearFactor.h @@ -25,48 +25,11 @@ #include #include #include +#include // boost::index_sequence #include #include -// boost::index_sequence was introduced in 1.66, so we'll manually define an -// implementation if user has 1.65. boost::index_sequence is used to get array -// indices that align with a parameter pack. -#if BOOST_VERSION >= 106600 -#include -#else -namespace boost { -namespace mp11 { -// Adapted from https://stackoverflow.com/a/32223343/9151520 -template -struct index_sequence { - using type = index_sequence; - using value_type = size_t; - static constexpr std::size_t size() noexcept { return sizeof...(Ints); } -}; -namespace detail { -template -struct _merge_and_renumber; - -template -struct _merge_and_renumber, index_sequence > - : index_sequence {}; -} // namespace detail -template -struct make_index_sequence - : detail::_merge_and_renumber< - typename make_index_sequence::type, - typename make_index_sequence::type> {}; -template <> -struct make_index_sequence<0> : index_sequence<> {}; -template <> -struct make_index_sequence<1> : index_sequence<0> {}; -template -using index_sequence_for = make_index_sequence; -} // namespace mp11 -} // namespace boost -#endif - namespace gtsam { using boost::assign::cref_list_of; From d62033a856f4e78ce0625ff9dd43539d30e39a2a Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Sun, 30 Jan 2022 17:38:42 -0500 Subject: [PATCH 0070/1686] fix namespace collision with symbol_shorthand::X in unit test --- tests/testNonlinearFactor.cpp | 12 ++++++++---- 1 file changed, 8 insertions(+), 4 deletions(-) diff --git a/tests/testNonlinearFactor.cpp b/tests/testNonlinearFactor.cpp index 27b61cf89..bdc2d576d 100644 --- a/tests/testNonlinearFactor.cpp +++ b/tests/testNonlinearFactor.cpp @@ -382,8 +382,9 @@ class TestFactor4 : public NoiseModelFactor4 { "This type wrong"); public: + static constexpr auto X_ = symbol_shorthand::X; // collision with X<1> typedef NoiseModelFactor4 Base; - TestFactor4() : Base(noiseModel::Diagonal::Sigmas((Vector(1) << 2.0).finished()), X(1), X(2), X(3), X(4)) {} + TestFactor4() : Base(noiseModel::Diagonal::Sigmas((Vector(1) << 2.0).finished()), X_(1), X_(2), X_(3), X_(4)) {} Vector evaluateError(const double& x1, const double& x2, const double& x3, const double& x4, @@ -446,8 +447,9 @@ TEST(NonlinearFactor, NoiseModelFactor4) { /* ************************************************************************* */ class TestFactor5 : public NoiseModelFactor5 { public: + static constexpr auto X_ = symbol_shorthand::X; // collision with X<1> typedef NoiseModelFactor5 Base; - TestFactor5() : Base(noiseModel::Diagonal::Sigmas((Vector(1) << 2.0).finished()), X(1), X(2), X(3), X(4), X(5)) {} + TestFactor5() : Base(noiseModel::Diagonal::Sigmas((Vector(1) << 2.0).finished()), X_(1), X_(2), X_(3), X_(4), X_(5)) {} Vector evaluateError(const X1& x1, const X2& x2, const X3& x3, const X4& x4, const X5& x5, @@ -495,8 +497,9 @@ TEST(NonlinearFactor, NoiseModelFactor5) { /* ************************************************************************* */ class TestFactor6 : public NoiseModelFactor6 { public: + static constexpr auto X_ = symbol_shorthand::X; // collision with X<1> typedef NoiseModelFactor6 Base; - TestFactor6() : Base(noiseModel::Diagonal::Sigmas((Vector(1) << 2.0).finished()), X(1), X(2), X(3), X(4), X(5), X(6)) {} + TestFactor6() : Base(noiseModel::Diagonal::Sigmas((Vector(1) << 2.0).finished()), X_(1), X_(2), X_(3), X_(4), X_(5), X_(6)) {} Vector evaluateError(const X1& x1, const X2& x2, const X3& x3, const X4& x4, const X5& x5, const X6& x6, @@ -551,8 +554,9 @@ TEST(NonlinearFactor, NoiseModelFactor6) { /* ************************************************************************* */ class TestFactorN : public NoiseModelFactorN { public: + static constexpr auto X_ = symbol_shorthand::X; // collision with X<1> typedef NoiseModelFactorN Base; - TestFactorN() : Base(noiseModel::Diagonal::Sigmas((Vector(1) << 2.0).finished()), X(1), X(2), X(3), X(4)) {} + TestFactorN() : Base(noiseModel::Diagonal::Sigmas((Vector(1) << 2.0).finished()), X_(1), X_(2), X_(3), X_(4)) {} Vector evaluateError(const double& x1, const double& x2, const double& x3, const double& x4, From a2fb0e49d51c9c822ad13f017c2521e572d6274c Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Sun, 30 Jan 2022 21:30:03 -0500 Subject: [PATCH 0071/1686] Revert "create backwards compatibility unit test for NoiseModelFactor1" This reverts commit c9dbb6e04085dad6dc7e48c99dbe6b5624a4575f. --- gtsam/nonlinear/tests/priorFactor.xml | 77 ------------------- .../tests/testSerializationNonlinear.cpp | 53 ------------- 2 files changed, 130 deletions(-) delete mode 100644 gtsam/nonlinear/tests/priorFactor.xml diff --git a/gtsam/nonlinear/tests/priorFactor.xml b/gtsam/nonlinear/tests/priorFactor.xml deleted file mode 100644 index 46752262b..000000000 --- a/gtsam/nonlinear/tests/priorFactor.xml +++ /dev/null @@ -1,77 +0,0 @@ - - - - - - - - - 1 - 0 - 12345 - - - - - - - - - 6 - - - 0 - - - - 6 - - 1.00000000000000000e+00 - 1.00000000000000000e+00 - 1.00000000000000000e+00 - 1.00000000000000000e+00 - 1.00000000000000000e+00 - 1.00000000000000000e+00 - - - - 6 - - 1.00000000000000000e+00 - 1.00000000000000000e+00 - 1.00000000000000000e+00 - 1.00000000000000000e+00 - 1.00000000000000000e+00 - 1.00000000000000000e+00 - - - - 1.00000000000000000e+00 - 1.00000000000000000e+00 - - - - - - - - 4.11982245665682978e-01 - -8.33737651774156818e-01 - -3.67630462924899259e-01 - -5.87266449276209815e-02 - -4.26917621276207360e-01 - 9.02381585483330806e-01 - -9.09297426825681709e-01 - -3.50175488374014632e-01 - -2.24845095366152908e-01 - - - - 4.00000000000000000e+00 - 5.00000000000000000e+00 - 6.00000000000000000e+00 - - - - - diff --git a/gtsam/nonlinear/tests/testSerializationNonlinear.cpp b/gtsam/nonlinear/tests/testSerializationNonlinear.cpp index f7b524a5c..4a73cbb0b 100644 --- a/gtsam/nonlinear/tests/testSerializationNonlinear.cpp +++ b/gtsam/nonlinear/tests/testSerializationNonlinear.cpp @@ -107,59 +107,6 @@ TEST (Serialization, TemplatedValues) { EXPECT(equalsBinary(values)); } -bool str_assert_equal(const string& expected, const string& actual) { - if (actual == expected) return true; - printf("Not equal:\n"); - std::cout << "expected:\n" << expected << std::endl; - std::cout << "actual:\n" << actual << std::endl; - return false; -} -TEST(Serialization, NoiseModelFactor1_backwards_compatibility) { - PriorFactor factor( - 12345, Pose3(Rot3::RzRyRx(Vector3(1., 2., 3.)), Point3(4., 5., 6.)), - noiseModel::Unit::Create(6)); - - // String - std::string actual_str = serialize(factor); - // Generated from hash 3ba65669113f41d0e56a03b4b314047776bab5c4 (>4.2a4) - std::string expected_str = - "22 serialization::archive 19 1 0\n" - "0 0 0 0 0 0 0 1 0 12345 0 1 6 21 gtsam_noiseModel_Unit 1 0\n" - "1 1 0\n" - "2 1 0\n" - "3 0 0 0 0 6 0 1 0 0 0 6 1.00000000000000000e+00 1.00000000000000000e+00 " - "1.00000000000000000e+00 1.00000000000000000e+00 1.00000000000000000e+00 " - "1.00000000000000000e+00 6 1.00000000000000000e+00 " - "1.00000000000000000e+00 1.00000000000000000e+00 1.00000000000000000e+00 " - "1.00000000000000000e+00 1.00000000000000000e+00 1.00000000000000000e+00 " - "1.00000000000000000e+00 0 0 0 0 4.11982245665682978e-01 " - "-8.33737651774156818e-01 -3.67630462924899259e-01 " - "-5.87266449276209815e-02 -4.26917621276207360e-01 " - "9.02381585483330806e-01 -9.09297426825681709e-01 " - "-3.50175488374014632e-01 -2.24845095366152908e-01 0 0 " - "4.00000000000000000e+00 5.00000000000000000e+00 " - "6.00000000000000000e+00\n"; - EXPECT(str_assert_equal(expected_str, actual_str)); - PriorFactor factor_deserialized_str = PriorFactor(); - deserializeFromString(expected_str, factor_deserialized_str); - EXPECT(assert_equal(factor, factor_deserialized_str)); - - // XML - std::string actual_xml = serializeXML(factor); - std::string expected_xml; - { // read from file - // Generated from hash 3ba65669113f41d0e56a03b4b314047776bab5c4 (>4.2a4) - std::ifstream f("priorFactor.xml"); - std::stringstream buffer; - buffer << f.rdbuf(); - expected_xml = buffer.str(); - } - EXPECT(str_assert_equal(expected_xml, actual_xml)); - PriorFactor factor_deserialized_xml = PriorFactor(); - deserializeFromXMLFile("priorFactor.xml", factor_deserialized_xml); - EXPECT(assert_equal(factor, factor_deserialized_xml)); -} - TEST(Serialization, ISAM2) { gtsam::ISAM2Params parameters; From 1a427cd96c3c00e20c5a4518256523ab966f7270 Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Sun, 30 Jan 2022 23:48:22 -0500 Subject: [PATCH 0072/1686] Serialize test strings generated with Boost 1.65 --- gtsam/nonlinear/tests/priorFactor.xml | 77 +++++++++++++++++++ .../tests/testSerializationNonlinear.cpp | 47 +++++++++++ 2 files changed, 124 insertions(+) create mode 100644 gtsam/nonlinear/tests/priorFactor.xml diff --git a/gtsam/nonlinear/tests/priorFactor.xml b/gtsam/nonlinear/tests/priorFactor.xml new file mode 100644 index 000000000..0c580fb21 --- /dev/null +++ b/gtsam/nonlinear/tests/priorFactor.xml @@ -0,0 +1,77 @@ + + + + + + + + + 1 + 0 + 12345 + + + + + + + + + 6 + + + 0 + + + + 6 + + 1.00000000000000000e+00 + 1.00000000000000000e+00 + 1.00000000000000000e+00 + 1.00000000000000000e+00 + 1.00000000000000000e+00 + 1.00000000000000000e+00 + + + + 6 + + 1.00000000000000000e+00 + 1.00000000000000000e+00 + 1.00000000000000000e+00 + 1.00000000000000000e+00 + 1.00000000000000000e+00 + 1.00000000000000000e+00 + + + + 1.00000000000000000e+00 + 1.00000000000000000e+00 + + + + + + + + 4.11982245665682978e-01 + -8.33737651774156818e-01 + -3.67630462924899259e-01 + -5.87266449276209815e-02 + -4.26917621276207360e-01 + 9.02381585483330806e-01 + -9.09297426825681709e-01 + -3.50175488374014632e-01 + -2.24845095366152908e-01 + + + + 4.00000000000000000e+00 + 5.00000000000000000e+00 + 6.00000000000000000e+00 + + + + + diff --git a/gtsam/nonlinear/tests/testSerializationNonlinear.cpp b/gtsam/nonlinear/tests/testSerializationNonlinear.cpp index 4a73cbb0b..023785f21 100644 --- a/gtsam/nonlinear/tests/testSerializationNonlinear.cpp +++ b/gtsam/nonlinear/tests/testSerializationNonlinear.cpp @@ -107,6 +107,53 @@ TEST (Serialization, TemplatedValues) { EXPECT(equalsBinary(values)); } +/** + * Test deserializing from a known serialization generated by code from commit + * 3ba65669113f41d0e56a03b4b314047776bab5c4 (>4.2a4) + * We only test that deserialization matches since + * (1) that's the main backward compatibility requirement and + * (2) serialized string depends on boost version + */ +TEST(Serialization, NoiseModelFactor1_backwards_compatibility) { + PriorFactor factor( + 12345, Pose3(Rot3::RzRyRx(Vector3(1., 2., 3.)), Point3(4., 5., 6.)), + noiseModel::Unit::Create(6)); + + // String + std::string expected_str = + "22 serialization::archive 15 1 0\n" + "0 0 0 0 0 0 0 1 0 12345 0 1 6 21 gtsam_noiseModel_Unit 1 0\n" + "1 1 0\n" + "2 1 0\n" + "3 0 0 0 0 6 0 1 0 0 0 6 1.00000000000000000e+00 1.00000000000000000e+00 " + "1.00000000000000000e+00 1.00000000000000000e+00 1.00000000000000000e+00 " + "1.00000000000000000e+00 6 1.00000000000000000e+00 " + "1.00000000000000000e+00 1.00000000000000000e+00 1.00000000000000000e+00 " + "1.00000000000000000e+00 1.00000000000000000e+00 1.00000000000000000e+00 " + "1.00000000000000000e+00 0 0 0 0 4.11982245665682978e-01 " + "-8.33737651774156818e-01 -3.67630462924899259e-01 " + "-5.87266449276209815e-02 -4.26917621276207360e-01 " + "9.02381585483330806e-01 -9.09297426825681709e-01 " + "-3.50175488374014632e-01 -2.24845095366152908e-01 0 0 " + "4.00000000000000000e+00 5.00000000000000000e+00 " + "6.00000000000000000e+00\n"; + PriorFactor factor_deserialized_str = PriorFactor(); + deserializeFromString(expected_str, factor_deserialized_str); + EXPECT(assert_equal(factor, factor_deserialized_str)); + + // XML + std::string expected_xml; + { // read from file + std::ifstream f("priorFactor.xml"); + std::stringstream buffer; + buffer << f.rdbuf(); + expected_xml = buffer.str(); + } + PriorFactor factor_deserialized_xml = PriorFactor(); + deserializeFromXMLFile("priorFactor.xml", factor_deserialized_xml); + EXPECT(assert_equal(factor, factor_deserialized_xml)); +} + TEST(Serialization, ISAM2) { gtsam::ISAM2Params parameters; From 6653d666ef6e23eab9366545344e689492287edf Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Mon, 31 Jan 2022 01:08:47 -0500 Subject: [PATCH 0073/1686] fix test xml file path --- gtsam/nonlinear/tests/testSerializationNonlinear.cpp | 11 +++-------- 1 file changed, 3 insertions(+), 8 deletions(-) diff --git a/gtsam/nonlinear/tests/testSerializationNonlinear.cpp b/gtsam/nonlinear/tests/testSerializationNonlinear.cpp index 023785f21..b6b5033a2 100644 --- a/gtsam/nonlinear/tests/testSerializationNonlinear.cpp +++ b/gtsam/nonlinear/tests/testSerializationNonlinear.cpp @@ -142,15 +142,10 @@ TEST(Serialization, NoiseModelFactor1_backwards_compatibility) { EXPECT(assert_equal(factor, factor_deserialized_str)); // XML - std::string expected_xml; - { // read from file - std::ifstream f("priorFactor.xml"); - std::stringstream buffer; - buffer << f.rdbuf(); - expected_xml = buffer.str(); - } PriorFactor factor_deserialized_xml = PriorFactor(); - deserializeFromXMLFile("priorFactor.xml", factor_deserialized_xml); + deserializeFromXMLFile(GTSAM_SOURCE_TREE_DATASET_DIR + "/../../gtsam/nonlinear/tests/priorFactor.xml", + factor_deserialized_xml); EXPECT(assert_equal(factor, factor_deserialized_xml)); } From d0279d2738548b8e25aca2b9a39c172b99a561a6 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 31 Jan 2022 11:57:31 -0500 Subject: [PATCH 0074/1686] Add pybind11/stl.h and get it compiling --- gtsam/base/base.i | 36 ----------------------------- python/gtsam/gtsam.tpl | 1 + python/gtsam/specializations/base.h | 3 --- 3 files changed, 1 insertion(+), 39 deletions(-) diff --git a/gtsam/base/base.i b/gtsam/base/base.i index 9838f97d3..f4184fa12 100644 --- a/gtsam/base/base.i +++ b/gtsam/base/base.i @@ -41,45 +41,9 @@ class DSFMap { std::map sets(); }; -class IndexPairSet { - IndexPairSet(); - // common STL methods - size_t size() const; - bool empty() const; - void clear(); - - // structure specific methods - void insert(gtsam::IndexPair key); - bool erase(gtsam::IndexPair key); // returns true if value was removed - bool count(gtsam::IndexPair key) const; // returns true if value exists -}; - -class IndexPairVector { - IndexPairVector(); - IndexPairVector(const gtsam::IndexPairVector& other); - - // common STL methods - size_t size() const; - bool empty() const; - void clear(); - - // structure specific methods - gtsam::IndexPair at(size_t i) const; - void push_back(gtsam::IndexPair key) const; -}; gtsam::IndexPairVector IndexPairSetAsArray(gtsam::IndexPairSet& set); -class IndexPairSetMap { - IndexPairSetMap(); - // common STL methods - size_t size() const; - bool empty() const; - void clear(); - - // structure specific methods - gtsam::IndexPairSet at(gtsam::IndexPair& key); -}; #include bool linear_independent(Matrix A, Matrix B, double tol); diff --git a/python/gtsam/gtsam.tpl b/python/gtsam/gtsam.tpl index b760e4eb5..bdeb2bccc 100644 --- a/python/gtsam/gtsam.tpl +++ b/python/gtsam/gtsam.tpl @@ -11,6 +11,7 @@ {include_boost} #include +#include #include #include #include diff --git a/python/gtsam/specializations/base.h b/python/gtsam/specializations/base.h index 9eefdeca8..995753da1 100644 --- a/python/gtsam/specializations/base.h +++ b/python/gtsam/specializations/base.h @@ -11,7 +11,4 @@ * and saves one copy operation. */ -py::bind_map(m_, "IndexPairSetMap"); -py::bind_vector(m_, "IndexPairVector"); - py::bind_vector >(m_, "JacobianVector"); From 394bb82dba39cb8b8f456612957cc1f8025dd19b Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 31 Jan 2022 12:14:31 -0500 Subject: [PATCH 0075/1686] remove unnecessary includes --- python/gtsam/preamble/basis.h | 2 -- python/gtsam/preamble/discrete.h | 2 -- python/gtsam/preamble/inference.h | 2 -- 3 files changed, 6 deletions(-) diff --git a/python/gtsam/preamble/basis.h b/python/gtsam/preamble/basis.h index 56a07cfdd..d07a75f6f 100644 --- a/python/gtsam/preamble/basis.h +++ b/python/gtsam/preamble/basis.h @@ -10,5 +10,3 @@ * Without this they will be automatically converted to a Python object, and all * mutations on Python side will not be reflected on C++. */ - -#include diff --git a/python/gtsam/preamble/discrete.h b/python/gtsam/preamble/discrete.h index 608508c32..598ab626d 100644 --- a/python/gtsam/preamble/discrete.h +++ b/python/gtsam/preamble/discrete.h @@ -11,6 +11,4 @@ * mutations on Python side will not be reflected on C++. */ -#include - PYBIND11_MAKE_OPAQUE(gtsam::DiscreteKeys); diff --git a/python/gtsam/preamble/inference.h b/python/gtsam/preamble/inference.h index 320e0ac71..bd71c0817 100644 --- a/python/gtsam/preamble/inference.h +++ b/python/gtsam/preamble/inference.h @@ -11,5 +11,3 @@ * mutations on Python side will not be reflected on C++. */ -#include - From 19287ad5c889b08cf64855fe48b7a89bd0d4e174 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 31 Jan 2022 12:15:43 -0500 Subject: [PATCH 0076/1686] fix geometry modules --- gtsam/geometry/geometry.i | 54 ------------------------- python/gtsam/preamble/geometry.h | 12 ++---- python/gtsam/specializations/geometry.h | 7 ---- 3 files changed, 3 insertions(+), 70 deletions(-) diff --git a/gtsam/geometry/geometry.i b/gtsam/geometry/geometry.i index 1e42966f8..97ffe6f18 100644 --- a/gtsam/geometry/geometry.i +++ b/gtsam/geometry/geometry.i @@ -29,38 +29,6 @@ class Point2 { void serialize() const; }; -class Point2Pairs { - Point2Pairs(); - size_t size() const; - bool empty() const; - gtsam::Point2Pair at(size_t n) const; - void push_back(const gtsam::Point2Pair& point_pair); -}; - -// std::vector -class Point2Vector { - // Constructors - Point2Vector(); - Point2Vector(const gtsam::Point2Vector& v); - - // Capacity - size_t size() const; - size_t max_size() const; - void resize(size_t sz); - size_t capacity() const; - bool empty() const; - void reserve(size_t n); - - // Element access - gtsam::Point2 at(size_t n) const; - gtsam::Point2 front() const; - gtsam::Point2 back() const; - - // Modifiers - void assign(size_t n, const gtsam::Point2& u); - void push_back(const gtsam::Point2& x); - void pop_back(); -}; #include class StereoPoint2 { @@ -127,13 +95,6 @@ class Point3 { void serialize() const; }; -class Point3Pairs { - Point3Pairs(); - size_t size() const; - bool empty() const; - gtsam::Point3Pair at(size_t n) const; - void push_back(const gtsam::Point3Pair& point_pair); -}; #include class Rot2 { @@ -486,21 +447,6 @@ class Pose3 { void serialize() const; }; -class Pose3Pairs { - Pose3Pairs(); - size_t size() const; - bool empty() const; - gtsam::Pose3Pair at(size_t n) const; - void push_back(const gtsam::Pose3Pair& pose_pair); -}; - -class Pose3Vector { - Pose3Vector(); - size_t size() const; - bool empty() const; - gtsam::Pose3 at(size_t n) const; - void push_back(const gtsam::Pose3& pose); -}; #include class Unit3 { diff --git a/python/gtsam/preamble/geometry.h b/python/gtsam/preamble/geometry.h index 35fe2a577..ca03cdfe2 100644 --- a/python/gtsam/preamble/geometry.h +++ b/python/gtsam/preamble/geometry.h @@ -10,7 +10,6 @@ * Without this they will be automatically converted to a Python object, and all * mutations on Python side will not be reflected on C++. */ -#include // Support for binding boost::optional types in C++11. // https://pybind11.readthedocs.io/en/stable/advanced/cast/stl.html @@ -19,12 +18,7 @@ namespace pybind11 { namespace detail { struct type_caster> : optional_caster> {}; }} -PYBIND11_MAKE_OPAQUE( - std::vector>); -PYBIND11_MAKE_OPAQUE(gtsam::Point2Pairs); -PYBIND11_MAKE_OPAQUE(gtsam::Point3Pairs); -PYBIND11_MAKE_OPAQUE(gtsam::Pose3Pairs); -PYBIND11_MAKE_OPAQUE(std::vector); -PYBIND11_MAKE_OPAQUE( - gtsam::CameraSet>); PYBIND11_MAKE_OPAQUE(gtsam::CameraSet>); +PYBIND11_MAKE_OPAQUE(gtsam::CameraSet>); +PYBIND11_MAKE_OPAQUE(gtsam::CameraSet>); +PYBIND11_MAKE_OPAQUE(gtsam::CameraSet>); diff --git a/python/gtsam/specializations/geometry.h b/python/gtsam/specializations/geometry.h index a492ce8eb..f63e942a2 100644 --- a/python/gtsam/specializations/geometry.h +++ b/python/gtsam/specializations/geometry.h @@ -11,13 +11,6 @@ * and saves one copy operation. */ -py::bind_vector< - std::vector>>( - m_, "Point2Vector"); -py::bind_vector>(m_, "Point2Pairs"); -py::bind_vector>(m_, "Point3Pairs"); -py::bind_vector>(m_, "Pose3Pairs"); -py::bind_vector>(m_, "Pose3Vector"); py::bind_vector>>( m_, "CameraSetCal3_S2"); py::bind_vector>>( From f5da8522221b6d6e2e5f7de0eeec890f08074a5c Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 31 Jan 2022 12:49:06 -0500 Subject: [PATCH 0077/1686] remove KeyVector --- gtsam/gtsam.i | 54 ---------------------------- python/gtsam/preamble/gtsam.h | 5 --- python/gtsam/specializations/gtsam.h | 8 ----- 3 files changed, 67 deletions(-) diff --git a/gtsam/gtsam.i b/gtsam/gtsam.i index d4e959c3d..45bd61d0b 100644 --- a/gtsam/gtsam.i +++ b/gtsam/gtsam.i @@ -66,27 +66,6 @@ class KeySet { void serialize() const; }; -// Actually a vector -class KeyVector { - KeyVector(); - KeyVector(const gtsam::KeyVector& other); - - // Note: no print function - - // common STL methods - size_t size() const; - bool empty() const; - void clear(); - - // structure specific methods - size_t at(size_t i) const; - size_t front() const; - size_t back() const; - void push_back(size_t key) const; - - void serialize() const; -}; - // Actually a FastMap class KeyGroupMap { KeyGroupMap(); @@ -104,39 +83,6 @@ class KeyGroupMap { bool insert2(size_t key, int val); }; -// Actually a FastSet -class FactorIndexSet { - FactorIndexSet(); - FactorIndexSet(const gtsam::FactorIndexSet& set); - - // common STL methods - size_t size() const; - bool empty() const; - void clear(); - - // structure specific methods - void insert(size_t factorIndex); - bool erase(size_t factorIndex); // returns true if value was removed - bool count(size_t factorIndex) const; // returns true if value exists -}; - -// Actually a vector -class FactorIndices { - FactorIndices(); - FactorIndices(const gtsam::FactorIndices& other); - - // common STL methods - size_t size() const; - bool empty() const; - void clear(); - - // structure specific methods - size_t at(size_t i) const; - size_t front() const; - size_t back() const; - void push_back(size_t factorIndex) const; -}; - //************************************************************************* // Utilities //************************************************************************* diff --git a/python/gtsam/preamble/gtsam.h b/python/gtsam/preamble/gtsam.h index ec39c410a..d07a75f6f 100644 --- a/python/gtsam/preamble/gtsam.h +++ b/python/gtsam/preamble/gtsam.h @@ -10,8 +10,3 @@ * Without this they will be automatically converted to a Python object, and all * mutations on Python side will not be reflected on C++. */ -#ifdef GTSAM_ALLOCATOR_TBB -PYBIND11_MAKE_OPAQUE(std::vector>); -#else -PYBIND11_MAKE_OPAQUE(std::vector); -#endif diff --git a/python/gtsam/specializations/gtsam.h b/python/gtsam/specializations/gtsam.h index 490d71902..da8842eaf 100644 --- a/python/gtsam/specializations/gtsam.h +++ b/python/gtsam/specializations/gtsam.h @@ -10,11 +10,3 @@ * with `PYBIND11_MAKE_OPAQUE` this allows the types to be modified with Python, * and saves one copy operation. */ - -#ifdef GTSAM_ALLOCATOR_TBB -py::bind_vector > >(m_, "KeyVector"); -py::implicitly_convertible > >(); -#else -py::bind_vector >(m_, "KeyVector"); -py::implicitly_convertible >(); -#endif From b93145cd89c420a47a95cd0deea29474548dad6a Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 31 Jan 2022 13:33:09 -0500 Subject: [PATCH 0078/1686] remove unneeded code --- gtsam/geometry/Rot3.h | 3 --- gtsam/sfm/sfm.i | 16 ---------------- gtsam/slam/slam.i | 20 +------------------- python/gtsam/gtsam.tpl | 2 +- python/gtsam/preamble/base.h | 1 - python/gtsam/preamble/slam.h | 6 ------ python/gtsam/specializations/sfm.h | 4 ---- python/gtsam/specializations/slam.h | 8 -------- 8 files changed, 2 insertions(+), 58 deletions(-) diff --git a/gtsam/geometry/Rot3.h b/gtsam/geometry/Rot3.h index 18bd88b52..d313883d9 100644 --- a/gtsam/geometry/Rot3.h +++ b/gtsam/geometry/Rot3.h @@ -564,9 +564,6 @@ class GTSAM_EXPORT Rot3 : public LieGroup { #endif }; - /// std::vector of Rot3s, mainly for wrapper - using Rot3Vector = std::vector >; - /** * [RQ] receives a 3 by 3 matrix and returns an upper triangular matrix R * and 3 rotation angles corresponding to the rotation matrix Q=Qz'*Qy'*Qx' diff --git a/gtsam/sfm/sfm.i b/gtsam/sfm/sfm.i index 705892e60..31057ec4b 100644 --- a/gtsam/sfm/sfm.i +++ b/gtsam/sfm/sfm.i @@ -29,13 +29,6 @@ class BinaryMeasurement { typedef gtsam::BinaryMeasurement BinaryMeasurementUnit3; typedef gtsam::BinaryMeasurement BinaryMeasurementRot3; -class BinaryMeasurementsUnit3 { - BinaryMeasurementsUnit3(); - size_t size() const; - gtsam::BinaryMeasurement at(size_t idx) const; - void push_back(const gtsam::BinaryMeasurement& measurement); -}; - #include // TODO(frank): copy/pasta below until we have integer template paremeters in @@ -178,15 +171,6 @@ class ShonanAveraging3 { #include -class KeyPairDoubleMap { - KeyPairDoubleMap(); - KeyPairDoubleMap(const gtsam::KeyPairDoubleMap& other); - - size_t size() const; - bool empty() const; - void clear(); - size_t at(const pair& keypair) const; -}; class MFAS { MFAS(const gtsam::BinaryMeasurementsUnit3& relativeTranslations, diff --git a/gtsam/slam/slam.i b/gtsam/slam/slam.i index e044dd2c1..da06c0e26 100644 --- a/gtsam/slam/slam.i +++ b/gtsam/slam/slam.i @@ -268,24 +268,6 @@ void save2D(const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& config, gtsam::noiseModel::Diagonal* model, string filename); -// std::vector::shared_ptr> -// Ignored by pybind -> will be List[BetweenFactorPose2] -class BetweenFactorPose2s { - BetweenFactorPose2s(); - size_t size() const; - gtsam::BetweenFactor* at(size_t i) const; - void push_back(const gtsam::BetweenFactor* factor); -}; -gtsam::BetweenFactorPose2s parse2DFactors(string filename); - -// std::vector::shared_ptr> -// Ignored by pybind -> will be List[BetweenFactorPose3] -class BetweenFactorPose3s { - BetweenFactorPose3s(); - size_t size() const; - gtsam::BetweenFactor* at(size_t i) const; - void push_back(const gtsam::BetweenFactor* factor); -}; gtsam::BetweenFactorPose3s parse3DFactors(string filename); pair load3D(string filename); @@ -323,7 +305,7 @@ virtual class KarcherMeanFactor : gtsam::NonlinearFactor { KarcherMeanFactor(const gtsam::KeyVector& keys); }; -gtsam::Rot3 FindKarcherMean(const gtsam::Rot3Vector& rotations); +gtsam::Rot3 FindKarcherMean(const std::vector& rotations); #include gtsam::noiseModel::Isotropic* ConvertNoiseModel(gtsam::noiseModel::Base* model, diff --git a/python/gtsam/gtsam.tpl b/python/gtsam/gtsam.tpl index bdeb2bccc..a974b246b 100644 --- a/python/gtsam/gtsam.tpl +++ b/python/gtsam/gtsam.tpl @@ -11,8 +11,8 @@ {include_boost} #include -#include #include +#include #include #include #include diff --git a/python/gtsam/preamble/base.h b/python/gtsam/preamble/base.h index 626b47ae4..a7effd1ca 100644 --- a/python/gtsam/preamble/base.h +++ b/python/gtsam/preamble/base.h @@ -12,5 +12,4 @@ */ PYBIND11_MAKE_OPAQUE(std::vector); - PYBIND11_MAKE_OPAQUE(std::vector); // JacobianVector diff --git a/python/gtsam/preamble/slam.h b/python/gtsam/preamble/slam.h index f7bf5863c..d07a75f6f 100644 --- a/python/gtsam/preamble/slam.h +++ b/python/gtsam/preamble/slam.h @@ -10,9 +10,3 @@ * Without this they will be automatically converted to a Python object, and all * mutations on Python side will not be reflected on C++. */ - -PYBIND11_MAKE_OPAQUE( - std::vector > >); -PYBIND11_MAKE_OPAQUE( - std::vector > >); -PYBIND11_MAKE_OPAQUE(gtsam::Rot3Vector); diff --git a/python/gtsam/specializations/sfm.h b/python/gtsam/specializations/sfm.h index 6de15217f..da8842eaf 100644 --- a/python/gtsam/specializations/sfm.h +++ b/python/gtsam/specializations/sfm.h @@ -10,7 +10,3 @@ * with `PYBIND11_MAKE_OPAQUE` this allows the types to be modified with Python, * and saves one copy operation. */ - -py::bind_vector > >( - m_, "BinaryMeasurementsUnit3"); -py::bind_map(m_, "KeyPairDoubleMap"); diff --git a/python/gtsam/specializations/slam.h b/python/gtsam/specializations/slam.h index 6a439c370..da8842eaf 100644 --- a/python/gtsam/specializations/slam.h +++ b/python/gtsam/specializations/slam.h @@ -10,11 +10,3 @@ * with `PYBIND11_MAKE_OPAQUE` this allows the types to be modified with Python, * and saves one copy operation. */ - -py::bind_vector< - std::vector>>>( - m_, "BetweenFactorPose3s"); -py::bind_vector< - std::vector>>>( - m_, "BetweenFactorPose2s"); -py::bind_vector(m_, "Rot3Vector"); From 042c236123a9a804676fc1bcbbd72ba82cdb6390 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 31 Jan 2022 14:08:13 -0500 Subject: [PATCH 0079/1686] update python tests --- gtsam/base/base.i | 14 +++++++- .../examples/TranslationAveragingExample.py | 11 +++--- python/gtsam/symbol_shorthand.py | 2 +- python/gtsam/tests/test_Cal3Fisheye.py | 13 ++++--- python/gtsam/tests/test_Cal3Unified.py | 13 ++++--- python/gtsam/tests/test_DecisionTreeFactor.py | 3 +- python/gtsam/tests/test_KarcherMeanFactor.py | 11 +++--- python/gtsam/tests/test_Pose2.py | 7 ++-- python/gtsam/tests/test_ShonanAveraging.py | 15 +++----- python/gtsam/tests/test_Sim3.py | 13 ++++--- .../gtsam/tests/test_TranslationRecovery.py | 6 ++-- python/gtsam/tests/test_Triangulation.py | 34 ++++++------------- 12 files changed, 63 insertions(+), 79 deletions(-) diff --git a/gtsam/base/base.i b/gtsam/base/base.i index f4184fa12..fbbd91553 100644 --- a/gtsam/base/base.i +++ b/gtsam/base/base.i @@ -41,10 +41,22 @@ class DSFMap { std::map sets(); }; +class IndexPairVector { + IndexPairVector(); + IndexPairVector(const gtsam::IndexPairVector& other); + + // common STL methods + size_t size() const; + bool empty() const; + void clear(); + + // structure specific methods + gtsam::IndexPair at(size_t i) const; + void push_back(gtsam::IndexPair key) const; +}; gtsam::IndexPairVector IndexPairSetAsArray(gtsam::IndexPairSet& set); - #include bool linear_independent(Matrix A, Matrix B, double tol); diff --git a/python/gtsam/examples/TranslationAveragingExample.py b/python/gtsam/examples/TranslationAveragingExample.py index 054b61126..a29b7e6a4 100644 --- a/python/gtsam/examples/TranslationAveragingExample.py +++ b/python/gtsam/examples/TranslationAveragingExample.py @@ -17,9 +17,8 @@ Date: September 2020 from collections import defaultdict from typing import List, Tuple -import numpy as np - import gtsam +import numpy as np from gtsam.examples import SFMdata # Hyperparameters for 1dsfm, values used from Kyle Wilson's code. @@ -59,7 +58,7 @@ def get_data() -> Tuple[gtsam.Values, List[gtsam.BinaryMeasurementUnit3]]: return wRc_values, i_iZj_list -def filter_outliers(w_iZj_list: gtsam.BinaryMeasurementsUnit3) -> gtsam.BinaryMeasurementsUnit3: +def filter_outliers(w_iZj_list: List[gtsam.BinaryMeasurementUnit3]) -> List[gtsam.BinaryMeasurementUnit3]: """Removes outliers from a list of Unit3 measurements that are the translation directions from camera i to camera j in the world frame.""" @@ -89,14 +88,14 @@ def filter_outliers(w_iZj_list: gtsam.BinaryMeasurementsUnit3) -> gtsam.BinaryMe avg_outlier_weights[keypair] += weight / len(outlier_weights) # Remove w_iZj that have weight greater than threshold, these are outliers. - w_iZj_inliers = gtsam.BinaryMeasurementsUnit3() + w_iZj_inliers = [] [w_iZj_inliers.append(w_iZj) for w_iZj in w_iZj_list if avg_outlier_weights[( w_iZj.key1(), w_iZj.key2())] < OUTLIER_WEIGHT_THRESHOLD] return w_iZj_inliers -def estimate_poses(i_iZj_list: gtsam.BinaryMeasurementsUnit3, +def estimate_poses(i_iZj_list: List[gtsam.BinaryMeasurementUnit3], wRc_values: gtsam.Values) -> gtsam.Values: """Estimate poses given rotations and normalized translation directions between cameras. @@ -112,7 +111,7 @@ def estimate_poses(i_iZj_list: gtsam.BinaryMeasurementsUnit3, """ # Convert the translation direction measurements to world frame using the rotations. - w_iZj_list = gtsam.BinaryMeasurementsUnit3() + w_iZj_list = [] for i_iZj in i_iZj_list: w_iZj = gtsam.Unit3(wRc_values.atRot3(i_iZj.key1()) .rotate(i_iZj.measured().point3())) diff --git a/python/gtsam/symbol_shorthand.py b/python/gtsam/symbol_shorthand.py index 748d36558..5f7866d18 100644 --- a/python/gtsam/symbol_shorthand.py +++ b/python/gtsam/symbol_shorthand.py @@ -1,4 +1,4 @@ # This trick is to allow direct import of sub-modules # without this, we can only do `from gtsam.gtsam.symbol_shorthand import X` # with this trick, we can do `from gtsam.symbol_shorthand import X` -from .gtsam.symbol_shorthand import * \ No newline at end of file +from .gtsam.symbol_shorthand import * diff --git a/python/gtsam/tests/test_Cal3Fisheye.py b/python/gtsam/tests/test_Cal3Fisheye.py index e54afc757..246ec19ee 100644 --- a/python/gtsam/tests/test_Cal3Fisheye.py +++ b/python/gtsam/tests/test_Cal3Fisheye.py @@ -11,11 +11,10 @@ Refactored: Roderick Koehle """ import unittest -import numpy as np - import gtsam -from gtsam.utils.test_case import GtsamTestCase +import numpy as np from gtsam.symbol_shorthand import K, L, P +from gtsam.utils.test_case import GtsamTestCase def ulp(ftype=np.float64): @@ -51,9 +50,9 @@ class TestCal3Fisheye(GtsamTestCase): camera1 = gtsam.PinholeCameraCal3Fisheye(pose1) camera2 = gtsam.PinholeCameraCal3Fisheye(pose2) cls.origin = np.array([0.0, 0.0, 0.0]) - cls.poses = gtsam.Pose3Vector([pose1, pose2]) - cls.cameras = gtsam.CameraSetCal3Fisheye([camera1, camera2]) - cls.measurements = gtsam.Point2Vector([k.project(cls.origin) for k in cls.cameras]) + cls.poses = [pose1, pose2] + cls.cameras = [camera1, camera2] + cls.measurements = [k.project(cls.origin) for k in cls.cameras] def test_Cal3Fisheye(self): K = gtsam.Cal3Fisheye() @@ -187,7 +186,7 @@ class TestCal3Fisheye(GtsamTestCase): def test_triangulation_rectify(self): """Estimate spatial point from image measurements using rectification""" - rectified = gtsam.Point2Vector([k.calibration().calibrate(pt) for k, pt in zip(self.cameras, self.measurements)]) + rectified = [k.calibration().calibrate(pt) for k, pt in zip(self.cameras, self.measurements)] shared_cal = gtsam.Cal3_S2() triangulated = gtsam.triangulatePoint3(self.poses, shared_cal, rectified, rank_tol=1e-9, optimize=False) self.gtsamAssertEquals(triangulated, self.origin) diff --git a/python/gtsam/tests/test_Cal3Unified.py b/python/gtsam/tests/test_Cal3Unified.py index bafbacfa4..da9f4a939 100644 --- a/python/gtsam/tests/test_Cal3Unified.py +++ b/python/gtsam/tests/test_Cal3Unified.py @@ -10,11 +10,10 @@ Author: Frank Dellaert & Duy Nguyen Ta (Python) """ import unittest -import numpy as np - import gtsam -from gtsam.utils.test_case import GtsamTestCase +import numpy as np from gtsam.symbol_shorthand import K, L, P +from gtsam.utils.test_case import GtsamTestCase class TestCal3Unified(GtsamTestCase): @@ -48,9 +47,9 @@ class TestCal3Unified(GtsamTestCase): camera1 = gtsam.PinholeCameraCal3Unified(pose1, cls.stereographic) camera2 = gtsam.PinholeCameraCal3Unified(pose2, cls.stereographic) cls.origin = np.array([0.0, 0.0, 0.0]) - cls.poses = gtsam.Pose3Vector([pose1, pose2]) - cls.cameras = gtsam.CameraSetCal3Unified([camera1, camera2]) - cls.measurements = gtsam.Point2Vector([k.project(cls.origin) for k in cls.cameras]) + cls.poses = [pose1, pose2] + cls.cameras = [camera1, camera2] + cls.measurements = [k.project(cls.origin) for k in cls.cameras] def test_Cal3Unified(self): K = gtsam.Cal3Unified() @@ -147,7 +146,7 @@ class TestCal3Unified(GtsamTestCase): def test_triangulation_rectify(self): """Estimate spatial point from image measurements using rectification""" - rectified = gtsam.Point2Vector([k.calibration().calibrate(pt) for k, pt in zip(self.cameras, self.measurements)]) + rectified = [k.calibration().calibrate(pt) for k, pt in zip(self.cameras, self.measurements)] shared_cal = gtsam.Cal3_S2() triangulated = gtsam.triangulatePoint3(self.poses, shared_cal, rectified, rank_tol=1e-9, optimize=False) self.gtsamAssertEquals(triangulated, self.origin) diff --git a/python/gtsam/tests/test_DecisionTreeFactor.py b/python/gtsam/tests/test_DecisionTreeFactor.py index 0499e7215..1b8598953 100644 --- a/python/gtsam/tests/test_DecisionTreeFactor.py +++ b/python/gtsam/tests/test_DecisionTreeFactor.py @@ -13,7 +13,8 @@ Author: Frank Dellaert import unittest -from gtsam import DecisionTreeFactor, DiscreteValues, DiscreteDistribution, Ordering +from gtsam import (DecisionTreeFactor, DiscreteDistribution, DiscreteValues, + Ordering) from gtsam.utils.test_case import GtsamTestCase diff --git a/python/gtsam/tests/test_KarcherMeanFactor.py b/python/gtsam/tests/test_KarcherMeanFactor.py index f4ec64283..9ec33ad8a 100644 --- a/python/gtsam/tests/test_KarcherMeanFactor.py +++ b/python/gtsam/tests/test_KarcherMeanFactor.py @@ -31,7 +31,7 @@ class TestKarcherMean(GtsamTestCase): def test_find(self): # Check that optimizing for Karcher mean (which minimizes Between distance) # gets correct result. - rotations = gtsam.Rot3Vector([R, R.inverse()]) + rotations = [R, R.inverse()] expected = Rot3() actual = gtsam.FindKarcherMean(rotations) self.gtsamAssertEquals(expected, actual) @@ -42,7 +42,7 @@ class TestKarcherMean(GtsamTestCase): a2Rb2 = Rot3() a3Rb3 = Rot3() - aRb_list = gtsam.Rot3Vector([a1Rb1, a2Rb2, a3Rb3]) + aRb_list = [a1Rb1, a2Rb2, a3Rb3] aRb_expected = Rot3() aRb = gtsam.FindKarcherMean(aRb_list) @@ -58,9 +58,7 @@ class TestKarcherMean(GtsamTestCase): graph = gtsam.NonlinearFactorGraph() R12 = R.compose(R.compose(R)) graph.add(gtsam.BetweenFactorRot3(1, 2, R12, MODEL)) - keys = gtsam.KeyVector() - keys.append(1) - keys.append(2) + keys = [1, 2] graph.add(gtsam.KarcherMeanFactorRot3(keys)) initial = gtsam.Values() @@ -69,8 +67,7 @@ class TestKarcherMean(GtsamTestCase): expected = Rot3() result = gtsam.GaussNewtonOptimizer(graph, initial).optimize() - actual = gtsam.FindKarcherMean( - gtsam.Rot3Vector([result.atRot3(1), result.atRot3(2)])) + actual = gtsam.FindKarcherMean([result.atRot3(1), result.atRot3(2)]) self.gtsamAssertEquals(expected, actual) self.gtsamAssertEquals( R12, result.atRot3(1).between(result.atRot3(2))) diff --git a/python/gtsam/tests/test_Pose2.py b/python/gtsam/tests/test_Pose2.py index e5ffbad7d..d70483482 100644 --- a/python/gtsam/tests/test_Pose2.py +++ b/python/gtsam/tests/test_Pose2.py @@ -10,10 +10,9 @@ Author: Frank Dellaert & Duy Nguyen Ta & John Lambert """ import unittest -import numpy as np - import gtsam -from gtsam import Point2, Point2Pairs, Pose2 +import numpy as np +from gtsam import Point2, Pose2 from gtsam.utils.test_case import GtsamTestCase @@ -55,7 +54,7 @@ class TestPose2(GtsamTestCase): ] # fmt: on - ab_pairs = Point2Pairs(list(zip(pts_a, pts_b))) + ab_pairs = list(zip(pts_a, pts_b)) bTa = gtsam.align(ab_pairs) aTb = bTa.inverse() assert aTb is not None diff --git a/python/gtsam/tests/test_ShonanAveraging.py b/python/gtsam/tests/test_ShonanAveraging.py index 19b9f8dc1..036ea401c 100644 --- a/python/gtsam/tests/test_ShonanAveraging.py +++ b/python/gtsam/tests/test_ShonanAveraging.py @@ -14,16 +14,9 @@ import unittest import gtsam import numpy as np -from gtsam import ( - BetweenFactorPose2, - LevenbergMarquardtParams, - Rot2, - Pose2, - ShonanAveraging2, - ShonanAveragingParameters2, - ShonanAveraging3, - ShonanAveragingParameters3, -) +from gtsam import (BetweenFactorPose2, LevenbergMarquardtParams, Pose2, Rot2, + ShonanAveraging2, ShonanAveraging3, + ShonanAveragingParameters2, ShonanAveragingParameters3) from gtsam.utils.test_case import GtsamTestCase DEFAULT_PARAMS = ShonanAveragingParameters3( @@ -183,7 +176,7 @@ class TestShonanAveraging(GtsamTestCase): shonan_params.setCertifyOptimality(True) noise_model = gtsam.noiseModel.Unit.Create(3) - between_factors = gtsam.BetweenFactorPose2s() + between_factors = [] for (i1, i2), i2Ri1 in i2Ri1_dict.items(): i2Ti1 = Pose2(i2Ri1, np.zeros(2)) between_factors.append( diff --git a/python/gtsam/tests/test_Sim3.py b/python/gtsam/tests/test_Sim3.py index c00a36435..c3fd9e909 100644 --- a/python/gtsam/tests/test_Sim3.py +++ b/python/gtsam/tests/test_Sim3.py @@ -12,10 +12,9 @@ Author: John Lambert import unittest from typing import List, Optional -import numpy as np - import gtsam -from gtsam import Point3, Pose3, Pose3Pairs, Rot3, Similarity3 +import numpy as np +from gtsam import Point3, Pose3, Rot3, Similarity3 from gtsam.utils.test_case import GtsamTestCase @@ -49,7 +48,7 @@ class TestSim3(GtsamTestCase): wToi_list = [wTo0, wTo1, wTo2] - we_pairs = Pose3Pairs(list(zip(wToi_list, eToi_list))) + we_pairs = list(zip(wToi_list, eToi_list)) # Recover the transformation wSe (i.e. world_S_egovehicle) wSe = Similarity3.Align(we_pairs) @@ -84,7 +83,7 @@ class TestSim3(GtsamTestCase): wToi_list = [wTo0, wTo1, wTo2] - we_pairs = Pose3Pairs(list(zip(wToi_list, eToi_list))) + we_pairs = list(zip(wToi_list, eToi_list)) # Recover the transformation wSe (i.e. world_S_egovehicle) wSe = Similarity3.Align(we_pairs) @@ -122,7 +121,7 @@ class TestSim3(GtsamTestCase): bTi_list = [bTi0, bTi1, bTi2, bTi3] - ab_pairs = Pose3Pairs(list(zip(aTi_list, bTi_list))) + ab_pairs = list(zip(aTi_list, bTi_list)) # Recover the transformation wSe (i.e. world_S_egovehicle) aSb = Similarity3.Align(ab_pairs) @@ -689,7 +688,7 @@ def align_poses_sim3(aTi_list: List[Pose3], bTi_list: List[Pose3]) -> Similarity assert len(aTi_list) == len(bTi_list) assert n_to_align >= 2, "SIM(3) alignment uses at least 2 frames" - ab_pairs = Pose3Pairs(list(zip(aTi_list, bTi_list))) + ab_pairs = list(zip(aTi_list, bTi_list)) aSb = Similarity3.Align(ab_pairs) diff --git a/python/gtsam/tests/test_TranslationRecovery.py b/python/gtsam/tests/test_TranslationRecovery.py index 0fb0518b6..962b3cc9a 100644 --- a/python/gtsam/tests/test_TranslationRecovery.py +++ b/python/gtsam/tests/test_TranslationRecovery.py @@ -1,9 +1,9 @@ from __future__ import print_function -import numpy as np import unittest import gtsam +import numpy as np """ Returns example pose values of 3 points A, B and C in the world frame """ def ExampleValues(): @@ -19,7 +19,7 @@ def ExampleValues(): """ Returns binary measurements for the points in the given edges.""" def SimulateMeasurements(gt_poses, graph_edges): - measurements = gtsam.BinaryMeasurementsUnit3() + measurements = [] for edge in graph_edges: Ta = gt_poses.atPose3(edge[0]).translation() Tb = gt_poses.atPose3(edge[1]).translation() @@ -34,7 +34,7 @@ class TestTranslationRecovery(unittest.TestCase): def test_constructor(self): """Construct from binary measurements.""" - algorithm = gtsam.TranslationRecovery(gtsam.BinaryMeasurementsUnit3()) + algorithm = gtsam.TranslationRecovery([]) self.assertIsInstance(algorithm, gtsam.TranslationRecovery) def test_run(self): diff --git a/python/gtsam/tests/test_Triangulation.py b/python/gtsam/tests/test_Triangulation.py index 0a258a0af..0de0f6d95 100644 --- a/python/gtsam/tests/test_Triangulation.py +++ b/python/gtsam/tests/test_Triangulation.py @@ -11,23 +11,11 @@ Authors: Frank Dellaert & Fan Jiang (Python) & Sushmita Warrier & John Lambert import unittest from typing import Iterable, List, Optional, Tuple, Union -import numpy as np - import gtsam -from gtsam import ( - Cal3_S2, - Cal3Bundler, - CameraSetCal3_S2, - CameraSetCal3Bundler, - PinholeCameraCal3_S2, - PinholeCameraCal3Bundler, - Point2, - Point2Vector, - Point3, - Pose3, - Pose3Vector, - Rot3, -) +import numpy as np +from gtsam import (Cal3_S2, Cal3Bundler, CameraSetCal3_S2, + CameraSetCal3Bundler, PinholeCameraCal3_S2, + PinholeCameraCal3Bundler, Point2, Point3, Pose3, Rot3) from gtsam.utils.test_case import GtsamTestCase UPRIGHT = Rot3.Ypr(-np.pi / 2, 0.0, -np.pi / 2) @@ -44,9 +32,7 @@ class TestTriangulationExample(GtsamTestCase): # create second camera 1 meter to the right of first camera pose2 = pose1.compose(Pose3(Rot3(), Point3(1, 0, 0))) # twoPoses - self.poses = Pose3Vector() - self.poses.append(pose1) - self.poses.append(pose2) + self.poses = [pose1, pose2] # landmark ~5 meters infront of camera self.landmark = Point3(5, 0.5, 1.2) @@ -58,7 +44,7 @@ class TestTriangulationExample(GtsamTestCase): cal_params: Iterable[Iterable[Union[int, float]]], camera_set: Optional[Union[CameraSetCal3Bundler, CameraSetCal3_S2]] = None, - ) -> Tuple[Point2Vector, Union[CameraSetCal3Bundler, CameraSetCal3_S2, + ) -> Tuple[List[Point2], Union[CameraSetCal3Bundler, CameraSetCal3_S2, List[Cal3Bundler], List[Cal3_S2]]]: """ Generate vector of measurements for given calibration and camera model. @@ -76,7 +62,7 @@ class TestTriangulationExample(GtsamTestCase): cameras = camera_set() else: cameras = [] - measurements = Point2Vector() + measurements = [] for k, pose in zip(cal_params, self.poses): K = calibration(*k) @@ -105,7 +91,7 @@ class TestTriangulationExample(GtsamTestCase): self.gtsamAssertEquals(self.landmark, triangulated_landmark, 1e-9) # Add some noise and try again: result should be ~ (4.995, 0.499167, 1.19814) - measurements_noisy = Point2Vector() + measurements_noisy = [] measurements_noisy.append(measurements[0] - np.array([0.1, 0.5])) measurements_noisy.append(measurements[1] - np.array([-0.2, 0.3])) @@ -172,8 +158,8 @@ class TestTriangulationExample(GtsamTestCase): z2: Point2 = camera2.project(landmark) z3: Point2 = camera3.project(landmark) - poses = gtsam.Pose3Vector([pose1, pose2, pose3]) - measurements = Point2Vector([z1, z2, z3]) + poses = [pose1, pose2, pose3] + measurements = [z1, z2, z3] # noise free, so should give exactly the landmark actual = gtsam.triangulatePoint3(poses, From fe9c5718bbea01f523eb4afb344d5b82f948a484 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 31 Jan 2022 14:09:57 -0500 Subject: [PATCH 0080/1686] update CMake ignore list --- python/CMakeLists.txt | 27 ++------------------------- 1 file changed, 2 insertions(+), 25 deletions(-) diff --git a/python/CMakeLists.txt b/python/CMakeLists.txt index 85ddc7b6d..e666dced3 100644 --- a/python/CMakeLists.txt +++ b/python/CMakeLists.txt @@ -34,22 +34,7 @@ set(ignore gtsam::Point2 gtsam::Point3 gtsam::ISAM2ThresholdMapValue - gtsam::FactorIndices - gtsam::FactorIndexSet - gtsam::IndexPairSetMap - gtsam::IndexPairVector - gtsam::BetweenFactorPose2s - gtsam::BetweenFactorPose3s - gtsam::Point2Vector - gtsam::Point2Pairs - gtsam::Point3Pairs - gtsam::Pose3Pairs - gtsam::Pose3Vector - gtsam::Rot3Vector - gtsam::KeyVector - gtsam::BinaryMeasurementsUnit3 - gtsam::DiscreteKey - gtsam::KeyPairDoubleMap) + gtsam::DiscreteKey) set(interface_headers ${PROJECT_SOURCE_DIR}/gtsam/gtsam.i @@ -117,19 +102,11 @@ if(GTSAM_UNSTABLE_BUILD_PYTHON) gtsam::Point2 gtsam::Point3 gtsam::ISAM2ThresholdMapValue - gtsam::FactorIndices - gtsam::FactorIndexSet - gtsam::BetweenFactorPose3s - gtsam::Point2Vector - gtsam::Pose3Vector - gtsam::KeyVector gtsam::FixedLagSmootherKeyTimestampMapValue - gtsam::BinaryMeasurementsUnit3 gtsam::CameraSetCal3_S2 gtsam::CameraSetCal3Bundler gtsam::CameraSetCal3Unified - gtsam::CameraSetCal3Fisheye - gtsam::KeyPairDoubleMap) + gtsam::CameraSetCal3Fisheye) pybind_wrap(${GTSAM_PYTHON_UNSTABLE_TARGET} # target ${PROJECT_SOURCE_DIR}/gtsam_unstable/gtsam_unstable.i # interface_header From c68c986321d2b88fd17900da87c6302e8c236a5c Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 31 Jan 2022 17:54:50 -0500 Subject: [PATCH 0081/1686] Fix IndexPairVector wrapping --- gtsam/base/base.i | 13 ------------- python/gtsam/preamble/base.h | 1 - 2 files changed, 14 deletions(-) diff --git a/gtsam/base/base.i b/gtsam/base/base.i index fbbd91553..212578736 100644 --- a/gtsam/base/base.i +++ b/gtsam/base/base.i @@ -41,19 +41,6 @@ class DSFMap { std::map sets(); }; -class IndexPairVector { - IndexPairVector(); - IndexPairVector(const gtsam::IndexPairVector& other); - - // common STL methods - size_t size() const; - bool empty() const; - void clear(); - - // structure specific methods - gtsam::IndexPair at(size_t i) const; - void push_back(gtsam::IndexPair key) const; -}; gtsam::IndexPairVector IndexPairSetAsArray(gtsam::IndexPairSet& set); diff --git a/python/gtsam/preamble/base.h b/python/gtsam/preamble/base.h index a7effd1ca..affb03ffa 100644 --- a/python/gtsam/preamble/base.h +++ b/python/gtsam/preamble/base.h @@ -11,5 +11,4 @@ * mutations on Python side will not be reflected on C++. */ -PYBIND11_MAKE_OPAQUE(std::vector); PYBIND11_MAKE_OPAQUE(std::vector); // JacobianVector From ef912eefd3689edf05133c45e3f74483970456e1 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 31 Jan 2022 18:53:39 -0500 Subject: [PATCH 0082/1686] minor cleanup --- python/gtsam/preamble/base.h | 2 -- 1 file changed, 2 deletions(-) diff --git a/python/gtsam/preamble/base.h b/python/gtsam/preamble/base.h index affb03ffa..d07a75f6f 100644 --- a/python/gtsam/preamble/base.h +++ b/python/gtsam/preamble/base.h @@ -10,5 +10,3 @@ * Without this they will be automatically converted to a Python object, and all * mutations on Python side will not be reflected on C++. */ - -PYBIND11_MAKE_OPAQUE(std::vector); // JacobianVector From fbe9a21070c90454bfdf9e3c5dc43d6387e64ffc Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 31 Jan 2022 18:55:40 -0500 Subject: [PATCH 0083/1686] attempt to get custom factor tests passing --- gtsam/nonlinear/CustomFactor.cpp | 16 +++++++++---- gtsam/nonlinear/CustomFactor.h | 5 ++-- python/gtsam/tests/test_custom_factor.py | 29 ++++++++++++------------ 3 files changed, 29 insertions(+), 21 deletions(-) diff --git a/gtsam/nonlinear/CustomFactor.cpp b/gtsam/nonlinear/CustomFactor.cpp index e33caed6f..b8368c497 100644 --- a/gtsam/nonlinear/CustomFactor.cpp +++ b/gtsam/nonlinear/CustomFactor.cpp @@ -22,13 +22,14 @@ namespace gtsam { /* * Calculates the unwhitened error by invoking the callback functor (i.e. from Python). */ -Vector CustomFactor::unwhitenedError(const Values& x, boost::optional&> H) const { +Vector CustomFactor::unwhitenedError( + const Values &x, boost::optional&> H) const { if(this->active(x)) { if(H) { /* * In this case, we pass the raw pointer to the `std::vector` object directly to pybind. - * As the type `std::vector` has been marked as opaque in `preamble.h`, any changes in + * As the type `std::vector` has been marked as opaque in `preamble/base.h`, any changes in * Python will be immediately reflected on the C++ side. * * Example: @@ -43,13 +44,20 @@ Vector CustomFactor::unwhitenedError(const Values& x, boost::optionalerror_function_(*this, x, H.get_ptr()); + std::pair errorAndJacobian = + this->error_function_(*this, x, H.get_ptr()); + + Vector error = errorAndJacobian.first; + (*H) = errorAndJacobian.second; + + return error; } else { /* * In this case, we pass the a `nullptr` to pybind, and it will translate to `None` in Python. * Users can check for `None` in their callback to determine if the Jacobian is requested. */ - return this->error_function_(*this, x, nullptr); + auto errorAndJacobian = this->error_function_(*this, x, nullptr); + return errorAndJacobian.first; } } else { return Vector::Zero(this->dim()); diff --git a/gtsam/nonlinear/CustomFactor.h b/gtsam/nonlinear/CustomFactor.h index 615b5418e..6261636b5 100644 --- a/gtsam/nonlinear/CustomFactor.h +++ b/gtsam/nonlinear/CustomFactor.h @@ -35,7 +35,8 @@ class CustomFactor; * This is safe because this is passing a const pointer, and pybind11 will maintain the `std::vector` memory layout. * Thus the pointer will never be invalidated. */ -using CustomErrorFunction = std::function; +using CustomErrorFunction = std::function( + const CustomFactor &, const Values &, JacobianVector *)>; /** * @brief Custom factor that takes a std::function as the error @@ -77,7 +78,7 @@ public: * Calls the errorFunction closure, which is a std::function object * One can check if a derivative is needed in the errorFunction by checking the length of Jacobian array */ - Vector unwhitenedError(const Values &x, boost::optional &> H = boost::none) const override; + Vector unwhitenedError(const Values &x, boost::optional&> H = boost::none) const override; /** print */ void print(const std::string &s, diff --git a/python/gtsam/tests/test_custom_factor.py b/python/gtsam/tests/test_custom_factor.py index 4f0f33361..03e6917f0 100644 --- a/python/gtsam/tests/test_custom_factor.py +++ b/python/gtsam/tests/test_custom_factor.py @@ -8,13 +8,12 @@ See LICENSE for the license information CustomFactor unit tests. Author: Fan Jiang """ -from typing import List import unittest -from gtsam import Values, Pose2, CustomFactor - -import numpy as np +from typing import List import gtsam +import numpy as np +from gtsam import CustomFactor, JacobianFactor, Pose2, Values from gtsam.utils.test_case import GtsamTestCase @@ -24,17 +23,17 @@ class TestCustomFactor(GtsamTestCase): def error_func(this: CustomFactor, v: gtsam.Values, H: List[np.ndarray]): """Minimal error function stub""" - return np.array([1, 0, 0]) + return np.array([1, 0, 0]), H noise_model = gtsam.noiseModel.Unit.Create(3) - cf = CustomFactor(noise_model, gtsam.KeyVector([0]), error_func) + cf = CustomFactor(noise_model, [0], error_func) def test_new_keylist(self): """Test the creation of a new CustomFactor""" def error_func(this: CustomFactor, v: gtsam.Values, H: List[np.ndarray]): """Minimal error function stub""" - return np.array([1, 0, 0]) + return np.array([1, 0, 0]), H noise_model = gtsam.noiseModel.Unit.Create(3) cf = CustomFactor(noise_model, [0], error_func) @@ -47,7 +46,7 @@ class TestCustomFactor(GtsamTestCase): """Minimal error function with no Jacobian""" key0 = this.keys()[0] error = -v.atPose2(key0).localCoordinates(expected_pose) - return error + return error, H noise_model = gtsam.noiseModel.Unit.Create(3) cf = CustomFactor(noise_model, [0], error_func) @@ -81,10 +80,10 @@ class TestCustomFactor(GtsamTestCase): result = gT1.between(gT2) H[0] = -result.inverse().AdjointMap() H[1] = np.eye(3) - return error + return error, H noise_model = gtsam.noiseModel.Unit.Create(3) - cf = CustomFactor(noise_model, gtsam.KeyVector([0, 1]), error_func) + cf = CustomFactor(noise_model, [0, 1], error_func) v = Values() v.insert(0, gT1) v.insert(1, gT2) @@ -104,9 +103,9 @@ class TestCustomFactor(GtsamTestCase): gT1 = Pose2(1, 2, np.pi / 2) gT2 = Pose2(-1, 4, np.pi) - def error_func(this: CustomFactor, v: gtsam.Values, _: List[np.ndarray]): + def error_func(this: CustomFactor, v: gtsam.Values, H: List[np.ndarray]): """Minimal error function stub""" - return np.array([1, 0, 0]) + return np.array([1, 0, 0]), H noise_model = gtsam.noiseModel.Unit.Create(3) from gtsam.symbol_shorthand import X @@ -144,10 +143,10 @@ class TestCustomFactor(GtsamTestCase): result = gT1.between(gT2) H[0] = -result.inverse().AdjointMap() H[1] = np.eye(3) - return error + return error, H noise_model = gtsam.noiseModel.Unit.Create(3) - cf = CustomFactor(noise_model, gtsam.KeyVector([0, 1]), error_func) + cf = CustomFactor(noise_model, [0, 1], error_func) v = Values() v.insert(0, gT1) v.insert(1, gT2) @@ -182,7 +181,7 @@ class TestCustomFactor(GtsamTestCase): result = gT1.between(gT2) H[0] = -result.inverse().AdjointMap() H[1] = np.eye(3) - return error + return error, H noise_model = gtsam.noiseModel.Unit.Create(3) cf = CustomFactor(noise_model, [0, 1], error_func) From 784bdc64c5266990201e5d8659d05a2084fe7567 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sun, 6 Feb 2022 00:08:31 -0500 Subject: [PATCH 0084/1686] minor fixes to Pose2 and Rot2 --- gtsam/geometry/Pose2.h | 4 ++-- gtsam/geometry/Rot2.cpp | 16 ++++++++-------- gtsam/geometry/Rot2.h | 2 +- 3 files changed, 11 insertions(+), 11 deletions(-) diff --git a/gtsam/geometry/Pose2.h b/gtsam/geometry/Pose2.h index 12087a34c..eb8ddfb5b 100644 --- a/gtsam/geometry/Pose2.h +++ b/gtsam/geometry/Pose2.h @@ -324,8 +324,8 @@ GTSAM_EXPORT boost::optional align(const std::vector& pairs); // Convenience typedef using Pose2Pair = std::pair; -using Pose2Pairs = std::vector >; - +using Pose2Pairs = std::vector; + template <> struct traits : public internal::LieGroup {}; diff --git a/gtsam/geometry/Rot2.cpp b/gtsam/geometry/Rot2.cpp index 9f62869e4..d43b9b12d 100644 --- a/gtsam/geometry/Rot2.cpp +++ b/gtsam/geometry/Rot2.cpp @@ -130,15 +130,15 @@ Rot2 Rot2::relativeBearing(const Point2& d, OptionalJacobian<1, 2> H) { } /* ************************************************************************* */ -static Rot2 ClosestTo(const Matrix2& M) { - double c = M(0,0); - double s = M(1,0); - double theta_rad = atan2(s, c); - c = cos(theta_rad); - s = sin(theta_rad); - return Rot2::fromCosSin(c, s); +Rot2 Rot2::ClosestTo(const Matrix2& M) { + double c = M(0, 0); + double s = M(1, 0); + double theta_rad = std::atan2(s, c); + c = cos(theta_rad); + s = sin(theta_rad); + return Rot2::fromCosSin(c, s); } - + /* ************************************************************************* */ } // gtsam diff --git a/gtsam/geometry/Rot2.h b/gtsam/geometry/Rot2.h index 42dba3487..2690ca248 100644 --- a/gtsam/geometry/Rot2.h +++ b/gtsam/geometry/Rot2.h @@ -209,7 +209,7 @@ namespace gtsam { /** return 2*2 transpose (inverse) rotation matrix */ Matrix2 transpose() const; - + /** Find closest valid rotation matrix, given a 2x2 matrix */ static Rot2 ClosestTo(const Matrix2& M); From bf668e58697f5236ba20363b7b100714ea70820b Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sun, 6 Feb 2022 00:08:54 -0500 Subject: [PATCH 0085/1686] Similarity2 fixes --- gtsam/geometry/Similarity2.cpp | 180 ++++++++++++++++++--------------- gtsam/geometry/Similarity2.h | 110 +++++++++----------- 2 files changed, 146 insertions(+), 144 deletions(-) diff --git a/gtsam/geometry/Similarity2.cpp b/gtsam/geometry/Similarity2.cpp index 5a63e70cb..12529f52d 100644 --- a/gtsam/geometry/Similarity2.cpp +++ b/gtsam/geometry/Similarity2.cpp @@ -15,21 +15,21 @@ * @author John Lambert */ -#include - -#include -#include #include +#include +#include +#include #include namespace gtsam { using std::vector; -namespace { +namespace internal { + /// Subtract centroids from point pairs. -static Point2Pairs subtractCentroids(const Point2Pairs &abPointPairs, - const Point2Pair ¢roids) { +static Point2Pairs subtractCentroids(const Point2Pairs& abPointPairs, + const Point2Pair& centroids) { Point2Pairs d_abPointPairs; for (const Point2Pair& abPair : abPointPairs) { Point2 da = abPair.first - centroids.first; @@ -40,10 +40,11 @@ static Point2Pairs subtractCentroids(const Point2Pairs &abPointPairs, } /// Form inner products x and y and calculate scale. -static const double calculateScale(const Point2Pairs &d_abPointPairs, - const Rot2 &aRb) { +static double calculateScale(const Point2Pairs& d_abPointPairs, + const Rot2& aRb) { double x = 0, y = 0; Point2 da, db; + for (const Point2Pair& d_abPair : d_abPointPairs) { std::tie(da, db) = d_abPair; const Vector2 da_prime = aRb * db; @@ -55,7 +56,7 @@ static const double calculateScale(const Point2Pairs &d_abPointPairs, } /// Form outer product H. -static Matrix2 calculateH(const Point2Pairs &d_abPointPairs) { +static Matrix2 calculateH(const Point2Pairs& d_abPointPairs) { Matrix2 H = Z_2x2; for (const Point2Pair& d_abPair : d_abPointPairs) { H += d_abPair.first * d_abPair.second.transpose(); @@ -63,10 +64,17 @@ static Matrix2 calculateH(const Point2Pairs &d_abPointPairs) { return H; } -/// This method estimates the similarity transform from differences point pairs, -// given a known or estimated rotation and point centroids. -static Similarity2 align(const Point2Pairs &d_abPointPairs, const Rot2 &aRb, - const Point2Pair ¢roids) { +/** + * @brief This method estimates the similarity transform from differences point + * pairs, given a known or estimated rotation and point centroids. + * + * @param d_abPointPairs + * @param aRb + * @param centroids + * @return Similarity2 + */ +static Similarity2 align(const Point2Pairs& d_abPointPairs, const Rot2& aRb, + const Point2Pair& centroids) { const double s = calculateScale(d_abPointPairs, aRb); // dividing aTb by s is required because the registration cost function // minimizes ||a - sRb - t||, whereas Sim(2) computes s(Rb + t) @@ -74,39 +82,44 @@ static Similarity2 align(const Point2Pairs &d_abPointPairs, const Rot2 &aRb, return Similarity2(aRb, aTb, s); } -/// This method estimates the similarity transform from point pairs, given a known or estimated rotation. -// Refer to: http://www5.informatik.uni-erlangen.de/Forschung/Publikationen/2005/Zinsser05-PSR.pdf Chapter 3 -static Similarity2 alignGivenR(const Point2Pairs &abPointPairs, - const Rot2 &aRb) { +/** + * @brief This method estimates the similarity transform from point pairs, + * given a known or estimated rotation. + * Refer to: + * http://www5.informatik.uni-erlangen.de/Forschung/Publikationen/2005/Zinsser05-PSR.pdf + * Chapter 3 + * + * @param abPointPairs + * @param aRb + * @return Similarity2 + */ +static Similarity2 alignGivenR(const Point2Pairs& abPointPairs, + const Rot2& aRb) { auto centroids = means(abPointPairs); - auto d_abPointPairs = subtractCentroids(abPointPairs, centroids); - return align(d_abPointPairs, aRb, centroids); + auto d_abPointPairs = internal::subtractCentroids(abPointPairs, centroids); + return internal::align(d_abPointPairs, aRb, centroids); } -} // namespace +} // namespace internal -Similarity2::Similarity2() : - t_(0,0), s_(1) { -} +Similarity2::Similarity2() : t_(0, 0), s_(1) {} -Similarity2::Similarity2(double s) : - t_(0,0), s_(s) { -} +Similarity2::Similarity2(double s) : t_(0, 0), s_(s) {} -Similarity2::Similarity2(const Rot2& R, const Point2& t, double s) : - R_(R), t_(t), s_(s) { -} +Similarity2::Similarity2(const Rot2& R, const Point2& t, double s) + : R_(R), t_(t), s_(s) {} -// Similarity2::Similarity2(const Matrix2& R, const Vector2& t, double s) : -// R_(Rot2::ClosestTo(R)), t_(t), s_(s) { -// } +Similarity2::Similarity2(const Matrix2& R, const Vector2& t, double s) + : R_(Rot2::ClosestTo(R)), t_(t), s_(s) {} -// Similarity2::Similarity2(const Matrix3& T) : -// R_(Rot2::ClosestTo(T.topLeftCorner<2, 2>())), t_(T.topRightCorner<2, 1>()), s_(1.0 / T(2, 2)) { -// } +Similarity2::Similarity2(const Matrix3& T) + : R_(Rot2::ClosestTo(T.topLeftCorner<2, 2>())), + t_(T.topRightCorner<2, 1>()), + s_(1.0 / T(2, 2)) {} bool Similarity2::equals(const Similarity2& other, double tol) const { - return R_.equals(other.R_, tol) && traits::Equals(t_, other.t_, tol) - && s_ < (other.s_ + tol) && s_ > (other.s_ - tol); + return R_.equals(other.R_, tol) && + traits::Equals(t_, other.t_, tol) && s_ < (other.s_ + tol) && + s_ > (other.s_ - tol); } bool Similarity2::operator==(const Similarity2& other) const { @@ -117,15 +130,15 @@ void Similarity2::print(const std::string& s) const { std::cout << std::endl; std::cout << s; rotation().print("\nR:\n"); - std::cout << "t: " << translation().transpose() << " s: " << scale() << std::endl; + std::cout << "t: " << translation().transpose() << " s: " << scale() + << std::endl; } -Similarity2 Similarity2::identity() { - return Similarity2(); +Similarity2 Similarity2::identity() { return Similarity2(); } + +Similarity2 Similarity2::operator*(const Similarity2& S) const { + return Similarity2(R_ * S.R_, ((1.0 / S.s_) * t_) + R_ * S.t_, s_ * S.s_); } -// Similarity2 Similarity2::operator*(const Similarity2& S) const { -// return Similarity2(R_ * S.R_, ((1.0 / S.s_) * t_) + R_ * S.t_, s_ * S.s_); -// } Similarity2 Similarity2::inverse() const { const Rot2 Rt = R_.inverse(); @@ -148,57 +161,56 @@ Point2 Similarity2::operator*(const Point2& p) const { return transformFrom(p); } -// Similarity2 Similarity2::Align(const Point2Pairs &abPointPairs) { -// // Refer to Chapter 3 of -// // http://www5.informatik.uni-erlangen.de/Forschung/Publikationen/2005/Zinsser05-PSR.pdf -// if (abPointPairs.size() < 2) -// throw std::runtime_error("input should have at least 2 pairs of points"); -// auto centroids = means(abPointPairs); -// auto d_abPointPairs = subtractCentroids(abPointPairs, centroids); -// Matrix3 H = calculateH(d_abPointPairs); -// // ClosestTo finds rotation matrix closest to H in Frobenius sense -// Rot2 aRb = Rot2::ClosestTo(H); -// return align(d_abPointPairs, aRb, centroids); -// } +Similarity2 Similarity2::Align(const Point2Pairs& abPointPairs) { + // Refer to Chapter 3 of + // http://www5.informatik.uni-erlangen.de/Forschung/Publikationen/2005/Zinsser05-PSR.pdf + if (abPointPairs.size() < 2) + throw std::runtime_error("input should have at least 2 pairs of points"); + auto centroids = means(abPointPairs); + auto d_abPointPairs = internal::subtractCentroids(abPointPairs, centroids); + Matrix2 H = internal::calculateH(d_abPointPairs); + // ClosestTo finds rotation matrix closest to H in Frobenius sense + Rot2 aRb = Rot2::ClosestTo(H); + return internal::align(d_abPointPairs, aRb, centroids); +} -// Similarity2 Similarity2::Align(const vector &abPosePairs) { -// const size_t n = abPosePairs.size(); -// if (n < 2) -// throw std::runtime_error("input should have at least 2 pairs of poses"); +Similarity2 Similarity2::Align(const Pose2Pairs& abPosePairs) { + const size_t n = abPosePairs.size(); + if (n < 2) + throw std::runtime_error("input should have at least 2 pairs of poses"); -// // calculate rotation -// vector rotations; -// Point2Pairs abPointPairs; -// rotations.reserve(n); -// abPointPairs.reserve(n); -// // Below denotes the pose of the i'th object/camera/etc in frame "a" or frame "b" -// Pose2 aTi, bTi; -// for (const Pose2Pair &abPair : abPosePairs) { -// std::tie(aTi, bTi) = abPair; -// const Rot2 aRb = aTi.rotation().compose(bTi.rotation().inverse()); -// rotations.emplace_back(aRb); -// abPointPairs.emplace_back(aTi.translation(), bTi.translation()); -// } -// const Rot2 aRb_estimate = FindKarcherMean(rotations); + // calculate rotation + vector rotations; + Point2Pairs abPointPairs; + rotations.reserve(n); + abPointPairs.reserve(n); + // Below denotes the pose of the i'th object/camera/etc + // in frame "a" or frame "b". + Pose2 aTi, bTi; + for (const Pose2Pair& abPair : abPosePairs) { + std::tie(aTi, bTi) = abPair; + const Rot2 aRb = aTi.rotation().compose(bTi.rotation().inverse()); + rotations.emplace_back(aRb); + abPointPairs.emplace_back(aTi.translation(), bTi.translation()); + } + const Rot2 aRb_estimate; // = FindKarcherMean(rotations); -// return alignGivenR(abPointPairs, aRb_estimate); -// } + return internal::alignGivenR(abPointPairs, aRb_estimate); +} -std::ostream &operator<<(std::ostream &os, const Similarity2& p) { - os << "[" << p.rotation().theta() << " " - << p.translation().transpose() << " " << p.scale() << "]\';"; +std::ostream& operator<<(std::ostream& os, const Similarity2& p) { + os << "[" << p.rotation().theta() << " " << p.translation().transpose() << " " + << p.scale() << "]\';"; return os; } -const Matrix3 Similarity2::matrix() const { +Matrix3 Similarity2::matrix() const { Matrix3 T; T.topRows<2>() << R_.matrix(), t_; T.bottomRows<1>() << 0, 0, 1.0 / s_; return T; } -Similarity2::operator Pose2() const { - return Pose2(R_, s_ * t_); -} +Similarity2::operator Pose2() const { return Pose2(R_, s_ * t_); } -} // namespace gtsam +} // namespace gtsam diff --git a/gtsam/geometry/Similarity2.h b/gtsam/geometry/Similarity2.h index 85a6324c5..93a1227f5 100644 --- a/gtsam/geometry/Similarity2.h +++ b/gtsam/geometry/Similarity2.h @@ -17,13 +17,12 @@ #pragma once -#include -#include -#include #include #include #include - +#include +#include +#include namespace gtsam { @@ -33,21 +32,19 @@ class Pose2; /** * 2D similarity transform */ -class Similarity2: public LieGroup { - +class Similarity2 : public LieGroup { /// @name Pose Concept /// @{ typedef Rot2 Rotation; typedef Point2 Translation; /// @} -private: + private: Rot2 R_; Point2 t_; double s_; -public: - + public: /// @name Constructors /// @{ @@ -60,11 +57,11 @@ public: /// Construct from GTSAM types GTSAM_EXPORT Similarity2(const Rot2& R, const Point2& t, double s); - // /// Construct from Eigen types - // GTSAM_EXPORT Similarity2(const Matrix2& R, const Vector2& t, double s); + /// Construct from Eigen types + GTSAM_EXPORT Similarity2(const Matrix2& R, const Vector2& t, double s); - // /// Construct from matrix [R t; 0 s^-1] - // GTSAM_EXPORT Similarity2(const Matrix3& T); + /// Construct from matrix [R t; 0 s^-1] + GTSAM_EXPORT Similarity2(const Matrix3& T); /// @} /// @name Testable @@ -79,7 +76,8 @@ public: /// Print with optional string GTSAM_EXPORT void print(const std::string& s) const; - GTSAM_EXPORT friend std::ostream &operator<<(std::ostream &os, const Similarity2& p); + GTSAM_EXPORT friend std::ostream& operator<<(std::ostream& os, + const Similarity2& p); /// @} /// @name Group @@ -94,22 +92,22 @@ public: /// Return the inverse GTSAM_EXPORT Similarity2 inverse() const; - // /// @} - // /// @name Group action on Point2 - // /// @{ + /// @} + /// @name Group action on Point2 + /// @{ /// Action on a point p is s*(R*p+t) GTSAM_EXPORT Point2 transformFrom(const Point2& p) const; - /** + /** * Action on a pose T. - * |Rs ts| |R t| |Rs*R Rs*t+ts| + * |Rs ts| |R t| |Rs*R Rs*t+ts| * |0 1/s| * |0 1| = | 0 1/s |, the result is still a Sim2 object. * To retrieve a Pose2, we normalized the scale value into 1. * |Rs*R Rs*t+ts| |Rs*R s(Rs*t+ts)| * | 0 1/s | = | 0 1 | - * - * This group action satisfies the compatibility condition. + * + * This group action satisfies the compatibility condition. * For more details, refer to: https://en.wikipedia.org/wiki/Group_action */ GTSAM_EXPORT Pose2 transformFrom(const Pose2& T) const; @@ -117,22 +115,26 @@ public: /* syntactic sugar for transformFrom */ GTSAM_EXPORT Point2 operator*(const Point2& p) const; - // /** - // * Create Similarity2 by aligning at least two point pairs - // */ - // GTSAM_EXPORT static Similarity2 Align(const std::vector& abPointPairs); - - // /** - // * Create the Similarity2 object that aligns at least two pose pairs. - // * Each pair is of the form (aTi, bTi). - // * Given a list of pairs in frame a, and a list of pairs in frame b, Align() - // * will compute the best-fit Similarity2 aSb transformation to align them. - // * First, the rotation aRb will be computed as the average (Karcher mean) of - // * many estimates aRb (from each pair). Afterwards, the scale factor will be computed - // * using the algorithm described here: - // * http://www5.informatik.uni-erlangen.de/Forschung/Publikationen/2005/Zinsser05-PSR.pdf - // */ - // GTSAM_EXPORT static Similarity2 Align(const std::vector& abPosePairs); + /** + * Create Similarity2 by aligning at least two point pairs + */ + GTSAM_EXPORT static Similarity2 Align(const Point2Pairs& abPointPairs); + + /** + * Create the Similarity2 object that aligns at least two pose pairs. + * Each pair is of the form (aTi, bTi). + * Given a list of pairs in frame a, and a list of pairs in frame b, + Align() + * will compute the best-fit Similarity2 aSb transformation to align them. + * First, the rotation aRb will be computed as the average (Karcher mean) + of + * many estimates aRb (from each pair). Afterwards, the scale factor will + be computed + * using the algorithm described here: + * http://www5.informatik.uni-erlangen.de/Forschung/Publikationen/2005/Zinsser05-PSR.pdf + */ + GTSAM_EXPORT static Similarity2 Align( + const std::vector& abPosePairs); /// @} /// @name Lie Group @@ -145,45 +147,33 @@ public: /// @{ /// Calculate 4*4 matrix group equivalent - GTSAM_EXPORT const Matrix3 matrix() const; + GTSAM_EXPORT Matrix3 matrix() const; /// Return a GTSAM rotation - const Rot2& rotation() const { - return R_; - } + Rot2 rotation() const { return R_; } /// Return a GTSAM translation - const Point2& translation() const { - return t_; - } + Point2 translation() const { return t_; } /// Return the scale - double scale() const { - return s_; - } + double scale() const { return s_; } /// Convert to a rigid body pose (R, s*t) - /// TODO(frank): why is this here? Red flag! Definitely don't have it as a cast. GTSAM_EXPORT operator Pose2() const; /// Dimensionality of tangent space = 4 DOF - used to autodetect sizes - inline static size_t Dim() { - return 4; - } + inline static size_t Dim() { return 4; } /// Dimensionality of tangent space = 4 DOF - inline size_t dim() const { - return 4; - } + inline size_t dim() const { return 4; } /// @} }; +template <> +struct traits : public internal::LieGroup {}; -// template<> -// struct traits : public internal::LieGroup {}; +template <> +struct traits : public internal::LieGroup {}; -// template<> -// struct traits : public internal::LieGroup {}; - -} // namespace gtsam +} // namespace gtsam From a57465ee642558b35f8fefcc7a351c6937f84959 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sun, 6 Feb 2022 00:09:06 -0500 Subject: [PATCH 0086/1686] Similarity3 fixes --- gtsam/geometry/Similarity3.cpp | 16 ++++++++-------- gtsam/geometry/Similarity3.h | 6 +++--- 2 files changed, 11 insertions(+), 11 deletions(-) diff --git a/gtsam/geometry/Similarity3.cpp b/gtsam/geometry/Similarity3.cpp index fcaf0c874..58bace0f1 100644 --- a/gtsam/geometry/Similarity3.cpp +++ b/gtsam/geometry/Similarity3.cpp @@ -26,7 +26,7 @@ namespace gtsam { using std::vector; -namespace { +namespace internal { /// Subtract centroids from point pairs. static Point3Pairs subtractCentroids(const Point3Pairs &abPointPairs, const Point3Pair ¢roids) { @@ -79,10 +79,10 @@ static Similarity3 align(const Point3Pairs &d_abPointPairs, const Rot3 &aRb, static Similarity3 alignGivenR(const Point3Pairs &abPointPairs, const Rot3 &aRb) { auto centroids = means(abPointPairs); - auto d_abPointPairs = subtractCentroids(abPointPairs, centroids); + auto d_abPointPairs = internal::subtractCentroids(abPointPairs, centroids); return align(d_abPointPairs, aRb, centroids); } -} // namespace +} // namespace internal Similarity3::Similarity3() : t_(0,0,0), s_(1) { @@ -163,11 +163,11 @@ Similarity3 Similarity3::Align(const Point3Pairs &abPointPairs) { if (abPointPairs.size() < 3) throw std::runtime_error("input should have at least 3 pairs of points"); auto centroids = means(abPointPairs); - auto d_abPointPairs = subtractCentroids(abPointPairs, centroids); - Matrix3 H = calculateH(d_abPointPairs); + auto d_abPointPairs = internal::subtractCentroids(abPointPairs, centroids); + Matrix3 H = internal::calculateH(d_abPointPairs); // ClosestTo finds rotation matrix closest to H in Frobenius sense Rot3 aRb = Rot3::ClosestTo(H); - return align(d_abPointPairs, aRb, centroids); + return internal::align(d_abPointPairs, aRb, centroids); } Similarity3 Similarity3::Align(const vector &abPosePairs) { @@ -190,7 +190,7 @@ Similarity3 Similarity3::Align(const vector &abPosePairs) { } const Rot3 aRb_estimate = FindKarcherMean(rotations); - return alignGivenR(abPointPairs, aRb_estimate); + return internal::alignGivenR(abPointPairs, aRb_estimate); } Matrix4 Similarity3::wedge(const Vector7 &xi) { @@ -281,7 +281,7 @@ std::ostream &operator<<(std::ostream &os, const Similarity3& p) { return os; } -const Matrix4 Similarity3::matrix() const { +Matrix4 Similarity3::matrix() const { Matrix4 T; T.topRows<3>() << R_.matrix(), t_; T.bottomRows<1>() << 0, 0, 0, 1.0 / s_; diff --git a/gtsam/geometry/Similarity3.h b/gtsam/geometry/Similarity3.h index 0ef787b05..27fdba6d7 100644 --- a/gtsam/geometry/Similarity3.h +++ b/gtsam/geometry/Similarity3.h @@ -180,15 +180,15 @@ public: /// @{ /// Calculate 4*4 matrix group equivalent - GTSAM_EXPORT const Matrix4 matrix() const; + GTSAM_EXPORT Matrix4 matrix() const; /// Return a GTSAM rotation - const Rot3& rotation() const { + Rot3 rotation() const { return R_; } /// Return a GTSAM translation - const Point3& translation() const { + Point3 translation() const { return t_; } From 5e7598606a152142405e45fc7c00c85632af0508 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sun, 6 Feb 2022 00:09:16 -0500 Subject: [PATCH 0087/1686] fix wrapper --- gtsam/geometry/geometry.i | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/gtsam/geometry/geometry.i b/gtsam/geometry/geometry.i index 151c42155..6ad7baedd 100644 --- a/gtsam/geometry/geometry.i +++ b/gtsam/geometry/geometry.i @@ -907,9 +907,9 @@ class Similarity2 { static gtsam::Similarity2 Align(const gtsam::Pose2Pairs& abPosePairs); // Standard Interface - const Matrix matrix() const; - const gtsam::Rot2& rotation(); - const gtsam::Point2& translation(); + Matrix matrix() const; + gtsam::Rot2& rotation(); + gtsam::Point2& translation(); double scale() const; }; @@ -929,9 +929,9 @@ class Similarity3 { static gtsam::Similarity3 Align(const gtsam::Pose3Pairs& abPosePairs); // Standard Interface - const Matrix matrix() const; - const gtsam::Rot3& rotation(); - const gtsam::Point3& translation(); + Matrix matrix() const; + gtsam::Rot3& rotation(); + gtsam::Point3& translation(); double scale() const; }; From b484a214e6793655206786fa8fd1d55af43b8b9c Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sun, 6 Feb 2022 00:09:33 -0500 Subject: [PATCH 0088/1686] fix tests --- gtsam/navigation/tests/testGPSFactor.cpp | 13 ++++--- gtsam/navigation/tests/testMagFactor.cpp | 49 +++++++++++++++--------- 2 files changed, 38 insertions(+), 24 deletions(-) diff --git a/gtsam/navigation/tests/testGPSFactor.cpp b/gtsam/navigation/tests/testGPSFactor.cpp index b784c0c94..5b96b80a8 100644 --- a/gtsam/navigation/tests/testGPSFactor.cpp +++ b/gtsam/navigation/tests/testGPSFactor.cpp @@ -27,7 +27,6 @@ #include #include -using namespace std::placeholders; using namespace std; using namespace gtsam; using namespace GeographicLib; @@ -71,8 +70,10 @@ TEST( GPSFactor, Constructor ) { EXPECT(assert_equal(Z_3x1,factor.evaluateError(T),1e-5)); // Calculate numerical derivatives - Matrix expectedH = numericalDerivative11( - std::bind(&GPSFactor::evaluateError, &factor, _1, boost::none), T); + Matrix expectedH = numericalDerivative11( + std::bind(&GPSFactor::evaluateError, &factor, std::placeholders::_1, + boost::none), + T); // Use the factor to calculate the derivative Matrix actualH; @@ -100,8 +101,10 @@ TEST( GPSFactor2, Constructor ) { EXPECT(assert_equal(Z_3x1,factor.evaluateError(T),1e-5)); // Calculate numerical derivatives - Matrix expectedH = numericalDerivative11( - std::bind(&GPSFactor2::evaluateError, &factor, _1, boost::none), T); + Matrix expectedH = numericalDerivative11( + std::bind(&GPSFactor2::evaluateError, &factor, std::placeholders::_1, + boost::none), + T); // Use the factor to calculate the derivative Matrix actualH; diff --git a/gtsam/navigation/tests/testMagFactor.cpp b/gtsam/navigation/tests/testMagFactor.cpp index 5107b3b6b..2450b16c7 100644 --- a/gtsam/navigation/tests/testMagFactor.cpp +++ b/gtsam/navigation/tests/testMagFactor.cpp @@ -26,7 +26,6 @@ #include -using namespace std::placeholders; using namespace std; using namespace gtsam; using namespace GeographicLib; @@ -63,8 +62,10 @@ TEST( MagFactor, unrotate ) { Matrix H; Point3 expected(22735.5, 314.502, 44202.5); EXPECT( assert_equal(expected, MagFactor::unrotate(theta,nM,H),1e-1)); - EXPECT( assert_equal(numericalDerivative11 // - (std::bind(&MagFactor::unrotate, _1, nM, none), theta), H, 1e-6)); + EXPECT(assert_equal( + numericalDerivative11 // + (std::bind(&MagFactor::unrotate, std::placeholders::_1, nM, none), theta), + H, 1e-6)); } // ************************************************************************* @@ -75,36 +76,46 @@ TEST( MagFactor, Factors ) { // MagFactor MagFactor f(1, measured, s, dir, bias, model); EXPECT( assert_equal(Z_3x1,f.evaluateError(theta,H1),1e-5)); - EXPECT( assert_equal((Matrix)numericalDerivative11 // - (std::bind(&MagFactor::evaluateError, &f, _1, none), theta), H1, 1e-7)); + EXPECT(assert_equal( + (Matrix)numericalDerivative11 // + (std::bind(&MagFactor::evaluateError, &f, std::placeholders::_1, none), + theta), + H1, 1e-7)); -// MagFactor1 + // MagFactor1 MagFactor1 f1(1, measured, s, dir, bias, model); EXPECT( assert_equal(Z_3x1,f1.evaluateError(nRb,H1),1e-5)); - EXPECT( assert_equal(numericalDerivative11 // - (std::bind(&MagFactor1::evaluateError, &f1, _1, none), nRb), H1, 1e-7)); + EXPECT(assert_equal( + numericalDerivative11 // + (std::bind(&MagFactor1::evaluateError, &f1, std::placeholders::_1, none), + nRb), + H1, 1e-7)); -// MagFactor2 + // MagFactor2 MagFactor2 f2(1, 2, measured, nRb, model); EXPECT( assert_equal(Z_3x1,f2.evaluateError(scaled,bias,H1,H2),1e-5)); - EXPECT( assert_equal(numericalDerivative11 // - (std::bind(&MagFactor2::evaluateError, &f2, _1, bias, none, none), scaled),// - H1, 1e-7)); - EXPECT( assert_equal(numericalDerivative11 // - (std::bind(&MagFactor2::evaluateError, &f2, scaled, _1, none, none), bias),// - H2, 1e-7)); + EXPECT(assert_equal(numericalDerivative11 // + (std::bind(&MagFactor2::evaluateError, &f2, + std::placeholders::_1, bias, none, none), + scaled), // + H1, 1e-7)); + EXPECT(assert_equal(numericalDerivative11 // + (std::bind(&MagFactor2::evaluateError, &f2, scaled, + std::placeholders::_1, none, none), + bias), // + H2, 1e-7)); -// MagFactor2 + // MagFactor2 MagFactor3 f3(1, 2, 3, measured, nRb, model); EXPECT(assert_equal(Z_3x1,f3.evaluateError(s,dir,bias,H1,H2,H3),1e-5)); EXPECT(assert_equal((Matrix)numericalDerivative11 // - (std::bind(&MagFactor3::evaluateError, &f3, _1, dir, bias, none, none, none), s),// + (std::bind(&MagFactor3::evaluateError, &f3, std::placeholders::_1, dir, bias, none, none, none), s),// H1, 1e-7)); EXPECT(assert_equal(numericalDerivative11 // - (std::bind(&MagFactor3::evaluateError, &f3, s, _1, bias, none, none, none), dir),// + (std::bind(&MagFactor3::evaluateError, &f3, s, std::placeholders::_1, bias, none, none, none), dir),// H2, 1e-7)); EXPECT(assert_equal(numericalDerivative11 // - (std::bind(&MagFactor3::evaluateError, &f3, s, dir, _1, none, none, none), bias),// + (std::bind(&MagFactor3::evaluateError, &f3, s, dir, std::placeholders::_1, none, none, none), bias),// H3, 1e-7)); } From c716f63219d5d8b0ae1fca0242ad3320cca53438 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sun, 6 Feb 2022 11:26:29 -0500 Subject: [PATCH 0089/1686] wrap Pose2Pairs --- python/gtsam/preamble/geometry.h | 4 ++-- python/gtsam/specializations/geometry.h | 1 + 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/python/gtsam/preamble/geometry.h b/python/gtsam/preamble/geometry.h index 35fe2a577..bd0441d06 100644 --- a/python/gtsam/preamble/geometry.h +++ b/python/gtsam/preamble/geometry.h @@ -23,8 +23,8 @@ PYBIND11_MAKE_OPAQUE( std::vector>); PYBIND11_MAKE_OPAQUE(gtsam::Point2Pairs); PYBIND11_MAKE_OPAQUE(gtsam::Point3Pairs); +PYBIND11_MAKE_OPAQUE(gtsam::Pose2Pairs); PYBIND11_MAKE_OPAQUE(gtsam::Pose3Pairs); PYBIND11_MAKE_OPAQUE(std::vector); -PYBIND11_MAKE_OPAQUE( - gtsam::CameraSet>); +PYBIND11_MAKE_OPAQUE(gtsam::CameraSet>); PYBIND11_MAKE_OPAQUE(gtsam::CameraSet>); diff --git a/python/gtsam/specializations/geometry.h b/python/gtsam/specializations/geometry.h index a492ce8eb..5a0ea35ef 100644 --- a/python/gtsam/specializations/geometry.h +++ b/python/gtsam/specializations/geometry.h @@ -16,6 +16,7 @@ py::bind_vector< m_, "Point2Vector"); py::bind_vector>(m_, "Point2Pairs"); py::bind_vector>(m_, "Point3Pairs"); +py::bind_vector>(m_, "Pose2Pairs"); py::bind_vector>(m_, "Pose3Pairs"); py::bind_vector>(m_, "Pose3Vector"); py::bind_vector>>( From 509870619b4efe14b5bb8d8f1536be1f370988a9 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sun, 6 Feb 2022 11:26:43 -0500 Subject: [PATCH 0090/1686] wrap equals for Sim2 and Sim3 --- gtsam/geometry/geometry.i | 2 ++ 1 file changed, 2 insertions(+) diff --git a/gtsam/geometry/geometry.i b/gtsam/geometry/geometry.i index f872283f3..350f23d18 100644 --- a/gtsam/geometry/geometry.i +++ b/gtsam/geometry/geometry.i @@ -862,6 +862,7 @@ class Similarity2 { static gtsam::Similarity2 Align(const gtsam::Pose2Pairs& abPosePairs); // Standard Interface + bool equals(const gtsam::Similarity2& sim, double tol) const; Matrix matrix() const; gtsam::Rot2& rotation(); gtsam::Point2& translation(); @@ -884,6 +885,7 @@ class Similarity3 { static gtsam::Similarity3 Align(const gtsam::Pose3Pairs& abPosePairs); // Standard Interface + bool equals(const gtsam::Similarity3& sim, double tol) const; Matrix matrix() const; gtsam::Rot3& rotation(); gtsam::Point3& translation(); From 464af9f7111e89de58dcf30eac38f29a44cd098b Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sun, 6 Feb 2022 11:28:24 -0500 Subject: [PATCH 0091/1686] Fix syntactic errors in test_Sim2.py --- python/gtsam/tests/test_Sim2.py | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/python/gtsam/tests/test_Sim2.py b/python/gtsam/tests/test_Sim2.py index 67bc770d2..1d09dcc3b 100644 --- a/python/gtsam/tests/test_Sim2.py +++ b/python/gtsam/tests/test_Sim2.py @@ -65,7 +65,7 @@ class TestSim2(GtsamTestCase): world frame has poses rotated about z-axis (90 degree yaw) world and egovehicle frame translated by 11 meters w.r.t. each other """ - Rz90 = Rot3.Rz(np.deg2rad(90)) + Rz90 = Rot2.Rz(np.deg2rad(90)) # Create source poses (three objects o1, o2, o3 living in the egovehicle "e" frame) # Suppose they are 3d cuboids detected by an onboard sensor in the egovehicle frame @@ -107,10 +107,10 @@ class TestSim2(GtsamTestCase): R180 = Rot2.fromDegrees(180) R270 = Rot2.fromDegrees(270) - aTi0 = Pose3(R0, np.array([2, 3])) - aTi1 = Pose3(R90, np.array([12, 3])) - aTi2 = Pose3(R180, np.array([12, 13])) - aTi3 = Pose3(R270, np.array([2, 13])) + aTi0 = Pose2(R0, np.array([2, 3])) + aTi1 = Pose2(R90, np.array([12, 3])) + aTi2 = Pose2(R180, np.array([12, 13])) + aTi3 = Pose2(R270, np.array([2, 13])) aTi_list = [aTi0, aTi1, aTi2, aTi3] @@ -144,7 +144,7 @@ class TestSim2(GtsamTestCase): """Ensure object equality works properly (are equal).""" bSa = Similarity2(R=Rot2(), t=np.array([1, 2]), s=3.0) bSa_ = Similarity2(R=Rot2(), t=np.array([1.0, 2.0]), s=3) - assert bSa == bSa_ + self.gtsamAssertEquals(bSa, bSa_) def test_not_eq_translation(self) -> None: """Ensure object equality works properly (not equal translation).""" From cc8d80fb7ecab4f1043d02678f24ddfe121b78aa Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sun, 6 Feb 2022 12:14:30 -0500 Subject: [PATCH 0092/1686] Remove SFINAE from KarcherMean so we can also use it for Rot2 --- gtsam/slam/KarcherMeanFactor-inl.h | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/gtsam/slam/KarcherMeanFactor-inl.h b/gtsam/slam/KarcherMeanFactor-inl.h index c81a9adc5..00f741705 100644 --- a/gtsam/slam/KarcherMeanFactor-inl.h +++ b/gtsam/slam/KarcherMeanFactor-inl.h @@ -40,8 +40,7 @@ T FindKarcherMeanImpl(const vector& rotations) { return result.at(kKey); } -template ::value >::type > +template T FindKarcherMean(const std::vector& rotations) { return FindKarcherMeanImpl(rotations); } From 37ae7038fa033e861f99375cea9b9b1dbbfb7727 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sun, 6 Feb 2022 12:27:50 -0500 Subject: [PATCH 0093/1686] Fix tests --- gtsam/geometry/Similarity2.cpp | 2 +- python/gtsam/tests/test_Sim2.py | 22 +++++++++++----------- 2 files changed, 12 insertions(+), 12 deletions(-) diff --git a/gtsam/geometry/Similarity2.cpp b/gtsam/geometry/Similarity2.cpp index 12529f52d..6e5da635b 100644 --- a/gtsam/geometry/Similarity2.cpp +++ b/gtsam/geometry/Similarity2.cpp @@ -193,7 +193,7 @@ Similarity2 Similarity2::Align(const Pose2Pairs& abPosePairs) { rotations.emplace_back(aRb); abPointPairs.emplace_back(aTi.translation(), bTi.translation()); } - const Rot2 aRb_estimate; // = FindKarcherMean(rotations); + const Rot2 aRb_estimate = FindKarcherMean(rotations); return internal::alignGivenR(abPointPairs, aRb_estimate); } diff --git a/python/gtsam/tests/test_Sim2.py b/python/gtsam/tests/test_Sim2.py index 1d09dcc3b..3e39ac45c 100644 --- a/python/gtsam/tests/test_Sim2.py +++ b/python/gtsam/tests/test_Sim2.py @@ -27,10 +27,10 @@ class TestSim2(GtsamTestCase): Scenario: 3 object poses same scale (no gauge ambiguity) - world frame has poses rotated about x-axis (90 degree roll) + world frame has poses rotated about 180 degrees. world and egovehicle frame translated by 15 meters w.r.t. each other """ - Rx90 = Rot2.fromDegrees(90) + R180 = Rot2.fromDegrees(180) # Create source poses (three objects o1, o2, o3 living in the egovehicle "e" frame) # Suppose they are 3d cuboids detected by an onboard sensor in the egovehicle frame @@ -41,10 +41,10 @@ class TestSim2(GtsamTestCase): eToi_list = [eTo0, eTo1, eTo2] # Create destination poses - # (same three objects, but instead living in the world/city "w" frame) - wTo0 = Pose2(Rx90, np.array([-10, 0])) - wTo1 = Pose2(Rx90, np.array([-5, 0])) - wTo2 = Pose2(Rx90, np.array([0, 0])) + # (same three objects, but instead living in the world "w" frame) + wTo0 = Pose2(R180, np.array([-10, 0])) + wTo1 = Pose2(R180, np.array([-5, 0])) + wTo2 = Pose2(R180, np.array([0, 0])) wToi_list = [wTo0, wTo1, wTo2] @@ -62,10 +62,10 @@ class TestSim2(GtsamTestCase): Scenario: 3 object poses with gauge ambiguity (2x scale) - world frame has poses rotated about z-axis (90 degree yaw) + world frame has poses rotated by 90 degrees. world and egovehicle frame translated by 11 meters w.r.t. each other """ - Rz90 = Rot2.Rz(np.deg2rad(90)) + R90 = Rot2.fromDegrees(90) # Create source poses (three objects o1, o2, o3 living in the egovehicle "e" frame) # Suppose they are 3d cuboids detected by an onboard sensor in the egovehicle frame @@ -77,9 +77,9 @@ class TestSim2(GtsamTestCase): # Create destination poses # (same three objects, but instead living in the world/city "w" frame) - wTo0 = Pose2(Rz90, np.array([0, 12])) - wTo1 = Pose2(Rz90, np.array([0, 14])) - wTo2 = Pose2(Rz90, np.array([0, 18])) + wTo0 = Pose2(R90, np.array([0, 12])) + wTo1 = Pose2(R90, np.array([0, 14])) + wTo2 = Pose2(R90, np.array([0, 18])) wToi_list = [wTo0, wTo1, wTo2] From ac01db4f4d1af145d09094047629f9d7271ec803 Mon Sep 17 00:00:00 2001 From: Mike Sheffler Date: Tue, 15 Feb 2022 00:19:54 -0800 Subject: [PATCH 0094/1686] 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 0095/1686] 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 0096/1686] 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 0097/1686] 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 0098/1686] 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 0099/1686] 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 0100/1686] 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 0101/1686] 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 0102/1686] 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 0103/1686] 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 0104/1686] 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 0105/1686] 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 0106/1686] 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 0107/1686] 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 0108/1686] 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 0109/1686] 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 0110/1686] 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 0111/1686] 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 0112/1686] 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 0113/1686] 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 0114/1686] 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 0115/1686] 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 0116/1686] 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 0117/1686] 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 0118/1686] 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 0119/1686] 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 0120/1686] 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 0121/1686] 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 0122/1686] 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 0123/1686] 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 0124/1686] 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 0125/1686] 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 0126/1686] 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 0127/1686] 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 0128/1686] 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 0129/1686] 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 0130/1686] 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 0131/1686] 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 0132/1686] 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 0133/1686] 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 0134/1686] 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 0135/1686] 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 0136/1686] 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 0137/1686] 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 0138/1686] 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 0139/1686] 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 0140/1686] 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 0141/1686] 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 0142/1686] 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 0143/1686] 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 0144/1686] * 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 0145/1686] 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 0146/1686] 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 0147/1686] 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 0148/1686] 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 0149/1686] 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 0150/1686] 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 0151/1686] 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 0152/1686] 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 0153/1686] 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 0154/1686] 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 0155/1686] 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 0156/1686] 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 0157/1686] 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 0158/1686] 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 0159/1686] 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 0160/1686] 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 0161/1686] 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 0162/1686] 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 0163/1686] 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 0164/1686] 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 0165/1686] 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 bf8137b0c404997ba6d1678e0b733e3347b0f007 Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Tue, 8 Mar 2022 09:48:05 -0500 Subject: [PATCH 0166/1686] refactor python NonlinearOptimizerTest --- python/gtsam/tests/test_NonlinearOptimizer.py | 78 +++++++++---------- 1 file changed, 38 insertions(+), 40 deletions(-) diff --git a/python/gtsam/tests/test_NonlinearOptimizer.py b/python/gtsam/tests/test_NonlinearOptimizer.py index e2561ae52..2158e10bb 100644 --- a/python/gtsam/tests/test_NonlinearOptimizer.py +++ b/python/gtsam/tests/test_NonlinearOptimizer.py @@ -15,12 +15,10 @@ from __future__ import print_function import unittest import gtsam -from gtsam import (DoglegOptimizer, DoglegParams, - DummyPreconditionerParameters, GaussNewtonOptimizer, - GaussNewtonParams, GncLMParams, GncLMOptimizer, - LevenbergMarquardtOptimizer, LevenbergMarquardtParams, - NonlinearFactorGraph, Ordering, - PCGSolverParameters, Point2, PriorFactorPoint2, Values) +from gtsam import (DoglegOptimizer, DoglegParams, DummyPreconditionerParameters, + GaussNewtonOptimizer, GaussNewtonParams, GncLMParams, GncLMOptimizer, + LevenbergMarquardtOptimizer, LevenbergMarquardtParams, NonlinearFactorGraph, + Ordering, PCGSolverParameters, Point2, PriorFactorPoint2, Values) from gtsam.utils.test_case import GtsamTestCase KEY1 = 1 @@ -28,62 +26,62 @@ KEY2 = 2 class TestScenario(GtsamTestCase): - def test_optimize(self): - """Do trivial test with three optimizer variants.""" - fg = NonlinearFactorGraph() + """Do trivial test with three optimizer variants.""" + + def setUp(self): + """Set up the optimization problem and ordering""" + # create graph + self.fg = NonlinearFactorGraph() model = gtsam.noiseModel.Unit.Create(2) - fg.add(PriorFactorPoint2(KEY1, Point2(0, 0), model)) + self.fg.add(PriorFactorPoint2(KEY1, Point2(0, 0), model)) # test error at minimum xstar = Point2(0, 0) - optimal_values = Values() - optimal_values.insert(KEY1, xstar) - self.assertEqual(0.0, fg.error(optimal_values), 0.0) + self.optimal_values = Values() + self.optimal_values.insert(KEY1, xstar) + self.assertEqual(0.0, self.fg.error(self.optimal_values), 0.0) # test error at initial = [(1-cos(3))^2 + (sin(3))^2]*50 = x0 = Point2(3, 3) - initial_values = Values() - initial_values.insert(KEY1, x0) - self.assertEqual(9.0, fg.error(initial_values), 1e-3) + self.initial_values = Values() + self.initial_values.insert(KEY1, x0) + self.assertEqual(9.0, self.fg.error(self.initial_values), 1e-3) # optimize parameters - ordering = Ordering() - ordering.push_back(KEY1) + self.ordering = Ordering() + self.ordering.push_back(KEY1) - # Gauss-Newton + def test_gauss_newton(self): gnParams = GaussNewtonParams() - gnParams.setOrdering(ordering) - actual1 = GaussNewtonOptimizer(fg, initial_values, gnParams).optimize() - self.assertAlmostEqual(0, fg.error(actual1)) + gnParams.setOrdering(self.ordering) + actual = GaussNewtonOptimizer(self.fg, self.initial_values, gnParams).optimize() + self.assertAlmostEqual(0, self.fg.error(actual)) - # Levenberg-Marquardt + def test_levenberg_marquardt(self): lmParams = LevenbergMarquardtParams.CeresDefaults() - lmParams.setOrdering(ordering) - actual2 = LevenbergMarquardtOptimizer( - fg, initial_values, lmParams).optimize() - self.assertAlmostEqual(0, fg.error(actual2)) + lmParams.setOrdering(self.ordering) + actual = LevenbergMarquardtOptimizer(self.fg, self.initial_values, lmParams).optimize() + self.assertAlmostEqual(0, self.fg.error(actual)) - # Levenberg-Marquardt + def test_levenberg_marquardt_pcg(self): lmParams = LevenbergMarquardtParams.CeresDefaults() lmParams.setLinearSolverType("ITERATIVE") cgParams = PCGSolverParameters() cgParams.setPreconditionerParams(DummyPreconditionerParameters()) lmParams.setIterativeParams(cgParams) - actual2 = LevenbergMarquardtOptimizer( - fg, initial_values, lmParams).optimize() - self.assertAlmostEqual(0, fg.error(actual2)) + actual = LevenbergMarquardtOptimizer(self.fg, self.initial_values, lmParams).optimize() + self.assertAlmostEqual(0, self.fg.error(actual)) - # Dogleg + def test_dogleg(self): dlParams = DoglegParams() - dlParams.setOrdering(ordering) - actual3 = DoglegOptimizer(fg, initial_values, dlParams).optimize() - self.assertAlmostEqual(0, fg.error(actual3)) - - # Graduated Non-Convexity (GNC) + dlParams.setOrdering(self.ordering) + actual = DoglegOptimizer(self.fg, self.initial_values, dlParams).optimize() + self.assertAlmostEqual(0, self.fg.error(actual)) + + def test_graduated_non_convexity(self): gncParams = GncLMParams() - actual4 = GncLMOptimizer(fg, initial_values, gncParams).optimize() - self.assertAlmostEqual(0, fg.error(actual4)) - + actual = GncLMOptimizer(self.fg, self.initial_values, gncParams).optimize() + self.assertAlmostEqual(0, self.fg.error(actual)) if __name__ == "__main__": From 5f601f76d5eb22434f8681155f5d492fba840401 Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Tue, 8 Mar 2022 09:57:11 -0500 Subject: [PATCH 0167/1686] add iteration hook to NonlinearOptimizerParams --- gtsam/nonlinear/nonlinear.i | 2 ++ python/gtsam/tests/test_NonlinearOptimizer.py | 20 +++++++++++++++++++ 2 files changed, 22 insertions(+) diff --git a/gtsam/nonlinear/nonlinear.i b/gtsam/nonlinear/nonlinear.i index da5e8b29c..7d2911374 100644 --- a/gtsam/nonlinear/nonlinear.i +++ b/gtsam/nonlinear/nonlinear.i @@ -403,6 +403,8 @@ virtual class NonlinearOptimizerParams { bool isSequential() const; bool isCholmod() const; bool isIterative() const; + + gtsam::NonlinearOptimizerParams::IterationHook iterationHook; }; bool checkConvergence(double relativeErrorTreshold, diff --git a/python/gtsam/tests/test_NonlinearOptimizer.py b/python/gtsam/tests/test_NonlinearOptimizer.py index 2158e10bb..37afd9e1c 100644 --- a/python/gtsam/tests/test_NonlinearOptimizer.py +++ b/python/gtsam/tests/test_NonlinearOptimizer.py @@ -83,6 +83,26 @@ class TestScenario(GtsamTestCase): actual = GncLMOptimizer(self.fg, self.initial_values, gncParams).optimize() self.assertAlmostEqual(0, self.fg.error(actual)) + def test_iteration_hook(self): + # set up iteration hook to track some testable values + iteration_count = 0 + final_error = 0 + final_values = None + def iteration_hook(iter, error_before, error_after): + nonlocal iteration_count, final_error, final_values + iteration_count = iter + final_error = error_after + final_values = optimizer.values() + # optimize + params = LevenbergMarquardtParams.CeresDefaults() + params.setOrdering(self.ordering) + params.iterationHook = iteration_hook + optimizer = LevenbergMarquardtOptimizer(self.fg, self.initial_values, params) + actual = optimizer.optimize() + self.assertAlmostEqual(0, self.fg.error(actual)) + self.gtsamAssertEquals(final_values, actual) + self.assertEqual(self.fg.error(actual), final_error) + self.assertEqual(optimizer.iterations(), iteration_count) if __name__ == "__main__": unittest.main() From ddca736c7bd3f2cf2f0eaae9925fbb4a3d6a7cc7 Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Tue, 8 Mar 2022 10:13:48 -0500 Subject: [PATCH 0168/1686] add comment about matlab not having iteration hook --- gtsam/nonlinear/nonlinear.i | 1 + 1 file changed, 1 insertion(+) diff --git a/gtsam/nonlinear/nonlinear.i b/gtsam/nonlinear/nonlinear.i index 7d2911374..e227de37c 100644 --- a/gtsam/nonlinear/nonlinear.i +++ b/gtsam/nonlinear/nonlinear.i @@ -404,6 +404,7 @@ virtual class NonlinearOptimizerParams { bool isCholmod() const; bool isIterative() const; + // This only applies to python since matlab does not have lambda machinery. gtsam::NonlinearOptimizerParams::IterationHook iterationHook; }; From ba32a0de85c94eebae4d27116cec3885db9f66bc Mon Sep 17 00:00:00 2001 From: Thomas Sayre-McCord Date: Tue, 8 Mar 2022 16:34:09 +0100 Subject: [PATCH 0169/1686] 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 0170/1686] 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 0171/1686] 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 0172/1686] 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 0173/1686] 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 0174/1686] 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 0175/1686] 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 0176/1686] 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 0177/1686] 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 ea4ebb6843daec9cd42bb7579e431d6686d1d8f7 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Fri, 11 Mar 2022 15:51:34 -0500 Subject: [PATCH 0178/1686] Fix typo --- gtsam/inference/EliminateableFactorGraph.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/inference/EliminateableFactorGraph.h b/gtsam/inference/EliminateableFactorGraph.h index c904d2f7f..900346f7f 100644 --- a/gtsam/inference/EliminateableFactorGraph.h +++ b/gtsam/inference/EliminateableFactorGraph.h @@ -204,7 +204,7 @@ namespace gtsam { OptionalVariableIndex variableIndex = boost::none) const; /** Do multifrontal elimination of the given \c variables in an ordering computed by COLAMD to - * produce a Bayes net and a remaining factor graph. This computes the factorization \f$ p(X) + * produce a Bayes tree and a remaining factor graph. This computes the factorization \f$ p(X) * = p(A|B) p(B) \f$, where \f$ A = \f$ \c variables, \f$ X \f$ is all the variables in the * factor graph, and \f$ B = X\backslash A \f$. */ std::pair, boost::shared_ptr > From 0567303ed3334508cf5ab0c19903b22a5d3fd9e1 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Fri, 11 Mar 2022 15:52:28 -0500 Subject: [PATCH 0179/1686] Prototype a type-erased hybrid machinery --- gtsam/CMakeLists.txt | 1 + gtsam/hybrid/CGMixtureFactor.cpp | 5 + gtsam/hybrid/CGMixtureFactor.h | 23 +++++ gtsam/hybrid/CMakeLists.txt | 8 ++ gtsam/hybrid/HybridBayesNet.cpp | 16 ++++ gtsam/hybrid/HybridBayesNet.h | 43 +++++++++ gtsam/hybrid/HybridBayesTree.cpp | 38 ++++++++ gtsam/hybrid/HybridBayesTree.h | 77 +++++++++++++++ gtsam/hybrid/HybridConditional.cpp | 23 +++++ gtsam/hybrid/HybridConditional.h | 99 ++++++++++++++++++++ gtsam/hybrid/HybridDiscreteFactor.cpp | 19 ++++ gtsam/hybrid/HybridDiscreteFactor.h | 34 +++++++ gtsam/hybrid/HybridEliminationTree.cpp | 43 +++++++++ gtsam/hybrid/HybridEliminationTree.h | 62 ++++++++++++ gtsam/hybrid/HybridFactor.cpp | 18 ++++ gtsam/hybrid/HybridFactor.h | 83 ++++++++++++++++ gtsam/hybrid/HybridFactorGraph.cpp | 58 ++++++++++++ gtsam/hybrid/HybridFactorGraph.h | 83 ++++++++++++++++ gtsam/hybrid/HybridGaussianFactor.cpp | 23 +++++ gtsam/hybrid/HybridGaussianFactor.h | 39 ++++++++ gtsam/hybrid/HybridJunctionTree.cpp | 34 +++++++ gtsam/hybrid/HybridJunctionTree.h | 67 +++++++++++++ gtsam/hybrid/tests/CMakeLists.txt | 1 + gtsam/hybrid/tests/testHybridConditional.cpp | 73 +++++++++++++++ 24 files changed, 970 insertions(+) create mode 100644 gtsam/hybrid/CGMixtureFactor.cpp create mode 100644 gtsam/hybrid/CGMixtureFactor.h create mode 100644 gtsam/hybrid/CMakeLists.txt create mode 100644 gtsam/hybrid/HybridBayesNet.cpp create mode 100644 gtsam/hybrid/HybridBayesNet.h create mode 100644 gtsam/hybrid/HybridBayesTree.cpp create mode 100644 gtsam/hybrid/HybridBayesTree.h create mode 100644 gtsam/hybrid/HybridConditional.cpp create mode 100644 gtsam/hybrid/HybridConditional.h create mode 100644 gtsam/hybrid/HybridDiscreteFactor.cpp create mode 100644 gtsam/hybrid/HybridDiscreteFactor.h create mode 100644 gtsam/hybrid/HybridEliminationTree.cpp create mode 100644 gtsam/hybrid/HybridEliminationTree.h create mode 100644 gtsam/hybrid/HybridFactor.cpp create mode 100644 gtsam/hybrid/HybridFactor.h create mode 100644 gtsam/hybrid/HybridFactorGraph.cpp create mode 100644 gtsam/hybrid/HybridFactorGraph.h create mode 100644 gtsam/hybrid/HybridGaussianFactor.cpp create mode 100644 gtsam/hybrid/HybridGaussianFactor.h create mode 100644 gtsam/hybrid/HybridJunctionTree.cpp create mode 100644 gtsam/hybrid/HybridJunctionTree.h create mode 100644 gtsam/hybrid/tests/CMakeLists.txt create mode 100644 gtsam/hybrid/tests/testHybridConditional.cpp diff --git a/gtsam/CMakeLists.txt b/gtsam/CMakeLists.txt index a293c6ec2..845ac7cd0 100644 --- a/gtsam/CMakeLists.txt +++ b/gtsam/CMakeLists.txt @@ -10,6 +10,7 @@ set (gtsam_subdirs inference symbolic discrete + hybrid linear nonlinear sam diff --git a/gtsam/hybrid/CGMixtureFactor.cpp b/gtsam/hybrid/CGMixtureFactor.cpp new file mode 100644 index 000000000..d789825f7 --- /dev/null +++ b/gtsam/hybrid/CGMixtureFactor.cpp @@ -0,0 +1,5 @@ +// +// Created by Fan Jiang on 3/11/22. +// + +#include "CGMixtureFactor.h" diff --git a/gtsam/hybrid/CGMixtureFactor.h b/gtsam/hybrid/CGMixtureFactor.h new file mode 100644 index 000000000..f2fa1e54a --- /dev/null +++ b/gtsam/hybrid/CGMixtureFactor.h @@ -0,0 +1,23 @@ +/* ---------------------------------------------------------------------------- + * Copyright 2021 The Ambitious Folks of the MRG + * See LICENSE for the license information + * -------------------------------------------------------------------------- */ + +/** + * @file CGMixtureFactor.h + * @brief Custom hybrid factor graph for discrete + continuous factors + * @author Kevin Doherty, kdoherty@mit.edu + * @author Varun Agrawal + * @author Fan Jiang + * @date December 2021 + */ + +#include + +namespace gtsam { + +class CGMixtureFactor : HybridFactor { + +}; + +} diff --git a/gtsam/hybrid/CMakeLists.txt b/gtsam/hybrid/CMakeLists.txt new file mode 100644 index 000000000..f1cfcd5c4 --- /dev/null +++ b/gtsam/hybrid/CMakeLists.txt @@ -0,0 +1,8 @@ +# Install headers +set(subdir hybrid) +file(GLOB hybrid_headers "*.h") +# FIXME: exclude headers +install(FILES ${hybrid_headers} DESTINATION include/gtsam/hybrid) + +# Add all tests +add_subdirectory(tests) diff --git a/gtsam/hybrid/HybridBayesNet.cpp b/gtsam/hybrid/HybridBayesNet.cpp new file mode 100644 index 000000000..1292711d8 --- /dev/null +++ b/gtsam/hybrid/HybridBayesNet.cpp @@ -0,0 +1,16 @@ +/* ---------------------------------------------------------------------------- + * 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 HybridBayesNet.cpp + * @brief A bayes net of Gaussian Conditionals indexed by discrete keys. + * @author Fan Jiang + * @date January 2022 + */ + +#include diff --git a/gtsam/hybrid/HybridBayesNet.h b/gtsam/hybrid/HybridBayesNet.h new file mode 100644 index 000000000..53d10518f --- /dev/null +++ b/gtsam/hybrid/HybridBayesNet.h @@ -0,0 +1,43 @@ +/* ---------------------------------------------------------------------------- + * 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 HybridBayesNet.h + * @brief A bayes net of Gaussian Conditionals indexed by discrete keys. + * @author Varun Agrawal + * @author Fan Jiang + * @author Frank Dellaert + * @date December 2021 + */ + +#pragma once + +#include +#include + +#include // TODO! + +namespace gtsam { + +/** + * A hybrid Bayes net can have discrete conditionals, Gaussian mixtures, + * or pure Gaussian conditionals. + */ +class GTSAM_EXPORT HybridBayesNet : public BayesNet { + public: + using Base = BayesNet; + using This = HybridBayesNet; + using ConditionalType = HybridConditional; + using shared_ptr = boost::shared_ptr; + using sharedConditional = boost::shared_ptr; + + /** Construct empty bayes net */ + HybridBayesNet() : Base() {} +}; + +} // namespace gtsam \ No newline at end of file diff --git a/gtsam/hybrid/HybridBayesTree.cpp b/gtsam/hybrid/HybridBayesTree.cpp new file mode 100644 index 000000000..72f3fd794 --- /dev/null +++ b/gtsam/hybrid/HybridBayesTree.cpp @@ -0,0 +1,38 @@ +/* ---------------------------------------------------------------------------- + + * 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 HybridBayesTree.cpp + * @brief Hybrid Bayes Tree, the result of eliminating a HybridJunctionTree + * @brief HybridBayesTree + * @author Frank Dellaert + * @author Richard Roberts + */ + +#include +#include +#include +#include +#include + +namespace gtsam { + +// Instantiate base class +template class BayesTreeCliqueBase; +template class BayesTree; + +/* ************************************************************************* */ +bool HybridBayesTree::equals(const This& other, double tol) const { + return Base::equals(other, tol); +} + +/* **************************************************************************/ +} // namespace gtsam diff --git a/gtsam/hybrid/HybridBayesTree.h b/gtsam/hybrid/HybridBayesTree.h new file mode 100644 index 000000000..2ea40cecc --- /dev/null +++ b/gtsam/hybrid/HybridBayesTree.h @@ -0,0 +1,77 @@ +/* ---------------------------------------------------------------------------- + + * 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 HybridBayesTree.h + * @brief Hybrid Bayes Tree, the result of eliminating a + * HybridJunctionTree + * @brief HybridBayesTree + * @author Frank Dellaert + * @author Richard Roberts + */ + +#pragma once + +#include +#include +#include +#include +#include + +#include + +namespace gtsam { + +// Forward declarations +class HybridConditional; +class VectorValues; + +/* ************************************************************************* */ +/** A clique in a HybridBayesTree */ +class GTSAM_EXPORT HybridBayesTreeClique + : public BayesTreeCliqueBase { + public: + typedef HybridBayesTreeClique This; + typedef BayesTreeCliqueBase + Base; + typedef boost::shared_ptr shared_ptr; + typedef boost::weak_ptr weak_ptr; + HybridBayesTreeClique() {} + virtual ~HybridBayesTreeClique() {} + HybridBayesTreeClique( + const boost::shared_ptr& conditional) + : Base(conditional) {} + +}; + +/* ************************************************************************* */ +/** A Bayes tree representing a Hybrid density */ +class GTSAM_EXPORT HybridBayesTree + : public BayesTree { + private: + typedef BayesTree Base; + + public: + typedef HybridBayesTree This; + typedef boost::shared_ptr shared_ptr; + + /// @name Standard interface + /// @{ + /** Default constructor, creates an empty Bayes tree */ + HybridBayesTree() = default; + + /** Check equality */ + bool equals(const This& other, double tol = 1e-9) const; + + /// @} +}; + +} // namespace gtsam diff --git a/gtsam/hybrid/HybridConditional.cpp b/gtsam/hybrid/HybridConditional.cpp new file mode 100644 index 000000000..e6b2eb47f --- /dev/null +++ b/gtsam/hybrid/HybridConditional.cpp @@ -0,0 +1,23 @@ +// +// Created by Fan Jiang on 3/11/22. +// + +#include +#include + +namespace gtsam { +void HybridConditional::print(const std::string &s, + const KeyFormatter &formatter) const { + Conditional::print(s, formatter); +} + +bool HybridConditional::equals(const HybridFactor &other, + double tol) const { + return false; +} + +HybridConditional HybridConditional::operator*(const HybridConditional &other) const { + return {}; +} +} + diff --git a/gtsam/hybrid/HybridConditional.h b/gtsam/hybrid/HybridConditional.h new file mode 100644 index 000000000..d6dd8250f --- /dev/null +++ b/gtsam/hybrid/HybridConditional.h @@ -0,0 +1,99 @@ +/* ---------------------------------------------------------------------------- + + * 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 HybridConditional.h + * @date Mar 11, 2022 + * @author Fan Jiang + */ + +#pragma once + +#include +#include +#include + + +#include +#include +#include +#include + +namespace gtsam { + +/** + * Hybrid Conditional Density + * + * As a type-erased variant of: + * - DiscreteConditional + * - GaussianMixture + * - GaussianConditional + */ +class GTSAM_EXPORT HybridConditional +: public HybridFactor, +public Conditional { +public: +// typedefs needed to play nice with gtsam +typedef HybridConditional This; ///< Typedef to this class +typedef boost::shared_ptr shared_ptr; ///< shared_ptr to this class +typedef HybridFactor BaseFactor; ///< Typedef to our factor base class +typedef Conditional + BaseConditional; ///< Typedef to our conditional base class + +private: +// Type-erased pointer to the inner type +std::unique_ptr inner; + +public: +/// @name Standard Constructors +/// @{ + +/// Default constructor needed for serialization. +HybridConditional() = default; + +/** + * @brief Combine two conditionals, yielding a new conditional with the union + * of the frontal keys, ordered by gtsam::Key. + * + * The two conditionals must make a valid Bayes net fragment, i.e., + * the frontal variables cannot overlap, and must be acyclic: + * Example of correct use: + * P(A,B) = P(A|B) * P(B) + * P(A,B|C) = P(A|B) * P(B|C) + * P(A,B,C) = P(A,B|C) * P(C) + * Example of incorrect use: + * P(A|B) * P(A|C) = ? + * P(A|B) * P(B|A) = ? + * We check for overlapping frontals, but do *not* check for cyclic. + */ +HybridConditional operator*(const HybridConditional& other) const; + +/// @} +/// @name Testable +/// @{ + +/// GTSAM-style print +void print( + const std::string& s = "Hybrid Conditional: ", + const KeyFormatter& formatter = DefaultKeyFormatter) const override; + +/// GTSAM-style equals +bool equals(const HybridFactor& other, double tol = 1e-9) const override; + +/// @} +}; +// DiscreteConditional + +// traits +template <> +struct traits : public Testable {}; + +} // namespace gtsam diff --git a/gtsam/hybrid/HybridDiscreteFactor.cpp b/gtsam/hybrid/HybridDiscreteFactor.cpp new file mode 100644 index 000000000..fded0a2df --- /dev/null +++ b/gtsam/hybrid/HybridDiscreteFactor.cpp @@ -0,0 +1,19 @@ +// +// Created by Fan Jiang on 3/11/22. +// + +#include + +#include + +namespace gtsam { + +HybridDiscreteFactor::HybridDiscreteFactor(DiscreteFactor::shared_ptr other) { + inner = other; +} + +HybridDiscreteFactor::HybridDiscreteFactor(DecisionTreeFactor &&dtf) : inner(boost::make_shared(std::move(dtf))) { + +}; + +} \ No newline at end of file diff --git a/gtsam/hybrid/HybridDiscreteFactor.h b/gtsam/hybrid/HybridDiscreteFactor.h new file mode 100644 index 000000000..4b1c00672 --- /dev/null +++ b/gtsam/hybrid/HybridDiscreteFactor.h @@ -0,0 +1,34 @@ +/* ---------------------------------------------------------------------------- + + * 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 HybridDiscreteFactor.h + * @date Mar 11, 2022 + * @author Fan Jiang + */ + +#include +#include +#include + +namespace gtsam { + +class HybridDiscreteFactor : public HybridFactor { + public: + DiscreteFactor::shared_ptr inner; + + // Implicit conversion from a shared ptr of GF + HybridDiscreteFactor(DiscreteFactor::shared_ptr other); + + // Forwarding constructor from concrete JacobianFactor + HybridDiscreteFactor(DecisionTreeFactor &&dtf); +}; +} diff --git a/gtsam/hybrid/HybridEliminationTree.cpp b/gtsam/hybrid/HybridEliminationTree.cpp new file mode 100644 index 000000000..ff106095a --- /dev/null +++ b/gtsam/hybrid/HybridEliminationTree.cpp @@ -0,0 +1,43 @@ +/* ---------------------------------------------------------------------------- + + * 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 HybridEliminationTree.cpp + * @date Mar 11, 2022 + * @author Fan Jiang + */ + +#include +#include + +namespace gtsam { + +// Instantiate base class +template class EliminationTree; + +/* ************************************************************************* */ +HybridEliminationTree::HybridEliminationTree( + const HybridFactorGraph& factorGraph, const VariableIndex& structure, + const Ordering& order) : + Base(factorGraph, structure, order) {} + +/* ************************************************************************* */ +HybridEliminationTree::HybridEliminationTree( + const HybridFactorGraph& factorGraph, const Ordering& order) : + Base(factorGraph, order) {} + +/* ************************************************************************* */ +bool HybridEliminationTree::equals(const This& other, double tol) const +{ + return Base::equals(other, tol); +} + +} diff --git a/gtsam/hybrid/HybridEliminationTree.h b/gtsam/hybrid/HybridEliminationTree.h new file mode 100644 index 000000000..e218ce9f6 --- /dev/null +++ b/gtsam/hybrid/HybridEliminationTree.h @@ -0,0 +1,62 @@ +/* ---------------------------------------------------------------------------- + + * 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 HybridEliminationTree.h + * @date Mar 11, 2022 + * @author Fan Jiang + */ + +#pragma once + +#include +#include +#include + +namespace gtsam { + +class GTSAM_EXPORT HybridEliminationTree : + public EliminationTree +{ + public: + typedef EliminationTree Base; ///< Base class + typedef HybridEliminationTree This; ///< This class + typedef boost::shared_ptr shared_ptr; ///< Shared pointer to this class + + /** + * Build the elimination tree of a factor graph using pre-computed column structure. + * @param factorGraph The factor graph for which to build the elimination tree + * @param structure The set of factors involving each variable. If this is not + * precomputed, you can call the Create(const FactorGraph&) + * named constructor instead. + * @return The elimination tree + */ + HybridEliminationTree(const HybridFactorGraph& factorGraph, + const VariableIndex& structure, const Ordering& order); + + /** Build the elimination tree of a factor graph. Note that this has to compute the column + * structure as a VariableIndex, so if you already have this precomputed, use the other + * constructor instead. + * @param factorGraph The factor graph for which to build the elimination tree + */ + HybridEliminationTree(const HybridFactorGraph& factorGraph, + const Ordering& order); + + /** Test whether the tree is equal to another */ + bool equals(const This& other, double tol = 1e-9) const; + + private: + + friend class ::EliminationTreeTester; + +}; + +} diff --git a/gtsam/hybrid/HybridFactor.cpp b/gtsam/hybrid/HybridFactor.cpp new file mode 100644 index 000000000..907350e83 --- /dev/null +++ b/gtsam/hybrid/HybridFactor.cpp @@ -0,0 +1,18 @@ +/* ---------------------------------------------------------------------------- + + * 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 HybridFactor.cpp + * @date Mar 11, 2022 + * @author Fan Jiang + */ + +#include diff --git a/gtsam/hybrid/HybridFactor.h b/gtsam/hybrid/HybridFactor.h new file mode 100644 index 000000000..5af1a23a9 --- /dev/null +++ b/gtsam/hybrid/HybridFactor.h @@ -0,0 +1,83 @@ +/* ---------------------------------------------------------------------------- + + * 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 HybridFactor.h + * @date Mar 11, 2022 + * @author Fan Jiang + */ + +#pragma once + +#include +#include +#include + +#include +namespace gtsam { + +/** + * Base class for hybrid probabilistic factors + */ +class GTSAM_EXPORT HybridFactor: public Factor { + +public: + +// typedefs needed to play nice with gtsam +typedef HybridFactor This; ///< This class +typedef boost::shared_ptr shared_ptr; ///< shared_ptr to this class +typedef Factor Base; ///< Our base class + +using Values = Values; ///< backwards compatibility + +public: + +/// @name Standard Constructors +/// @{ + +/** Default constructor creates empty factor */ +HybridFactor() {} + +/** Construct from container of keys. This constructor is used internally from derived factor + * constructors, either from a container of keys or from a boost::assign::list_of. */ +template +HybridFactor(const CONTAINER& keys) : Base(keys) {} + +/// Virtual destructor +virtual ~HybridFactor() { +} + +/// @} +/// @name Testable +/// @{ + +/// equals +virtual bool equals(const HybridFactor& lf, double tol = 1e-9) const = 0; + +/// print +void print( + const std::string& s = "HybridFactor\n", + const KeyFormatter& formatter = DefaultKeyFormatter) const override { +Base::print(s, formatter); +} + +/// @} +/// @name Standard Interface +/// @{ + +/// @} +}; +// HybridFactor + +// traits +template<> struct traits : public Testable {}; + +}// namespace gtsam diff --git a/gtsam/hybrid/HybridFactorGraph.cpp b/gtsam/hybrid/HybridFactorGraph.cpp new file mode 100644 index 000000000..686fddc51 --- /dev/null +++ b/gtsam/hybrid/HybridFactorGraph.cpp @@ -0,0 +1,58 @@ +// +// Created by Fan Jiang on 3/11/22. +// + +#include +#include +#include + +#include + +#include + +namespace gtsam { + +template class EliminateableFactorGraph; + +/* ************************************************************************ */ +std::pair // +EliminateHybrid(const HybridFactorGraph& factors, + const Ordering& frontalKeys) { + // NOTE(fan): Because we are in the Conditional Gaussian regime there are only + // few cases: continuous variable, we make a GM if there are hybrid factors; + // continuous variable, we make a GF if there are no hybrid factors; + // discrete variable, no continuous factor is allowed (escapes CG regime), so + // we panic, if discrete only we do the discrete elimination. + + // The issue here is that, how can we know which variable is discrete if we + // unify Values? Obviously we can tell using the factors, but is that fast? + + // PRODUCT: multiply all factors + gttic(product); + HybridGaussianFactor product(JacobianFactor(0, I_3x3, Z_3x1)); +// for (auto&& factor : factors) product = (*factor) * product; + gttoc(product); + + // sum out frontals, this is the factor on the separator + gttic(sum); +// HybridFactor::shared_ptr sum = product.sum(frontalKeys); + gttoc(sum); + + // Ordering keys for the conditional so that frontalKeys are really in front +// Ordering orderedKeys; +// orderedKeys.insert(orderedKeys.end(), frontalKeys.begin(), +// frontalKeys.end()); +// orderedKeys.insert(orderedKeys.end(), sum->keys().begin(), +// sum->keys().end()); + + // now divide product/sum to get conditional + gttic(divide); +// auto conditional = +// boost::make_shared(product, *sum, orderedKeys); + gttoc(divide); + +// return std::make_pair(conditional, sum); + return std::make_pair(boost::make_shared(), boost::make_shared(product)); +} + +} diff --git a/gtsam/hybrid/HybridFactorGraph.h b/gtsam/hybrid/HybridFactorGraph.h new file mode 100644 index 000000000..fb0de644d --- /dev/null +++ b/gtsam/hybrid/HybridFactorGraph.h @@ -0,0 +1,83 @@ +/* ---------------------------------------------------------------------------- + + * 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 HybridFactorGraph.h + * @brief Hybrid factor graph that uses type erasure + * @author Fan Jiang + * @date Mar 11, 2022 + */ + +#pragma once + +#include +#include +#include +#include + +namespace gtsam { + +// Forward declarations +class HybridFactorGraph; +class HybridConditional; +class HybridBayesNet; +class HybridEliminationTree; +class HybridBayesTree; +class HybridJunctionTree; + +/** Main elimination function for HybridFactorGraph */ +GTSAM_EXPORT std::pair, HybridFactor::shared_ptr> +EliminateHybrid(const HybridFactorGraph& factors, const Ordering& keys); + +/* ************************************************************************* */ +template<> struct EliminationTraits +{ + typedef HybridFactor FactorType; ///< Type of factors in factor graph + typedef HybridFactorGraph FactorGraphType; ///< Type of the factor graph (e.g. HybridFactorGraph) + typedef HybridConditional ConditionalType; ///< Type of conditionals from elimination + typedef HybridBayesNet BayesNetType; ///< Type of Bayes net from sequential elimination + typedef HybridEliminationTree EliminationTreeType; ///< Type of elimination tree + typedef HybridBayesTree BayesTreeType; ///< Type of Bayes tree + typedef HybridJunctionTree JunctionTreeType; ///< Type of Junction tree + /// The default dense elimination function + static std::pair, boost::shared_ptr > + DefaultEliminate(const FactorGraphType& factors, const Ordering& keys) { + return EliminateHybrid(factors, keys); } +}; + + +class HybridFactorGraph : public FactorGraph, public EliminateableFactorGraph { + public: + using Base = FactorGraph; + using This = HybridFactorGraph; ///< this class + using BaseEliminateable = + EliminateableFactorGraph; ///< for elimination + using shared_ptr = boost::shared_ptr; ///< shared_ptr to This + + using Values = gtsam::Values; ///< backwards compatibility + using Indices = KeyVector; ///> map from keys to values + + public: + HybridFactorGraph() = default; + + /** Construct from container of factors (shared_ptr or plain objects) */ + template + explicit HybridFactorGraph(const CONTAINER& factors) : Base(factors) {} + + /** Implicit copy/downcast constructor to override explicit template container + * constructor */ + template + HybridFactorGraph(const FactorGraph& graph) : Base(graph) {} + +}; + +} + diff --git a/gtsam/hybrid/HybridGaussianFactor.cpp b/gtsam/hybrid/HybridGaussianFactor.cpp new file mode 100644 index 000000000..1910c3307 --- /dev/null +++ b/gtsam/hybrid/HybridGaussianFactor.cpp @@ -0,0 +1,23 @@ +// +// Created by Fan Jiang on 3/11/22. +// + +#include + +#include + +namespace gtsam { + +HybridGaussianFactor::HybridGaussianFactor(GaussianFactor::shared_ptr other) : Base(other->keys()){ + inner = other; +} + +HybridGaussianFactor::HybridGaussianFactor(JacobianFactor &&jf) : Base(jf.keys()), inner(boost::make_shared(std::move(jf))) { + +} + +bool HybridGaussianFactor::equals(const HybridFactor& lf, double tol) const { + return false; +}; + +} \ No newline at end of file diff --git a/gtsam/hybrid/HybridGaussianFactor.h b/gtsam/hybrid/HybridGaussianFactor.h new file mode 100644 index 000000000..e40682dc1 --- /dev/null +++ b/gtsam/hybrid/HybridGaussianFactor.h @@ -0,0 +1,39 @@ +/* ---------------------------------------------------------------------------- + + * 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 HybridGaussianFactor.h + * @date Mar 11, 2022 + * @author Fan Jiang + */ + +#include +#include +#include + +namespace gtsam { + +class HybridGaussianFactor : public HybridFactor { + public: + using Base = HybridFactor; + + GaussianFactor::shared_ptr inner; + + // Implicit conversion from a shared ptr of GF + HybridGaussianFactor(GaussianFactor::shared_ptr other); + + // Forwarding constructor from concrete JacobianFactor + HybridGaussianFactor(JacobianFactor &&jf); + + public: + virtual bool equals(const HybridFactor& lf, double tol) const override; +}; +} diff --git a/gtsam/hybrid/HybridJunctionTree.cpp b/gtsam/hybrid/HybridJunctionTree.cpp new file mode 100644 index 000000000..eabfc2e7c --- /dev/null +++ b/gtsam/hybrid/HybridJunctionTree.cpp @@ -0,0 +1,34 @@ +/* ---------------------------------------------------------------------------- + + * 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 HybridJunctionTree.cpp + * @date Mar 29, 2013 + * @author Frank Dellaert + * @author Richard Roberts + */ + +#include +#include +#include + +namespace gtsam { + +// Instantiate base classes +template class EliminatableClusterTree; +template class JunctionTree; + +/* ************************************************************************* */ +HybridJunctionTree::HybridJunctionTree( + const HybridEliminationTree& eliminationTree) : + Base(eliminationTree) {} + +} diff --git a/gtsam/hybrid/HybridJunctionTree.h b/gtsam/hybrid/HybridJunctionTree.h new file mode 100644 index 000000000..1901e7007 --- /dev/null +++ b/gtsam/hybrid/HybridJunctionTree.h @@ -0,0 +1,67 @@ +/* ---------------------------------------------------------------------------- + + * 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 HybridJunctionTree.h + * @date Mar 11, 2022 + * @author Fan Jiang + */ + +#pragma once + +#include +#include +#include + +namespace gtsam { + +// Forward declarations +class HybridEliminationTree; + +/** + * An EliminatableClusterTree, i.e., a set of variable clusters with factors, arranged in a tree, + * with the additional property that it represents the clique tree associated with a Bayes net. + * + * In GTSAM a junction tree is an intermediate data structure in multifrontal + * variable elimination. Each node is a cluster of factors, along with a + * clique of variables that are eliminated all at once. In detail, every node k represents + * a clique (maximal fully connected subset) of an associated chordal graph, such as a + * chordal Bayes net resulting from elimination. + * + * The difference with the BayesTree is that a JunctionTree stores factors, whereas a + * BayesTree stores conditionals, that are the product of eliminating the factors in the + * corresponding JunctionTree cliques. + * + * The tree structure and elimination method are exactly analogous to the EliminationTree, + * except that in the JunctionTree, at each node multiple variables are eliminated at a time. + * + * \addtogroup Multifrontal + * \nosubgrouping + */ +class GTSAM_EXPORT HybridJunctionTree : + public JunctionTree { + public: + typedef JunctionTree Base; ///< Base class + typedef HybridJunctionTree This; ///< This class + typedef boost::shared_ptr shared_ptr; ///< Shared pointer to this class + + /** + * Build the elimination tree of a factor graph using precomputed column structure. + * @param factorGraph The factor graph for which to build the elimination tree + * @param structure The set of factors involving each variable. If this is not + * precomputed, you can call the Create(const FactorGraph&) + * named constructor instead. + * @return The elimination tree + */ + HybridJunctionTree(const HybridEliminationTree& eliminationTree); +}; + +} diff --git a/gtsam/hybrid/tests/CMakeLists.txt b/gtsam/hybrid/tests/CMakeLists.txt new file mode 100644 index 000000000..b52e18586 --- /dev/null +++ b/gtsam/hybrid/tests/CMakeLists.txt @@ -0,0 +1 @@ +gtsamAddTestsGlob(hybrid "test*.cpp" "" "gtsam") \ No newline at end of file diff --git a/gtsam/hybrid/tests/testHybridConditional.cpp b/gtsam/hybrid/tests/testHybridConditional.cpp new file mode 100644 index 000000000..295d6011d --- /dev/null +++ b/gtsam/hybrid/tests/testHybridConditional.cpp @@ -0,0 +1,73 @@ +/* ---------------------------------------------------------------------------- + + * 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 testHybridConditional.cpp + * @date Mar 11, 2022 + * @author Fan Jiang + */ + +#include +#include +#include +#include +#include +#include + +#include +#include + +#include + +#include +using namespace boost::assign; + +using namespace std; +using namespace gtsam; + +/* ************************************************************************* */ +TEST_UNSAFE(HybridFactorGraph, test) { + HybridConditional test; + GTSAM_PRINT(test); + + HybridFactorGraph hfg; + + hfg.add(HybridGaussianFactor(JacobianFactor(0, I_3x3, Z_3x1))); + GTSAM_PRINT(hfg); +} + +TEST_UNSAFE(HybridFactorGraph, eliminate) { + HybridFactorGraph hfg; + + hfg.add(HybridGaussianFactor(JacobianFactor(0, I_3x3, Z_3x1))); + + auto result = hfg.eliminatePartialSequential({0}); + + GTSAM_PRINT(*result.first); +} + +TEST(HybridFactorGraph, eliminateMultifrontal) { + HybridFactorGraph hfg; + + hfg.add(HybridGaussianFactor(JacobianFactor(0, I_3x3, Z_3x1))); + + auto result = hfg.eliminatePartialMultifrontal({0}); + + GTSAM_PRINT(*result.first); +} + +/* ************************************************************************* */ +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} +/* ************************************************************************* */ + From efa37ff315fb0ad9f837e2bb8a589afcd2cb9256 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Fri, 11 Mar 2022 19:20:39 -0500 Subject: [PATCH 0180/1686] Add better mocking for actual elimination --- gtsam/hybrid/HybridBayesTree.cpp | 5 ++- gtsam/hybrid/HybridBayesTree.h | 5 ++- gtsam/hybrid/HybridConditional.h | 4 +++ gtsam/hybrid/HybridDiscreteFactor.cpp | 11 ++++-- gtsam/hybrid/HybridDiscreteFactor.h | 5 +++ gtsam/hybrid/HybridFactorGraph.cpp | 37 ++++++++++++++------ gtsam/hybrid/HybridGaussianFactor.cpp | 2 +- gtsam/hybrid/HybridJunctionTree.cpp | 5 ++- gtsam/hybrid/tests/testHybridConditional.cpp | 5 +++ 9 files changed, 57 insertions(+), 22 deletions(-) diff --git a/gtsam/hybrid/HybridBayesTree.cpp b/gtsam/hybrid/HybridBayesTree.cpp index 72f3fd794..85e6c84ae 100644 --- a/gtsam/hybrid/HybridBayesTree.cpp +++ b/gtsam/hybrid/HybridBayesTree.cpp @@ -12,9 +12,8 @@ /** * @file HybridBayesTree.cpp * @brief Hybrid Bayes Tree, the result of eliminating a HybridJunctionTree - * @brief HybridBayesTree - * @author Frank Dellaert - * @author Richard Roberts + * @date Mar 11, 2022 + * @author Fan Jiang */ #include diff --git a/gtsam/hybrid/HybridBayesTree.h b/gtsam/hybrid/HybridBayesTree.h index 2ea40cecc..06df66112 100644 --- a/gtsam/hybrid/HybridBayesTree.h +++ b/gtsam/hybrid/HybridBayesTree.h @@ -13,9 +13,8 @@ * @file HybridBayesTree.h * @brief Hybrid Bayes Tree, the result of eliminating a * HybridJunctionTree - * @brief HybridBayesTree - * @author Frank Dellaert - * @author Richard Roberts + * @date Mar 11, 2022 + * @author Fan Jiang */ #pragma once diff --git a/gtsam/hybrid/HybridConditional.h b/gtsam/hybrid/HybridConditional.h index d6dd8250f..e9aa5f616 100644 --- a/gtsam/hybrid/HybridConditional.h +++ b/gtsam/hybrid/HybridConditional.h @@ -59,6 +59,10 @@ public: /// Default constructor needed for serialization. HybridConditional() = default; +HybridConditional(size_t nFrontals, const KeyVector& keys) : BaseFactor(keys), BaseConditional(nFrontals) { + +} + /** * @brief Combine two conditionals, yielding a new conditional with the union * of the frontal keys, ordered by gtsam::Key. diff --git a/gtsam/hybrid/HybridDiscreteFactor.cpp b/gtsam/hybrid/HybridDiscreteFactor.cpp index fded0a2df..0bd2c9a64 100644 --- a/gtsam/hybrid/HybridDiscreteFactor.cpp +++ b/gtsam/hybrid/HybridDiscreteFactor.cpp @@ -8,12 +8,19 @@ namespace gtsam { -HybridDiscreteFactor::HybridDiscreteFactor(DiscreteFactor::shared_ptr other) { +HybridDiscreteFactor::HybridDiscreteFactor(DiscreteFactor::shared_ptr other) + : Base(other->keys()) { inner = other; } -HybridDiscreteFactor::HybridDiscreteFactor(DecisionTreeFactor &&dtf) : inner(boost::make_shared(std::move(dtf))) { +HybridDiscreteFactor::HybridDiscreteFactor(DecisionTreeFactor &&dtf) + : Base(dtf.keys()), + inner(boost::make_shared(std::move(dtf))) { +} + +bool HybridDiscreteFactor::equals(const HybridFactor &lf, double tol) const { + return false; }; } \ No newline at end of file diff --git a/gtsam/hybrid/HybridDiscreteFactor.h b/gtsam/hybrid/HybridDiscreteFactor.h index 4b1c00672..cfb94bc69 100644 --- a/gtsam/hybrid/HybridDiscreteFactor.h +++ b/gtsam/hybrid/HybridDiscreteFactor.h @@ -23,6 +23,8 @@ namespace gtsam { class HybridDiscreteFactor : public HybridFactor { public: + using Base = HybridFactor; + DiscreteFactor::shared_ptr inner; // Implicit conversion from a shared ptr of GF @@ -30,5 +32,8 @@ class HybridDiscreteFactor : public HybridFactor { // Forwarding constructor from concrete JacobianFactor HybridDiscreteFactor(DecisionTreeFactor &&dtf); + + public: + virtual bool equals(const HybridFactor& lf, double tol) const override; }; } diff --git a/gtsam/hybrid/HybridFactorGraph.cpp b/gtsam/hybrid/HybridFactorGraph.cpp index 686fddc51..0f9d8ddca 100644 --- a/gtsam/hybrid/HybridFactorGraph.cpp +++ b/gtsam/hybrid/HybridFactorGraph.cpp @@ -7,17 +7,19 @@ #include #include +#include #include namespace gtsam { -template class EliminateableFactorGraph; +template +class EliminateableFactorGraph; /* ************************************************************************ */ std::pair // -EliminateHybrid(const HybridFactorGraph& factors, - const Ordering& frontalKeys) { +EliminateHybrid(const HybridFactorGraph &factors, + const Ordering &frontalKeys) { // NOTE(fan): Because we are in the Conditional Gaussian regime there are only // few cases: continuous variable, we make a GM if there are hybrid factors; // continuous variable, we make a GF if there are no hybrid factors; @@ -29,7 +31,20 @@ EliminateHybrid(const HybridFactorGraph& factors, // PRODUCT: multiply all factors gttic(product); - HybridGaussianFactor product(JacobianFactor(0, I_3x3, Z_3x1)); + KeySet allKeys; + // TODO: we do a mock by just doing the correct key thing + std::cout << "Begin Eliminate\n"; + for (auto &&factor : factors) { + std::cout << ">>> Eliminating: "; + factor->printKeys(); + allKeys.insert(factor->begin(), factor->end()); + } + for (auto &k : frontalKeys) { + allKeys.erase(k); + } + + HybridConditional sum(allKeys.size(), Ordering(allKeys)); +// HybridDiscreteFactor product(DiscreteConditional()); // for (auto&& factor : factors) product = (*factor) * product; gttoc(product); @@ -39,11 +54,11 @@ EliminateHybrid(const HybridFactorGraph& factors, gttoc(sum); // Ordering keys for the conditional so that frontalKeys are really in front -// Ordering orderedKeys; -// orderedKeys.insert(orderedKeys.end(), frontalKeys.begin(), -// frontalKeys.end()); -// orderedKeys.insert(orderedKeys.end(), sum->keys().begin(), -// sum->keys().end()); + Ordering orderedKeys; + orderedKeys.insert(orderedKeys.end(), frontalKeys.begin(), + frontalKeys.end()); + orderedKeys.insert(orderedKeys.end(), sum.keys().begin(), + sum.keys().end()); // now divide product/sum to get conditional gttic(divide); @@ -52,7 +67,9 @@ EliminateHybrid(const HybridFactorGraph& factors, gttoc(divide); // return std::make_pair(conditional, sum); - return std::make_pair(boost::make_shared(), boost::make_shared(product)); + return std::make_pair(boost::make_shared(frontalKeys.size(), + orderedKeys), + boost::make_shared(std::move(sum))); } } diff --git a/gtsam/hybrid/HybridGaussianFactor.cpp b/gtsam/hybrid/HybridGaussianFactor.cpp index 1910c3307..1e87cbbc3 100644 --- a/gtsam/hybrid/HybridGaussianFactor.cpp +++ b/gtsam/hybrid/HybridGaussianFactor.cpp @@ -8,7 +8,7 @@ namespace gtsam { -HybridGaussianFactor::HybridGaussianFactor(GaussianFactor::shared_ptr other) : Base(other->keys()){ +HybridGaussianFactor::HybridGaussianFactor(GaussianFactor::shared_ptr other) : Base(other->keys()) { inner = other; } diff --git a/gtsam/hybrid/HybridJunctionTree.cpp b/gtsam/hybrid/HybridJunctionTree.cpp index eabfc2e7c..0e3d2ea00 100644 --- a/gtsam/hybrid/HybridJunctionTree.cpp +++ b/gtsam/hybrid/HybridJunctionTree.cpp @@ -11,9 +11,8 @@ /** * @file HybridJunctionTree.cpp - * @date Mar 29, 2013 - * @author Frank Dellaert - * @author Richard Roberts + * @date Mar 11, 2022 + * @author Fan Jiang */ #include diff --git a/gtsam/hybrid/tests/testHybridConditional.cpp b/gtsam/hybrid/tests/testHybridConditional.cpp index 295d6011d..6eef100c1 100644 --- a/gtsam/hybrid/tests/testHybridConditional.cpp +++ b/gtsam/hybrid/tests/testHybridConditional.cpp @@ -19,6 +19,7 @@ #include #include #include +#include #include #include @@ -57,11 +58,15 @@ TEST_UNSAFE(HybridFactorGraph, eliminate) { TEST(HybridFactorGraph, eliminateMultifrontal) { HybridFactorGraph hfg; + DiscreteKey X(1, 2); + hfg.add(HybridGaussianFactor(JacobianFactor(0, I_3x3, Z_3x1))); + hfg.add(HybridDiscreteFactor(DecisionTreeFactor(X, {2, 8}))); auto result = hfg.eliminatePartialMultifrontal({0}); GTSAM_PRINT(*result.first); + GTSAM_PRINT(*result.second); } /* ************************************************************************* */ From 3aac52c3d3b6ec692dbc7f0d7874a0cd335814a1 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Sat, 12 Mar 2022 10:49:11 -0500 Subject: [PATCH 0181/1686] Fix compilation error --- gtsam/hybrid/HybridFactor.h | 49 +++++++++++++++--------------- gtsam/hybrid/HybridFactorGraph.cpp | 3 ++ 2 files changed, 27 insertions(+), 25 deletions(-) diff --git a/gtsam/hybrid/HybridFactor.h b/gtsam/hybrid/HybridFactor.h index 5af1a23a9..eb28bc168 100644 --- a/gtsam/hybrid/HybridFactor.h +++ b/gtsam/hybrid/HybridFactor.h @@ -27,47 +27,45 @@ namespace gtsam { /** * Base class for hybrid probabilistic factors */ -class GTSAM_EXPORT HybridFactor: public Factor { +class GTSAM_EXPORT HybridFactor : public Factor { public: -// typedefs needed to play nice with gtsam -typedef HybridFactor This; ///< This class -typedef boost::shared_ptr shared_ptr; ///< shared_ptr to this class -typedef Factor Base; ///< Our base class - -using Values = Values; ///< backwards compatibility + // typedefs needed to play nice with gtsam + typedef HybridFactor This; ///< This class + typedef boost::shared_ptr shared_ptr; ///< shared_ptr to this class + typedef Factor Base; ///< Our base class public: /// @name Standard Constructors /// @{ -/** Default constructor creates empty factor */ -HybridFactor() {} + /** Default constructor creates empty factor */ + HybridFactor() {} -/** Construct from container of keys. This constructor is used internally from derived factor - * constructors, either from a container of keys or from a boost::assign::list_of. */ -template -HybridFactor(const CONTAINER& keys) : Base(keys) {} + /** Construct from container of keys. This constructor is used internally from derived factor + * constructors, either from a container of keys or from a boost::assign::list_of. */ + template + HybridFactor(const CONTAINER &keys) : Base(keys) {} -/// Virtual destructor -virtual ~HybridFactor() { -} + /// Virtual destructor + virtual ~HybridFactor() { + } /// @} /// @name Testable /// @{ -/// equals -virtual bool equals(const HybridFactor& lf, double tol = 1e-9) const = 0; + /// equals + virtual bool equals(const HybridFactor &lf, double tol = 1e-9) const = 0; -/// print -void print( - const std::string& s = "HybridFactor\n", - const KeyFormatter& formatter = DefaultKeyFormatter) const override { -Base::print(s, formatter); -} + /// print + void print( + const std::string &s = "HybridFactor\n", + const KeyFormatter &formatter = DefaultKeyFormatter) const override { + Base::print(s, formatter); + } /// @} /// @name Standard Interface @@ -78,6 +76,7 @@ Base::print(s, formatter); // HybridFactor // traits -template<> struct traits : public Testable {}; +template<> +struct traits : public Testable {}; }// namespace gtsam diff --git a/gtsam/hybrid/HybridFactorGraph.cpp b/gtsam/hybrid/HybridFactorGraph.cpp index 0f9d8ddca..bd245b16a 100644 --- a/gtsam/hybrid/HybridFactorGraph.cpp +++ b/gtsam/hybrid/HybridFactorGraph.cpp @@ -29,6 +29,9 @@ EliminateHybrid(const HybridFactorGraph &factors, // The issue here is that, how can we know which variable is discrete if we // unify Values? Obviously we can tell using the factors, but is that fast? + // In the case of multifrontal, we will need to use a constrained ordering + // so that the discrete parts will be guaranteed to be eliminated last! + // PRODUCT: multiply all factors gttic(product); KeySet allKeys; From 53551e051dedae2c245f47dbf69bf390844bb3ab Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Sat, 12 Mar 2022 11:51:48 -0500 Subject: [PATCH 0182/1686] Add shorthand for inserting raw JacobianFactor --- gtsam/hybrid/CGMixtureFactor.h | 22 +++++++++++-- gtsam/hybrid/HybridDiscreteFactor.cpp | 2 +- gtsam/hybrid/HybridDiscreteFactor.h | 2 ++ gtsam/hybrid/HybridFactor.h | 34 ++++++++++++++++++-- gtsam/hybrid/HybridFactorGraph.cpp | 3 ++ gtsam/hybrid/HybridFactorGraph.h | 6 ++++ gtsam/hybrid/HybridGaussianFactor.h | 2 ++ gtsam/hybrid/tests/testHybridConditional.cpp | 12 ++++--- 8 files changed, 72 insertions(+), 11 deletions(-) diff --git a/gtsam/hybrid/CGMixtureFactor.h b/gtsam/hybrid/CGMixtureFactor.h index f2fa1e54a..b46146eb3 100644 --- a/gtsam/hybrid/CGMixtureFactor.h +++ b/gtsam/hybrid/CGMixtureFactor.h @@ -5,19 +5,35 @@ /** * @file CGMixtureFactor.h - * @brief Custom hybrid factor graph for discrete + continuous factors - * @author Kevin Doherty, kdoherty@mit.edu + * @brief A set of Gaussian factors indexed by a set of discrete keys. * @author Varun Agrawal * @author Fan Jiang + * @author Frank Dellaert * @date December 2021 */ #include +#include +#include +#include namespace gtsam { -class CGMixtureFactor : HybridFactor { +class CGMixtureFactor : public HybridFactor { +public: + using Base = HybridFactor; + using This = CGMixtureFactor; + using shared_ptr = boost::shared_ptr; + using Factors = DecisionTree; + + Factors factors_; + + CGMixtureFactor() = default; + + CGMixtureFactor(const KeyVector &continuousKeys, const DiscreteKeys &discreteKeys, const Factors &factors) : Base(continuousKeys, discreteKeys) { + + } }; } diff --git a/gtsam/hybrid/HybridDiscreteFactor.cpp b/gtsam/hybrid/HybridDiscreteFactor.cpp index 0bd2c9a64..13766933b 100644 --- a/gtsam/hybrid/HybridDiscreteFactor.cpp +++ b/gtsam/hybrid/HybridDiscreteFactor.cpp @@ -14,7 +14,7 @@ HybridDiscreteFactor::HybridDiscreteFactor(DiscreteFactor::shared_ptr other) } HybridDiscreteFactor::HybridDiscreteFactor(DecisionTreeFactor &&dtf) - : Base(dtf.keys()), + : Base(dtf.discreteKeys()), inner(boost::make_shared(std::move(dtf))) { } diff --git a/gtsam/hybrid/HybridDiscreteFactor.h b/gtsam/hybrid/HybridDiscreteFactor.h index cfb94bc69..0395c9512 100644 --- a/gtsam/hybrid/HybridDiscreteFactor.h +++ b/gtsam/hybrid/HybridDiscreteFactor.h @@ -24,6 +24,8 @@ namespace gtsam { class HybridDiscreteFactor : public HybridFactor { public: using Base = HybridFactor; + using This = HybridDiscreteFactor; + using shared_ptr = boost::shared_ptr; DiscreteFactor::shared_ptr inner; diff --git a/gtsam/hybrid/HybridFactor.h b/gtsam/hybrid/HybridFactor.h index eb28bc168..64b49f605 100644 --- a/gtsam/hybrid/HybridFactor.h +++ b/gtsam/hybrid/HybridFactor.h @@ -19,6 +19,7 @@ #include #include +#include #include #include @@ -36,6 +37,12 @@ public: typedef boost::shared_ptr shared_ptr; ///< shared_ptr to this class typedef Factor Base; ///< Our base class + bool isDiscrete_ = false; + bool isContinuous_ = false; + bool isHybrid_ = false; + + DiscreteKeys discreteKeys_; + public: /// @name Standard Constructors @@ -46,8 +53,25 @@ public: /** Construct from container of keys. This constructor is used internally from derived factor * constructors, either from a container of keys or from a boost::assign::list_of. */ - template - HybridFactor(const CONTAINER &keys) : Base(keys) {} +// template +// HybridFactor(const CONTAINER &keys) : Base(keys) {} + + HybridFactor(const KeyVector &keys) : Base(keys), isContinuous_(true) {} + + static KeyVector CollectKeys(const KeyVector &continuousKeys, const DiscreteKeys &discreteKeys) { + KeyVector allKeys; + std::copy(continuousKeys.begin(), continuousKeys.end(), std::back_inserter(allKeys)); + std::transform(discreteKeys.begin(), + discreteKeys.end(), + std::back_inserter(allKeys), + [](const DiscreteKey &k) { return k.first; }); + return allKeys; + } + + HybridFactor(const KeyVector &continuousKeys, const DiscreteKeys &discreteKeys) : Base( + CollectKeys(continuousKeys, discreteKeys)), isHybrid_(true) {} + + HybridFactor(const DiscreteKeys &discreteKeys) : Base(CollectKeys({}, discreteKeys)), isDiscrete_(true) {} /// Virtual destructor virtual ~HybridFactor() { @@ -64,7 +88,11 @@ public: void print( const std::string &s = "HybridFactor\n", const KeyFormatter &formatter = DefaultKeyFormatter) const override { - Base::print(s, formatter); + std::cout << s; + if (isContinuous_) std::cout << "Cont. "; + if (isDiscrete_) std::cout << "Disc. "; + if (isHybrid_) std::cout << "Hybr. "; + this->printKeys("", formatter); } /// @} diff --git a/gtsam/hybrid/HybridFactorGraph.cpp b/gtsam/hybrid/HybridFactorGraph.cpp index bd245b16a..080efc0e9 100644 --- a/gtsam/hybrid/HybridFactorGraph.cpp +++ b/gtsam/hybrid/HybridFactorGraph.cpp @@ -75,4 +75,7 @@ EliminateHybrid(const HybridFactorGraph &factors, boost::make_shared(std::move(sum))); } +void HybridFactorGraph::add(JacobianFactor &&factor) { + FactorGraph::add(boost::make_shared(std::move(factor))); +} } diff --git a/gtsam/hybrid/HybridFactorGraph.h b/gtsam/hybrid/HybridFactorGraph.h index fb0de644d..13bbd005d 100644 --- a/gtsam/hybrid/HybridFactorGraph.h +++ b/gtsam/hybrid/HybridFactorGraph.h @@ -33,6 +33,8 @@ class HybridEliminationTree; class HybridBayesTree; class HybridJunctionTree; +class JacobianFactor; + /** Main elimination function for HybridFactorGraph */ GTSAM_EXPORT std::pair, HybridFactor::shared_ptr> EliminateHybrid(const HybridFactorGraph& factors, const Ordering& keys); @@ -77,6 +79,10 @@ class HybridFactorGraph : public FactorGraph, public Eliminateable template HybridFactorGraph(const FactorGraph& graph) : Base(graph) {} + using FactorGraph::add; + + /// Add a factor directly using a shared_ptr. + void add(JacobianFactor &&factor); }; } diff --git a/gtsam/hybrid/HybridGaussianFactor.h b/gtsam/hybrid/HybridGaussianFactor.h index e40682dc1..d8a97ba30 100644 --- a/gtsam/hybrid/HybridGaussianFactor.h +++ b/gtsam/hybrid/HybridGaussianFactor.h @@ -24,6 +24,8 @@ namespace gtsam { class HybridGaussianFactor : public HybridFactor { public: using Base = HybridFactor; + using This = HybridGaussianFactor; + using shared_ptr = boost::shared_ptr; GaussianFactor::shared_ptr inner; diff --git a/gtsam/hybrid/tests/testHybridConditional.cpp b/gtsam/hybrid/tests/testHybridConditional.cpp index 6eef100c1..a56bcadf0 100644 --- a/gtsam/hybrid/tests/testHybridConditional.cpp +++ b/gtsam/hybrid/tests/testHybridConditional.cpp @@ -26,6 +26,8 @@ #include #include +#include + #include #include @@ -34,6 +36,8 @@ using namespace boost::assign; using namespace std; using namespace gtsam; +using gtsam::symbol_shorthand::X; + /* ************************************************************************* */ TEST_UNSAFE(HybridFactorGraph, test) { HybridConditional test; @@ -58,12 +62,12 @@ TEST_UNSAFE(HybridFactorGraph, eliminate) { TEST(HybridFactorGraph, eliminateMultifrontal) { HybridFactorGraph hfg; - DiscreteKey X(1, 2); + DiscreteKey x(X(1), 2); - hfg.add(HybridGaussianFactor(JacobianFactor(0, I_3x3, Z_3x1))); - hfg.add(HybridDiscreteFactor(DecisionTreeFactor(X, {2, 8}))); + hfg.add(JacobianFactor(X(0), I_3x3, Z_3x1)); + hfg.add(HybridDiscreteFactor(DecisionTreeFactor(x, {2, 8}))); - auto result = hfg.eliminatePartialMultifrontal({0}); + auto result = hfg.eliminatePartialMultifrontal({X(0)}); GTSAM_PRINT(*result.first); GTSAM_PRINT(*result.second); From 095f6ad7cc96d284fb663a4cfb62f0d5f48f9204 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Sat, 12 Mar 2022 12:42:58 -0500 Subject: [PATCH 0183/1686] Add full elimination --- gtsam/hybrid/HybridFactorGraph.h | 12 +++++++----- gtsam/hybrid/tests/testHybridConditional.cpp | 13 +++++++++++++ 2 files changed, 20 insertions(+), 5 deletions(-) diff --git a/gtsam/hybrid/HybridFactorGraph.h b/gtsam/hybrid/HybridFactorGraph.h index 13bbd005d..9a57d36e6 100644 --- a/gtsam/hybrid/HybridFactorGraph.h +++ b/gtsam/hybrid/HybridFactorGraph.h @@ -70,17 +70,19 @@ class HybridFactorGraph : public FactorGraph, public Eliminateable public: HybridFactorGraph() = default; - /** Construct from container of factors (shared_ptr or plain objects) */ - template - explicit HybridFactorGraph(const CONTAINER& factors) : Base(factors) {} +// /** Construct from container of factors (shared_ptr or plain objects) */ +// template +// explicit HybridFactorGraph(const CONTAINER& factors) : Base(factors) {} /** Implicit copy/downcast constructor to override explicit template container - * constructor */ + * constructor. In BayesTree this is used for: + * `cachedSeparatorMarginal_.reset(*separatorMarginal)` + * */ template HybridFactorGraph(const FactorGraph& graph) : Base(graph) {} using FactorGraph::add; - + /// Add a factor directly using a shared_ptr. void add(JacobianFactor &&factor); }; diff --git a/gtsam/hybrid/tests/testHybridConditional.cpp b/gtsam/hybrid/tests/testHybridConditional.cpp index a56bcadf0..d5a21f34d 100644 --- a/gtsam/hybrid/tests/testHybridConditional.cpp +++ b/gtsam/hybrid/tests/testHybridConditional.cpp @@ -73,6 +73,19 @@ TEST(HybridFactorGraph, eliminateMultifrontal) { GTSAM_PRINT(*result.second); } +TEST(HybridFactorGraph, eliminateFullMultifrontal) { + HybridFactorGraph hfg; + + DiscreteKey x(X(1), 2); + + hfg.add(JacobianFactor(X(0), I_3x3, Z_3x1)); + hfg.add(HybridDiscreteFactor(DecisionTreeFactor(x, {2, 8}))); + + auto result = hfg.eliminateMultifrontal(); + + GTSAM_PRINT(*result); +} + /* ************************************************************************* */ int main() { TestResult tr; From 2bae2865d74efc139c8c77fcfe8a4d60bcb8eaab Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Sat, 12 Mar 2022 16:29:26 -0500 Subject: [PATCH 0184/1686] More mock-ups added --- gtsam/hybrid/CGMixtureFactor.cpp | 14 ++++++++- gtsam/hybrid/CGMixtureFactor.h | 18 ++++++++---- gtsam/hybrid/CLGaussianConditional.cpp | 20 +++++++++++++ gtsam/hybrid/CLGaussianConditional.h | 31 ++++++++++++++++++++ gtsam/hybrid/HybridConditional.h | 2 +- gtsam/hybrid/HybridFactorGraph.cpp | 14 +++++---- gtsam/hybrid/HybridGaussianFactor.h | 6 ++-- gtsam/hybrid/tests/testHybridConditional.cpp | 25 +++++++++++----- 8 files changed, 107 insertions(+), 23 deletions(-) create mode 100644 gtsam/hybrid/CLGaussianConditional.cpp create mode 100644 gtsam/hybrid/CLGaussianConditional.h diff --git a/gtsam/hybrid/CGMixtureFactor.cpp b/gtsam/hybrid/CGMixtureFactor.cpp index d789825f7..2ddf80ec2 100644 --- a/gtsam/hybrid/CGMixtureFactor.cpp +++ b/gtsam/hybrid/CGMixtureFactor.cpp @@ -2,4 +2,16 @@ // Created by Fan Jiang on 3/11/22. // -#include "CGMixtureFactor.h" +#include + +namespace gtsam { + +CGMixtureFactor::CGMixtureFactor(const KeyVector &continuousKeys, + const DiscreteKeys &discreteKeys, + const Factors &factors) : Base(continuousKeys, discreteKeys), + factors_(factors) {} +bool CGMixtureFactor::equals(const HybridFactor &lf, double tol) const { + return false; +} + +} \ No newline at end of file diff --git a/gtsam/hybrid/CGMixtureFactor.h b/gtsam/hybrid/CGMixtureFactor.h index b46146eb3..9c9e43ec2 100644 --- a/gtsam/hybrid/CGMixtureFactor.h +++ b/gtsam/hybrid/CGMixtureFactor.h @@ -1,15 +1,21 @@ /* ---------------------------------------------------------------------------- - * Copyright 2021 The Ambitious Folks of the MRG + + * 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 CGMixtureFactor.h * @brief A set of Gaussian factors indexed by a set of discrete keys. - * @author Varun Agrawal * @author Fan Jiang + * @author Varun Agrawal * @author Frank Dellaert - * @date December 2021 + * @date Mar 12, 2022 */ #include @@ -31,9 +37,11 @@ public: CGMixtureFactor() = default; - CGMixtureFactor(const KeyVector &continuousKeys, const DiscreteKeys &discreteKeys, const Factors &factors) : Base(continuousKeys, discreteKeys) { + CGMixtureFactor(const KeyVector &continuousKeys, + const DiscreteKeys &discreteKeys, + const Factors &factors); - } + bool equals(const HybridFactor &lf, double tol = 1e-9) const override; }; } diff --git a/gtsam/hybrid/CLGaussianConditional.cpp b/gtsam/hybrid/CLGaussianConditional.cpp new file mode 100644 index 000000000..09babc4e2 --- /dev/null +++ b/gtsam/hybrid/CLGaussianConditional.cpp @@ -0,0 +1,20 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file CLGaussianConditional.cpp + * @brief A hybrid conditional in the Conditional Linear Gaussian scheme + * @author Fan Jiang + * @date Mar 12, 2022 + */ + +#include + diff --git a/gtsam/hybrid/CLGaussianConditional.h b/gtsam/hybrid/CLGaussianConditional.h new file mode 100644 index 000000000..03a2d99e7 --- /dev/null +++ b/gtsam/hybrid/CLGaussianConditional.h @@ -0,0 +1,31 @@ +/* ---------------------------------------------------------------------------- + + * 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 CLGaussianConditional.h + * @brief A hybrid conditional in the Conditional Linear Gaussian scheme + * @author Fan Jiang + * @date Mar 12, 2022 + */ + +#include +#include + +namespace gtsam { +class CLGaussianConditional : public HybridFactor, public Conditional { +public: + using This = CLGaussianConditional; + using shared_ptr = boost::shared_ptr; + using BaseFactor = HybridFactor; + + +}; +} \ No newline at end of file diff --git a/gtsam/hybrid/HybridConditional.h b/gtsam/hybrid/HybridConditional.h index e9aa5f616..26083e13e 100644 --- a/gtsam/hybrid/HybridConditional.h +++ b/gtsam/hybrid/HybridConditional.h @@ -34,7 +34,7 @@ namespace gtsam { * * As a type-erased variant of: * - DiscreteConditional - * - GaussianMixture + * - CLGaussianConditional * - GaussianConditional */ class GTSAM_EXPORT HybridConditional diff --git a/gtsam/hybrid/HybridFactorGraph.cpp b/gtsam/hybrid/HybridFactorGraph.cpp index 080efc0e9..cd5bc651d 100644 --- a/gtsam/hybrid/HybridFactorGraph.cpp +++ b/gtsam/hybrid/HybridFactorGraph.cpp @@ -32,20 +32,24 @@ EliminateHybrid(const HybridFactorGraph &factors, // In the case of multifrontal, we will need to use a constrained ordering // so that the discrete parts will be guaranteed to be eliminated last! - // PRODUCT: multiply all factors - gttic(product); + // PREPROCESS: Identify the nature of the current elimination KeySet allKeys; // TODO: we do a mock by just doing the correct key thing - std::cout << "Begin Eliminate\n"; + std::cout << "Begin Eliminate: "; + frontalKeys.print(); + for (auto &&factor : factors) { - std::cout << ">>> Eliminating: "; - factor->printKeys(); + std::cout << ">>> Adding factor: "; + factor->print(); allKeys.insert(factor->begin(), factor->end()); } for (auto &k : frontalKeys) { allKeys.erase(k); } + // PRODUCT: multiply all factors + gttic(product); + HybridConditional sum(allKeys.size(), Ordering(allKeys)); // HybridDiscreteFactor product(DiscreteConditional()); // for (auto&& factor : factors) product = (*factor) * product; diff --git a/gtsam/hybrid/HybridGaussianFactor.h b/gtsam/hybrid/HybridGaussianFactor.h index d8a97ba30..34a7c0004 100644 --- a/gtsam/hybrid/HybridGaussianFactor.h +++ b/gtsam/hybrid/HybridGaussianFactor.h @@ -29,11 +29,11 @@ class HybridGaussianFactor : public HybridFactor { GaussianFactor::shared_ptr inner; - // Implicit conversion from a shared ptr of GF - HybridGaussianFactor(GaussianFactor::shared_ptr other); + // Explicit conversion from a shared ptr of GF + explicit HybridGaussianFactor(GaussianFactor::shared_ptr other); // Forwarding constructor from concrete JacobianFactor - HybridGaussianFactor(JacobianFactor &&jf); + explicit HybridGaussianFactor(JacobianFactor &&jf); public: virtual bool equals(const HybridFactor& lf, double tol) const override; diff --git a/gtsam/hybrid/tests/testHybridConditional.cpp b/gtsam/hybrid/tests/testHybridConditional.cpp index d5a21f34d..46ec40475 100644 --- a/gtsam/hybrid/tests/testHybridConditional.cpp +++ b/gtsam/hybrid/tests/testHybridConditional.cpp @@ -20,6 +20,7 @@ #include #include #include +#include #include #include @@ -37,16 +38,15 @@ using namespace std; using namespace gtsam; using gtsam::symbol_shorthand::X; +using gtsam::symbol_shorthand::C; /* ************************************************************************* */ -TEST_UNSAFE(HybridFactorGraph, test) { +TEST_UNSAFE(HybridFactorGraph, creation) { HybridConditional test; - GTSAM_PRINT(test); HybridFactorGraph hfg; hfg.add(HybridGaussianFactor(JacobianFactor(0, I_3x3, Z_3x1))); - GTSAM_PRINT(hfg); } TEST_UNSAFE(HybridFactorGraph, eliminate) { @@ -56,7 +56,7 @@ TEST_UNSAFE(HybridFactorGraph, eliminate) { auto result = hfg.eliminatePartialSequential({0}); - GTSAM_PRINT(*result.first); + EXPECT_LONGS_EQUAL(result.first->size(), 1); } TEST(HybridFactorGraph, eliminateMultifrontal) { @@ -69,21 +69,30 @@ TEST(HybridFactorGraph, eliminateMultifrontal) { auto result = hfg.eliminatePartialMultifrontal({X(0)}); - GTSAM_PRINT(*result.first); - GTSAM_PRINT(*result.second); + EXPECT_LONGS_EQUAL(result.first->size(), 1); + EXPECT_LONGS_EQUAL(result.second->size(), 1); } TEST(HybridFactorGraph, eliminateFullMultifrontal) { + + std::cout << ">>>>>>>>>>>>>>\n"; + HybridFactorGraph hfg; - DiscreteKey x(X(1), 2); + DiscreteKey x(C(1), 2); hfg.add(JacobianFactor(X(0), I_3x3, Z_3x1)); + hfg.add(JacobianFactor(X(0), I_3x3, X(1), -I_3x3, Z_3x1)); + + DecisionTree dt; + + hfg.add(CGMixtureFactor({X(1)}, { x }, dt)); hfg.add(HybridDiscreteFactor(DecisionTreeFactor(x, {2, 8}))); - auto result = hfg.eliminateMultifrontal(); + auto result = hfg.eliminateMultifrontal(Ordering::ColamdConstrainedLast(hfg, {C(1)})); GTSAM_PRINT(*result); + GTSAM_PRINT(*result->marginalFactor(C(1))); } /* ************************************************************************* */ From ee4f9d19f0ff7486076b647327d0c7c3d1274c6a Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Sun, 13 Mar 2022 11:42:36 -0400 Subject: [PATCH 0185/1686] Added mixture factor functionality --- gtsam/hybrid/CGMixtureFactor.cpp | 17 ++++++++++ gtsam/hybrid/CGMixtureFactor.h | 3 ++ gtsam/hybrid/CLGaussianConditional.cpp | 31 +++++++++++++++++ gtsam/hybrid/CLGaussianConditional.h | 17 ++++++++++ gtsam/hybrid/HybridDiscreteFactor.cpp | 5 +++ gtsam/hybrid/HybridDiscreteFactor.h | 2 ++ gtsam/hybrid/HybridFactor.cpp | 35 ++++++++++++++++++++ gtsam/hybrid/HybridFactor.h | 25 +++++--------- gtsam/hybrid/HybridFactorGraph.cpp | 15 +++++---- gtsam/hybrid/HybridGaussianFactor.cpp | 4 +++ gtsam/hybrid/HybridGaussianFactor.h | 2 ++ gtsam/hybrid/tests/testHybridConditional.cpp | 21 ++++++++++-- 12 files changed, 151 insertions(+), 26 deletions(-) diff --git a/gtsam/hybrid/CGMixtureFactor.cpp b/gtsam/hybrid/CGMixtureFactor.cpp index 2ddf80ec2..16ead783e 100644 --- a/gtsam/hybrid/CGMixtureFactor.cpp +++ b/gtsam/hybrid/CGMixtureFactor.cpp @@ -4,6 +4,9 @@ #include +#include +#include + namespace gtsam { CGMixtureFactor::CGMixtureFactor(const KeyVector &continuousKeys, @@ -14,4 +17,18 @@ bool CGMixtureFactor::equals(const HybridFactor &lf, double tol) const { return false; } +void CGMixtureFactor::print(const std::string &s, const KeyFormatter &formatter) const { + HybridFactor::print(s, formatter); + factors_.print( + "mixture = ", + [&](Key k) { + return formatter(k); + }, [&](const GaussianFactor::shared_ptr &gf) -> std::string { + RedirectCout rd; + if (!gf->empty()) gf->print("", formatter); + else return {"nullptr"}; + return rd.str(); + }); +} + } \ No newline at end of file diff --git a/gtsam/hybrid/CGMixtureFactor.h b/gtsam/hybrid/CGMixtureFactor.h index 9c9e43ec2..7ff53b7ed 100644 --- a/gtsam/hybrid/CGMixtureFactor.h +++ b/gtsam/hybrid/CGMixtureFactor.h @@ -42,6 +42,9 @@ public: const Factors &factors); bool equals(const HybridFactor &lf, double tol = 1e-9) const override; + + void print(const std::string &s = "HybridFactor\n", + const KeyFormatter &formatter = DefaultKeyFormatter) const override; }; } diff --git a/gtsam/hybrid/CLGaussianConditional.cpp b/gtsam/hybrid/CLGaussianConditional.cpp index 09babc4e2..dbc9631c8 100644 --- a/gtsam/hybrid/CLGaussianConditional.cpp +++ b/gtsam/hybrid/CLGaussianConditional.cpp @@ -18,3 +18,34 @@ #include +#include + +namespace gtsam { + +CLGaussianConditional::CLGaussianConditional(const KeyVector &continuousFrontals, + const KeyVector &continuousParents, + const DiscreteKeys &discreteParents, + const CLGaussianConditional::Conditionals &factors) + : BaseFactor( + CollectKeys(continuousFrontals, continuousParents), discreteParents), + BaseConditional(continuousFrontals.size()) { + +} + +bool CLGaussianConditional::equals(const HybridFactor &lf, double tol) const { + return false; +} + +void CLGaussianConditional::print(const std::string &s, const KeyFormatter &formatter) const { + std::cout << s << ": "; + if (isContinuous_) std::cout << "Cont. "; + if (isDiscrete_) std::cout << "Disc. "; + if (isHybrid_) std::cout << "Hybr. "; + BaseConditional::print("", formatter); + std::cout << "Discrete Keys = "; + for (auto &dk : discreteKeys_) { + std::cout << "(" << formatter(dk.first) << ", " << dk.second << "), "; + } + std::cout << "\n"; +} +} \ No newline at end of file diff --git a/gtsam/hybrid/CLGaussianConditional.h b/gtsam/hybrid/CLGaussianConditional.h index 03a2d99e7..14989df72 100644 --- a/gtsam/hybrid/CLGaussianConditional.h +++ b/gtsam/hybrid/CLGaussianConditional.h @@ -19,13 +19,30 @@ #include #include +#include +#include + namespace gtsam { class CLGaussianConditional : public HybridFactor, public Conditional { public: using This = CLGaussianConditional; using shared_ptr = boost::shared_ptr; using BaseFactor = HybridFactor; + using BaseConditional = Conditional; + using Conditionals = DecisionTree; +public: + + CLGaussianConditional(const KeyVector &continuousFrontals, + const KeyVector &continuousParents, + const DiscreteKeys &discreteParents, + const Conditionals &factors); + + bool equals(const HybridFactor &lf, double tol = 1e-9) const override; + + void print( + const std::string &s = "CLGaussianConditional\n", + const KeyFormatter &formatter = DefaultKeyFormatter) const override; }; } \ No newline at end of file diff --git a/gtsam/hybrid/HybridDiscreteFactor.cpp b/gtsam/hybrid/HybridDiscreteFactor.cpp index 13766933b..1758e9025 100644 --- a/gtsam/hybrid/HybridDiscreteFactor.cpp +++ b/gtsam/hybrid/HybridDiscreteFactor.cpp @@ -21,6 +21,11 @@ HybridDiscreteFactor::HybridDiscreteFactor(DecisionTreeFactor &&dtf) bool HybridDiscreteFactor::equals(const HybridFactor &lf, double tol) const { return false; +} + +void HybridDiscreteFactor::print(const std::string &s, const KeyFormatter &formatter) const { + HybridFactor::print(s, formatter); + inner->print("inner: ", formatter); }; } \ No newline at end of file diff --git a/gtsam/hybrid/HybridDiscreteFactor.h b/gtsam/hybrid/HybridDiscreteFactor.h index 0395c9512..9d574b736 100644 --- a/gtsam/hybrid/HybridDiscreteFactor.h +++ b/gtsam/hybrid/HybridDiscreteFactor.h @@ -37,5 +37,7 @@ class HybridDiscreteFactor : public HybridFactor { public: virtual bool equals(const HybridFactor& lf, double tol) const override; + + void print(const std::string &s = "HybridFactor\n", const KeyFormatter &formatter = DefaultKeyFormatter) const override; }; } diff --git a/gtsam/hybrid/HybridFactor.cpp b/gtsam/hybrid/HybridFactor.cpp index 907350e83..3095136a4 100644 --- a/gtsam/hybrid/HybridFactor.cpp +++ b/gtsam/hybrid/HybridFactor.cpp @@ -16,3 +16,38 @@ */ #include + +namespace gtsam { + +KeyVector CollectKeys(const KeyVector &continuousKeys, const DiscreteKeys &discreteKeys) { + KeyVector allKeys; + std::copy(continuousKeys.begin(), continuousKeys.end(), std::back_inserter(allKeys)); + std::transform(discreteKeys.begin(), + discreteKeys.end(), + std::back_inserter(allKeys), + [](const DiscreteKey &k) { return k.first; }); + return allKeys; +} + +KeyVector CollectKeys(const KeyVector &keys1, const KeyVector &keys2) { + KeyVector allKeys; + std::copy(keys1.begin(), keys1.end(), std::back_inserter(allKeys)); + std::copy(keys2.begin(), keys2.end(), std::back_inserter(allKeys)); + return allKeys; +} + +HybridFactor::HybridFactor() = default; + +HybridFactor::HybridFactor(const KeyVector &keys) : Base(keys), isContinuous_(true) {} + +HybridFactor::HybridFactor(const KeyVector &continuousKeys, const DiscreteKeys &discreteKeys) + : Base( + CollectKeys(continuousKeys, discreteKeys)), isHybrid_(true), discreteKeys_(discreteKeys) {} + +HybridFactor::HybridFactor(const DiscreteKeys &discreteKeys) : Base(CollectKeys({}, discreteKeys)), + isDiscrete_(true), + discreteKeys_(discreteKeys) {} + +HybridFactor::~HybridFactor() = default; + +} \ No newline at end of file diff --git a/gtsam/hybrid/HybridFactor.h b/gtsam/hybrid/HybridFactor.h index 64b49f605..619d16078 100644 --- a/gtsam/hybrid/HybridFactor.h +++ b/gtsam/hybrid/HybridFactor.h @@ -25,6 +25,9 @@ #include namespace gtsam { +KeyVector CollectKeys(const KeyVector &continuousKeys, const DiscreteKeys &discreteKeys); +KeyVector CollectKeys(const KeyVector &keys1, const KeyVector &keys2); + /** * Base class for hybrid probabilistic factors */ @@ -49,33 +52,21 @@ public: /// @{ /** Default constructor creates empty factor */ - HybridFactor() {} + HybridFactor(); /** Construct from container of keys. This constructor is used internally from derived factor * constructors, either from a container of keys or from a boost::assign::list_of. */ // template // HybridFactor(const CONTAINER &keys) : Base(keys) {} - HybridFactor(const KeyVector &keys) : Base(keys), isContinuous_(true) {} + explicit HybridFactor(const KeyVector &keys); - static KeyVector CollectKeys(const KeyVector &continuousKeys, const DiscreteKeys &discreteKeys) { - KeyVector allKeys; - std::copy(continuousKeys.begin(), continuousKeys.end(), std::back_inserter(allKeys)); - std::transform(discreteKeys.begin(), - discreteKeys.end(), - std::back_inserter(allKeys), - [](const DiscreteKey &k) { return k.first; }); - return allKeys; - } + HybridFactor(const KeyVector &continuousKeys, const DiscreteKeys &discreteKeys); - HybridFactor(const KeyVector &continuousKeys, const DiscreteKeys &discreteKeys) : Base( - CollectKeys(continuousKeys, discreteKeys)), isHybrid_(true) {} - - HybridFactor(const DiscreteKeys &discreteKeys) : Base(CollectKeys({}, discreteKeys)), isDiscrete_(true) {} + explicit HybridFactor(const DiscreteKeys &discreteKeys); /// Virtual destructor - virtual ~HybridFactor() { - } + virtual ~HybridFactor(); /// @} /// @name Testable diff --git a/gtsam/hybrid/HybridFactorGraph.cpp b/gtsam/hybrid/HybridFactorGraph.cpp index cd5bc651d..2dc54d75d 100644 --- a/gtsam/hybrid/HybridFactorGraph.cpp +++ b/gtsam/hybrid/HybridFactorGraph.cpp @@ -34,6 +34,7 @@ EliminateHybrid(const HybridFactorGraph &factors, // PREPROCESS: Identify the nature of the current elimination KeySet allKeys; + // TODO: we do a mock by just doing the correct key thing std::cout << "Begin Eliminate: "; frontalKeys.print(); @@ -43,6 +44,7 @@ EliminateHybrid(const HybridFactorGraph &factors, factor->print(); allKeys.insert(factor->begin(), factor->end()); } + for (auto &k : frontalKeys) { allKeys.erase(k); } @@ -51,13 +53,14 @@ EliminateHybrid(const HybridFactorGraph &factors, gttic(product); HybridConditional sum(allKeys.size(), Ordering(allKeys)); -// HybridDiscreteFactor product(DiscreteConditional()); -// for (auto&& factor : factors) product = (*factor) * product; + + // HybridDiscreteFactor product(DiscreteConditional()); + // for (auto&& factor : factors) product = (*factor) * product; gttoc(product); // sum out frontals, this is the factor on the separator gttic(sum); -// HybridFactor::shared_ptr sum = product.sum(frontalKeys); + // HybridFactor::shared_ptr sum = product.sum(frontalKeys); gttoc(sum); // Ordering keys for the conditional so that frontalKeys are really in front @@ -69,11 +72,11 @@ EliminateHybrid(const HybridFactorGraph &factors, // now divide product/sum to get conditional gttic(divide); -// auto conditional = -// boost::make_shared(product, *sum, orderedKeys); + // auto conditional = + // boost::make_shared(product, *sum, orderedKeys); gttoc(divide); -// return std::make_pair(conditional, sum); + // return std::make_pair(conditional, sum); return std::make_pair(boost::make_shared(frontalKeys.size(), orderedKeys), boost::make_shared(std::move(sum))); diff --git a/gtsam/hybrid/HybridGaussianFactor.cpp b/gtsam/hybrid/HybridGaussianFactor.cpp index 1e87cbbc3..faa4ba998 100644 --- a/gtsam/hybrid/HybridGaussianFactor.cpp +++ b/gtsam/hybrid/HybridGaussianFactor.cpp @@ -18,6 +18,10 @@ HybridGaussianFactor::HybridGaussianFactor(JacobianFactor &&jf) : Base(jf.keys() bool HybridGaussianFactor::equals(const HybridFactor& lf, double tol) const { return false; +} +void HybridGaussianFactor::print(const std::string &s, const KeyFormatter &formatter) const { + HybridFactor::print(s, formatter); + inner->print("inner: ", formatter); }; } \ No newline at end of file diff --git a/gtsam/hybrid/HybridGaussianFactor.h b/gtsam/hybrid/HybridGaussianFactor.h index 34a7c0004..8562075b4 100644 --- a/gtsam/hybrid/HybridGaussianFactor.h +++ b/gtsam/hybrid/HybridGaussianFactor.h @@ -37,5 +37,7 @@ class HybridGaussianFactor : public HybridFactor { public: virtual bool equals(const HybridFactor& lf, double tol) const override; + + void print(const std::string &s = "HybridFactor\n", const KeyFormatter &formatter = DefaultKeyFormatter) const override; }; } diff --git a/gtsam/hybrid/tests/testHybridConditional.cpp b/gtsam/hybrid/tests/testHybridConditional.cpp index 46ec40475..4611026b3 100644 --- a/gtsam/hybrid/tests/testHybridConditional.cpp +++ b/gtsam/hybrid/tests/testHybridConditional.cpp @@ -20,6 +20,7 @@ #include #include #include +#include #include #include #include @@ -47,6 +48,13 @@ TEST_UNSAFE(HybridFactorGraph, creation) { HybridFactorGraph hfg; hfg.add(HybridGaussianFactor(JacobianFactor(0, I_3x3, Z_3x1))); + + CLGaussianConditional clgc( + {X(0)}, {X(1)}, + DiscreteKeys(DiscreteKey{C(0), 2}), + CLGaussianConditional::Conditionals() + ); + GTSAM_PRINT(clgc); } TEST_UNSAFE(HybridFactorGraph, eliminate) { @@ -84,12 +92,19 @@ TEST(HybridFactorGraph, eliminateFullMultifrontal) { hfg.add(JacobianFactor(X(0), I_3x3, Z_3x1)); hfg.add(JacobianFactor(X(0), I_3x3, X(1), -I_3x3, Z_3x1)); - DecisionTree dt; + DecisionTree dt(C(1), + boost::make_shared(X(1), + I_3x3, + Z_3x1), + boost::make_shared(X(1), + I_3x3, + Vector3::Ones())); - hfg.add(CGMixtureFactor({X(1)}, { x }, dt)); + hfg.add(CGMixtureFactor({X(1)}, {x}, dt)); hfg.add(HybridDiscreteFactor(DecisionTreeFactor(x, {2, 8}))); + hfg.add(HybridDiscreteFactor(DecisionTreeFactor({{C(1), 2}, {C(2), 2}}, "1 2 3 4"))); - auto result = hfg.eliminateMultifrontal(Ordering::ColamdConstrainedLast(hfg, {C(1)})); + auto result = hfg.eliminateMultifrontal(Ordering::ColamdConstrainedLast(hfg, {C(1), C(2)})); GTSAM_PRINT(*result); GTSAM_PRINT(*result->marginalFactor(C(1))); From 5ea614a82a0528a78758d5d6782cfbb948a43179 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Sun, 13 Mar 2022 20:09:53 -0400 Subject: [PATCH 0186/1686] Added more mockups and color output of the elimination process --- gtsam/hybrid/CLGaussianConditional.cpp | 17 +++- gtsam/hybrid/CLGaussianConditional.h | 4 +- gtsam/hybrid/HybridConditional.h | 71 ++++++++------- gtsam/hybrid/HybridFactor.cpp | 7 ++ gtsam/hybrid/HybridFactor.h | 1 + gtsam/hybrid/HybridFactorGraph.cpp | 93 ++++++++++++++++---- gtsam/hybrid/tests/testHybridConditional.cpp | 15 +++- 7 files changed, 151 insertions(+), 57 deletions(-) diff --git a/gtsam/hybrid/CLGaussianConditional.cpp b/gtsam/hybrid/CLGaussianConditional.cpp index dbc9631c8..37c82a0d5 100644 --- a/gtsam/hybrid/CLGaussianConditional.cpp +++ b/gtsam/hybrid/CLGaussianConditional.cpp @@ -18,17 +18,20 @@ #include +#include + #include +#include namespace gtsam { CLGaussianConditional::CLGaussianConditional(const KeyVector &continuousFrontals, const KeyVector &continuousParents, const DiscreteKeys &discreteParents, - const CLGaussianConditional::Conditionals &factors) + const CLGaussianConditional::Conditionals &conditionals) : BaseFactor( CollectKeys(continuousFrontals, continuousParents), discreteParents), - BaseConditional(continuousFrontals.size()) { + BaseConditional(continuousFrontals.size()), conditionals_(conditionals) { } @@ -47,5 +50,15 @@ void CLGaussianConditional::print(const std::string &s, const KeyFormatter &form std::cout << "(" << formatter(dk.first) << ", " << dk.second << "), "; } std::cout << "\n"; + conditionals_.print( + "", + [&](Key k) { + return formatter(k); + }, [&](const GaussianConditional::shared_ptr &gf) -> std::string { + RedirectCout rd; + if (!gf->empty()) gf->print("", formatter); + else return {"nullptr"}; + return rd.str(); + }); } } \ No newline at end of file diff --git a/gtsam/hybrid/CLGaussianConditional.h b/gtsam/hybrid/CLGaussianConditional.h index 14989df72..0319c60a7 100644 --- a/gtsam/hybrid/CLGaussianConditional.h +++ b/gtsam/hybrid/CLGaussianConditional.h @@ -32,12 +32,14 @@ public: using Conditionals = DecisionTree; + Conditionals conditionals_; + public: CLGaussianConditional(const KeyVector &continuousFrontals, const KeyVector &continuousParents, const DiscreteKeys &discreteParents, - const Conditionals &factors); + const Conditionals &conditionals); bool equals(const HybridFactor &lf, double tol = 1e-9) const override; diff --git a/gtsam/hybrid/HybridConditional.h b/gtsam/hybrid/HybridConditional.h index 26083e13e..92856cae2 100644 --- a/gtsam/hybrid/HybridConditional.h +++ b/gtsam/hybrid/HybridConditional.h @@ -41,56 +41,59 @@ class GTSAM_EXPORT HybridConditional : public HybridFactor, public Conditional { public: -// typedefs needed to play nice with gtsam -typedef HybridConditional This; ///< Typedef to this class -typedef boost::shared_ptr shared_ptr; ///< shared_ptr to this class -typedef HybridFactor BaseFactor; ///< Typedef to our factor base class -typedef Conditional - BaseConditional; ///< Typedef to our conditional base class + // typedefs needed to play nice with gtsam + typedef HybridConditional This; ///< Typedef to this class + typedef boost::shared_ptr shared_ptr; ///< shared_ptr to this class + typedef HybridFactor BaseFactor; ///< Typedef to our factor base class + typedef Conditional + BaseConditional; ///< Typedef to our conditional base class private: -// Type-erased pointer to the inner type -std::unique_ptr inner; + // Type-erased pointer to the inner type + std::unique_ptr inner; public: /// @name Standard Constructors /// @{ -/// Default constructor needed for serialization. -HybridConditional() = default; + /// Default constructor needed for serialization. + HybridConditional() = default; -HybridConditional(size_t nFrontals, const KeyVector& keys) : BaseFactor(keys), BaseConditional(nFrontals) { + HybridConditional(const KeyVector &continuousKeys, + const DiscreteKeys &discreteKeys, + size_t nFrontals) + : BaseFactor(continuousKeys, discreteKeys), BaseConditional(nFrontals) { -} + } -/** - * @brief Combine two conditionals, yielding a new conditional with the union - * of the frontal keys, ordered by gtsam::Key. - * - * The two conditionals must make a valid Bayes net fragment, i.e., - * the frontal variables cannot overlap, and must be acyclic: - * Example of correct use: - * P(A,B) = P(A|B) * P(B) - * P(A,B|C) = P(A|B) * P(B|C) - * P(A,B,C) = P(A,B|C) * P(C) - * Example of incorrect use: - * P(A|B) * P(A|C) = ? - * P(A|B) * P(B|A) = ? - * We check for overlapping frontals, but do *not* check for cyclic. - */ -HybridConditional operator*(const HybridConditional& other) const; + /** + * @brief Combine two conditionals, yielding a new conditional with the union + * of the frontal keys, ordered by gtsam::Key. + * + * The two conditionals must make a valid Bayes net fragment, i.e., + * the frontal variables cannot overlap, and must be acyclic: + * Example of correct use: + * P(A,B) = P(A|B) * P(B) + * P(A,B|C) = P(A|B) * P(B|C) + * P(A,B,C) = P(A,B|C) * P(C) + * Example of incorrect use: + * P(A|B) * P(A|C) = ? + * P(A|B) * P(B|A) = ? + * We check for overlapping frontals, but do *not* check for cyclic. + */ + HybridConditional operator*(const HybridConditional& other) const; /// @} /// @name Testable /// @{ -/// GTSAM-style print -void print( - const std::string& s = "Hybrid Conditional: ", - const KeyFormatter& formatter = DefaultKeyFormatter) const override; + /// GTSAM-style print + void print( + const std::string& s = "Hybrid Conditional: ", + const KeyFormatter& formatter = DefaultKeyFormatter) const override; -/// GTSAM-style equals -bool equals(const HybridFactor& other, double tol = 1e-9) const override; + /// GTSAM-style equals + bool equals(const HybridFactor& other, double tol = 1e-9) const override; /// @} }; diff --git a/gtsam/hybrid/HybridFactor.cpp b/gtsam/hybrid/HybridFactor.cpp index 3095136a4..171ea790a 100644 --- a/gtsam/hybrid/HybridFactor.cpp +++ b/gtsam/hybrid/HybridFactor.cpp @@ -36,6 +36,13 @@ KeyVector CollectKeys(const KeyVector &keys1, const KeyVector &keys2) { return allKeys; } +DiscreteKeys CollectDiscreteKeys(const DiscreteKeys &key1, const DiscreteKeys &key2) { + DiscreteKeys allKeys; + std::copy(key1.begin(), key1.end(), std::back_inserter(allKeys)); + std::copy(key2.begin(), key2.end(), std::back_inserter(allKeys)); + return allKeys; +} + HybridFactor::HybridFactor() = default; HybridFactor::HybridFactor(const KeyVector &keys) : Base(keys), isContinuous_(true) {} diff --git a/gtsam/hybrid/HybridFactor.h b/gtsam/hybrid/HybridFactor.h index 619d16078..dd925fee2 100644 --- a/gtsam/hybrid/HybridFactor.h +++ b/gtsam/hybrid/HybridFactor.h @@ -27,6 +27,7 @@ namespace gtsam { KeyVector CollectKeys(const KeyVector &continuousKeys, const DiscreteKeys &discreteKeys); KeyVector CollectKeys(const KeyVector &keys1, const KeyVector &keys2); +DiscreteKeys CollectDiscreteKeys(const DiscreteKeys &key1, const DiscreteKeys &key2); /** * Base class for hybrid probabilistic factors diff --git a/gtsam/hybrid/HybridFactorGraph.cpp b/gtsam/hybrid/HybridFactorGraph.cpp index 2dc54d75d..177513f60 100644 --- a/gtsam/hybrid/HybridFactorGraph.cpp +++ b/gtsam/hybrid/HybridFactorGraph.cpp @@ -5,17 +5,26 @@ #include #include #include +#include #include #include #include +#include + namespace gtsam { template class EliminateableFactorGraph; +static std::string BLACK_BOLD = "\033[1;30m"; +static std::string RED_BOLD = "\033[1;31m"; +static std::string GREEN = "\033[0;32m"; +static std::string GREEN_BOLD = "\033[1;32m"; +static std::string RESET = "\033[0m"; + /* ************************************************************************ */ std::pair // EliminateHybrid(const HybridFactorGraph &factors, @@ -33,26 +42,66 @@ EliminateHybrid(const HybridFactorGraph &factors, // so that the discrete parts will be guaranteed to be eliminated last! // PREPROCESS: Identify the nature of the current elimination - KeySet allKeys; + std::unordered_map discreteCardinalities; + std::set discreteSeparator; + std::set discreteFrontals; + + KeySet separatorKeys; + KeySet allContinuousKeys; + KeySet continuousFrontals; + KeySet continuousSeparator; // TODO: we do a mock by just doing the correct key thing - std::cout << "Begin Eliminate: "; + + // This initializes separatorKeys and discreteCardinalities + for (auto &&factor : factors) { + std::cout << ">>> Adding factor: " << GREEN; + factor->print(); + std::cout << RESET; + separatorKeys.insert(factor->begin(), factor->end()); + if (!factor->isContinuous_) { + for (auto &k : factor->discreteKeys_) { + discreteCardinalities[k.first] = k; + } + } + } + + // remove frontals from separator + for (auto &k : frontalKeys) { + separatorKeys.erase(k); + } + + // Fill in discrete frontals and continuous frontals for the end result + for (auto &k : frontalKeys) { + if (discreteCardinalities.find(k) != discreteCardinalities.end()) { + discreteFrontals.insert(discreteCardinalities.at(k)); + } else { + continuousFrontals.insert(k); + } + } + + // Fill in discrete frontals and continuous frontals for the end result + for (auto &k : separatorKeys) { + if (discreteCardinalities.find(k) != discreteCardinalities.end()) { + discreteSeparator.insert(discreteCardinalities.at(k)); + } else { + continuousSeparator.insert(k); + } + } + + std::cout << RED_BOLD << "Begin Eliminate: " << RESET; frontalKeys.print(); - for (auto &&factor : factors) { - std::cout << ">>> Adding factor: "; - factor->print(); - allKeys.insert(factor->begin(), factor->end()); - } - - for (auto &k : frontalKeys) { - allKeys.erase(k); - } - + std::cout << RED_BOLD << "Discrete Keys: " << RESET; + for (auto &&key : discreteCardinalities) + std::cout << boost::format(" (%1%,%2%),") % DefaultKeyFormatter(key.second.first) % key.second.second; + std::cout << "\n" << RESET; // PRODUCT: multiply all factors gttic(product); - HybridConditional sum(allKeys.size(), Ordering(allKeys)); + HybridConditional sum(KeyVector(continuousSeparator.begin(), continuousSeparator.end()), + DiscreteKeys(discreteSeparator.begin(), discreteSeparator.end()), + separatorKeys.size()); // HybridDiscreteFactor product(DiscreteConditional()); // for (auto&& factor : factors) product = (*factor) * product; @@ -76,10 +125,22 @@ EliminateHybrid(const HybridFactorGraph &factors, // boost::make_shared(product, *sum, orderedKeys); gttoc(divide); + auto conditional = boost::make_shared( + CollectKeys({continuousFrontals.begin(), continuousFrontals.end()}, + {continuousSeparator.begin(), continuousSeparator.end()}), + CollectDiscreteKeys({discreteFrontals.begin(), discreteFrontals.end()}, + {discreteSeparator.begin(), discreteSeparator.end()}), + continuousFrontals.size() + discreteFrontals.size()); + std::cout << GREEN_BOLD << "[Conditional]\n" << RESET; + conditional->print(); + std::cout << GREEN_BOLD << "[Separator]\n" << RESET; + sum.print(); + std::cout << RED_BOLD << "[End Eliminate]\n" << RESET; + // return std::make_pair(conditional, sum); - return std::make_pair(boost::make_shared(frontalKeys.size(), - orderedKeys), - boost::make_shared(std::move(sum))); + return std::make_pair( + conditional, + boost::make_shared(std::move(sum))); } void HybridFactorGraph::add(JacobianFactor &&factor) { diff --git a/gtsam/hybrid/tests/testHybridConditional.cpp b/gtsam/hybrid/tests/testHybridConditional.cpp index 4611026b3..7292cb3f5 100644 --- a/gtsam/hybrid/tests/testHybridConditional.cpp +++ b/gtsam/hybrid/tests/testHybridConditional.cpp @@ -42,7 +42,7 @@ using gtsam::symbol_shorthand::X; using gtsam::symbol_shorthand::C; /* ************************************************************************* */ -TEST_UNSAFE(HybridFactorGraph, creation) { +TEST(HybridFactorGraph, creation) { HybridConditional test; HybridFactorGraph hfg; @@ -52,12 +52,19 @@ TEST_UNSAFE(HybridFactorGraph, creation) { CLGaussianConditional clgc( {X(0)}, {X(1)}, DiscreteKeys(DiscreteKey{C(0), 2}), - CLGaussianConditional::Conditionals() + CLGaussianConditional::Conditionals( + C(0), + boost::make_shared( + X(0), Z_3x1, I_3x3, X(1), I_3x3), + boost::make_shared( + X(0), Vector3::Ones(), + I_3x3, X(1), + I_3x3)) ); GTSAM_PRINT(clgc); } -TEST_UNSAFE(HybridFactorGraph, eliminate) { +TEST_DISABLED(HybridFactorGraph, eliminate) { HybridFactorGraph hfg; hfg.add(HybridGaussianFactor(JacobianFactor(0, I_3x3, Z_3x1))); @@ -67,7 +74,7 @@ TEST_UNSAFE(HybridFactorGraph, eliminate) { EXPECT_LONGS_EQUAL(result.first->size(), 1); } -TEST(HybridFactorGraph, eliminateMultifrontal) { +TEST_DISABLED(HybridFactorGraph, eliminateMultifrontal) { HybridFactorGraph hfg; DiscreteKey x(X(1), 2); From 0aeb59695e542bc1513ba63f900afd601dd86525 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Sun, 13 Mar 2022 23:15:20 -0400 Subject: [PATCH 0187/1686] add more comments --- gtsam/hybrid/HybridConditional.cpp | 21 +++++++++++-- gtsam/hybrid/HybridFactorGraph.cpp | 7 ++++- gtsam/hybrid/tests/testHybridConditional.cpp | 31 +++++++++++++++++++- 3 files changed, 55 insertions(+), 4 deletions(-) diff --git a/gtsam/hybrid/HybridConditional.cpp b/gtsam/hybrid/HybridConditional.cpp index e6b2eb47f..b3009d5b9 100644 --- a/gtsam/hybrid/HybridConditional.cpp +++ b/gtsam/hybrid/HybridConditional.cpp @@ -7,8 +7,25 @@ namespace gtsam { void HybridConditional::print(const std::string &s, - const KeyFormatter &formatter) const { - Conditional::print(s, formatter); + const KeyFormatter &formatter) const { + std::cout << s << "P("; + int index = 0; + const size_t N = keys().size(); + const size_t contN = N - discreteKeys_.size(); + while (index < N) { + if (index > 0) { + if (index == nrFrontals_) std::cout << " | "; else std::cout << ", "; + } + if (index < contN) { + std::cout << formatter(keys()[index]); + } else { + auto &dk = discreteKeys_[index - contN]; + std::cout << "(" << formatter(dk.first) << ", " << dk.second << ")"; + } + index++; + } + std::cout << ")\n"; + if (inner) inner->print("", formatter); } bool HybridConditional::equals(const HybridFactor &other, diff --git a/gtsam/hybrid/HybridFactorGraph.cpp b/gtsam/hybrid/HybridFactorGraph.cpp index 177513f60..af4c993df 100644 --- a/gtsam/hybrid/HybridFactorGraph.cpp +++ b/gtsam/hybrid/HybridFactorGraph.cpp @@ -30,11 +30,16 @@ std::pair // EliminateHybrid(const HybridFactorGraph &factors, const Ordering &frontalKeys) { // NOTE(fan): Because we are in the Conditional Gaussian regime there are only - // few cases: continuous variable, we make a GM if there are hybrid factors; + // a few cases: + // continuous variable, we make a GM if there are hybrid factors; // continuous variable, we make a GF if there are no hybrid factors; // discrete variable, no continuous factor is allowed (escapes CG regime), so // we panic, if discrete only we do the discrete elimination. + // However it is not that simple. During elimination it is possible that the multifrontal needs + // to eliminate an ordering that contains both Gaussian and hybrid variables, for example x1, c1. + // In this scenario, we will have a density P(x1, c1) that is a CLG P(x1|c1)P(c1) (see Murphy02) + // The issue here is that, how can we know which variable is discrete if we // unify Values? Obviously we can tell using the factors, but is that fast? diff --git a/gtsam/hybrid/tests/testHybridConditional.cpp b/gtsam/hybrid/tests/testHybridConditional.cpp index 7292cb3f5..f97989506 100644 --- a/gtsam/hybrid/tests/testHybridConditional.cpp +++ b/gtsam/hybrid/tests/testHybridConditional.cpp @@ -88,7 +88,7 @@ TEST_DISABLED(HybridFactorGraph, eliminateMultifrontal) { EXPECT_LONGS_EQUAL(result.second->size(), 1); } -TEST(HybridFactorGraph, eliminateFullMultifrontal) { +TEST_DISABLED(HybridFactorGraph, eliminateFullMultifrontalSimple) { std::cout << ">>>>>>>>>>>>>>\n"; @@ -117,6 +117,35 @@ TEST(HybridFactorGraph, eliminateFullMultifrontal) { GTSAM_PRINT(*result->marginalFactor(C(1))); } +TEST(HybridFactorGraph, eliminateFullMultifrontalCLG) { + + std::cout << ">>>>>>>>>>>>>>\n"; + + HybridFactorGraph hfg; + + DiscreteKey x(C(1), 2); + + hfg.add(JacobianFactor(X(0), I_3x3, Z_3x1)); + hfg.add(JacobianFactor(X(0), I_3x3, X(1), -I_3x3, Z_3x1)); + + DecisionTree dt(C(1), + boost::make_shared(X(1), + I_3x3, + Z_3x1), + boost::make_shared(X(1), + I_3x3, + Vector3::Ones())); + + hfg.add(CGMixtureFactor({X(1)}, {x}, dt)); + hfg.add(HybridDiscreteFactor(DecisionTreeFactor(x, {2, 8}))); +// hfg.add(HybridDiscreteFactor(DecisionTreeFactor({{C(1), 2}, {C(2), 2}}, "1 2 3 4"))); + + auto result = hfg.eliminateMultifrontal(Ordering::ColamdConstrainedLast(hfg, {C(1)})); + + GTSAM_PRINT(*result); + GTSAM_PRINT(*result->marginalFactor(C(1))); +} + /* ************************************************************************* */ int main() { TestResult tr; From bcf49e6243b67d237aa14b9a52728ed674f2453e Mon Sep 17 00:00:00 2001 From: Thomas Sayre-McCord Date: Mon, 14 Mar 2022 09:19:19 +0100 Subject: [PATCH 0188/1686] 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 fe5dde7e27e080f5a9abcf4692bdf16dc3164fce Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Mon, 14 Mar 2022 19:22:20 -0400 Subject: [PATCH 0189/1686] even better printing and comments --- gtsam/hybrid/HybridFactorGraph.cpp | 30 ++++++++++++++++---- gtsam/hybrid/tests/testHybridConditional.cpp | 26 ++++++++++++----- 2 files changed, 44 insertions(+), 12 deletions(-) diff --git a/gtsam/hybrid/HybridFactorGraph.cpp b/gtsam/hybrid/HybridFactorGraph.cpp index af4c993df..03610166e 100644 --- a/gtsam/hybrid/HybridFactorGraph.cpp +++ b/gtsam/hybrid/HybridFactorGraph.cpp @@ -2,6 +2,7 @@ // Created by Fan Jiang on 3/11/22. // +#include "gtsam/inference/Key.h" #include #include #include @@ -12,6 +13,7 @@ #include +#include #include namespace gtsam { @@ -57,6 +59,8 @@ EliminateHybrid(const HybridFactorGraph &factors, KeySet continuousSeparator; // TODO: we do a mock by just doing the correct key thing + std::cout << RED_BOLD << "Begin Eliminate: " << RESET; + frontalKeys.print(); // This initializes separatorKeys and discreteCardinalities for (auto &&factor : factors) { @@ -94,12 +98,28 @@ EliminateHybrid(const HybridFactorGraph &factors, } } - std::cout << RED_BOLD << "Begin Eliminate: " << RESET; - frontalKeys.print(); + std::cout << RED_BOLD << "Keys: " << RESET; + for (auto &f : frontalKeys) { + if (discreteCardinalities.find(f) != discreteCardinalities.end()) { + auto &key = discreteCardinalities.at(f); + std::cout << boost::format(" (%1%,%2%),") % DefaultKeyFormatter(key.first) % key.second; + } else { + std::cout << " " << DefaultKeyFormatter(f) << ","; + } + } - std::cout << RED_BOLD << "Discrete Keys: " << RESET; - for (auto &&key : discreteCardinalities) - std::cout << boost::format(" (%1%,%2%),") % DefaultKeyFormatter(key.second.first) % key.second.second; + if (separatorKeys.size() > 0) { + std::cout << " | "; + } + + for (auto &f : separatorKeys) { + if (discreteCardinalities.find(f) != discreteCardinalities.end()) { + auto &key = discreteCardinalities.at(f); + std::cout << boost::format(" (%1%,%2%),") % DefaultKeyFormatter(key.first) % key.second; + } else { + std::cout << DefaultKeyFormatter(f) << ","; + } + } std::cout << "\n" << RESET; // PRODUCT: multiply all factors gttic(product); diff --git a/gtsam/hybrid/tests/testHybridConditional.cpp b/gtsam/hybrid/tests/testHybridConditional.cpp index f97989506..c682f5216 100644 --- a/gtsam/hybrid/tests/testHybridConditional.cpp +++ b/gtsam/hybrid/tests/testHybridConditional.cpp @@ -15,6 +15,7 @@ * @author Fan Jiang */ +#include "Test.h" #include #include #include @@ -94,7 +95,7 @@ TEST_DISABLED(HybridFactorGraph, eliminateFullMultifrontalSimple) { HybridFactorGraph hfg; - DiscreteKey x(C(1), 2); + DiscreteKey c1(C(1), 2); hfg.add(JacobianFactor(X(0), I_3x3, Z_3x1)); hfg.add(JacobianFactor(X(0), I_3x3, X(1), -I_3x3, Z_3x1)); @@ -107,9 +108,12 @@ TEST_DISABLED(HybridFactorGraph, eliminateFullMultifrontalSimple) { I_3x3, Vector3::Ones())); - hfg.add(CGMixtureFactor({X(1)}, {x}, dt)); - hfg.add(HybridDiscreteFactor(DecisionTreeFactor(x, {2, 8}))); + hfg.add(CGMixtureFactor({X(1)}, {c1}, dt)); + hfg.add(CGMixtureFactor({X(0)}, {c1}, dt)); + hfg.add(HybridDiscreteFactor(DecisionTreeFactor(c1, {2, 8}))); hfg.add(HybridDiscreteFactor(DecisionTreeFactor({{C(1), 2}, {C(2), 2}}, "1 2 3 4"))); + // hfg.add(HybridDiscreteFactor(DecisionTreeFactor({{C(2), 2}, {C(3), 2}}, "1 2 3 4"))); + // hfg.add(HybridDiscreteFactor(DecisionTreeFactor({{C(3), 2}, {C(1), 2}}, "1 2 2 1"))); auto result = hfg.eliminateMultifrontal(Ordering::ColamdConstrainedLast(hfg, {C(1), C(2)})); @@ -123,7 +127,7 @@ TEST(HybridFactorGraph, eliminateFullMultifrontalCLG) { HybridFactorGraph hfg; - DiscreteKey x(C(1), 2); + DiscreteKey c(C(1), 2); hfg.add(JacobianFactor(X(0), I_3x3, Z_3x1)); hfg.add(JacobianFactor(X(0), I_3x3, X(1), -I_3x3, Z_3x1)); @@ -136,14 +140,22 @@ TEST(HybridFactorGraph, eliminateFullMultifrontalCLG) { I_3x3, Vector3::Ones())); - hfg.add(CGMixtureFactor({X(1)}, {x}, dt)); - hfg.add(HybridDiscreteFactor(DecisionTreeFactor(x, {2, 8}))); + hfg.add(CGMixtureFactor({X(1)}, {c}, dt)); + hfg.add(HybridDiscreteFactor(DecisionTreeFactor(c, {2, 8}))); // hfg.add(HybridDiscreteFactor(DecisionTreeFactor({{C(1), 2}, {C(2), 2}}, "1 2 3 4"))); auto result = hfg.eliminateMultifrontal(Ordering::ColamdConstrainedLast(hfg, {C(1)})); GTSAM_PRINT(*result); - GTSAM_PRINT(*result->marginalFactor(C(1))); + + // We immediately need to escape the CLG domain if we do this!!! + GTSAM_PRINT(*result->marginalFactor(X(1))); + /* + Explanation: the Junction tree will need to reeliminate to get to the marginal on X(1), which + is not possible because it involves eliminating discrete before continuous. The solution to this, + however, is in Murphy02. TLDR is that this is 1. expensive and 2. inexact. neverless it is doable. + And I believe that we should do this. + */ } /* ************************************************************************* */ From f237438bf30da2dab660761eb2523570c90121b5 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Tue, 15 Mar 2022 12:50:31 -0400 Subject: [PATCH 0190/1686] Address comments --- gtsam/hybrid/CGMixtureFactor.cpp | 22 ++++- gtsam/hybrid/CGMixtureFactor.h | 16 ++-- gtsam/hybrid/CLGaussianConditional.cpp | 40 +++++---- gtsam/hybrid/CLGaussianConditional.h | 18 ++-- gtsam/hybrid/HybridBayesTree.h | 15 ++-- gtsam/hybrid/HybridConditional.cpp | 33 ++++++-- gtsam/hybrid/HybridConditional.h | 36 ++++---- gtsam/hybrid/HybridDiscreteFactor.cpp | 29 +++++-- gtsam/hybrid/HybridDiscreteFactor.h | 10 ++- gtsam/hybrid/HybridEliminationTree.h | 45 +++++----- gtsam/hybrid/HybridFactor.cpp | 32 ++++--- gtsam/hybrid/HybridFactor.h | 61 +++++++------- gtsam/hybrid/HybridFactorGraph.cpp | 72 +++++++++------- gtsam/hybrid/HybridFactorGraph.h | 54 ++++++------ gtsam/hybrid/HybridGaussianFactor.cpp | 35 +++++--- gtsam/hybrid/HybridGaussianFactor.h | 10 ++- gtsam/hybrid/HybridJunctionTree.cpp | 10 +-- gtsam/hybrid/tests/testHybridConditional.cpp | 87 +++++++++----------- 18 files changed, 346 insertions(+), 279 deletions(-) diff --git a/gtsam/hybrid/CGMixtureFactor.cpp b/gtsam/hybrid/CGMixtureFactor.cpp index 16ead783e..705160273 100644 --- a/gtsam/hybrid/CGMixtureFactor.cpp +++ b/gtsam/hybrid/CGMixtureFactor.cpp @@ -1,6 +1,22 @@ -// -// Created by Fan Jiang on 3/11/22. -// +/* ---------------------------------------------------------------------------- + + * 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 CGMixtureFactor.cpp + * @brief A set of Gaussian factors indexed by a set of discrete keys. + * @author Fan Jiang + * @author Varun Agrawal + * @author Frank Dellaert + * @date Mar 12, 2022 + */ #include diff --git a/gtsam/hybrid/CGMixtureFactor.h b/gtsam/hybrid/CGMixtureFactor.h index 7ff53b7ed..0528d5401 100644 --- a/gtsam/hybrid/CGMixtureFactor.h +++ b/gtsam/hybrid/CGMixtureFactor.h @@ -18,15 +18,15 @@ * @date Mar 12, 2022 */ -#include -#include #include #include +#include +#include namespace gtsam { class CGMixtureFactor : public HybridFactor { -public: + public: using Base = HybridFactor; using This = CGMixtureFactor; using shared_ptr = boost::shared_ptr; @@ -38,13 +38,13 @@ public: CGMixtureFactor() = default; CGMixtureFactor(const KeyVector &continuousKeys, - const DiscreteKeys &discreteKeys, - const Factors &factors); + const DiscreteKeys &discreteKeys, const Factors &factors); bool equals(const HybridFactor &lf, double tol = 1e-9) const override; - void print(const std::string &s = "HybridFactor\n", - const KeyFormatter &formatter = DefaultKeyFormatter) const override; + void print( + const std::string &s = "HybridFactor\n", + const KeyFormatter &formatter = DefaultKeyFormatter) const override; }; -} +} // namespace gtsam diff --git a/gtsam/hybrid/CLGaussianConditional.cpp b/gtsam/hybrid/CLGaussianConditional.cpp index 37c82a0d5..30531c023 100644 --- a/gtsam/hybrid/CLGaussianConditional.cpp +++ b/gtsam/hybrid/CLGaussianConditional.cpp @@ -16,30 +16,28 @@ * @date Mar 12, 2022 */ -#include - #include - -#include #include +#include +#include namespace gtsam { -CLGaussianConditional::CLGaussianConditional(const KeyVector &continuousFrontals, - const KeyVector &continuousParents, - const DiscreteKeys &discreteParents, - const CLGaussianConditional::Conditionals &conditionals) - : BaseFactor( - CollectKeys(continuousFrontals, continuousParents), discreteParents), - BaseConditional(continuousFrontals.size()), conditionals_(conditionals) { - -} +CLGaussianConditional::CLGaussianConditional( + const KeyVector &continuousFrontals, const KeyVector &continuousParents, + const DiscreteKeys &discreteParents, + const CLGaussianConditional::Conditionals &conditionals) + : BaseFactor(CollectKeys(continuousFrontals, continuousParents), + discreteParents), + BaseConditional(continuousFrontals.size()), + conditionals_(conditionals) {} bool CLGaussianConditional::equals(const HybridFactor &lf, double tol) const { return false; } -void CLGaussianConditional::print(const std::string &s, const KeyFormatter &formatter) const { +void CLGaussianConditional::print(const std::string &s, + const KeyFormatter &formatter) const { std::cout << s << ": "; if (isContinuous_) std::cout << "Cont. "; if (isDiscrete_) std::cout << "Disc. "; @@ -51,14 +49,14 @@ void CLGaussianConditional::print(const std::string &s, const KeyFormatter &form } std::cout << "\n"; conditionals_.print( - "", - [&](Key k) { - return formatter(k); - }, [&](const GaussianConditional::shared_ptr &gf) -> std::string { + "", [&](Key k) { return formatter(k); }, + [&](const GaussianConditional::shared_ptr &gf) -> std::string { RedirectCout rd; - if (!gf->empty()) gf->print("", formatter); - else return {"nullptr"}; + if (!gf->empty()) + gf->print("", formatter); + else + return {"nullptr"}; return rd.str(); }); } -} \ No newline at end of file +} // namespace gtsam \ No newline at end of file diff --git a/gtsam/hybrid/CLGaussianConditional.h b/gtsam/hybrid/CLGaussianConditional.h index 0319c60a7..0429f4835 100644 --- a/gtsam/hybrid/CLGaussianConditional.h +++ b/gtsam/hybrid/CLGaussianConditional.h @@ -16,15 +16,16 @@ * @date Mar 12, 2022 */ -#include -#include - -#include #include +#include +#include +#include namespace gtsam { -class CLGaussianConditional : public HybridFactor, public Conditional { -public: +class CLGaussianConditional + : public HybridFactor, + public Conditional { + public: using This = CLGaussianConditional; using shared_ptr = boost::shared_ptr; using BaseFactor = HybridFactor; @@ -34,8 +35,7 @@ public: Conditionals conditionals_; -public: - + public: CLGaussianConditional(const KeyVector &continuousFrontals, const KeyVector &continuousParents, const DiscreteKeys &discreteParents, @@ -47,4 +47,4 @@ public: const std::string &s = "CLGaussianConditional\n", const KeyFormatter &formatter = DefaultKeyFormatter) const override; }; -} \ No newline at end of file +} // namespace gtsam \ No newline at end of file diff --git a/gtsam/hybrid/HybridBayesTree.h b/gtsam/hybrid/HybridBayesTree.h index 06df66112..74b967fc8 100644 --- a/gtsam/hybrid/HybridBayesTree.h +++ b/gtsam/hybrid/HybridBayesTree.h @@ -11,8 +11,7 @@ /** * @file HybridBayesTree.h - * @brief Hybrid Bayes Tree, the result of eliminating a - * HybridJunctionTree + * @brief Hybrid Bayes Tree, the result of eliminating a HybridJunctionTree * @date Mar 11, 2022 * @author Fan Jiang */ @@ -22,8 +21,8 @@ #include #include #include -#include #include +#include #include @@ -39,22 +38,18 @@ class GTSAM_EXPORT HybridBayesTreeClique : public BayesTreeCliqueBase { public: typedef HybridBayesTreeClique This; - typedef BayesTreeCliqueBase - Base; + typedef BayesTreeCliqueBase Base; typedef boost::shared_ptr shared_ptr; typedef boost::weak_ptr weak_ptr; HybridBayesTreeClique() {} virtual ~HybridBayesTreeClique() {} - HybridBayesTreeClique( - const boost::shared_ptr& conditional) + HybridBayesTreeClique(const boost::shared_ptr& conditional) : Base(conditional) {} - }; /* ************************************************************************* */ /** A Bayes tree representing a Hybrid density */ -class GTSAM_EXPORT HybridBayesTree - : public BayesTree { +class GTSAM_EXPORT HybridBayesTree : public BayesTree { private: typedef BayesTree Base; diff --git a/gtsam/hybrid/HybridConditional.cpp b/gtsam/hybrid/HybridConditional.cpp index b3009d5b9..5cb98d921 100644 --- a/gtsam/hybrid/HybridConditional.cpp +++ b/gtsam/hybrid/HybridConditional.cpp @@ -1,6 +1,19 @@ -// -// Created by Fan Jiang on 3/11/22. -// +/* ---------------------------------------------------------------------------- + + * 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 HybridConditional.cpp + * @date Mar 11, 2022 + * @author Fan Jiang + */ #include #include @@ -14,7 +27,10 @@ void HybridConditional::print(const std::string &s, const size_t contN = N - discreteKeys_.size(); while (index < N) { if (index > 0) { - if (index == nrFrontals_) std::cout << " | "; else std::cout << ", "; + if (index == nrFrontals_) + std::cout << " | "; + else + std::cout << ", "; } if (index < contN) { std::cout << formatter(keys()[index]); @@ -28,13 +44,12 @@ void HybridConditional::print(const std::string &s, if (inner) inner->print("", formatter); } -bool HybridConditional::equals(const HybridFactor &other, - double tol) const { +bool HybridConditional::equals(const HybridFactor &other, double tol) const { return false; } -HybridConditional HybridConditional::operator*(const HybridConditional &other) const { +HybridConditional HybridConditional::operator*( + const HybridConditional &other) const { return {}; } -} - +} // namespace gtsam diff --git a/gtsam/hybrid/HybridConditional.h b/gtsam/hybrid/HybridConditional.h index 92856cae2..89071092f 100644 --- a/gtsam/hybrid/HybridConditional.h +++ b/gtsam/hybrid/HybridConditional.h @@ -17,11 +17,10 @@ #pragma once -#include #include +#include #include - #include #include #include @@ -38,33 +37,30 @@ namespace gtsam { * - GaussianConditional */ class GTSAM_EXPORT HybridConditional -: public HybridFactor, -public Conditional { -public: + : public HybridFactor, + public Conditional { + public: // typedefs needed to play nice with gtsam - typedef HybridConditional This; ///< Typedef to this class + typedef HybridConditional This; ///< Typedef to this class typedef boost::shared_ptr shared_ptr; ///< shared_ptr to this class typedef HybridFactor BaseFactor; ///< Typedef to our factor base class typedef Conditional BaseConditional; ///< Typedef to our conditional base class -private: + private: // Type-erased pointer to the inner type std::unique_ptr inner; -public: -/// @name Standard Constructors -/// @{ + public: + /// @name Standard Constructors + /// @{ /// Default constructor needed for serialization. HybridConditional() = default; - HybridConditional(const KeyVector &continuousKeys, - const DiscreteKeys &discreteKeys, - size_t nFrontals) - : BaseFactor(continuousKeys, discreteKeys), BaseConditional(nFrontals) { - - } + HybridConditional(const KeyVector& continuousKeys, + const DiscreteKeys& discreteKeys, size_t nFrontals) + : BaseFactor(continuousKeys, discreteKeys), BaseConditional(nFrontals) {} /** * @brief Combine two conditionals, yielding a new conditional with the union @@ -83,9 +79,9 @@ public: */ HybridConditional operator*(const HybridConditional& other) const; -/// @} -/// @name Testable -/// @{ + /// @} + /// @name Testable + /// @{ /// GTSAM-style print void print( @@ -95,7 +91,7 @@ public: /// GTSAM-style equals bool equals(const HybridFactor& other, double tol = 1e-9) const override; -/// @} + /// @} }; // DiscreteConditional diff --git a/gtsam/hybrid/HybridDiscreteFactor.cpp b/gtsam/hybrid/HybridDiscreteFactor.cpp index 1758e9025..96d3842b8 100644 --- a/gtsam/hybrid/HybridDiscreteFactor.cpp +++ b/gtsam/hybrid/HybridDiscreteFactor.cpp @@ -1,6 +1,20 @@ -// -// Created by Fan Jiang on 3/11/22. -// +/* ---------------------------------------------------------------------------- + + * 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 HybridDiscreteFactor.cpp + * @brief Wrapper for a discrete factor + * @date Mar 11, 2022 + * @author Fan Jiang + */ #include @@ -15,17 +29,16 @@ HybridDiscreteFactor::HybridDiscreteFactor(DiscreteFactor::shared_ptr other) HybridDiscreteFactor::HybridDiscreteFactor(DecisionTreeFactor &&dtf) : Base(dtf.discreteKeys()), - inner(boost::make_shared(std::move(dtf))) { - -} + inner(boost::make_shared(std::move(dtf))) {} bool HybridDiscreteFactor::equals(const HybridFactor &lf, double tol) const { return false; } -void HybridDiscreteFactor::print(const std::string &s, const KeyFormatter &formatter) const { +void HybridDiscreteFactor::print(const std::string &s, + const KeyFormatter &formatter) const { HybridFactor::print(s, formatter); inner->print("inner: ", formatter); }; -} \ No newline at end of file +} // namespace gtsam \ No newline at end of file diff --git a/gtsam/hybrid/HybridDiscreteFactor.h b/gtsam/hybrid/HybridDiscreteFactor.h index 9d574b736..09da9cf70 100644 --- a/gtsam/hybrid/HybridDiscreteFactor.h +++ b/gtsam/hybrid/HybridDiscreteFactor.h @@ -15,8 +15,8 @@ * @author Fan Jiang */ -#include #include +#include #include namespace gtsam { @@ -36,8 +36,10 @@ class HybridDiscreteFactor : public HybridFactor { HybridDiscreteFactor(DecisionTreeFactor &&dtf); public: - virtual bool equals(const HybridFactor& lf, double tol) const override; + virtual bool equals(const HybridFactor &lf, double tol) const override; - void print(const std::string &s = "HybridFactor\n", const KeyFormatter &formatter = DefaultKeyFormatter) const override; + void print( + const std::string &s = "HybridFactor\n", + const KeyFormatter &formatter = DefaultKeyFormatter) const override; }; -} +} // namespace gtsam diff --git a/gtsam/hybrid/HybridEliminationTree.h b/gtsam/hybrid/HybridEliminationTree.h index e218ce9f6..b72bbcad9 100644 --- a/gtsam/hybrid/HybridEliminationTree.h +++ b/gtsam/hybrid/HybridEliminationTree.h @@ -23,40 +23,39 @@ namespace gtsam { -class GTSAM_EXPORT HybridEliminationTree : - public EliminationTree -{ +class GTSAM_EXPORT HybridEliminationTree + : public EliminationTree { public: - typedef EliminationTree Base; ///< Base class - typedef HybridEliminationTree This; ///< This class - typedef boost::shared_ptr shared_ptr; ///< Shared pointer to this class + typedef EliminationTree + Base; ///< Base class + typedef HybridEliminationTree This; ///< This class + typedef boost::shared_ptr shared_ptr; ///< Shared pointer to this class /** - * Build the elimination tree of a factor graph using pre-computed column structure. - * @param factorGraph The factor graph for which to build the elimination tree - * @param structure The set of factors involving each variable. If this is not - * precomputed, you can call the Create(const FactorGraph&) - * named constructor instead. - * @return The elimination tree - */ + * Build the elimination tree of a factor graph using pre-computed column + * structure. + * @param factorGraph The factor graph for which to build the elimination tree + * @param structure The set of factors involving each variable. If this is + * not precomputed, you can call the Create(const FactorGraph&) + * named constructor instead. + * @return The elimination tree + */ HybridEliminationTree(const HybridFactorGraph& factorGraph, - const VariableIndex& structure, const Ordering& order); + const VariableIndex& structure, const Ordering& order); - /** Build the elimination tree of a factor graph. Note that this has to compute the column - * structure as a VariableIndex, so if you already have this precomputed, use the other - * constructor instead. - * @param factorGraph The factor graph for which to build the elimination tree - */ + /** Build the elimination tree of a factor graph. Note that this has to + * compute the column structure as a VariableIndex, so if you already have + * this precomputed, use the other constructor instead. + * @param factorGraph The factor graph for which to build the elimination tree + */ HybridEliminationTree(const HybridFactorGraph& factorGraph, - const Ordering& order); + const Ordering& order); /** Test whether the tree is equal to another */ bool equals(const This& other, double tol = 1e-9) const; private: - friend class ::EliminationTreeTester; - }; -} +} // namespace gtsam diff --git a/gtsam/hybrid/HybridFactor.cpp b/gtsam/hybrid/HybridFactor.cpp index 171ea790a..f16092eff 100644 --- a/gtsam/hybrid/HybridFactor.cpp +++ b/gtsam/hybrid/HybridFactor.cpp @@ -19,11 +19,12 @@ namespace gtsam { -KeyVector CollectKeys(const KeyVector &continuousKeys, const DiscreteKeys &discreteKeys) { +KeyVector CollectKeys(const KeyVector &continuousKeys, + const DiscreteKeys &discreteKeys) { KeyVector allKeys; - std::copy(continuousKeys.begin(), continuousKeys.end(), std::back_inserter(allKeys)); - std::transform(discreteKeys.begin(), - discreteKeys.end(), + std::copy(continuousKeys.begin(), continuousKeys.end(), + std::back_inserter(allKeys)); + std::transform(discreteKeys.begin(), discreteKeys.end(), std::back_inserter(allKeys), [](const DiscreteKey &k) { return k.first; }); return allKeys; @@ -36,7 +37,8 @@ KeyVector CollectKeys(const KeyVector &keys1, const KeyVector &keys2) { return allKeys; } -DiscreteKeys CollectDiscreteKeys(const DiscreteKeys &key1, const DiscreteKeys &key2) { +DiscreteKeys CollectDiscreteKeys(const DiscreteKeys &key1, + const DiscreteKeys &key2) { DiscreteKeys allKeys; std::copy(key1.begin(), key1.end(), std::back_inserter(allKeys)); std::copy(key2.begin(), key2.end(), std::back_inserter(allKeys)); @@ -45,16 +47,20 @@ DiscreteKeys CollectDiscreteKeys(const DiscreteKeys &key1, const DiscreteKeys &k HybridFactor::HybridFactor() = default; -HybridFactor::HybridFactor(const KeyVector &keys) : Base(keys), isContinuous_(true) {} +HybridFactor::HybridFactor(const KeyVector &keys) + : Base(keys), isContinuous_(true) {} -HybridFactor::HybridFactor(const KeyVector &continuousKeys, const DiscreteKeys &discreteKeys) - : Base( - CollectKeys(continuousKeys, discreteKeys)), isHybrid_(true), discreteKeys_(discreteKeys) {} +HybridFactor::HybridFactor(const KeyVector &continuousKeys, + const DiscreteKeys &discreteKeys) + : Base(CollectKeys(continuousKeys, discreteKeys)), + isHybrid_(true), + discreteKeys_(discreteKeys) {} -HybridFactor::HybridFactor(const DiscreteKeys &discreteKeys) : Base(CollectKeys({}, discreteKeys)), - isDiscrete_(true), - discreteKeys_(discreteKeys) {} +HybridFactor::HybridFactor(const DiscreteKeys &discreteKeys) + : Base(CollectKeys({}, discreteKeys)), + isDiscrete_(true), + discreteKeys_(discreteKeys) {} HybridFactor::~HybridFactor() = default; -} \ No newline at end of file +} // namespace gtsam \ No newline at end of file diff --git a/gtsam/hybrid/HybridFactor.h b/gtsam/hybrid/HybridFactor.h index dd925fee2..cd562869e 100644 --- a/gtsam/hybrid/HybridFactor.h +++ b/gtsam/hybrid/HybridFactor.h @@ -17,29 +17,30 @@ #pragma once -#include -#include -#include #include +#include +#include +#include #include namespace gtsam { -KeyVector CollectKeys(const KeyVector &continuousKeys, const DiscreteKeys &discreteKeys); +KeyVector CollectKeys(const KeyVector &continuousKeys, + const DiscreteKeys &discreteKeys); KeyVector CollectKeys(const KeyVector &keys1, const KeyVector &keys2); -DiscreteKeys CollectDiscreteKeys(const DiscreteKeys &key1, const DiscreteKeys &key2); +DiscreteKeys CollectDiscreteKeys(const DiscreteKeys &key1, + const DiscreteKeys &key2); /** * Base class for hybrid probabilistic factors */ class GTSAM_EXPORT HybridFactor : public Factor { - -public: - + public: // typedefs needed to play nice with gtsam - typedef HybridFactor This; ///< This class - typedef boost::shared_ptr shared_ptr; ///< shared_ptr to this class - typedef Factor Base; ///< Our base class + typedef HybridFactor This; ///< This class + typedef boost::shared_ptr + shared_ptr; ///< shared_ptr to this class + typedef Factor Base; ///< Our base class bool isDiscrete_ = false; bool isContinuous_ = false; @@ -47,31 +48,33 @@ public: DiscreteKeys discreteKeys_; -public: - -/// @name Standard Constructors -/// @{ + public: + /// @name Standard Constructors + /// @{ /** Default constructor creates empty factor */ HybridFactor(); - /** Construct from container of keys. This constructor is used internally from derived factor - * constructors, either from a container of keys or from a boost::assign::list_of. */ -// template -// HybridFactor(const CONTAINER &keys) : Base(keys) {} + /** Construct from container of keys. This constructor is used internally + * from derived factor + * constructors, either from a container of keys or from a + * boost::assign::list_of. */ + // template + // HybridFactor(const CONTAINER &keys) : Base(keys) {} explicit HybridFactor(const KeyVector &keys); - HybridFactor(const KeyVector &continuousKeys, const DiscreteKeys &discreteKeys); + HybridFactor(const KeyVector &continuousKeys, + const DiscreteKeys &discreteKeys); explicit HybridFactor(const DiscreteKeys &discreteKeys); /// Virtual destructor virtual ~HybridFactor(); -/// @} -/// @name Testable -/// @{ + /// @} + /// @name Testable + /// @{ /// equals virtual bool equals(const HybridFactor &lf, double tol = 1e-9) const = 0; @@ -87,16 +90,16 @@ public: this->printKeys("", formatter); } -/// @} -/// @name Standard Interface -/// @{ + /// @} + /// @name Standard Interface + /// @{ -/// @} + /// @} }; // HybridFactor // traits -template<> +template <> struct traits : public Testable {}; -}// namespace gtsam +} // namespace gtsam diff --git a/gtsam/hybrid/HybridFactorGraph.cpp b/gtsam/hybrid/HybridFactorGraph.cpp index 03610166e..7d4daaceb 100644 --- a/gtsam/hybrid/HybridFactorGraph.cpp +++ b/gtsam/hybrid/HybridFactorGraph.cpp @@ -1,25 +1,37 @@ -// -// Created by Fan Jiang on 3/11/22. -// +/* ---------------------------------------------------------------------------- -#include "gtsam/inference/Key.h" -#include -#include -#include -#include + * 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 HybridFactorGraph.cpp + * @brief Hybrid factor graph that uses type erasure + * @author Fan Jiang + * @date Mar 11, 2022 + */ -#include #include - +#include +#include +#include +#include +#include #include #include #include +#include "gtsam/inference/Key.h" + namespace gtsam { -template -class EliminateableFactorGraph; +template class EliminateableFactorGraph; static std::string BLACK_BOLD = "\033[1;30m"; static std::string RED_BOLD = "\033[1;31m"; @@ -29,8 +41,7 @@ static std::string RESET = "\033[0m"; /* ************************************************************************ */ std::pair // -EliminateHybrid(const HybridFactorGraph &factors, - const Ordering &frontalKeys) { +EliminateHybrid(const HybridFactorGraph &factors, const Ordering &frontalKeys) { // NOTE(fan): Because we are in the Conditional Gaussian regime there are only // a few cases: // continuous variable, we make a GM if there are hybrid factors; @@ -38,9 +49,10 @@ EliminateHybrid(const HybridFactorGraph &factors, // discrete variable, no continuous factor is allowed (escapes CG regime), so // we panic, if discrete only we do the discrete elimination. - // However it is not that simple. During elimination it is possible that the multifrontal needs - // to eliminate an ordering that contains both Gaussian and hybrid variables, for example x1, c1. - // In this scenario, we will have a density P(x1, c1) that is a CLG P(x1|c1)P(c1) (see Murphy02) + // However it is not that simple. During elimination it is possible that the + // multifrontal needs to eliminate an ordering that contains both Gaussian and + // hybrid variables, for example x1, c1. In this scenario, we will have a + // density P(x1, c1) that is a CLG P(x1|c1)P(c1) (see Murphy02) // The issue here is that, how can we know which variable is discrete if we // unify Values? Obviously we can tell using the factors, but is that fast? @@ -102,7 +114,8 @@ EliminateHybrid(const HybridFactorGraph &factors, for (auto &f : frontalKeys) { if (discreteCardinalities.find(f) != discreteCardinalities.end()) { auto &key = discreteCardinalities.at(f); - std::cout << boost::format(" (%1%,%2%),") % DefaultKeyFormatter(key.first) % key.second; + std::cout << boost::format(" (%1%,%2%),") % + DefaultKeyFormatter(key.first) % key.second; } else { std::cout << " " << DefaultKeyFormatter(f) << ","; } @@ -115,7 +128,8 @@ EliminateHybrid(const HybridFactorGraph &factors, for (auto &f : separatorKeys) { if (discreteCardinalities.find(f) != discreteCardinalities.end()) { auto &key = discreteCardinalities.at(f); - std::cout << boost::format(" (%1%,%2%),") % DefaultKeyFormatter(key.first) % key.second; + std::cout << boost::format(" (%1%,%2%),") % + DefaultKeyFormatter(key.first) % key.second; } else { std::cout << DefaultKeyFormatter(f) << ","; } @@ -124,9 +138,10 @@ EliminateHybrid(const HybridFactorGraph &factors, // PRODUCT: multiply all factors gttic(product); - HybridConditional sum(KeyVector(continuousSeparator.begin(), continuousSeparator.end()), - DiscreteKeys(discreteSeparator.begin(), discreteSeparator.end()), - separatorKeys.size()); + HybridConditional sum( + KeyVector(continuousSeparator.begin(), continuousSeparator.end()), + DiscreteKeys(discreteSeparator.begin(), discreteSeparator.end()), + separatorKeys.size()); // HybridDiscreteFactor product(DiscreteConditional()); // for (auto&& factor : factors) product = (*factor) * product; @@ -139,10 +154,8 @@ EliminateHybrid(const HybridFactorGraph &factors, // Ordering keys for the conditional so that frontalKeys are really in front Ordering orderedKeys; - orderedKeys.insert(orderedKeys.end(), frontalKeys.begin(), - frontalKeys.end()); - orderedKeys.insert(orderedKeys.end(), sum.keys().begin(), - sum.keys().end()); + orderedKeys.insert(orderedKeys.end(), frontalKeys.begin(), frontalKeys.end()); + orderedKeys.insert(orderedKeys.end(), sum.keys().begin(), sum.keys().end()); // now divide product/sum to get conditional gttic(divide); @@ -163,12 +176,11 @@ EliminateHybrid(const HybridFactorGraph &factors, std::cout << RED_BOLD << "[End Eliminate]\n" << RESET; // return std::make_pair(conditional, sum); - return std::make_pair( - conditional, - boost::make_shared(std::move(sum))); + return std::make_pair(conditional, + boost::make_shared(std::move(sum))); } void HybridFactorGraph::add(JacobianFactor &&factor) { FactorGraph::add(boost::make_shared(std::move(factor))); } -} +} // namespace gtsam diff --git a/gtsam/hybrid/HybridFactorGraph.h b/gtsam/hybrid/HybridFactorGraph.h index 9a57d36e6..92f98c8f2 100644 --- a/gtsam/hybrid/HybridFactorGraph.h +++ b/gtsam/hybrid/HybridFactorGraph.h @@ -36,43 +36,50 @@ class HybridJunctionTree; class JacobianFactor; /** Main elimination function for HybridFactorGraph */ -GTSAM_EXPORT std::pair, HybridFactor::shared_ptr> -EliminateHybrid(const HybridFactorGraph& factors, const Ordering& keys); +GTSAM_EXPORT + std::pair, HybridFactor::shared_ptr> + EliminateHybrid(const HybridFactorGraph& factors, const Ordering& keys); /* ************************************************************************* */ -template<> struct EliminationTraits -{ - typedef HybridFactor FactorType; ///< Type of factors in factor graph - typedef HybridFactorGraph FactorGraphType; ///< Type of the factor graph (e.g. HybridFactorGraph) - typedef HybridConditional ConditionalType; ///< Type of conditionals from elimination - typedef HybridBayesNet BayesNetType; ///< Type of Bayes net from sequential elimination - typedef HybridEliminationTree EliminationTreeType; ///< Type of elimination tree - typedef HybridBayesTree BayesTreeType; ///< Type of Bayes tree - typedef HybridJunctionTree JunctionTreeType; ///< Type of Junction tree +template <> +struct EliminationTraits { + typedef HybridFactor FactorType; ///< Type of factors in factor graph + typedef HybridFactorGraph + FactorGraphType; ///< Type of the factor graph (e.g. HybridFactorGraph) + typedef HybridConditional + ConditionalType; ///< Type of conditionals from elimination + typedef HybridBayesNet + BayesNetType; ///< Type of Bayes net from sequential elimination + typedef HybridEliminationTree + EliminationTreeType; ///< Type of elimination tree + typedef HybridBayesTree BayesTreeType; ///< Type of Bayes tree + typedef HybridJunctionTree JunctionTreeType; ///< Type of Junction tree /// The default dense elimination function - static std::pair, boost::shared_ptr > + static std::pair, + boost::shared_ptr > DefaultEliminate(const FactorGraphType& factors, const Ordering& keys) { - return EliminateHybrid(factors, keys); } + return EliminateHybrid(factors, keys); + } }; - -class HybridFactorGraph : public FactorGraph, public EliminateableFactorGraph { +class HybridFactorGraph : public FactorGraph, + public EliminateableFactorGraph { public: using Base = FactorGraph; - using This = HybridFactorGraph; ///< this class + using This = HybridFactorGraph; ///< this class using BaseEliminateable = - EliminateableFactorGraph; ///< for elimination + EliminateableFactorGraph; ///< for elimination using shared_ptr = boost::shared_ptr; ///< shared_ptr to This using Values = gtsam::Values; ///< backwards compatibility - using Indices = KeyVector; ///> map from keys to values + using Indices = KeyVector; ///> map from keys to values public: HybridFactorGraph() = default; -// /** Construct from container of factors (shared_ptr or plain objects) */ -// template -// explicit HybridFactorGraph(const CONTAINER& factors) : Base(factors) {} + // /** Construct from container of factors (shared_ptr or plain objects) */ + // template + // explicit HybridFactorGraph(const CONTAINER& factors) : Base(factors) {} /** Implicit copy/downcast constructor to override explicit template container * constructor. In BayesTree this is used for: @@ -84,8 +91,7 @@ class HybridFactorGraph : public FactorGraph, public Eliminateable using FactorGraph::add; /// Add a factor directly using a shared_ptr. - void add(JacobianFactor &&factor); + void add(JacobianFactor&& factor); }; -} - +} // namespace gtsam diff --git a/gtsam/hybrid/HybridGaussianFactor.cpp b/gtsam/hybrid/HybridGaussianFactor.cpp index faa4ba998..d83f90024 100644 --- a/gtsam/hybrid/HybridGaussianFactor.cpp +++ b/gtsam/hybrid/HybridGaussianFactor.cpp @@ -1,6 +1,19 @@ -// -// Created by Fan Jiang on 3/11/22. -// +/* ---------------------------------------------------------------------------- + + * 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 HybridGaussianFactor.cpp + * @date Mar 11, 2022 + * @author Fan Jiang + */ #include @@ -8,20 +21,22 @@ namespace gtsam { -HybridGaussianFactor::HybridGaussianFactor(GaussianFactor::shared_ptr other) : Base(other->keys()) { +HybridGaussianFactor::HybridGaussianFactor(GaussianFactor::shared_ptr other) + : Base(other->keys()) { inner = other; } -HybridGaussianFactor::HybridGaussianFactor(JacobianFactor &&jf) : Base(jf.keys()), inner(boost::make_shared(std::move(jf))) { +HybridGaussianFactor::HybridGaussianFactor(JacobianFactor &&jf) + : Base(jf.keys()), + inner(boost::make_shared(std::move(jf))) {} -} - -bool HybridGaussianFactor::equals(const HybridFactor& lf, double tol) const { +bool HybridGaussianFactor::equals(const HybridFactor &lf, double tol) const { return false; } -void HybridGaussianFactor::print(const std::string &s, const KeyFormatter &formatter) const { +void HybridGaussianFactor::print(const std::string &s, + const KeyFormatter &formatter) const { HybridFactor::print(s, formatter); inner->print("inner: ", formatter); }; -} \ No newline at end of file +} // namespace gtsam \ No newline at end of file diff --git a/gtsam/hybrid/HybridGaussianFactor.h b/gtsam/hybrid/HybridGaussianFactor.h index 8562075b4..23a3c0110 100644 --- a/gtsam/hybrid/HybridGaussianFactor.h +++ b/gtsam/hybrid/HybridGaussianFactor.h @@ -15,9 +15,9 @@ * @author Fan Jiang */ +#include #include #include -#include namespace gtsam { @@ -36,8 +36,10 @@ class HybridGaussianFactor : public HybridFactor { explicit HybridGaussianFactor(JacobianFactor &&jf); public: - virtual bool equals(const HybridFactor& lf, double tol) const override; + virtual bool equals(const HybridFactor &lf, double tol) const override; - void print(const std::string &s = "HybridFactor\n", const KeyFormatter &formatter = DefaultKeyFormatter) const override; + void print( + const std::string &s = "HybridFactor\n", + const KeyFormatter &formatter = DefaultKeyFormatter) const override; }; -} +} // namespace gtsam diff --git a/gtsam/hybrid/HybridJunctionTree.cpp b/gtsam/hybrid/HybridJunctionTree.cpp index 0e3d2ea00..9da1bfed3 100644 --- a/gtsam/hybrid/HybridJunctionTree.cpp +++ b/gtsam/hybrid/HybridJunctionTree.cpp @@ -15,9 +15,9 @@ * @author Fan Jiang */ -#include -#include #include +#include +#include namespace gtsam { @@ -27,7 +27,7 @@ template class JunctionTree; /* ************************************************************************* */ HybridJunctionTree::HybridJunctionTree( - const HybridEliminationTree& eliminationTree) : - Base(eliminationTree) {} + const HybridEliminationTree& eliminationTree) + : Base(eliminationTree) {} -} +} // namespace gtsam diff --git a/gtsam/hybrid/tests/testHybridConditional.cpp b/gtsam/hybrid/tests/testHybridConditional.cpp index c682f5216..f945d0702 100644 --- a/gtsam/hybrid/tests/testHybridConditional.cpp +++ b/gtsam/hybrid/tests/testHybridConditional.cpp @@ -15,32 +15,30 @@ * @author Fan Jiang */ -#include "Test.h" -#include -#include -#include -#include -#include -#include +#include +#include #include +#include #include #include - -#include +#include +#include +#include +#include +#include #include - #include - -#include +#include #include + using namespace boost::assign; using namespace std; using namespace gtsam; -using gtsam::symbol_shorthand::X; using gtsam::symbol_shorthand::C; +using gtsam::symbol_shorthand::X; /* ************************************************************************* */ TEST(HybridFactorGraph, creation) { @@ -51,17 +49,13 @@ TEST(HybridFactorGraph, creation) { hfg.add(HybridGaussianFactor(JacobianFactor(0, I_3x3, Z_3x1))); CLGaussianConditional clgc( - {X(0)}, {X(1)}, - DiscreteKeys(DiscreteKey{C(0), 2}), + {X(0)}, {X(1)}, DiscreteKeys(DiscreteKey{C(0), 2}), CLGaussianConditional::Conditionals( C(0), - boost::make_shared( - X(0), Z_3x1, I_3x3, X(1), I_3x3), - boost::make_shared( - X(0), Vector3::Ones(), - I_3x3, X(1), - I_3x3)) - ); + boost::make_shared(X(0), Z_3x1, I_3x3, X(1), + I_3x3), + boost::make_shared(X(0), Vector3::Ones(), I_3x3, + X(1), I_3x3))); GTSAM_PRINT(clgc); } @@ -90,7 +84,6 @@ TEST_DISABLED(HybridFactorGraph, eliminateMultifrontal) { } TEST_DISABLED(HybridFactorGraph, eliminateFullMultifrontalSimple) { - std::cout << ">>>>>>>>>>>>>>\n"; HybridFactorGraph hfg; @@ -100,29 +93,27 @@ TEST_DISABLED(HybridFactorGraph, eliminateFullMultifrontalSimple) { hfg.add(JacobianFactor(X(0), I_3x3, Z_3x1)); hfg.add(JacobianFactor(X(0), I_3x3, X(1), -I_3x3, Z_3x1)); - DecisionTree dt(C(1), - boost::make_shared(X(1), - I_3x3, - Z_3x1), - boost::make_shared(X(1), - I_3x3, - Vector3::Ones())); + DecisionTree dt( + C(1), boost::make_shared(X(1), I_3x3, Z_3x1), + boost::make_shared(X(1), I_3x3, Vector3::Ones())); hfg.add(CGMixtureFactor({X(1)}, {c1}, dt)); hfg.add(CGMixtureFactor({X(0)}, {c1}, dt)); hfg.add(HybridDiscreteFactor(DecisionTreeFactor(c1, {2, 8}))); - hfg.add(HybridDiscreteFactor(DecisionTreeFactor({{C(1), 2}, {C(2), 2}}, "1 2 3 4"))); - // hfg.add(HybridDiscreteFactor(DecisionTreeFactor({{C(2), 2}, {C(3), 2}}, "1 2 3 4"))); - // hfg.add(HybridDiscreteFactor(DecisionTreeFactor({{C(3), 2}, {C(1), 2}}, "1 2 2 1"))); + hfg.add(HybridDiscreteFactor( + DecisionTreeFactor({{C(1), 2}, {C(2), 2}}, "1 2 3 4"))); + // hfg.add(HybridDiscreteFactor(DecisionTreeFactor({{C(2), 2}, {C(3), 2}}, "1 + // 2 3 4"))); hfg.add(HybridDiscreteFactor(DecisionTreeFactor({{C(3), 2}, + // {C(1), 2}}, "1 2 2 1"))); - auto result = hfg.eliminateMultifrontal(Ordering::ColamdConstrainedLast(hfg, {C(1), C(2)})); + auto result = hfg.eliminateMultifrontal( + Ordering::ColamdConstrainedLast(hfg, {C(1), C(2)})); GTSAM_PRINT(*result); GTSAM_PRINT(*result->marginalFactor(C(1))); } TEST(HybridFactorGraph, eliminateFullMultifrontalCLG) { - std::cout << ">>>>>>>>>>>>>>\n"; HybridFactorGraph hfg; @@ -132,29 +123,28 @@ TEST(HybridFactorGraph, eliminateFullMultifrontalCLG) { hfg.add(JacobianFactor(X(0), I_3x3, Z_3x1)); hfg.add(JacobianFactor(X(0), I_3x3, X(1), -I_3x3, Z_3x1)); - DecisionTree dt(C(1), - boost::make_shared(X(1), - I_3x3, - Z_3x1), - boost::make_shared(X(1), - I_3x3, - Vector3::Ones())); + DecisionTree dt( + C(1), boost::make_shared(X(1), I_3x3, Z_3x1), + boost::make_shared(X(1), I_3x3, Vector3::Ones())); hfg.add(CGMixtureFactor({X(1)}, {c}, dt)); hfg.add(HybridDiscreteFactor(DecisionTreeFactor(c, {2, 8}))); -// hfg.add(HybridDiscreteFactor(DecisionTreeFactor({{C(1), 2}, {C(2), 2}}, "1 2 3 4"))); + // hfg.add(HybridDiscreteFactor(DecisionTreeFactor({{C(1), 2}, {C(2), 2}}, "1 + // 2 3 4"))); - auto result = hfg.eliminateMultifrontal(Ordering::ColamdConstrainedLast(hfg, {C(1)})); + auto result = + hfg.eliminateMultifrontal(Ordering::ColamdConstrainedLast(hfg, {C(1)})); GTSAM_PRINT(*result); // We immediately need to escape the CLG domain if we do this!!! GTSAM_PRINT(*result->marginalFactor(X(1))); /* - Explanation: the Junction tree will need to reeliminate to get to the marginal on X(1), which - is not possible because it involves eliminating discrete before continuous. The solution to this, - however, is in Murphy02. TLDR is that this is 1. expensive and 2. inexact. neverless it is doable. - And I believe that we should do this. + Explanation: the Junction tree will need to reeliminate to get to the marginal + on X(1), which is not possible because it involves eliminating discrete before + continuous. The solution to this, however, is in Murphy02. TLDR is that this + is 1. expensive and 2. inexact. neverless it is doable. And I believe that we + should do this. */ } @@ -164,4 +154,3 @@ int main() { return TestRegistry::runAllTests(tr); } /* ************************************************************************* */ - From 36ee4ce7cbc8dc5ffdf5ca71b107fd7a2dc3beb0 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Tue, 15 Mar 2022 12:53:58 -0400 Subject: [PATCH 0191/1686] Missing pragma onces --- gtsam/CMakeLists.txt | 2 +- gtsam/hybrid/CGMixtureFactor.h | 2 ++ gtsam/hybrid/CLGaussianConditional.h | 2 ++ gtsam/hybrid/HybridDiscreteFactor.h | 2 ++ gtsam/hybrid/HybridGaussianFactor.h | 2 ++ 5 files changed, 9 insertions(+), 1 deletion(-) diff --git a/gtsam/CMakeLists.txt b/gtsam/CMakeLists.txt index 845ac7cd0..09f1ea806 100644 --- a/gtsam/CMakeLists.txt +++ b/gtsam/CMakeLists.txt @@ -10,7 +10,7 @@ set (gtsam_subdirs inference symbolic discrete - hybrid + hybrid linear nonlinear sam diff --git a/gtsam/hybrid/CGMixtureFactor.h b/gtsam/hybrid/CGMixtureFactor.h index 0528d5401..556c53cc5 100644 --- a/gtsam/hybrid/CGMixtureFactor.h +++ b/gtsam/hybrid/CGMixtureFactor.h @@ -18,6 +18,8 @@ * @date Mar 12, 2022 */ +#pragma once + #include #include #include diff --git a/gtsam/hybrid/CLGaussianConditional.h b/gtsam/hybrid/CLGaussianConditional.h index 0429f4835..d80cb804f 100644 --- a/gtsam/hybrid/CLGaussianConditional.h +++ b/gtsam/hybrid/CLGaussianConditional.h @@ -16,6 +16,8 @@ * @date Mar 12, 2022 */ +#pragma once + #include #include #include diff --git a/gtsam/hybrid/HybridDiscreteFactor.h b/gtsam/hybrid/HybridDiscreteFactor.h index 09da9cf70..f182f90a9 100644 --- a/gtsam/hybrid/HybridDiscreteFactor.h +++ b/gtsam/hybrid/HybridDiscreteFactor.h @@ -15,6 +15,8 @@ * @author Fan Jiang */ +#pragma once + #include #include #include diff --git a/gtsam/hybrid/HybridGaussianFactor.h b/gtsam/hybrid/HybridGaussianFactor.h index 23a3c0110..03c49564e 100644 --- a/gtsam/hybrid/HybridGaussianFactor.h +++ b/gtsam/hybrid/HybridGaussianFactor.h @@ -15,6 +15,8 @@ * @author Fan Jiang */ +#pragma once + #include #include #include From 5e9020237f8a821a641080911adebeab8da84426 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Fri, 18 Mar 2022 00:11:05 -0400 Subject: [PATCH 0192/1686] 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 0193/1686] 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 0194/1686] 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 0195/1686] 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 0196/1686] 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 0197/1686] 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 0198/1686] 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 0199/1686] 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 0200/1686] 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 0201/1686] 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 0202/1686] 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 0203/1686] 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 0204/1686] 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 0205/1686] 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 0206/1686] 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 0207/1686] 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 7ad2031b2fa81710fac83d96b021d4830d296ba7 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Tue, 22 Mar 2022 15:37:28 -0400 Subject: [PATCH 0208/1686] Now we have real multifrontal! --- ...ianConditional.cpp => GaussianMixture.cpp} | 12 +- ...aussianConditional.h => GaussianMixture.h} | 16 +- gtsam/hybrid/HybridConditional.cpp | 24 ++- gtsam/hybrid/HybridConditional.h | 11 +- gtsam/hybrid/HybridFactor.cpp | 14 +- gtsam/hybrid/HybridFactor.h | 8 +- gtsam/hybrid/HybridFactorGraph.cpp | 92 ++++++++--- gtsam/hybrid/HybridJunctionTree.cpp | 152 +++++++++++++++++- gtsam/hybrid/tests/testHybridConditional.cpp | 83 ++++++++-- gtsam/inference/JunctionTree.h | 2 +- 10 files changed, 360 insertions(+), 54 deletions(-) rename gtsam/hybrid/{CLGaussianConditional.cpp => GaussianMixture.cpp} (83%) rename gtsam/hybrid/{CLGaussianConditional.h => GaussianMixture.h} (74%) diff --git a/gtsam/hybrid/CLGaussianConditional.cpp b/gtsam/hybrid/GaussianMixture.cpp similarity index 83% rename from gtsam/hybrid/CLGaussianConditional.cpp rename to gtsam/hybrid/GaussianMixture.cpp index 30531c023..6af5f7192 100644 --- a/gtsam/hybrid/CLGaussianConditional.cpp +++ b/gtsam/hybrid/GaussianMixture.cpp @@ -10,7 +10,7 @@ * -------------------------------------------------------------------------- */ /** - * @file CLGaussianConditional.cpp + * @file GaussianMixture.cpp * @brief A hybrid conditional in the Conditional Linear Gaussian scheme * @author Fan Jiang * @date Mar 12, 2022 @@ -18,25 +18,25 @@ #include #include -#include +#include #include namespace gtsam { -CLGaussianConditional::CLGaussianConditional( +GaussianMixture::GaussianMixture( const KeyVector &continuousFrontals, const KeyVector &continuousParents, const DiscreteKeys &discreteParents, - const CLGaussianConditional::Conditionals &conditionals) + const GaussianMixture::Conditionals &conditionals) : BaseFactor(CollectKeys(continuousFrontals, continuousParents), discreteParents), BaseConditional(continuousFrontals.size()), conditionals_(conditionals) {} -bool CLGaussianConditional::equals(const HybridFactor &lf, double tol) const { +bool GaussianMixture::equals(const HybridFactor &lf, double tol) const { return false; } -void CLGaussianConditional::print(const std::string &s, +void GaussianMixture::print(const std::string &s, const KeyFormatter &formatter) const { std::cout << s << ": "; if (isContinuous_) std::cout << "Cont. "; diff --git a/gtsam/hybrid/CLGaussianConditional.h b/gtsam/hybrid/GaussianMixture.h similarity index 74% rename from gtsam/hybrid/CLGaussianConditional.h rename to gtsam/hybrid/GaussianMixture.h index d80cb804f..541a2b8a6 100644 --- a/gtsam/hybrid/CLGaussianConditional.h +++ b/gtsam/hybrid/GaussianMixture.h @@ -10,7 +10,7 @@ * -------------------------------------------------------------------------- */ /** - * @file CLGaussianConditional.h + * @file GaussianMixture.h * @brief A hybrid conditional in the Conditional Linear Gaussian scheme * @author Fan Jiang * @date Mar 12, 2022 @@ -24,21 +24,21 @@ #include namespace gtsam { -class CLGaussianConditional +class GaussianMixture : public HybridFactor, - public Conditional { + public Conditional { public: - using This = CLGaussianConditional; - using shared_ptr = boost::shared_ptr; + using This = GaussianMixture; + using shared_ptr = boost::shared_ptr; using BaseFactor = HybridFactor; - using BaseConditional = Conditional; + using BaseConditional = Conditional; using Conditionals = DecisionTree; Conditionals conditionals_; public: - CLGaussianConditional(const KeyVector &continuousFrontals, + GaussianMixture(const KeyVector &continuousFrontals, const KeyVector &continuousParents, const DiscreteKeys &discreteParents, const Conditionals &conditionals); @@ -46,7 +46,7 @@ class CLGaussianConditional bool equals(const HybridFactor &lf, double tol = 1e-9) const override; void print( - const std::string &s = "CLGaussianConditional\n", + const std::string &s = "GaussianMixture\n", const KeyFormatter &formatter = DefaultKeyFormatter) const override; }; } // namespace gtsam \ No newline at end of file diff --git a/gtsam/hybrid/HybridConditional.cpp b/gtsam/hybrid/HybridConditional.cpp index 5cb98d921..e212f4534 100644 --- a/gtsam/hybrid/HybridConditional.cpp +++ b/gtsam/hybrid/HybridConditional.cpp @@ -19,9 +19,31 @@ #include namespace gtsam { + +HybridConditional::HybridConditional(const KeyVector &continuousFrontals, + const DiscreteKeys &discreteFrontals, + const KeyVector &continuousParents, + const DiscreteKeys &discreteParents) + : HybridConditional( + CollectKeys({continuousFrontals.begin(), continuousFrontals.end()}, + {continuousParents.begin(), continuousParents.end()}), + CollectDiscreteKeys( + {discreteFrontals.begin(), discreteFrontals.end()}, + {discreteParents.begin(), discreteParents.end()}), + continuousFrontals.size() + discreteFrontals.size()) {} + +HybridConditional::HybridConditional( + boost::shared_ptr continuousConditional) + : BaseFactor(continuousConditional->keys()), + BaseConditional(continuousConditional->nrFrontals()) {} + void HybridConditional::print(const std::string &s, const KeyFormatter &formatter) const { - std::cout << s << "P("; + std::cout << s; + if (isContinuous_) std::cout << "Cont. "; + if (isDiscrete_) std::cout << "Disc. "; + if (isHybrid_) std::cout << "Hybr. "; + std::cout << "P("; int index = 0; const size_t N = keys().size(); const size_t contN = N - discreteKeys_.size(); diff --git a/gtsam/hybrid/HybridConditional.h b/gtsam/hybrid/HybridConditional.h index 89071092f..d851cd68e 100644 --- a/gtsam/hybrid/HybridConditional.h +++ b/gtsam/hybrid/HybridConditional.h @@ -25,6 +25,8 @@ #include #include #include +#include "gtsam/inference/Key.h" +#include "gtsam/linear/GaussianConditional.h" namespace gtsam { @@ -33,8 +35,8 @@ namespace gtsam { * * As a type-erased variant of: * - DiscreteConditional - * - CLGaussianConditional * - GaussianConditional + * - GaussianMixture */ class GTSAM_EXPORT HybridConditional : public HybridFactor, @@ -62,6 +64,13 @@ class GTSAM_EXPORT HybridConditional const DiscreteKeys& discreteKeys, size_t nFrontals) : BaseFactor(continuousKeys, discreteKeys), BaseConditional(nFrontals) {} + HybridConditional(const KeyVector& continuousFrontals, + const DiscreteKeys& discreteFrontals, + const KeyVector& continuousParents, + const DiscreteKeys& discreteParents); + + HybridConditional(boost::shared_ptr continuousConditional); + /** * @brief Combine two conditionals, yielding a new conditional with the union * of the frontal keys, ordered by gtsam::Key. diff --git a/gtsam/hybrid/HybridFactor.cpp b/gtsam/hybrid/HybridFactor.cpp index f16092eff..48a9dc468 100644 --- a/gtsam/hybrid/HybridFactor.cpp +++ b/gtsam/hybrid/HybridFactor.cpp @@ -53,7 +53,9 @@ HybridFactor::HybridFactor(const KeyVector &keys) HybridFactor::HybridFactor(const KeyVector &continuousKeys, const DiscreteKeys &discreteKeys) : Base(CollectKeys(continuousKeys, discreteKeys)), - isHybrid_(true), + isDiscrete_((continuousKeys.size() == 0) && (discreteKeys.size() != 0)), + isContinuous_((continuousKeys.size() != 0) && (discreteKeys.size() == 0)), + isHybrid_((continuousKeys.size() != 0) && (discreteKeys.size() != 0)), discreteKeys_(discreteKeys) {} HybridFactor::HybridFactor(const DiscreteKeys &discreteKeys) @@ -61,6 +63,16 @@ HybridFactor::HybridFactor(const DiscreteKeys &discreteKeys) isDiscrete_(true), discreteKeys_(discreteKeys) {} +void HybridFactor::print( + const std::string &s, + const KeyFormatter &formatter) const { + std::cout << s; + if (isContinuous_) std::cout << "Cont. "; + if (isDiscrete_) std::cout << "Disc. "; + if (isHybrid_) std::cout << "Hybr. "; + this->printKeys("", formatter); +} + HybridFactor::~HybridFactor() = default; } // namespace gtsam \ No newline at end of file diff --git a/gtsam/hybrid/HybridFactor.h b/gtsam/hybrid/HybridFactor.h index cd562869e..84d9b71bc 100644 --- a/gtsam/hybrid/HybridFactor.h +++ b/gtsam/hybrid/HybridFactor.h @@ -82,13 +82,7 @@ class GTSAM_EXPORT HybridFactor : public Factor { /// print void print( const std::string &s = "HybridFactor\n", - const KeyFormatter &formatter = DefaultKeyFormatter) const override { - std::cout << s; - if (isContinuous_) std::cout << "Cont. "; - if (isDiscrete_) std::cout << "Disc. "; - if (isHybrid_) std::cout << "Hybr. "; - this->printKeys("", formatter); - } + const KeyFormatter &formatter = DefaultKeyFormatter) const override; /// @} /// @name Standard Interface diff --git a/gtsam/hybrid/HybridFactorGraph.cpp b/gtsam/hybrid/HybridFactorGraph.cpp index 7d4daaceb..367f9f9ab 100644 --- a/gtsam/hybrid/HybridFactorGraph.cpp +++ b/gtsam/hybrid/HybridFactorGraph.cpp @@ -26,8 +26,11 @@ #include #include +#include #include "gtsam/inference/Key.h" +#include "gtsam/linear/GaussianFactorGraph.h" +#include "gtsam/linear/HessianFactor.h" namespace gtsam { @@ -60,6 +63,28 @@ EliminateHybrid(const HybridFactorGraph &factors, const Ordering &frontalKeys) { // In the case of multifrontal, we will need to use a constrained ordering // so that the discrete parts will be guaranteed to be eliminated last! + // Because of all these reasons, we need to think very carefully about how to + // implement the hybrid factors so that we do not get poor performance. + // + // The first thing is how to represent the GaussianMixture. A very possible + // scenario is that the incoming factors will have different levels of discrete + // keys. For example, imagine we are going to eliminate the fragment: + // $\phi(x1,c1,c2)$, $\phi(x1,c2,c3)$, which is perfectly valid. Now we will need + // to know how to retrieve the corresponding continuous densities for the assi- + // -gnment (c1,c2,c3) (OR (c2,c3,c1)! note there is NO defined order!). And we + // also need to consider when there is pruning. Two mixture factors could have + // different pruning patterns-one could have (c1=0,c2=1) pruned, and another + // could have (c2=0,c3=1) pruned, and this creates a big problem in how to + // identify the intersection of non-pruned branches. + + // One possible approach is first building the collection of all discrete keys. + // After that we enumerate the space of all key combinations *lazily* so that + // the exploration branch terminates whenever an assignment yields NULL in any + // of the hybrid factors. + + // When the number of assignments is large we may encounter stack overflows. + // However this is also the case with iSAM2, so no pressure :) + // PREPROCESS: Identify the nature of the current elimination std::unordered_map discreteCardinalities; std::set discreteSeparator; @@ -110,31 +135,62 @@ EliminateHybrid(const HybridFactorGraph &factors, const Ordering &frontalKeys) { } } - std::cout << RED_BOLD << "Keys: " << RESET; - for (auto &f : frontalKeys) { - if (discreteCardinalities.find(f) != discreteCardinalities.end()) { - auto &key = discreteCardinalities.at(f); - std::cout << boost::format(" (%1%,%2%),") % - DefaultKeyFormatter(key.first) % key.second; - } else { - std::cout << " " << DefaultKeyFormatter(f) << ","; + { + std::cout << RED_BOLD << "Keys: " << RESET; + for (auto &f : frontalKeys) { + if (discreteCardinalities.find(f) != discreteCardinalities.end()) { + auto &key = discreteCardinalities.at(f); + std::cout << boost::format(" (%1%,%2%),") % + DefaultKeyFormatter(key.first) % key.second; + } else { + std::cout << " " << DefaultKeyFormatter(f) << ","; + } } + + if (separatorKeys.size() > 0) { + std::cout << " | "; + } + + for (auto &f : separatorKeys) { + if (discreteCardinalities.find(f) != discreteCardinalities.end()) { + auto &key = discreteCardinalities.at(f); + std::cout << boost::format(" (%1%,%2%),") % + DefaultKeyFormatter(key.first) % key.second; + } else { + std::cout << DefaultKeyFormatter(f) << ","; + } + } + std::cout << "\n" << RESET; } - if (separatorKeys.size() > 0) { - std::cout << " | "; + // NOTE: We should really defer the product here because of pruning + + // Case 1: we are only dealing with continuous + if (discreteCardinalities.empty()) { + GaussianFactorGraph gfg; + for (auto &fp : factors) { + gfg.push_back(boost::static_pointer_cast(fp)->inner); + } + + auto result = EliminatePreferCholesky(gfg, frontalKeys); + return std::make_pair( + boost::make_shared(result.first), + boost::make_shared(result.second)); } - for (auto &f : separatorKeys) { - if (discreteCardinalities.find(f) != discreteCardinalities.end()) { - auto &key = discreteCardinalities.at(f); - std::cout << boost::format(" (%1%,%2%),") % - DefaultKeyFormatter(key.first) % key.second; - } else { - std::cout << DefaultKeyFormatter(f) << ","; + // Case 2: we are only dealing with discrete + if (discreteCardinalities.empty()) { + GaussianFactorGraph gfg; + for (auto &fp : factors) { + gfg.push_back(boost::static_pointer_cast(fp)->inner); } + + auto result = EliminatePreferCholesky(gfg, frontalKeys); + return std::make_pair( + boost::make_shared(result.first), + boost::make_shared(result.second)); } - std::cout << "\n" << RESET; + // PRODUCT: multiply all factors gttic(product); diff --git a/gtsam/hybrid/HybridJunctionTree.cpp b/gtsam/hybrid/HybridJunctionTree.cpp index 9da1bfed3..9445e26b8 100644 --- a/gtsam/hybrid/HybridJunctionTree.cpp +++ b/gtsam/hybrid/HybridJunctionTree.cpp @@ -19,15 +19,163 @@ #include #include +#include + +#include "gtsam/hybrid/HybridFactorGraph.h" +#include "gtsam/inference/Key.h" + namespace gtsam { // Instantiate base classes template class EliminatableClusterTree; template class JunctionTree; +struct HybridConstructorTraversalData { + typedef typename JunctionTree::Node Node; + typedef typename JunctionTree::sharedNode + sharedNode; + + HybridConstructorTraversalData* const parentData; + sharedNode myJTNode; + FastVector childSymbolicConditionals; + FastVector childSymbolicFactors; + KeySet discreteKeys; + + // Small inner class to store symbolic factors + class SymbolicFactors : public FactorGraph {}; + + HybridConstructorTraversalData(HybridConstructorTraversalData* _parentData) + : parentData(_parentData) {} + + // Pre-order visitor function + static HybridConstructorTraversalData ConstructorTraversalVisitorPre( + const boost::shared_ptr& node, + HybridConstructorTraversalData& parentData) { + // On the pre-order pass, before children have been visited, we just set up + // a traversal data structure with its own JT node, and create a child + // pointer in its parent. + HybridConstructorTraversalData myData = + HybridConstructorTraversalData(&parentData); + myData.myJTNode = boost::make_shared(node->key, node->factors); + parentData.myJTNode->addChild(myData.myJTNode); + + std::cout << "Getting discrete info: "; + for (HybridFactor::shared_ptr& f : node->factors) { + for (auto& k : f->discreteKeys_) { + std::cout << "DK: " << DefaultKeyFormatter(k.first) << "\n"; + myData.discreteKeys.insert(k.first); + } + } + + return myData; + } + + // Post-order visitor function + static void ConstructorTraversalVisitorPostAlg2( + const boost::shared_ptr& ETreeNode, + const HybridConstructorTraversalData& myData) { + // In this post-order visitor, we combine the symbolic elimination results + // from the elimination tree children and symbolically eliminate the current + // elimination tree node. We then check whether each of our elimination + // tree child nodes should be merged with us. The check for this is that + // our number of symbolic elimination parents is exactly 1 less than + // our child's symbolic elimination parents - this condition indicates that + // eliminating the current node did not introduce any parents beyond those + // already in the child-> + + // Do symbolic elimination for this node + SymbolicFactors symbolicFactors; + symbolicFactors.reserve(ETreeNode->factors.size() + + myData.childSymbolicFactors.size()); + // Add ETree node factors + symbolicFactors += ETreeNode->factors; + // Add symbolic factors passed up from children + symbolicFactors += myData.childSymbolicFactors; + + Ordering keyAsOrdering; + keyAsOrdering.push_back(ETreeNode->key); + SymbolicConditional::shared_ptr myConditional; + SymbolicFactor::shared_ptr mySeparatorFactor; + boost::tie(myConditional, mySeparatorFactor) = + internal::EliminateSymbolic(symbolicFactors, keyAsOrdering); + + std::cout << "Symbolic: "; + myConditional->print(); + + // Store symbolic elimination results in the parent + myData.parentData->childSymbolicConditionals.push_back(myConditional); + myData.parentData->childSymbolicFactors.push_back(mySeparatorFactor); + myData.parentData->discreteKeys.merge(myData.discreteKeys); + + sharedNode node = myData.myJTNode; + const FastVector& childConditionals = + myData.childSymbolicConditionals; + node->problemSize_ = (int)(myConditional->size() * symbolicFactors.size()); + + // Merge our children if they are in our clique - if our conditional has + // exactly one fewer parent than our child's conditional. + const size_t myNrParents = myConditional->nrParents(); + const size_t nrChildren = node->nrChildren(); + assert(childConditionals.size() == nrChildren); + + // decide which children to merge, as index into children + std::vector nrFrontals = node->nrFrontalsOfChildren(); + std::vector merge(nrChildren, false); + size_t myNrFrontals = 1; + for (size_t i = 0; i < nrChildren; i++) { + // Check if we should merge the i^th child + if (myNrParents + myNrFrontals == childConditionals[i]->nrParents()) { + const bool myType = + myData.discreteKeys.exists(myConditional->frontals()[0]); + const bool theirType = + myData.discreteKeys.exists(childConditionals[i]->frontals()[0]); + std::cout << "Type: " + << DefaultKeyFormatter(myConditional->frontals()[0]) << " vs " + << DefaultKeyFormatter(childConditionals[i]->frontals()[0]) + << "\n"; + if (myType == theirType) { + // Increment number of frontal variables + myNrFrontals += nrFrontals[i]; + std::cout << "Merging "; + childConditionals[i]->print(); + merge[i] = true; + } + } + } + + // now really merge + node->mergeChildren(merge); + } +}; + /* ************************************************************************* */ HybridJunctionTree::HybridJunctionTree( - const HybridEliminationTree& eliminationTree) - : Base(eliminationTree) {} + const HybridEliminationTree& eliminationTree) { + gttic(JunctionTree_FromEliminationTree); + // Here we rely on the BayesNet having been produced by this elimination tree, + // such that the conditionals are arranged in DFS post-order. We traverse the + // elimination tree, and inspect the symbolic conditional corresponding to + // each node. The elimination tree node is added to the same clique with its + // parent if it has exactly one more Bayes net conditional parent than + // does its elimination tree parent. + + // Traverse the elimination tree, doing symbolic elimination and merging nodes + // as we go. Gather the created junction tree roots in a dummy Node. + typedef typename HybridEliminationTree::Node ETreeNode; + typedef HybridConstructorTraversalData Data; + Data rootData(0); + rootData.myJTNode = + boost::make_shared(); // Make a dummy node to gather + // the junction tree roots + treeTraversal::DepthFirstForest(eliminationTree, rootData, + Data::ConstructorTraversalVisitorPre, + Data::ConstructorTraversalVisitorPostAlg2); + + // Assign roots from the dummy node + this->addChildrenAsRoots(rootData.myJTNode); + + // Transfer remaining factors from elimination tree + Base::remainingFactors_ = eliminationTree.remainingFactors(); +} } // namespace gtsam diff --git a/gtsam/hybrid/tests/testHybridConditional.cpp b/gtsam/hybrid/tests/testHybridConditional.cpp index f945d0702..d16715300 100644 --- a/gtsam/hybrid/tests/testHybridConditional.cpp +++ b/gtsam/hybrid/tests/testHybridConditional.cpp @@ -18,7 +18,7 @@ #include #include #include -#include +#include #include #include #include @@ -31,6 +31,7 @@ #include #include +#include "gtsam/base/Testable.h" using namespace boost::assign; @@ -48,9 +49,9 @@ TEST(HybridFactorGraph, creation) { hfg.add(HybridGaussianFactor(JacobianFactor(0, I_3x3, Z_3x1))); - CLGaussianConditional clgc( + GaussianMixture clgc( {X(0)}, {X(1)}, DiscreteKeys(DiscreteKey{C(0), 2}), - CLGaussianConditional::Conditionals( + GaussianMixture::Conditionals( C(0), boost::make_shared(X(0), Z_3x1, I_3x3, X(1), I_3x3), @@ -69,7 +70,7 @@ TEST_DISABLED(HybridFactorGraph, eliminate) { EXPECT_LONGS_EQUAL(result.first->size(), 1); } -TEST_DISABLED(HybridFactorGraph, eliminateMultifrontal) { +TEST(HybridFactorGraph, eliminateMultifrontal) { HybridFactorGraph hfg; DiscreteKey x(X(1), 2); @@ -132,13 +133,77 @@ TEST(HybridFactorGraph, eliminateFullMultifrontalCLG) { // hfg.add(HybridDiscreteFactor(DecisionTreeFactor({{C(1), 2}, {C(2), 2}}, "1 // 2 3 4"))); - auto result = - hfg.eliminateMultifrontal(Ordering::ColamdConstrainedLast(hfg, {C(1)})); + auto ordering_full = Ordering::ColamdConstrainedLast(hfg, {C(1)}); - GTSAM_PRINT(*result); + HybridBayesTree::shared_ptr hbt = hfg.eliminateMultifrontal(ordering_full); - // We immediately need to escape the CLG domain if we do this!!! - GTSAM_PRINT(*result->marginalFactor(X(1))); + GTSAM_PRINT(*hbt); + /* + Explanation: the Junction tree will need to reeliminate to get to the marginal + on X(1), which is not possible because it involves eliminating discrete before + continuous. The solution to this, however, is in Murphy02. TLDR is that this + is 1. expensive and 2. inexact. neverless it is doable. And I believe that we + should do this. + */ +} + +/** + * This test is about how to assemble the Bayes Tree roots after we do partial elimination +*/ +TEST_DISABLED(HybridFactorGraph, eliminateFullMultifrontalTwoClique) { + std::cout << ">>>>>>>>>>>>>>\n"; + + HybridFactorGraph hfg; + + hfg.add(JacobianFactor(X(0), I_3x3, X(1), -I_3x3, Z_3x1)); + hfg.add(JacobianFactor(X(1), I_3x3, X(2), -I_3x3, Z_3x1)); + + { + DecisionTree dt( + C(0), boost::make_shared(X(0), I_3x3, Z_3x1), + boost::make_shared(X(0), I_3x3, Vector3::Ones())); + + hfg.add(CGMixtureFactor({X(0)}, {{C(0), 2}}, dt)); + + DecisionTree dt1( + C(1), boost::make_shared(X(2), I_3x3, Z_3x1), + boost::make_shared(X(2), I_3x3, Vector3::Ones())); + + hfg.add(CGMixtureFactor({X(2)}, {{C(1), 2}}, dt1)); + } + + // hfg.add(HybridDiscreteFactor(DecisionTreeFactor(c, {2, 8}))); + hfg.add(HybridDiscreteFactor(DecisionTreeFactor({{C(1), 2}, {C(2), 2}}, "1 2 3 4"))); + + hfg.add(JacobianFactor(X(3), I_3x3, X(4), -I_3x3, Z_3x1)); + hfg.add(JacobianFactor(X(4), I_3x3, X(5), -I_3x3, Z_3x1)); + + { + DecisionTree dt( + C(3), boost::make_shared(X(3), I_3x3, Z_3x1), + boost::make_shared(X(3), I_3x3, Vector3::Ones())); + + hfg.add(CGMixtureFactor({X(3)}, {{C(3), 2}}, dt)); + + DecisionTree dt1( + C(2), boost::make_shared(X(5), I_3x3, Z_3x1), + boost::make_shared(X(5), I_3x3, Vector3::Ones())); + + hfg.add(CGMixtureFactor({X(5)}, {{C(2), 2}}, dt1)); + } + + auto ordering_full = Ordering::ColamdConstrainedLast(hfg, {C(0), C(1), C(2), C(3)}); + + GTSAM_PRINT(ordering_full); + + HybridBayesTree::shared_ptr hbt; + HybridFactorGraph::shared_ptr remaining; + std::tie(hbt, remaining) = + hfg.eliminatePartialMultifrontal(Ordering(ordering_full.begin(), ordering_full.end())); + + GTSAM_PRINT(*hbt); + + GTSAM_PRINT(*remaining); /* Explanation: the Junction tree will need to reeliminate to get to the marginal on X(1), which is not possible because it involves eliminating discrete before diff --git a/gtsam/inference/JunctionTree.h b/gtsam/inference/JunctionTree.h index e01f3721a..e914c325e 100644 --- a/gtsam/inference/JunctionTree.h +++ b/gtsam/inference/JunctionTree.h @@ -70,7 +70,7 @@ namespace gtsam { /// @} - private: + protected: // Private default constructor (used in static construction methods) JunctionTree() {} From 7b0356cbea59c3660c8e85e81f07917b007d0e9c Mon Sep 17 00:00:00 2001 From: lcarlone Date: Tue, 22 Mar 2022 20:40:08 -0400 Subject: [PATCH 0209/1686] edited --- gtsam/nonlinear/GncOptimizer.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/gtsam/nonlinear/GncOptimizer.h b/gtsam/nonlinear/GncOptimizer.h index c5c5d1883..96b03e803 100644 --- a/gtsam/nonlinear/GncOptimizer.h +++ b/gtsam/nonlinear/GncOptimizer.h @@ -447,11 +447,11 @@ class GTSAM_EXPORT GncOptimizer { return weights; } case GncLossType::TLS: { // use eq (14) in GNC paper - double upperbound = (mu + 1) / mu * barcSq_.maxCoeff(); - double lowerbound = mu / (mu + 1) * barcSq_.minCoeff(); for (size_t k : unknownWeights) { if (nfg_[k]) { double u2_k = nfg_[k]->error(currentEstimate); // squared (and whitened) residual + double upperbound = (mu + 1) / mu * barcSq_[k]; + double lowerbound = mu / (mu + 1) * barcSq_[k]; weights[k] = std::sqrt(barcSq_[k] * mu * (mu + 1) / u2_k) - mu; if (u2_k >= upperbound || weights[k] < 0) { weights[k] = 0; From d42fc214176fb8ced3436edc4c9662dc2f1ef65a Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Wed, 23 Mar 2022 20:16:05 -0400 Subject: [PATCH 0210/1686] Fully working Multifrontal --- gtsam/hybrid/CGMixtureFactor.cpp | 27 ++ gtsam/hybrid/CGMixtureFactor.h | 12 + gtsam/hybrid/GaussianMixture.cpp | 27 ++ gtsam/hybrid/GaussianMixture.h | 10 + gtsam/hybrid/HybridConditional.cpp | 29 +- gtsam/hybrid/HybridConditional.h | 43 +-- gtsam/hybrid/HybridDiscreteFactor.cpp | 5 +- gtsam/hybrid/HybridFactor.cpp | 3 +- gtsam/hybrid/HybridFactor.h | 3 + gtsam/hybrid/HybridFactorGraph.cpp | 345 +++++++++++++++---- gtsam/hybrid/tests/testHybridConditional.cpp | 56 +-- 11 files changed, 454 insertions(+), 106 deletions(-) diff --git a/gtsam/hybrid/CGMixtureFactor.cpp b/gtsam/hybrid/CGMixtureFactor.cpp index 705160273..08ae8b6e9 100644 --- a/gtsam/hybrid/CGMixtureFactor.cpp +++ b/gtsam/hybrid/CGMixtureFactor.cpp @@ -20,7 +20,9 @@ #include +#include #include +#include #include namespace gtsam { @@ -47,4 +49,29 @@ void CGMixtureFactor::print(const std::string &s, const KeyFormatter &formatter) }); } +const CGMixtureFactor::Factors& CGMixtureFactor::factors() { + return factors_; +} + +/* *******************************************************************************/ +CGMixtureFactor::Sum CGMixtureFactor::addTo(const CGMixtureFactor::Sum &sum) const { + using Y = GaussianFactorGraph; + auto add = [](const Y &graph1, const Y &graph2) { + auto result = graph1; + result.push_back(graph2); + return result; + }; + const Sum wrapped = wrappedFactors(); + return sum.empty() ? wrapped : sum.apply(wrapped, add); +} + +/* *******************************************************************************/ +CGMixtureFactor::Sum CGMixtureFactor::wrappedFactors() const { + auto wrap = [](const GaussianFactor::shared_ptr &factor) { + GaussianFactorGraph result; + result.push_back(factor); + return result; + }; + return {factors_, wrap}; +} } \ No newline at end of file diff --git a/gtsam/hybrid/CGMixtureFactor.h b/gtsam/hybrid/CGMixtureFactor.h index 556c53cc5..fd81cdd91 100644 --- a/gtsam/hybrid/CGMixtureFactor.h +++ b/gtsam/hybrid/CGMixtureFactor.h @@ -27,6 +27,8 @@ namespace gtsam { +class GaussianFactorGraph; + class CGMixtureFactor : public HybridFactor { public: using Base = HybridFactor; @@ -42,6 +44,16 @@ class CGMixtureFactor : public HybridFactor { CGMixtureFactor(const KeyVector &continuousKeys, const DiscreteKeys &discreteKeys, const Factors &factors); + using Sum = DecisionTree; + + const Factors& factors(); + + /* *******************************************************************************/ + Sum addTo(const Sum &sum) const; + + /* *******************************************************************************/ + Sum wrappedFactors() const; + bool equals(const HybridFactor &lf, double tol = 1e-9) const override; void print( diff --git a/gtsam/hybrid/GaussianMixture.cpp b/gtsam/hybrid/GaussianMixture.cpp index 6af5f7192..8135b2d2d 100644 --- a/gtsam/hybrid/GaussianMixture.cpp +++ b/gtsam/hybrid/GaussianMixture.cpp @@ -20,6 +20,7 @@ #include #include #include +#include namespace gtsam { @@ -32,6 +33,32 @@ GaussianMixture::GaussianMixture( BaseConditional(continuousFrontals.size()), conditionals_(conditionals) {} +const GaussianMixture::Conditionals& GaussianMixture::conditionals() { + return conditionals_; +} + +/* *******************************************************************************/ +GaussianMixture::Sum GaussianMixture::addTo(const GaussianMixture::Sum &sum) const { + using Y = GaussianFactorGraph; + auto add = [](const Y &graph1, const Y &graph2) { + auto result = graph1; + result.push_back(graph2); + return result; + }; + const Sum wrapped = wrappedConditionals(); + return sum.empty() ? wrapped : sum.apply(wrapped, add); +} + +/* *******************************************************************************/ +GaussianMixture::Sum GaussianMixture::wrappedConditionals() const { + auto wrap = [](const GaussianFactor::shared_ptr &factor) { + GaussianFactorGraph result; + result.push_back(factor); + return result; + }; + return {conditionals_, wrap}; +} + bool GaussianMixture::equals(const HybridFactor &lf, double tol) const { return false; } diff --git a/gtsam/hybrid/GaussianMixture.h b/gtsam/hybrid/GaussianMixture.h index 541a2b8a6..13171ae5d 100644 --- a/gtsam/hybrid/GaussianMixture.h +++ b/gtsam/hybrid/GaussianMixture.h @@ -43,6 +43,16 @@ class GaussianMixture const DiscreteKeys &discreteParents, const Conditionals &conditionals); + using Sum = DecisionTree; + + const Conditionals& conditionals(); + + /* *******************************************************************************/ + Sum addTo(const Sum &sum) const; + + /* *******************************************************************************/ + Sum wrappedConditionals() const; + bool equals(const HybridFactor &lf, double tol = 1e-9) const override; void print( diff --git a/gtsam/hybrid/HybridConditional.cpp b/gtsam/hybrid/HybridConditional.cpp index e212f4534..7ada061b9 100644 --- a/gtsam/hybrid/HybridConditional.cpp +++ b/gtsam/hybrid/HybridConditional.cpp @@ -17,6 +17,8 @@ #include #include +#include "gtsam/hybrid/HybridFactor.h" +#include "gtsam/inference/Key.h" namespace gtsam { @@ -34,8 +36,27 @@ HybridConditional::HybridConditional(const KeyVector &continuousFrontals, HybridConditional::HybridConditional( boost::shared_ptr continuousConditional) - : BaseFactor(continuousConditional->keys()), - BaseConditional(continuousConditional->nrFrontals()) {} + : HybridConditional(continuousConditional->keys(), {}, + continuousConditional->nrFrontals()) { + inner = continuousConditional; +} + +HybridConditional::HybridConditional( + boost::shared_ptr discreteConditional) + : HybridConditional({}, discreteConditional->discreteKeys(), + discreteConditional->nrFrontals()) { + inner = discreteConditional; +} + +HybridConditional::HybridConditional( + boost::shared_ptr gaussianMixture) + : BaseFactor(KeyVector(gaussianMixture->keys().begin(), + gaussianMixture->keys().begin() + + gaussianMixture->nrContinuous), + gaussianMixture->discreteKeys_), + BaseConditional(gaussianMixture->nrFrontals()) { + inner = gaussianMixture; +} void HybridConditional::print(const std::string &s, const KeyFormatter &formatter) const { @@ -70,8 +91,4 @@ bool HybridConditional::equals(const HybridFactor &other, double tol) const { return false; } -HybridConditional HybridConditional::operator*( - const HybridConditional &other) const { - return {}; -} } // namespace gtsam diff --git a/gtsam/hybrid/HybridConditional.h b/gtsam/hybrid/HybridConditional.h index d851cd68e..5fdf5064a 100644 --- a/gtsam/hybrid/HybridConditional.h +++ b/gtsam/hybrid/HybridConditional.h @@ -23,13 +23,20 @@ #include #include +#include #include +#include #include -#include "gtsam/inference/Key.h" -#include "gtsam/linear/GaussianConditional.h" +#include "gtsam/hybrid/GaussianMixture.h" + +#include +#include +#include namespace gtsam { +class HybridFactorGraph; + /** * Hybrid Conditional Density * @@ -49,9 +56,9 @@ class GTSAM_EXPORT HybridConditional typedef Conditional BaseConditional; ///< Typedef to our conditional base class - private: + protected: // Type-erased pointer to the inner type - std::unique_ptr inner; + boost::shared_ptr inner; public: /// @name Standard Constructors @@ -70,23 +77,15 @@ class GTSAM_EXPORT HybridConditional const DiscreteKeys& discreteParents); HybridConditional(boost::shared_ptr continuousConditional); + + HybridConditional(boost::shared_ptr discreteConditional); - /** - * @brief Combine two conditionals, yielding a new conditional with the union - * of the frontal keys, ordered by gtsam::Key. - * - * The two conditionals must make a valid Bayes net fragment, i.e., - * the frontal variables cannot overlap, and must be acyclic: - * Example of correct use: - * P(A,B) = P(A|B) * P(B) - * P(A,B|C) = P(A|B) * P(B|C) - * P(A,B,C) = P(A,B|C) * P(C) - * Example of incorrect use: - * P(A|B) * P(A|C) = ? - * P(A|B) * P(B|A) = ? - * We check for overlapping frontals, but do *not* check for cyclic. - */ - HybridConditional operator*(const HybridConditional& other) const; + HybridConditional(boost::shared_ptr gaussianMixture); + + GaussianMixture::shared_ptr asMixture() { + if (!isHybrid_) throw std::invalid_argument("Not a mixture"); + return boost::static_pointer_cast(inner); + } /// @} /// @name Testable @@ -101,6 +100,10 @@ class GTSAM_EXPORT HybridConditional bool equals(const HybridFactor& other, double tol = 1e-9) const override; /// @} + + friend std::pair // + EliminateHybrid(const HybridFactorGraph& factors, + const Ordering& frontalKeys); }; // DiscreteConditional diff --git a/gtsam/hybrid/HybridDiscreteFactor.cpp b/gtsam/hybrid/HybridDiscreteFactor.cpp index 96d3842b8..be5659f04 100644 --- a/gtsam/hybrid/HybridDiscreteFactor.cpp +++ b/gtsam/hybrid/HybridDiscreteFactor.cpp @@ -19,12 +19,15 @@ #include #include +#include "gtsam/discrete/DecisionTreeFactor.h" namespace gtsam { +// TODO(fan): THIS IS VERY VERY DIRTY! We need to get DiscreteFactor right! HybridDiscreteFactor::HybridDiscreteFactor(DiscreteFactor::shared_ptr other) - : Base(other->keys()) { + : Base(boost::dynamic_pointer_cast(other)->discreteKeys()) { inner = other; + } HybridDiscreteFactor::HybridDiscreteFactor(DecisionTreeFactor &&dtf) diff --git a/gtsam/hybrid/HybridFactor.cpp b/gtsam/hybrid/HybridFactor.cpp index 48a9dc468..a5ce8bd4e 100644 --- a/gtsam/hybrid/HybridFactor.cpp +++ b/gtsam/hybrid/HybridFactor.cpp @@ -48,7 +48,7 @@ DiscreteKeys CollectDiscreteKeys(const DiscreteKeys &key1, HybridFactor::HybridFactor() = default; HybridFactor::HybridFactor(const KeyVector &keys) - : Base(keys), isContinuous_(true) {} + : Base(keys), isContinuous_(true), nrContinuous(keys.size()) {} HybridFactor::HybridFactor(const KeyVector &continuousKeys, const DiscreteKeys &discreteKeys) @@ -56,6 +56,7 @@ HybridFactor::HybridFactor(const KeyVector &continuousKeys, isDiscrete_((continuousKeys.size() == 0) && (discreteKeys.size() != 0)), isContinuous_((continuousKeys.size() != 0) && (discreteKeys.size() == 0)), isHybrid_((continuousKeys.size() != 0) && (discreteKeys.size() != 0)), + nrContinuous(continuousKeys.size()), discreteKeys_(discreteKeys) {} HybridFactor::HybridFactor(const DiscreteKeys &discreteKeys) diff --git a/gtsam/hybrid/HybridFactor.h b/gtsam/hybrid/HybridFactor.h index 84d9b71bc..653d4270a 100644 --- a/gtsam/hybrid/HybridFactor.h +++ b/gtsam/hybrid/HybridFactor.h @@ -22,6 +22,7 @@ #include #include +#include #include namespace gtsam { @@ -46,6 +47,8 @@ class GTSAM_EXPORT HybridFactor : public Factor { bool isContinuous_ = false; bool isHybrid_ = false; + size_t nrContinuous = 0; + DiscreteKeys discreteKeys_; public: diff --git a/gtsam/hybrid/HybridFactorGraph.cpp b/gtsam/hybrid/HybridFactorGraph.cpp index 367f9f9ab..735b8cfa9 100644 --- a/gtsam/hybrid/HybridFactorGraph.cpp +++ b/gtsam/hybrid/HybridFactorGraph.cpp @@ -13,9 +13,17 @@ * @file HybridFactorGraph.cpp * @brief Hybrid factor graph that uses type erasure * @author Fan Jiang + * @author Varun Agrawal + * @author Frank Dellaert * @date Mar 11, 2022 */ +#include +#include +#include +#include +#include +#include #include #include #include @@ -23,14 +31,20 @@ #include #include #include +#include +#include +#include +#include +#include +#include #include +#include +#include +#include #include #include - -#include "gtsam/inference/Key.h" -#include "gtsam/linear/GaussianFactorGraph.h" -#include "gtsam/linear/HessianFactor.h" +#include namespace gtsam { @@ -42,6 +56,26 @@ static std::string GREEN = "\033[0;32m"; static std::string GREEN_BOLD = "\033[1;32m"; static std::string RESET = "\033[0m"; +static CGMixtureFactor::Sum &addGaussian( + CGMixtureFactor::Sum &sum, const GaussianFactor::shared_ptr &factor) { + using Y = GaussianFactorGraph; + // If the decision tree is not intiialized, then intialize it. + if (sum.empty()) { + GaussianFactorGraph result; + result.push_back(factor); + sum = CGMixtureFactor::Sum(result); + + } else { + auto add = [&factor](const Y &graph) { + auto result = graph; + result.push_back(factor); + return result; + }; + sum = sum.apply(add); + } + return sum; +} + /* ************************************************************************ */ std::pair // EliminateHybrid(const HybridFactorGraph &factors, const Ordering &frontalKeys) { @@ -65,29 +99,29 @@ EliminateHybrid(const HybridFactorGraph &factors, const Ordering &frontalKeys) { // Because of all these reasons, we need to think very carefully about how to // implement the hybrid factors so that we do not get poor performance. - // + // // The first thing is how to represent the GaussianMixture. A very possible - // scenario is that the incoming factors will have different levels of discrete - // keys. For example, imagine we are going to eliminate the fragment: - // $\phi(x1,c1,c2)$, $\phi(x1,c2,c3)$, which is perfectly valid. Now we will need - // to know how to retrieve the corresponding continuous densities for the assi- - // -gnment (c1,c2,c3) (OR (c2,c3,c1)! note there is NO defined order!). And we - // also need to consider when there is pruning. Two mixture factors could have - // different pruning patterns-one could have (c1=0,c2=1) pruned, and another - // could have (c2=0,c3=1) pruned, and this creates a big problem in how to - // identify the intersection of non-pruned branches. + // scenario is that the incoming factors will have different levels of + // discrete keys. For example, imagine we are going to eliminate the fragment: + // $\phi(x1,c1,c2)$, $\phi(x1,c2,c3)$, which is perfectly valid. Now we will + // need to know how to retrieve the corresponding continuous densities for the + // assi- -gnment (c1,c2,c3) (OR (c2,c3,c1)! note there is NO defined order!). + // And we also need to consider when there is pruning. Two mixture factors + // could have different pruning patterns-one could have (c1=0,c2=1) pruned, + // and another could have (c2=0,c3=1) pruned, and this creates a big problem + // in how to identify the intersection of non-pruned branches. - // One possible approach is first building the collection of all discrete keys. - // After that we enumerate the space of all key combinations *lazily* so that - // the exploration branch terminates whenever an assignment yields NULL in any - // of the hybrid factors. + // One possible approach is first building the collection of all discrete + // keys. After that we enumerate the space of all key combinations *lazily* so + // that the exploration branch terminates whenever an assignment yields NULL + // in any of the hybrid factors. // When the number of assignments is large we may encounter stack overflows. // However this is also the case with iSAM2, so no pressure :) // PREPROCESS: Identify the nature of the current elimination std::unordered_map discreteCardinalities; - std::set discreteSeparator; + std::set discreteSeparatorSet; std::set discreteFrontals; KeySet separatorKeys; @@ -123,15 +157,17 @@ EliminateHybrid(const HybridFactorGraph &factors, const Ordering &frontalKeys) { discreteFrontals.insert(discreteCardinalities.at(k)); } else { continuousFrontals.insert(k); + allContinuousKeys.insert(k); } } // Fill in discrete frontals and continuous frontals for the end result for (auto &k : separatorKeys) { if (discreteCardinalities.find(k) != discreteCardinalities.end()) { - discreteSeparator.insert(discreteCardinalities.at(k)); + discreteSeparatorSet.insert(discreteCardinalities.at(k)); } else { continuousSeparator.insert(k); + allContinuousKeys.insert(k); } } @@ -164,12 +200,18 @@ EliminateHybrid(const HybridFactorGraph &factors, const Ordering &frontalKeys) { } // NOTE: We should really defer the product here because of pruning - + // Case 1: we are only dealing with continuous - if (discreteCardinalities.empty()) { + if (discreteCardinalities.empty() && !allContinuousKeys.empty()) { + std::cout << RED_BOLD << "CONT. ONLY" << RESET << "\n"; GaussianFactorGraph gfg; for (auto &fp : factors) { - gfg.push_back(boost::static_pointer_cast(fp)->inner); + auto ptr = boost::dynamic_pointer_cast(fp); + if (ptr) + gfg.push_back(ptr->inner); + else + gfg.push_back(boost::static_pointer_cast( + boost::static_pointer_cast(fp)->inner)); } auto result = EliminatePreferCholesky(gfg, frontalKeys); @@ -179,61 +221,248 @@ EliminateHybrid(const HybridFactorGraph &factors, const Ordering &frontalKeys) { } // Case 2: we are only dealing with discrete - if (discreteCardinalities.empty()) { - GaussianFactorGraph gfg; + if (allContinuousKeys.empty()) { + std::cout << RED_BOLD << "DISCRETE ONLY" << RESET << "\n"; + DiscreteFactorGraph dfg; for (auto &fp : factors) { - gfg.push_back(boost::static_pointer_cast(fp)->inner); + auto ptr = boost::dynamic_pointer_cast(fp); + if (ptr) + dfg.push_back(ptr->inner); + else + dfg.push_back(boost::static_pointer_cast( + boost::static_pointer_cast(fp)->inner)); } - auto result = EliminatePreferCholesky(gfg, frontalKeys); + auto result = EliminateDiscrete(dfg, frontalKeys); + return std::make_pair( boost::make_shared(result.first), - boost::make_shared(result.second)); + boost::make_shared(result.second)); } + // Case 3: We are now in the hybrid land! + // NOTE: since we use the special JunctionTree, only possiblity is cont. + // conditioned on disc. + DiscreteKeys discreteSeparator(discreteSeparatorSet.begin(), + discreteSeparatorSet.end()); + + // We will need to know a mapping on when will a factor be fully determined by + // discrete keys std::vector> + // availableFactors; + + // { + // std::vector> keysForFactor; + // keysForFactor.reserve(factors.size()); + // std::transform( + // factors.begin(), factors.end(), std::back_inserter(keysForFactor), + // [](HybridFactor::shared_ptr factor) + // -> std::pair { + // return {KeySet(factor->keys().begin() + factor->nrContinuous, + // factor->keys().end()), + // factor}; + // }); + + // KeySet currentAllKeys; + // const auto N = discreteSeparator.size(); + // for (size_t k = 0; k < N; k++) { + // currentAllKeys.insert(discreteSeparator.at(k).first); + // std::vector shouldRemove(N, false); + // for (size_t i = 0; i < keysForFactor.size(); i++) { + // availableFactors.emplace_back(); + + // if (std::includes(currentAllKeys.begin(), currentAllKeys.end(), + // keysForFactor[i].first.begin(), + // keysForFactor[i].first.end())) { + // // mark for delete + // shouldRemove[i] = true; + // availableFactors.back().push_back(keysForFactor[i].second); + // } + // keysForFactor.erase( + // std::remove_if(keysForFactor.begin(), keysForFactor.end(), + // [&shouldRemove, &keysForFactor](std::pair const &i) { + // return shouldRemove.at(&i - + // keysForFactor.data()); + // }), + // keysForFactor.end()); + // } + // } + // } + + // std::function>( + // (Assignment, GaussianFactorGraph, int))> + // visitor = [&](Assignment history, GaussianFactorGraph gf, int pos) + // -> boost::shared_ptr> { + // const auto currentKey = discreteSeparator[pos].first; + // const auto currentCard = discreteSeparator[pos].second; + + // std::vector>> + // children(currentCard, nullptr); + // for (size_t choice = 0; choice < currentCard; choice++) { + // Assignment new_assignment = history; + // GaussianFactorGraph new_gf(gf); + // // we try to get all currently available factors + // for (auto &factor : availableFactors[pos]) { + // if (!factor) { + // continue; + // } + + // auto ptr_mf = boost::dynamic_pointer_cast(factor); + // if (ptr_mf) gf.push_back(ptr_mf->factors_(new_assignment)); + + // auto ptr_gm = boost::dynamic_pointer_cast(factor); + // if (ptr_gm) gf.push_back(ptr_gm->conditionals_(new_assignment)); + + // children[choice] = visitor(new_assignment, new_gf, pos + 1); + // } + // } + // }; + // PRODUCT: multiply all factors - gttic(product); - - HybridConditional sum( - KeyVector(continuousSeparator.begin(), continuousSeparator.end()), - DiscreteKeys(discreteSeparator.begin(), discreteSeparator.end()), - separatorKeys.size()); - - // HybridDiscreteFactor product(DiscreteConditional()); - // for (auto&& factor : factors) product = (*factor) * product; - gttoc(product); + // HybridConditional sum_factor( + // KeyVector(continuousSeparator.begin(), continuousSeparator.end()), + // DiscreteKeys(discreteSeparatorSet.begin(), discreteSeparatorSet.end()), + // separatorKeys.size()); // sum out frontals, this is the factor on the separator gttic(sum); - // HybridFactor::shared_ptr sum = product.sum(frontalKeys); + + std::cout << RED_BOLD << "HYBRID ELIM." << RESET << "\n"; + + CGMixtureFactor::Sum sum; + + std::vector deferredFactors; + + for (auto &f : factors) { + if (f->isHybrid_) { + auto cgmf = boost::dynamic_pointer_cast(f); + if (cgmf) { + sum = cgmf->addTo(sum); + } + + auto gm = boost::dynamic_pointer_cast(f); + if (gm) { + sum = gm->asMixture()->addTo(sum); + } + + } else if (f->isContinuous_) { + deferredFactors.push_back( + boost::dynamic_pointer_cast(f)->inner); + } else { + throw std::invalid_argument( + "factor is discrete in continuous elimination"); + } + } + + for (auto &f : deferredFactors) { + std::cout << GREEN_BOLD << "Adding Gaussian" << RESET << "\n"; + sum = addGaussian(sum, f); + } + + std::cout << GREEN_BOLD << "[GFG Tree]\n" << RESET; + sum.print("", DefaultKeyFormatter, [](GaussianFactorGraph gfg) { + RedirectCout rd; + gfg.print(""); + return rd.str(); + }); + gttoc(sum); - // Ordering keys for the conditional so that frontalKeys are really in front - Ordering orderedKeys; - orderedKeys.insert(orderedKeys.end(), frontalKeys.begin(), frontalKeys.end()); - orderedKeys.insert(orderedKeys.end(), sum.keys().begin(), sum.keys().end()); + using EliminationPair = GaussianFactorGraph::EliminationResult; - // now divide product/sum to get conditional - gttic(divide); - // auto conditional = - // boost::make_shared(product, *sum, orderedKeys); - gttoc(divide); + KeyVector keysOfEliminated; // Not the ordering + KeyVector keysOfSeparator; // TODO(frank): Is this just (keys - ordering)? + + auto eliminate = [&](const GaussianFactorGraph &graph) + -> GaussianFactorGraph::EliminationResult { + if (graph.empty()) { + return {nullptr, nullptr}; + } + auto result = EliminatePreferCholesky(graph, frontalKeys); + if (keysOfEliminated.empty()) { + keysOfEliminated = + result.first->keys(); // Initialize the keysOfEliminated to be the + } + // keysOfEliminated of the GaussianConditional + if (keysOfSeparator.empty()) { + keysOfSeparator = result.second->keys(); + } + return result; + }; + + DecisionTree eliminationResults(sum, eliminate); + + auto pair = unzip(eliminationResults); + + const GaussianMixture::Conditionals &conditionals = pair.first; + const CGMixtureFactor::Factors &separatorFactors = pair.second; + + // Create the GaussianMixture from the conditionals + auto conditional = boost::make_shared( + frontalKeys, keysOfSeparator, discreteSeparator, conditionals); - auto conditional = boost::make_shared( - CollectKeys({continuousFrontals.begin(), continuousFrontals.end()}, - {continuousSeparator.begin(), continuousSeparator.end()}), - CollectDiscreteKeys({discreteFrontals.begin(), discreteFrontals.end()}, - {discreteSeparator.begin(), discreteSeparator.end()}), - continuousFrontals.size() + discreteFrontals.size()); std::cout << GREEN_BOLD << "[Conditional]\n" << RESET; conditional->print(); std::cout << GREEN_BOLD << "[Separator]\n" << RESET; - sum.print(); + separatorFactors.print("", DefaultKeyFormatter, + [](GaussianFactor::shared_ptr gc) { + RedirectCout rd; + gc->print(""); + return rd.str(); + }); std::cout << RED_BOLD << "[End Eliminate]\n" << RESET; - // return std::make_pair(conditional, sum); - return std::make_pair(conditional, - boost::make_shared(std::move(sum))); + // If there are no more continuous parents, then we should create here a + // DiscreteFactor, with the error for each discrete choice. + if (keysOfSeparator.empty()) { + VectorValues empty_values; + auto factorError = [&](const GaussianFactor::shared_ptr &factor) { + if (!factor) return 0.0; // TODO(fan): does this make sense? + return exp(-factor->error(empty_values)); + }; + DecisionTree fdt(separatorFactors, factorError); + auto discreteFactor = + boost::make_shared(discreteSeparator, fdt); + + return {boost::make_shared(conditional), + boost::make_shared(discreteFactor)}; + + } else { + // Create a resulting DCGaussianMixture on the separator. + auto factor = boost::make_shared( + frontalKeys, discreteSeparator, separatorFactors); + return {boost::make_shared(conditional), factor}; + } + + // Ordering keys for the conditional so that frontalKeys are really in front + // Ordering orderedKeys; + // orderedKeys.insert(orderedKeys.end(), frontalKeys.begin(), + // frontalKeys.end()); orderedKeys.insert(orderedKeys.end(), + // sum_factor.keys().begin(), + // sum_factor.keys().end()); + + // // now divide product/sum to get conditional + // gttic(divide); + // // auto conditional = + // // boost::make_shared(product, *sum, orderedKeys); + // gttoc(divide); + + // auto conditional = boost::make_shared( + // CollectKeys({continuousFrontals.begin(), continuousFrontals.end()}, + // {continuousSeparator.begin(), continuousSeparator.end()}), + // CollectDiscreteKeys( + // {discreteFrontals.begin(), discreteFrontals.end()}, + // {discreteSeparatorSet.begin(), discreteSeparatorSet.end()}), + // continuousFrontals.size() + discreteFrontals.size()); + // std::cout << GREEN_BOLD << "[Conditional]\n" << RESET; + // conditional->print(); + // std::cout << GREEN_BOLD << "[Separator]\n" << RESET; + // sum_factor.print(); + // std::cout << RED_BOLD << "[End Eliminate]\n" << RESET; + + // // return std::make_pair(conditional, sum); + // return std::make_pair(conditional, boost::make_shared( + // std::move(sum_factor))); } void HybridFactorGraph::add(JacobianFactor &&factor) { diff --git a/gtsam/hybrid/tests/testHybridConditional.cpp b/gtsam/hybrid/tests/testHybridConditional.cpp index d16715300..6672a1870 100644 --- a/gtsam/hybrid/tests/testHybridConditional.cpp +++ b/gtsam/hybrid/tests/testHybridConditional.cpp @@ -31,7 +31,6 @@ #include #include -#include "gtsam/base/Testable.h" using namespace boost::assign; @@ -41,22 +40,33 @@ using namespace gtsam; using gtsam::symbol_shorthand::C; using gtsam::symbol_shorthand::X; +#define BOOST_STACKTRACE_GNU_SOURCE_NOT_REQUIRED + +#include // ::signal, ::raise + +#include + +void my_signal_handler(int signum) { + ::signal(signum, SIG_DFL); + std::cout << boost::stacktrace::stacktrace(); + ::raise(SIGABRT); +} + /* ************************************************************************* */ -TEST(HybridFactorGraph, creation) { +TEST_DISABLED(HybridFactorGraph, creation) { HybridConditional test; HybridFactorGraph hfg; hfg.add(HybridGaussianFactor(JacobianFactor(0, I_3x3, Z_3x1))); - GaussianMixture clgc( - {X(0)}, {X(1)}, DiscreteKeys(DiscreteKey{C(0), 2}), - GaussianMixture::Conditionals( - C(0), - boost::make_shared(X(0), Z_3x1, I_3x3, X(1), - I_3x3), - boost::make_shared(X(0), Vector3::Ones(), I_3x3, - X(1), I_3x3))); + GaussianMixture clgc({X(0)}, {X(1)}, DiscreteKeys(DiscreteKey{C(0), 2}), + GaussianMixture::Conditionals( + C(0), + boost::make_shared( + X(0), Z_3x1, I_3x3, X(1), I_3x3), + boost::make_shared( + X(0), Vector3::Ones(), I_3x3, X(1), I_3x3))); GTSAM_PRINT(clgc); } @@ -70,7 +80,7 @@ TEST_DISABLED(HybridFactorGraph, eliminate) { EXPECT_LONGS_EQUAL(result.first->size(), 1); } -TEST(HybridFactorGraph, eliminateMultifrontal) { +TEST_DISABLED(HybridFactorGraph, eliminateMultifrontal) { HybridFactorGraph hfg; DiscreteKey x(X(1), 2); @@ -84,7 +94,7 @@ TEST(HybridFactorGraph, eliminateMultifrontal) { EXPECT_LONGS_EQUAL(result.second->size(), 1); } -TEST_DISABLED(HybridFactorGraph, eliminateFullMultifrontalSimple) { +TEST(HybridFactorGraph, eliminateFullMultifrontalSimple) { std::cout << ">>>>>>>>>>>>>>\n"; HybridFactorGraph hfg; @@ -99,7 +109,7 @@ TEST_DISABLED(HybridFactorGraph, eliminateFullMultifrontalSimple) { boost::make_shared(X(1), I_3x3, Vector3::Ones())); hfg.add(CGMixtureFactor({X(1)}, {c1}, dt)); - hfg.add(CGMixtureFactor({X(0)}, {c1}, dt)); + // hfg.add(CGMixtureFactor({X(0)}, {c1}, dt)); hfg.add(HybridDiscreteFactor(DecisionTreeFactor(c1, {2, 8}))); hfg.add(HybridDiscreteFactor( DecisionTreeFactor({{C(1), 2}, {C(2), 2}}, "1 2 3 4"))); @@ -114,7 +124,7 @@ TEST_DISABLED(HybridFactorGraph, eliminateFullMultifrontalSimple) { GTSAM_PRINT(*result->marginalFactor(C(1))); } -TEST(HybridFactorGraph, eliminateFullMultifrontalCLG) { +TEST_DISABLED(HybridFactorGraph, eliminateFullMultifrontalCLG) { std::cout << ">>>>>>>>>>>>>>\n"; HybridFactorGraph hfg; @@ -148,8 +158,9 @@ TEST(HybridFactorGraph, eliminateFullMultifrontalCLG) { } /** - * This test is about how to assemble the Bayes Tree roots after we do partial elimination -*/ + * This test is about how to assemble the Bayes Tree roots after we do partial + * elimination + */ TEST_DISABLED(HybridFactorGraph, eliminateFullMultifrontalTwoClique) { std::cout << ">>>>>>>>>>>>>>\n"; @@ -173,7 +184,8 @@ TEST_DISABLED(HybridFactorGraph, eliminateFullMultifrontalTwoClique) { } // hfg.add(HybridDiscreteFactor(DecisionTreeFactor(c, {2, 8}))); - hfg.add(HybridDiscreteFactor(DecisionTreeFactor({{C(1), 2}, {C(2), 2}}, "1 2 3 4"))); + hfg.add(HybridDiscreteFactor( + DecisionTreeFactor({{C(1), 2}, {C(2), 2}}, "1 2 3 4"))); hfg.add(JacobianFactor(X(3), I_3x3, X(4), -I_3x3, Z_3x1)); hfg.add(JacobianFactor(X(4), I_3x3, X(5), -I_3x3, Z_3x1)); @@ -192,14 +204,15 @@ TEST_DISABLED(HybridFactorGraph, eliminateFullMultifrontalTwoClique) { hfg.add(CGMixtureFactor({X(5)}, {{C(2), 2}}, dt1)); } - auto ordering_full = Ordering::ColamdConstrainedLast(hfg, {C(0), C(1), C(2), C(3)}); + auto ordering_full = + Ordering::ColamdConstrainedLast(hfg, {C(0), C(1), C(2), C(3)}); GTSAM_PRINT(ordering_full); HybridBayesTree::shared_ptr hbt; HybridFactorGraph::shared_ptr remaining; - std::tie(hbt, remaining) = - hfg.eliminatePartialMultifrontal(Ordering(ordering_full.begin(), ordering_full.end())); + std::tie(hbt, remaining) = hfg.eliminatePartialMultifrontal( + Ordering(ordering_full.begin(), ordering_full.end())); GTSAM_PRINT(*hbt); @@ -215,6 +228,9 @@ TEST_DISABLED(HybridFactorGraph, eliminateFullMultifrontalTwoClique) { /* ************************************************************************* */ int main() { + ::signal(SIGSEGV, &my_signal_handler); + ::signal(SIGBUS, &my_signal_handler); + TestResult tr; return TestRegistry::runAllTests(tr); } From 1e8aae3f06b5cb704de3a1a7578b15216760159a Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Wed, 23 Mar 2022 20:18:02 -0400 Subject: [PATCH 0211/1686] Add a test for EliminateSequential --- gtsam/hybrid/tests/testHybridConditional.cpp | 31 +++++++++++++++++++- 1 file changed, 30 insertions(+), 1 deletion(-) diff --git a/gtsam/hybrid/tests/testHybridConditional.cpp b/gtsam/hybrid/tests/testHybridConditional.cpp index 6672a1870..32cb05325 100644 --- a/gtsam/hybrid/tests/testHybridConditional.cpp +++ b/gtsam/hybrid/tests/testHybridConditional.cpp @@ -94,6 +94,35 @@ TEST_DISABLED(HybridFactorGraph, eliminateMultifrontal) { EXPECT_LONGS_EQUAL(result.second->size(), 1); } +TEST(HybridFactorGraph, eliminateFullSequentialSimple) { + std::cout << ">>>>>>>>>>>>>>\n"; + + HybridFactorGraph hfg; + + DiscreteKey c1(C(1), 2); + + hfg.add(JacobianFactor(X(0), I_3x3, Z_3x1)); + hfg.add(JacobianFactor(X(0), I_3x3, X(1), -I_3x3, Z_3x1)); + + DecisionTree dt( + C(1), boost::make_shared(X(1), I_3x3, Z_3x1), + boost::make_shared(X(1), I_3x3, Vector3::Ones())); + + hfg.add(CGMixtureFactor({X(1)}, {c1}, dt)); + // hfg.add(CGMixtureFactor({X(0)}, {c1}, dt)); + hfg.add(HybridDiscreteFactor(DecisionTreeFactor(c1, {2, 8}))); + hfg.add(HybridDiscreteFactor( + DecisionTreeFactor({{C(1), 2}, {C(2), 2}}, "1 2 3 4"))); + // hfg.add(HybridDiscreteFactor(DecisionTreeFactor({{C(2), 2}, {C(3), 2}}, "1 + // 2 3 4"))); hfg.add(HybridDiscreteFactor(DecisionTreeFactor({{C(3), 2}, + // {C(1), 2}}, "1 2 2 1"))); + + auto result = hfg.eliminateSequential( + Ordering::ColamdConstrainedLast(hfg, {C(1), C(2)})); + + GTSAM_PRINT(*result); +} + TEST(HybridFactorGraph, eliminateFullMultifrontalSimple) { std::cout << ">>>>>>>>>>>>>>\n"; @@ -121,7 +150,7 @@ TEST(HybridFactorGraph, eliminateFullMultifrontalSimple) { Ordering::ColamdConstrainedLast(hfg, {C(1), C(2)})); GTSAM_PRINT(*result); - GTSAM_PRINT(*result->marginalFactor(C(1))); + GTSAM_PRINT(*result->marginalFactor(C(2))); } TEST_DISABLED(HybridFactorGraph, eliminateFullMultifrontalCLG) { From b4f8eea23138266f795b994048f559861939b180 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Wed, 23 Mar 2022 20:36:18 -0400 Subject: [PATCH 0212/1686] Address comments --- ...reFactor.cpp => GaussianMixtureFactor.cpp} | 18 ++++++++--------- ...ixtureFactor.h => GaussianMixtureFactor.h} | 10 +++++----- gtsam/hybrid/HybridBayesNet.h | 6 +++--- gtsam/hybrid/HybridBayesTree.h | 4 +++- gtsam/hybrid/HybridDiscreteFactor.h | 4 ++++ gtsam/hybrid/HybridFactor.h | 5 +++++ gtsam/hybrid/HybridFactorGraph.cpp | 18 ++++++++--------- gtsam/hybrid/HybridGaussianFactor.h | 4 ++++ gtsam/hybrid/tests/CMakeLists.txt | 2 +- gtsam/hybrid/tests/testHybridConditional.cpp | 20 +++++++++---------- 10 files changed, 53 insertions(+), 38 deletions(-) rename gtsam/hybrid/{CGMixtureFactor.cpp => GaussianMixtureFactor.cpp} (77%) rename gtsam/hybrid/{CGMixtureFactor.h => GaussianMixtureFactor.h} (87%) diff --git a/gtsam/hybrid/CGMixtureFactor.cpp b/gtsam/hybrid/GaussianMixtureFactor.cpp similarity index 77% rename from gtsam/hybrid/CGMixtureFactor.cpp rename to gtsam/hybrid/GaussianMixtureFactor.cpp index 08ae8b6e9..61cfb1d70 100644 --- a/gtsam/hybrid/CGMixtureFactor.cpp +++ b/gtsam/hybrid/GaussianMixtureFactor.cpp @@ -10,7 +10,7 @@ * -------------------------------------------------------------------------- */ /** - * @file CGMixtureFactor.cpp + * @file GaussianMixtureFactor.cpp * @brief A set of Gaussian factors indexed by a set of discrete keys. * @author Fan Jiang * @author Varun Agrawal @@ -18,7 +18,7 @@ * @date Mar 12, 2022 */ -#include +#include #include #include @@ -27,15 +27,15 @@ namespace gtsam { -CGMixtureFactor::CGMixtureFactor(const KeyVector &continuousKeys, +GaussianMixtureFactor::GaussianMixtureFactor(const KeyVector &continuousKeys, const DiscreteKeys &discreteKeys, const Factors &factors) : Base(continuousKeys, discreteKeys), factors_(factors) {} -bool CGMixtureFactor::equals(const HybridFactor &lf, double tol) const { +bool GaussianMixtureFactor::equals(const HybridFactor &lf, double tol) const { return false; } -void CGMixtureFactor::print(const std::string &s, const KeyFormatter &formatter) const { +void GaussianMixtureFactor::print(const std::string &s, const KeyFormatter &formatter) const { HybridFactor::print(s, formatter); factors_.print( "mixture = ", @@ -49,12 +49,12 @@ void CGMixtureFactor::print(const std::string &s, const KeyFormatter &formatter) }); } -const CGMixtureFactor::Factors& CGMixtureFactor::factors() { +const GaussianMixtureFactor::Factors& GaussianMixtureFactor::factors() { return factors_; } /* *******************************************************************************/ -CGMixtureFactor::Sum CGMixtureFactor::addTo(const CGMixtureFactor::Sum &sum) const { +GaussianMixtureFactor::Sum GaussianMixtureFactor::addTo(const GaussianMixtureFactor::Sum &sum) const { using Y = GaussianFactorGraph; auto add = [](const Y &graph1, const Y &graph2) { auto result = graph1; @@ -66,7 +66,7 @@ CGMixtureFactor::Sum CGMixtureFactor::addTo(const CGMixtureFactor::Sum &sum) con } /* *******************************************************************************/ -CGMixtureFactor::Sum CGMixtureFactor::wrappedFactors() const { +GaussianMixtureFactor::Sum GaussianMixtureFactor::wrappedFactors() const { auto wrap = [](const GaussianFactor::shared_ptr &factor) { GaussianFactorGraph result; result.push_back(factor); @@ -74,4 +74,4 @@ CGMixtureFactor::Sum CGMixtureFactor::wrappedFactors() const { }; return {factors_, wrap}; } -} \ No newline at end of file +} diff --git a/gtsam/hybrid/CGMixtureFactor.h b/gtsam/hybrid/GaussianMixtureFactor.h similarity index 87% rename from gtsam/hybrid/CGMixtureFactor.h rename to gtsam/hybrid/GaussianMixtureFactor.h index fd81cdd91..4cd5e71de 100644 --- a/gtsam/hybrid/CGMixtureFactor.h +++ b/gtsam/hybrid/GaussianMixtureFactor.h @@ -10,7 +10,7 @@ * -------------------------------------------------------------------------- */ /** - * @file CGMixtureFactor.h + * @file GaussianMixtureFactor.h * @brief A set of Gaussian factors indexed by a set of discrete keys. * @author Fan Jiang * @author Varun Agrawal @@ -29,19 +29,19 @@ namespace gtsam { class GaussianFactorGraph; -class CGMixtureFactor : public HybridFactor { +class GaussianMixtureFactor : public HybridFactor { public: using Base = HybridFactor; - using This = CGMixtureFactor; + using This = GaussianMixtureFactor; using shared_ptr = boost::shared_ptr; using Factors = DecisionTree; Factors factors_; - CGMixtureFactor() = default; + GaussianMixtureFactor() = default; - CGMixtureFactor(const KeyVector &continuousKeys, + GaussianMixtureFactor(const KeyVector &continuousKeys, const DiscreteKeys &discreteKeys, const Factors &factors); using Sum = DecisionTree; diff --git a/gtsam/hybrid/HybridBayesNet.h b/gtsam/hybrid/HybridBayesNet.h index 53d10518f..d7e2f33af 100644 --- a/gtsam/hybrid/HybridBayesNet.h +++ b/gtsam/hybrid/HybridBayesNet.h @@ -25,8 +25,8 @@ namespace gtsam { /** - * A hybrid Bayes net can have discrete conditionals, Gaussian mixtures, - * or pure Gaussian conditionals. + * A hybrid Bayes net is a collection of HybridConditionals, which can have + * discrete conditionals, Gaussian mixtures, or pure Gaussian conditionals. */ class GTSAM_EXPORT HybridBayesNet : public BayesNet { public: @@ -40,4 +40,4 @@ class GTSAM_EXPORT HybridBayesNet : public BayesNet { HybridBayesNet() : Base() {} }; -} // namespace gtsam \ No newline at end of file +} // namespace gtsam diff --git a/gtsam/hybrid/HybridBayesTree.h b/gtsam/hybrid/HybridBayesTree.h index 74b967fc8..ee51bdd6c 100644 --- a/gtsam/hybrid/HybridBayesTree.h +++ b/gtsam/hybrid/HybridBayesTree.h @@ -33,7 +33,9 @@ class HybridConditional; class VectorValues; /* ************************************************************************* */ -/** A clique in a HybridBayesTree */ +/** A clique in a HybridBayesTree + * which is a HybridConditional internally. + */ class GTSAM_EXPORT HybridBayesTreeClique : public BayesTreeCliqueBase { public: diff --git a/gtsam/hybrid/HybridDiscreteFactor.h b/gtsam/hybrid/HybridDiscreteFactor.h index f182f90a9..c55c5ecf0 100644 --- a/gtsam/hybrid/HybridDiscreteFactor.h +++ b/gtsam/hybrid/HybridDiscreteFactor.h @@ -23,6 +23,10 @@ namespace gtsam { +/** + * A HybridDiscreteFactor is a wrapper for DiscreteFactor, so we hide the + * implementation of DiscreteFactor, and thus avoiding diamond inheritance. + */ class HybridDiscreteFactor : public HybridFactor { public: using Base = HybridFactor; diff --git a/gtsam/hybrid/HybridFactor.h b/gtsam/hybrid/HybridFactor.h index 653d4270a..3d5bd7b21 100644 --- a/gtsam/hybrid/HybridFactor.h +++ b/gtsam/hybrid/HybridFactor.h @@ -34,6 +34,11 @@ DiscreteKeys CollectDiscreteKeys(const DiscreteKeys &key1, /** * Base class for hybrid probabilistic factors + * Examples: + * - HybridGaussianFactor + * - HybridDiscreteFactor + * - GaussianMixtureFactor + * - GaussianMixture */ class GTSAM_EXPORT HybridFactor : public Factor { public: diff --git a/gtsam/hybrid/HybridFactorGraph.cpp b/gtsam/hybrid/HybridFactorGraph.cpp index 735b8cfa9..574c3b781 100644 --- a/gtsam/hybrid/HybridFactorGraph.cpp +++ b/gtsam/hybrid/HybridFactorGraph.cpp @@ -21,7 +21,7 @@ #include #include #include -#include +#include #include #include #include @@ -56,14 +56,14 @@ static std::string GREEN = "\033[0;32m"; static std::string GREEN_BOLD = "\033[1;32m"; static std::string RESET = "\033[0m"; -static CGMixtureFactor::Sum &addGaussian( - CGMixtureFactor::Sum &sum, const GaussianFactor::shared_ptr &factor) { +static GaussianMixtureFactor::Sum &addGaussian( + GaussianMixtureFactor::Sum &sum, const GaussianFactor::shared_ptr &factor) { using Y = GaussianFactorGraph; // If the decision tree is not intiialized, then intialize it. if (sum.empty()) { GaussianFactorGraph result; result.push_back(factor); - sum = CGMixtureFactor::Sum(result); + sum = GaussianMixtureFactor::Sum(result); } else { auto add = [&factor](const Y &graph) { @@ -307,7 +307,7 @@ EliminateHybrid(const HybridFactorGraph &factors, const Ordering &frontalKeys) { // continue; // } - // auto ptr_mf = boost::dynamic_pointer_cast(factor); + // auto ptr_mf = boost::dynamic_pointer_cast(factor); // if (ptr_mf) gf.push_back(ptr_mf->factors_(new_assignment)); // auto ptr_gm = boost::dynamic_pointer_cast(factor); @@ -329,13 +329,13 @@ EliminateHybrid(const HybridFactorGraph &factors, const Ordering &frontalKeys) { std::cout << RED_BOLD << "HYBRID ELIM." << RESET << "\n"; - CGMixtureFactor::Sum sum; + GaussianMixtureFactor::Sum sum; std::vector deferredFactors; for (auto &f : factors) { if (f->isHybrid_) { - auto cgmf = boost::dynamic_pointer_cast(f); + auto cgmf = boost::dynamic_pointer_cast(f); if (cgmf) { sum = cgmf->addTo(sum); } @@ -395,7 +395,7 @@ EliminateHybrid(const HybridFactorGraph &factors, const Ordering &frontalKeys) { auto pair = unzip(eliminationResults); const GaussianMixture::Conditionals &conditionals = pair.first; - const CGMixtureFactor::Factors &separatorFactors = pair.second; + const GaussianMixtureFactor::Factors &separatorFactors = pair.second; // Create the GaussianMixture from the conditionals auto conditional = boost::make_shared( @@ -429,7 +429,7 @@ EliminateHybrid(const HybridFactorGraph &factors, const Ordering &frontalKeys) { } else { // Create a resulting DCGaussianMixture on the separator. - auto factor = boost::make_shared( + auto factor = boost::make_shared( frontalKeys, discreteSeparator, separatorFactors); return {boost::make_shared(conditional), factor}; } diff --git a/gtsam/hybrid/HybridGaussianFactor.h b/gtsam/hybrid/HybridGaussianFactor.h index 03c49564e..86c87a0ec 100644 --- a/gtsam/hybrid/HybridGaussianFactor.h +++ b/gtsam/hybrid/HybridGaussianFactor.h @@ -23,6 +23,10 @@ namespace gtsam { +/** + * A HybridGaussianFactor is a wrapper for GaussianFactor so that we do not have + * a diamond inheritance. + */ class HybridGaussianFactor : public HybridFactor { public: using Base = HybridFactor; diff --git a/gtsam/hybrid/tests/CMakeLists.txt b/gtsam/hybrid/tests/CMakeLists.txt index b52e18586..06ad2c505 100644 --- a/gtsam/hybrid/tests/CMakeLists.txt +++ b/gtsam/hybrid/tests/CMakeLists.txt @@ -1 +1 @@ -gtsamAddTestsGlob(hybrid "test*.cpp" "" "gtsam") \ No newline at end of file +gtsamAddTestsGlob(hybrid "test*.cpp" "" "gtsam") diff --git a/gtsam/hybrid/tests/testHybridConditional.cpp b/gtsam/hybrid/tests/testHybridConditional.cpp index 32cb05325..876105510 100644 --- a/gtsam/hybrid/tests/testHybridConditional.cpp +++ b/gtsam/hybrid/tests/testHybridConditional.cpp @@ -17,7 +17,7 @@ #include #include -#include +#include #include #include #include @@ -108,8 +108,8 @@ TEST(HybridFactorGraph, eliminateFullSequentialSimple) { C(1), boost::make_shared(X(1), I_3x3, Z_3x1), boost::make_shared(X(1), I_3x3, Vector3::Ones())); - hfg.add(CGMixtureFactor({X(1)}, {c1}, dt)); - // hfg.add(CGMixtureFactor({X(0)}, {c1}, dt)); + hfg.add(GaussianMixtureFactor({X(1)}, {c1}, dt)); + // hfg.add(GaussianMixtureFactor({X(0)}, {c1}, dt)); hfg.add(HybridDiscreteFactor(DecisionTreeFactor(c1, {2, 8}))); hfg.add(HybridDiscreteFactor( DecisionTreeFactor({{C(1), 2}, {C(2), 2}}, "1 2 3 4"))); @@ -137,8 +137,8 @@ TEST(HybridFactorGraph, eliminateFullMultifrontalSimple) { C(1), boost::make_shared(X(1), I_3x3, Z_3x1), boost::make_shared(X(1), I_3x3, Vector3::Ones())); - hfg.add(CGMixtureFactor({X(1)}, {c1}, dt)); - // hfg.add(CGMixtureFactor({X(0)}, {c1}, dt)); + hfg.add(GaussianMixtureFactor({X(1)}, {c1}, dt)); + // hfg.add(GaussianMixtureFactor({X(0)}, {c1}, dt)); hfg.add(HybridDiscreteFactor(DecisionTreeFactor(c1, {2, 8}))); hfg.add(HybridDiscreteFactor( DecisionTreeFactor({{C(1), 2}, {C(2), 2}}, "1 2 3 4"))); @@ -167,7 +167,7 @@ TEST_DISABLED(HybridFactorGraph, eliminateFullMultifrontalCLG) { C(1), boost::make_shared(X(1), I_3x3, Z_3x1), boost::make_shared(X(1), I_3x3, Vector3::Ones())); - hfg.add(CGMixtureFactor({X(1)}, {c}, dt)); + hfg.add(GaussianMixtureFactor({X(1)}, {c}, dt)); hfg.add(HybridDiscreteFactor(DecisionTreeFactor(c, {2, 8}))); // hfg.add(HybridDiscreteFactor(DecisionTreeFactor({{C(1), 2}, {C(2), 2}}, "1 // 2 3 4"))); @@ -203,13 +203,13 @@ TEST_DISABLED(HybridFactorGraph, eliminateFullMultifrontalTwoClique) { C(0), boost::make_shared(X(0), I_3x3, Z_3x1), boost::make_shared(X(0), I_3x3, Vector3::Ones())); - hfg.add(CGMixtureFactor({X(0)}, {{C(0), 2}}, dt)); + hfg.add(GaussianMixtureFactor({X(0)}, {{C(0), 2}}, dt)); DecisionTree dt1( C(1), boost::make_shared(X(2), I_3x3, Z_3x1), boost::make_shared(X(2), I_3x3, Vector3::Ones())); - hfg.add(CGMixtureFactor({X(2)}, {{C(1), 2}}, dt1)); + hfg.add(GaussianMixtureFactor({X(2)}, {{C(1), 2}}, dt1)); } // hfg.add(HybridDiscreteFactor(DecisionTreeFactor(c, {2, 8}))); @@ -224,13 +224,13 @@ TEST_DISABLED(HybridFactorGraph, eliminateFullMultifrontalTwoClique) { C(3), boost::make_shared(X(3), I_3x3, Z_3x1), boost::make_shared(X(3), I_3x3, Vector3::Ones())); - hfg.add(CGMixtureFactor({X(3)}, {{C(3), 2}}, dt)); + hfg.add(GaussianMixtureFactor({X(3)}, {{C(3), 2}}, dt)); DecisionTree dt1( C(2), boost::make_shared(X(5), I_3x3, Z_3x1), boost::make_shared(X(5), I_3x3, Vector3::Ones())); - hfg.add(CGMixtureFactor({X(5)}, {{C(2), 2}}, dt1)); + hfg.add(GaussianMixtureFactor({X(5)}, {{C(2), 2}}, dt1)); } auto ordering_full = From 4f8dfeb5b254ab75f34fca053c56bede74e3f5d6 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Wed, 23 Mar 2022 20:36:56 -0400 Subject: [PATCH 0213/1686] Remove warning --- gtsam/hybrid/HybridJunctionTree.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/gtsam/hybrid/HybridJunctionTree.cpp b/gtsam/hybrid/HybridJunctionTree.cpp index 9445e26b8..7c48934fc 100644 --- a/gtsam/hybrid/HybridJunctionTree.cpp +++ b/gtsam/hybrid/HybridJunctionTree.cpp @@ -161,7 +161,6 @@ HybridJunctionTree::HybridJunctionTree( // Traverse the elimination tree, doing symbolic elimination and merging nodes // as we go. Gather the created junction tree roots in a dummy Node. - typedef typename HybridEliminationTree::Node ETreeNode; typedef HybridConstructorTraversalData Data; Data rootData(0); rootData.myJTNode = From 293ef614acc01156bdbb767761a7f5dba42b998b Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Wed, 23 Mar 2022 20:42:26 -0400 Subject: [PATCH 0214/1686] Address comments --- gtsam/hybrid/HybridEliminationTree.h | 3 +++ gtsam/hybrid/HybridFactorGraph.h | 10 ++++++++-- gtsam/hybrid/HybridGaussianFactor.cpp | 2 +- 3 files changed, 12 insertions(+), 3 deletions(-) diff --git a/gtsam/hybrid/HybridEliminationTree.h b/gtsam/hybrid/HybridEliminationTree.h index b72bbcad9..902beb279 100644 --- a/gtsam/hybrid/HybridEliminationTree.h +++ b/gtsam/hybrid/HybridEliminationTree.h @@ -23,6 +23,9 @@ namespace gtsam { +/** + * Elimination Tree type for Hybrid + */ class GTSAM_EXPORT HybridEliminationTree : public EliminationTree { public: diff --git a/gtsam/hybrid/HybridFactorGraph.h b/gtsam/hybrid/HybridFactorGraph.h index 92f98c8f2..21332d80a 100644 --- a/gtsam/hybrid/HybridFactorGraph.h +++ b/gtsam/hybrid/HybridFactorGraph.h @@ -37,8 +37,8 @@ class JacobianFactor; /** Main elimination function for HybridFactorGraph */ GTSAM_EXPORT - std::pair, HybridFactor::shared_ptr> - EliminateHybrid(const HybridFactorGraph& factors, const Ordering& keys); +std::pair, HybridFactor::shared_ptr> +EliminateHybrid(const HybridFactorGraph& factors, const Ordering& keys); /* ************************************************************************* */ template <> @@ -62,6 +62,12 @@ struct EliminationTraits { } }; +/** + * Hybrid Factor Graph + * ----------------------- + * This is the linear version of a hybrid factor graph. Everything inside needs + * to be hybrid factor or hybrid conditional. + */ class HybridFactorGraph : public FactorGraph, public EliminateableFactorGraph { public: diff --git a/gtsam/hybrid/HybridGaussianFactor.cpp b/gtsam/hybrid/HybridGaussianFactor.cpp index d83f90024..5fa4b555a 100644 --- a/gtsam/hybrid/HybridGaussianFactor.cpp +++ b/gtsam/hybrid/HybridGaussianFactor.cpp @@ -39,4 +39,4 @@ void HybridGaussianFactor::print(const std::string &s, inner->print("inner: ", formatter); }; -} // namespace gtsam \ No newline at end of file +} // namespace gtsam From a36c86a4f168a03f316d3c13f8bb78b13dfc3a71 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Wed, 23 Mar 2022 20:50:36 -0400 Subject: [PATCH 0215/1686] Display debug messages only when DEBUG = true --- gtsam/hybrid/HybridFactorGraph.cpp | 186 ++++++++--------------------- 1 file changed, 49 insertions(+), 137 deletions(-) diff --git a/gtsam/hybrid/HybridFactorGraph.cpp b/gtsam/hybrid/HybridFactorGraph.cpp index 574c3b781..9e7eebc57 100644 --- a/gtsam/hybrid/HybridFactorGraph.cpp +++ b/gtsam/hybrid/HybridFactorGraph.cpp @@ -21,8 +21,8 @@ #include #include #include -#include #include +#include #include #include #include @@ -56,6 +56,8 @@ static std::string GREEN = "\033[0;32m"; static std::string GREEN_BOLD = "\033[1;32m"; static std::string RESET = "\033[0m"; +static bool DEBUG = false; + static GaussianMixtureFactor::Sum &addGaussian( GaussianMixtureFactor::Sum &sum, const GaussianFactor::shared_ptr &factor) { using Y = GaussianFactorGraph; @@ -129,15 +131,18 @@ EliminateHybrid(const HybridFactorGraph &factors, const Ordering &frontalKeys) { KeySet continuousFrontals; KeySet continuousSeparator; - // TODO: we do a mock by just doing the correct key thing - std::cout << RED_BOLD << "Begin Eliminate: " << RESET; - frontalKeys.print(); + if (DEBUG) { + std::cout << RED_BOLD << "Begin Eliminate: " << RESET; + frontalKeys.print(); + } // This initializes separatorKeys and discreteCardinalities for (auto &&factor : factors) { - std::cout << ">>> Adding factor: " << GREEN; - factor->print(); - std::cout << RESET; + if (DEBUG) { + std::cout << ">>> Adding factor: " << GREEN; + factor->print(); + std::cout << RESET; + } separatorKeys.insert(factor->begin(), factor->end()); if (!factor->isContinuous_) { for (auto &k : factor->discreteKeys_) { @@ -171,7 +176,8 @@ EliminateHybrid(const HybridFactorGraph &factors, const Ordering &frontalKeys) { } } - { + // Only for printing + if (DEBUG) { std::cout << RED_BOLD << "Keys: " << RESET; for (auto &f : frontalKeys) { if (discreteCardinalities.find(f) != discreteCardinalities.end()) { @@ -203,7 +209,10 @@ EliminateHybrid(const HybridFactorGraph &factors, const Ordering &frontalKeys) { // Case 1: we are only dealing with continuous if (discreteCardinalities.empty() && !allContinuousKeys.empty()) { - std::cout << RED_BOLD << "CONT. ONLY" << RESET << "\n"; + if (DEBUG) { + std::cout << RED_BOLD << "CONT. ONLY" << RESET << "\n"; + } + GaussianFactorGraph gfg; for (auto &fp : factors) { auto ptr = boost::dynamic_pointer_cast(fp); @@ -222,7 +231,10 @@ EliminateHybrid(const HybridFactorGraph &factors, const Ordering &frontalKeys) { // Case 2: we are only dealing with discrete if (allContinuousKeys.empty()) { - std::cout << RED_BOLD << "DISCRETE ONLY" << RESET << "\n"; + if (DEBUG) { + std::cout << RED_BOLD << "DISCRETE ONLY" << RESET << "\n"; + } + DiscreteFactorGraph dfg; for (auto &fp : factors) { auto ptr = boost::dynamic_pointer_cast(fp); @@ -246,88 +258,12 @@ EliminateHybrid(const HybridFactorGraph &factors, const Ordering &frontalKeys) { DiscreteKeys discreteSeparator(discreteSeparatorSet.begin(), discreteSeparatorSet.end()); - // We will need to know a mapping on when will a factor be fully determined by - // discrete keys std::vector> - // availableFactors; - - // { - // std::vector> keysForFactor; - // keysForFactor.reserve(factors.size()); - // std::transform( - // factors.begin(), factors.end(), std::back_inserter(keysForFactor), - // [](HybridFactor::shared_ptr factor) - // -> std::pair { - // return {KeySet(factor->keys().begin() + factor->nrContinuous, - // factor->keys().end()), - // factor}; - // }); - - // KeySet currentAllKeys; - // const auto N = discreteSeparator.size(); - // for (size_t k = 0; k < N; k++) { - // currentAllKeys.insert(discreteSeparator.at(k).first); - // std::vector shouldRemove(N, false); - // for (size_t i = 0; i < keysForFactor.size(); i++) { - // availableFactors.emplace_back(); - - // if (std::includes(currentAllKeys.begin(), currentAllKeys.end(), - // keysForFactor[i].first.begin(), - // keysForFactor[i].first.end())) { - // // mark for delete - // shouldRemove[i] = true; - // availableFactors.back().push_back(keysForFactor[i].second); - // } - // keysForFactor.erase( - // std::remove_if(keysForFactor.begin(), keysForFactor.end(), - // [&shouldRemove, &keysForFactor](std::pair const &i) { - // return shouldRemove.at(&i - - // keysForFactor.data()); - // }), - // keysForFactor.end()); - // } - // } - // } - - // std::function>( - // (Assignment, GaussianFactorGraph, int))> - // visitor = [&](Assignment history, GaussianFactorGraph gf, int pos) - // -> boost::shared_ptr> { - // const auto currentKey = discreteSeparator[pos].first; - // const auto currentCard = discreteSeparator[pos].second; - - // std::vector>> - // children(currentCard, nullptr); - // for (size_t choice = 0; choice < currentCard; choice++) { - // Assignment new_assignment = history; - // GaussianFactorGraph new_gf(gf); - // // we try to get all currently available factors - // for (auto &factor : availableFactors[pos]) { - // if (!factor) { - // continue; - // } - - // auto ptr_mf = boost::dynamic_pointer_cast(factor); - // if (ptr_mf) gf.push_back(ptr_mf->factors_(new_assignment)); - - // auto ptr_gm = boost::dynamic_pointer_cast(factor); - // if (ptr_gm) gf.push_back(ptr_gm->conditionals_(new_assignment)); - - // children[choice] = visitor(new_assignment, new_gf, pos + 1); - // } - // } - // }; - - // PRODUCT: multiply all factors - // HybridConditional sum_factor( - // KeyVector(continuousSeparator.begin(), continuousSeparator.end()), - // DiscreteKeys(discreteSeparatorSet.begin(), discreteSeparatorSet.end()), - // separatorKeys.size()); - // sum out frontals, this is the factor on the separator gttic(sum); - std::cout << RED_BOLD << "HYBRID ELIM." << RESET << "\n"; + if (DEBUG) { + std::cout << RED_BOLD << "HYBRID ELIM." << RESET << "\n"; + } GaussianMixtureFactor::Sum sum; @@ -355,16 +291,20 @@ EliminateHybrid(const HybridFactorGraph &factors, const Ordering &frontalKeys) { } for (auto &f : deferredFactors) { - std::cout << GREEN_BOLD << "Adding Gaussian" << RESET << "\n"; + if (DEBUG) { + std::cout << GREEN_BOLD << "Adding Gaussian" << RESET << "\n"; + } sum = addGaussian(sum, f); } - std::cout << GREEN_BOLD << "[GFG Tree]\n" << RESET; - sum.print("", DefaultKeyFormatter, [](GaussianFactorGraph gfg) { - RedirectCout rd; - gfg.print(""); - return rd.str(); - }); + if (DEBUG) { + std::cout << GREEN_BOLD << "[GFG Tree]\n" << RESET; + sum.print("", DefaultKeyFormatter, [](GaussianFactorGraph gfg) { + RedirectCout rd; + gfg.print(""); + return rd.str(); + }); + } gttoc(sum); @@ -401,23 +341,25 @@ EliminateHybrid(const HybridFactorGraph &factors, const Ordering &frontalKeys) { auto conditional = boost::make_shared( frontalKeys, keysOfSeparator, discreteSeparator, conditionals); - std::cout << GREEN_BOLD << "[Conditional]\n" << RESET; - conditional->print(); - std::cout << GREEN_BOLD << "[Separator]\n" << RESET; - separatorFactors.print("", DefaultKeyFormatter, - [](GaussianFactor::shared_ptr gc) { - RedirectCout rd; - gc->print(""); - return rd.str(); - }); - std::cout << RED_BOLD << "[End Eliminate]\n" << RESET; + if (DEBUG) { + std::cout << GREEN_BOLD << "[Conditional]\n" << RESET; + conditional->print(); + std::cout << GREEN_BOLD << "[Separator]\n" << RESET; + separatorFactors.print("", DefaultKeyFormatter, + [](GaussianFactor::shared_ptr gc) { + RedirectCout rd; + gc->print(""); + return rd.str(); + }); + std::cout << RED_BOLD << "[End Eliminate]\n" << RESET; + } // If there are no more continuous parents, then we should create here a // DiscreteFactor, with the error for each discrete choice. if (keysOfSeparator.empty()) { VectorValues empty_values; auto factorError = [&](const GaussianFactor::shared_ptr &factor) { - if (!factor) return 0.0; // TODO(fan): does this make sense? + if (!factor) return 0.0; // TODO(fan): does this make sense? return exp(-factor->error(empty_values)); }; DecisionTree fdt(separatorFactors, factorError); @@ -433,36 +375,6 @@ EliminateHybrid(const HybridFactorGraph &factors, const Ordering &frontalKeys) { frontalKeys, discreteSeparator, separatorFactors); return {boost::make_shared(conditional), factor}; } - - // Ordering keys for the conditional so that frontalKeys are really in front - // Ordering orderedKeys; - // orderedKeys.insert(orderedKeys.end(), frontalKeys.begin(), - // frontalKeys.end()); orderedKeys.insert(orderedKeys.end(), - // sum_factor.keys().begin(), - // sum_factor.keys().end()); - - // // now divide product/sum to get conditional - // gttic(divide); - // // auto conditional = - // // boost::make_shared(product, *sum, orderedKeys); - // gttoc(divide); - - // auto conditional = boost::make_shared( - // CollectKeys({continuousFrontals.begin(), continuousFrontals.end()}, - // {continuousSeparator.begin(), continuousSeparator.end()}), - // CollectDiscreteKeys( - // {discreteFrontals.begin(), discreteFrontals.end()}, - // {discreteSeparatorSet.begin(), discreteSeparatorSet.end()}), - // continuousFrontals.size() + discreteFrontals.size()); - // std::cout << GREEN_BOLD << "[Conditional]\n" << RESET; - // conditional->print(); - // std::cout << GREEN_BOLD << "[Separator]\n" << RESET; - // sum_factor.print(); - // std::cout << RED_BOLD << "[End Eliminate]\n" << RESET; - - // // return std::make_pair(conditional, sum); - // return std::make_pair(conditional, boost::make_shared( - // std::move(sum_factor))); } void HybridFactorGraph::add(JacobianFactor &&factor) { From 8b4283b281a691c7c797ba943abfe1355ca8d162 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Wed, 23 Mar 2022 20:54:53 -0400 Subject: [PATCH 0216/1686] Add doxygen for GMM --- gtsam/hybrid/GaussianMixture.h | 21 ++++++++++++++------- 1 file changed, 14 insertions(+), 7 deletions(-) diff --git a/gtsam/hybrid/GaussianMixture.h b/gtsam/hybrid/GaussianMixture.h index 13171ae5d..9879e80bd 100644 --- a/gtsam/hybrid/GaussianMixture.h +++ b/gtsam/hybrid/GaussianMixture.h @@ -24,9 +24,8 @@ #include namespace gtsam { -class GaussianMixture - : public HybridFactor, - public Conditional { +class GaussianMixture : public HybridFactor, + public Conditional { public: using This = GaussianMixture; using shared_ptr = boost::shared_ptr; @@ -38,14 +37,22 @@ class GaussianMixture Conditionals conditionals_; public: + /** + * @brief Construct a new Gaussian Mixture object + * + * @param continuousFrontals the continuous frontals. + * @param continuousParents the continuous parents. + * @param discreteParents the discrete parents. Will be placed last. + * @param conditionals a decision tree of GaussianConditionals. + */ GaussianMixture(const KeyVector &continuousFrontals, - const KeyVector &continuousParents, - const DiscreteKeys &discreteParents, - const Conditionals &conditionals); + const KeyVector &continuousParents, + const DiscreteKeys &discreteParents, + const Conditionals &conditionals); using Sum = DecisionTree; - const Conditionals& conditionals(); + const Conditionals &conditionals(); /* *******************************************************************************/ Sum addTo(const Sum &sum) const; From 5f03e0f68b27aa62d6fe519ea65beecdb838ef8d Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Wed, 23 Mar 2022 20:59:31 -0400 Subject: [PATCH 0217/1686] Address compilation error on GCC --- gtsam/hybrid/HybridConditional.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/hybrid/HybridConditional.cpp b/gtsam/hybrid/HybridConditional.cpp index 7ada061b9..ed4b01608 100644 --- a/gtsam/hybrid/HybridConditional.cpp +++ b/gtsam/hybrid/HybridConditional.cpp @@ -28,7 +28,7 @@ HybridConditional::HybridConditional(const KeyVector &continuousFrontals, const DiscreteKeys &discreteParents) : HybridConditional( CollectKeys({continuousFrontals.begin(), continuousFrontals.end()}, - {continuousParents.begin(), continuousParents.end()}), + KeyVector {continuousParents.begin(), continuousParents.end()}), CollectDiscreteKeys( {discreteFrontals.begin(), discreteFrontals.end()}, {discreteParents.begin(), discreteParents.end()}), From 8d888606a36fe48fee634c4ef0a8bcbffb365e44 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Wed, 23 Mar 2022 21:31:22 -0400 Subject: [PATCH 0218/1686] Fix GCC error --- gtsam/hybrid/GaussianMixture.cpp | 2 ++ gtsam/hybrid/tests/testHybridConditional.cpp | 4 ++-- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/gtsam/hybrid/GaussianMixture.cpp b/gtsam/hybrid/GaussianMixture.cpp index 8135b2d2d..26668da59 100644 --- a/gtsam/hybrid/GaussianMixture.cpp +++ b/gtsam/hybrid/GaussianMixture.cpp @@ -13,6 +13,8 @@ * @file GaussianMixture.cpp * @brief A hybrid conditional in the Conditional Linear Gaussian scheme * @author Fan Jiang + * @author Varun Agrawal + * @author Frank Dellaert * @date Mar 12, 2022 */ diff --git a/gtsam/hybrid/tests/testHybridConditional.cpp b/gtsam/hybrid/tests/testHybridConditional.cpp index 876105510..95703b0af 100644 --- a/gtsam/hybrid/tests/testHybridConditional.cpp +++ b/gtsam/hybrid/tests/testHybridConditional.cpp @@ -17,8 +17,8 @@ #include #include -#include #include +#include #include #include #include @@ -75,7 +75,7 @@ TEST_DISABLED(HybridFactorGraph, eliminate) { hfg.add(HybridGaussianFactor(JacobianFactor(0, I_3x3, Z_3x1))); - auto result = hfg.eliminatePartialSequential({0}); + auto result = hfg.eliminatePartialSequential(KeyVector{0}); EXPECT_LONGS_EQUAL(result.first->size(), 1); } From 17237becb46e5e0ee12855f3cfb5f85d1b49c72d Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 24 Mar 2022 11:58:06 -0400 Subject: [PATCH 0219/1686] 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 0220/1686] 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 0221/1686] 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 0222/1686] 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 0223/1686] 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 0224/1686] 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 0225/1686] 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 0226/1686] 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 0227/1686] 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 a7e7977c5ff12e0814ca6ce140606788e26224cf Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Fri, 25 Mar 2022 16:47:28 -0400 Subject: [PATCH 0228/1686] Improve printing --- gtsam/linear/GaussianConditional.cpp | 15 ++++++++----- gtsam/linear/GaussianConditional.h | 4 ++-- .../linear/tests/testGaussianConditional.cpp | 22 ++++++++++++++----- 3 files changed, 28 insertions(+), 13 deletions(-) diff --git a/gtsam/linear/GaussianConditional.cpp b/gtsam/linear/GaussianConditional.cpp index c44ab246b..020a24be5 100644 --- a/gtsam/linear/GaussianConditional.cpp +++ b/gtsam/linear/GaussianConditional.cpp @@ -89,15 +89,20 @@ namespace gtsam { /* ************************************************************************ */ void GaussianConditional::print(const string &s, const KeyFormatter& formatter) const { - cout << s << " p("; + cout << s << "GaussianConditional p("; for (const_iterator it = beginFrontals(); it != endFrontals(); ++it) { - cout << (boost::format("%1%")%(formatter(*it))).str() << " "; + cout << (boost::format("%1%") % (formatter(*it))).str() + << (nrFrontals() > 1 ? " " : ""); } - cout << "|"; - for (const_iterator it = beginParents(); it != endParents(); ++it) { - cout << " " << (boost::format("%1%")%(formatter(*it))).str(); + + if (nrParents()) { + 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 4a9515207..6d4a74abc 100644 --- a/gtsam/linear/tests/testGaussianConditional.cpp +++ b/gtsam/linear/tests/testGaussianConditional.cpp @@ -404,13 +404,23 @@ 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); + GaussianConditional conditional(X(0), b, Matrix2::Identity(), + noiseModel::Isotropic::Sigma(2, sigma)); // Test printing for single parent. std::string expected = + "GaussianConditional p(x0)\n" + " R = [ 1 0 ]\n" + " [ 0 1 ]\n" + " d = [ 20 40 ]\n" + "isotropic dim=2 sigma=3\n"; + EXPECT(assert_print_equal(expected, conditional)); + + auto conditional1 = + GaussianConditional::FromMeanAndStddev(X(0), A1, X(1), b, sigma); + + // Test printing for single parent. + std::string expected1 = "GaussianConditional p(x0 | x1)\n" " R = [ 1 0 ]\n" " [ 0 1 ]\n" @@ -418,7 +428,7 @@ TEST(GaussianConditional, Print) { " [ -3 -4 ]\n" " d = [ 20 40 ]\n" "isotropic dim=2 sigma=3\n"; - EXPECT(assert_print_equal(expected, conditional, s)); + EXPECT(assert_print_equal(expected1, conditional1)); // Test printing for multiple parents. auto conditional2 = GaussianConditional::FromMeanAndStddev(X(0), A1, Y(0), A2, @@ -433,7 +443,7 @@ TEST(GaussianConditional, Print) { " [ -7 -8 ]\n" " d = [ 20 40 ]\n" "isotropic dim=2 sigma=3\n"; - EXPECT(assert_print_equal(expected2, conditional2, s)); + EXPECT(assert_print_equal(expected2, conditional2)); } /* ************************************************************************* */ From 0dfd69fa4af4028672636a77dafdf7c4ab1faf13 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Fri, 25 Mar 2022 16:50:21 -0400 Subject: [PATCH 0229/1686] update comment in test --- gtsam/linear/tests/testGaussianConditional.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/linear/tests/testGaussianConditional.cpp b/gtsam/linear/tests/testGaussianConditional.cpp index 6d4a74abc..5fbde44e0 100644 --- a/gtsam/linear/tests/testGaussianConditional.cpp +++ b/gtsam/linear/tests/testGaussianConditional.cpp @@ -407,7 +407,7 @@ TEST(GaussianConditional, Print) { GaussianConditional conditional(X(0), b, Matrix2::Identity(), noiseModel::Isotropic::Sigma(2, sigma)); - // Test printing for single parent. + // Test printing for no parents. std::string expected = "GaussianConditional p(x0)\n" " R = [ 1 0 ]\n" 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 0230/1686] 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 d2dc620b1e3031fc35c5ebe9d5030235b54ebf68 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Fri, 25 Mar 2022 17:14:00 -0600 Subject: [PATCH 0231/1686] Add Python bindings --- gtsam/hybrid/GaussianMixture.cpp | 19 ++- gtsam/hybrid/GaussianMixture.h | 5 + gtsam/hybrid/GaussianMixtureFactor.cpp | 45 ++++--- gtsam/hybrid/GaussianMixtureFactor.h | 11 +- gtsam/hybrid/HybridConditional.cpp | 9 +- gtsam/hybrid/HybridDiscreteFactor.h | 4 +- gtsam/hybrid/HybridFactorGraph.cpp | 14 ++ gtsam/hybrid/HybridFactorGraph.h | 7 + gtsam/hybrid/hybrid.i | 134 +++++++++++++++++++ gtsam/hybrid/tests/testHybridConditional.cpp | 29 ++-- gtsam/inference/inference.i | 13 +- python/CMakeLists.txt | 1 + python/gtsam/preamble/hybrid.h | 14 ++ python/gtsam/specializations/hybrid.h | 4 + python/gtsam/tests/test_HybridFactorGraph.py | 49 +++++++ 15 files changed, 311 insertions(+), 47 deletions(-) create mode 100644 gtsam/hybrid/hybrid.i create mode 100644 python/gtsam/preamble/hybrid.h create mode 100644 python/gtsam/specializations/hybrid.h create mode 100644 python/gtsam/tests/test_HybridFactorGraph.py diff --git a/gtsam/hybrid/GaussianMixture.cpp b/gtsam/hybrid/GaussianMixture.cpp index 26668da59..bc674966c 100644 --- a/gtsam/hybrid/GaussianMixture.cpp +++ b/gtsam/hybrid/GaussianMixture.cpp @@ -35,12 +35,23 @@ GaussianMixture::GaussianMixture( BaseConditional(continuousFrontals.size()), conditionals_(conditionals) {} -const GaussianMixture::Conditionals& GaussianMixture::conditionals() { +const GaussianMixture::Conditionals &GaussianMixture::conditionals() { return conditionals_; } +GaussianMixture GaussianMixture::FromConditionalList( + const KeyVector &continuousFrontals, const KeyVector &continuousParents, + const DiscreteKeys &discreteParents, + const std::vector &conditionalsList) { + Conditionals dt(discreteParents, conditionalsList); + + return GaussianMixture(continuousFrontals, continuousParents, discreteParents, + dt); +} + /* *******************************************************************************/ -GaussianMixture::Sum GaussianMixture::addTo(const GaussianMixture::Sum &sum) const { +GaussianMixture::Sum GaussianMixture::addTo( + const GaussianMixture::Sum &sum) const { using Y = GaussianFactorGraph; auto add = [](const Y &graph1, const Y &graph2) { auto result = graph1; @@ -66,7 +77,7 @@ bool GaussianMixture::equals(const HybridFactor &lf, double tol) const { } void GaussianMixture::print(const std::string &s, - const KeyFormatter &formatter) const { + const KeyFormatter &formatter) const { std::cout << s << ": "; if (isContinuous_) std::cout << "Cont. "; if (isDiscrete_) std::cout << "Disc. "; @@ -88,4 +99,4 @@ void GaussianMixture::print(const std::string &s, return rd.str(); }); } -} // namespace gtsam \ No newline at end of file +} // namespace gtsam diff --git a/gtsam/hybrid/GaussianMixture.h b/gtsam/hybrid/GaussianMixture.h index 9879e80bd..4412e741c 100644 --- a/gtsam/hybrid/GaussianMixture.h +++ b/gtsam/hybrid/GaussianMixture.h @@ -60,6 +60,11 @@ class GaussianMixture : public HybridFactor, /* *******************************************************************************/ Sum wrappedConditionals() const; + static This FromConditionalList( + const KeyVector &continuousFrontals, const KeyVector &continuousParents, + const DiscreteKeys &discreteParents, + const std::vector &conditionals); + bool equals(const HybridFactor &lf, double tol = 1e-9) const override; void print( diff --git a/gtsam/hybrid/GaussianMixtureFactor.cpp b/gtsam/hybrid/GaussianMixtureFactor.cpp index 61cfb1d70..3963e675e 100644 --- a/gtsam/hybrid/GaussianMixtureFactor.cpp +++ b/gtsam/hybrid/GaussianMixtureFactor.cpp @@ -18,43 +18,52 @@ * @date Mar 12, 2022 */ -#include - -#include -#include -#include #include +#include +#include +#include +#include namespace gtsam { GaussianMixtureFactor::GaussianMixtureFactor(const KeyVector &continuousKeys, - const DiscreteKeys &discreteKeys, - const Factors &factors) : Base(continuousKeys, discreteKeys), - factors_(factors) {} + const DiscreteKeys &discreteKeys, + const Factors &factors) + : Base(continuousKeys, discreteKeys), factors_(factors) {} bool GaussianMixtureFactor::equals(const HybridFactor &lf, double tol) const { return false; } -void GaussianMixtureFactor::print(const std::string &s, const KeyFormatter &formatter) const { +GaussianMixtureFactor GaussianMixtureFactor::FromFactorList( + const KeyVector &continuousKeys, const DiscreteKeys &discreteKeys, + const std::vector &factorsList) { + Factors dt(discreteKeys, factorsList); + + return GaussianMixtureFactor(continuousKeys, discreteKeys, dt); +} + +void GaussianMixtureFactor::print(const std::string &s, + const KeyFormatter &formatter) const { HybridFactor::print(s, formatter); factors_.print( - "mixture = ", - [&](Key k) { - return formatter(k); - }, [&](const GaussianFactor::shared_ptr &gf) -> std::string { + "mixture = ", [&](Key k) { return formatter(k); }, + [&](const GaussianFactor::shared_ptr &gf) -> std::string { RedirectCout rd; - if (!gf->empty()) gf->print("", formatter); - else return {"nullptr"}; + if (!gf->empty()) + gf->print("", formatter); + else + return {"nullptr"}; return rd.str(); }); } -const GaussianMixtureFactor::Factors& GaussianMixtureFactor::factors() { +const GaussianMixtureFactor::Factors &GaussianMixtureFactor::factors() { return factors_; } /* *******************************************************************************/ -GaussianMixtureFactor::Sum GaussianMixtureFactor::addTo(const GaussianMixtureFactor::Sum &sum) const { +GaussianMixtureFactor::Sum GaussianMixtureFactor::addTo( + const GaussianMixtureFactor::Sum &sum) const { using Y = GaussianFactorGraph; auto add = [](const Y &graph1, const Y &graph2) { auto result = graph1; @@ -74,4 +83,4 @@ GaussianMixtureFactor::Sum GaussianMixtureFactor::wrappedFactors() const { }; return {factors_, wrap}; } -} +} // namespace gtsam diff --git a/gtsam/hybrid/GaussianMixtureFactor.h b/gtsam/hybrid/GaussianMixtureFactor.h index 4cd5e71de..57a0cca03 100644 --- a/gtsam/hybrid/GaussianMixtureFactor.h +++ b/gtsam/hybrid/GaussianMixtureFactor.h @@ -29,6 +29,8 @@ namespace gtsam { class GaussianFactorGraph; +typedef std::vector GaussianFactorVector; + class GaussianMixtureFactor : public HybridFactor { public: using Base = HybridFactor; @@ -42,11 +44,16 @@ class GaussianMixtureFactor : public HybridFactor { GaussianMixtureFactor() = default; GaussianMixtureFactor(const KeyVector &continuousKeys, - const DiscreteKeys &discreteKeys, const Factors &factors); + const DiscreteKeys &discreteKeys, + const Factors &factors); using Sum = DecisionTree; - const Factors& factors(); + const Factors &factors(); + + static This FromFactorList( + const KeyVector &continuousKeys, const DiscreteKeys &discreteKeys, + const std::vector &factors); /* *******************************************************************************/ Sum addTo(const Sum &sum) const; diff --git a/gtsam/hybrid/HybridConditional.cpp b/gtsam/hybrid/HybridConditional.cpp index ed4b01608..48bee192c 100644 --- a/gtsam/hybrid/HybridConditional.cpp +++ b/gtsam/hybrid/HybridConditional.cpp @@ -16,9 +16,9 @@ */ #include +#include #include -#include "gtsam/hybrid/HybridFactor.h" -#include "gtsam/inference/Key.h" +#include namespace gtsam { @@ -27,8 +27,9 @@ HybridConditional::HybridConditional(const KeyVector &continuousFrontals, const KeyVector &continuousParents, const DiscreteKeys &discreteParents) : HybridConditional( - CollectKeys({continuousFrontals.begin(), continuousFrontals.end()}, - KeyVector {continuousParents.begin(), continuousParents.end()}), + CollectKeys( + {continuousFrontals.begin(), continuousFrontals.end()}, + KeyVector{continuousParents.begin(), continuousParents.end()}), CollectDiscreteKeys( {discreteFrontals.begin(), discreteFrontals.end()}, {discreteParents.begin(), discreteParents.end()}), diff --git a/gtsam/hybrid/HybridDiscreteFactor.h b/gtsam/hybrid/HybridDiscreteFactor.h index c55c5ecf0..809510eac 100644 --- a/gtsam/hybrid/HybridDiscreteFactor.h +++ b/gtsam/hybrid/HybridDiscreteFactor.h @@ -35,10 +35,10 @@ class HybridDiscreteFactor : public HybridFactor { DiscreteFactor::shared_ptr inner; - // Implicit conversion from a shared ptr of GF + // Implicit conversion from a shared ptr of DF HybridDiscreteFactor(DiscreteFactor::shared_ptr other); - // Forwarding constructor from concrete JacobianFactor + // Forwarding constructor from concrete DecisionTreeFactor HybridDiscreteFactor(DecisionTreeFactor &&dtf); public: diff --git a/gtsam/hybrid/HybridFactorGraph.cpp b/gtsam/hybrid/HybridFactorGraph.cpp index 9e7eebc57..6c7599a12 100644 --- a/gtsam/hybrid/HybridFactorGraph.cpp +++ b/gtsam/hybrid/HybridFactorGraph.cpp @@ -35,6 +35,7 @@ #include #include #include +#include #include #include @@ -380,4 +381,17 @@ EliminateHybrid(const HybridFactorGraph &factors, const Ordering &frontalKeys) { void HybridFactorGraph::add(JacobianFactor &&factor) { FactorGraph::add(boost::make_shared(std::move(factor))); } + +void HybridFactorGraph::add(DecisionTreeFactor &&factor) { + FactorGraph::add(boost::make_shared(std::move(factor))); +} + +void HybridFactorGraph::add(DecisionTreeFactor::shared_ptr factor) { + FactorGraph::add(boost::make_shared(factor)); +} + +void HybridFactorGraph::add(JacobianFactor::shared_ptr factor) { + FactorGraph::add(boost::make_shared(factor)); +} + } // namespace gtsam diff --git a/gtsam/hybrid/HybridFactorGraph.h b/gtsam/hybrid/HybridFactorGraph.h index 21332d80a..bfd6a8690 100644 --- a/gtsam/hybrid/HybridFactorGraph.h +++ b/gtsam/hybrid/HybridFactorGraph.h @@ -32,6 +32,7 @@ class HybridBayesNet; class HybridEliminationTree; class HybridBayesTree; class HybridJunctionTree; +class DecisionTreeFactor; class JacobianFactor; @@ -98,6 +99,12 @@ class HybridFactorGraph : public FactorGraph, /// Add a factor directly using a shared_ptr. void add(JacobianFactor&& factor); + + void add(DecisionTreeFactor&& factor); + + void add(boost::shared_ptr factor); + + void add(boost::shared_ptr factor); }; } // namespace gtsam diff --git a/gtsam/hybrid/hybrid.i b/gtsam/hybrid/hybrid.i new file mode 100644 index 000000000..c84cd82c5 --- /dev/null +++ b/gtsam/hybrid/hybrid.i @@ -0,0 +1,134 @@ +//************************************************************************* +// hybrid +//************************************************************************* + +namespace gtsam { + +#include +virtual class HybridFactor { + void print(string s = "HybridFactor\n", + const gtsam::KeyFormatter& keyFormatter = + gtsam::DefaultKeyFormatter) const; + bool equals(const gtsam::HybridFactor& other, double tol = 1e-9) const; + bool empty() const; + size_t size() const; + gtsam::KeyVector keys() const; +}; + +#include +class GaussianMixtureFactor : gtsam::HybridFactor { + static GaussianMixtureFactor FromFactorList( + const gtsam::KeyVector& continuousKeys, + const gtsam::DiscreteKeys& discreteKeys, + const std::vector& factorsList); + + void print(string s = "GaussianMixtureFactor\n", + const gtsam::KeyFormatter& keyFormatter = + gtsam::DefaultKeyFormatter) const; +}; + +#include +class GaussianMixture : gtsam::HybridFactor { + static GaussianMixture FromConditionalList( + const gtsam::KeyVector& continuousFrontals, + const gtsam::KeyVector& continuousParents, + const gtsam::DiscreteKeys& discreteParents, + const std::vector& + conditionalsList); + + void print(string s = "GaussianMixture\n", + const gtsam::KeyFormatter& keyFormatter = + gtsam::DefaultKeyFormatter) const; +}; + +#include +class HybridBayesTreeClique { + HybridBayesTreeClique(); + HybridBayesTreeClique(const gtsam::HybridConditional* conditional); + const gtsam::HybridConditional* conditional() const; + bool isRoot() const; + // double evaluate(const gtsam::HybridValues& values) const; +}; + +#include +class HybridBayesTree { + HybridBayesTree(); + void print(string s = "HybridBayesTree\n", + const gtsam::KeyFormatter& keyFormatter = + gtsam::DefaultKeyFormatter) const; + bool equals(const gtsam::HybridBayesTree& other, double tol = 1e-9) const; + + size_t size() const; + bool empty() const; + const HybridBayesTreeClique* operator[](size_t j) const; + + string dot(const gtsam::KeyFormatter& keyFormatter = + gtsam::DefaultKeyFormatter) const; +}; + +class HybridBayesNet { + HybridBayesNet(); + void add(const gtsam::HybridConditional& s); + bool empty() const; + size_t size() const; + gtsam::KeySet keys() const; + const gtsam::HybridConditional* at(size_t i) const; + void print(string s = "HybridBayesNet\n", + const gtsam::KeyFormatter& keyFormatter = + gtsam::DefaultKeyFormatter) const; + bool equals(const gtsam::HybridBayesNet& other, double tol = 1e-9) const; + + string dot( + const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter, + const gtsam::DotWriter& writer = gtsam::DotWriter()) const; + void saveGraph( + string s, + const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter, + const gtsam::DotWriter& writer = gtsam::DotWriter()) const; +}; + +#include +class HybridFactorGraph { + HybridFactorGraph(); + HybridFactorGraph(const gtsam::HybridBayesNet& bayesNet); + + // Building the graph + void push_back(const gtsam::HybridFactor* factor); + void push_back(const gtsam::HybridConditional* conditional); + void push_back(const gtsam::HybridFactorGraph& graph); + void push_back(const gtsam::HybridBayesNet& bayesNet); + void push_back(const gtsam::HybridBayesTree& bayesTree); + void push_back(const gtsam::GaussianMixtureFactor* gmm); + + void add(gtsam::DecisionTreeFactor* factor); + void add(gtsam::JacobianFactor* factor); + + bool empty() const; + size_t size() const; + gtsam::KeySet keys() const; + const gtsam::HybridFactor* at(size_t i) const; + + void print(string s = "") const; + bool equals(const gtsam::HybridFactorGraph& fg, double tol = 1e-9) const; + + gtsam::HybridBayesNet* eliminateSequential(); + gtsam::HybridBayesNet* eliminateSequential( + gtsam::Ordering::OrderingType type); + gtsam::HybridBayesNet* eliminateSequential(const gtsam::Ordering& ordering); + pair + eliminatePartialSequential(const gtsam::Ordering& ordering); + + gtsam::HybridBayesTree* eliminateMultifrontal(); + gtsam::HybridBayesTree* eliminateMultifrontal( + gtsam::Ordering::OrderingType type); + gtsam::HybridBayesTree* eliminateMultifrontal( + const gtsam::Ordering& ordering); + pair + eliminatePartialMultifrontal(const gtsam::Ordering& ordering); + + string dot( + const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter, + const gtsam::DotWriter& writer = gtsam::DotWriter()) const; +}; + +} // namespace gtsam diff --git a/gtsam/hybrid/tests/testHybridConditional.cpp b/gtsam/hybrid/tests/testHybridConditional.cpp index 95703b0af..97685b87d 100644 --- a/gtsam/hybrid/tests/testHybridConditional.cpp +++ b/gtsam/hybrid/tests/testHybridConditional.cpp @@ -133,15 +133,19 @@ TEST(HybridFactorGraph, eliminateFullMultifrontalSimple) { hfg.add(JacobianFactor(X(0), I_3x3, Z_3x1)); hfg.add(JacobianFactor(X(0), I_3x3, X(1), -I_3x3, Z_3x1)); - DecisionTree dt( - C(1), boost::make_shared(X(1), I_3x3, Z_3x1), - boost::make_shared(X(1), I_3x3, Vector3::Ones())); + // DecisionTree dt( + // C(1), boost::make_shared(X(1), I_3x3, Z_3x1), + // boost::make_shared(X(1), I_3x3, Vector3::Ones())); + + // hfg.add(GaussianMixtureFactor({X(1)}, {c1}, dt)); + hfg.add(GaussianMixtureFactor::FromFactorList( + {X(1)}, {{C(1), 2}}, + {boost::make_shared(X(1), I_3x3, Z_3x1), + boost::make_shared(X(1), I_3x3, Vector3::Ones())})); - hfg.add(GaussianMixtureFactor({X(1)}, {c1}, dt)); // hfg.add(GaussianMixtureFactor({X(0)}, {c1}, dt)); - hfg.add(HybridDiscreteFactor(DecisionTreeFactor(c1, {2, 8}))); - hfg.add(HybridDiscreteFactor( - DecisionTreeFactor({{C(1), 2}, {C(2), 2}}, "1 2 3 4"))); + hfg.add(DecisionTreeFactor(c1, {2, 8})); + hfg.add(DecisionTreeFactor({{C(1), 2}, {C(2), 2}}, "1 2 3 4")); // hfg.add(HybridDiscreteFactor(DecisionTreeFactor({{C(2), 2}, {C(3), 2}}, "1 // 2 3 4"))); hfg.add(HybridDiscreteFactor(DecisionTreeFactor({{C(3), 2}, // {C(1), 2}}, "1 2 2 1"))); @@ -199,11 +203,14 @@ TEST_DISABLED(HybridFactorGraph, eliminateFullMultifrontalTwoClique) { hfg.add(JacobianFactor(X(1), I_3x3, X(2), -I_3x3, Z_3x1)); { - DecisionTree dt( - C(0), boost::make_shared(X(0), I_3x3, Z_3x1), - boost::make_shared(X(0), I_3x3, Vector3::Ones())); + // DecisionTree dt( + // C(0), boost::make_shared(X(0), I_3x3, Z_3x1), + // boost::make_shared(X(0), I_3x3, Vector3::Ones())); - hfg.add(GaussianMixtureFactor({X(0)}, {{C(0), 2}}, dt)); + hfg.add(GaussianMixtureFactor::FromFactorList( + {X(0)}, {{C(0), 2}}, + {boost::make_shared(X(0), I_3x3, Z_3x1), + boost::make_shared(X(0), I_3x3, Vector3::Ones())})); DecisionTree dt1( C(1), boost::make_shared(X(2), I_3x3, Z_3x1), diff --git a/gtsam/inference/inference.i b/gtsam/inference/inference.i index e7b074ec4..bbf1b2daa 100644 --- a/gtsam/inference/inference.i +++ b/gtsam/inference/inference.i @@ -9,6 +9,7 @@ namespace gtsam { #include #include #include +#include #include @@ -106,36 +107,36 @@ class Ordering { template < FACTOR_GRAPH = {gtsam::NonlinearFactorGraph, gtsam::DiscreteFactorGraph, - gtsam::SymbolicFactorGraph, gtsam::GaussianFactorGraph}> + gtsam::SymbolicFactorGraph, gtsam::GaussianFactorGraph, gtsam::HybridFactorGraph}> static gtsam::Ordering Colamd(const FACTOR_GRAPH& graph); template < FACTOR_GRAPH = {gtsam::NonlinearFactorGraph, gtsam::DiscreteFactorGraph, - gtsam::SymbolicFactorGraph, gtsam::GaussianFactorGraph}> + gtsam::SymbolicFactorGraph, gtsam::GaussianFactorGraph, gtsam::HybridFactorGraph}> static gtsam::Ordering ColamdConstrainedLast( const FACTOR_GRAPH& graph, const gtsam::KeyVector& constrainLast, bool forceOrder = false); template < FACTOR_GRAPH = {gtsam::NonlinearFactorGraph, gtsam::DiscreteFactorGraph, - gtsam::SymbolicFactorGraph, gtsam::GaussianFactorGraph}> + gtsam::SymbolicFactorGraph, gtsam::GaussianFactorGraph, gtsam::HybridFactorGraph}> static gtsam::Ordering ColamdConstrainedFirst( const FACTOR_GRAPH& graph, const gtsam::KeyVector& constrainFirst, bool forceOrder = false); template < FACTOR_GRAPH = {gtsam::NonlinearFactorGraph, gtsam::DiscreteFactorGraph, - gtsam::SymbolicFactorGraph, gtsam::GaussianFactorGraph}> + gtsam::SymbolicFactorGraph, gtsam::GaussianFactorGraph, gtsam::HybridFactorGraph}> static gtsam::Ordering Natural(const FACTOR_GRAPH& graph); template < FACTOR_GRAPH = {gtsam::NonlinearFactorGraph, gtsam::DiscreteFactorGraph, - gtsam::SymbolicFactorGraph, gtsam::GaussianFactorGraph}> + gtsam::SymbolicFactorGraph, gtsam::GaussianFactorGraph, gtsam::HybridFactorGraph}> static gtsam::Ordering Metis(const FACTOR_GRAPH& graph); template < FACTOR_GRAPH = {gtsam::NonlinearFactorGraph, gtsam::DiscreteFactorGraph, - gtsam::SymbolicFactorGraph, gtsam::GaussianFactorGraph}> + gtsam::SymbolicFactorGraph, gtsam::GaussianFactorGraph, gtsam::HybridFactorGraph}> static gtsam::Ordering Create(gtsam::Ordering::OrderingType orderingType, const FACTOR_GRAPH& graph); diff --git a/python/CMakeLists.txt b/python/CMakeLists.txt index 85ddc7b6d..5059ac95d 100644 --- a/python/CMakeLists.txt +++ b/python/CMakeLists.txt @@ -65,6 +65,7 @@ set(interface_headers ${PROJECT_SOURCE_DIR}/gtsam/sfm/sfm.i ${PROJECT_SOURCE_DIR}/gtsam/navigation/navigation.i ${PROJECT_SOURCE_DIR}/gtsam/basis/basis.i + ${PROJECT_SOURCE_DIR}/gtsam/hybrid/hybrid.i ) set(GTSAM_PYTHON_TARGET gtsam_py) diff --git a/python/gtsam/preamble/hybrid.h b/python/gtsam/preamble/hybrid.h new file mode 100644 index 000000000..56a07cfdd --- /dev/null +++ b/python/gtsam/preamble/hybrid.h @@ -0,0 +1,14 @@ +/* Please refer to: + * https://pybind11.readthedocs.io/en/stable/advanced/cast/stl.html + * These are required to save one copy operation on Python calls. + * + * NOTES + * ================= + * + * `PYBIND11_MAKE_OPAQUE` will mark the type as "opaque" for the pybind11 + * automatic STL binding, such that the raw objects can be accessed in Python. + * Without this they will be automatically converted to a Python object, and all + * mutations on Python side will not be reflected on C++. + */ + +#include diff --git a/python/gtsam/specializations/hybrid.h b/python/gtsam/specializations/hybrid.h new file mode 100644 index 000000000..bede6d86c --- /dev/null +++ b/python/gtsam/specializations/hybrid.h @@ -0,0 +1,4 @@ + +py::bind_vector >(m_, "GaussianFactorVector"); + +py::implicitly_convertible >(); diff --git a/python/gtsam/tests/test_HybridFactorGraph.py b/python/gtsam/tests/test_HybridFactorGraph.py new file mode 100644 index 000000000..d8b0f1f33 --- /dev/null +++ b/python/gtsam/tests/test_HybridFactorGraph.py @@ -0,0 +1,49 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +Unit tests for Hybrid Factor Graphs. +Author: Fan Jiang +""" +# pylint: disable=invalid-name, no-name-in-module, no-member + +from __future__ import print_function + +import unittest + +import gtsam +import numpy as np +from gtsam.symbol_shorthand import X, C +from gtsam.utils.test_case import GtsamTestCase + + +class TestHybridFactorGraph(GtsamTestCase): + def test_create(self): + noiseModel = gtsam.noiseModel.Unit.Create(3) + dk = gtsam.DiscreteKeys() + dk.push_back((C(0), 2)) + + # print(dk.at(0)) + jf1 = gtsam.JacobianFactor(X(0), np.eye(3), np.zeros((3, 1)), + noiseModel) + jf2 = gtsam.JacobianFactor(X(0), np.eye(3), np.ones((3, 1)), + noiseModel) + + gmf = gtsam.GaussianMixtureFactor.FromFactorList([X(0)], dk, + [jf1, jf2]) + + hfg = gtsam.HybridFactorGraph() + hfg.add(jf1) + hfg.add(jf2) + hfg.push_back(gmf) + + hfg.eliminateSequential( + gtsam.Ordering.ColamdConstrainedLastHybridFactorGraph( + hfg, [C(0)])).print() + + +if __name__ == "__main__": + unittest.main() From 7f2fa61fb53422aa195cd5815d51f3b5c4e47814 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Fri, 25 Mar 2022 23:28:40 -0600 Subject: [PATCH 0232/1686] Added more Python examples --- gtsam/hybrid/HybridConditional.h | 34 +++++++++++++++----- gtsam/hybrid/HybridFactorGraph.cpp | 26 +++++++-------- gtsam/hybrid/HybridJunctionTree.cpp | 11 +++++++ gtsam/hybrid/hybrid.i | 11 +++++++ python/gtsam/tests/test_HybridFactorGraph.py | 12 +++++-- 5 files changed, 71 insertions(+), 23 deletions(-) diff --git a/gtsam/hybrid/HybridConditional.h b/gtsam/hybrid/HybridConditional.h index 5fdf5064a..dea8fa9f4 100644 --- a/gtsam/hybrid/HybridConditional.h +++ b/gtsam/hybrid/HybridConditional.h @@ -19,7 +19,10 @@ #include #include +#include #include +#include +#include #include #include @@ -27,11 +30,8 @@ #include #include #include -#include "gtsam/hybrid/GaussianMixture.h" -#include -#include -#include +#include "gtsam/hybrid/GaussianMixture.h" namespace gtsam { @@ -44,6 +44,19 @@ class HybridFactorGraph; * - DiscreteConditional * - GaussianConditional * - GaussianMixture + * + * The reason why this is important is that `Conditional` is a CRTP class. + * CRTP is static polymorphism such that all CRTP classes, while bearing the + * same name, are different classes not sharing a vtable. This prevents them + * from being contained in any container, and thus it is impossible to + * dynamically cast between them. A better option, as illustrated here, is + * treating them as an implementation detail - such that the hybrid mechanism + * does not know what is inside the HybridConditional. This prevents us from + * having diamond inheritances, and neutralized the need to change other + * components of GTSAM to make hybrid elimination work. + * + * A great reference to the type-erasure pattern is Edurado Madrid's CppCon + * talk. */ class GTSAM_EXPORT HybridConditional : public HybridFactor, @@ -76,15 +89,20 @@ class GTSAM_EXPORT HybridConditional const KeyVector& continuousParents, const DiscreteKeys& discreteParents); - HybridConditional(boost::shared_ptr continuousConditional); + HybridConditional( + boost::shared_ptr continuousConditional); HybridConditional(boost::shared_ptr discreteConditional); - + HybridConditional(boost::shared_ptr gaussianMixture); GaussianMixture::shared_ptr asMixture() { - if (!isHybrid_) throw std::invalid_argument("Not a mixture"); - return boost::static_pointer_cast(inner); + if (!isHybrid_) throw std::invalid_argument("Not a mixture"); + return boost::static_pointer_cast(inner); + } + + boost::shared_ptr getInner() { + return inner; } /// @} diff --git a/gtsam/hybrid/HybridFactorGraph.cpp b/gtsam/hybrid/HybridFactorGraph.cpp index 6c7599a12..7a26dfadb 100644 --- a/gtsam/hybrid/HybridFactorGraph.cpp +++ b/gtsam/hybrid/HybridFactorGraph.cpp @@ -57,7 +57,7 @@ static std::string GREEN = "\033[0;32m"; static std::string GREEN_BOLD = "\033[1;32m"; static std::string RESET = "\033[0m"; -static bool DEBUG = false; +constexpr bool DEBUG = false; static GaussianMixtureFactor::Sum &addGaussian( GaussianMixtureFactor::Sum &sum, const GaussianFactor::shared_ptr &factor) { @@ -123,7 +123,7 @@ EliminateHybrid(const HybridFactorGraph &factors, const Ordering &frontalKeys) { // However this is also the case with iSAM2, so no pressure :) // PREPROCESS: Identify the nature of the current elimination - std::unordered_map discreteCardinalities; + std::unordered_map mapFromKeyToDiscreteKey; std::set discreteSeparatorSet; std::set discreteFrontals; @@ -137,7 +137,7 @@ EliminateHybrid(const HybridFactorGraph &factors, const Ordering &frontalKeys) { frontalKeys.print(); } - // This initializes separatorKeys and discreteCardinalities + // This initializes separatorKeys and mapFromKeyToDiscreteKey for (auto &&factor : factors) { if (DEBUG) { std::cout << ">>> Adding factor: " << GREEN; @@ -147,7 +147,7 @@ EliminateHybrid(const HybridFactorGraph &factors, const Ordering &frontalKeys) { separatorKeys.insert(factor->begin(), factor->end()); if (!factor->isContinuous_) { for (auto &k : factor->discreteKeys_) { - discreteCardinalities[k.first] = k; + mapFromKeyToDiscreteKey[k.first] = k; } } } @@ -159,8 +159,8 @@ EliminateHybrid(const HybridFactorGraph &factors, const Ordering &frontalKeys) { // Fill in discrete frontals and continuous frontals for the end result for (auto &k : frontalKeys) { - if (discreteCardinalities.find(k) != discreteCardinalities.end()) { - discreteFrontals.insert(discreteCardinalities.at(k)); + if (mapFromKeyToDiscreteKey.find(k) != mapFromKeyToDiscreteKey.end()) { + discreteFrontals.insert(mapFromKeyToDiscreteKey.at(k)); } else { continuousFrontals.insert(k); allContinuousKeys.insert(k); @@ -169,8 +169,8 @@ EliminateHybrid(const HybridFactorGraph &factors, const Ordering &frontalKeys) { // Fill in discrete frontals and continuous frontals for the end result for (auto &k : separatorKeys) { - if (discreteCardinalities.find(k) != discreteCardinalities.end()) { - discreteSeparatorSet.insert(discreteCardinalities.at(k)); + if (mapFromKeyToDiscreteKey.find(k) != mapFromKeyToDiscreteKey.end()) { + discreteSeparatorSet.insert(mapFromKeyToDiscreteKey.at(k)); } else { continuousSeparator.insert(k); allContinuousKeys.insert(k); @@ -181,8 +181,8 @@ EliminateHybrid(const HybridFactorGraph &factors, const Ordering &frontalKeys) { if (DEBUG) { std::cout << RED_BOLD << "Keys: " << RESET; for (auto &f : frontalKeys) { - if (discreteCardinalities.find(f) != discreteCardinalities.end()) { - auto &key = discreteCardinalities.at(f); + if (mapFromKeyToDiscreteKey.find(f) != mapFromKeyToDiscreteKey.end()) { + auto &key = mapFromKeyToDiscreteKey.at(f); std::cout << boost::format(" (%1%,%2%),") % DefaultKeyFormatter(key.first) % key.second; } else { @@ -195,8 +195,8 @@ EliminateHybrid(const HybridFactorGraph &factors, const Ordering &frontalKeys) { } for (auto &f : separatorKeys) { - if (discreteCardinalities.find(f) != discreteCardinalities.end()) { - auto &key = discreteCardinalities.at(f); + if (mapFromKeyToDiscreteKey.find(f) != mapFromKeyToDiscreteKey.end()) { + auto &key = mapFromKeyToDiscreteKey.at(f); std::cout << boost::format(" (%1%,%2%),") % DefaultKeyFormatter(key.first) % key.second; } else { @@ -209,7 +209,7 @@ EliminateHybrid(const HybridFactorGraph &factors, const Ordering &frontalKeys) { // NOTE: We should really defer the product here because of pruning // Case 1: we are only dealing with continuous - if (discreteCardinalities.empty() && !allContinuousKeys.empty()) { + if (mapFromKeyToDiscreteKey.empty() && !allContinuousKeys.empty()) { if (DEBUG) { std::cout << RED_BOLD << "CONT. ONLY" << RESET << "\n"; } diff --git a/gtsam/hybrid/HybridJunctionTree.cpp b/gtsam/hybrid/HybridJunctionTree.cpp index 7c48934fc..22b40ad05 100644 --- a/gtsam/hybrid/HybridJunctionTree.cpp +++ b/gtsam/hybrid/HybridJunctionTree.cpp @@ -59,10 +59,15 @@ struct HybridConstructorTraversalData { myData.myJTNode = boost::make_shared(node->key, node->factors); parentData.myJTNode->addChild(myData.myJTNode); +#ifndef NDEBUG std::cout << "Getting discrete info: "; +#endif for (HybridFactor::shared_ptr& f : node->factors) { for (auto& k : f->discreteKeys_) { +#ifndef NDEBUG std::cout << "DK: " << DefaultKeyFormatter(k.first) << "\n"; +#endif + myData.discreteKeys.insert(k.first); } } @@ -99,8 +104,10 @@ struct HybridConstructorTraversalData { boost::tie(myConditional, mySeparatorFactor) = internal::EliminateSymbolic(symbolicFactors, keyAsOrdering); +#ifndef NDEBUG std::cout << "Symbolic: "; myConditional->print(); +#endif // Store symbolic elimination results in the parent myData.parentData->childSymbolicConditionals.push_back(myConditional); @@ -129,15 +136,19 @@ struct HybridConstructorTraversalData { myData.discreteKeys.exists(myConditional->frontals()[0]); const bool theirType = myData.discreteKeys.exists(childConditionals[i]->frontals()[0]); +#ifndef NDEBUG std::cout << "Type: " << DefaultKeyFormatter(myConditional->frontals()[0]) << " vs " << DefaultKeyFormatter(childConditionals[i]->frontals()[0]) << "\n"; +#endif if (myType == theirType) { // Increment number of frontal variables myNrFrontals += nrFrontals[i]; +#ifndef NDEBUG std::cout << "Merging "; childConditionals[i]->print(); +#endif merge[i] = true; } } diff --git a/gtsam/hybrid/hybrid.i b/gtsam/hybrid/hybrid.i index c84cd82c5..052575011 100644 --- a/gtsam/hybrid/hybrid.i +++ b/gtsam/hybrid/hybrid.i @@ -15,6 +15,17 @@ virtual class HybridFactor { gtsam::KeyVector keys() const; }; +#include +virtual class HybridConditional { + void print(string s = "Hybrid Conditional\n", + const gtsam::KeyFormatter& keyFormatter = + gtsam::DefaultKeyFormatter) const; + bool equals(const gtsam::HybridConditional& other, double tol = 1e-9) const; + size_t nrFrontals() const; + size_t nrParents() const; + Factor* getInner(); +}; + #include class GaussianMixtureFactor : gtsam::HybridFactor { static GaussianMixtureFactor FromFactorList( diff --git a/python/gtsam/tests/test_HybridFactorGraph.py b/python/gtsam/tests/test_HybridFactorGraph.py index d8b0f1f33..48187b7a2 100644 --- a/python/gtsam/tests/test_HybridFactorGraph.py +++ b/python/gtsam/tests/test_HybridFactorGraph.py @@ -40,9 +40,17 @@ class TestHybridFactorGraph(GtsamTestCase): hfg.add(jf2) hfg.push_back(gmf) - hfg.eliminateSequential( + hbn = hfg.eliminateSequential( gtsam.Ordering.ColamdConstrainedLastHybridFactorGraph( - hfg, [C(0)])).print() + hfg, [C(0)])) + + print("hbn = ", hbn) + + mixture = hbn.at(0).getInner() + print(mixture) + + discrete_conditional = hbn.at(hbn.size()-1).getInner() + print(discrete_conditional) if __name__ == "__main__": From 08bbcc889ee44dc52e643613c91c244b48e45a66 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sat, 26 Mar 2022 15:57:52 -0400 Subject: [PATCH 0233/1686] 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 0234/1686] 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 0235/1686] 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 e86e4ade963a83013e59d40e5507aa87ea5d7293 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sat, 26 Mar 2022 17:45:37 -0400 Subject: [PATCH 0236/1686] Squashed 'wrap/' changes from 24da9d1be..1a7dc9722 1a7dc9722 Merge pull request #147 from borglab/update-pybind 772d6ce66 bump pybind11 to v2.9.1 git-subtree-dir: wrap git-subtree-split: 1a7dc9722e347162dadbf791fe1839d77bf3e3d8 --- pybind11/.appveyor.yml | 2 +- pybind11/.clang-format | 19 + pybind11/.clang-tidy | 61 +- pybind11/.github/CODEOWNERS | 9 + pybind11/.github/CONTRIBUTING.md | 92 +- pybind11/.github/ISSUE_TEMPLATE/bug-report.md | 28 - .../.github/ISSUE_TEMPLATE/bug-report.yml | 45 + pybind11/.github/ISSUE_TEMPLATE/config.yml | 3 + .../.github/ISSUE_TEMPLATE/feature-request.md | 16 - pybind11/.github/ISSUE_TEMPLATE/question.md | 21 - pybind11/.github/dependabot.yml | 16 + pybind11/.github/labeler.yml | 8 + pybind11/.github/labeler_merged.yml | 3 + pybind11/.github/pull_request_template.md | 19 + pybind11/.github/workflows/ci.yml | 690 +++++++-- pybind11/.github/workflows/configure.yml | 58 +- pybind11/.github/workflows/format.yml | 17 +- pybind11/.github/workflows/labeler.yml | 16 + pybind11/.github/workflows/pip.yml | 108 ++ pybind11/.github/workflows/upstream.yml | 112 ++ pybind11/.gitignore | 2 + pybind11/.pre-commit-config.yaml | 85 +- pybind11/CMakeLists.txt | 86 +- pybind11/MANIFEST.in | 4 +- pybind11/README.md | 145 -- pybind11/README.rst | 180 +++ pybind11/docs/Doxyfile | 4 +- pybind11/docs/advanced/cast/custom.rst | 4 +- pybind11/docs/advanced/cast/eigen.rst | 6 +- pybind11/docs/advanced/cast/overview.rst | 182 +-- pybind11/docs/advanced/cast/stl.rst | 13 +- pybind11/docs/advanced/cast/strings.rst | 32 +- pybind11/docs/advanced/classes.rst | 100 +- pybind11/docs/advanced/embedding.rst | 37 +- pybind11/docs/advanced/exceptions.rst | 134 +- pybind11/docs/advanced/functions.rst | 94 +- pybind11/docs/advanced/misc.rst | 18 +- pybind11/docs/advanced/pycpp/numpy.rst | 73 +- pybind11/docs/advanced/pycpp/object.rst | 49 +- pybind11/docs/advanced/pycpp/utilities.rst | 27 +- pybind11/docs/advanced/smart_ptrs.rst | 1 + pybind11/docs/basics.rst | 19 +- pybind11/docs/benchmark.py | 42 +- pybind11/docs/changelog.rst | 862 ++++++++++- pybind11/docs/classes.rst | 42 +- pybind11/docs/cmake/index.rst | 8 + pybind11/docs/compiling.rst | 164 +- pybind11/docs/conf.py | 249 ++-- pybind11/docs/faq.rst | 81 +- pybind11/docs/index.rst | 13 +- pybind11/docs/intro.rst | 93 -- pybind11/docs/limitations.rst | 63 +- pybind11/docs/reference.rst | 15 +- pybind11/docs/release.rst | 110 +- pybind11/docs/requirements.txt | 10 +- pybind11/docs/upgrade.rst | 84 +- pybind11/include/pybind11/attr.h | 140 +- pybind11/include/pybind11/buffer_info.h | 38 +- pybind11/include/pybind11/cast.h | 1318 ++++------------- pybind11/include/pybind11/chrono.h | 40 +- pybind11/include/pybind11/complex.h | 2 +- pybind11/include/pybind11/detail/class.h | 119 +- pybind11/include/pybind11/detail/common.h | 309 +++- pybind11/include/pybind11/detail/descr.h | 61 +- pybind11/include/pybind11/detail/init.h | 24 +- pybind11/include/pybind11/detail/internals.h | 403 +++-- .../pybind11/detail/type_caster_base.h | 985 ++++++++++++ pybind11/include/pybind11/detail/typeid.h | 2 +- pybind11/include/pybind11/eigen.h | 117 +- pybind11/include/pybind11/embed.h | 155 +- pybind11/include/pybind11/eval.h | 47 +- pybind11/include/pybind11/functional.h | 48 +- pybind11/include/pybind11/gil.h | 193 +++ pybind11/include/pybind11/iostream.h | 121 +- pybind11/include/pybind11/numpy.h | 314 ++-- pybind11/include/pybind11/operators.h | 14 +- pybind11/include/pybind11/pybind11.h | 1173 +++++++++------ pybind11/include/pybind11/pytypes.h | 469 ++++-- pybind11/include/pybind11/stl.h | 89 +- pybind11/include/pybind11/stl/filesystem.h | 103 ++ pybind11/include/pybind11/stl_bind.h | 194 ++- pybind11/noxfile.py | 93 ++ pybind11/pybind11/__init__.py | 5 +- pybind11/pybind11/__main__.py | 7 +- pybind11/pybind11/_version.py | 2 +- pybind11/pybind11/_version.pyi | 6 + pybind11/pybind11/commands.py | 3 +- pybind11/pybind11/py.typed | 0 pybind11/pybind11/setup_helpers.py | 284 +++- pybind11/pybind11/setup_helpers.pyi | 63 + pybind11/pyproject.toml | 40 +- pybind11/setup.cfg | 39 +- pybind11/setup.py | 55 +- pybind11/tests/CMakeLists.txt | 356 +++-- pybind11/tests/conftest.py | 26 +- pybind11/tests/constructor_stats.h | 2 +- pybind11/tests/env.py | 19 + .../tests/extra_python_package/test_files.py | 54 +- .../extra_setuptools/test_setuphelper.py | 68 +- pybind11/tests/local_bindings.h | 31 +- pybind11/tests/object.h | 14 +- .../tests/pybind11_cross_module_tests.cpp | 34 +- pybind11/tests/pybind11_tests.cpp | 8 +- pybind11/tests/pybind11_tests.h | 40 +- pybind11/tests/pytest.ini | 4 +- pybind11/tests/requirements.txt | 18 +- pybind11/tests/test_async.cpp | 2 +- pybind11/tests/test_buffers.cpp | 87 +- pybind11/tests/test_buffers.py | 82 +- pybind11/tests/test_builtin_casters.cpp | 152 +- pybind11/tests/test_builtin_casters.py | 274 +++- pybind11/tests/test_call_policies.cpp | 8 +- pybind11/tests/test_call_policies.py | 84 +- pybind11/tests/test_callbacks.cpp | 113 +- pybind11/tests/test_callbacks.py | 93 +- pybind11/tests/test_chrono.py | 78 +- pybind11/tests/test_class.cpp | 129 +- pybind11/tests/test_class.py | 192 ++- .../tests/test_cmake_build/CMakeLists.txt | 7 +- pybind11/tests/test_cmake_build/embed.cpp | 4 +- .../installed_embed/CMakeLists.txt | 6 +- .../installed_function/CMakeLists.txt | 3 +- .../installed_target/CMakeLists.txt | 3 +- .../subdirectory_embed/CMakeLists.txt | 8 +- .../subdirectory_function/CMakeLists.txt | 5 +- .../subdirectory_target/CMakeLists.txt | 5 +- pybind11/tests/test_cmake_build/test.py | 4 + pybind11/tests/test_const_name.cpp | 70 + pybind11/tests/test_const_name.py | 31 + .../tests/test_constants_and_functions.cpp | 54 +- .../tests/test_constants_and_functions.py | 11 + pybind11/tests/test_copy_move.cpp | 61 +- pybind11/tests/test_copy_move.py | 25 +- pybind11/tests/test_custom_type_casters.cpp | 45 +- pybind11/tests/test_custom_type_casters.py | 47 +- pybind11/tests/test_custom_type_setup.cpp | 41 + pybind11/tests/test_custom_type_setup.py | 50 + pybind11/tests/test_docstring_options.cpp | 8 + pybind11/tests/test_docstring_options.py | 13 +- pybind11/tests/test_eigen.cpp | 79 +- pybind11/tests/test_eigen.py | 290 ++-- pybind11/tests/test_embed/CMakeLists.txt | 8 +- pybind11/tests/test_embed/external_module.cpp | 2 +- .../tests/test_embed/test_interpreter.cpp | 147 +- pybind11/tests/test_embed/test_interpreter.py | 5 + pybind11/tests/test_embed/test_trampoline.py | 18 + pybind11/tests/test_enum.cpp | 61 + pybind11/tests/test_enum.py | 117 +- pybind11/tests/test_eval.cpp | 34 +- pybind11/tests/test_eval.py | 26 +- pybind11/tests/test_eval_call.py | 2 +- pybind11/tests/test_exceptions.cpp | 105 +- pybind11/tests/test_exceptions.h | 12 + pybind11/tests/test_exceptions.py | 106 +- pybind11/tests/test_factory_constructors.cpp | 226 +-- pybind11/tests/test_factory_constructors.py | 122 +- pybind11/tests/test_gil_scoped.cpp | 27 +- pybind11/tests/test_gil_scoped.py | 21 +- pybind11/tests/test_iostream.cpp | 86 +- pybind11/tests/test_iostream.py | 164 +- pybind11/tests/test_kwargs_and_defaults.cpp | 81 +- pybind11/tests/test_kwargs_and_defaults.py | 207 ++- pybind11/tests/test_local_bindings.cpp | 12 +- pybind11/tests/test_local_bindings.py | 57 +- .../tests/test_methods_and_attributes.cpp | 157 +- pybind11/tests/test_methods_and_attributes.py | 147 +- pybind11/tests/test_modules.cpp | 10 +- pybind11/tests/test_modules.py | 31 +- pybind11/tests/test_multiple_inheritance.cpp | 148 +- pybind11/tests/test_multiple_inheritance.py | 154 +- pybind11/tests/test_numpy_array.cpp | 228 +-- pybind11/tests/test_numpy_array.py | 297 ++-- pybind11/tests/test_numpy_dtypes.cpp | 78 +- pybind11/tests/test_numpy_dtypes.py | 315 ++-- pybind11/tests/test_numpy_vectorize.cpp | 72 +- pybind11/tests/test_numpy_vectorize.py | 159 +- pybind11/tests/test_opaque_types.cpp | 8 +- pybind11/tests/test_opaque_types.py | 16 +- pybind11/tests/test_operator_overloading.cpp | 46 +- pybind11/tests/test_operator_overloading.py | 50 +- pybind11/tests/test_pickling.cpp | 93 +- pybind11/tests/test_pickling.py | 40 +- pybind11/tests/test_pytypes.cpp | 262 +++- pybind11/tests/test_pytypes.py | 363 ++++- .../tests/test_sequences_and_iterators.cpp | 290 +++- .../tests/test_sequences_and_iterators.py | 98 +- pybind11/tests/test_smart_ptr.cpp | 434 +++--- pybind11/tests/test_smart_ptr.py | 65 +- pybind11/tests/test_stl.cpp | 229 ++- pybind11/tests/test_stl.py | 156 +- pybind11/tests/test_stl_binders.cpp | 22 +- pybind11/tests/test_stl_binders.py | 103 +- pybind11/tests/test_tagbased_polymorphic.cpp | 18 +- pybind11/tests/test_tagbased_polymorphic.py | 14 +- pybind11/tests/test_thread.cpp | 66 + pybind11/tests/test_thread.py | 44 + pybind11/tests/test_virtual_functions.cpp | 91 +- pybind11/tests/test_virtual_functions.py | 118 +- pybind11/tests/valgrind-numpy-scipy.supp | 140 ++ pybind11/tests/valgrind-python.supp | 117 ++ pybind11/tools/FindEigen3.cmake | 3 + pybind11/tools/FindPythonLibsNew.cmake | 4 +- pybind11/tools/check-style.sh | 6 +- pybind11/tools/libsize.py | 7 +- pybind11/tools/make_changelog.py | 64 + pybind11/tools/pybind11Common.cmake | 141 +- pybind11/tools/pybind11Config.cmake.in | 194 ++- pybind11/tools/pybind11NewTools.cmake | 127 +- pybind11/tools/pybind11Tools.cmake | 92 +- pybind11/tools/pyproject.toml | 2 +- pybind11/tools/setup_global.py.in | 20 +- pybind11/tools/setup_main.py.in | 6 + 212 files changed, 15792 insertions(+), 5586 deletions(-) create mode 100644 pybind11/.clang-format create mode 100644 pybind11/.github/CODEOWNERS delete mode 100644 pybind11/.github/ISSUE_TEMPLATE/bug-report.md create mode 100644 pybind11/.github/ISSUE_TEMPLATE/bug-report.yml delete mode 100644 pybind11/.github/ISSUE_TEMPLATE/feature-request.md delete mode 100644 pybind11/.github/ISSUE_TEMPLATE/question.md create mode 100644 pybind11/.github/dependabot.yml create mode 100644 pybind11/.github/labeler.yml create mode 100644 pybind11/.github/labeler_merged.yml create mode 100644 pybind11/.github/pull_request_template.md create mode 100644 pybind11/.github/workflows/labeler.yml create mode 100644 pybind11/.github/workflows/pip.yml create mode 100644 pybind11/.github/workflows/upstream.yml delete mode 100644 pybind11/README.md create mode 100644 pybind11/README.rst create mode 100644 pybind11/docs/cmake/index.rst delete mode 100644 pybind11/docs/intro.rst create mode 100644 pybind11/include/pybind11/detail/type_caster_base.h create mode 100644 pybind11/include/pybind11/gil.h create mode 100644 pybind11/include/pybind11/stl/filesystem.h create mode 100644 pybind11/noxfile.py create mode 100644 pybind11/pybind11/_version.pyi create mode 100644 pybind11/pybind11/py.typed create mode 100644 pybind11/pybind11/setup_helpers.pyi create mode 100644 pybind11/tests/test_const_name.cpp create mode 100644 pybind11/tests/test_const_name.py create mode 100644 pybind11/tests/test_custom_type_setup.cpp create mode 100644 pybind11/tests/test_custom_type_setup.py create mode 100644 pybind11/tests/test_embed/test_trampoline.py create mode 100644 pybind11/tests/test_exceptions.h create mode 100644 pybind11/tests/test_thread.cpp create mode 100644 pybind11/tests/test_thread.py create mode 100644 pybind11/tests/valgrind-numpy-scipy.supp create mode 100644 pybind11/tests/valgrind-python.supp create mode 100755 pybind11/tools/make_changelog.py diff --git a/pybind11/.appveyor.yml b/pybind11/.appveyor.yml index 149a8a3dc..85445d41a 100644 --- a/pybind11/.appveyor.yml +++ b/pybind11/.appveyor.yml @@ -19,7 +19,7 @@ install: if ($env:PLATFORM -eq "x64") { $env:PYTHON = "$env:PYTHON-x64" } $env:PATH = "C:\Python$env:PYTHON\;C:\Python$env:PYTHON\Scripts\;$env:PATH" python -W ignore -m pip install --upgrade pip wheel - python -W ignore -m pip install pytest numpy --no-warn-script-location + python -W ignore -m pip install pytest numpy --no-warn-script-location pytest-timeout - ps: | Start-FileDownload 'https://gitlab.com/libeigen/eigen/-/archive/3.3.7/eigen-3.3.7.zip' 7z x eigen-3.3.7.zip -y > $null diff --git a/pybind11/.clang-format b/pybind11/.clang-format new file mode 100644 index 000000000..8e0fd8b01 --- /dev/null +++ b/pybind11/.clang-format @@ -0,0 +1,19 @@ +--- +# See all possible options and defaults with: +# clang-format --style=llvm --dump-config +BasedOnStyle: LLVM +AccessModifierOffset: -4 +AlwaysBreakTemplateDeclarations: Yes +BinPackArguments: false +BinPackParameters: false +BreakBeforeBinaryOperators: All +BreakConstructorInitializers: BeforeColon +ColumnLimit: 99 +IndentCaseLabels: true +IndentPPDirectives: AfterHash +IndentWidth: 4 +Language: Cpp +SpaceAfterCStyleCast: true +Standard: Cpp11 +TabWidth: 4 +... diff --git a/pybind11/.clang-tidy b/pybind11/.clang-tidy index e29d92989..d853a703c 100644 --- a/pybind11/.clang-tidy +++ b/pybind11/.clang-tidy @@ -1,13 +1,66 @@ FormatStyle: file Checks: ' +*bugprone*, +cppcoreguidelines-init-variables, +cppcoreguidelines-slicing, +clang-analyzer-optin.cplusplus.VirtualCall, +google-explicit-constructor, llvm-namespace-comment, -modernize-use-override, -readability-container-size-empty, -modernize-use-using, -modernize-use-equals-default, +misc-misplaced-const, +misc-non-copyable-objects, +misc-static-assert, +misc-throw-by-value-catch-by-reference, +misc-uniqueptr-reset-release, +misc-unused-parameters, +modernize-avoid-bind, +modernize-make-shared, +modernize-redundant-void-arg, +modernize-replace-auto-ptr, +modernize-replace-disallow-copy-and-assign-macro, +modernize-replace-random-shuffle, +modernize-shrink-to-fit, modernize-use-auto, +modernize-use-bool-literals, +modernize-use-equals-default, +modernize-use-equals-delete, +modernize-use-default-member-init, +modernize-use-noexcept, modernize-use-emplace, +modernize-use-override, +modernize-use-using, +*performance*, +readability-avoid-const-params-in-decls, +readability-const-return-type, +readability-container-size-empty, +readability-delete-null-pointer, +readability-else-after-return, +readability-implicit-bool-conversion, +readability-make-member-function-const, +readability-misplaced-array-index, +readability-non-const-parameter, +readability-redundant-function-ptr-dereference, +readability-redundant-smartptr-get, +readability-redundant-string-cstr, +readability-simplify-subscript-expr, +readability-static-accessed-through-instance, +readability-static-definition-in-anonymous-namespace, +readability-string-compare, +readability-suspicious-call-argument, +readability-uniqueptr-delete-release, +-bugprone-exception-escape, +-bugprone-reserved-identifier, +-bugprone-unused-raii, ' +CheckOptions: +- key: performance-for-range-copy.WarnOnAllAutoCopies + value: true +- key: performance-unnecessary-value-param.AllowedTypes + value: 'exception_ptr$;' +- key: readability-implicit-bool-conversion.AllowPointerConditions + value: true + HeaderFilterRegex: 'pybind11/.*h' + +WarningsAsErrors: '*' diff --git a/pybind11/.github/CODEOWNERS b/pybind11/.github/CODEOWNERS new file mode 100644 index 000000000..4e2c66902 --- /dev/null +++ b/pybind11/.github/CODEOWNERS @@ -0,0 +1,9 @@ +*.cmake @henryiii +CMakeLists.txt @henryiii +*.yml @henryiii +*.yaml @henryiii +/tools/ @henryiii +/pybind11/ @henryiii +noxfile.py @henryiii +.clang-format @henryiii +.clang-tidy @henryiii diff --git a/pybind11/.github/CONTRIBUTING.md b/pybind11/.github/CONTRIBUTING.md index 4ced21baa..e8294c83c 100644 --- a/pybind11/.github/CONTRIBUTING.md +++ b/pybind11/.github/CONTRIBUTING.md @@ -53,6 +53,33 @@ derivative works thereof, in binary and source code form. ## Development of pybind11 +### Quick setup + +To setup a quick development environment, use [`nox`](https://nox.thea.codes). +This will allow you to do some common tasks with minimal setup effort, but will +take more time to run and be less flexible than a full development environment. +If you use [`pipx run nox`](https://pipx.pypa.io), you don't even need to +install `nox`. Examples: + +```bash +# List all available sessions +nox -l + +# Run linters +nox -s lint + +# Run tests on Python 3.9 +nox -s tests-3.9 + +# Build and preview docs +nox -s docs -- serve + +# Build SDists and wheels +nox -s build +``` + +### Full setup + To setup an ideal development environment, run the following commands on a system with CMake 3.14+: @@ -93,7 +120,7 @@ The valid options are: * `-DPYBIND11_NOPYTHON=ON`: Disable all Python searching (disables tests) * `-DBUILD_TESTING=ON`: Enable the tests * `-DDOWNLOAD_CATCH=ON`: Download catch to build the C++ tests -* `-DOWNLOAD_EIGEN=ON`: Download Eigen for the NumPy tests +* `-DDOWNLOAD_EIGEN=ON`: Download Eigen for the NumPy tests * `-DPYBIND11_INSTALL=ON/OFF`: Enable the install target (on by default for the master project) * `-DUSE_PYTHON_INSTALL_DIR=ON`: Try to install into the python dir @@ -126,13 +153,26 @@ cmake --build build --target check `--target` can be spelled `-t` in CMake 3.15+. You can also run individual tests with these targets: -* `pytest`: Python tests only +* `pytest`: Python tests only, using the +[pytest](https://docs.pytest.org/en/stable/) framework * `cpptest`: C++ tests only * `test_cmake_build`: Install / subdirectory tests If you want to build just a subset of tests, use -`-DPYBIND11_TEST_OVERRIDE="test_callbacks.cpp;test_pickling.cpp"`. If this is -empty, all tests will be built. +`-DPYBIND11_TEST_OVERRIDE="test_callbacks;test_pickling"`. If this is +empty, all tests will be built. Tests are specified without an extension if they need both a .py and +.cpp file. + +You may also pass flags to the `pytest` target by editing `tests/pytest.ini` or +by using the `PYTEST_ADDOPTS` environment variable +(see [`pytest` docs](https://docs.pytest.org/en/2.7.3/customize.html#adding-default-options)). As an example: + +```bash +env PYTEST_ADDOPTS="--capture=no --exitfirst" \ + cmake --build build --target pytest +# Or using abbreviated flags +env PYTEST_ADDOPTS="-s -x" cmake --build build --target pytest +``` ### Formatting @@ -164,16 +204,42 @@ name, pre-commit): pre-commit install ``` -### Clang-Tidy +### Clang-Format -To run Clang tidy, the following recipe should work. Files will be modified in -place, so you can use git to monitor the changes. +As of v2.6.2, pybind11 ships with a [`clang-format`][clang-format] +configuration file at the top level of the repo (the filename is +`.clang-format`). Currently, formatting is NOT applied automatically, but +manually using `clang-format` for newly developed files is highly encouraged. +To check if a file needs formatting: ```bash -docker run --rm -v $PWD:/pybind11 -it silkeh/clang:10 -apt-get update && apt-get install python3-dev python3-pytest -cmake -S pybind11/ -B build -DCMAKE_CXX_CLANG_TIDY="$(which clang-tidy);-fix" -cmake --build build +clang-format -style=file --dry-run some.cpp +``` + +The output will show things to be fixed, if any. To actually format the file: + +```bash +clang-format -style=file -i some.cpp +``` + +Note that the `-style-file` option searches the parent directories for the +`.clang-format` file, i.e. the commands above can be run in any subdirectory +of the pybind11 repo. + +### Clang-Tidy + +[`clang-tidy`][clang-tidy] performs deeper static code analyses and is +more complex to run, compared to `clang-format`, but support for `clang-tidy` +is built into the pybind11 CMake configuration. To run `clang-tidy`, the +following recipe should work. Run the `docker` command from the top-level +directory inside your pybind11 git clone. Files will be modified in place, +so you can use git to monitor the changes. + +```bash +docker run --rm -v $PWD:/mounted_pybind11 -it silkeh/clang:12 +apt-get update && apt-get install -y python3-dev python3-pytest +cmake -S /mounted_pybind11/ -B build -DCMAKE_CXX_CLANG_TIDY="$(which clang-tidy);-fix" -DDOWNLOAD_EIGEN=ON -DDOWNLOAD_CATCH=ON -DCMAKE_CXX_STANDARD=17 +cmake --build build -j 2 -- --keep-going ``` ### Include what you use @@ -186,7 +252,7 @@ cmake -S . -B build-iwyu -DCMAKE_CXX_INCLUDE_WHAT_YOU_USE=$(which include-what-y cmake --build build ``` -The report is sent to stderr; you can pip it into a file if you wish. +The report is sent to stderr; you can pipe it into a file if you wish. ### Build recipes @@ -313,6 +379,8 @@ if you really want to. [pre-commit]: https://pre-commit.com +[clang-format]: https://clang.llvm.org/docs/ClangFormat.html +[clang-tidy]: https://clang.llvm.org/extra/clang-tidy/ [pybind11.readthedocs.org]: http://pybind11.readthedocs.org/en/latest [issue tracker]: https://github.com/pybind/pybind11/issues [gitter]: https://gitter.im/pybind/Lobby diff --git a/pybind11/.github/ISSUE_TEMPLATE/bug-report.md b/pybind11/.github/ISSUE_TEMPLATE/bug-report.md deleted file mode 100644 index ae36ea650..000000000 --- a/pybind11/.github/ISSUE_TEMPLATE/bug-report.md +++ /dev/null @@ -1,28 +0,0 @@ ---- -name: Bug Report -about: File an issue about a bug -title: "[BUG] " ---- - - -Make sure you've completed the following steps before submitting your issue -- thank you! - -1. Make sure you've read the [documentation][]. Your issue may be addressed there. -2. Search the [issue tracker][] to verify that this hasn't already been reported. +1 or comment there if it has. -3. Consider asking first in the [Gitter chat room][]. -4. Include a self-contained and minimal piece of code that reproduces the problem. If that's not possible, try to make the description as clear as possible. - a. If possible, make a PR with a new, failing test to give us a starting point to work on! - -[documentation]: https://pybind11.readthedocs.io -[issue tracker]: https://github.com/pybind/pybind11/issues -[Gitter chat room]: https://gitter.im/pybind/Lobby - -*After reading, remove this checklist and the template text in parentheses below.* - -## Issue description - -(Provide a short description, state the expected behavior and what actually happens.) - -## Reproducible example code - -(The code should be minimal, have no external dependencies, isolate the function(s) that cause breakage. Submit matched and complete C++ and Python snippets that can be easily compiled and run to diagnose the issue.) diff --git a/pybind11/.github/ISSUE_TEMPLATE/bug-report.yml b/pybind11/.github/ISSUE_TEMPLATE/bug-report.yml new file mode 100644 index 000000000..bd6a9a8e2 --- /dev/null +++ b/pybind11/.github/ISSUE_TEMPLATE/bug-report.yml @@ -0,0 +1,45 @@ +name: Bug Report +description: File an issue about a bug +title: "[BUG]: " +labels: [triage] +body: + - type: markdown + attributes: + value: | + Maintainers will only make a best effort to triage PRs. Please do your best to make the issue as easy to act on as possible, and only open if clearly a problem with pybind11 (ask first if unsure). + - type: checkboxes + id: steps + attributes: + label: Required prerequisites + description: Make sure you've completed the following steps before submitting your issue -- thank you! + options: + - label: Make sure you've read the [documentation](https://pybind11.readthedocs.io). Your issue may be addressed there. + required: true + - label: Search the [issue tracker](https://github.com/pybind/pybind11/issues) and [Discussions](https:/pybind/pybind11/discussions) to verify that this hasn't already been reported. +1 or comment there if it has. + required: true + - label: Consider asking first in the [Gitter chat room](https://gitter.im/pybind/Lobby) or in a [Discussion](https:/pybind/pybind11/discussions/new). + required: false + + - type: textarea + id: description + attributes: + label: Problem description + placeholder: >- + Provide a short description, state the expected behavior and what + actually happens. Include relevant information like what version of + pybind11 you are using, what system you are on, and any useful commands + / output. + validations: + required: true + + - type: textarea + id: code + attributes: + label: Reproducible example code + placeholder: >- + The code should be minimal, have no external dependencies, isolate the + function(s) that cause breakage. Submit matched and complete C++ and + Python snippets that can be easily compiled and run to diagnose the + issue. If possible, make a PR with a new, failing test to give us a + starting point to work on! + render: text diff --git a/pybind11/.github/ISSUE_TEMPLATE/config.yml b/pybind11/.github/ISSUE_TEMPLATE/config.yml index 20e743136..27f9a8044 100644 --- a/pybind11/.github/ISSUE_TEMPLATE/config.yml +++ b/pybind11/.github/ISSUE_TEMPLATE/config.yml @@ -1,5 +1,8 @@ blank_issues_enabled: false contact_links: + - name: Ask a question + url: https://github.com/pybind/pybind11/discussions/new + about: Please ask and answer questions here, or propose new ideas. - name: Gitter room url: https://gitter.im/pybind/Lobby about: A room for discussing pybind11 with an active community diff --git a/pybind11/.github/ISSUE_TEMPLATE/feature-request.md b/pybind11/.github/ISSUE_TEMPLATE/feature-request.md deleted file mode 100644 index 5f6ec81ec..000000000 --- a/pybind11/.github/ISSUE_TEMPLATE/feature-request.md +++ /dev/null @@ -1,16 +0,0 @@ ---- -name: Feature Request -about: File an issue about adding a feature -title: "[FEAT] " ---- - - -Make sure you've completed the following steps before submitting your issue -- thank you! - -1. Check if your feature has already been mentioned / rejected / planned in other issues. -2. If those resources didn't help, consider asking in the [Gitter chat room][] to see if this is interesting / useful to a larger audience and possible to implement reasonably, -4. If you have a useful feature that passes the previous items (or not suitable for chat), please fill in the details below. - -[Gitter chat room]: https://gitter.im/pybind/Lobby - -*After reading, remove this checklist.* diff --git a/pybind11/.github/ISSUE_TEMPLATE/question.md b/pybind11/.github/ISSUE_TEMPLATE/question.md deleted file mode 100644 index b199b6ee8..000000000 --- a/pybind11/.github/ISSUE_TEMPLATE/question.md +++ /dev/null @@ -1,21 +0,0 @@ ---- -name: Question -about: File an issue about unexplained behavior -title: "[QUESTION] " ---- - -If you have a question, please check the following first: - -1. Check if your question has already been answered in the [FAQ][] section. -2. Make sure you've read the [documentation][]. Your issue may be addressed there. -3. If those resources didn't help and you only have a short question (not a bug report), consider asking in the [Gitter chat room][] -4. Search the [issue tracker][], including the closed issues, to see if your question has already been asked/answered. +1 or comment if it has been asked but has no answer. -5. If you have a more complex question which is not answered in the previous items (or not suitable for chat), please fill in the details below. -6. Include a self-contained and minimal piece of code that illustrates your question. If that's not possible, try to make the description as clear as possible. - -[FAQ]: http://pybind11.readthedocs.io/en/latest/faq.html -[documentation]: https://pybind11.readthedocs.io -[issue tracker]: https://github.com/pybind/pybind11/issues -[Gitter chat room]: https://gitter.im/pybind/Lobby - -*After reading, remove this checklist.* diff --git a/pybind11/.github/dependabot.yml b/pybind11/.github/dependabot.yml new file mode 100644 index 000000000..73273365c --- /dev/null +++ b/pybind11/.github/dependabot.yml @@ -0,0 +1,16 @@ +version: 2 +updates: + # Maintain dependencies for GitHub Actions + - package-ecosystem: "github-actions" + directory: "/" + schedule: + interval: "daily" + ignore: + # Official actions have moving tags like v1 + # that are used, so they don't need updates here + - dependency-name: "actions/checkout" + - dependency-name: "actions/setup-python" + - dependency-name: "actions/cache" + - dependency-name: "actions/upload-artifact" + - dependency-name: "actions/download-artifact" + - dependency-name: "actions/labeler" diff --git a/pybind11/.github/labeler.yml b/pybind11/.github/labeler.yml new file mode 100644 index 000000000..abb0d05aa --- /dev/null +++ b/pybind11/.github/labeler.yml @@ -0,0 +1,8 @@ +docs: +- any: + - 'docs/**/*.rst' + - '!docs/changelog.rst' + - '!docs/upgrade.rst' + +ci: +- '.github/workflows/*.yml' diff --git a/pybind11/.github/labeler_merged.yml b/pybind11/.github/labeler_merged.yml new file mode 100644 index 000000000..2374ad42e --- /dev/null +++ b/pybind11/.github/labeler_merged.yml @@ -0,0 +1,3 @@ +needs changelog: +- all: + - '!docs/changelog.rst' diff --git a/pybind11/.github/pull_request_template.md b/pybind11/.github/pull_request_template.md new file mode 100644 index 000000000..54b7f5100 --- /dev/null +++ b/pybind11/.github/pull_request_template.md @@ -0,0 +1,19 @@ + +## Description + + + + +## Suggested changelog entry: + + + +```rst + +``` + + diff --git a/pybind11/.github/workflows/ci.yml b/pybind11/.github/workflows/ci.yml index 1749d07f0..050c525ce 100644 --- a/pybind11/.github/workflows/ci.yml +++ b/pybind11/.github/workflows/ci.yml @@ -9,6 +9,13 @@ on: - stable - v* +concurrency: + group: test-${{ github.ref }} + cancel-in-progress: true + +env: + PIP_ONLY_BINARY: numpy + jobs: # This is the "main" test suite, which tests a large number of different # versions of default compilers and Python versions in GitHub Actions. @@ -16,71 +23,42 @@ jobs: strategy: fail-fast: false matrix: - runs-on: [ubuntu-latest, windows-latest, macos-latest] - arch: [x64] + runs-on: [ubuntu-latest, windows-2022, macos-latest] python: - - 2.7 - - 3.5 - - 3.8 - - pypy2 - - pypy3 + - '2.7' + - '3.5' + - '3.6' + - '3.9' + - '3.10' + - 'pypy-3.7-v7.3.7' + - 'pypy-3.8-v7.3.7' # Items in here will either be added to the build matrix (if not # present), or add new keys to an existing matrix element if all the # existing keys match. # - # We support three optional keys: args (both build), args1 (first - # build), and args2 (second build). + # We support an optional key: args, for cmake args include: + # Just add a key - runs-on: ubuntu-latest - python: 3.6 - arch: x64 + python: '3.6' args: > -DPYBIND11_FINDPYTHON=ON - - runs-on: windows-2016 - python: 3.7 - arch: x86 - args2: > - -DCMAKE_CXX_FLAGS="/permissive- /EHsc /GR" + -DCMAKE_CXX_FLAGS="-D_=1" - runs-on: windows-latest - python: 3.6 - arch: x64 + python: '3.6' args: > -DPYBIND11_FINDPYTHON=ON - - runs-on: windows-latest - python: 3.7 - arch: x64 - - - runs-on: ubuntu-latest - python: 3.9-dev - arch: x64 - runs-on: macos-latest - python: 3.9-dev - arch: x64 - args: > - -DPYBIND11_FINDPYTHON=ON + python: 'pypy-2.7' + # Inject a couple Windows 2019 runs + - runs-on: windows-2019 + python: '3.9' + - runs-on: windows-2019 + python: '2.7' - # These items will be removed from the build matrix, keys must match. - exclude: - # Currently 32bit only, and we build 64bit - - runs-on: windows-latest - python: pypy2 - arch: x64 - - runs-on: windows-latest - python: pypy3 - arch: x64 - - # Currently broken on embed_test - - runs-on: windows-latest - python: 3.8 - arch: x64 - - runs-on: windows-latest - python: 3.9-dev - arch: x64 - - name: "🐍 ${{ matrix.python }} • ${{ matrix.runs-on }} • ${{ matrix.arch }} ${{ matrix.args }}" + name: "🐍 ${{ matrix.python }} • ${{ matrix.runs-on }} • x64 ${{ matrix.args }}" runs-on: ${{ matrix.runs-on }} - continue-on-error: ${{ endsWith(matrix.python, 'dev') }} steps: - uses: actions/checkout@v2 @@ -89,13 +67,18 @@ jobs: uses: actions/setup-python@v2 with: python-version: ${{ matrix.python }} - architecture: ${{ matrix.arch }} - - name: Setup Boost (Windows / Linux latest) - run: echo "::set-env name=BOOST_ROOT::$BOOST_ROOT_1_72_0" + - name: Setup Boost (Linux) + # Can't use boost + define _ + if: runner.os == 'Linux' && matrix.python != '3.6' + run: sudo apt-get install libboost-dev + + - name: Setup Boost (macOS) + if: runner.os == 'macOS' + run: brew install boost - name: Update CMake - uses: jwlawson/actions-setup-cmake@v1.3 + uses: jwlawson/actions-setup-cmake@v1.12 - name: Cache wheels if: runner.os == 'macOS' @@ -106,10 +89,11 @@ jobs: # for ways to do this more generally path: ~/Library/Caches/pip # Look to see if there is a cache hit for the corresponding requirements file - key: ${{ runner.os }}-pip-${{ matrix.python }}-${{ matrix.arch }}-${{ hashFiles('tests/requirements.txt') }} + key: ${{ runner.os }}-pip-${{ matrix.python }}-x64-${{ hashFiles('tests/requirements.txt') }} - name: Prepare env - run: python -m pip install -r tests/requirements.txt --prefer-binary + run: | + python -m pip install -r tests/requirements.txt - name: Setup annotations on Linux if: runner.os == 'Linux' @@ -132,6 +116,8 @@ jobs: run: cmake --build . --target pytest -j 2 - name: C++11 tests + # TODO: Figure out how to load the DLL on Python 3.8+ + if: "!(runner.os == 'Windows' && (matrix.python == 3.8 || matrix.python == 3.9 || matrix.python == '3.10' || matrix.python == '3.11-dev' || matrix.python == 'pypy-3.8'))" run: cmake --build . --target cpptest -j 2 - name: Interface test C++11 @@ -141,7 +127,7 @@ jobs: run: git clean -fdx # Second build - C++17 mode and in a build directory - - name: Configure ${{ matrix.args2 }} + - name: Configure C++17 run: > cmake -S . -B build2 -DPYBIND11_WERROR=ON @@ -149,7 +135,6 @@ jobs: -DDOWNLOAD_EIGEN=ON -DCMAKE_CXX_STANDARD=17 ${{ matrix.args }} - ${{ matrix.args2 }} - name: Build run: cmake --build build2 -j 2 @@ -158,8 +143,28 @@ jobs: run: cmake --build build2 --target pytest - name: C++ tests + # TODO: Figure out how to load the DLL on Python 3.8+ + if: "!(runner.os == 'Windows' && (matrix.python == 3.8 || matrix.python == 3.9 || matrix.python == '3.10' || matrix.python == '3.11-dev' || matrix.python == 'pypy-3.8'))" run: cmake --build build2 --target cpptest + # Third build - C++17 mode with unstable ABI + - name: Configure (unstable ABI) + run: > + cmake -S . -B build3 + -DPYBIND11_WERROR=ON + -DDOWNLOAD_CATCH=ON + -DDOWNLOAD_EIGEN=ON + -DCMAKE_CXX_STANDARD=17 + -DPYBIND11_INTERNALS_VERSION=10000000 + "-DPYBIND11_TEST_OVERRIDE=test_call_policies.cpp;test_gil_scoped.cpp;test_thread.cpp" + ${{ matrix.args }} + + - name: Build (unstable ABI) + run: cmake --build build3 -j 2 + + - name: Python tests (unstable ABI) + run: cmake --build build3 --target pytest + - name: Interface test run: cmake --build build2 --target test_cmake_build @@ -167,21 +172,105 @@ jobs: # MSVC, but for now, this action works: - name: Prepare compiler environment for Windows 🐍 2.7 if: matrix.python == 2.7 && runner.os == 'Windows' - uses: ilammy/msvc-dev-cmd@v1 + uses: ilammy/msvc-dev-cmd@v1.10.0 with: arch: x64 # This makes two environment variables available in the following step(s) - name: Set Windows 🐍 2.7 environment variables if: matrix.python == 2.7 && runner.os == 'Windows' + shell: bash run: | - echo "::set-env name=DISTUTILS_USE_SDK::1" - echo "::set-env name=MSSdk::1" + echo "DISTUTILS_USE_SDK=1" >> $GITHUB_ENV + echo "MSSdk=1" >> $GITHUB_ENV # This makes sure the setup_helpers module can build packages using # setuptools - name: Setuptools helpers test run: pytest tests/extra_setuptools + if: "!(matrix.python == '3.5' && matrix.runs-on == 'windows-2022')" + + + deadsnakes: + strategy: + fail-fast: false + matrix: + include: + # TODO: Fails on 3.10, investigate + - python-version: "3.9" + python-debug: true + valgrind: true + # - python-version: "3.11-dev" + # python-debug: false + + name: "🐍 ${{ matrix.python-version }}${{ matrix.python-debug && '-dbg' || '' }} (deadsnakes)${{ matrix.valgrind && ' • Valgrind' || '' }} • x64" + runs-on: ubuntu-latest + + steps: + - uses: actions/checkout@v2 + + - name: Setup Python ${{ matrix.python-version }} (deadsnakes) + uses: deadsnakes/action@v2.1.1 + with: + python-version: ${{ matrix.python-version }} + debug: ${{ matrix.python-debug }} + + - name: Update CMake + uses: jwlawson/actions-setup-cmake@v1.12 + + - name: Valgrind cache + if: matrix.valgrind + uses: actions/cache@v2 + id: cache-valgrind + with: + path: valgrind + key: 3.16.1 # Valgrind version + + - name: Compile Valgrind + if: matrix.valgrind && steps.cache-valgrind.outputs.cache-hit != 'true' + run: | + VALGRIND_VERSION=3.16.1 + curl https://sourceware.org/pub/valgrind/valgrind-$VALGRIND_VERSION.tar.bz2 -o - | tar xj + mv valgrind-$VALGRIND_VERSION valgrind + cd valgrind + ./configure + make -j 2 > /dev/null + + - name: Install Valgrind + if: matrix.valgrind + working-directory: valgrind + run: | + sudo make install + sudo apt-get update + sudo apt-get install libc6-dbg # Needed by Valgrind + + - name: Prepare env + run: | + python -m pip install -r tests/requirements.txt + + - name: Configure + env: + SETUPTOOLS_USE_DISTUTILS: stdlib + run: > + cmake -S . -B build + -DCMAKE_BUILD_TYPE=Debug + -DPYBIND11_WERROR=ON + -DDOWNLOAD_CATCH=ON + -DDOWNLOAD_EIGEN=ON + -DCMAKE_CXX_STANDARD=17 + + - name: Build + run: cmake --build build -j 2 + + - name: Python tests + run: cmake --build build --target pytest + + - name: C++ tests + run: cmake --build build --target cpptest + + - name: Run Valgrind on Python tests + if: matrix.valgrind + run: cmake --build build --target memcheck # Testing on clang using the excellent silkeh clang docker images @@ -194,12 +283,20 @@ jobs: - 3.6 - 3.7 - 3.9 - - 5 - 7 - 9 - dev + std: + - 11 + include: + - clang: 5 + std: 14 + - clang: 10 + std: 20 + - clang: 10 + std: 17 - name: "🐍 3 • Clang ${{ matrix.clang }} • x64" + name: "🐍 3 • Clang ${{ matrix.clang }} • C++${{ matrix.std }} • x64" container: "silkeh/clang:${{ matrix.clang }}" steps: @@ -214,6 +311,7 @@ jobs: cmake -S . -B build -DPYBIND11_WERROR=ON -DDOWNLOAD_CATCH=ON + -DCMAKE_CXX_STANDARD=${{ matrix.std }} -DPYTHON_EXECUTABLE=$(python3 -c "import sys; print(sys.executable)") - name: Build @@ -252,50 +350,54 @@ jobs: run: cmake --build build --target pytest - # Testing CentOS 8 + PGI compilers - centos-nvhpc8: - runs-on: ubuntu-latest - name: "🐍 3 • CentOS8 / PGI 20.7 • x64" - container: centos:8 - - steps: - - uses: actions/checkout@v2 - - - name: Add Python 3 and a few requirements - run: yum update -y && yum install -y git python3-devel python3-numpy python3-pytest make environment-modules - - - name: Install CMake with pip - run: | - python3 -m pip install --upgrade pip - python3 -m pip install cmake --prefer-binary - - - name: Install NVidia HPC SDK - run: yum -y install https://developer.download.nvidia.com/hpc-sdk/nvhpc-20-7-20.7-1.x86_64.rpm https://developer.download.nvidia.com/hpc-sdk/nvhpc-2020-20.7-1.x86_64.rpm - - - name: Configure - shell: bash - run: | - source /etc/profile.d/modules.sh - module load /opt/nvidia/hpc_sdk/modulefiles/nvhpc/20.7 - cmake -S . -B build -DDOWNLOAD_CATCH=ON -DCMAKE_CXX_STANDARD=14 -DPYTHON_EXECUTABLE=$(python3 -c "import sys; print(sys.executable)") - - - name: Build - run: cmake --build build -j 2 --verbose - - - name: Python tests - run: cmake --build build --target pytest - - - name: C++ tests - run: cmake --build build --target cpptest - - - name: Interface test - run: cmake --build build --target test_cmake_build +# TODO: Internal compiler error - report to NVidia +# # Testing CentOS 8 + PGI compilers +# centos-nvhpc8: +# runs-on: ubuntu-latest +# name: "🐍 3 • CentOS8 / PGI 20.11 • x64" +# container: centos:8 +# +# steps: +# - uses: actions/checkout@v2 +# +# - name: Add Python 3 and a few requirements +# run: yum update -y && yum install -y git python3-devel python3-numpy python3-pytest make environment-modules +# +# - name: Install CMake with pip +# run: | +# python3 -m pip install --upgrade pip +# python3 -m pip install cmake --prefer-binary +# +# - name: Install NVidia HPC SDK +# run: > +# yum -y install +# https://developer.download.nvidia.com/hpc-sdk/20.11/nvhpc-20-11-20.11-1.x86_64.rpm +# https://developer.download.nvidia.com/hpc-sdk/20.11/nvhpc-2020-20.11-1.x86_64.rpm +# +# - name: Configure +# shell: bash +# run: | +# source /etc/profile.d/modules.sh +# module load /opt/nvidia/hpc_sdk/modulefiles/nvhpc/20.11 +# cmake -S . -B build -DDOWNLOAD_CATCH=ON -DCMAKE_CXX_STANDARD=14 -DPYTHON_EXECUTABLE=$(python3 -c "import sys; print(sys.executable)") +# +# - name: Build +# run: cmake --build build -j 2 --verbose +# +# - name: Python tests +# run: cmake --build build --target pytest +# +# - name: C++ tests +# run: cmake --build build --target cpptest +# +# - name: Interface test +# run: cmake --build build --target test_cmake_build # Testing on CentOS 7 + PGI compilers, which seems to require more workarounds centos-nvhpc7: runs-on: ubuntu-latest - name: "🐍 3 • CentOS7 / PGI 20.7 • x64" + name: "🐍 3 • CentOS7 / PGI 20.9 • x64" container: centos:7 steps: @@ -305,17 +407,17 @@ jobs: run: yum update -y && yum install -y epel-release && yum install -y git python3-devel make environment-modules cmake3 - name: Install NVidia HPC SDK - run: yum -y install https://developer.download.nvidia.com/hpc-sdk/nvhpc-20-7-20.7-1.x86_64.rpm https://developer.download.nvidia.com/hpc-sdk/nvhpc-2020-20.7-1.x86_64.rpm + run: yum -y install https://developer.download.nvidia.com/hpc-sdk/20.9/nvhpc-20-9-20.9-1.x86_64.rpm https://developer.download.nvidia.com/hpc-sdk/20.9/nvhpc-2020-20.9-1.x86_64.rpm # On CentOS 7, we have to filter a few tests (compiler internal error) - # and allow deeper templete recursion (not needed on CentOS 8 with a newer + # and allow deeper template recursion (not needed on CentOS 8 with a newer # standard library). On some systems, you many need further workarounds: # https://github.com/pybind/pybind11/pull/2475 - name: Configure shell: bash run: | source /etc/profile.d/modules.sh - module load /opt/nvidia/hpc_sdk/modulefiles/nvhpc/20.7 + module load /opt/nvidia/hpc_sdk/modulefiles/nvhpc/20.9 cmake3 -S . -B build -DDOWNLOAD_CATCH=ON \ -DCMAKE_CXX_STANDARD=11 \ -DPYTHON_EXECUTABLE=$(python3 -c "import sys; print(sys.executable)") \ @@ -340,6 +442,7 @@ jobs: - name: Interface test run: cmake3 --build build --target test_cmake_build + # Testing on GCC using the GCC docker images (only recent images supported) gcc: runs-on: ubuntu-latest @@ -349,8 +452,13 @@ jobs: gcc: - 7 - latest + std: + - 11 + include: + - gcc: 10 + std: 20 - name: "🐍 3 • GCC ${{ matrix.gcc }} • x64" + name: "🐍 3 • GCC ${{ matrix.gcc }} • C++${{ matrix.std }}• x64" container: "gcc:${{ matrix.gcc }}" steps: @@ -362,10 +470,8 @@ jobs: - name: Update pip run: python3 -m pip install --upgrade pip - - name: Setup CMake 3.18 - uses: jwlawson/actions-setup-cmake@v1.3 - with: - cmake-version: 3.18 + - name: Update CMake + uses: jwlawson/actions-setup-cmake@v1.12 - name: Configure shell: bash @@ -373,7 +479,7 @@ jobs: cmake -S . -B build -DPYBIND11_WERROR=ON -DDOWNLOAD_CATCH=ON - -DCMAKE_CXX_STANDARD=11 + -DCMAKE_CXX_STANDARD=${{ matrix.std }} -DPYTHON_EXECUTABLE=$(python3 -c "import sys; print(sys.executable)") - name: Build @@ -389,6 +495,103 @@ jobs: run: cmake --build build --target test_cmake_build + # Testing on ICC using the oneAPI apt repo + icc: + runs-on: ubuntu-20.04 + strategy: + fail-fast: false + + name: "🐍 3 • ICC latest • x64" + + steps: + - uses: actions/checkout@v2 + + - name: Add apt repo + run: | + sudo apt-get update + sudo apt-get install -y wget build-essential pkg-config cmake ca-certificates gnupg + wget https://apt.repos.intel.com/intel-gpg-keys/GPG-PUB-KEY-INTEL-SW-PRODUCTS-2023.PUB + sudo apt-key add GPG-PUB-KEY-INTEL-SW-PRODUCTS-2023.PUB + echo "deb https://apt.repos.intel.com/oneapi all main" | sudo tee /etc/apt/sources.list.d/oneAPI.list + + - name: Add ICC & Python 3 + run: sudo apt-get update; sudo apt-get install -y intel-oneapi-compiler-dpcpp-cpp-and-cpp-classic cmake python3-dev python3-numpy python3-pytest python3-pip + + - name: Update pip + run: | + set +e; source /opt/intel/oneapi/setvars.sh; set -e + python3 -m pip install --upgrade pip + + - name: Install dependencies + run: | + set +e; source /opt/intel/oneapi/setvars.sh; set -e + python3 -m pip install -r tests/requirements.txt + + - name: Configure C++11 + run: | + set +e; source /opt/intel/oneapi/setvars.sh; set -e + cmake -S . -B build-11 \ + -DPYBIND11_WERROR=ON \ + -DDOWNLOAD_CATCH=ON \ + -DDOWNLOAD_EIGEN=OFF \ + -DCMAKE_CXX_STANDARD=11 \ + -DCMAKE_CXX_COMPILER=$(which icpc) \ + -DPYTHON_EXECUTABLE=$(python3 -c "import sys; print(sys.executable)") + + - name: Build C++11 + run: | + set +e; source /opt/intel/oneapi/setvars.sh; set -e + cmake --build build-11 -j 2 -v + + - name: Python tests C++11 + run: | + set +e; source /opt/intel/oneapi/setvars.sh; set -e + sudo service apport stop + cmake --build build-11 --target check + + - name: C++ tests C++11 + run: | + set +e; source /opt/intel/oneapi/setvars.sh; set -e + cmake --build build-11 --target cpptest + + - name: Interface test C++11 + run: | + set +e; source /opt/intel/oneapi/setvars.sh; set -e + cmake --build build-11 --target test_cmake_build + + - name: Configure C++17 + run: | + set +e; source /opt/intel/oneapi/setvars.sh; set -e + cmake -S . -B build-17 \ + -DPYBIND11_WERROR=ON \ + -DDOWNLOAD_CATCH=ON \ + -DDOWNLOAD_EIGEN=OFF \ + -DCMAKE_CXX_STANDARD=17 \ + -DCMAKE_CXX_COMPILER=$(which icpc) \ + -DPYTHON_EXECUTABLE=$(python3 -c "import sys; print(sys.executable)") + + - name: Build C++17 + run: | + set +e; source /opt/intel/oneapi/setvars.sh; set -e + cmake --build build-17 -j 2 -v + + - name: Python tests C++17 + run: | + set +e; source /opt/intel/oneapi/setvars.sh; set -e + sudo service apport stop + cmake --build build-17 --target check + + - name: C++ tests C++17 + run: | + set +e; source /opt/intel/oneapi/setvars.sh; set -e + cmake --build build-17 --target cpptest + + - name: Interface test C++17 + run: | + set +e; source /opt/intel/oneapi/setvars.sh; set -e + cmake --build build-17 --target test_cmake_build + + # Testing on CentOS (manylinux uses a centos base, and this is an easy way # to get GCC 4.8, which is the manylinux1 compiler). centos: @@ -397,11 +600,11 @@ jobs: fail-fast: false matrix: centos: - - 7 # GCC 4.8 - - 8 + - centos7 # GCC 4.8 + - stream8 name: "🐍 3 • CentOS ${{ matrix.centos }} • x64" - container: "centos:${{ matrix.centos }}" + container: "quay.io/centos/centos:${{ matrix.centos }}" steps: - uses: actions/checkout@v2 @@ -413,12 +616,14 @@ jobs: run: python3 -m pip install --upgrade pip - name: Install dependencies - run: python3 -m pip install cmake -r tests/requirements.txt --prefer-binary + run: | + python3 -m pip install cmake -r tests/requirements.txt - name: Configure shell: bash run: > cmake -S . -B build + -DCMAKE_BUILD_TYPE=MinSizeRel -DPYBIND11_WERROR=ON -DDOWNLOAD_CATCH=ON -DDOWNLOAD_EIGEN=ON @@ -476,7 +681,7 @@ jobs: -DPYTHON_EXECUTABLE=$(python3 -c "import sys; print(sys.executable)") working-directory: /build-tests - - name: Run tests + - name: Python tests run: make pytest -j 2 working-directory: /build-tests @@ -493,16 +698,13 @@ jobs: - uses: actions/setup-python@v2 - name: Install Doxygen - run: sudo apt install -y doxygen - - - name: Install docs & setup requirements - run: python3 -m pip install -r docs/requirements.txt + run: sudo apt-get install -y doxygen librsvg2-bin # Changed to rsvg-convert in 20.04 - name: Build docs - run: python3 -m sphinx -W -b html docs docs/.build + run: pipx run nox -s docs - name: Make SDist - run: python3 setup.py sdist + run: pipx run nox -s build -- --sdist - run: git status --ignored @@ -514,6 +716,250 @@ jobs: - name: Compare Dists (headers only) working-directory: include run: | - python3 -m pip install --user -U ../dist/* + python3 -m pip install --user -U ../dist/*.tar.gz installed=$(python3 -c "import pybind11; print(pybind11.get_include() + '/pybind11')") diff -rq $installed ./pybind11 + + win32: + strategy: + fail-fast: false + matrix: + python: + - 3.5 + - 3.6 + - 3.7 + - 3.8 + - 3.9 + - pypy-3.6 + + include: + - python: 3.9 + args: -DCMAKE_CXX_STANDARD=20 -DDOWNLOAD_EIGEN=OFF + - python: 3.8 + args: -DCMAKE_CXX_STANDARD=17 + + name: "🐍 ${{ matrix.python }} • MSVC 2019 • x86 ${{ matrix.args }}" + runs-on: windows-latest + + steps: + - uses: actions/checkout@v2 + + - name: Setup Python ${{ matrix.python }} + uses: actions/setup-python@v2 + with: + python-version: ${{ matrix.python }} + architecture: x86 + + - name: Update CMake + uses: jwlawson/actions-setup-cmake@v1.12 + + - name: Prepare MSVC + uses: ilammy/msvc-dev-cmd@v1.10.0 + with: + arch: x86 + + - name: Prepare env + run: | + python -m pip install -r tests/requirements.txt + + # First build - C++11 mode and inplace + - name: Configure ${{ matrix.args }} + run: > + cmake -S . -B build + -G "Visual Studio 16 2019" -A Win32 + -DPYBIND11_WERROR=ON + -DDOWNLOAD_CATCH=ON + -DDOWNLOAD_EIGEN=ON + ${{ matrix.args }} + - name: Build C++11 + run: cmake --build build -j 2 + + - name: Python tests + run: cmake --build build -t pytest + + win32-msvc2015: + name: "🐍 ${{ matrix.python }} • MSVC 2015 • x64" + runs-on: windows-latest + strategy: + fail-fast: false + matrix: + python: + - 2.7 + - 3.6 + - 3.7 + # todo: check/cpptest does not support 3.8+ yet + + steps: + - uses: actions/checkout@v2 + + - name: Setup 🐍 ${{ matrix.python }} + uses: actions/setup-python@v2 + with: + python-version: ${{ matrix.python }} + + - name: Update CMake + uses: jwlawson/actions-setup-cmake@v1.12 + + - name: Prepare MSVC + uses: ilammy/msvc-dev-cmd@v1.10.0 + with: + toolset: 14.0 + + - name: Prepare env + run: | + python -m pip install -r tests/requirements.txt + + # First build - C++11 mode and inplace + - name: Configure + run: > + cmake -S . -B build + -G "Visual Studio 14 2015" -A x64 + -DPYBIND11_WERROR=ON + -DDOWNLOAD_CATCH=ON + -DDOWNLOAD_EIGEN=ON + + - name: Build C++14 + run: cmake --build build -j 2 + + - name: Run all checks + run: cmake --build build -t check + + + win32-msvc2017: + name: "🐍 ${{ matrix.python }} • MSVC 2017 • x64" + runs-on: windows-2016 + strategy: + fail-fast: false + matrix: + python: + - 2.7 + - 3.5 + - 3.7 + std: + - 14 + + include: + - python: 2.7 + std: 17 + args: > + -DCMAKE_CXX_FLAGS="/permissive- /EHsc /GR" + - python: 3.7 + std: 17 + args: > + -DCMAKE_CXX_FLAGS="/permissive- /EHsc /GR" + + steps: + - uses: actions/checkout@v2 + + - name: Setup 🐍 ${{ matrix.python }} + uses: actions/setup-python@v2 + with: + python-version: ${{ matrix.python }} + + - name: Update CMake + uses: jwlawson/actions-setup-cmake@v1.12 + + - name: Prepare env + run: | + python -m pip install -r tests/requirements.txt + + # First build - C++11 mode and inplace + - name: Configure + run: > + cmake -S . -B build + -G "Visual Studio 15 2017" -A x64 + -DPYBIND11_WERROR=ON + -DDOWNLOAD_CATCH=ON + -DDOWNLOAD_EIGEN=ON + -DCMAKE_CXX_STANDARD=${{ matrix.std }} + ${{ matrix.args }} + + - name: Build ${{ matrix.std }} + run: cmake --build build -j 2 + + - name: Run all checks + run: cmake --build build -t check + + mingw: + name: "🐍 3 • windows-latest • ${{ matrix.sys }}" + runs-on: windows-latest + defaults: + run: + shell: msys2 {0} + strategy: + fail-fast: false + matrix: + include: + - { sys: mingw64, env: x86_64 } + - { sys: mingw32, env: i686 } + steps: + - uses: msys2/setup-msys2@v2 + with: + msystem: ${{matrix.sys}} + install: >- + git + mingw-w64-${{matrix.env}}-gcc + mingw-w64-${{matrix.env}}-python-pip + mingw-w64-${{matrix.env}}-python-numpy + mingw-w64-${{matrix.env}}-python-scipy + mingw-w64-${{matrix.env}}-cmake + mingw-w64-${{matrix.env}}-make + mingw-w64-${{matrix.env}}-python-pytest + mingw-w64-${{matrix.env}}-eigen3 + mingw-w64-${{matrix.env}}-boost + mingw-w64-${{matrix.env}}-catch + + - uses: actions/checkout@v2 + + - name: Configure C++11 + # LTO leads to many undefined reference like + # `pybind11::detail::function_call::function_call(pybind11::detail::function_call&&) + run: cmake -G "MinGW Makefiles" -DCMAKE_CXX_STANDARD=11 -S . -B build + + - name: Build C++11 + run: cmake --build build -j 2 + + - name: Python tests C++11 + run: cmake --build build --target pytest -j 2 + + - name: C++11 tests + run: PYTHONHOME=/${{matrix.sys}} PYTHONPATH=/${{matrix.sys}} cmake --build build --target cpptest -j 2 + + - name: Interface test C++11 + run: PYTHONHOME=/${{matrix.sys}} PYTHONPATH=/${{matrix.sys}} cmake --build build --target test_cmake_build + + - name: Clean directory + run: git clean -fdx + + - name: Configure C++14 + run: cmake -G "MinGW Makefiles" -DCMAKE_CXX_STANDARD=14 -S . -B build2 + + - name: Build C++14 + run: cmake --build build2 -j 2 + + - name: Python tests C++14 + run: cmake --build build2 --target pytest -j 2 + + - name: C++14 tests + run: PYTHONHOME=/${{matrix.sys}} PYTHONPATH=/${{matrix.sys}} cmake --build build2 --target cpptest -j 2 + + - name: Interface test C++14 + run: PYTHONHOME=/${{matrix.sys}} PYTHONPATH=/${{matrix.sys}} cmake --build build2 --target test_cmake_build + + - name: Clean directory + run: git clean -fdx + + - name: Configure C++17 + run: cmake -G "MinGW Makefiles" -DCMAKE_CXX_STANDARD=17 -S . -B build3 + + - name: Build C++17 + run: cmake --build build3 -j 2 + + - name: Python tests C++17 + run: cmake --build build3 --target pytest -j 2 + + - name: C++17 tests + run: PYTHONHOME=/${{matrix.sys}} PYTHONPATH=/${{matrix.sys}} cmake --build build3 --target cpptest -j 2 + + - name: Interface test C++17 + run: PYTHONHOME=/${{matrix.sys}} PYTHONPATH=/${{matrix.sys}} cmake --build build3 --target test_cmake_build diff --git a/pybind11/.github/workflows/configure.yml b/pybind11/.github/workflows/configure.yml index 3dd248e04..66ab0e3d7 100644 --- a/pybind11/.github/workflows/configure.yml +++ b/pybind11/.github/workflows/configure.yml @@ -18,7 +18,7 @@ jobs: matrix: runs-on: [ubuntu-latest, macos-latest, windows-latest] arch: [x64] - cmake: [3.18] + cmake: ["3.21"] include: - runs-on: ubuntu-latest @@ -55,7 +55,7 @@ jobs: # An action for adding a specific version of CMake: # https://github.com/jwlawson/actions-setup-cmake - name: Setup CMake ${{ matrix.cmake }} - uses: jwlawson/actions-setup-cmake@v1.3 + uses: jwlawson/actions-setup-cmake@v1.12 with: cmake-version: ${{ matrix.cmake }} @@ -82,57 +82,3 @@ jobs: working-directory: build dir if: github.event_name == 'workflow_dispatch' run: cmake --build . --config Release --target check - - # This builds the sdists and wheels and makes sure the files are exactly as - # expected. Using Windows and Python 2.7, since that is often the most - # challenging matrix element. - test-packaging: - name: 🐍 2.7 • 📦 tests • windows-latest - runs-on: windows-latest - - steps: - - uses: actions/checkout@v2 - - - name: Setup 🐍 2.7 - uses: actions/setup-python@v2 - with: - python-version: 2.7 - - - name: Prepare env - run: python -m pip install -r tests/requirements.txt --prefer-binary - - - name: Python Packaging tests - run: pytest tests/extra_python_package/ - - - # This runs the packaging tests and also builds and saves the packages as - # artifacts. - packaging: - name: 🐍 3.8 • 📦 & 📦 tests • ubuntu-latest - runs-on: ubuntu-latest - - steps: - - uses: actions/checkout@v2 - - - name: Setup 🐍 3.8 - uses: actions/setup-python@v2 - with: - python-version: 3.8 - - - name: Prepare env - run: python -m pip install -r tests/requirements.txt build twine --prefer-binary - - - name: Python Packaging tests - run: pytest tests/extra_python_package/ - - - name: Build SDist and wheels - run: | - python -m build -s -w . - PYBIND11_GLOBAL_SDIST=1 python -m build -s -w . - - - name: Check metadata - run: twine check dist/* - - - uses: actions/upload-artifact@v2 - with: - path: dist/* diff --git a/pybind11/.github/workflows/format.yml b/pybind11/.github/workflows/format.yml index 28cfeb9b7..ab7b40503 100644 --- a/pybind11/.github/workflows/format.yml +++ b/pybind11/.github/workflows/format.yml @@ -19,15 +19,17 @@ jobs: steps: - uses: actions/checkout@v2 - uses: actions/setup-python@v2 - - uses: pre-commit/action@v2.0.0 + - uses: pre-commit/action@v2.0.3 with: # Slow hooks are marked with manual - slow is okay here, run them too - extra_args: --hook-stage manual + extra_args: --hook-stage manual --all-files clang-tidy: + # When making changes here, please also review the "Clang-Tidy" section + # in .github/CONTRIBUTING.md and update as needed. name: Clang-Tidy runs-on: ubuntu-latest - container: silkeh/clang:10 + container: silkeh/clang:12 steps: - uses: actions/checkout@v2 @@ -35,7 +37,12 @@ jobs: run: apt-get update && apt-get install -y python3-dev python3-pytest - name: Configure - run: cmake -S . -B build -DCMAKE_CXX_CLANG_TIDY="$(which clang-tidy);--warnings-as-errors=*" + run: > + cmake -S . -B build + -DCMAKE_CXX_CLANG_TIDY="$(which clang-tidy)" + -DDOWNLOAD_EIGEN=ON + -DDOWNLOAD_CATCH=ON + -DCMAKE_CXX_STANDARD=17 - name: Build - run: cmake --build build -j 2 + run: cmake --build build -j 2 -- --keep-going diff --git a/pybind11/.github/workflows/labeler.yml b/pybind11/.github/workflows/labeler.yml new file mode 100644 index 000000000..d2b597968 --- /dev/null +++ b/pybind11/.github/workflows/labeler.yml @@ -0,0 +1,16 @@ +name: Labeler +on: + pull_request_target: + types: [closed] + +jobs: + label: + name: Labeler + runs-on: ubuntu-latest + steps: + + - uses: actions/labeler@main + if: github.event.pull_request.merged == true + with: + repo-token: ${{ secrets.GITHUB_TOKEN }} + configuration-path: .github/labeler_merged.yml diff --git a/pybind11/.github/workflows/pip.yml b/pybind11/.github/workflows/pip.yml new file mode 100644 index 000000000..f74b79f0c --- /dev/null +++ b/pybind11/.github/workflows/pip.yml @@ -0,0 +1,108 @@ +name: Pip + +on: + workflow_dispatch: + pull_request: + push: + branches: + - master + - stable + - v* + release: + types: + - published + +env: + PIP_ONLY_BINARY: numpy + +jobs: + # This builds the sdists and wheels and makes sure the files are exactly as + # expected. Using Windows and Python 2.7, since that is often the most + # challenging matrix element. + test-packaging: + name: 🐍 2.7 • 📦 tests • windows-latest + runs-on: windows-latest + + steps: + - uses: actions/checkout@v2 + + - name: Setup 🐍 2.7 + uses: actions/setup-python@v2 + with: + python-version: 2.7 + + - name: Prepare env + run: | + python -m pip install -r tests/requirements.txt + + - name: Python Packaging tests + run: pytest tests/extra_python_package/ + + + # This runs the packaging tests and also builds and saves the packages as + # artifacts. + packaging: + name: 🐍 3.8 • 📦 & 📦 tests • ubuntu-latest + runs-on: ubuntu-latest + + steps: + - uses: actions/checkout@v2 + + - name: Setup 🐍 3.8 + uses: actions/setup-python@v2 + with: + python-version: 3.8 + + - name: Prepare env + run: | + python -m pip install -r tests/requirements.txt build twine + + - name: Python Packaging tests + run: pytest tests/extra_python_package/ + + - name: Build SDist and wheels + run: | + python -m build + PYBIND11_GLOBAL_SDIST=1 python -m build + + - name: Check metadata + run: twine check dist/* + + - name: Save standard package + uses: actions/upload-artifact@v2 + with: + name: standard + path: dist/pybind11-* + + - name: Save global package + uses: actions/upload-artifact@v2 + with: + name: global + path: dist/pybind11_global-* + + + + # When a GitHub release is made, upload the artifacts to PyPI + upload: + name: Upload to PyPI + runs-on: ubuntu-latest + if: github.event_name == 'release' && github.event.action == 'published' + needs: [packaging] + + steps: + - uses: actions/setup-python@v2 + + # Downloads all to directories matching the artifact names + - uses: actions/download-artifact@v2 + + - name: Publish standard package + uses: pypa/gh-action-pypi-publish@v1.5.0 + with: + password: ${{ secrets.pypi_password }} + packages_dir: standard/ + + - name: Publish global package + uses: pypa/gh-action-pypi-publish@v1.5.0 + with: + password: ${{ secrets.pypi_password_global }} + packages_dir: global/ diff --git a/pybind11/.github/workflows/upstream.yml b/pybind11/.github/workflows/upstream.yml new file mode 100644 index 000000000..138c9ad29 --- /dev/null +++ b/pybind11/.github/workflows/upstream.yml @@ -0,0 +1,112 @@ + +name: Upstream + +on: + workflow_dispatch: + pull_request: + +concurrency: + group: upstream-${{ github.ref }} + cancel-in-progress: true + +env: + PIP_ONLY_BINARY: numpy + +jobs: + standard: + name: "🐍 3.11 dev • ubuntu-latest • x64" + runs-on: ubuntu-latest + if: "contains(github.event.pull_request.labels.*.name, 'python dev')" + + steps: + - uses: actions/checkout@v2 + + - name: Setup Python 3.11 + uses: actions/setup-python@v2 + with: + python-version: "3.11-dev" + + - name: Setup Boost (Linux) + if: runner.os == 'Linux' + run: sudo apt-get install libboost-dev + + - name: Update CMake + uses: jwlawson/actions-setup-cmake@v1.12 + + - name: Prepare env + run: | + python -m pip install -r tests/requirements.txt + + - name: Setup annotations on Linux + if: runner.os == 'Linux' + run: python -m pip install pytest-github-actions-annotate-failures + + # First build - C++11 mode and inplace + - name: Configure C++11 + run: > + cmake -S . -B . + -DPYBIND11_WERROR=ON + -DDOWNLOAD_CATCH=ON + -DDOWNLOAD_EIGEN=ON + -DCMAKE_CXX_STANDARD=11 + + - name: Build C++11 + run: cmake --build . -j 2 + + - name: Python tests C++11 + run: cmake --build . --target pytest -j 2 + + - name: C++11 tests + run: cmake --build . --target cpptest -j 2 + + - name: Interface test C++11 + run: cmake --build . --target test_cmake_build + + - name: Clean directory + run: git clean -fdx + + # Second build - C++17 mode and in a build directory + - name: Configure C++17 + run: > + cmake -S . -B build2 + -DPYBIND11_WERROR=ON + -DDOWNLOAD_CATCH=ON + -DDOWNLOAD_EIGEN=ON + -DCMAKE_CXX_STANDARD=17 + ${{ matrix.args }} + ${{ matrix.args2 }} + + - name: Build + run: cmake --build build2 -j 2 + + - name: Python tests + run: cmake --build build2 --target pytest + + - name: C++ tests + run: cmake --build build2 --target cpptest + + # Third build - C++17 mode with unstable ABI + - name: Configure (unstable ABI) + run: > + cmake -S . -B build3 + -DPYBIND11_WERROR=ON + -DDOWNLOAD_CATCH=ON + -DDOWNLOAD_EIGEN=ON + -DCMAKE_CXX_STANDARD=17 + -DPYBIND11_INTERNALS_VERSION=10000000 + "-DPYBIND11_TEST_OVERRIDE=test_call_policies.cpp;test_gil_scoped.cpp;test_thread.cpp" + ${{ matrix.args }} + + - name: Build (unstable ABI) + run: cmake --build build3 -j 2 + + - name: Python tests (unstable ABI) + run: cmake --build build3 --target pytest + + - name: Interface test + run: cmake --build build2 --target test_cmake_build + + # This makes sure the setup_helpers module can build packages using + # setuptools + - name: Setuptools helpers test + run: pytest tests/extra_setuptools diff --git a/pybind11/.gitignore b/pybind11/.gitignore index 3f36b89e0..3cf4fbbda 100644 --- a/pybind11/.gitignore +++ b/pybind11/.gitignore @@ -41,3 +41,5 @@ pybind11Targets.cmake /.vscode /pybind11/include/* /pybind11/share/* +/docs/_build/* +.ipynb_checkpoints/ diff --git a/pybind11/.pre-commit-config.yaml b/pybind11/.pre-commit-config.yaml index 71513c991..2014cb2b4 100644 --- a/pybind11/.pre-commit-config.yaml +++ b/pybind11/.pre-commit-config.yaml @@ -15,12 +15,14 @@ repos: # Standard hooks - repo: https://github.com/pre-commit/pre-commit-hooks - rev: v3.2.0 + rev: v4.1.0 hooks: - id: check-added-large-files - id: check-case-conflict + - id: check-docstring-first - id: check-merge-conflict - id: check-symlinks + - id: check-toml - id: check-yaml - id: debug-statements - id: end-of-file-fixer @@ -28,54 +30,115 @@ repos: - id: requirements-txt-fixer - id: trailing-whitespace - id: fix-encoding-pragma + exclude: ^noxfile.py$ + +- repo: https://github.com/asottile/pyupgrade + rev: v2.31.0 + hooks: + - id: pyupgrade + +- repo: https://github.com/PyCQA/isort + rev: 5.10.1 + hooks: + - id: isort # Black, the code formatter, natively supports pre-commit - repo: https://github.com/psf/black - rev: 20.8b1 + rev: 21.12b0 # Keep in sync with blacken-docs hooks: - id: black - # Not all Python files are Blacked, yet - files: ^(setup.py|pybind11|tests/extra) + +- repo: https://github.com/asottile/blacken-docs + rev: v1.12.0 + hooks: + - id: blacken-docs + additional_dependencies: + - black==21.12b0 # keep in sync with black hook # Changes tabs to spaces - repo: https://github.com/Lucas-C/pre-commit-hooks - rev: v1.1.9 + rev: v1.1.10 hooks: - id: remove-tabs +# Autoremoves unused imports +- repo: https://github.com/hadialqattan/pycln + rev: v1.1.0 + hooks: + - id: pycln + +- repo: https://github.com/pre-commit/pygrep-hooks + rev: v1.9.0 + hooks: + - id: python-check-blanket-noqa + - id: python-check-blanket-type-ignore + - id: python-no-log-warn + - id: rst-backticks + - id: rst-directive-colons + - id: rst-inline-touching-normal + # Flake8 also supports pre-commit natively (same author) -- repo: https://gitlab.com/pycqa/flake8 - rev: 3.8.3 +- repo: https://github.com/PyCQA/flake8 + rev: 4.0.1 hooks: - id: flake8 - additional_dependencies: [flake8-bugbear, pep8-naming] + additional_dependencies: &flake8_dependencies + - flake8-bugbear + - pep8-naming exclude: ^(docs/.*|tools/.*)$ +- repo: https://github.com/asottile/yesqa + rev: v1.3.0 + hooks: + - id: yesqa + additional_dependencies: *flake8_dependencies + # CMake formatting - repo: https://github.com/cheshirekow/cmake-format-precommit - rev: v0.6.11 + rev: v0.6.13 hooks: - id: cmake-format additional_dependencies: [pyyaml] types: [file] files: (\.cmake|CMakeLists.txt)(.in)?$ +# Check static types with mypy +- repo: https://github.com/pre-commit/mirrors-mypy + rev: v0.931 + hooks: + - id: mypy + # Running per-file misbehaves a bit, so just run on all files, it's fast + pass_filenames: false + additional_dependencies: [typed_ast] + # Checks the manifest for missing files (native support) - repo: https://github.com/mgedmin/check-manifest - rev: "0.42" + rev: "0.47" hooks: - id: check-manifest # This is a slow hook, so only run this if --hook-stage manual is passed stages: [manual] additional_dependencies: [cmake, ninja] +- repo: https://github.com/codespell-project/codespell + rev: v2.1.0 + hooks: + - id: codespell + exclude: ".supp$" + args: ["-L", "nd,ot,thist"] + +- repo: https://github.com/shellcheck-py/shellcheck-py + rev: v0.8.0.3 + hooks: + - id: shellcheck + # The original pybind11 checks for a few C++ style items - repo: local hooks: - id: disallow-caps name: Disallow improper capitalization language: pygrep - entry: PyBind|Numpy|Cmake + entry: PyBind|Numpy|Cmake|CCache|PyTest exclude: .pre-commit-config.yaml - repo: local diff --git a/pybind11/CMakeLists.txt b/pybind11/CMakeLists.txt index 123abf77d..3787982cb 100644 --- a/pybind11/CMakeLists.txt +++ b/pybind11/CMakeLists.txt @@ -7,13 +7,18 @@ cmake_minimum_required(VERSION 3.4) -# The `cmake_minimum_required(VERSION 3.4...3.18)` syntax does not work with +# The `cmake_minimum_required(VERSION 3.4...3.22)` syntax does not work with # some versions of VS that have a patched CMake 3.11. This forces us to emulate # the behavior using the following workaround: -if(${CMAKE_VERSION} VERSION_LESS 3.18) +if(${CMAKE_VERSION} VERSION_LESS 3.22) cmake_policy(VERSION ${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION}) else() - cmake_policy(VERSION 3.18) + cmake_policy(VERSION 3.22) +endif() + +# Avoid infinite recursion if tests include this as a subdirectory +if(DEFINED PYBIND11_MASTER_PROJECT) + return() endif() # Extract project version from source @@ -73,6 +78,10 @@ if(CMAKE_SOURCE_DIR STREQUAL PROJECT_SOURCE_DIR) set(CMAKE_CXX_EXTENSIONS OFF) set(CMAKE_CXX_STANDARD_REQUIRED ON) endif() + + set(pybind11_system "") + + set_property(GLOBAL PROPERTY USE_FOLDERS ON) else() set(PYBIND11_MASTER_PROJECT OFF) set(pybind11_system SYSTEM) @@ -82,6 +91,9 @@ endif() option(PYBIND11_INSTALL "Install pybind11 header files?" ${PYBIND11_MASTER_PROJECT}) option(PYBIND11_TEST "Build pybind11 test suite?" ${PYBIND11_MASTER_PROJECT}) option(PYBIND11_NOPYTHON "Disable search for Python" OFF) +set(PYBIND11_INTERNALS_VERSION + "" + CACHE STRING "Override the ABI version, may be used to enable the unstable ABI.") cmake_dependent_option( USE_PYTHON_INCLUDE_DIR @@ -98,6 +110,7 @@ set(PYBIND11_HEADERS include/pybind11/detail/descr.h include/pybind11/detail/init.h include/pybind11/detail/internals.h + include/pybind11/detail/type_caster_base.h include/pybind11/detail/typeid.h include/pybind11/attr.h include/pybind11/buffer_info.h @@ -109,6 +122,7 @@ set(PYBIND11_HEADERS include/pybind11/eigen.h include/pybind11/embed.h include/pybind11/eval.h + include/pybind11/gil.h include/pybind11/iostream.h include/pybind11/functional.h include/pybind11/numpy.h @@ -116,7 +130,8 @@ set(PYBIND11_HEADERS include/pybind11/pybind11.h include/pybind11/pytypes.h include/pybind11/stl.h - include/pybind11/stl_bind.h) + include/pybind11/stl_bind.h + include/pybind11/stl/filesystem.h) # Compare with grep and warn if mismatched if(PYBIND11_MASTER_PROJECT AND NOT CMAKE_VERSION VERSION_LESS 3.12) @@ -142,22 +157,45 @@ endif() string(REPLACE "include/" "${CMAKE_CURRENT_SOURCE_DIR}/include/" PYBIND11_HEADERS "${PYBIND11_HEADERS}") -# Cache variables so pybind11_add_module can be used in parent projects -set(PYBIND11_INCLUDE_DIR +# Cache variable so this can be used in parent projects +set(pybind11_INCLUDE_DIR "${CMAKE_CURRENT_LIST_DIR}/include" - CACHE INTERNAL "") + CACHE INTERNAL "Directory where pybind11 headers are located") + +# Backward compatible variable for add_subdirectory mode +if(NOT PYBIND11_MASTER_PROJECT) + set(PYBIND11_INCLUDE_DIR + "${pybind11_INCLUDE_DIR}" + CACHE INTERNAL "") +endif() # Note: when creating targets, you cannot use if statements at configure time - # you need generator expressions, because those will be placed in the target file. # You can also place ifs *in* the Config.in, but not here. # This section builds targets, but does *not* touch Python +# Non-IMPORT targets cannot be defined twice +if(NOT TARGET pybind11_headers) + # Build the headers-only target (no Python included): + # (long name used here to keep this from clashing in subdirectory mode) + add_library(pybind11_headers INTERFACE) + add_library(pybind11::pybind11_headers ALIAS pybind11_headers) # to match exported target + add_library(pybind11::headers ALIAS pybind11_headers) # easier to use/remember -# Build the headers-only target (no Python included): -# (long name used here to keep this from clashing in subdirectory mode) -add_library(pybind11_headers INTERFACE) -add_library(pybind11::pybind11_headers ALIAS pybind11_headers) # to match exported target -add_library(pybind11::headers ALIAS pybind11_headers) # easier to use/remember + target_include_directories( + pybind11_headers ${pybind11_system} INTERFACE $ + $) + + target_compile_features(pybind11_headers INTERFACE cxx_inheriting_constructors cxx_user_literals + cxx_right_angle_brackets) + if(NOT "${PYBIND11_INTERNALS_VERSION}" STREQUAL "") + target_compile_definitions( + pybind11_headers INTERFACE "PYBIND11_INTERNALS_VERSION=${PYBIND11_INTERNALS_VERSION}") + endif() +else() + # It is invalid to install a target twice, too. + set(PYBIND11_INSTALL OFF) +endif() include("${CMAKE_CURRENT_SOURCE_DIR}/tools/pybind11Common.cmake") @@ -168,21 +206,18 @@ elseif(USE_PYTHON_INCLUDE_DIR AND DEFINED PYTHON_INCLUDE_DIR) file(RELATIVE_PATH CMAKE_INSTALL_INCLUDEDIR ${CMAKE_INSTALL_PREFIX} ${PYTHON_INCLUDE_DIRS}) endif() -# Fill in headers target -target_include_directories( - pybind11_headers ${pybind11_system} INTERFACE $ - $) - -target_compile_features(pybind11_headers INTERFACE cxx_inheriting_constructors cxx_user_literals - cxx_right_angle_brackets) - if(PYBIND11_INSTALL) - install(DIRECTORY ${PYBIND11_INCLUDE_DIR}/pybind11 DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}) - # GNUInstallDirs "DATADIR" wrong here; CMake search path wants "share". + install(DIRECTORY ${pybind11_INCLUDE_DIR}/pybind11 DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}) set(PYBIND11_CMAKECONFIG_INSTALL_DIR - "share/cmake/${PROJECT_NAME}" + "${CMAKE_INSTALL_DATAROOTDIR}/cmake/${PROJECT_NAME}" CACHE STRING "install path for pybind11Config.cmake") + if(IS_ABSOLUTE "${CMAKE_INSTALL_INCLUDEDIR}") + set(pybind11_INCLUDEDIR "${CMAKE_INSTALL_FULL_INCLUDEDIR}") + else() + set(pybind11_INCLUDEDIR "\$\{PACKAGE_PREFIX_DIR\}/${CMAKE_INSTALL_INCLUDEDIR}") + endif() + configure_package_config_file( tools/${PROJECT_NAME}Config.cmake.in "${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}Config.cmake" INSTALL_DESTINATION ${PYBIND11_CMAKECONFIG_INSTALL_DIR}) @@ -260,8 +295,5 @@ endif() if(NOT PYBIND11_MASTER_PROJECT) set(pybind11_FOUND TRUE - CACHE INTERNAL "true if pybind11 and all required components found on the system") - set(pybind11_INCLUDE_DIR - "${PYBIND11_INCLUDE_DIR}" - CACHE INTERNAL "Directory where pybind11 headers are located") + CACHE INTERNAL "True if pybind11 and all required components found on the system") endif() diff --git a/pybind11/MANIFEST.in b/pybind11/MANIFEST.in index 9336b6030..aed183e87 100644 --- a/pybind11/MANIFEST.in +++ b/pybind11/MANIFEST.in @@ -1,4 +1,6 @@ recursive-include pybind11/include/pybind11 *.h recursive-include pybind11 *.py +recursive-include pybind11 py.typed +recursive-include pybind11 *.pyi include pybind11/share/cmake/pybind11/*.cmake -include LICENSE README.md pyproject.toml setup.py setup.cfg +include LICENSE README.rst pyproject.toml setup.py setup.cfg diff --git a/pybind11/README.md b/pybind11/README.md deleted file mode 100644 index 69a0fc90b..000000000 --- a/pybind11/README.md +++ /dev/null @@ -1,145 +0,0 @@ -![pybind11 logo](https://github.com/pybind/pybind11/raw/master/docs/pybind11-logo.png) - -# pybind11 — Seamless operability between C++11 and Python - -[![Documentation Status](https://readthedocs.org/projects/pybind11/badge/?version=master)](http://pybind11.readthedocs.org/en/master/?badge=master) -[![Documentation Status](https://readthedocs.org/projects/pybind11/badge/?version=stable)](http://pybind11.readthedocs.org/en/stable/?badge=stable) -[![Gitter chat](https://img.shields.io/gitter/room/gitterHQ/gitter.svg)](https://gitter.im/pybind/Lobby) -[![CI](https://github.com/pybind/pybind11/workflows/CI/badge.svg)](https://github.com/pybind/pybind11/actions) -[![Build status](https://ci.appveyor.com/api/projects/status/riaj54pn4h08xy40?svg=true)](https://ci.appveyor.com/project/wjakob/pybind11) - -**pybind11** is a lightweight header-only library that exposes C++ types in -Python and vice versa, mainly to create Python bindings of existing C++ code. -Its goals and syntax are similar to the excellent [Boost.Python][] library by -David Abrahams: to minimize boilerplate code in traditional extension modules -by inferring type information using compile-time introspection. - -The main issue with Boost.Python—and the reason for creating such a similar -project—is Boost. Boost is an enormously large and complex suite of utility -libraries that works with almost every C++ compiler in existence. This -compatibility has its cost: arcane template tricks and workarounds are -necessary to support the oldest and buggiest of compiler specimens. Now that -C++11-compatible compilers are widely available, this heavy machinery has -become an excessively large and unnecessary dependency. - -Think of this library as a tiny self-contained version of Boost.Python with -everything stripped away that isn't relevant for binding generation. Without -comments, the core header files only require ~4K lines of code and depend on -Python (2.7 or 3.5+, or PyPy) and the C++ standard library. This compact -implementation was possible thanks to some of the new C++11 language features -(specifically: tuples, lambda functions and variadic templates). Since its -creation, this library has grown beyond Boost.Python in many ways, leading to -dramatically simpler binding code in many common situations. - -Tutorial and reference documentation is provided at -[pybind11.readthedocs.org][]. A PDF version of the manual is available -[here][docs-pdf]. - -## Core features -pybind11 can map the following core C++ features to Python: - -- Functions accepting and returning custom data structures per value, reference, or pointer -- Instance methods and static methods -- Overloaded functions -- Instance attributes and static attributes -- Arbitrary exception types -- Enumerations -- Callbacks -- Iterators and ranges -- Custom operators -- Single and multiple inheritance -- STL data structures -- Smart pointers with reference counting like `std::shared_ptr` -- Internal references with correct reference counting -- C++ classes with virtual (and pure virtual) methods can be extended in Python - -## Goodies -In addition to the core functionality, pybind11 provides some extra goodies: - -- Python 2.7, 3.5+, and PyPy (tested on 7.3) are supported with an implementation-agnostic - interface. - -- It is possible to bind C++11 lambda functions with captured variables. The - lambda capture data is stored inside the resulting Python function object. - -- pybind11 uses C++11 move constructors and move assignment operators whenever - possible to efficiently transfer custom data types. - -- It's easy to expose the internal storage of custom data types through - Pythons' buffer protocols. This is handy e.g. for fast conversion between - C++ matrix classes like Eigen and NumPy without expensive copy operations. - -- pybind11 can automatically vectorize functions so that they are transparently - applied to all entries of one or more NumPy array arguments. - -- Python's slice-based access and assignment operations can be supported with - just a few lines of code. - -- Everything is contained in just a few header files; there is no need to link - against any additional libraries. - -- Binaries are generally smaller by a factor of at least 2 compared to - equivalent bindings generated by Boost.Python. A recent pybind11 conversion - of PyRosetta, an enormous Boost.Python binding project, - [reported][pyrosetta-report] a binary size reduction of **5.4x** and compile - time reduction by **5.8x**. - -- Function signatures are precomputed at compile time (using `constexpr`), - leading to smaller binaries. - -- With little extra effort, C++ types can be pickled and unpickled similar to - regular Python objects. - -## Supported compilers - -1. Clang/LLVM 3.3 or newer (for Apple Xcode's clang, this is 5.0.0 or newer) -2. GCC 4.8 or newer -3. Microsoft Visual Studio 2015 Update 3 or newer -4. Intel C++ compiler 17 or newer (16 with pybind11 v2.0 and 15 with pybind11 - v2.0 and a [workaround][intel-15-workaround]) -5. Cygwin/GCC (tested on 2.5.1) -6. NVCC (CUDA 11 tested) -7. NVIDIA PGI (20.7 tested) - -## About - -This project was created by [Wenzel Jakob](http://rgl.epfl.ch/people/wjakob). -Significant features and/or improvements to the code were contributed by -Jonas Adler, -Lori A. Burns, -Sylvain Corlay, -Trent Houliston, -Axel Huebl, -@hulucc, -Sergey Lyskov -Johan Mabille, -Tomasz Miąsko, -Dean Moldovan, -Ben Pritchard, -Jason Rhinelander, -Boris Schäling, -Pim Schellart, -Henry Schreiner, -Ivan Smirnov, and -Patrick Stewart. - -### Contributing - -See the [contributing guide][] for information on building and contributing to -pybind11. - - -### License - -pybind11 is provided under a BSD-style license that can be found in the -[`LICENSE`][] file. By using, distributing, or contributing to this project, -you agree to the terms and conditions of this license. - - -[pybind11.readthedocs.org]: http://pybind11.readthedocs.org/en/master -[docs-pdf]: https://media.readthedocs.org/pdf/pybind11/master/pybind11.pdf -[Boost.Python]: http://www.boost.org/doc/libs/1_58_0/libs/python/doc/ -[pyrosetta-report]: http://graylab.jhu.edu/RosettaCon2016/PyRosetta-4.pdf -[contributing guide]: https://github.com/pybind/pybind11/blob/master/.github/CONTRIBUTING.md -[`LICENSE`]: https://github.com/pybind/pybind11/blob/master/LICENSE -[intel-15-workaround]: https://github.com/pybind/pybind11/issues/276 diff --git a/pybind11/README.rst b/pybind11/README.rst new file mode 100644 index 000000000..45c4af5a6 --- /dev/null +++ b/pybind11/README.rst @@ -0,0 +1,180 @@ +.. figure:: https://github.com/pybind/pybind11/raw/master/docs/pybind11-logo.png + :alt: pybind11 logo + +**pybind11 — Seamless operability between C++11 and Python** + +|Latest Documentation Status| |Stable Documentation Status| |Gitter chat| |GitHub Discussions| |CI| |Build status| + +|Repology| |PyPI package| |Conda-forge| |Python Versions| + +`Setuptools example `_ +• `Scikit-build example `_ +• `CMake example `_ + +.. start + + +**pybind11** is a lightweight header-only library that exposes C++ types +in Python and vice versa, mainly to create Python bindings of existing +C++ code. Its goals and syntax are similar to the excellent +`Boost.Python `_ +library by David Abrahams: to minimize boilerplate code in traditional +extension modules by inferring type information using compile-time +introspection. + +The main issue with Boost.Python—and the reason for creating such a +similar project—is Boost. Boost is an enormously large and complex suite +of utility libraries that works with almost every C++ compiler in +existence. This compatibility has its cost: arcane template tricks and +workarounds are necessary to support the oldest and buggiest of compiler +specimens. Now that C++11-compatible compilers are widely available, +this heavy machinery has become an excessively large and unnecessary +dependency. + +Think of this library as a tiny self-contained version of Boost.Python +with everything stripped away that isn’t relevant for binding +generation. Without comments, the core header files only require ~4K +lines of code and depend on Python (2.7 or 3.5+, or PyPy) and the C++ +standard library. This compact implementation was possible thanks to +some of the new C++11 language features (specifically: tuples, lambda +functions and variadic templates). Since its creation, this library has +grown beyond Boost.Python in many ways, leading to dramatically simpler +binding code in many common situations. + +Tutorial and reference documentation is provided at +`pybind11.readthedocs.io `_. +A PDF version of the manual is available +`here `_. +And the source code is always available at +`github.com/pybind/pybind11 `_. + + +Core features +------------- + + +pybind11 can map the following core C++ features to Python: + +- Functions accepting and returning custom data structures per value, + reference, or pointer +- Instance methods and static methods +- Overloaded functions +- Instance attributes and static attributes +- Arbitrary exception types +- Enumerations +- Callbacks +- Iterators and ranges +- Custom operators +- Single and multiple inheritance +- STL data structures +- Smart pointers with reference counting like ``std::shared_ptr`` +- Internal references with correct reference counting +- C++ classes with virtual (and pure virtual) methods can be extended + in Python + +Goodies +------- + +In addition to the core functionality, pybind11 provides some extra +goodies: + +- Python 2.7, 3.5+, and PyPy/PyPy3 7.3 are supported with an + implementation-agnostic interface. + +- It is possible to bind C++11 lambda functions with captured + variables. The lambda capture data is stored inside the resulting + Python function object. + +- pybind11 uses C++11 move constructors and move assignment operators + whenever possible to efficiently transfer custom data types. + +- It’s easy to expose the internal storage of custom data types through + Pythons’ buffer protocols. This is handy e.g. for fast conversion + between C++ matrix classes like Eigen and NumPy without expensive + copy operations. + +- pybind11 can automatically vectorize functions so that they are + transparently applied to all entries of one or more NumPy array + arguments. + +- Python's slice-based access and assignment operations can be + supported with just a few lines of code. + +- Everything is contained in just a few header files; there is no need + to link against any additional libraries. + +- Binaries are generally smaller by a factor of at least 2 compared to + equivalent bindings generated by Boost.Python. A recent pybind11 + conversion of PyRosetta, an enormous Boost.Python binding project, + `reported `_ + a binary size reduction of **5.4x** and compile time reduction by + **5.8x**. + +- Function signatures are precomputed at compile time (using + ``constexpr``), leading to smaller binaries. + +- With little extra effort, C++ types can be pickled and unpickled + similar to regular Python objects. + +Supported compilers +------------------- + +1. Clang/LLVM 3.3 or newer (for Apple Xcode’s clang, this is 5.0.0 or + newer) +2. GCC 4.8 or newer +3. Microsoft Visual Studio 2015 Update 3 or newer +4. Intel classic C++ compiler 18 or newer (ICC 20.2 tested in CI) +5. Cygwin/GCC (previously tested on 2.5.1) +6. NVCC (CUDA 11.0 tested in CI) +7. NVIDIA PGI (20.9 tested in CI) + +About +----- + +This project was created by `Wenzel +Jakob `_. Significant features and/or +improvements to the code were contributed by Jonas Adler, Lori A. Burns, +Sylvain Corlay, Eric Cousineau, Aaron Gokaslan, Ralf Grosse-Kunstleve, Trent Houliston, Axel +Huebl, @hulucc, Yannick Jadoul, Sergey Lyskov Johan Mabille, Tomasz Miąsko, +Dean Moldovan, Ben Pritchard, Jason Rhinelander, Boris Schäling, Pim +Schellart, Henry Schreiner, Ivan Smirnov, Boris Staletic, and Patrick Stewart. + +We thank Google for a generous financial contribution to the continuous +integration infrastructure used by this project. + + +Contributing +~~~~~~~~~~~~ + +See the `contributing +guide `_ +for information on building and contributing to pybind11. + +License +~~~~~~~ + +pybind11 is provided under a BSD-style license that can be found in the +`LICENSE `_ +file. By using, distributing, or contributing to this project, you agree +to the terms and conditions of this license. + +.. |Latest Documentation Status| image:: https://readthedocs.org/projects/pybind11/badge?version=latest + :target: http://pybind11.readthedocs.org/en/latest +.. |Stable Documentation Status| image:: https://img.shields.io/badge/docs-stable-blue.svg + :target: http://pybind11.readthedocs.org/en/stable +.. |Gitter chat| image:: https://img.shields.io/gitter/room/gitterHQ/gitter.svg + :target: https://gitter.im/pybind/Lobby +.. |CI| image:: https://github.com/pybind/pybind11/workflows/CI/badge.svg + :target: https://github.com/pybind/pybind11/actions +.. |Build status| image:: https://ci.appveyor.com/api/projects/status/riaj54pn4h08xy40?svg=true + :target: https://ci.appveyor.com/project/wjakob/pybind11 +.. |PyPI package| image:: https://img.shields.io/pypi/v/pybind11.svg + :target: https://pypi.org/project/pybind11/ +.. |Conda-forge| image:: https://img.shields.io/conda/vn/conda-forge/pybind11.svg + :target: https://github.com/conda-forge/pybind11-feedstock +.. |Repology| image:: https://repology.org/badge/latest-versions/python:pybind11.svg + :target: https://repology.org/project/python:pybind11/versions +.. |Python Versions| image:: https://img.shields.io/pypi/pyversions/pybind11.svg + :target: https://pypi.org/project/pybind11/ +.. |GitHub Discussions| image:: https://img.shields.io/static/v1?label=Discussions&message=Ask&color=blue&logo=github + :target: https://github.com/pybind/pybind11/discussions diff --git a/pybind11/docs/Doxyfile b/pybind11/docs/Doxyfile index 24ece0d8d..62c267556 100644 --- a/pybind11/docs/Doxyfile +++ b/pybind11/docs/Doxyfile @@ -18,5 +18,5 @@ ALIASES += "endrst=\endverbatim" QUIET = YES WARNINGS = YES WARN_IF_UNDOCUMENTED = NO -PREDEFINED = DOXYGEN_SHOULD_SKIP_THIS \ - PY_MAJOR_VERSION=3 +PREDEFINED = PY_MAJOR_VERSION=3 \ + PYBIND11_NOINLINE diff --git a/pybind11/docs/advanced/cast/custom.rst b/pybind11/docs/advanced/cast/custom.rst index a779444c2..1df4d3e14 100644 --- a/pybind11/docs/advanced/cast/custom.rst +++ b/pybind11/docs/advanced/cast/custom.rst @@ -26,7 +26,9 @@ The following Python snippet demonstrates the intended usage from the Python sid def __int__(self): return 123 + from example import print + print(A()) To register the necessary conversion routines, it is necessary to add an @@ -44,7 +46,7 @@ type is explicitly allowed. * function signatures and declares a local variable * 'value' of type inty */ - PYBIND11_TYPE_CASTER(inty, _("inty")); + PYBIND11_TYPE_CASTER(inty, const_name("inty")); /** * Conversion part 1 (Python->C++): convert a PyObject into a inty diff --git a/pybind11/docs/advanced/cast/eigen.rst b/pybind11/docs/advanced/cast/eigen.rst index e01472d5a..a5c11a3f1 100644 --- a/pybind11/docs/advanced/cast/eigen.rst +++ b/pybind11/docs/advanced/cast/eigen.rst @@ -52,7 +52,7 @@ can be mapped *and* if the numpy array is writeable (that is the passed variable will be transparently carried out directly on the ``numpy.ndarray``. -This means you can can write code such as the following and have it work as +This means you can write code such as the following and have it work as expected: .. code-block:: cpp @@ -112,7 +112,7 @@ example: .. code-block:: python a = MyClass() - m = a.get_matrix() # flags.writeable = True, flags.owndata = False + m = a.get_matrix() # flags.writeable = True, flags.owndata = False v = a.view_matrix() # flags.writeable = False, flags.owndata = False c = a.copy_matrix() # flags.writeable = True, flags.owndata = True # m[5,6] and v[5,6] refer to the same element, c[5,6] does not. @@ -203,7 +203,7 @@ adding the ``order='F'`` option when creating an array: .. code-block:: python - myarray = np.array(source, order='F') + myarray = np.array(source, order="F") Such an object will be passable to a bound function accepting an ``Eigen::Ref`` (or similar column-major Eigen type). diff --git a/pybind11/docs/advanced/cast/overview.rst b/pybind11/docs/advanced/cast/overview.rst index b0e32a52f..6a834a3e5 100644 --- a/pybind11/docs/advanced/cast/overview.rst +++ b/pybind11/docs/advanced/cast/overview.rst @@ -75,91 +75,97 @@ The following basic data types are supported out of the box (some may require an additional extension header to be included). To pass other data structures as arguments and return values, refer to the section on binding :ref:`classes`. -+------------------------------------+---------------------------+-------------------------------+ -| Data type | Description | Header file | -+====================================+===========================+===============================+ -| ``int8_t``, ``uint8_t`` | 8-bit integers | :file:`pybind11/pybind11.h` | -+------------------------------------+---------------------------+-------------------------------+ -| ``int16_t``, ``uint16_t`` | 16-bit integers | :file:`pybind11/pybind11.h` | -+------------------------------------+---------------------------+-------------------------------+ -| ``int32_t``, ``uint32_t`` | 32-bit integers | :file:`pybind11/pybind11.h` | -+------------------------------------+---------------------------+-------------------------------+ -| ``int64_t``, ``uint64_t`` | 64-bit integers | :file:`pybind11/pybind11.h` | -+------------------------------------+---------------------------+-------------------------------+ -| ``ssize_t``, ``size_t`` | Platform-dependent size | :file:`pybind11/pybind11.h` | -+------------------------------------+---------------------------+-------------------------------+ -| ``float``, ``double`` | Floating point types | :file:`pybind11/pybind11.h` | -+------------------------------------+---------------------------+-------------------------------+ -| ``bool`` | Two-state Boolean type | :file:`pybind11/pybind11.h` | -+------------------------------------+---------------------------+-------------------------------+ -| ``char`` | Character literal | :file:`pybind11/pybind11.h` | -+------------------------------------+---------------------------+-------------------------------+ -| ``char16_t`` | UTF-16 character literal | :file:`pybind11/pybind11.h` | -+------------------------------------+---------------------------+-------------------------------+ -| ``char32_t`` | UTF-32 character literal | :file:`pybind11/pybind11.h` | -+------------------------------------+---------------------------+-------------------------------+ -| ``wchar_t`` | Wide character literal | :file:`pybind11/pybind11.h` | -+------------------------------------+---------------------------+-------------------------------+ -| ``const char *`` | UTF-8 string literal | :file:`pybind11/pybind11.h` | -+------------------------------------+---------------------------+-------------------------------+ -| ``const char16_t *`` | UTF-16 string literal | :file:`pybind11/pybind11.h` | -+------------------------------------+---------------------------+-------------------------------+ -| ``const char32_t *`` | UTF-32 string literal | :file:`pybind11/pybind11.h` | -+------------------------------------+---------------------------+-------------------------------+ -| ``const wchar_t *`` | Wide string literal | :file:`pybind11/pybind11.h` | -+------------------------------------+---------------------------+-------------------------------+ -| ``std::string`` | STL dynamic UTF-8 string | :file:`pybind11/pybind11.h` | -+------------------------------------+---------------------------+-------------------------------+ -| ``std::u16string`` | STL dynamic UTF-16 string | :file:`pybind11/pybind11.h` | -+------------------------------------+---------------------------+-------------------------------+ -| ``std::u32string`` | STL dynamic UTF-32 string | :file:`pybind11/pybind11.h` | -+------------------------------------+---------------------------+-------------------------------+ -| ``std::wstring`` | STL dynamic wide string | :file:`pybind11/pybind11.h` | -+------------------------------------+---------------------------+-------------------------------+ -| ``std::string_view``, | STL C++17 string views | :file:`pybind11/pybind11.h` | -| ``std::u16string_view``, etc. | | | -+------------------------------------+---------------------------+-------------------------------+ -| ``std::pair`` | Pair of two custom types | :file:`pybind11/pybind11.h` | -+------------------------------------+---------------------------+-------------------------------+ -| ``std::tuple<...>`` | Arbitrary tuple of types | :file:`pybind11/pybind11.h` | -+------------------------------------+---------------------------+-------------------------------+ -| ``std::reference_wrapper<...>`` | Reference type wrapper | :file:`pybind11/pybind11.h` | -+------------------------------------+---------------------------+-------------------------------+ -| ``std::complex`` | Complex numbers | :file:`pybind11/complex.h` | -+------------------------------------+---------------------------+-------------------------------+ -| ``std::array`` | STL static array | :file:`pybind11/stl.h` | -+------------------------------------+---------------------------+-------------------------------+ -| ``std::vector`` | STL dynamic array | :file:`pybind11/stl.h` | -+------------------------------------+---------------------------+-------------------------------+ -| ``std::deque`` | STL double-ended queue | :file:`pybind11/stl.h` | -+------------------------------------+---------------------------+-------------------------------+ -| ``std::valarray`` | STL value array | :file:`pybind11/stl.h` | -+------------------------------------+---------------------------+-------------------------------+ -| ``std::list`` | STL linked list | :file:`pybind11/stl.h` | -+------------------------------------+---------------------------+-------------------------------+ -| ``std::map`` | STL ordered map | :file:`pybind11/stl.h` | -+------------------------------------+---------------------------+-------------------------------+ -| ``std::unordered_map`` | STL unordered map | :file:`pybind11/stl.h` | -+------------------------------------+---------------------------+-------------------------------+ -| ``std::set`` | STL ordered set | :file:`pybind11/stl.h` | -+------------------------------------+---------------------------+-------------------------------+ -| ``std::unordered_set`` | STL unordered set | :file:`pybind11/stl.h` | -+------------------------------------+---------------------------+-------------------------------+ -| ``std::optional`` | STL optional type (C++17) | :file:`pybind11/stl.h` | -+------------------------------------+---------------------------+-------------------------------+ -| ``std::experimental::optional`` | STL optional type (exp.) | :file:`pybind11/stl.h` | -+------------------------------------+---------------------------+-------------------------------+ -| ``std::variant<...>`` | Type-safe union (C++17) | :file:`pybind11/stl.h` | -+------------------------------------+---------------------------+-------------------------------+ -| ``std::function<...>`` | STL polymorphic function | :file:`pybind11/functional.h` | -+------------------------------------+---------------------------+-------------------------------+ -| ``std::chrono::duration<...>`` | STL time duration | :file:`pybind11/chrono.h` | -+------------------------------------+---------------------------+-------------------------------+ -| ``std::chrono::time_point<...>`` | STL date/time | :file:`pybind11/chrono.h` | -+------------------------------------+---------------------------+-------------------------------+ -| ``Eigen::Matrix<...>`` | Eigen: dense matrix | :file:`pybind11/eigen.h` | -+------------------------------------+---------------------------+-------------------------------+ -| ``Eigen::Map<...>`` | Eigen: mapped memory | :file:`pybind11/eigen.h` | -+------------------------------------+---------------------------+-------------------------------+ -| ``Eigen::SparseMatrix<...>`` | Eigen: sparse matrix | :file:`pybind11/eigen.h` | -+------------------------------------+---------------------------+-------------------------------+ ++------------------------------------+---------------------------+-----------------------------------+ +| Data type | Description | Header file | ++====================================+===========================+===================================+ +| ``int8_t``, ``uint8_t`` | 8-bit integers | :file:`pybind11/pybind11.h` | ++------------------------------------+---------------------------+-----------------------------------+ +| ``int16_t``, ``uint16_t`` | 16-bit integers | :file:`pybind11/pybind11.h` | ++------------------------------------+---------------------------+-----------------------------------+ +| ``int32_t``, ``uint32_t`` | 32-bit integers | :file:`pybind11/pybind11.h` | ++------------------------------------+---------------------------+-----------------------------------+ +| ``int64_t``, ``uint64_t`` | 64-bit integers | :file:`pybind11/pybind11.h` | ++------------------------------------+---------------------------+-----------------------------------+ +| ``ssize_t``, ``size_t`` | Platform-dependent size | :file:`pybind11/pybind11.h` | ++------------------------------------+---------------------------+-----------------------------------+ +| ``float``, ``double`` | Floating point types | :file:`pybind11/pybind11.h` | ++------------------------------------+---------------------------+-----------------------------------+ +| ``bool`` | Two-state Boolean type | :file:`pybind11/pybind11.h` | ++------------------------------------+---------------------------+-----------------------------------+ +| ``char`` | Character literal | :file:`pybind11/pybind11.h` | ++------------------------------------+---------------------------+-----------------------------------+ +| ``char16_t`` | UTF-16 character literal | :file:`pybind11/pybind11.h` | ++------------------------------------+---------------------------+-----------------------------------+ +| ``char32_t`` | UTF-32 character literal | :file:`pybind11/pybind11.h` | ++------------------------------------+---------------------------+-----------------------------------+ +| ``wchar_t`` | Wide character literal | :file:`pybind11/pybind11.h` | ++------------------------------------+---------------------------+-----------------------------------+ +| ``const char *`` | UTF-8 string literal | :file:`pybind11/pybind11.h` | ++------------------------------------+---------------------------+-----------------------------------+ +| ``const char16_t *`` | UTF-16 string literal | :file:`pybind11/pybind11.h` | ++------------------------------------+---------------------------+-----------------------------------+ +| ``const char32_t *`` | UTF-32 string literal | :file:`pybind11/pybind11.h` | ++------------------------------------+---------------------------+-----------------------------------+ +| ``const wchar_t *`` | Wide string literal | :file:`pybind11/pybind11.h` | ++------------------------------------+---------------------------+-----------------------------------+ +| ``std::string`` | STL dynamic UTF-8 string | :file:`pybind11/pybind11.h` | ++------------------------------------+---------------------------+-----------------------------------+ +| ``std::u16string`` | STL dynamic UTF-16 string | :file:`pybind11/pybind11.h` | ++------------------------------------+---------------------------+-----------------------------------+ +| ``std::u32string`` | STL dynamic UTF-32 string | :file:`pybind11/pybind11.h` | ++------------------------------------+---------------------------+-----------------------------------+ +| ``std::wstring`` | STL dynamic wide string | :file:`pybind11/pybind11.h` | ++------------------------------------+---------------------------+-----------------------------------+ +| ``std::string_view``, | STL C++17 string views | :file:`pybind11/pybind11.h` | +| ``std::u16string_view``, etc. | | | ++------------------------------------+---------------------------+-----------------------------------+ +| ``std::pair`` | Pair of two custom types | :file:`pybind11/pybind11.h` | ++------------------------------------+---------------------------+-----------------------------------+ +| ``std::tuple<...>`` | Arbitrary tuple of types | :file:`pybind11/pybind11.h` | ++------------------------------------+---------------------------+-----------------------------------+ +| ``std::reference_wrapper<...>`` | Reference type wrapper | :file:`pybind11/pybind11.h` | ++------------------------------------+---------------------------+-----------------------------------+ +| ``std::complex`` | Complex numbers | :file:`pybind11/complex.h` | ++------------------------------------+---------------------------+-----------------------------------+ +| ``std::array`` | STL static array | :file:`pybind11/stl.h` | ++------------------------------------+---------------------------+-----------------------------------+ +| ``std::vector`` | STL dynamic array | :file:`pybind11/stl.h` | ++------------------------------------+---------------------------+-----------------------------------+ +| ``std::deque`` | STL double-ended queue | :file:`pybind11/stl.h` | ++------------------------------------+---------------------------+-----------------------------------+ +| ``std::valarray`` | STL value array | :file:`pybind11/stl.h` | ++------------------------------------+---------------------------+-----------------------------------+ +| ``std::list`` | STL linked list | :file:`pybind11/stl.h` | ++------------------------------------+---------------------------+-----------------------------------+ +| ``std::map`` | STL ordered map | :file:`pybind11/stl.h` | ++------------------------------------+---------------------------+-----------------------------------+ +| ``std::unordered_map`` | STL unordered map | :file:`pybind11/stl.h` | ++------------------------------------+---------------------------+-----------------------------------+ +| ``std::set`` | STL ordered set | :file:`pybind11/stl.h` | ++------------------------------------+---------------------------+-----------------------------------+ +| ``std::unordered_set`` | STL unordered set | :file:`pybind11/stl.h` | ++------------------------------------+---------------------------+-----------------------------------+ +| ``std::optional`` | STL optional type (C++17) | :file:`pybind11/stl.h` | ++------------------------------------+---------------------------+-----------------------------------+ +| ``std::experimental::optional`` | STL optional type (exp.) | :file:`pybind11/stl.h` | ++------------------------------------+---------------------------+-----------------------------------+ +| ``std::variant<...>`` | Type-safe union (C++17) | :file:`pybind11/stl.h` | ++------------------------------------+---------------------------+-----------------------------------+ +| ``std::filesystem::path`` | STL path (C++17) [#]_ | :file:`pybind11/stl/filesystem.h` | ++------------------------------------+---------------------------+-----------------------------------+ +| ``std::function<...>`` | STL polymorphic function | :file:`pybind11/functional.h` | ++------------------------------------+---------------------------+-----------------------------------+ +| ``std::chrono::duration<...>`` | STL time duration | :file:`pybind11/chrono.h` | ++------------------------------------+---------------------------+-----------------------------------+ +| ``std::chrono::time_point<...>`` | STL date/time | :file:`pybind11/chrono.h` | ++------------------------------------+---------------------------+-----------------------------------+ +| ``Eigen::Matrix<...>`` | Eigen: dense matrix | :file:`pybind11/eigen.h` | ++------------------------------------+---------------------------+-----------------------------------+ +| ``Eigen::Map<...>`` | Eigen: mapped memory | :file:`pybind11/eigen.h` | ++------------------------------------+---------------------------+-----------------------------------+ +| ``Eigen::SparseMatrix<...>`` | Eigen: sparse matrix | :file:`pybind11/eigen.h` | ++------------------------------------+---------------------------+-----------------------------------+ + +.. [#] ``std::filesystem::path`` is converted to ``pathlib.Path`` and + ``os.PathLike`` is converted to ``std::filesystem::path``, but this requires + Python 3.6 (for ``__fspath__`` support). diff --git a/pybind11/docs/advanced/cast/stl.rst b/pybind11/docs/advanced/cast/stl.rst index 7f708b81e..b8622ee09 100644 --- a/pybind11/docs/advanced/cast/stl.rst +++ b/pybind11/docs/advanced/cast/stl.rst @@ -5,7 +5,7 @@ Automatic conversion ==================== When including the additional header file :file:`pybind11/stl.h`, conversions -between ``std::vector<>``/``std::deque<>``/``std::list<>``/``std::array<>``, +between ``std::vector<>``/``std::deque<>``/``std::list<>``/``std::array<>``/``std::valarray<>``, ``std::set<>``/``std::unordered_set<>``, and ``std::map<>``/``std::unordered_map<>`` and the Python ``list``, ``set`` and ``dict`` data structures are automatically enabled. The types ``std::pair<>`` @@ -72,6 +72,17 @@ The ``visit_helper`` specialization is not required if your ``name::variant`` pr a ``name::visit()`` function. For any other function name, the specialization must be included to tell pybind11 how to visit the variant. +.. warning:: + + When converting a ``variant`` type, pybind11 follows the same rules as when + determining which function overload to call (:ref:`overload_resolution`), and + so the same caveats hold. In particular, the order in which the ``variant``'s + alternatives are listed is important, since pybind11 will try conversions in + this order. This means that, for example, when converting ``variant``, + the ``bool`` variant will never be selected, as any Python ``bool`` is already + an ``int`` and is convertible to a C++ ``int``. Changing the order of alternatives + (and using ``variant``, in this example) provides a solution. + .. note:: pybind11 only supports the modern implementation of ``boost::variant`` diff --git a/pybind11/docs/advanced/cast/strings.rst b/pybind11/docs/advanced/cast/strings.rst index e25701eca..cfd7e7b7a 100644 --- a/pybind11/docs/advanced/cast/strings.rst +++ b/pybind11/docs/advanced/cast/strings.rst @@ -36,13 +36,13 @@ everywhere `_. } ); -.. code-block:: python +.. code-block:: pycon - >>> utf8_test('🎂') + >>> utf8_test("🎂") utf-8 is icing on the cake. 🎂 - >>> utf8_charptr('🍕') + >>> utf8_charptr("🍕") My favorite food is 🍕 @@ -80,7 +80,7 @@ raise a ``UnicodeDecodeError``. } ); -.. code-block:: python +.. code-block:: pycon >>> isinstance(example.std_string_return(), str) True @@ -114,7 +114,7 @@ conversion has the same overhead as implicit conversion. } ); -.. code-block:: python +.. code-block:: pycon >>> str_output() 'Send your résumé to Alice in HR' @@ -143,7 +143,7 @@ returned to Python as ``bytes``, then one can return the data as a } ); -.. code-block:: python +.. code-block:: pycon >>> example.return_bytes() b'\xba\xd0\xba\xd0' @@ -160,7 +160,7 @@ encoding, but cannot convert ``std::string`` back to ``bytes`` implicitly. } ); -.. code-block:: python +.. code-block:: pycon >>> isinstance(example.asymmetry(b"have some bytes"), str) True @@ -229,16 +229,16 @@ character. m.def("pass_char", [](char c) { return c; }); m.def("pass_wchar", [](wchar_t w) { return w; }); -.. code-block:: python +.. code-block:: pycon - >>> example.pass_char('A') + >>> example.pass_char("A") 'A' While C++ will cast integers to character types (``char c = 0x65;``), pybind11 does not convert Python integers to characters implicitly. The Python function ``chr()`` can be used to convert integers to characters. -.. code-block:: python +.. code-block:: pycon >>> example.pass_char(0x65) TypeError @@ -259,17 +259,17 @@ a combining acute accent). The combining character will be lost if the two-character sequence is passed as an argument, even though it renders as a single grapheme. -.. code-block:: python +.. code-block:: pycon - >>> example.pass_wchar('é') + >>> example.pass_wchar("é") 'é' - >>> combining_e_acute = 'e' + '\u0301' + >>> combining_e_acute = "e" + "\u0301" >>> combining_e_acute 'é' - >>> combining_e_acute == 'é' + >>> combining_e_acute == "é" False >>> example.pass_wchar(combining_e_acute) @@ -278,9 +278,9 @@ single grapheme. Normalizing combining characters before passing the character literal to C++ may resolve *some* of these issues: -.. code-block:: python +.. code-block:: pycon - >>> example.pass_wchar(unicodedata.normalize('NFC', combining_e_acute)) + >>> example.pass_wchar(unicodedata.normalize("NFC", combining_e_acute)) 'é' In some languages (Thai for example), there are `graphemes that cannot be diff --git a/pybind11/docs/advanced/classes.rst b/pybind11/docs/advanced/classes.rst index 492790206..f3339336d 100644 --- a/pybind11/docs/advanced/classes.rst +++ b/pybind11/docs/advanced/classes.rst @@ -9,7 +9,7 @@ that you are already familiar with the basics from :doc:`/classes`. Overriding virtual functions in Python ====================================== -Suppose that a C++ class or interface has a virtual function that we'd like to +Suppose that a C++ class or interface has a virtual function that we'd like to override from within Python (we'll focus on the class ``Animal``; ``Dog`` is given as a specific example of how one would do this with traditional C++ code). @@ -136,7 +136,7 @@ a virtual method call. u'woof! woof! woof! ' >>> class Cat(Animal): ... def go(self, n_times): - ... return "meow! " * n_times + ... return "meow! " * n_times ... >>> c = Cat() >>> call_go(c) @@ -159,8 +159,9 @@ Here is an example: class Dachshund(Dog): def __init__(self, name): - Dog.__init__(self) # Without this, a TypeError is raised. + Dog.__init__(self) # Without this, a TypeError is raised. self.name = name + def bark(self): return "yap!" @@ -259,7 +260,7 @@ override the ``name()`` method): .. note:: - Note the trailing commas in the ``PYBIND11_OVERIDE`` calls to ``name()`` + Note the trailing commas in the ``PYBIND11_OVERRIDE`` calls to ``name()`` and ``bark()``. These are needed to portably implement a trampoline for a function that does not take any arguments. For functions that take a nonzero number of arguments, the trailing comma must be omitted. @@ -804,7 +805,7 @@ to bind these two functions: } )); -The ``__setstate__`` part of the ``py::picke()`` definition follows the same +The ``__setstate__`` part of the ``py::pickle()`` definition follows the same rules as the single-argument version of ``py::init()``. The return type can be a value, pointer or holder type. See :ref:`custom_constructors` for details. @@ -1153,12 +1154,65 @@ error: >>> class PyFinalChild(IsFinal): ... pass + ... TypeError: type 'IsFinal' is not an acceptable base type .. note:: This attribute is currently ignored on PyPy .. versionadded:: 2.6 +Binding classes with template parameters +======================================== + +pybind11 can also wrap classes that have template parameters. Consider these classes: + +.. code-block:: cpp + + struct Cat {}; + struct Dog {}; + + template + struct Cage { + Cage(PetType& pet); + PetType& get(); + }; + +C++ templates may only be instantiated at compile time, so pybind11 can only +wrap instantiated templated classes. You cannot wrap a non-instantiated template: + +.. code-block:: cpp + + // BROKEN (this will not compile) + py::class_(m, "Cage"); + .def("get", &Cage::get); + +You must explicitly specify each template/type combination that you want to +wrap separately. + +.. code-block:: cpp + + // ok + py::class_>(m, "CatCage") + .def("get", &Cage::get); + + // ok + py::class_>(m, "DogCage") + .def("get", &Cage::get); + +If your class methods have template parameters you can wrap those as well, +but once again each instantiation must be explicitly specified: + +.. code-block:: cpp + + typename + struct MyClass { + template + T fn(V v); + }; + + py::class>(m, "MyClassT") + .def("fn", &MyClass::fn); + Custom automatic downcasters ============================ @@ -1247,7 +1301,7 @@ Accessing the type object You can get the type object from a C++ class that has already been registered using: -.. code-block:: python +.. code-block:: cpp py::type T_py = py::type::of(); @@ -1259,3 +1313,37 @@ object, just like ``type(ob)`` in Python. Other types, like ``py::type::of()``, do not work, see :ref:`type-conversions`. .. versionadded:: 2.6 + +Custom type setup +================= + +For advanced use cases, such as enabling garbage collection support, you may +wish to directly manipulate the ``PyHeapTypeObject`` corresponding to a +``py::class_`` definition. + +You can do that using ``py::custom_type_setup``: + +.. code-block:: cpp + + struct OwnsPythonObjects { + py::object value = py::none(); + }; + py::class_ cls( + m, "OwnsPythonObjects", py::custom_type_setup([](PyHeapTypeObject *heap_type) { + auto *type = &heap_type->ht_type; + type->tp_flags |= Py_TPFLAGS_HAVE_GC; + type->tp_traverse = [](PyObject *self_base, visitproc visit, void *arg) { + auto &self = py::cast(py::handle(self_base)); + Py_VISIT(self.value.ptr()); + return 0; + }; + type->tp_clear = [](PyObject *self_base) { + auto &self = py::cast(py::handle(self_base)); + self.value = py::none(); + return 0; + }; + })); + cls.def(py::init<>()); + cls.def_readwrite("value", &OwnsPythonObjects::value); + +.. versionadded:: 2.8 diff --git a/pybind11/docs/advanced/embedding.rst b/pybind11/docs/advanced/embedding.rst index 98a5c5219..dd980d483 100644 --- a/pybind11/docs/advanced/embedding.rst +++ b/pybind11/docs/advanced/embedding.rst @@ -40,15 +40,15 @@ The essential structure of the ``main.cpp`` file looks like this: } The interpreter must be initialized before using any Python API, which includes -all the functions and classes in pybind11. The RAII guard class `scoped_interpreter` +all the functions and classes in pybind11. The RAII guard class ``scoped_interpreter`` takes care of the interpreter lifetime. After the guard is destroyed, the interpreter shuts down and clears its memory. No Python functions can be called after this. Executing Python code ===================== -There are a few different ways to run Python code. One option is to use `eval`, -`exec` or `eval_file`, as explained in :ref:`eval`. Here is a quick example in +There are a few different ways to run Python code. One option is to use ``eval``, +``exec`` or ``eval_file``, as explained in :ref:`eval`. Here is a quick example in the context of an executable with an embedded interpreter: .. code-block:: cpp @@ -108,11 +108,11 @@ The two approaches can also be combined: Importing modules ================= -Python modules can be imported using `module::import()`: +Python modules can be imported using ``module_::import()``: .. code-block:: cpp - py::module sys = py::module::import("sys"); + py::module_ sys = py::module_::import("sys"); py::print(sys.attr("path")); For convenience, the current working directory is included in ``sys.path`` when @@ -122,18 +122,19 @@ embedding the interpreter. This makes it easy to import local Python files: """calc.py located in the working directory""" + def add(i, j): return i + j .. code-block:: cpp - py::module calc = py::module::import("calc"); + py::module_ calc = py::module_::import("calc"); py::object result = calc.attr("add")(1, 2); int n = result.cast(); assert(n == 3); -Modules can be reloaded using `module::reload()` if the source is modified e.g. +Modules can be reloaded using ``module_::reload()`` if the source is modified e.g. by an external process. This can be useful in scenarios where the application imports a user defined data processing script which needs to be updated after changes by the user. Note that this function does not reload modules recursively. @@ -143,7 +144,7 @@ changes by the user. Note that this function does not reload modules recursively Adding embedded modules ======================= -Embedded binary modules can be added using the `PYBIND11_EMBEDDED_MODULE` macro. +Embedded binary modules can be added using the ``PYBIND11_EMBEDDED_MODULE`` macro. Note that the definition must be placed at global scope. They can be imported like any other module. @@ -153,7 +154,7 @@ like any other module. namespace py = pybind11; PYBIND11_EMBEDDED_MODULE(fast_calc, m) { - // `m` is a `py::module` which is used to bind functions and classes + // `m` is a `py::module_` which is used to bind functions and classes m.def("add", [](int i, int j) { return i + j; }); @@ -162,14 +163,14 @@ like any other module. int main() { py::scoped_interpreter guard{}; - auto fast_calc = py::module::import("fast_calc"); + auto fast_calc = py::module_::import("fast_calc"); auto result = fast_calc.attr("add")(1, 2).cast(); assert(result == 3); } Unlike extension modules where only a single binary module can be created, on the embedded side an unlimited number of modules can be added using multiple -`PYBIND11_EMBEDDED_MODULE` definitions (as long as they have unique names). +``PYBIND11_EMBEDDED_MODULE`` definitions (as long as they have unique names). These modules are added to Python's list of builtins, so they can also be imported in pure Python files loaded by the interpreter. Everything interacts @@ -196,7 +197,7 @@ naturally: int main() { py::scoped_interpreter guard{}; - auto py_module = py::module::import("py_module"); + auto py_module = py::module_::import("py_module"); auto locals = py::dict("fmt"_a="{} + {} = {}", **py_module.attr("__dict__")); assert(locals["a"].cast() == 1); @@ -215,9 +216,9 @@ naturally: Interpreter lifetime ==================== -The Python interpreter shuts down when `scoped_interpreter` is destroyed. After +The Python interpreter shuts down when ``scoped_interpreter`` is destroyed. After this, creating a new instance will restart the interpreter. Alternatively, the -`initialize_interpreter` / `finalize_interpreter` pair of functions can be used +``initialize_interpreter`` / ``finalize_interpreter`` pair of functions can be used to directly set the state at any time. Modules created with pybind11 can be safely re-initialized after the interpreter @@ -229,8 +230,8 @@ global data. All the details can be found in the CPython documentation. .. warning:: - Creating two concurrent `scoped_interpreter` guards is a fatal error. So is - calling `initialize_interpreter` for a second time after the interpreter + Creating two concurrent ``scoped_interpreter`` guards is a fatal error. So is + calling ``initialize_interpreter`` for a second time after the interpreter has already been initialized. Do not use the raw CPython API functions ``Py_Initialize`` and @@ -241,7 +242,7 @@ global data. All the details can be found in the CPython documentation. Sub-interpreter support ======================= -Creating multiple copies of `scoped_interpreter` is not possible because it +Creating multiple copies of ``scoped_interpreter`` is not possible because it represents the main Python interpreter. Sub-interpreters are something different and they do permit the existence of multiple interpreters. This is an advanced feature of the CPython API and should be handled with care. pybind11 does not @@ -257,5 +258,5 @@ We'll just mention a couple of caveats the sub-interpreters support in pybind11: 2. Managing multiple threads, multiple interpreters and the GIL can be challenging and there are several caveats here, even within the pure CPython API (please refer to the Python docs for details). As for - pybind11, keep in mind that `gil_scoped_release` and `gil_scoped_acquire` + pybind11, keep in mind that ``gil_scoped_release`` and ``gil_scoped_acquire`` do not take sub-interpreters into account. diff --git a/pybind11/docs/advanced/exceptions.rst b/pybind11/docs/advanced/exceptions.rst index a96f8e8f4..7cd8447b9 100644 --- a/pybind11/docs/advanced/exceptions.rst +++ b/pybind11/docs/advanced/exceptions.rst @@ -43,18 +43,28 @@ at its exception handler. | | of bounds access in ``__getitem__``, | | | ``__setitem__``, etc.) | +--------------------------------------+--------------------------------------+ -| :class:`pybind11::value_error` | ``ValueError`` (used to indicate | -| | wrong value passed in | -| | ``container.remove(...)``) | -+--------------------------------------+--------------------------------------+ | :class:`pybind11::key_error` | ``KeyError`` (used to indicate out | | | of bounds access in ``__getitem__``, | | | ``__setitem__`` in dict-like | | | objects, etc.) | +--------------------------------------+--------------------------------------+ +| :class:`pybind11::value_error` | ``ValueError`` (used to indicate | +| | wrong value passed in | +| | ``container.remove(...)``) | ++--------------------------------------+--------------------------------------+ +| :class:`pybind11::type_error` | ``TypeError`` | ++--------------------------------------+--------------------------------------+ +| :class:`pybind11::buffer_error` | ``BufferError`` | ++--------------------------------------+--------------------------------------+ +| :class:`pybind11::import_error` | ``ImportError`` | ++--------------------------------------+--------------------------------------+ +| :class:`pybind11::attribute_error` | ``AttributeError`` | ++--------------------------------------+--------------------------------------+ +| Any other exception | ``RuntimeError`` | ++--------------------------------------+--------------------------------------+ Exception translation is not bidirectional. That is, *catching* the C++ -exceptions defined above above will not trap exceptions that originate from +exceptions defined above will not trap exceptions that originate from Python. For that, catch :class:`pybind11::error_already_set`. See :ref:`below ` for further details. @@ -67,9 +77,10 @@ Registering custom translators If the default exception conversion policy described above is insufficient, pybind11 also provides support for registering custom exception translators. -To register a simple exception conversion that translates a C++ exception into -a new Python exception using the C++ exception's ``what()`` method, a helper -function is available: +Similar to pybind11 classes, exception translators can be local to the module +they are defined in or global to the entire python session. To register a simple +exception conversion that translates a C++ exception into a new Python exception +using the C++ exception's ``what()`` method, a helper function is available: .. code-block:: cpp @@ -79,29 +90,39 @@ This call creates a Python exception class with the name ``PyExp`` in the given module and automatically converts any encountered exceptions of type ``CppExp`` into Python exceptions of type ``PyExp``. +A matching function is available for registering a local exception translator: + +.. code-block:: cpp + + py::register_local_exception(module, "PyExp"); + + It is possible to specify base class for the exception using the third -parameter, a `handle`: +parameter, a ``handle``: .. code-block:: cpp py::register_exception(module, "PyExp", PyExc_RuntimeError); + py::register_local_exception(module, "PyExp", PyExc_RuntimeError); -Then `PyExp` can be caught both as `PyExp` and `RuntimeError`. +Then ``PyExp`` can be caught both as ``PyExp`` and ``RuntimeError``. The class objects of the built-in Python exceptions are listed in the Python documentation on `Standard Exceptions `_. -The default base class is `PyExc_Exception`. +The default base class is ``PyExc_Exception``. -When more advanced exception translation is needed, the function -``py::register_exception_translator(translator)`` can be used to register +When more advanced exception translation is needed, the functions +``py::register_exception_translator(translator)`` and +``py::register_local_exception_translator(translator)`` can be used to register functions that can translate arbitrary exception types (and which may include -additional logic to do so). The function takes a stateless callable (e.g. a +additional logic to do so). The functions takes a stateless callable (e.g. a function pointer or a lambda function without captured variables) with the call signature ``void(std::exception_ptr)``. When a C++ exception is thrown, the registered exception translators are tried in reverse order of registration (i.e. the last registered translator gets the -first shot at handling the exception). +first shot at handling the exception). All local translators will be tried +before a global translator is tried. Inside the translator, ``std::rethrow_exception`` should be used within a try block to re-throw the exception. One or more catch clauses to catch @@ -156,6 +177,57 @@ section. may be explicitly (re-)thrown to delegate it to the other, previously-declared existing exception translators. + Note that ``libc++`` and ``libstdc++`` `behave differently `_ + with ``-fvisibility=hidden``. Therefore exceptions that are used across ABI boundaries need to be explicitly exported, as exercised in ``tests/test_exceptions.h``. + See also: "Problems with C++ exceptions" under `GCC Wiki `_. + + +Local vs Global Exception Translators +===================================== + +When a global exception translator is registered, it will be applied across all +modules in the reverse order of registration. This can create behavior where the +order of module import influences how exceptions are translated. + +If module1 has the following translator: + +.. code-block:: cpp + + py::register_exception_translator([](std::exception_ptr p) { + try { + if (p) std::rethrow_exception(p); + } catch (const std::invalid_argument &e) { + PyErr_SetString("module1 handled this") + } + } + +and module2 has the following similar translator: + +.. code-block:: cpp + + py::register_exception_translator([](std::exception_ptr p) { + try { + if (p) std::rethrow_exception(p); + } catch (const std::invalid_argument &e) { + PyErr_SetString("module2 handled this") + } + } + +then which translator handles the invalid_argument will be determined by the +order that module1 and module2 are imported. Since exception translators are +applied in the reverse order of registration, which ever module was imported +last will "win" and that translator will be applied. + +If there are multiple pybind11 modules that share exception types (either +standard built-in or custom) loaded into a single python instance and +consistent error handling behavior is needed, then local translators should be +used. + +Changing the previous example to use ``register_local_exception_translator`` +would mean that when invalid_argument is thrown in the module2 code, the +module2 translator will always handle it, while in module1, the module1 +translator will do the same. + .. _handling_python_exceptions_cpp: Handling exceptions from Python in C++ @@ -182,13 +254,13 @@ For example: try { // open("missing.txt", "r") - auto file = py::module::import("io").attr("open")("missing.txt", "r"); + auto file = py::module_::import("io").attr("open")("missing.txt", "r"); auto text = file.attr("read")(); file.attr("close")(); } catch (py::error_already_set &e) { if (e.matches(PyExc_FileNotFoundError)) { py::print("missing.txt not found"); - } else if (e.match(PyExc_PermissionError)) { + } else if (e.matches(PyExc_PermissionError)) { py::print("missing.txt found but not accessible"); } else { throw; @@ -253,6 +325,34 @@ Alternately, to ignore the error, call `PyErr_Clear Any Python error must be thrown or cleared, or Python/pybind11 will be left in an invalid state. +Chaining exceptions ('raise from') +================================== + +In Python 3.3 a mechanism for indicating that exceptions were caused by other +exceptions was introduced: + +.. code-block:: py + + try: + print(1 / 0) + except Exception as exc: + raise RuntimeError("could not divide by zero") from exc + +To do a similar thing in pybind11, you can use the ``py::raise_from`` function. It +sets the current python error indicator, so to continue propagating the exception +you should ``throw py::error_already_set()`` (Python 3 only). + +.. code-block:: cpp + + try { + py::eval("print(1 / 0")); + } catch (py::error_already_set &e) { + py::raise_from(e, PyExc_RuntimeError, "could not divide by zero"); + throw py::error_already_set(); + } + +.. versionadded:: 2.8 + .. _unraisable_exceptions: Handling unraisable exceptions diff --git a/pybind11/docs/advanced/functions.rst b/pybind11/docs/advanced/functions.rst index c895517c5..bf5b5fa00 100644 --- a/pybind11/docs/advanced/functions.rst +++ b/pybind11/docs/advanced/functions.rst @@ -17,7 +17,7 @@ bindings for functions that return a non-trivial type. Just by looking at the type information, it is not clear whether Python should take charge of the returned value and eventually free its resources, or if this is handled on the C++ side. For this reason, pybind11 provides a several *return value policy* -annotations that can be passed to the :func:`module::def` and +annotations that can be passed to the :func:`module_::def` and :func:`class_::def` functions. The default policy is :enum:`return_value_policy::automatic`. @@ -50,7 +50,7 @@ implied transfer of ownership, i.e.: .. code-block:: cpp - m.def("get_data", &get_data, return_value_policy::reference); + m.def("get_data", &get_data, py::return_value_policy::reference); On the other hand, this is not the right policy for many other situations, where ignoring ownership could lead to resource leaks. @@ -90,17 +90,18 @@ The following table provides an overview of available policies: | | return value is referenced by Python. This is the default policy for | | | property getters created via ``def_property``, ``def_readwrite``, etc. | +--------------------------------------------------+----------------------------------------------------------------------------+ -| :enum:`return_value_policy::automatic` | **Default policy.** This policy falls back to the policy | +| :enum:`return_value_policy::automatic` | This policy falls back to the policy | | | :enum:`return_value_policy::take_ownership` when the return value is a | | | pointer. Otherwise, it uses :enum:`return_value_policy::move` or | | | :enum:`return_value_policy::copy` for rvalue and lvalue references, | | | respectively. See above for a description of what all of these different | -| | policies do. | +| | policies do. This is the default policy for ``py::class_``-wrapped types. | +--------------------------------------------------+----------------------------------------------------------------------------+ | :enum:`return_value_policy::automatic_reference` | As above, but use policy :enum:`return_value_policy::reference` when the | | | return value is a pointer. This is the default conversion policy for | | | function arguments when calling Python functions manually from C++ code | -| | (i.e. via handle::operator()). You probably won't need to use this. | +| | (i.e. via ``handle::operator()``) and the casters in ``pybind11/stl.h``. | +| | You probably won't need to use this explicitly. | +--------------------------------------------------+----------------------------------------------------------------------------+ Return value policies can also be applied to properties: @@ -119,7 +120,7 @@ targeted arguments can be passed through the :class:`cpp_function` constructor: .. code-block:: cpp class_(m, "MyClass") - .def_property("data" + .def_property("data", py::cpp_function(&MyClass::getData, py::return_value_policy::copy), py::cpp_function(&MyClass::setData) ); @@ -182,6 +183,9 @@ relies on the ability to create a *weak reference* to the nurse object. When the nurse object is not a pybind11-registered type and does not support weak references, an exception will be thrown. +If you use an incorrect argument index, you will get a ``RuntimeError`` saying +``Could not activate keep_alive!``. You should review the indices you're using. + Consider the following example: here, the binding code for a list append operation ties the lifetime of the newly added element to the underlying container: @@ -228,7 +232,7 @@ is equivalent to the following pseudocode: }); The only requirement is that ``T`` is default-constructible, but otherwise any -scope guard will work. This is very useful in combination with `gil_scoped_release`. +scope guard will work. This is very useful in combination with ``gil_scoped_release``. See :ref:`gil`. Multiple guards can also be specified as ``py::call_guard``. The @@ -251,7 +255,7 @@ For instance, the following statement iterates over a Python ``dict``: .. code-block:: cpp - void print_dict(py::dict dict) { + void print_dict(const py::dict& dict) { /* Easily interact with Python types */ for (auto item : dict) std::cout << "key=" << std::string(py::str(item.first)) << ", " @@ -268,7 +272,7 @@ And used in Python as usual: .. code-block:: pycon - >>> print_dict({'foo': 123, 'bar': 'hello'}) + >>> print_dict({"foo": 123, "bar": "hello"}) key=foo, value=123 key=bar, value=hello @@ -289,7 +293,7 @@ Such functions can also be created using pybind11: .. code-block:: cpp - void generic(py::args args, py::kwargs kwargs) { + void generic(py::args args, const py::kwargs& kwargs) { /// .. do something with args if (kwargs) /// .. do something with kwargs @@ -302,8 +306,9 @@ The class ``py::args`` derives from ``py::tuple`` and ``py::kwargs`` derives from ``py::dict``. You may also use just one or the other, and may combine these with other -arguments as long as the ``py::args`` and ``py::kwargs`` arguments are the last -arguments accepted by the function. +arguments. Note, however, that ``py::kwargs`` must always be the last argument +of the function, and ``py::args`` implies that any further arguments are +keyword-only (see :ref:`keyword_only_arguments`). Please refer to the other examples for details on how to iterate over these, and on how to cast their entries into C++ objects. A demonstration is also @@ -362,6 +367,8 @@ like so: py::class_("MyClass") .def("myFunction", py::arg("arg") = static_cast(nullptr)); +.. _keyword_only_arguments: + Keyword-only arguments ====================== @@ -373,10 +380,11 @@ argument in a function definition: def f(a, *, b): # a can be positional or via keyword; b must be via keyword pass + f(a=1, b=2) # good f(b=2, a=1) # good - f(1, b=2) # good - f(1, 2) # TypeError: f() takes 1 positional argument but 2 were given + f(1, b=2) # good + f(1, 2) # TypeError: f() takes 1 positional argument but 2 were given Pybind11 provides a ``py::kw_only`` object that allows you to implement the same behaviour by specifying the object between positional and keyword-only @@ -392,6 +400,15 @@ feature does *not* require Python 3 to work. .. versionadded:: 2.6 +As of pybind11 2.9, a ``py::args`` argument implies that any following arguments +are keyword-only, as if ``py::kw_only()`` had been specified in the same +relative location of the argument list as the ``py::args`` argument. The +``py::kw_only()`` may be included to be explicit about this, but is not +required. (Prior to 2.9 ``py::args`` may only occur at the end of the argument +list, or immediately before a ``py::kwargs`` argument at the end). + +.. versionadded:: 2.9 + Positional-only arguments ========================= @@ -524,6 +541,8 @@ The default behaviour when the tag is unspecified is to allow ``None``. not allow ``None`` as argument. To pass optional argument of these copied types consider using ``std::optional`` +.. _overload_resolution: + Overload resolution order ========================= @@ -540,11 +559,13 @@ an explicit ``py::arg().noconvert()`` attribute in the function definition). If the second pass also fails a ``TypeError`` is raised. Within each pass, overloads are tried in the order they were registered with -pybind11. +pybind11. If the ``py::prepend()`` tag is added to the definition, a function +can be placed at the beginning of the overload sequence instead, allowing user +overloads to proceed built in functions. What this means in practice is that pybind11 will prefer any overload that does -not require conversion of arguments to an overload that does, but otherwise prefers -earlier-defined overloads to later-defined ones. +not require conversion of arguments to an overload that does, but otherwise +prefers earlier-defined overloads to later-defined ones. .. note:: @@ -553,3 +574,42 @@ earlier-defined overloads to later-defined ones. requiring one conversion over one requiring three, but only prioritizes overloads requiring no conversion at all to overloads that require conversion of at least one argument. + +.. versionadded:: 2.6 + + The ``py::prepend()`` tag. + +Binding functions with template parameters +========================================== + +You can bind functions that have template parameters. Here's a function: + +.. code-block:: cpp + + template + void set(T t); + +C++ templates cannot be instantiated at runtime, so you cannot bind the +non-instantiated function: + +.. code-block:: cpp + + // BROKEN (this will not compile) + m.def("set", &set); + +You must bind each instantiated function template separately. You may bind +each instantiation with the same name, which will be treated the same as +an overloaded function: + +.. code-block:: cpp + + m.def("set", &set); + m.def("set", &set); + +Sometimes it's more clear to bind them with separate names, which is also +an option: + +.. code-block:: cpp + + m.def("setInt", &set); + m.def("setString", &set); diff --git a/pybind11/docs/advanced/misc.rst b/pybind11/docs/advanced/misc.rst index a5899c67a..edab15fcb 100644 --- a/pybind11/docs/advanced/misc.rst +++ b/pybind11/docs/advanced/misc.rst @@ -84,7 +84,7 @@ could be realized as follows (important changes highlighted): }); } -The ``call_go`` wrapper can also be simplified using the `call_guard` policy +The ``call_go`` wrapper can also be simplified using the ``call_guard`` policy (see :ref:`call_policies`) which yields the same result: .. code-block:: cpp @@ -132,7 +132,7 @@ However, it can be acquired as follows: .. code-block:: cpp - py::object pet = (py::object) py::module::import("basic").attr("Pet"); + py::object pet = (py::object) py::module_::import("basic").attr("Pet"); py::class_(m, "Dog", pet) .def(py::init()) @@ -146,7 +146,7 @@ has been executed: .. code-block:: cpp - py::module::import("basic"); + py::module_::import("basic"); py::class_(m, "Dog") .def(py::init()) @@ -223,7 +223,7 @@ avoids this issue involves weak reference with a cleanup callback: .. code-block:: cpp - // Register a callback function that is invoked when the BaseClass object is colelcted + // Register a callback function that is invoked when the BaseClass object is collected py::cpp_function cleanup_callback( [](py::handle weakref) { // perform cleanup here -- this function is called with the GIL held @@ -237,13 +237,13 @@ avoids this issue involves weak reference with a cleanup callback: .. note:: - PyPy (at least version 5.9) does not garbage collect objects when the - interpreter exits. An alternative approach (which also works on CPython) is to use - the :py:mod:`atexit` module [#f7]_, for example: + PyPy does not garbage collect objects when the interpreter exits. An alternative + approach (which also works on CPython) is to use the :py:mod:`atexit` module [#f7]_, + for example: .. code-block:: cpp - auto atexit = py::module::import("atexit"); + auto atexit = py::module_::import("atexit"); atexit.attr("register")(py::cpp_function([]() { // perform cleanup here -- this function is called with the GIL held })); @@ -284,7 +284,7 @@ work, it is important that all lines are indented consistently, i.e.: )mydelimiter"); By default, pybind11 automatically generates and prepends a signature to the docstring of a function -registered with ``module::def()`` and ``class_::def()``. Sometimes this +registered with ``module_::def()`` and ``class_::def()``. Sometimes this behavior is not desirable, because you want to provide your own signature or remove the docstring completely to exclude the function from the Sphinx documentation. The class ``options`` allows you to selectively suppress auto-generated signatures: diff --git a/pybind11/docs/advanced/pycpp/numpy.rst b/pybind11/docs/advanced/pycpp/numpy.rst index e50d24a99..30daeefff 100644 --- a/pybind11/docs/advanced/pycpp/numpy.rst +++ b/pybind11/docs/advanced/pycpp/numpy.rst @@ -57,11 +57,11 @@ specification. struct buffer_info { void *ptr; - ssize_t itemsize; + py::ssize_t itemsize; std::string format; - ssize_t ndim; - std::vector shape; - std::vector strides; + py::ssize_t ndim; + std::vector shape; + std::vector strides; }; To create a C++ function that can take a Python buffer object as an argument, @@ -150,8 +150,10 @@ NumPy array containing double precision values. When it is invoked with a different type (e.g. an integer or a list of integers), the binding code will attempt to cast the input into a NumPy array -of the requested type. Note that this feature requires the -:file:`pybind11/numpy.h` header to be included. +of the requested type. This feature requires the :file:`pybind11/numpy.h` +header to be included. Note that :file:`pybind11/numpy.h` does not depend on +the NumPy headers, and thus can be used without declaring a build-time +dependency on NumPy; NumPy>=1.7.0 is a runtime dependency. Data in NumPy arrays is not guaranteed to packed in a dense manner; furthermore, entries can be separated by arbitrary column and row strides. @@ -169,6 +171,31 @@ template parameter, and it ensures that non-conforming arguments are converted into an array satisfying the specified requirements instead of trying the next function overload. +There are several methods on arrays; the methods listed below under references +work, as well as the following functions based on the NumPy API: + +- ``.dtype()`` returns the type of the contained values. + +- ``.strides()`` returns a pointer to the strides of the array (optionally pass + an integer axis to get a number). + +- ``.flags()`` returns the flag settings. ``.writable()`` and ``.owndata()`` + are directly available. + +- ``.offset_at()`` returns the offset (optionally pass indices). + +- ``.squeeze()`` returns a view with length-1 axes removed. + +- ``.view(dtype)`` returns a view of the array with a different dtype. + +- ``.reshape({i, j, ...})`` returns a view of the array with a different shape. + ``.resize({...})`` is also available. + +- ``.index_at(i, j, ...)`` gets the count from the beginning to a given index. + + +There are also several methods for getting references (described below). + Structured types ================ @@ -231,8 +258,8 @@ by the compiler. The result is returned as a NumPy array of type .. code-block:: pycon - >>> x = np.array([[1, 3],[5, 7]]) - >>> y = np.array([[2, 4],[6, 8]]) + >>> x = np.array([[1, 3], [5, 7]]) + >>> y = np.array([[2, 4], [6, 8]]) >>> z = 3 >>> result = vectorized_func(x, y, z) @@ -309,17 +336,17 @@ where ``N`` gives the required dimensionality of the array: m.def("sum_3d", [](py::array_t x) { auto r = x.unchecked<3>(); // x must have ndim = 3; can be non-writeable double sum = 0; - for (ssize_t i = 0; i < r.shape(0); i++) - for (ssize_t j = 0; j < r.shape(1); j++) - for (ssize_t k = 0; k < r.shape(2); k++) + for (py::ssize_t i = 0; i < r.shape(0); i++) + for (py::ssize_t j = 0; j < r.shape(1); j++) + for (py::ssize_t k = 0; k < r.shape(2); k++) sum += r(i, j, k); return sum; }); m.def("increment_3d", [](py::array_t x) { auto r = x.mutable_unchecked<3>(); // Will throw if ndim != 3 or flags.writeable is false - for (ssize_t i = 0; i < r.shape(0); i++) - for (ssize_t j = 0; j < r.shape(1); j++) - for (ssize_t k = 0; k < r.shape(2); k++) + for (py::ssize_t i = 0; i < r.shape(0); i++) + for (py::ssize_t j = 0; j < r.shape(1); j++) + for (py::ssize_t k = 0; k < r.shape(2); k++) r(i, j, k) += 1.0; }, py::arg().noconvert()); @@ -343,21 +370,21 @@ The returned proxy object supports some of the same methods as ``py::array`` so that it can be used as a drop-in replacement for some existing, index-checked uses of ``py::array``: -- ``r.ndim()`` returns the number of dimensions +- ``.ndim()`` returns the number of dimensions -- ``r.data(1, 2, ...)`` and ``r.mutable_data(1, 2, ...)``` returns a pointer to +- ``.data(1, 2, ...)`` and ``r.mutable_data(1, 2, ...)``` returns a pointer to the ``const T`` or ``T`` data, respectively, at the given indices. The latter is only available to proxies obtained via ``a.mutable_unchecked()``. -- ``itemsize()`` returns the size of an item in bytes, i.e. ``sizeof(T)``. +- ``.itemsize()`` returns the size of an item in bytes, i.e. ``sizeof(T)``. -- ``ndim()`` returns the number of dimensions. +- ``.ndim()`` returns the number of dimensions. -- ``shape(n)`` returns the size of dimension ``n`` +- ``.shape(n)`` returns the size of dimension ``n`` -- ``size()`` returns the total number of elements (i.e. the product of the shapes). +- ``.size()`` returns the total number of elements (i.e. the product of the shapes). -- ``nbytes()`` returns the number of bytes used by the referenced elements +- ``.nbytes()`` returns the number of bytes used by the referenced elements (i.e. ``itemsize()`` times ``size()``). .. seealso:: @@ -376,7 +403,7 @@ In Python 2, the syntactic sugar ``...`` is not available, but the singleton .. code-block:: python - a = # a NumPy array + a = ... # a NumPy array b = a[0, ..., 0] The function ``py::ellipsis()`` function can be used to perform the same @@ -388,7 +415,7 @@ operation on the C++ side: py::array b = a[py::make_tuple(0, py::ellipsis(), 0)]; .. versionchanged:: 2.6 - ``py::ellipsis()`` is now also avaliable in Python 2. + ``py::ellipsis()`` is now also available in Python 2. Memory view =========== diff --git a/pybind11/docs/advanced/pycpp/object.rst b/pybind11/docs/advanced/pycpp/object.rst index 70e493acd..93e1a94d8 100644 --- a/pybind11/docs/advanced/pycpp/object.rst +++ b/pybind11/docs/advanced/pycpp/object.rst @@ -20,6 +20,40 @@ Available types include :class:`handle`, :class:`object`, :class:`bool_`, Be sure to review the :ref:`pytypes_gotchas` before using this heavily in your C++ API. +.. _instantiating_compound_types: + +Instantiating compound Python types from C++ +============================================ + +Dictionaries can be initialized in the :class:`dict` constructor: + +.. code-block:: cpp + + using namespace pybind11::literals; // to bring in the `_a` literal + py::dict d("spam"_a=py::none(), "eggs"_a=42); + +A tuple of python objects can be instantiated using :func:`py::make_tuple`: + +.. code-block:: cpp + + py::tuple tup = py::make_tuple(42, py::none(), "spam"); + +Each element is converted to a supported Python type. + +A `simple namespace`_ can be instantiated using + +.. code-block:: cpp + + using namespace pybind11::literals; // to bring in the `_a` literal + py::object SimpleNamespace = py::module_::import("types").attr("SimpleNamespace"); + py::object ns = SimpleNamespace("spam"_a=py::none(), "eggs"_a=42); + +Attributes on a namespace can be modified with the :func:`py::delattr`, +:func:`py::getattr`, and :func:`py::setattr` functions. Simple namespaces can +be useful as lightweight stand-ins for class instances. + +.. _simple namespace: https://docs.python.org/3/library/types.html#types.SimpleNamespace + .. _casting_back_and_forth: Casting back and forth @@ -30,7 +64,7 @@ types to Python, which can be done using :func:`py::cast`: .. code-block:: cpp - MyClass *cls = ..; + MyClass *cls = ...; py::object obj = py::cast(cls); The reverse direction uses the following syntax: @@ -56,12 +90,12 @@ This example obtains a reference to the Python ``Decimal`` class. .. code-block:: cpp // Equivalent to "from decimal import Decimal" - py::object Decimal = py::module::import("decimal").attr("Decimal"); + py::object Decimal = py::module_::import("decimal").attr("Decimal"); .. code-block:: cpp // Try to import scipy - py::object scipy = py::module::import("scipy"); + py::object scipy = py::module_::import("scipy"); return scipy.attr("__version__"); @@ -81,7 +115,7 @@ via ``operator()``. .. code-block:: cpp // Use Python to make our directories - py::object os = py::module::import("os"); + py::object os = py::module_::import("os"); py::object makedirs = os.attr("makedirs"); makedirs("/tmp/path/to/somewhere"); @@ -132,6 +166,7 @@ Keyword arguments are also supported. In Python, there is the usual call syntax: def f(number, say, to): ... # function code + f(1234, say="hello", to=some_instance) # keyword call in Python In C++, the same call can be made using: @@ -196,9 +231,9 @@ C++ functions that require a specific subtype rather than a generic :class:`obje #include using namespace pybind11::literals; - py::module os = py::module::import("os"); - py::module path = py::module::import("os.path"); // like 'import os.path as path' - py::module np = py::module::import("numpy"); // like 'import numpy as np' + py::module_ os = py::module_::import("os"); + py::module_ path = py::module_::import("os.path"); // like 'import os.path as path' + py::module_ np = py::module_::import("numpy"); // like 'import numpy as np' py::str curdir_abs = path.attr("abspath")(path.attr("curdir")); py::print(py::str("Current directory: ") + curdir_abs); diff --git a/pybind11/docs/advanced/pycpp/utilities.rst b/pybind11/docs/advanced/pycpp/utilities.rst index 369e7c94d..af0f9cb2b 100644 --- a/pybind11/docs/advanced/pycpp/utilities.rst +++ b/pybind11/docs/advanced/pycpp/utilities.rst @@ -28,7 +28,7 @@ Capturing standard output from ostream Often, a library will use the streams ``std::cout`` and ``std::cerr`` to print, but this does not play well with Python's standard ``sys.stdout`` and ``sys.stderr`` -redirection. Replacing a library's printing with `py::print ` may not +redirection. Replacing a library's printing with ``py::print `` may not be feasible. This can be fixed using a guard around the library function that redirects output to the corresponding Python streams: @@ -42,20 +42,31 @@ redirects output to the corresponding Python streams: m.def("noisy_func", []() { py::scoped_ostream_redirect stream( std::cout, // std::ostream& - py::module::import("sys").attr("stdout") // Python output + py::module_::import("sys").attr("stdout") // Python output ); call_noisy_func(); }); +.. warning:: + + The implementation in ``pybind11/iostream.h`` is NOT thread safe. Multiple + threads writing to a redirected ostream concurrently cause data races + and potentially buffer overflows. Therefore it is currently a requirement + that all (possibly) concurrent redirected ostream writes are protected by + a mutex. #HelpAppreciated: Work on iostream.h thread safety. For more + background see the discussions under + `PR #2982 `_ and + `PR #2995 `_. + This method respects flushes on the output streams and will flush if needed when the scoped guard is destroyed. This allows the output to be redirected in real time, such as to a Jupyter notebook. The two arguments, the C++ stream and the Python output, are optional, and default to standard output if not given. An -extra type, `py::scoped_estream_redirect `, is identical +extra type, ``py::scoped_estream_redirect ``, is identical except for defaulting to ``std::cerr`` and ``sys.stderr``; this can be useful with -`py::call_guard`, which allows multiple items, but uses the default constructor: +``py::call_guard``, which allows multiple items, but uses the default constructor: -.. code-block:: py +.. code-block:: cpp // Alternative: Call single function using call guard m.def("noisy_func", &call_noisy_function, @@ -63,7 +74,7 @@ except for defaulting to ``std::cerr`` and ``sys.stderr``; this can be useful wi py::scoped_estream_redirect>()); The redirection can also be done in Python with the addition of a context -manager, using the `py::add_ostream_redirect() ` function: +manager, using the ``py::add_ostream_redirect() `` function: .. code-block:: cpp @@ -92,7 +103,7 @@ arguments to disable one of the streams if needed. Evaluating Python expressions from strings and files ==================================================== -pybind11 provides the `eval`, `exec` and `eval_file` functions to evaluate +pybind11 provides the ``eval``, ``exec`` and ``eval_file`` functions to evaluate Python expressions and statements. The following example illustrates how they can be used. @@ -104,7 +115,7 @@ can be used. ... // Evaluate in scope of main module - py::object scope = py::module::import("__main__").attr("__dict__"); + py::object scope = py::module_::import("__main__").attr("__dict__"); // Evaluate an isolated expression int result = py::eval("my_variable + 10", scope).cast(); diff --git a/pybind11/docs/advanced/smart_ptrs.rst b/pybind11/docs/advanced/smart_ptrs.rst index da57748ca..5a2220109 100644 --- a/pybind11/docs/advanced/smart_ptrs.rst +++ b/pybind11/docs/advanced/smart_ptrs.rst @@ -77,6 +77,7 @@ segmentation fault). .. code-block:: python from example import Parent + print(Parent().get_child()) The problem is that ``Parent::get_child()`` returns a pointer to an instance of diff --git a/pybind11/docs/basics.rst b/pybind11/docs/basics.rst index 71440c9c6..e0479b298 100644 --- a/pybind11/docs/basics.rst +++ b/pybind11/docs/basics.rst @@ -39,7 +39,7 @@ on various C++11 language features that break older versions of Visual Studio. To use the C++17 in Visual Studio 2017 (MSVC 14.1), pybind11 requires the flag ``/permissive-`` to be passed to the compiler `to enforce standard conformance`_. When - building with Visual Studio 2019, this is not strictly necessary, but still adviced. + building with Visual Studio 2019, this is not strictly necessary, but still advised. .. _`to enforce standard conformance`: https://docs.microsoft.com/en-us/cpp/build/reference/permissive-standards-conformance?view=vs-2017 @@ -109,7 +109,7 @@ a file named :file:`example.cpp` with the following contents: PYBIND11_MODULE(example, m) { m.doc() = "pybind11 example plugin"; // optional module docstring - m.def("add", &add, "A function which adds two numbers"); + m.def("add", &add, "A function that adds two numbers"); } .. [#f1] In practice, implementation and binding code will generally be located @@ -118,8 +118,8 @@ a file named :file:`example.cpp` with the following contents: The :func:`PYBIND11_MODULE` macro creates a function that will be called when an ``import`` statement is issued from within Python. The module name (``example``) is given as the first macro argument (it should not be in quotes). The second -argument (``m``) defines a variable of type :class:`py::module ` which -is the main interface for creating bindings. The method :func:`module::def` +argument (``m``) defines a variable of type :class:`py::module_ ` which +is the main interface for creating bindings. The method :func:`module_::def` generates binding code that exposes the ``add()`` function to Python. .. note:: @@ -136,7 +136,14 @@ On Linux, the above example can be compiled using the following command: .. code-block:: bash - $ c++ -O3 -Wall -shared -std=c++11 -fPIC `python3 -m pybind11 --includes` example.cpp -o example`python3-config --extension-suffix` + $ c++ -O3 -Wall -shared -std=c++11 -fPIC $(python3 -m pybind11 --includes) example.cpp -o example$(python3-config --extension-suffix) + +.. note:: + + If you used :ref:`include_as_a_submodule` to get the pybind11 source, then + use ``$(python3-config --includes) -Iextern/pybind11/include`` instead of + ``$(python3 -m pybind11 --includes)`` in the above compilation, as + explained in :ref:`building_manually`. For more details on the required compiler flags on Linux and macOS, see :ref:`building_manually`. For complete cross-platform compilation instructions, @@ -181,7 +188,7 @@ names of the arguments ("i" and "j" in this case). py::arg("i"), py::arg("j")); :class:`arg` is one of several special tag classes which can be used to pass -metadata into :func:`module::def`. With this modified binding code, we can now +metadata into :func:`module_::def`. With this modified binding code, we can now call the function using keyword arguments, which is a more readable alternative particularly for functions taking many parameters: diff --git a/pybind11/docs/benchmark.py b/pybind11/docs/benchmark.py index 023477212..f19079367 100644 --- a/pybind11/docs/benchmark.py +++ b/pybind11/docs/benchmark.py @@ -1,8 +1,7 @@ # -*- coding: utf-8 -*- -import random -import os -import time import datetime as dt +import os +import random nfns = 4 # Functions per class nargs = 4 # Arguments per function @@ -14,7 +13,7 @@ def generate_dummy_code_pybind11(nclasses=10): for cl in range(nclasses): decl += "class cl%03i;\n" % cl - decl += '\n' + decl += "\n" for cl in range(nclasses): decl += "class cl%03i {\n" % cl @@ -22,18 +21,17 @@ def generate_dummy_code_pybind11(nclasses=10): bindings += ' py::class_(m, "cl%03i")\n' % (cl, cl) for fn in range(nfns): ret = random.randint(0, nclasses - 1) - params = [random.randint(0, nclasses - 1) for i in range(nargs)] + params = [random.randint(0, nclasses - 1) for i in range(nargs)] decl += " cl%03i *fn_%03i(" % (ret, fn) decl += ", ".join("cl%03i *" % p for p in params) decl += ");\n" - bindings += ' .def("fn_%03i", &cl%03i::fn_%03i)\n' % \ - (fn, cl, fn) + bindings += ' .def("fn_%03i", &cl%03i::fn_%03i)\n' % (fn, cl, fn) decl += "};\n\n" - bindings += ' ;\n' + bindings += " ;\n" result = "#include \n\n" result += "namespace py = pybind11;\n\n" - result += decl + '\n' + result += decl + "\n" result += "PYBIND11_MODULE(example, m) {\n" result += bindings result += "}" @@ -46,7 +44,7 @@ def generate_dummy_code_boost(nclasses=10): for cl in range(nclasses): decl += "class cl%03i;\n" % cl - decl += '\n' + decl += "\n" for cl in range(nclasses): decl += "class cl%03i {\n" % cl @@ -54,18 +52,20 @@ def generate_dummy_code_boost(nclasses=10): bindings += ' py::class_("cl%03i")\n' % (cl, cl) for fn in range(nfns): ret = random.randint(0, nclasses - 1) - params = [random.randint(0, nclasses - 1) for i in range(nargs)] + params = [random.randint(0, nclasses - 1) for i in range(nargs)] decl += " cl%03i *fn_%03i(" % (ret, fn) decl += ", ".join("cl%03i *" % p for p in params) decl += ");\n" - bindings += ' .def("fn_%03i", &cl%03i::fn_%03i, py::return_value_policy())\n' % \ - (fn, cl, fn) + bindings += ( + ' .def("fn_%03i", &cl%03i::fn_%03i, py::return_value_policy())\n' + % (fn, cl, fn) + ) decl += "};\n\n" - bindings += ' ;\n' + bindings += " ;\n" result = "#include \n\n" result += "namespace py = boost::python;\n\n" - result += decl + '\n' + result += decl + "\n" result += "BOOST_PYTHON_MODULE(example) {\n" result += bindings result += "}" @@ -73,17 +73,19 @@ def generate_dummy_code_boost(nclasses=10): for codegen in [generate_dummy_code_pybind11, generate_dummy_code_boost]: - print ("{") + print("{") for i in range(0, 10): nclasses = 2 ** i with open("test.cpp", "w") as f: f.write(codegen(nclasses)) n1 = dt.datetime.now() - os.system("g++ -Os -shared -rdynamic -undefined dynamic_lookup " + os.system( + "g++ -Os -shared -rdynamic -undefined dynamic_lookup " "-fvisibility=hidden -std=c++14 test.cpp -I include " - "-I /System/Library/Frameworks/Python.framework/Headers -o test.so") + "-I /System/Library/Frameworks/Python.framework/Headers -o test.so" + ) n2 = dt.datetime.now() elapsed = (n2 - n1).total_seconds() - size = os.stat('test.so').st_size + size = os.stat("test.so").st_size print(" {%i, %f, %i}," % (nclasses * nfns, elapsed, size)) - print ("}") + print("}") diff --git a/pybind11/docs/changelog.rst b/pybind11/docs/changelog.rst index 8f95c1274..16bf3aa3f 100644 --- a/pybind11/docs/changelog.rst +++ b/pybind11/docs/changelog.rst @@ -6,21 +6,697 @@ Changelog Starting with version 1.8.0, pybind11 releases use a `semantic versioning `_ policy. -v2.6.0 (IN PROGRESS) +Version 2.9.1 (Feb 2, 2022) +--------------------------- + +Changes: + +* If possible, attach Python exception with ``py::raise_from`` to ``TypeError`` + when casting from C++ to Python. This will give additional info if Python + exceptions occur in the caster. Adds a test case of trying to convert a set + from C++ to Python when the hash function is not defined in Python. + `#3605 `_ + +* Add a mapping of C++11 nested exceptions to their Python exception + equivalent using ``py::raise_from``. This attaches the nested exceptions in + Python using the ``__cause__`` field. + `#3608 `_ + +* Propagate Python exception traceback using ``raise_from`` if a pybind11 + function runs out of overloads. + `#3671 `_ + +* ``py::multiple_inheritance`` is now only needed when C++ bases are hidden + from pybind11. + `#3650 `_ and + `#3659 `_ + + +Bug fixes: + +* Remove a boolean cast in ``numpy.h`` that causes MSVC C4800 warnings when + compiling against Python 3.10 or newer. + `#3669 `_ + +* Render ``py::bool_`` and ``py::float_`` as ``bool`` and ``float`` + respectively. + `#3622 `_ + +Build system improvements: + +* Fix CMake extension suffix computation on Python 3.10+. + `#3663 `_ + +* Allow ``CMAKE_ARGS`` to override CMake args in pybind11's own ``setup.py``. + `#3577 `_ + +* Remove a few deprecated c-headers. + `#3610 `_ + +* More uniform handling of test targets. + `#3590 `_ + +* Add clang-tidy readability check to catch potentially swapped function args. + `#3611 `_ + + +Version 2.9.0 (Dec 28, 2021) +---------------------------- + +This is the last version to support Python 2.7 and 3.5. + +New Features: + +* Allow ``py::args`` to be followed by other arguments; the remaining arguments + are implicitly keyword-only, as if a ``py::kw_only{}`` annotation had been + used. + `#3402 `_ + +Changes: + +* Make str/bytes/memoryview more interoperable with ``std::string_view``. + `#3521 `_ + +* Replace ``_`` with ``const_name`` in internals, avoid defining ``pybind::_`` + if ``_`` defined as macro (common gettext usage) + `#3423 `_ + + +Bug fixes: + +* Fix a rare warning about extra copy in an Eigen constructor. + `#3486 `_ + +* Fix caching of the C++ overrides. + `#3465 `_ + +* Add missing ``std::forward`` calls to some ``cpp_function`` overloads. + `#3443 `_ + +* Support PyPy 7.3.7 and the PyPy3.8 beta. Test python-3.11 on PRs with the + ``python dev`` label. + `#3419 `_ + +* Replace usage of deprecated ``Eigen::MappedSparseMatrix`` with + ``Eigen::Map>`` for Eigen 3.3+. + `#3499 `_ + +* Tweaks to support Microsoft Visual Studio 2022. + `#3497 `_ + +Build system improvements: + +* Nicer CMake printout and IDE organisation for pybind11's own tests. + `#3479 `_ + +* CMake: report version type as part of the version string to avoid a spurious + space in the package status message. + `#3472 `_ + +* Flags starting with ``-g`` in ``$CFLAGS`` and ``$CPPFLAGS`` are no longer + overridden by ``.Pybind11Extension``. + `#3436 `_ + +* Ensure ThreadPool is closed in ``setup_helpers``. + `#3548 `_ + +* Avoid LTS on ``mips64`` and ``ppc64le`` (reported broken). + `#3557 `_ + + +v2.8.1 (Oct 27, 2021) +--------------------- + +Changes and additions: + +* The simple namespace creation shortcut added in 2.8.0 was deprecated due to + usage of CPython internal API, and will be removed soon. Use + ``py::module_::import("types").attr("SimpleNamespace")``. + `#3374 `_ + +* Add C++ Exception type to throw and catch ``AttributeError``. Useful for + defining custom ``__setattr__`` and ``__getattr__`` methods. + `#3387 `_ + +Fixes: + +* Fixed the potential for dangling references when using properties with + ``std::optional`` types. + `#3376 `_ + +* Modernize usage of ``PyCodeObject`` on Python 3.9+ (moving toward support for + Python 3.11a1) + `#3368 `_ + +* A long-standing bug in ``eigen.h`` was fixed (originally PR #3343). The bug + was unmasked by newly added ``static_assert``'s in the Eigen 3.4.0 release. + `#3352 `_ + +* Support multiple raw inclusion of CMake helper files (Conan.io does this for + multi-config generators). + `#3420 `_ + +* Fix harmless warning on upcoming CMake 3.22. + `#3368 `_ + +* Fix 2.8.0 regression with MSVC 2017 + C++17 mode + Python 3. + `#3407 `_ + +* Fix 2.8.0 regression that caused undefined behavior (typically + segfaults) in ``make_key_iterator``/``make_value_iterator`` if dereferencing + the iterator returned a temporary value instead of a reference. + `#3348 `_ + + +v2.8.0 (Oct 4, 2021) -------------------- +New features: + +* Added ``py::raise_from`` to enable chaining exceptions. + `#3215 `_ + +* Allow exception translators to be optionally registered local to a module + instead of applying globally across all pybind11 modules. Use + ``register_local_exception_translator(ExceptionTranslator&& translator)`` + instead of ``register_exception_translator(ExceptionTranslator&& + translator)`` to keep your exception remapping code local to the module. + `#2650 `_ + +* Add ``make_simple_namespace`` function for instantiating Python + ``SimpleNamespace`` objects. **Deprecated in 2.8.1.** + `#2840 `_ + +* ``pybind11::scoped_interpreter`` and ``initialize_interpreter`` have new + arguments to allow ``sys.argv`` initialization. + `#2341 `_ + +* Allow Python builtins to be used as callbacks in CPython. + `#1413 `_ + +* Added ``view`` to view arrays with a different datatype. + `#987 `_ + +* Implemented ``reshape`` on arrays. + `#984 `_ + +* Enable defining custom ``__new__`` methods on classes by fixing bug + preventing overriding methods if they have non-pybind11 siblings. + `#3265 `_ + +* Add ``make_value_iterator()``, and fix ``make_key_iterator()`` to return + references instead of copies. + `#3293 `_ + +* Improve the classes generated by ``bind_map``: `#3310 `_ + + * Change ``.items`` from an iterator to a dictionary view. + * Add ``.keys`` and ``.values`` (both dictionary views). + * Allow ``__contains__`` to take any object. + +* ``pybind11::custom_type_setup`` was added, for customizing the + ``PyHeapTypeObject`` corresponding to a class, which may be useful for + enabling garbage collection support, among other things. + `#3287 `_ + + +Changes: + +* Set ``__file__`` constant when running ``eval_file`` in an embedded interpreter. + `#3233 `_ + +* Python objects and (C++17) ``std::optional`` now accepted in ``py::slice`` + constructor. + `#1101 `_ + +* The pybind11 proxy types ``str``, ``bytes``, ``bytearray``, ``tuple``, + ``list`` now consistently support passing ``ssize_t`` values for sizes and + indexes. Previously, only ``size_t`` was accepted in several interfaces. + `#3219 `_ + +* Avoid evaluating ``PYBIND11_TLS_REPLACE_VALUE`` arguments more than once. + `#3290 `_ + +Fixes: + +* Bug fix: enum value's ``__int__`` returning non-int when underlying type is + bool or of char type. + `#1334 `_ + +* Fixes bug in setting error state in Capsule's pointer methods. + `#3261 `_ + +* A long-standing memory leak in ``py::cpp_function::initialize`` was fixed. + `#3229 `_ + +* Fixes thread safety for some ``pybind11::type_caster`` which require lifetime + extension, such as for ``std::string_view``. + `#3237 `_ + +* Restore compatibility with gcc 4.8.4 as distributed by ubuntu-trusty, linuxmint-17. + `#3270 `_ + + +Build system improvements: + +* Fix regression in CMake Python package config: improper use of absolute path. + `#3144 `_ + +* Cached Python version information could become stale when CMake was re-run + with a different Python version. The build system now detects this and + updates this information. + `#3299 `_ + +* Specified UTF8-encoding in setup.py calls of open(). + `#3137 `_ + +* Fix a harmless warning from CMake 3.21 with the classic Python discovery. + `#3220 `_ + +* Eigen repo and version can now be specified as cmake options. + `#3324 `_ + + +Backend and tidying up: + +* Reduced thread-local storage required for keeping alive temporary data for + type conversion to one key per ABI version, rather than one key per extension + module. This makes the total thread-local storage required by pybind11 2 + keys per ABI version. + `#3275 `_ + +* Optimize NumPy array construction with additional moves. + `#3183 `_ + +* Conversion to ``std::string`` and ``std::string_view`` now avoids making an + extra copy of the data on Python >= 3.3. + `#3257 `_ + +* Remove const modifier from certain C++ methods on Python collections + (``list``, ``set``, ``dict``) such as (``clear()``, ``append()``, + ``insert()``, etc...) and annotated them with ``py-non-const``. + +* Enable readability ``clang-tidy-const-return`` and remove useless consts. + `#3254 `_ + `#3194 `_ + +* The clang-tidy ``google-explicit-constructor`` option was enabled. + `#3250 `_ + +* Mark a pytype move constructor as noexcept (perf). + `#3236 `_ + +* Enable clang-tidy check to guard against inheritance slicing. + `#3210 `_ + +* Legacy warning suppression pragma were removed from eigen.h. On Unix + platforms, please use -isystem for Eigen include directories, to suppress + compiler warnings originating from Eigen headers. Note that CMake does this + by default. No adjustments are needed for Windows. + `#3198 `_ + +* Format pybind11 with isort consistent ordering of imports + `#3195 `_ + +* The warnings-suppression "pragma clamp" at the top/bottom of pybind11 was + removed, clearing the path to refactoring and IWYU cleanup. + `#3186 `_ + +* Enable most bugprone checks in clang-tidy and fix the found potential bugs + and poor coding styles. + `#3166 `_ + +* Add ``clang-tidy-readability`` rules to make boolean casts explicit improving + code readability. Also enabled other misc and readability clang-tidy checks. + `#3148 `_ + +* Move object in ``.pop()`` for list. + `#3116 `_ + + + + +v2.7.1 (Aug 3, 2021) +--------------------- + +Minor missing functionality added: + +* Allow Python builtins to be used as callbacks in CPython. + `#1413 `_ + +Bug fixes: + +* Fix regression in CMake Python package config: improper use of absolute path. + `#3144 `_ + +* Fix Mingw64 and add to the CI testing matrix. + `#3132 `_ + +* Specified UTF8-encoding in setup.py calls of open(). + `#3137 `_ + +* Add clang-tidy-readability rules to make boolean casts explicit improving + code readability. Also enabled other misc and readability clang-tidy checks. + `#3148 `_ + +* Move object in ``.pop()`` for list. + `#3116 `_ + +Backend and tidying up: + +* Removed and fixed warning suppressions. + `#3127 `_ + `#3129 `_ + `#3135 `_ + `#3141 `_ + `#3142 `_ + `#3150 `_ + `#3152 `_ + `#3160 `_ + `#3161 `_ + + +v2.7.0 (Jul 16, 2021) +--------------------- + +New features: + +* Enable ``py::implicitly_convertible`` for + ``py::class_``-wrapped types. + `#3059 `_ + +* Allow function pointer extraction from overloaded functions. + `#2944 `_ + +* NumPy: added ``.char_()`` to type which gives the NumPy public ``char`` + result, which also distinguishes types by bit length (unlike ``.kind()``). + `#2864 `_ + +* Add ``pybind11::bytearray`` to manipulate ``bytearray`` similar to ``bytes``. + `#2799 `_ + +* ``pybind11/stl/filesystem.h`` registers a type caster that, on C++17/Python + 3.6+, converts ``std::filesystem::path`` to ``pathlib.Path`` and any + ``os.PathLike`` to ``std::filesystem::path``. + `#2730 `_ + +* A ``PYBIND11_VERSION_HEX`` define was added, similar to ``PY_VERSION_HEX``. + `#3120 `_ + + + +Changes: + +* ``py::str`` changed to exclusively hold ``PyUnicodeObject``. Previously + ``py::str`` could also hold ``bytes``, which is probably surprising, was + never documented, and can mask bugs (e.g. accidental use of ``py::str`` + instead of ``py::bytes``). + `#2409 `_ + +* Add a safety guard to ensure that the Python GIL is held when C++ calls back + into Python via ``object_api<>::operator()`` (e.g. ``py::function`` + ``__call__``). (This feature is available for Python 3.6+ only.) + `#2919 `_ + +* Catch a missing ``self`` argument in calls to ``__init__()``. + `#2914 `_ + +* Use ``std::string_view`` if available to avoid a copy when passing an object + to a ``std::ostream``. + `#3042 `_ + +* An important warning about thread safety was added to the ``iostream.h`` + documentation; attempts to make ``py::scoped_ostream_redirect`` thread safe + have been removed, as it was only partially effective. + `#2995 `_ + + +Fixes: + +* Performance: avoid unnecessary strlen calls. + `#3058 `_ + +* Fix auto-generated documentation string when using ``const T`` in + ``pyarray_t``. + `#3020 `_ + +* Unify error messages thrown by ``simple_collector``/``unpacking_collector``. + `#3013 `_ + +* ``pybind11::builtin_exception`` is now explicitly exported, which means the + types included/defined in different modules are identical, and exceptions + raised in different modules can be caught correctly. The documentation was + updated to explain that custom exceptions that are used across module + boundaries need to be explicitly exported as well. + `#2999 `_ + +* Fixed exception when printing UTF-8 to a ``scoped_ostream_redirect``. + `#2982 `_ + +* Pickle support enhancement: ``setstate`` implementation will attempt to + ``setattr`` ``__dict__`` only if the unpickled ``dict`` object is not empty, + to not force use of ``py::dynamic_attr()`` unnecessarily. + `#2972 `_ + +* Allow negative timedelta values to roundtrip. + `#2870 `_ + +* Fix unchecked errors could potentially swallow signals/other exceptions. + `#2863 `_ + +* Add null pointer check with ``std::localtime``. + `#2846 `_ + +* Fix the ``weakref`` constructor from ``py::object`` to create a new + ``weakref`` on conversion. + `#2832 `_ + +* Avoid relying on exceptions in C++17 when getting a ``shared_ptr`` holder + from a ``shared_from_this`` class. + `#2819 `_ + +* Allow the codec's exception to be raised instead of :code:`RuntimeError` when + casting from :code:`py::str` to :code:`std::string`. + `#2903 `_ + + +Build system improvements: + +* In ``setup_helpers.py``, test for platforms that have some multiprocessing + features but lack semaphores, which ``ParallelCompile`` requires. + `#3043 `_ + +* Fix ``pybind11_INCLUDE_DIR`` in case ``CMAKE_INSTALL_INCLUDEDIR`` is + absolute. + `#3005 `_ + +* Fix bug not respecting ``WITH_SOABI`` or ``WITHOUT_SOABI`` to CMake. + `#2938 `_ + +* Fix the default ``Pybind11Extension`` compilation flags with a Mingw64 python. + `#2921 `_ + +* Clang on Windows: do not pass ``/MP`` (ignored flag). + `#2824 `_ + +* ``pybind11.setup_helpers.intree_extensions`` can be used to generate + ``Pybind11Extension`` instances from cpp files placed in the Python package + source tree. + `#2831 `_ + +Backend and tidying up: + +* Enable clang-tidy performance, readability, and modernization checks + throughout the codebase to enforce best coding practices. + `#3046 `_, + `#3049 `_, + `#3051 `_, + `#3052 `_, + `#3080 `_, and + `#3094 `_ + + +* Checks for common misspellings were added to the pre-commit hooks. + `#3076 `_ + +* Changed ``Werror`` to stricter ``Werror-all`` for Intel compiler and fixed + minor issues. + `#2948 `_ + +* Fixed compilation with GCC < 5 when the user defines ``_GLIBCXX_USE_CXX11_ABI``. + `#2956 `_ + +* Added nox support for easier local testing and linting of contributions. + `#3101 `_ and + `#3121 `_ + +* Avoid RTD style issue with docutils 0.17+. + `#3119 `_ + +* Support pipx run, such as ``pipx run pybind11 --include`` for a quick compile. + `#3117 `_ + + + +v2.6.2 (Jan 26, 2021) +--------------------- + +Minor missing functionality added: + +* enum: add missing Enum.value property. + `#2739 `_ + +* Allow thread termination to be avoided during shutdown for CPython 3.7+ via + ``.disarm`` for ``gil_scoped_acquire``/``gil_scoped_release``. + `#2657 `_ + +Fixed or improved behavior in a few special cases: + +* Fix bug where the constructor of ``object`` subclasses would not throw on + being passed a Python object of the wrong type. + `#2701 `_ + +* The ``type_caster`` for integers does not convert Python objects with + ``__int__`` anymore with ``noconvert`` or during the first round of trying + overloads. + `#2698 `_ + +* When casting to a C++ integer, ``__index__`` is always called and not + considered as conversion, consistent with Python 3.8+. + `#2801 `_ + +Build improvements: + +* Setup helpers: ``extra_compile_args`` and ``extra_link_args`` automatically set by + Pybind11Extension are now prepended, which allows them to be overridden + by user-set ``extra_compile_args`` and ``extra_link_args``. + `#2808 `_ + +* Setup helpers: Don't trigger unused parameter warning. + `#2735 `_ + +* CMake: Support running with ``--warn-uninitialized`` active. + `#2806 `_ + +* CMake: Avoid error if included from two submodule directories. + `#2804 `_ + +* CMake: Fix ``STATIC`` / ``SHARED`` being ignored in FindPython mode. + `#2796 `_ + +* CMake: Respect the setting for ``CMAKE_CXX_VISIBILITY_PRESET`` if defined. + `#2793 `_ + +* CMake: Fix issue with FindPython2/FindPython3 not working with ``pybind11::embed``. + `#2662 `_ + +* CMake: mixing local and installed pybind11's would prioritize the installed + one over the local one (regression in 2.6.0). + `#2716 `_ + + +Bug fixes: + +* Fixed segfault in multithreaded environments when using + ``scoped_ostream_redirect``. + `#2675 `_ + +* Leave docstring unset when all docstring-related options are disabled, rather + than set an empty string. + `#2745 `_ + +* The module key in builtins that pybind11 uses to store its internals changed + from std::string to a python str type (more natural on Python 2, no change on + Python 3). + `#2814 `_ + +* Fixed assertion error related to unhandled (later overwritten) exception in + CPython 3.8 and 3.9 debug builds. + `#2685 `_ + +* Fix ``py::gil_scoped_acquire`` assert with CPython 3.9 debug build. + `#2683 `_ + +* Fix issue with a test failing on pytest 6.2. + `#2741 `_ + +Warning fixes: + +* Fix warning modifying constructor parameter 'flag' that shadows a field of + 'set_flag' ``[-Wshadow-field-in-constructor-modified]``. + `#2780 `_ + +* Suppressed some deprecation warnings about old-style + ``__init__``/``__setstate__`` in the tests. + `#2759 `_ + +Valgrind work: + +* Fix invalid access when calling a pybind11 ``__init__`` on a non-pybind11 + class instance. + `#2755 `_ + +* Fixed various minor memory leaks in pybind11's test suite. + `#2758 `_ + +* Resolved memory leak in cpp_function initialization when exceptions occurred. + `#2756 `_ + +* Added a Valgrind build, checking for leaks and memory-related UB, to CI. + `#2746 `_ + +Compiler support: + +* Intel compiler was not activating C++14 support due to a broken define. + `#2679 `_ + +* Support ICC and NVIDIA HPC SDK in C++17 mode. + `#2729 `_ + +* Support Intel OneAPI compiler (ICC 20.2) and add to CI. + `#2573 `_ + + + +v2.6.1 (Nov 11, 2020) +--------------------- + +* ``py::exec``, ``py::eval``, and ``py::eval_file`` now add the builtins module + as ``"__builtins__"`` to their ``globals`` argument, better matching ``exec`` + and ``eval`` in pure Python. + `#2616 `_ + +* ``setup_helpers`` will no longer set a minimum macOS version higher than the + current version. + `#2622 `_ + +* Allow deleting static properties. + `#2629 `_ + +* Seal a leak in ``def_buffer``, cleaning up the ``capture`` object after the + ``class_`` object goes out of scope. + `#2634 `_ + +* ``pybind11_INCLUDE_DIRS`` was incorrect, potentially causing a regression if + it was expected to include ``PYTHON_INCLUDE_DIRS`` (please use targets + instead). + `#2636 `_ + +* Added parameter names to the ``py::enum_`` constructor and methods, avoiding + ``arg0`` in the generated docstrings. + `#2637 `_ + +* Added ``needs_recompile`` optional function to the ``ParallelCompiler`` + helper, to allow a recompile to be skipped based on a user-defined function. + `#2643 `_ + + +v2.6.0 (Oct 21, 2020) +--------------------- + See :ref:`upgrade-guide-2.6` for help upgrading to the new version. -* Provide an additional spelling of ``py::module`` - ``py::module_`` (with a - trailing underscore), for C++20 compatibility. Only relevant when used - unqualified. - `#2489 `_ - -* ``pybind11_add_module()`` now accepts an optional ``OPT_SIZE`` flag that - switches the binding target to size-based optimization regardless global - CMake build type (except in debug mode, where optimizations remain disabled). - This reduces binary size quite substantially (~25%). - `#2463 `_ +New features: * Keyword-only arguments supported in Python 2 or 3 with ``py::kw_only()``. `#2100 `_ @@ -28,11 +704,17 @@ See :ref:`upgrade-guide-2.6` for help upgrading to the new version. * Positional-only arguments supported in Python 2 or 3 with ``py::pos_only()``. `#2459 `_ +* ``py::is_final()`` class modifier to block subclassing (CPython only). + `#2151 `_ + +* Added ``py::prepend()``, allowing a function to be placed at the beginning of + the overload chain. + `#1131 `_ + * Access to the type object now provided with ``py::type::of()`` and ``py::type::of(h)``. `#2364 `_ - * Perfect forwarding support for methods. `#2048 `_ @@ -42,11 +724,48 @@ See :ref:`upgrade-guide-2.6` for help upgrading to the new version. * ``py::hash`` is now public. `#2217 `_ -* ``py::is_final()`` class modifier to block subclassing (CPython only). - `#2151 `_ +* ``py::class_`` is now supported. Note that writing to one data + member of the union and reading another (type punning) is UB in C++. Thus + pybind11-bound enums should never be used for such conversions. + `#2320 `_. -* ``py::memoryview`` update and documentation. - `#2223 `_ +* Classes now check local scope when registering members, allowing a subclass + to have a member with the same name as a parent (such as an enum). + `#2335 `_ + +Code correctness features: + +* Error now thrown when ``__init__`` is forgotten on subclasses. + `#2152 `_ + +* Throw error if conversion to a pybind11 type if the Python object isn't a + valid instance of that type, such as ``py::bytes(o)`` when ``py::object o`` + isn't a bytes instance. + `#2349 `_ + +* Throw if conversion to ``str`` fails. + `#2477 `_ + + +API changes: + +* ``py::module`` was renamed ``py::module_`` to avoid issues with C++20 when + used unqualified, but an alias ``py::module`` is provided for backward + compatibility. + `#2489 `_ + +* Public constructors for ``py::module_`` have been deprecated; please use + ``pybind11::module_::create_extension_module`` if you were using the public + constructor (fairly rare after ``PYBIND11_MODULE`` was introduced). + `#2552 `_ + +* ``PYBIND11_OVERLOAD*`` macros and ``get_overload`` function replaced by + correctly-named ``PYBIND11_OVERRIDE*`` and ``get_override``, fixing + inconsistencies in the presence of a closing ``;`` in these macros. + ``get_type_overload`` is deprecated. + `#2325 `_ + +Packaging / building improvements: * The Python package was reworked to be more powerful and useful. `#2433 `_ @@ -54,7 +773,7 @@ See :ref:`upgrade-guide-2.6` for help upgrading to the new version. * :ref:`build-setuptools` is easier thanks to a new ``pybind11.setup_helpers`` module, which provides utilities to use setuptools with pybind11. It can be used via PEP 518, ``setup_requires``, - or by directly copying ``setup_helpers.py`` into your project. + or by directly importing or copying ``setup_helpers.py`` into your project. * CMake configuration files are now included in the Python package. Use ``pybind11.get_cmake_dir()`` or ``python -m pybind11 --cmakedir`` to get @@ -62,17 +781,21 @@ See :ref:`upgrade-guide-2.6` for help upgrading to the new version. site-packages location in your ``CMAKE_MODULE_PATH``. Or you can use the new ``pybind11[global]`` extra when you install ``pybind11``, which installs the CMake files and headers into your base environment in the - standard location + standard location. * ``pybind11-config`` is another way to write ``python -m pybind11`` if you have your PATH set up. + * Added external typing support to the helper module, code from + ``import pybind11`` can now be type checked. + `#2588 `_ + * Minimum CMake required increased to 3.4. `#2338 `_ and `#2370 `_ - * Full integration with CMake’s C++ standard system replaces - ``PYBIND11_CPP_STANDARD``. + * Full integration with CMake’s C++ standard system and compile features + replaces ``PYBIND11_CPP_STANDARD``. * Generated config file is now portable to different Python/compiler/CMake versions. @@ -85,27 +808,36 @@ See :ref:`upgrade-guide-2.6` for help upgrading to the new version. ``CMAKE_INTERPROCEDURAL_OPTIMIZATION``, ``set(CMAKE_CXX_VISIBILITY_PRESET hidden)``. -* Optional :ref:`find-python-mode` and :ref:`nopython-mode` with CMake. - `#2370 `_ + * ``CUDA`` as a language is now supported. + + * Helper functions ``pybind11_strip``, ``pybind11_extension``, + ``pybind11_find_import`` added, see :doc:`cmake/index`. + + * Optional :ref:`find-python-mode` and :ref:`nopython-mode` with CMake. + `#2370 `_ * Uninstall target added. `#2265 `_ and `#2346 `_ -* ``PYBIND11_OVERLOAD*`` macros and ``get_overload`` function replaced by - correctly-named ``PYBIND11_OVERRIDE*`` and ``get_override``, fixing - inconsistencies in the presene of a closing ``;`` in these macros. - ``get_type_overload`` is deprecated. - `#2325 `_ +* ``pybind11_add_module()`` now accepts an optional ``OPT_SIZE`` flag that + switches the binding target to size-based optimization if the global build + type can not always be fixed to ``MinSizeRel`` (except in debug mode, where + optimizations remain disabled). ``MinSizeRel`` or this flag reduces binary + size quite substantially (~25% on some platforms). + `#2463 `_ -Smaller or developer focused features: +Smaller or developer focused features and fixes: -* Moved ``mkdoc.py`` to a new repo, `pybind11-mkdoc`_. +* Moved ``mkdoc.py`` to a new repo, `pybind11-mkdoc`_. There are no longer + submodules in the main repo. -.. _pybind11-mkdoc: https://github.com/pybind/pybind11-mkdoc +* ``py::memoryview`` segfault fix and update, with new + ``py::memoryview::from_memory`` in Python 3, and documentation. + `#2223 `_ -* Error now thrown when ``__init__`` is forgotten on subclasses. - `#2152 `_ +* Fix for ``buffer_info`` on Python 2. + `#2503 `_ * If ``__eq__`` defined but not ``__hash__``, ``__hash__`` is now set to ``None``. @@ -114,12 +846,6 @@ Smaller or developer focused features: * ``py::ellipsis`` now also works on Python 2. `#2360 `_ -* Throw if conversion to ``str`` fails. - `#2477 `_ - -* Added missing signature for ``py::array``. - `#2363 `_ - * Pointer to ``std::tuple`` & ``std::pair`` supported in cast. `#2334 `_ @@ -127,7 +853,26 @@ Smaller or developer focused features: argument type. `#2293 `_ -* Bugfixes related to more extensive testing +* Added missing signature for ``py::array``. + `#2363 `_ + +* ``unchecked_mutable_reference`` has access to operator ``()`` and ``[]`` when + const. + `#2514 `_ + +* ``py::vectorize`` is now supported on functions that return void. + `#1969 `_ + +* ``py::capsule`` supports ``get_pointer`` and ``set_pointer``. + `#1131 `_ + +* Fix crash when different instances share the same pointer of the same type. + `#2252 `_ + +* Fix for ``py::len`` not clearing Python's error state when it fails and throws. + `#2575 `_ + +* Bugfixes related to more extensive testing, new GitHub Actions CI. `#2321 `_ * Bug in timezone issue in Eastern hemisphere midnight fixed. @@ -141,16 +886,27 @@ Smaller or developer focused features: requested ordering. `#2484 `_ -* PyPy fixes, including support for PyPy3 and PyPy 7. +* Avoid a segfault on some compilers when types are removed in Python. + `#2564 `_ + +* ``py::arg::none()`` is now also respected when passing keyword arguments. + `#2611 `_ + +* PyPy fixes, PyPy 7.3.x now supported, including PyPy3. (Known issue with + PyPy2 and Windows `#2596 `_). `#2146 `_ -* CPython 3.9 fixes. +* CPython 3.9.0 workaround for undefined behavior (macOS segfault). + `#2576 `_ + +* CPython 3.9 warning fixes. `#2253 `_ -* More C++20 support. +* Improved C++20 support, now tested in CI. `#2489 `_ + `#2599 `_ -* Debug Python interpreter support. +* Improved but still incomplete debug Python interpreter support. `#2025 `_ * NVCC (CUDA 11) now supported and tested in CI. @@ -159,11 +915,20 @@ Smaller or developer focused features: * NVIDIA PGI compilers now supported and tested in CI. `#2475 `_ -* Extensive style checking in CI, with `pre-commit`_ support. +* At least Intel 18 now explicitly required when compiling with Intel. + `#2577 `_ + +* Extensive style checking in CI, with `pre-commit`_ support. Code + modernization, checked by clang-tidy. + +* Expanded docs, including new main page, new installing section, and CMake + helpers page, along with over a dozen new sections on existing pages. + +* In GitHub, new docs for contributing and new issue templates. .. _pre-commit: https://pre-commit.com - +.. _pybind11-mkdoc: https://github.com/pybind/pybind11-mkdoc v2.5.0 (Mar 31, 2020) ----------------------------------------------------- @@ -261,7 +1026,7 @@ v2.4.0 (Sep 19, 2019) `#1888 `_. * ``py::details::overload_cast_impl`` is available in C++11 mode, can be used - like ``overload_cast`` with an additional set of parantheses. + like ``overload_cast`` with an additional set of parentheses. `#1581 `_. * Fixed ``get_include()`` on Conda. @@ -520,7 +1285,7 @@ v2.2.2 (February 7, 2018) v2.2.1 (September 14, 2017) ----------------------------------------------------- -* Added ``py::module::reload()`` member function for reloading a module. +* Added ``py::module_::reload()`` member function for reloading a module. `#1040 `_. * Fixed a reference leak in the number converter. @@ -583,6 +1348,7 @@ v2.2.0 (August 31, 2017) from cpp_module import CppBase1, CppBase2 + class PyDerived(CppBase1, CppBase2): def __init__(self): CppBase1.__init__(self) # C++ bases must be initialized explicitly @@ -795,7 +1561,7 @@ v2.2.0 (August 31, 2017) * Intel C++ compiler compatibility fixes. `#937 `_. -* Fixed implicit conversion of `py::enum_` to integer types on Python 2.7. +* Fixed implicit conversion of ``py::enum_`` to integer types on Python 2.7. `#821 `_. * Added ``py::hash`` to fetch the hash value of Python objects, and diff --git a/pybind11/docs/classes.rst b/pybind11/docs/classes.rst index f3610ef36..13fa8b538 100644 --- a/pybind11/docs/classes.rst +++ b/pybind11/docs/classes.rst @@ -44,12 +44,12 @@ interactive Python session demonstrating this example is shown below: % python >>> import example - >>> p = example.Pet('Molly') + >>> p = example.Pet("Molly") >>> print(p) >>> p.getName() u'Molly' - >>> p.setName('Charly') + >>> p.setName("Charly") >>> p.getName() u'Charly' @@ -122,10 +122,10 @@ This makes it possible to write .. code-block:: pycon - >>> p = example.Pet('Molly') + >>> p = example.Pet("Molly") >>> p.name u'Molly' - >>> p.name = 'Charly' + >>> p.name = "Charly" >>> p.name u'Charly' @@ -174,10 +174,10 @@ Native Python classes can pick up new attributes dynamically: .. code-block:: pycon >>> class Pet: - ... name = 'Molly' + ... name = "Molly" ... >>> p = Pet() - >>> p.name = 'Charly' # overwrite existing + >>> p.name = "Charly" # overwrite existing >>> p.age = 2 # dynamically add a new attribute By default, classes exported from C++ do not support this and the only writable @@ -195,7 +195,7 @@ Trying to set any other attribute results in an error: .. code-block:: pycon >>> p = example.Pet() - >>> p.name = 'Charly' # OK, attribute defined in C++ + >>> p.name = "Charly" # OK, attribute defined in C++ >>> p.age = 2 # fail AttributeError: 'Pet' object has no attribute 'age' @@ -213,7 +213,7 @@ Now everything works as expected: .. code-block:: pycon >>> p = example.Pet() - >>> p.name = 'Charly' # OK, overwrite value in C++ + >>> p.name = "Charly" # OK, overwrite value in C++ >>> p.age = 2 # OK, dynamically add a new attribute >>> p.__dict__ # just like a native Python class {'age': 2} @@ -280,7 +280,7 @@ expose fields and methods of both types: .. code-block:: pycon - >>> p = example.Dog('Molly') + >>> p = example.Dog("Molly") >>> p.name u'Molly' >>> p.bark() @@ -446,8 +446,7 @@ you can use ``py::detail::overload_cast_impl`` with an additional set of parenth Enumerations and internal types =============================== -Let's now suppose that the example class contains an internal enumeration type, -e.g.: +Let's now suppose that the example class contains internal types like enumerations, e.g.: .. code-block:: cpp @@ -457,10 +456,15 @@ e.g.: Cat }; + struct Attributes { + float age = 0; + }; + Pet(const std::string &name, Kind type) : name(name), type(type) { } std::string name; Kind type; + Attributes attr; }; The binding code for this example looks as follows: @@ -471,22 +475,28 @@ The binding code for this example looks as follows: pet.def(py::init()) .def_readwrite("name", &Pet::name) - .def_readwrite("type", &Pet::type); + .def_readwrite("type", &Pet::type) + .def_readwrite("attr", &Pet::attr); py::enum_(pet, "Kind") .value("Dog", Pet::Kind::Dog) .value("Cat", Pet::Kind::Cat) .export_values(); -To ensure that the ``Kind`` type is created within the scope of ``Pet``, the -``pet`` :class:`class_` instance must be supplied to the :class:`enum_`. + py::class_ attributes(pet, "Attributes") + .def(py::init<>()) + .def_readwrite("age", &Pet::Attributes::age); + + +To ensure that the nested types ``Kind`` and ``Attributes`` are created within the scope of ``Pet``, the +``pet`` :class:`class_` instance must be supplied to the :class:`enum_` and :class:`class_` constructor. The :func:`enum_::export_values` function exports the enum entries into the parent scope, which should be skipped for newer C++11-style strongly typed enums. .. code-block:: pycon - >>> p = Pet('Lucy', Pet.Cat) + >>> p = Pet("Lucy", Pet.Cat) >>> p.type Kind.Cat >>> int(p.type) @@ -508,7 +518,7 @@ The ``name`` property returns the name of the enum value as a unicode string. .. code-block:: pycon - >>> p = Pet( "Lucy", Pet.Cat ) + >>> p = Pet("Lucy", Pet.Cat) >>> pet_type = p.type >>> pet_type Pet.Cat diff --git a/pybind11/docs/cmake/index.rst b/pybind11/docs/cmake/index.rst new file mode 100644 index 000000000..eaf66d70f --- /dev/null +++ b/pybind11/docs/cmake/index.rst @@ -0,0 +1,8 @@ +CMake helpers +------------- + +Pybind11 can be used with ``add_subdirectory(extern/pybind11)``, or from an +install with ``find_package(pybind11 CONFIG)``. The interface provided in +either case is functionally identical. + +.. cmake-module:: ../../tools/pybind11Config.cmake.in diff --git a/pybind11/docs/compiling.rst b/pybind11/docs/compiling.rst index cbf14a466..75608bd57 100644 --- a/pybind11/docs/compiling.rst +++ b/pybind11/docs/compiling.rst @@ -31,20 +31,18 @@ An example of a ``setup.py`` using pybind11's helpers: .. code-block:: python + from glob import glob from setuptools import setup from pybind11.setup_helpers import Pybind11Extension ext_modules = [ Pybind11Extension( "python_example", - ["src/main.cpp"], + sorted(glob("src/*.cpp")), # Sort source files for reproducibility ), ] - setup( - ..., - ext_modules=ext_modules - ) + setup(..., ext_modules=ext_modules) If you want to do an automatic search for the highest supported C++ standard, that is supported via a ``build_ext`` command override; it will only affect @@ -52,21 +50,81 @@ that is supported via a ``build_ext`` command override; it will only affect .. code-block:: python + from glob import glob from setuptools import setup from pybind11.setup_helpers import Pybind11Extension, build_ext ext_modules = [ Pybind11Extension( "python_example", - ["src/main.cpp"], + sorted(glob("src/*.cpp")), ), ] - setup( - ..., - cmdclass={"build_ext": build_ext}, - ext_modules=ext_modules - ) + setup(..., cmdclass={"build_ext": build_ext}, ext_modules=ext_modules) + +If you have single-file extension modules that are directly stored in the +Python source tree (``foo.cpp`` in the same directory as where a ``foo.py`` +would be located), you can also generate ``Pybind11Extensions`` using +``setup_helpers.intree_extensions``: ``intree_extensions(["path/to/foo.cpp", +...])`` returns a list of ``Pybind11Extensions`` which can be passed to +``ext_modules``, possibly after further customizing their attributes +(``libraries``, ``include_dirs``, etc.). By doing so, a ``foo.*.so`` extension +module will be generated and made available upon installation. + +``intree_extension`` will automatically detect if you are using a ``src``-style +layout (as long as no namespace packages are involved), but you can also +explicitly pass ``package_dir`` to it (as in ``setuptools.setup``). + +Since pybind11 does not require NumPy when building, a light-weight replacement +for NumPy's parallel compilation distutils tool is included. Use it like this: + +.. code-block:: python + + from pybind11.setup_helpers import ParallelCompile + + # Optional multithreaded build + ParallelCompile("NPY_NUM_BUILD_JOBS").install() + + setup(...) + +The argument is the name of an environment variable to control the number of +threads, such as ``NPY_NUM_BUILD_JOBS`` (as used by NumPy), though you can set +something different if you want; ``CMAKE_BUILD_PARALLEL_LEVEL`` is another choice +a user might expect. You can also pass ``default=N`` to set the default number +of threads (0 will take the number of threads available) and ``max=N``, the +maximum number of threads; if you have a large extension you may want set this +to a memory dependent number. + +If you are developing rapidly and have a lot of C++ files, you may want to +avoid rebuilding files that have not changed. For simple cases were you are +using ``pip install -e .`` and do not have local headers, you can skip the +rebuild if an object file is newer than its source (headers are not checked!) +with the following: + +.. code-block:: python + + from pybind11.setup_helpers import ParallelCompile, naive_recompile + + ParallelCompile("NPY_NUM_BUILD_JOBS", needs_recompile=naive_recompile).install() + + +If you have a more complex build, you can implement a smarter function and pass +it to ``needs_recompile``, or you can use [Ccache]_ instead. ``CXX="cache g++" +pip install -e .`` would be the way to use it with GCC, for example. Unlike the +simple solution, this even works even when not compiling in editable mode, but +it does require Ccache to be installed. + +Keep in mind that Pip will not even attempt to rebuild if it thinks it has +already built a copy of your code, which it deduces from the version number. +One way to avoid this is to use [setuptools_scm]_, which will generate a +version number that includes the number of commits since your last tag and a +hash for a dirty directory. Another way to force a rebuild is purge your cache +or use Pip's ``--no-cache-dir`` option. + +.. [Ccache] https://ccache.dev + +.. [setuptools_scm] https://github.com/pypa/setuptools_scm .. _setup_helpers-pep518: @@ -85,7 +143,7 @@ Your ``pyproject.toml`` file will likely look something like this: .. code-block:: toml [build-system] - requires = ["setuptools", "wheel", "pybind11==2.6.0"] + requires = ["setuptools>=42", "wheel", "pybind11~=2.6.1"] build-backend = "setuptools.build_meta" .. note:: @@ -96,10 +154,12 @@ Your ``pyproject.toml`` file will likely look something like this: in Python) using something like `cibuildwheel`_, remember that ``setup.py`` and ``pyproject.toml`` are not even contained in the wheel, so this high Pip requirement is only for source builds, and will not affect users of - your binary wheels. + your binary wheels. If you are building SDists and wheels, then + `pypa-build`_ is the recommended official tool. .. _PEP 517: https://www.python.org/dev/peps/pep-0517/ .. _cibuildwheel: https://cibuildwheel.readthedocs.io +.. _pypa-build: https://pypa-build.readthedocs.io/en/latest/ .. _setup_helpers-setup_requires: @@ -140,6 +200,23 @@ this, you will need to import from a local file in ``setup.py`` and ensure the helper file is part of your MANIFEST. +Closely related, if you include pybind11 as a subproject, you can run the +``setup_helpers.py`` inplace. If loaded correctly, this should even pick up +the correct include for pybind11, though you can turn it off as shown above if +you want to input it manually. + +Suggested usage if you have pybind11 as a submodule in ``extern/pybind11``: + +.. code-block:: python + + DIR = os.path.abspath(os.path.dirname(__file__)) + + sys.path.append(os.path.join(DIR, "extern", "pybind11")) + from pybind11.setup_helpers import Pybind11Extension # noqa: E402 + + del sys.path[-1] + + .. versionchanged:: 2.6 Added ``setup_helpers`` file. @@ -184,6 +261,8 @@ PyPI integration, can be found in the [cmake_example]_ repository. .. versionchanged:: 2.6 CMake 3.4+ is required. +Further information can be found at :doc:`cmake/index`. + pybind11_add_module ------------------- @@ -224,8 +303,15 @@ As stated above, LTO is enabled by default. Some newer compilers also support different flavors of LTO such as `ThinLTO`_. Setting ``THIN_LTO`` will cause the function to prefer this flavor if available. The function falls back to regular LTO if ``-flto=thin`` is not available. If -``CMAKE_INTERPROCEDURAL_OPTIMIZATION`` is set (either ON or OFF), then that -will be respected instead of the built-in flag search. +``CMAKE_INTERPROCEDURAL_OPTIMIZATION`` is set (either ``ON`` or ``OFF``), then +that will be respected instead of the built-in flag search. + +.. note:: + + If you want to set the property form on targets or the + ``CMAKE_INTERPROCEDURAL_OPTIMIZATION_`` versions of this, you should + still use ``set(CMAKE_INTERPROCEDURAL_OPTIMIZATION OFF)`` (otherwise a + no-op) to disable pybind11's ipo flags. The ``OPT_SIZE`` flag enables size-based optimization equivalent to the standard ``/Os`` or ``-Os`` compiler flags and the ``MinSizeRel`` build type, @@ -252,10 +338,9 @@ standard explicitly with .. code-block:: cmake - set(CMAKE_CXX_STANDARD 14) # or 11, 14, 17, 20 + set(CMAKE_CXX_STANDARD 14 CACHE STRING "C++ version selection") # or 11, 14, 17, 20 set(CMAKE_CXX_STANDARD_REQUIRED ON) # optional, ensure standard is supported - set(CMAKE_CXX_EXTENSIONS OFF) # optional, keep compiler extensionsn off - + set(CMAKE_CXX_EXTENSIONS OFF) # optional, keep compiler extensions off The variables can also be set when calling CMake from the command line using the ``-D=`` flag. You can also manually set ``CXX_STANDARD`` @@ -325,13 +410,14 @@ can refer to the same [cmake_example]_ repository for a full sample project FindPython mode --------------- -CMake 3.12+ (3.15+ recommended) added a new module called FindPython that had a -highly improved search algorithm and modern targets and tools. If you use -FindPython, pybind11 will detect this and use the existing targets instead: +CMake 3.12+ (3.15+ recommended, 3.18.2+ ideal) added a new module called +FindPython that had a highly improved search algorithm and modern targets +and tools. If you use FindPython, pybind11 will detect this and use the +existing targets instead: .. code-block:: cmake - cmake_minumum_required(VERSION 3.15...3.18) + cmake_minimum_required(VERSION 3.15...3.19) project(example LANGUAGES CXX) find_package(Python COMPONENTS Interpreter Development REQUIRED) @@ -357,6 +443,14 @@ setting ``Python_ROOT_DIR`` may be the most common one (though with virtualenv/venv support, and Conda support, this tends to find the correct Python version more often than the old system did). +.. warning:: + + When the Python libraries (i.e. ``libpythonXX.a`` and ``libpythonXX.so`` + on Unix) are not available, as is the case on a manylinux image, the + ``Development`` component will not be resolved by ``FindPython``. When not + using the embedding functionality, CMake 3.18+ allows you to specify + ``Development.Module`` instead of ``Development`` to resolve this issue. + .. versionadded:: 2.6 Advanced: interface library targets @@ -428,7 +522,7 @@ Instead of setting properties, you can set ``CMAKE_*`` variables to initialize t compiler flags are provided to ensure high quality code generation. In contrast to the ``pybind11_add_module()`` command, the CMake interface provides a *composable* set of targets to ensure that you retain flexibility. - It can be expecially important to provide or set these properties; the + It can be especially important to provide or set these properties; the :ref:`FAQ ` contains an explanation on why these are needed. .. versionadded:: 2.6 @@ -481,7 +575,7 @@ On Linux, you can compile an example such as the one given in .. code-block:: bash - $ c++ -O3 -Wall -shared -std=c++11 -fPIC `python3 -m pybind11 --includes` example.cpp -o example`python3-config --extension-suffix` + $ c++ -O3 -Wall -shared -std=c++11 -fPIC $(python3 -m pybind11 --includes) example.cpp -o example$(python3-config --extension-suffix) The flags given here assume that you're using Python 3. For Python 2, just change the executable appropriately (to ``python`` or ``python2``). @@ -493,7 +587,7 @@ using ``pip`` or ``conda``. If it hasn't, you can also manually specify ``python3-config --includes``. Note that Python 2.7 modules don't use a special suffix, so you should simply -use ``example.so`` instead of ``example`python3-config --extension-suffix```. +use ``example.so`` instead of ``example$(python3-config --extension-suffix)``. Besides, the ``--extension-suffix`` option may or may not be available, depending on the distribution; in the latter case, the module extension can be manually set to ``.so``. @@ -504,7 +598,7 @@ building the module: .. code-block:: bash - $ c++ -O3 -Wall -shared -std=c++11 -undefined dynamic_lookup `python3 -m pybind11 --includes` example.cpp -o example`python3-config --extension-suffix` + $ c++ -O3 -Wall -shared -std=c++11 -undefined dynamic_lookup $(python3 -m pybind11 --includes) example.cpp -o example$(python3-config --extension-suffix) In general, it is advisable to include several additional build parameters that can considerably reduce the size of the created binary. Refer to section @@ -523,23 +617,11 @@ build system that works on all platforms including Windows. contains one (which will lead to a segfault). -Building with vcpkg +Building with Bazel =================== -You can download and install pybind11 using the Microsoft `vcpkg -`_ dependency manager: -.. code-block:: bash - - git clone https://github.com/Microsoft/vcpkg.git - cd vcpkg - ./bootstrap-vcpkg.sh - ./vcpkg integrate install - vcpkg install pybind11 - -The pybind11 port in vcpkg is kept up to date by Microsoft team members and -community contributors. If the version is out of date, please `create an issue -or pull request `_ on the vcpkg -repository. +You can build with the Bazel build system using the `pybind11_bazel +`_ repository. Generating binding code automatically ===================================== diff --git a/pybind11/docs/conf.py b/pybind11/docs/conf.py index 0946f30e2..092e274e0 100644 --- a/pybind11/docs/conf.py +++ b/pybind11/docs/conf.py @@ -13,57 +13,68 @@ # All configuration values have a default; values that are commented out # serve to show the default. -import sys import os -import shlex +import re import subprocess +import sys +from pathlib import Path + +DIR = Path(__file__).parent.resolve() # If extensions (or modules to document with autodoc) are in another directory, # add these directories to sys.path here. If the directory is relative to the # documentation root, use os.path.abspath to make it absolute, like shown here. -#sys.path.insert(0, os.path.abspath('.')) +# sys.path.insert(0, os.path.abspath('.')) # -- General configuration ------------------------------------------------ # If your documentation needs a minimal Sphinx version, state it here. -#needs_sphinx = '1.0' +# needs_sphinx = '1.0' # Add any Sphinx extension module names here, as strings. They can be # extensions coming with Sphinx (named 'sphinx.ext.*') or your custom # ones. -extensions = ['breathe'] +extensions = [ + "breathe", + "sphinxcontrib.rsvgconverter", + "sphinxcontrib.moderncmakedomain", +] -breathe_projects = {'pybind11': '.build/doxygenxml/'} -breathe_default_project = 'pybind11' -breathe_domain_by_extension = {'h': 'cpp'} +breathe_projects = {"pybind11": ".build/doxygenxml/"} +breathe_default_project = "pybind11" +breathe_domain_by_extension = {"h": "cpp"} # Add any paths that contain templates here, relative to this directory. -templates_path = ['.templates'] +templates_path = [".templates"] # The suffix(es) of source filenames. # You can specify multiple suffix as a list of string: # source_suffix = ['.rst', '.md'] -source_suffix = '.rst' +source_suffix = ".rst" # The encoding of source files. -#source_encoding = 'utf-8-sig' +# source_encoding = 'utf-8-sig' # The master toctree document. -master_doc = 'index' +master_doc = "index" # General information about the project. -project = 'pybind11' -copyright = '2017, Wenzel Jakob' -author = 'Wenzel Jakob' +project = "pybind11" +copyright = "2017, Wenzel Jakob" +author = "Wenzel Jakob" # The version info for the project you're documenting, acts as replacement for # |version| and |release|, also used in various other places throughout the # built documents. -# -# The short X.Y version. -version = '2.5' + +# Read the listed version +with open("../pybind11/_version.py") as f: + code = compile(f.read(), "../pybind11/_version.py", "exec") +loc = {} +exec(code, loc) + # The full version, including alpha/beta/rc tags. -release = '2.5.dev1' +version = loc["__version__"] # The language for content autogenerated by Sphinx. Refer to documentation # for a list of supported languages. @@ -74,37 +85,37 @@ language = None # There are two options for replacing |today|: either, you set today to some # non-false value, then it is used: -#today = '' +# today = '' # Else, today_fmt is used as the format for a strftime call. -#today_fmt = '%B %d, %Y' +# today_fmt = '%B %d, %Y' # List of patterns, relative to source directory, that match files and # directories to ignore when looking for source files. -exclude_patterns = ['.build', 'release.rst'] +exclude_patterns = [".build", "release.rst"] # The reST default role (used for this markup: `text`) to use for all # documents. -default_role = 'any' +default_role = "any" # If true, '()' will be appended to :func: etc. cross-reference text. -#add_function_parentheses = True +# add_function_parentheses = True # If true, the current module name will be prepended to all description # unit titles (such as .. function::). -#add_module_names = True +# add_module_names = True # If true, sectionauthor and moduleauthor directives will be shown in the # output. They are ignored by default. -#show_authors = False +# show_authors = False # The name of the Pygments (syntax highlighting) style to use. -#pygments_style = 'monokai' +# pygments_style = 'monokai' # A list of ignored prefixes for module index sorting. -#modindex_common_prefix = [] +# modindex_common_prefix = [] # If true, keep warnings as "system message" paragraphs in the built documents. -#keep_warnings = False +# keep_warnings = False # If true, `todo` and `todoList` produce output, else they produce nothing. todo_include_todos = False @@ -115,141 +126,150 @@ todo_include_todos = False # The theme to use for HTML and HTML Help pages. See the documentation for # a list of builtin themes. -on_rtd = os.environ.get('READTHEDOCS', None) == 'True' +on_rtd = os.environ.get("READTHEDOCS", None) == "True" if not on_rtd: # only import and set the theme if we're building docs locally import sphinx_rtd_theme - html_theme = 'sphinx_rtd_theme' + + html_theme = "sphinx_rtd_theme" html_theme_path = [sphinx_rtd_theme.get_html_theme_path()] - html_context = { - 'css_files': [ - '_static/theme_overrides.css' - ] - } + html_context = {"css_files": ["_static/theme_overrides.css"]} else: html_context = { - 'css_files': [ - '//media.readthedocs.org/css/sphinx_rtd_theme.css', - '//media.readthedocs.org/css/readthedocs-doc-embed.css', - '_static/theme_overrides.css' + "css_files": [ + "//media.readthedocs.org/css/sphinx_rtd_theme.css", + "//media.readthedocs.org/css/readthedocs-doc-embed.css", + "_static/theme_overrides.css", ] } # Theme options are theme-specific and customize the look and feel of a theme # further. For a list of options available for each theme, see the # documentation. -#html_theme_options = {} +# html_theme_options = {} # Add any paths that contain custom themes here, relative to this directory. -#html_theme_path = [] +# html_theme_path = [] # The name for this set of Sphinx documents. If None, it defaults to -# " v documentation". -#html_title = None +# " v documentation". +# html_title = None # A shorter title for the navigation bar. Default is the same as html_title. -#html_short_title = None +# html_short_title = None # The name of an image file (relative to this directory) to place at the top # of the sidebar. -#html_logo = None +# html_logo = None # The name of an image file (within the static path) to use as favicon of the # docs. This file should be a Windows icon file (.ico) being 16x16 or 32x32 # pixels large. -#html_favicon = None +# html_favicon = None # Add any paths that contain custom static files (such as style sheets) here, # relative to this directory. They are copied after the builtin static files, # so a file named "default.css" will overwrite the builtin "default.css". -html_static_path = ['_static'] +html_static_path = ["_static"] # Add any extra paths that contain custom files (such as robots.txt or # .htaccess) here, relative to this directory. These files are copied # directly to the root of the documentation. -#html_extra_path = [] +# html_extra_path = [] # If not '', a 'Last updated on:' timestamp is inserted at every page bottom, # using the given strftime format. -#html_last_updated_fmt = '%b %d, %Y' +# html_last_updated_fmt = '%b %d, %Y' # If true, SmartyPants will be used to convert quotes and dashes to # typographically correct entities. -#html_use_smartypants = True +# html_use_smartypants = True # Custom sidebar templates, maps document names to template names. -#html_sidebars = {} +# html_sidebars = {} # Additional templates that should be rendered to pages, maps page names to # template names. -#html_additional_pages = {} +# html_additional_pages = {} # If false, no module index is generated. -#html_domain_indices = True +# html_domain_indices = True # If false, no index is generated. -#html_use_index = True +# html_use_index = True # If true, the index is split into individual pages for each letter. -#html_split_index = False +# html_split_index = False # If true, links to the reST sources are added to the pages. -#html_show_sourcelink = True +# html_show_sourcelink = True # If true, "Created using Sphinx" is shown in the HTML footer. Default is True. -#html_show_sphinx = True +# html_show_sphinx = True # If true, "(C) Copyright ..." is shown in the HTML footer. Default is True. -#html_show_copyright = True +# html_show_copyright = True # If true, an OpenSearch description file will be output, and all pages will # contain a tag referring to it. The value of this option must be the # base URL from which the finished HTML is served. -#html_use_opensearch = '' +# html_use_opensearch = '' # This is the file name suffix for HTML files (e.g. ".xhtml"). -#html_file_suffix = None +# html_file_suffix = None # Language to be used for generating the HTML full-text search index. # Sphinx supports the following languages: # 'da', 'de', 'en', 'es', 'fi', 'fr', 'h', 'it', 'ja' # 'nl', 'no', 'pt', 'ro', 'r', 'sv', 'tr' -#html_search_language = 'en' +# html_search_language = 'en' # A dictionary with options for the search language support, empty by default. # Now only 'ja' uses this config value -#html_search_options = {'type': 'default'} +# html_search_options = {'type': 'default'} # The name of a javascript file (relative to the configuration directory) that # implements a search results scorer. If empty, the default will be used. -#html_search_scorer = 'scorer.js' +# html_search_scorer = 'scorer.js' # Output file base name for HTML help builder. -htmlhelp_basename = 'pybind11doc' +htmlhelp_basename = "pybind11doc" # -- Options for LaTeX output --------------------------------------------- +latex_engine = "pdflatex" + latex_elements = { -# The paper size ('letterpaper' or 'a4paper'). -#'papersize': 'letterpaper', + # The paper size ('letterpaper' or 'a4paper'). + # 'papersize': 'letterpaper', + # + # The font size ('10pt', '11pt' or '12pt'). + # 'pointsize': '10pt', + # + # Additional stuff for the LaTeX preamble. + # remove blank pages (between the title page and the TOC, etc.) + "classoptions": ",openany,oneside", + "preamble": r""" +\usepackage{fontawesome} +\usepackage{textgreek} +\DeclareUnicodeCharacter{00A0}{} +\DeclareUnicodeCharacter{2194}{\faArrowsH} +\DeclareUnicodeCharacter{1F382}{\faBirthdayCake} +\DeclareUnicodeCharacter{1F355}{\faAdjust} +\DeclareUnicodeCharacter{0301}{'} +\DeclareUnicodeCharacter{03C0}{\textpi} -# The font size ('10pt', '11pt' or '12pt'). -#'pointsize': '10pt', - -# Additional stuff for the LaTeX preamble. -'preamble': r'\DeclareUnicodeCharacter{00A0}{}', - -# Latex figure (float) alignment -#'figure_align': 'htbp', +""", + # Latex figure (float) alignment + # 'figure_align': 'htbp', } # Grouping the document tree into LaTeX files. List of tuples # (source start file, target name, title, # author, documentclass [howto, manual, or own class]). latex_documents = [ - (master_doc, 'pybind11.tex', 'pybind11 Documentation', - 'Wenzel Jakob', 'manual'), + (master_doc, "pybind11.tex", "pybind11 Documentation", "Wenzel Jakob", "manual"), ] # The name of an image file (relative to this directory) to place at the top of @@ -258,32 +278,29 @@ latex_documents = [ # For "manual" documents, if this is true, then toplevel headings are parts, # not chapters. -#latex_use_parts = False +# latex_use_parts = False # If true, show page references after internal links. -#latex_show_pagerefs = False +# latex_show_pagerefs = False # If true, show URL addresses after external links. -#latex_show_urls = False +# latex_show_urls = False # Documents to append as an appendix to all manuals. -#latex_appendices = [] +# latex_appendices = [] # If false, no module index is generated. -#latex_domain_indices = True +# latex_domain_indices = True # -- Options for manual page output --------------------------------------- # One entry per manual page. List of tuples # (source start file, name, description, authors, manual section). -man_pages = [ - (master_doc, 'pybind11', 'pybind11 Documentation', - [author], 1) -] +man_pages = [(master_doc, "pybind11", "pybind11 Documentation", [author], 1)] # If true, show URL addresses after external links. -#man_show_urls = False +# man_show_urls = False # -- Options for Texinfo output ------------------------------------------- @@ -292,41 +309,73 @@ man_pages = [ # (source start file, target name, title, author, # dir menu entry, description, category) texinfo_documents = [ - (master_doc, 'pybind11', 'pybind11 Documentation', - author, 'pybind11', 'One line description of project.', - 'Miscellaneous'), + ( + master_doc, + "pybind11", + "pybind11 Documentation", + author, + "pybind11", + "One line description of project.", + "Miscellaneous", + ), ] # Documents to append as an appendix to all manuals. -#texinfo_appendices = [] +# texinfo_appendices = [] # If false, no module index is generated. -#texinfo_domain_indices = True +# texinfo_domain_indices = True # How to display URL addresses: 'footnote', 'no', or 'inline'. -#texinfo_show_urls = 'footnote' +# texinfo_show_urls = 'footnote' # If true, do not generate a @detailmenu in the "Top" node's menu. -#texinfo_no_detailmenu = False +# texinfo_no_detailmenu = False -primary_domain = 'cpp' -highlight_language = 'cpp' +primary_domain = "cpp" +highlight_language = "cpp" def generate_doxygen_xml(app): - build_dir = os.path.join(app.confdir, '.build') + build_dir = os.path.join(app.confdir, ".build") if not os.path.exists(build_dir): os.mkdir(build_dir) try: - subprocess.call(['doxygen', '--version']) - retcode = subprocess.call(['doxygen'], cwd=app.confdir) + subprocess.call(["doxygen", "--version"]) + retcode = subprocess.call(["doxygen"], cwd=app.confdir) if retcode < 0: sys.stderr.write("doxygen error code: {}\n".format(-retcode)) except OSError as e: sys.stderr.write("doxygen execution failed: {}\n".format(e)) +def prepare(app): + with open(DIR.parent / "README.rst") as f: + contents = f.read() + + if app.builder.name == "latex": + # Remove badges and stuff from start + contents = contents[contents.find(r".. start") :] + + # Filter out section titles for index.rst for LaTeX + contents = re.sub(r"^(.*)\n[-~]{3,}$", r"**\1**", contents, flags=re.MULTILINE) + + with open(DIR / "readme.rst", "w") as f: + f.write(contents) + + +def clean_up(app, exception): + (DIR / "readme.rst").unlink() + + def setup(app): - """Add hook for building doxygen xml when needed""" + + # Add hook for building doxygen xml when needed app.connect("builder-inited", generate_doxygen_xml) + + # Copy the readme in + app.connect("builder-inited", prepare) + + # Clean up the generated readme + app.connect("build-finished", clean_up) diff --git a/pybind11/docs/faq.rst b/pybind11/docs/faq.rst index 5f7866fa7..e2f477b1f 100644 --- a/pybind11/docs/faq.rst +++ b/pybind11/docs/faq.rst @@ -5,7 +5,7 @@ Frequently asked questions =========================================================== 1. Make sure that the name specified in PYBIND11_MODULE is identical to the -filename of the extension library (without suffixes such as .so) +filename of the extension library (without suffixes such as ``.so``). 2. If the above did not fix the issue, you are likely using an incompatible version of Python (for instance, the extension library was compiled against @@ -27,18 +27,6 @@ The Python interpreter immediately crashes when importing my module See the first answer. -CMake doesn't detect the right Python version -============================================= - -The CMake-based build system will try to automatically detect the installed -version of Python and link against that. When this fails, or when there are -multiple versions of Python and it finds the wrong one, delete -``CMakeCache.txt`` and then invoke CMake as follows: - -.. code-block:: bash - - cmake -DPYTHON_EXECUTABLE:FILEPATH= . - .. _faq_reference_arguments: Limitations involving reference arguments @@ -66,7 +54,7 @@ provided by the caller -- in fact, it does nothing at all. .. code-block:: python def increment(i): - i += 1 # nope.. + i += 1 # nope.. pybind11 is also affected by such language-level conventions, which means that binding ``increment`` or ``increment_ptr`` will also create Python functions @@ -100,8 +88,8 @@ following example: .. code-block:: cpp - void init_ex1(py::module &); - void init_ex2(py::module &); + void init_ex1(py::module_ &); + void init_ex2(py::module_ &); /* ... */ PYBIND11_MODULE(example, m) { @@ -114,7 +102,7 @@ following example: .. code-block:: cpp - void init_ex1(py::module &m) { + void init_ex1(py::module_ &m) { m.def("add", [](int a, int b) { return a + b; }); } @@ -122,7 +110,7 @@ following example: .. code-block:: cpp - void init_ex2(py::module &m) { + void init_ex2(py::module_ &m) { m.def("sub", [](int a, int b) { return a - b; }); } @@ -181,8 +169,8 @@ can be changed, but even if it isn't it is not always enough to guarantee complete independence of the symbols involved when not using ``-fvisibility=hidden``. -Additionally, ``-fvisiblity=hidden`` can deliver considerably binary size -savings. (See the following section for more details). +Additionally, ``-fvisibility=hidden`` can deliver considerably binary size +savings. (See the following section for more details.) .. _`faq:symhidden`: @@ -192,7 +180,7 @@ How can I create smaller binaries? To do its job, pybind11 extensively relies on a programming technique known as *template metaprogramming*, which is a way of performing computation at compile -time using type information. Template metaprogamming usually instantiates code +time using type information. Template metaprogramming usually instantiates code involving significant numbers of deeply nested types that are either completely removed or reduced to just a few instructions during the compiler's optimization phase. However, due to the nested nature of these types, the resulting symbol @@ -275,17 +263,34 @@ been received, you must either explicitly interrupt execution by throwing }); } +CMake doesn't detect the right Python version +============================================= + +The CMake-based build system will try to automatically detect the installed +version of Python and link against that. When this fails, or when there are +multiple versions of Python and it finds the wrong one, delete +``CMakeCache.txt`` and then add ``-DPYTHON_EXECUTABLE=$(which python)`` to your +CMake configure line. (Replace ``$(which python)`` with a path to python if +your prefer.) + +You can alternatively try ``-DPYBIND11_FINDPYTHON=ON``, which will activate the +new CMake FindPython support instead of pybind11's custom search. Requires +CMake 3.12+, and 3.15+ or 3.18.2+ are even better. You can set this in your +``CMakeLists.txt`` before adding or finding pybind11, as well. + Inconsistent detection of Python version in CMake and pybind11 ============================================================== -The functions ``find_package(PythonInterp)`` and ``find_package(PythonLibs)`` provided by CMake -for Python version detection are not used by pybind11 due to unreliability and limitations that make -them unsuitable for pybind11's needs. Instead pybind provides its own, more reliable Python detection -CMake code. Conflicts can arise, however, when using pybind11 in a project that *also* uses the CMake -Python detection in a system with several Python versions installed. +The functions ``find_package(PythonInterp)`` and ``find_package(PythonLibs)`` +provided by CMake for Python version detection are modified by pybind11 due to +unreliability and limitations that make them unsuitable for pybind11's needs. +Instead pybind11 provides its own, more reliable Python detection CMake code. +Conflicts can arise, however, when using pybind11 in a project that *also* uses +the CMake Python detection in a system with several Python versions installed. -This difference may cause inconsistencies and errors if *both* mechanisms are used in the same project. Consider the following -CMake code executed in a system with Python 2.7 and 3.x installed: +This difference may cause inconsistencies and errors if *both* mechanisms are +used in the same project. Consider the following CMake code executed in a +system with Python 2.7 and 3.x installed: .. code-block:: cmake @@ -303,10 +308,24 @@ In contrast this code: find_package(PythonInterp) find_package(PythonLibs) -will detect Python 3.x for pybind11 and may crash on ``find_package(PythonLibs)`` afterwards. +will detect Python 3.x for pybind11 and may crash on +``find_package(PythonLibs)`` afterwards. -It is advised to avoid using ``find_package(PythonInterp)`` and ``find_package(PythonLibs)`` from CMake and rely -on pybind11 in detecting Python version. If this is not possible CMake machinery should be called *before* including pybind11. +There are three possible solutions: + +1. Avoid using ``find_package(PythonInterp)`` and ``find_package(PythonLibs)`` + from CMake and rely on pybind11 in detecting Python version. If this is not + possible, the CMake machinery should be called *before* including pybind11. +2. Set ``PYBIND11_FINDPYTHON`` to ``True`` or use ``find_package(Python + COMPONENTS Interpreter Development)`` on modern CMake (3.12+, 3.15+ better, + 3.18.2+ best). Pybind11 in these cases uses the new CMake FindPython instead + of the old, deprecated search tools, and these modules are much better at + finding the correct Python. +3. Set ``PYBIND11_NOPYTHON`` to ``TRUE``. Pybind11 will not search for Python. + However, you will have to use the target-based system, and do more setup + yourself, because it does not know about or include things that depend on + Python, like ``pybind11_add_module``. This might be ideal for integrating + into an existing system, like scikit-build's Python helpers. How to cite this project? ========================= diff --git a/pybind11/docs/index.rst b/pybind11/docs/index.rst index d236611b7..4e2e8ca3a 100644 --- a/pybind11/docs/index.rst +++ b/pybind11/docs/index.rst @@ -1,18 +1,17 @@ -.. only: not latex +.. only:: latex - .. image:: pybind11-logo.png + Intro + ===== -pybind11 --- Seamless operability between C++11 and Python -========================================================== +.. include:: readme.rst -.. only: not latex +.. only:: not latex Contents: .. toctree:: :maxdepth: 1 - intro changelog upgrade @@ -20,6 +19,7 @@ pybind11 --- Seamless operability between C++11 and Python :caption: The Basics :maxdepth: 2 + installing basics classes compiling @@ -45,3 +45,4 @@ pybind11 --- Seamless operability between C++11 and Python benchmark limitations reference + cmake/index diff --git a/pybind11/docs/intro.rst b/pybind11/docs/intro.rst deleted file mode 100644 index 10e1799a1..000000000 --- a/pybind11/docs/intro.rst +++ /dev/null @@ -1,93 +0,0 @@ -.. image:: pybind11-logo.png - -About this project -================== -**pybind11** is a lightweight header-only library that exposes C++ types in Python -and vice versa, mainly to create Python bindings of existing C++ code. Its -goals and syntax are similar to the excellent `Boost.Python`_ library by David -Abrahams: to minimize boilerplate code in traditional extension modules by -inferring type information using compile-time introspection. - -.. _Boost.Python: http://www.boost.org/doc/libs/release/libs/python/doc/index.html - -The main issue with Boost.Python—and the reason for creating such a similar -project—is Boost. Boost is an enormously large and complex suite of utility -libraries that works with almost every C++ compiler in existence. This -compatibility has its cost: arcane template tricks and workarounds are -necessary to support the oldest and buggiest of compiler specimens. Now that -C++11-compatible compilers are widely available, this heavy machinery has -become an excessively large and unnecessary dependency. -Think of this library as a tiny self-contained version of Boost.Python with -everything stripped away that isn't relevant for binding generation. Without -comments, the core header files only require ~4K lines of code and depend on -Python (2.7 or 3.x, or PyPy2.7 >= 5.7) and the C++ standard library. This -compact implementation was possible thanks to some of the new C++11 language -features (specifically: tuples, lambda functions and variadic templates). Since -its creation, this library has grown beyond Boost.Python in many ways, leading -to dramatically simpler binding code in many common situations. - -Core features -************* -The following core C++ features can be mapped to Python - -- Functions accepting and returning custom data structures per value, reference, or pointer -- Instance methods and static methods -- Overloaded functions -- Instance attributes and static attributes -- Arbitrary exception types -- Enumerations -- Callbacks -- Iterators and ranges -- Custom operators -- Single and multiple inheritance -- STL data structures -- Smart pointers with reference counting like ``std::shared_ptr`` -- Internal references with correct reference counting -- C++ classes with virtual (and pure virtual) methods can be extended in Python - -Goodies -******* -In addition to the core functionality, pybind11 provides some extra goodies: - -- Python 2.7, 3.x, and PyPy (PyPy2.7 >= 5.7) are supported with an - implementation-agnostic interface. - -- It is possible to bind C++11 lambda functions with captured variables. The - lambda capture data is stored inside the resulting Python function object. - -- pybind11 uses C++11 move constructors and move assignment operators whenever - possible to efficiently transfer custom data types. - -- It's easy to expose the internal storage of custom data types through - Pythons' buffer protocols. This is handy e.g. for fast conversion between - C++ matrix classes like Eigen and NumPy without expensive copy operations. - -- pybind11 can automatically vectorize functions so that they are transparently - applied to all entries of one or more NumPy array arguments. - -- Python's slice-based access and assignment operations can be supported with - just a few lines of code. - -- Everything is contained in just a few header files; there is no need to link - against any additional libraries. - -- Binaries are generally smaller by a factor of at least 2 compared to - equivalent bindings generated by Boost.Python. A recent pybind11 conversion - of `PyRosetta`_, an enormous Boost.Python binding project, reported a binary - size reduction of **5.4x** and compile time reduction by **5.8x**. - -- Function signatures are precomputed at compile time (using ``constexpr``), - leading to smaller binaries. - -- With little extra effort, C++ types can be pickled and unpickled similar to - regular Python objects. - -.. _PyRosetta: http://graylab.jhu.edu/RosettaCon2016/PyRosetta-4.pdf - -Supported compilers -******************* - -1. Clang/LLVM (any non-ancient version with C++11 support) -2. GCC 4.8 or newer -3. Microsoft Visual Studio 2015 or newer -4. Intel C++ compiler v17 or newer (v16 with pybind11 v2.0 and v15 with pybind11 v2.0 and a `workaround `_ ) diff --git a/pybind11/docs/limitations.rst b/pybind11/docs/limitations.rst index 59474f82f..def5ad659 100644 --- a/pybind11/docs/limitations.rst +++ b/pybind11/docs/limitations.rst @@ -1,6 +1,9 @@ Limitations ########### +Design choices +^^^^^^^^^^^^^^ + pybind11 strives to be a general solution to binding generation, but it also has certain limitations: @@ -11,9 +14,59 @@ certain limitations: - The NumPy interface ``pybind11::array`` greatly simplifies accessing numerical data from C++ (and vice versa), but it's not a full-blown array - class like ``Eigen::Array`` or ``boost.multi_array``. + class like ``Eigen::Array`` or ``boost.multi_array``. ``Eigen`` objects are + directly supported, however, with ``pybind11/eigen.h``. -These features could be implemented but would lead to a significant increase in -complexity. I've decided to draw the line here to keep this project simple and -compact. Users who absolutely require these features are encouraged to fork -pybind11. +Large but useful features could be implemented in pybind11 but would lead to a +significant increase in complexity. Pybind11 strives to be simple and compact. +Users who require large new features are encouraged to write an extension to +pybind11; see `pybind11_json `_ for an +example. + + +Known bugs +^^^^^^^^^^ + +These are issues that hopefully will one day be fixed, but currently are +unsolved. If you know how to help with one of these issues, contributions +are welcome! + +- Intel 20.2 is currently having an issue with the test suite. + `#2573 `_ + +- Debug mode Python does not support 1-5 tests in the test suite currently. + `#2422 `_ + +- PyPy3 7.3.1 and 7.3.2 have issues with several tests on 32-bit Windows. + +Known limitations +^^^^^^^^^^^^^^^^^ + +These are issues that are probably solvable, but have not been fixed yet. A +clean, well written patch would likely be accepted to solve them. + +- Type casters are not kept alive recursively. + `#2527 `_ + One consequence is that containers of ``char *`` are currently not supported. + `#2245 `_ + +- The ``cpptest`` does not run on Windows with Python 3.8 or newer, due to DLL + loader changes. User code that is correctly installed should not be affected. + `#2560 `_ + +Python 3.9.0 warning +^^^^^^^^^^^^^^^^^^^^ + +Combining older versions of pybind11 (< 2.6.0) with Python on exactly 3.9.0 +will trigger undefined behavior that typically manifests as crashes during +interpreter shutdown (but could also destroy your data. **You have been +warned**). + +This issue was `fixed in Python `_. +As a mitigation for this bug, pybind11 2.6.0 or newer includes a workaround +specifically when Python 3.9.0 is detected at runtime, leaking about 50 bytes +of memory when a callback function is garbage collected. For reference, the +pybind11 test suite has about 2,000 such callbacks, but only 49 are garbage +collected before the end-of-process. Wheels (even if built with Python 3.9.0) +will correctly avoid the leak when run in Python 3.9.1, and this does not +affect other 3.X versions. diff --git a/pybind11/docs/reference.rst b/pybind11/docs/reference.rst index e3a61afb6..e64a03519 100644 --- a/pybind11/docs/reference.rst +++ b/pybind11/docs/reference.rst @@ -52,6 +52,20 @@ Convenience classes for specific Python types .. doxygengroup:: pytypes :members: +Convenience functions converting to Python types +================================================ + +.. doxygenfunction:: make_tuple(Args&&...) + +.. doxygenfunction:: make_iterator(Iterator, Sentinel, Extra &&...) +.. doxygenfunction:: make_iterator(Type &, Extra&&...) + +.. doxygenfunction:: make_key_iterator(Iterator, Sentinel, Extra &&...) +.. doxygenfunction:: make_key_iterator(Type &, Extra&&...) + +.. doxygenfunction:: make_value_iterator(Iterator, Sentinel, Extra &&...) +.. doxygenfunction:: make_value_iterator(Type &, Extra&&...) + .. _extras: Passing extra arguments to ``def`` or ``class_`` @@ -110,7 +124,6 @@ Exceptions .. doxygenclass:: builtin_exception :members: - Literals ======== diff --git a/pybind11/docs/release.rst b/pybind11/docs/release.rst index 9846f971a..e761cdf7a 100644 --- a/pybind11/docs/release.rst +++ b/pybind11/docs/release.rst @@ -1,21 +1,97 @@ -To release a new version of pybind11: +On version numbers +^^^^^^^^^^^^^^^^^^ -- Update the version number and push to pypi - - Update ``pybind11/_version.py`` (set release version, remove 'dev'). - - Update ``PYBIND11_VERSION_MAJOR`` etc. in ``include/pybind11/detail/common.h``. - - Ensure that all the information in ``setup.py`` is up-to-date. - - Update version in ``docs/conf.py``. - - Tag release date in ``docs/changelog.rst``. - - ``git add`` and ``git commit``. - - if new minor version: ``git checkout -b vX.Y``, ``git push -u origin vX.Y`` +The two version numbers (C++ and Python) must match when combined (checked when +you build the PyPI package), and must be a valid `PEP 440 +`_ version when combined. + +For example: + +.. code-block:: C++ + + #define PYBIND11_VERSION_MAJOR X + #define PYBIND11_VERSION_MINOR Y + #define PYBIND11_VERSION_PATCH Z.dev1 + +For beta, ``PYBIND11_VERSION_PATCH`` should be ``Z.b1``. RC's can be ``Z.rc1``. +Always include the dot (even though PEP 440 allows it to be dropped). For a +final release, this must be a simple integer. There is also a HEX version of +the version just below. + + +To release a new version of pybind11: +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +If you don't have nox, you should either use ``pipx run nox`` instead, or use +``pipx install nox`` or ``brew install nox`` (Unix). + +- Update the version number + - Update ``PYBIND11_VERSION_MAJOR`` etc. in + ``include/pybind11/detail/common.h``. PATCH should be a simple integer. + - Update the version HEX just below, as well. + - Update ``pybind11/_version.py`` (match above) + - Run ``nox -s tests_packaging`` to ensure this was done correctly. + - Ensure that all the information in ``setup.cfg`` is up-to-date, like + supported Python versions. + - Add release date in ``docs/changelog.rst``. + - Check to make sure + `needs-changelog `_ + issues are entered in the changelog (clear the label when done). + - ``git add`` and ``git commit``, ``git push``. **Ensure CI passes**. (If it + fails due to a known flake issue, either ignore or restart CI.) +- Add a release branch if this is a new minor version, or update the existing release branch if it is a patch version + - New branch: ``git checkout -b vX.Y``, ``git push -u origin vX.Y`` + - Update branch: ``git checkout vX.Y``, ``git merge ``, ``git push`` +- Update tags (optional; if you skip this, the GitHub release makes a + non-annotated tag for you) - ``git tag -a vX.Y.Z -m 'vX.Y.Z release'``. - - ``git push`` - ``git push --tags``. - - ``python setup.py sdist upload``. - - ``python setup.py bdist_wheel upload``. +- Update stable + - ``git checkout stable`` + - ``git merge master`` + - ``git push`` +- Make a GitHub release (this shows up in the UI, sends new release + notifications to users watching releases, and also uploads PyPI packages). + (Note: if you do not use an existing tag, this creates a new lightweight tag + for you, so you could skip the above step.) + - GUI method: Under `releases `_ + click "Draft a new release" on the far right, fill in the tag name + (if you didn't tag above, it will be made here), fill in a release name + like "Version X.Y.Z", and copy-and-paste the markdown-formatted (!) changelog + into the description (usually ``cat docs/changelog.rst | pandoc -f rst -t gfm``). + Check "pre-release" if this is a beta/RC. + - CLI method: with ``gh`` installed, run ``gh release create vX.Y.Z -t "Version X.Y.Z"`` + If this is a pre-release, add ``-p``. + - Get back to work - - Update ``_version.py`` (add 'dev' and increment minor). - - Update version in ``docs/conf.py`` - - Update version macros in ``include/pybind11/common.h`` - - ``git add`` and ``git commit``. - ``git push`` + - Make sure you are on master, not somewhere else: ``git checkout master`` + - Update version macros in ``include/pybind11/detail/common.h`` (set PATCH to + ``0.dev1`` and increment MINOR). + - Update ``_version.py`` to match + - Run ``nox -s tests_packaging`` to ensure this was done correctly. + - Add a spot for in-development updates in ``docs/changelog.rst``. + - ``git add``, ``git commit``, ``git push`` + +If a version branch is updated, remember to set PATCH to ``1.dev1``. + +If you'd like to bump homebrew, run: + +.. code-block:: console + + brew bump-formula-pr --url https://github.com/pybind/pybind11/archive/vX.Y.Z.tar.gz + +Conda-forge should automatically make a PR in a few hours, and automatically +merge it if there are no issues. + + +Manual packaging +^^^^^^^^^^^^^^^^ + +If you need to manually upload releases, you can download the releases from the job artifacts and upload them with twine. You can also make the files locally (not recommended in general, as your local directory is more likely to be "dirty" and SDists love picking up random unrelated/hidden files); this is the procedure: + +.. code-block:: bash + + nox -s build + twine upload dist/* + +This makes SDists and wheels, and the final line uploads them. diff --git a/pybind11/docs/requirements.txt b/pybind11/docs/requirements.txt index f4c3dc2e0..b2801b1f0 100644 --- a/pybind11/docs/requirements.txt +++ b/pybind11/docs/requirements.txt @@ -1,5 +1,5 @@ -breathe==4.20.0 -commonmark==0.9.1 -recommonmark==0.6.0 -sphinx==3.2.1 -sphinx_rtd_theme==0.5.0 +breathe==4.31.0 +sphinx==3.5.4 +sphinx_rtd_theme==1.0.0 +sphinxcontrib-moderncmakedomain==3.19 +sphinxcontrib-svg2pdfconverter==1.1.1 diff --git a/pybind11/docs/upgrade.rst b/pybind11/docs/upgrade.rst index 62e2312e9..d91d51e6f 100644 --- a/pybind11/docs/upgrade.rst +++ b/pybind11/docs/upgrade.rst @@ -8,31 +8,90 @@ to a new version. But it goes into more detail. This includes things like deprecated APIs and their replacements, build system changes, general code modernization and other useful information. +.. _upgrade-guide-2.9: + +v2.9 +==== + +* Any usage of the recently added ``py::make_simple_namespace`` should be + converted to using ``py::module_::import("types").attr("SimpleNamespace")`` + instead. + +* The use of ``_`` in custom type casters can now be replaced with the more + readable ``const_name`` instead. The old ``_`` shortcut has been retained + unless it is being used as a macro (like for gettext). + + +.. _upgrade-guide-2.7: + +v2.7 +==== + +*Before* v2.7, ``py::str`` can hold ``PyUnicodeObject`` or ``PyBytesObject``, +and ``py::isinstance()`` is ``true`` for both ``py::str`` and +``py::bytes``. Starting with v2.7, ``py::str`` exclusively holds +``PyUnicodeObject`` (`#2409 `_), +and ``py::isinstance()`` is ``true`` only for ``py::str``. To help in +the transition of user code, the ``PYBIND11_STR_LEGACY_PERMISSIVE`` macro +is provided as an escape hatch to go back to the legacy behavior. This macro +will be removed in future releases. Two types of required fixes are expected +to be common: + +* Accidental use of ``py::str`` instead of ``py::bytes``, masked by the legacy + behavior. These are probably very easy to fix, by changing from + ``py::str`` to ``py::bytes``. + +* Reliance on py::isinstance(obj) being ``true`` for + ``py::bytes``. This is likely to be easy to fix in most cases by adding + ``|| py::isinstance(obj)``, but a fix may be more involved, e.g. if + ``py::isinstance`` appears in a template. Such situations will require + careful review and custom fixes. + + .. _upgrade-guide-2.6: v2.6 ==== -The ``tools/clang`` submodule and ``tools/mkdoc.py`` have been moved to a -standalone package, `pybind11-mkdoc`_. If you were using those tools, please -use them via a pip install from the new location. +Usage of the ``PYBIND11_OVERLOAD*`` macros and ``get_overload`` function should +be replaced by ``PYBIND11_OVERRIDE*`` and ``get_override``. In the future, the +old macros may be deprecated and removed. -.. _pybind11-mkdoc: https://github.com/pybind/pybind11-mkdoc +``py::module`` has been renamed ``py::module_``, but a backward compatible +typedef has been included. This change was to avoid a language change in C++20 +that requires unqualified ``module`` not be placed at the start of a logical +line. Qualified usage is unaffected and the typedef will remain unless the +C++ language rules change again. + +The public constructors of ``py::module_`` have been deprecated. Use +``PYBIND11_MODULE`` or ``module_::create_extension_module`` instead. An error is now thrown when ``__init__`` is forgotten on subclasses. This was incorrect before, but was not checked. Add a call to ``__init__`` if it is missing. +A ``py::type_error`` is now thrown when casting to a subclass (like +``py::bytes`` from ``py::object``) if the conversion is not valid. Make a valid +conversion instead. + The undocumented ``h.get_type()`` method has been deprecated and replaced by ``py::type::of(h)``. +Enums now have a ``__str__`` method pre-defined; if you want to override it, +the simplest fix is to add the new ``py::prepend()`` tag when defining +``"__str__"``. + If ``__eq__`` defined but not ``__hash__``, ``__hash__`` is now set to ``None``, as in normal CPython. You should add ``__hash__`` if you intended the class to be hashable, possibly using the new ``py::hash`` shortcut. -Usage of the ``PYBIND11_OVERLOAD*`` macros and ``get_overload`` function should -be replaced by ``PYBIND11_OVERRIDE*`` and ``get_override``. In the future, the -old macros may be deprecated and removed. +The constructors for ``py::array`` now always take signed integers for size, +for consistency. This may lead to compiler warnings on some systems. Cast to +``py::ssize_t`` instead of ``std::size_t``. + +The ``tools/clang`` submodule and ``tools/mkdoc.py`` have been moved to a +standalone package, `pybind11-mkdoc`_. If you were using those tools, please +use them via a pip install from the new location. The ``pybind11`` package on PyPI no longer fills the wheel "headers" slot - if you were using the headers from this slot, they are available by requesting the @@ -41,6 +100,8 @@ be unaffected, as the ``pybind11/include`` location is reported by ``python -m pybind11 --includes`` and ``pybind11.get_include()`` is still correct and has not changed since 2.5). +.. _pybind11-mkdoc: https://github.com/pybind/pybind11-mkdoc + CMake support: -------------- @@ -54,7 +115,7 @@ something. The changes are: * If you do not request a standard, pybind11 targets will compile with the compiler default, but not less than C++11, instead of forcing C++14 always. - If you depend on the old behavior, please use ``set(CMAKE_CXX_STANDARD 14)`` + If you depend on the old behavior, please use ``set(CMAKE_CXX_STANDARD 14 CACHE STRING "")`` instead. * Direct ``pybind11::module`` usage should always be accompanied by at least @@ -80,7 +141,8 @@ In addition, the following changes may be of interest: * Using ``find_package(Python COMPONENTS Interpreter Development)`` before pybind11 will cause pybind11 to use the new Python mechanisms instead of its own custom search, based on a patched version of classic ``FindPythonInterp`` - / ``FindPythonLibs``. In the future, this may become the default. + / ``FindPythonLibs``. In the future, this may become the default. A recent + (3.15+ or 3.18.2+) version of CMake is recommended. @@ -170,7 +232,7 @@ way to get and set object state. See :ref:`pickling` for details. ... .def(py::pickle( [](const Foo &self) { // __getstate__ - return py::make_tuple(f.value1(), f.value2(), ...); // unchanged + return py::make_tuple(self.value1(), self.value2(), ...); // unchanged }, [](py::tuple t) { // __setstate__, note: no `self` argument return new Foo(t[0].cast(), ...); @@ -234,7 +296,7 @@ Within pybind11's CMake build system, ``pybind11_add_module`` has always been setting the ``-fvisibility=hidden`` flag in release mode. From now on, it's being applied unconditionally, even in debug mode and it can no longer be opted out of with the ``NO_EXTRAS`` option. The ``pybind11::module`` target now also -adds this flag to it's interface. The ``pybind11::embed`` target is unchanged. +adds this flag to its interface. The ``pybind11::embed`` target is unchanged. The most significant change here is for the ``pybind11::module`` target. If you were previously relying on default visibility, i.e. if your Python module was diff --git a/pybind11/include/pybind11/attr.h b/pybind11/include/pybind11/attr.h index d0a8b34b8..f1b66fb80 100644 --- a/pybind11/include/pybind11/attr.h +++ b/pybind11/include/pybind11/attr.h @@ -12,13 +12,17 @@ #include "cast.h" +#include + PYBIND11_NAMESPACE_BEGIN(PYBIND11_NAMESPACE) /// \addtogroup annotations /// @{ /// Annotation for methods -struct is_method { handle class_; is_method(const handle &c) : class_(c) { } }; +struct is_method { handle class_; + explicit is_method(const handle &c) : class_(c) {} +}; /// Annotation for operators struct is_operator { }; @@ -27,16 +31,24 @@ struct is_operator { }; struct is_final { }; /// Annotation for parent scope -struct scope { handle value; scope(const handle &s) : value(s) { } }; +struct scope { handle value; + explicit scope(const handle &s) : value(s) {} +}; /// Annotation for documentation -struct doc { const char *value; doc(const char *value) : value(value) { } }; +struct doc { const char *value; + explicit doc(const char *value) : value(value) {} +}; /// Annotation for function names -struct name { const char *value; name(const char *value) : value(value) { } }; +struct name { const char *value; + explicit name(const char *value) : value(value) {} +}; /// Annotation indicating that a function is an overload associated with a given "sibling" -struct sibling { handle value; sibling(const handle &value) : value(value.ptr()) { } }; +struct sibling { handle value; + explicit sibling(const handle &value) : value(value.ptr()) {} +}; /// Annotation indicating that a class derives from another given type template struct base { @@ -62,18 +74,41 @@ struct metaclass { handle value; PYBIND11_DEPRECATED("py::metaclass() is no longer required. It's turned on by default now.") - metaclass() { } // NOLINT(modernize-use-equals-default): breaks MSVC 2015 when adding an attribute + // NOLINTNEXTLINE(modernize-use-equals-default): breaks MSVC 2015 when adding an attribute + metaclass() {} /// Override pybind11's default metaclass explicit metaclass(handle value) : value(value) { } }; +/// Specifies a custom callback with signature `void (PyHeapTypeObject*)` that +/// may be used to customize the Python type. +/// +/// The callback is invoked immediately before `PyType_Ready`. +/// +/// Note: This is an advanced interface, and uses of it may require changes to +/// work with later versions of pybind11. You may wish to consult the +/// implementation of `make_new_python_type` in `detail/classes.h` to understand +/// the context in which the callback will be run. +struct custom_type_setup { + using callback = std::function; + + explicit custom_type_setup(callback value) : value(std::move(value)) {} + + callback value; +}; + /// Annotation that marks a class as local to the module: -struct module_local { const bool value; constexpr module_local(bool v = true) : value(v) { } }; +struct module_local { const bool value; + constexpr explicit module_local(bool v = true) : value(v) {} +}; /// Annotation to mark enums as an arithmetic type struct arithmetic { }; +/// Mark a function for addition at the beginning of the existing overload chain instead of the end +struct prepend { }; + /** \rst A call policy which places one or more guard variables (``Ts...``) around the function call. @@ -120,7 +155,7 @@ enum op_id : int; enum op_type : int; struct undefined_t; template struct op_; -inline void keep_alive_impl(size_t Nurse, size_t Patient, function_call &call, handle ret); +void keep_alive_impl(size_t Nurse, size_t Patient, function_call &call, handle ret); /// Internal data structure which holds metadata about a keyword argument struct argument_record { @@ -138,8 +173,8 @@ struct argument_record { struct function_record { function_record() : is_constructor(false), is_new_style_constructor(false), is_stateless(false), - is_operator(false), is_method(false), - has_args(false), has_kwargs(false), has_kw_only_args(false) { } + is_operator(false), is_method(false), has_args(false), + has_kwargs(false), prepend(false) { } /// Function name char *name = nullptr; /* why no C++ strings? They generate heavier code.. */ @@ -186,14 +221,15 @@ struct function_record { /// True if the function has a '**kwargs' argument bool has_kwargs : 1; - /// True once a 'py::kw_only' is encountered (any following args are keyword-only) - bool has_kw_only_args : 1; + /// True if this function is to be inserted at the beginning of the overload resolution chain + bool prepend : 1; /// Number of arguments (including py::args and/or py::kwargs, if present) std::uint16_t nargs; - /// Number of trailing arguments (counted in `nargs`) that are keyword-only - std::uint16_t nargs_kw_only = 0; + /// Number of leading positional arguments, which are terminated by a py::args or py::kwargs + /// argument or by a py::kw_only annotation. + std::uint16_t nargs_pos = 0; /// Number of leading arguments (counted in `nargs`) that are positional-only std::uint16_t nargs_pos_only = 0; @@ -253,6 +289,9 @@ struct type_record { /// Custom metaclass (optional) handle metaclass; + /// Custom type setup. + custom_type_setup::callback custom_type_setup_callback; + /// Multiple inheritance marker bool multiple_inheritance : 1; @@ -370,20 +409,23 @@ template <> struct process_attribute : process_attribu static void init(const is_new_style_constructor &, function_record *r) { r->is_new_style_constructor = true; } }; -inline void process_kw_only_arg(const arg &a, function_record *r) { - if (!a.name || strlen(a.name) == 0) - pybind11_fail("arg(): cannot specify an unnamed argument after an kw_only() annotation"); - ++r->nargs_kw_only; +inline void check_kw_only_arg(const arg &a, function_record *r) { + if (r->args.size() > r->nargs_pos && (!a.name || a.name[0] == '\0')) + pybind11_fail("arg(): cannot specify an unnamed argument after a kw_only() annotation or args() argument"); +} + +inline void append_self_arg_if_needed(function_record *r) { + if (r->is_method && r->args.empty()) + r->args.emplace_back("self", nullptr, handle(), /*convert=*/ true, /*none=*/ false); } /// Process a keyword argument attribute (*without* a default value) template <> struct process_attribute : process_attribute_default { static void init(const arg &a, function_record *r) { - if (r->is_method && r->args.empty()) - r->args.emplace_back("self", nullptr, handle(), true /*convert*/, false /*none not allowed*/); + append_self_arg_if_needed(r); r->args.emplace_back(a.name, nullptr, handle(), !a.flag_noconvert, a.flag_none); - if (r->has_kw_only_args) process_kw_only_arg(a, r); + check_kw_only_arg(a, r); } }; @@ -391,7 +433,7 @@ template <> struct process_attribute : process_attribute_default { template <> struct process_attribute : process_attribute_default { static void init(const arg_v &a, function_record *r) { if (r->is_method && r->args.empty()) - r->args.emplace_back("self", nullptr /*descr*/, handle() /*parent*/, true /*convert*/, false /*none not allowed*/); + r->args.emplace_back("self", /*descr=*/ nullptr, /*parent=*/ handle(), /*convert=*/ true, /*none=*/ false); if (!a.value) { #if !defined(NDEBUG) @@ -416,21 +458,28 @@ template <> struct process_attribute : process_attribute_default { } r->args.emplace_back(a.name, a.descr, a.value.inc_ref(), !a.flag_noconvert, a.flag_none); - if (r->has_kw_only_args) process_kw_only_arg(a, r); + check_kw_only_arg(a, r); } }; /// Process a keyword-only-arguments-follow pseudo argument template <> struct process_attribute : process_attribute_default { static void init(const kw_only &, function_record *r) { - r->has_kw_only_args = true; + append_self_arg_if_needed(r); + if (r->has_args && r->nargs_pos != static_cast(r->args.size())) + pybind11_fail("Mismatched args() and kw_only(): they must occur at the same relative argument location (or omit kw_only() entirely)"); + r->nargs_pos = static_cast(r->args.size()); } }; /// Process a positional-only-argument maker template <> struct process_attribute : process_attribute_default { static void init(const pos_only &, function_record *r) { + append_self_arg_if_needed(r); r->nargs_pos_only = static_cast(r->args.size()); + if (r->nargs_pos_only > r->nargs_pos) + pybind11_fail("pos_only(): cannot follow a py::args() argument"); + // It also can't follow a kw_only, but a static_assert in pybind11.h checks that } }; @@ -457,6 +506,13 @@ struct process_attribute : process_attribute_default static void init(const dynamic_attr &, type_record *r) { r->dynamic_attr = true; } }; +template <> +struct process_attribute { + static void init(const custom_type_setup &value, type_record *r) { + r->custom_type_setup_callback = value.value; + } +}; + template <> struct process_attribute : process_attribute_default { static void init(const is_final &, type_record *r) { r->is_final = true; } @@ -477,6 +533,12 @@ struct process_attribute : process_attribute_default static void init(const module_local &l, type_record *r) { r->module_local = l.value; } }; +/// Process a 'prepend' attribute, putting this at the beginning of the overload chain +template <> +struct process_attribute : process_attribute_default { + static void init(const prepend &, function_record *r) { r->prepend = true; } +}; + /// Process an 'arithmetic' attribute for enums (does nothing here) template <> struct process_attribute : process_attribute_default {}; @@ -503,20 +565,31 @@ template struct process_attribute struct process_attributes { static void init(const Args&... args, function_record *r) { - int unused[] = { 0, (process_attribute::type>::init(args, r), 0) ... }; - ignore_unused(unused); + PYBIND11_WORKAROUND_INCORRECT_MSVC_C4100(r); + PYBIND11_WORKAROUND_INCORRECT_GCC_UNUSED_BUT_SET_PARAMETER(r); + using expander = int[]; + (void) expander{ + 0, ((void) process_attribute::type>::init(args, r), 0)...}; } static void init(const Args&... args, type_record *r) { - int unused[] = { 0, (process_attribute::type>::init(args, r), 0) ... }; - ignore_unused(unused); + PYBIND11_WORKAROUND_INCORRECT_MSVC_C4100(r); + PYBIND11_WORKAROUND_INCORRECT_GCC_UNUSED_BUT_SET_PARAMETER(r); + using expander = int[]; + (void) expander{0, + (process_attribute::type>::init(args, r), 0)...}; } static void precall(function_call &call) { - int unused[] = { 0, (process_attribute::type>::precall(call), 0) ... }; - ignore_unused(unused); + PYBIND11_WORKAROUND_INCORRECT_MSVC_C4100(call); + using expander = int[]; + (void) expander{0, + (process_attribute::type>::precall(call), 0)...}; } static void postcall(function_call &call, handle fn_ret) { - int unused[] = { 0, (process_attribute::type>::postcall(call, fn_ret), 0) ... }; - ignore_unused(unused); + PYBIND11_WORKAROUND_INCORRECT_MSVC_C4100(call, fn_ret); + PYBIND11_WORKAROUND_INCORRECT_GCC_UNUSED_BUT_SET_PARAMETER(fn_ret); + using expander = int[]; + (void) expander{ + 0, (process_attribute::type>::postcall(call, fn_ret), 0)...}; } }; @@ -532,7 +605,8 @@ template ::value...), size_t self = constexpr_sum(std::is_same::value...)> constexpr bool expected_num_args(size_t nargs, bool has_args, bool has_kwargs) { - return named == 0 || (self + named + has_args + has_kwargs) == nargs; + PYBIND11_WORKAROUND_INCORRECT_MSVC_C4100(nargs, has_args, has_kwargs); + return named == 0 || (self + named + size_t(has_args) + size_t(has_kwargs)) == nargs; } PYBIND11_NAMESPACE_END(detail) diff --git a/pybind11/include/pybind11/buffer_info.h b/pybind11/include/pybind11/buffer_info.h index 308be06a3..eba68d1aa 100644 --- a/pybind11/include/pybind11/buffer_info.h +++ b/pybind11/include/pybind11/buffer_info.h @@ -13,6 +13,29 @@ PYBIND11_NAMESPACE_BEGIN(PYBIND11_NAMESPACE) +PYBIND11_NAMESPACE_BEGIN(detail) + +// Default, C-style strides +inline std::vector c_strides(const std::vector &shape, ssize_t itemsize) { + auto ndim = shape.size(); + std::vector strides(ndim, itemsize); + if (ndim > 0) + for (size_t i = ndim - 1; i > 0; --i) + strides[i - 1] = strides[i] * shape[i]; + return strides; +} + +// F-style strides; default when constructing an array_t with `ExtraFlags & f_style` +inline std::vector f_strides(const std::vector &shape, ssize_t itemsize) { + auto ndim = shape.size(); + std::vector strides(ndim, itemsize); + for (size_t i = 1; i < ndim; ++i) + strides[i] = strides[i - 1] * shape[i - 1]; + return strides; +} + +PYBIND11_NAMESPACE_END(detail) + /// Information record describing a Python buffer object struct buffer_info { void *ptr = nullptr; // Pointer to the underlying storage @@ -53,7 +76,14 @@ struct buffer_info { explicit buffer_info(Py_buffer *view, bool ownview = true) : buffer_info(view->buf, view->itemsize, view->format, view->ndim, - {view->shape, view->shape + view->ndim}, {view->strides, view->strides + view->ndim}, view->readonly) { + {view->shape, view->shape + view->ndim}, + /* Though buffer::request() requests PyBUF_STRIDES, ctypes objects + * ignore this flag and return a view with NULL strides. + * When strides are NULL, build them manually. */ + view->strides + ? std::vector(view->strides, view->strides + view->ndim) + : detail::c_strides({view->shape, view->shape + view->ndim}, view->itemsize), + (view->readonly != 0)) { this->m_view = view; this->ownview = ownview; } @@ -61,11 +91,9 @@ struct buffer_info { buffer_info(const buffer_info &) = delete; buffer_info& operator=(const buffer_info &) = delete; - buffer_info(buffer_info &&other) { - (*this) = std::move(other); - } + buffer_info(buffer_info &&other) noexcept { (*this) = std::move(other); } - buffer_info& operator=(buffer_info &&rhs) { + buffer_info &operator=(buffer_info &&rhs) noexcept { ptr = rhs.ptr; itemsize = rhs.itemsize; size = rhs.size; diff --git a/pybind11/include/pybind11/cast.h b/pybind11/include/pybind11/cast.h index b071008e6..165102443 100644 --- a/pybind11/include/pybind11/cast.h +++ b/pybind11/include/pybind11/cast.h @@ -11,938 +11,25 @@ #pragma once #include "pytypes.h" -#include "detail/typeid.h" +#include "detail/common.h" #include "detail/descr.h" -#include "detail/internals.h" +#include "detail/type_caster_base.h" +#include "detail/typeid.h" #include -#include +#include +#include +#include +#include +#include +#include #include #include - -#if defined(PYBIND11_CPP17) -# if defined(__has_include) -# if __has_include() -# define PYBIND11_HAS_STRING_VIEW -# endif -# elif defined(_MSC_VER) -# define PYBIND11_HAS_STRING_VIEW -# endif -#endif -#ifdef PYBIND11_HAS_STRING_VIEW -#include -#endif - -#if defined(__cpp_lib_char8_t) && __cpp_lib_char8_t >= 201811L -# define PYBIND11_HAS_U8STRING -#endif +#include +#include PYBIND11_NAMESPACE_BEGIN(PYBIND11_NAMESPACE) PYBIND11_NAMESPACE_BEGIN(detail) -/// A life support system for temporary objects created by `type_caster::load()`. -/// Adding a patient will keep it alive up until the enclosing function returns. -class loader_life_support { -public: - /// A new patient frame is created when a function is entered - loader_life_support() { - get_internals().loader_patient_stack.push_back(nullptr); - } - - /// ... and destroyed after it returns - ~loader_life_support() { - auto &stack = get_internals().loader_patient_stack; - if (stack.empty()) - pybind11_fail("loader_life_support: internal error"); - - auto ptr = stack.back(); - stack.pop_back(); - Py_CLEAR(ptr); - - // A heuristic to reduce the stack's capacity (e.g. after long recursive calls) - if (stack.capacity() > 16 && !stack.empty() && stack.capacity() / stack.size() > 2) - stack.shrink_to_fit(); - } - - /// This can only be used inside a pybind11-bound function, either by `argument_loader` - /// at argument preparation time or by `py::cast()` at execution time. - PYBIND11_NOINLINE static void add_patient(handle h) { - auto &stack = get_internals().loader_patient_stack; - if (stack.empty()) - throw cast_error("When called outside a bound function, py::cast() cannot " - "do Python -> C++ conversions which require the creation " - "of temporary values"); - - auto &list_ptr = stack.back(); - if (list_ptr == nullptr) { - list_ptr = PyList_New(1); - if (!list_ptr) - pybind11_fail("loader_life_support: error allocating list"); - PyList_SET_ITEM(list_ptr, 0, h.inc_ref().ptr()); - } else { - auto result = PyList_Append(list_ptr, h.ptr()); - if (result == -1) - pybind11_fail("loader_life_support: error adding patient"); - } - } -}; - -// Gets the cache entry for the given type, creating it if necessary. The return value is the pair -// returned by emplace, i.e. an iterator for the entry and a bool set to `true` if the entry was -// just created. -inline std::pair all_type_info_get_cache(PyTypeObject *type); - -// Populates a just-created cache entry. -PYBIND11_NOINLINE inline void all_type_info_populate(PyTypeObject *t, std::vector &bases) { - std::vector check; - for (handle parent : reinterpret_borrow(t->tp_bases)) - check.push_back((PyTypeObject *) parent.ptr()); - - auto const &type_dict = get_internals().registered_types_py; - for (size_t i = 0; i < check.size(); i++) { - auto type = check[i]; - // Ignore Python2 old-style class super type: - if (!PyType_Check((PyObject *) type)) continue; - - // Check `type` in the current set of registered python types: - auto it = type_dict.find(type); - if (it != type_dict.end()) { - // We found a cache entry for it, so it's either pybind-registered or has pre-computed - // pybind bases, but we have to make sure we haven't already seen the type(s) before: we - // want to follow Python/virtual C++ rules that there should only be one instance of a - // common base. - for (auto *tinfo : it->second) { - // NB: Could use a second set here, rather than doing a linear search, but since - // having a large number of immediate pybind11-registered types seems fairly - // unlikely, that probably isn't worthwhile. - bool found = false; - for (auto *known : bases) { - if (known == tinfo) { found = true; break; } - } - if (!found) bases.push_back(tinfo); - } - } - else if (type->tp_bases) { - // It's some python type, so keep follow its bases classes to look for one or more - // registered types - if (i + 1 == check.size()) { - // When we're at the end, we can pop off the current element to avoid growing - // `check` when adding just one base (which is typical--i.e. when there is no - // multiple inheritance) - check.pop_back(); - i--; - } - for (handle parent : reinterpret_borrow(type->tp_bases)) - check.push_back((PyTypeObject *) parent.ptr()); - } - } -} - -/** - * Extracts vector of type_info pointers of pybind-registered roots of the given Python type. Will - * be just 1 pybind type for the Python type of a pybind-registered class, or for any Python-side - * derived class that uses single inheritance. Will contain as many types as required for a Python - * class that uses multiple inheritance to inherit (directly or indirectly) from multiple - * pybind-registered classes. Will be empty if neither the type nor any base classes are - * pybind-registered. - * - * The value is cached for the lifetime of the Python type. - */ -inline const std::vector &all_type_info(PyTypeObject *type) { - auto ins = all_type_info_get_cache(type); - if (ins.second) - // New cache entry: populate it - all_type_info_populate(type, ins.first->second); - - return ins.first->second; -} - -/** - * Gets a single pybind11 type info for a python type. Returns nullptr if neither the type nor any - * ancestors are pybind11-registered. Throws an exception if there are multiple bases--use - * `all_type_info` instead if you want to support multiple bases. - */ -PYBIND11_NOINLINE inline detail::type_info* get_type_info(PyTypeObject *type) { - auto &bases = all_type_info(type); - if (bases.empty()) - return nullptr; - if (bases.size() > 1) - pybind11_fail("pybind11::detail::get_type_info: type has multiple pybind11-registered bases"); - return bases.front(); -} - -inline detail::type_info *get_local_type_info(const std::type_index &tp) { - auto &locals = registered_local_types_cpp(); - auto it = locals.find(tp); - if (it != locals.end()) - return it->second; - return nullptr; -} - -inline detail::type_info *get_global_type_info(const std::type_index &tp) { - auto &types = get_internals().registered_types_cpp; - auto it = types.find(tp); - if (it != types.end()) - return it->second; - return nullptr; -} - -/// Return the type info for a given C++ type; on lookup failure can either throw or return nullptr. -PYBIND11_NOINLINE inline detail::type_info *get_type_info(const std::type_index &tp, - bool throw_if_missing = false) { - if (auto ltype = get_local_type_info(tp)) - return ltype; - if (auto gtype = get_global_type_info(tp)) - return gtype; - - if (throw_if_missing) { - std::string tname = tp.name(); - detail::clean_type_id(tname); - pybind11_fail("pybind11::detail::get_type_info: unable to find type info for \"" + tname + "\""); - } - return nullptr; -} - -PYBIND11_NOINLINE inline handle get_type_handle(const std::type_info &tp, bool throw_if_missing) { - detail::type_info *type_info = get_type_info(tp, throw_if_missing); - return handle(type_info ? ((PyObject *) type_info->type) : nullptr); -} - -struct value_and_holder { - instance *inst = nullptr; - size_t index = 0u; - const detail::type_info *type = nullptr; - void **vh = nullptr; - - // Main constructor for a found value/holder: - value_and_holder(instance *i, const detail::type_info *type, size_t vpos, size_t index) : - inst{i}, index{index}, type{type}, - vh{inst->simple_layout ? inst->simple_value_holder : &inst->nonsimple.values_and_holders[vpos]} - {} - - // Default constructor (used to signal a value-and-holder not found by get_value_and_holder()) - value_and_holder() = default; - - // Used for past-the-end iterator - value_and_holder(size_t index) : index{index} {} - - template V *&value_ptr() const { - return reinterpret_cast(vh[0]); - } - // True if this `value_and_holder` has a non-null value pointer - explicit operator bool() const { return value_ptr(); } - - template H &holder() const { - return reinterpret_cast(vh[1]); - } - bool holder_constructed() const { - return inst->simple_layout - ? inst->simple_holder_constructed - : inst->nonsimple.status[index] & instance::status_holder_constructed; - } - void set_holder_constructed(bool v = true) { - if (inst->simple_layout) - inst->simple_holder_constructed = v; - else if (v) - inst->nonsimple.status[index] |= instance::status_holder_constructed; - else - inst->nonsimple.status[index] &= (uint8_t) ~instance::status_holder_constructed; - } - bool instance_registered() const { - return inst->simple_layout - ? inst->simple_instance_registered - : inst->nonsimple.status[index] & instance::status_instance_registered; - } - void set_instance_registered(bool v = true) { - if (inst->simple_layout) - inst->simple_instance_registered = v; - else if (v) - inst->nonsimple.status[index] |= instance::status_instance_registered; - else - inst->nonsimple.status[index] &= (uint8_t) ~instance::status_instance_registered; - } -}; - -// Container for accessing and iterating over an instance's values/holders -struct values_and_holders { -private: - instance *inst; - using type_vec = std::vector; - const type_vec &tinfo; - -public: - values_and_holders(instance *inst) : inst{inst}, tinfo(all_type_info(Py_TYPE(inst))) {} - - struct iterator { - private: - instance *inst = nullptr; - const type_vec *types = nullptr; - value_and_holder curr; - friend struct values_and_holders; - iterator(instance *inst, const type_vec *tinfo) - : inst{inst}, types{tinfo}, - curr(inst /* instance */, - types->empty() ? nullptr : (*types)[0] /* type info */, - 0, /* vpos: (non-simple types only): the first vptr comes first */ - 0 /* index */) - {} - // Past-the-end iterator: - iterator(size_t end) : curr(end) {} - public: - bool operator==(const iterator &other) const { return curr.index == other.curr.index; } - bool operator!=(const iterator &other) const { return curr.index != other.curr.index; } - iterator &operator++() { - if (!inst->simple_layout) - curr.vh += 1 + (*types)[curr.index]->holder_size_in_ptrs; - ++curr.index; - curr.type = curr.index < types->size() ? (*types)[curr.index] : nullptr; - return *this; - } - value_and_holder &operator*() { return curr; } - value_and_holder *operator->() { return &curr; } - }; - - iterator begin() { return iterator(inst, &tinfo); } - iterator end() { return iterator(tinfo.size()); } - - iterator find(const type_info *find_type) { - auto it = begin(), endit = end(); - while (it != endit && it->type != find_type) ++it; - return it; - } - - size_t size() { return tinfo.size(); } -}; - -/** - * Extracts C++ value and holder pointer references from an instance (which may contain multiple - * values/holders for python-side multiple inheritance) that match the given type. Throws an error - * if the given type (or ValueType, if omitted) is not a pybind11 base of the given instance. If - * `find_type` is omitted (or explicitly specified as nullptr) the first value/holder are returned, - * regardless of type (and the resulting .type will be nullptr). - * - * The returned object should be short-lived: in particular, it must not outlive the called-upon - * instance. - */ -PYBIND11_NOINLINE inline value_and_holder instance::get_value_and_holder(const type_info *find_type /*= nullptr default in common.h*/, bool throw_if_missing /*= true in common.h*/) { - // Optimize common case: - if (!find_type || Py_TYPE(this) == find_type->type) - return value_and_holder(this, find_type, 0, 0); - - detail::values_and_holders vhs(this); - auto it = vhs.find(find_type); - if (it != vhs.end()) - return *it; - - if (!throw_if_missing) - return value_and_holder(); - -#if defined(NDEBUG) - pybind11_fail("pybind11::detail::instance::get_value_and_holder: " - "type is not a pybind11 base of the given instance " - "(compile in debug mode for type details)"); -#else - pybind11_fail("pybind11::detail::instance::get_value_and_holder: `" + - std::string(find_type->type->tp_name) + "' is not a pybind11 base of the given `" + - std::string(Py_TYPE(this)->tp_name) + "' instance"); -#endif -} - -PYBIND11_NOINLINE inline void instance::allocate_layout() { - auto &tinfo = all_type_info(Py_TYPE(this)); - - const size_t n_types = tinfo.size(); - - if (n_types == 0) - pybind11_fail("instance allocation failed: new instance has no pybind11-registered base types"); - - simple_layout = - n_types == 1 && tinfo.front()->holder_size_in_ptrs <= instance_simple_holder_in_ptrs(); - - // Simple path: no python-side multiple inheritance, and a small-enough holder - if (simple_layout) { - simple_value_holder[0] = nullptr; - simple_holder_constructed = false; - simple_instance_registered = false; - } - else { // multiple base types or a too-large holder - // Allocate space to hold: [v1*][h1][v2*][h2]...[bb...] where [vN*] is a value pointer, - // [hN] is the (uninitialized) holder instance for value N, and [bb...] is a set of bool - // values that tracks whether each associated holder has been initialized. Each [block] is - // padded, if necessary, to an integer multiple of sizeof(void *). - size_t space = 0; - for (auto t : tinfo) { - space += 1; // value pointer - space += t->holder_size_in_ptrs; // holder instance - } - size_t flags_at = space; - space += size_in_ptrs(n_types); // status bytes (holder_constructed and instance_registered) - - // Allocate space for flags, values, and holders, and initialize it to 0 (flags and values, - // in particular, need to be 0). Use Python's memory allocation functions: in Python 3.6 - // they default to using pymalloc, which is designed to be efficient for small allocations - // like the one we're doing here; in earlier versions (and for larger allocations) they are - // just wrappers around malloc. -#if PY_VERSION_HEX >= 0x03050000 - nonsimple.values_and_holders = (void **) PyMem_Calloc(space, sizeof(void *)); - if (!nonsimple.values_and_holders) throw std::bad_alloc(); -#else - nonsimple.values_and_holders = (void **) PyMem_New(void *, space); - if (!nonsimple.values_and_holders) throw std::bad_alloc(); - std::memset(nonsimple.values_and_holders, 0, space * sizeof(void *)); -#endif - nonsimple.status = reinterpret_cast(&nonsimple.values_and_holders[flags_at]); - } - owned = true; -} - -PYBIND11_NOINLINE inline void instance::deallocate_layout() { - if (!simple_layout) - PyMem_Free(nonsimple.values_and_holders); -} - -PYBIND11_NOINLINE inline bool isinstance_generic(handle obj, const std::type_info &tp) { - handle type = detail::get_type_handle(tp, false); - if (!type) - return false; - return isinstance(obj, type); -} - -PYBIND11_NOINLINE inline std::string error_string() { - if (!PyErr_Occurred()) { - PyErr_SetString(PyExc_RuntimeError, "Unknown internal error occurred"); - return "Unknown internal error occurred"; - } - - error_scope scope; // Preserve error state - - std::string errorString; - if (scope.type) { - errorString += handle(scope.type).attr("__name__").cast(); - errorString += ": "; - } - if (scope.value) - errorString += (std::string) str(scope.value); - - PyErr_NormalizeException(&scope.type, &scope.value, &scope.trace); - -#if PY_MAJOR_VERSION >= 3 - if (scope.trace != nullptr) - PyException_SetTraceback(scope.value, scope.trace); -#endif - -#if !defined(PYPY_VERSION) - if (scope.trace) { - auto *trace = (PyTracebackObject *) scope.trace; - - /* Get the deepest trace possible */ - while (trace->tb_next) - trace = trace->tb_next; - - PyFrameObject *frame = trace->tb_frame; - errorString += "\n\nAt:\n"; - while (frame) { - int lineno = PyFrame_GetLineNumber(frame); - errorString += - " " + handle(frame->f_code->co_filename).cast() + - "(" + std::to_string(lineno) + "): " + - handle(frame->f_code->co_name).cast() + "\n"; - frame = frame->f_back; - } - } -#endif - - return errorString; -} - -PYBIND11_NOINLINE inline handle get_object_handle(const void *ptr, const detail::type_info *type ) { - auto &instances = get_internals().registered_instances; - auto range = instances.equal_range(ptr); - for (auto it = range.first; it != range.second; ++it) { - for (const auto &vh : values_and_holders(it->second)) { - if (vh.type == type) - return handle((PyObject *) it->second); - } - } - return handle(); -} - -inline PyThreadState *get_thread_state_unchecked() { -#if defined(PYPY_VERSION) - return PyThreadState_GET(); -#elif PY_VERSION_HEX < 0x03000000 - return _PyThreadState_Current; -#elif PY_VERSION_HEX < 0x03050000 - return (PyThreadState*) _Py_atomic_load_relaxed(&_PyThreadState_Current); -#elif PY_VERSION_HEX < 0x03050200 - return (PyThreadState*) _PyThreadState_Current.value; -#else - return _PyThreadState_UncheckedGet(); -#endif -} - -// Forward declarations -inline void keep_alive_impl(handle nurse, handle patient); -inline PyObject *make_new_instance(PyTypeObject *type); - -class type_caster_generic { -public: - PYBIND11_NOINLINE type_caster_generic(const std::type_info &type_info) - : typeinfo(get_type_info(type_info)), cpptype(&type_info) { } - - type_caster_generic(const type_info *typeinfo) - : typeinfo(typeinfo), cpptype(typeinfo ? typeinfo->cpptype : nullptr) { } - - bool load(handle src, bool convert) { - return load_impl(src, convert); - } - - PYBIND11_NOINLINE static handle cast(const void *_src, return_value_policy policy, handle parent, - const detail::type_info *tinfo, - void *(*copy_constructor)(const void *), - void *(*move_constructor)(const void *), - const void *existing_holder = nullptr) { - if (!tinfo) // no type info: error will be set already - return handle(); - - void *src = const_cast(_src); - if (src == nullptr) - return none().release(); - - auto it_instances = get_internals().registered_instances.equal_range(src); - for (auto it_i = it_instances.first; it_i != it_instances.second; ++it_i) { - for (auto instance_type : detail::all_type_info(Py_TYPE(it_i->second))) { - if (instance_type && same_type(*instance_type->cpptype, *tinfo->cpptype)) - return handle((PyObject *) it_i->second).inc_ref(); - } - } - - auto inst = reinterpret_steal(make_new_instance(tinfo->type)); - auto wrapper = reinterpret_cast(inst.ptr()); - wrapper->owned = false; - void *&valueptr = values_and_holders(wrapper).begin()->value_ptr(); - - switch (policy) { - case return_value_policy::automatic: - case return_value_policy::take_ownership: - valueptr = src; - wrapper->owned = true; - break; - - case return_value_policy::automatic_reference: - case return_value_policy::reference: - valueptr = src; - wrapper->owned = false; - break; - - case return_value_policy::copy: - if (copy_constructor) - valueptr = copy_constructor(src); - else { -#if defined(NDEBUG) - throw cast_error("return_value_policy = copy, but type is " - "non-copyable! (compile in debug mode for details)"); -#else - std::string type_name(tinfo->cpptype->name()); - detail::clean_type_id(type_name); - throw cast_error("return_value_policy = copy, but type " + - type_name + " is non-copyable!"); -#endif - } - wrapper->owned = true; - break; - - case return_value_policy::move: - if (move_constructor) - valueptr = move_constructor(src); - else if (copy_constructor) - valueptr = copy_constructor(src); - else { -#if defined(NDEBUG) - throw cast_error("return_value_policy = move, but type is neither " - "movable nor copyable! " - "(compile in debug mode for details)"); -#else - std::string type_name(tinfo->cpptype->name()); - detail::clean_type_id(type_name); - throw cast_error("return_value_policy = move, but type " + - type_name + " is neither movable nor copyable!"); -#endif - } - wrapper->owned = true; - break; - - case return_value_policy::reference_internal: - valueptr = src; - wrapper->owned = false; - keep_alive_impl(inst, parent); - break; - - default: - throw cast_error("unhandled return_value_policy: should not happen!"); - } - - tinfo->init_instance(wrapper, existing_holder); - - return inst.release(); - } - - // Base methods for generic caster; there are overridden in copyable_holder_caster - void load_value(value_and_holder &&v_h) { - auto *&vptr = v_h.value_ptr(); - // Lazy allocation for unallocated values: - if (vptr == nullptr) { - auto *type = v_h.type ? v_h.type : typeinfo; - if (type->operator_new) { - vptr = type->operator_new(type->type_size); - } else { - #if defined(__cpp_aligned_new) && (!defined(_MSC_VER) || _MSC_VER >= 1912) - if (type->type_align > __STDCPP_DEFAULT_NEW_ALIGNMENT__) - vptr = ::operator new(type->type_size, - std::align_val_t(type->type_align)); - else - #endif - vptr = ::operator new(type->type_size); - } - } - value = vptr; - } - bool try_implicit_casts(handle src, bool convert) { - for (auto &cast : typeinfo->implicit_casts) { - type_caster_generic sub_caster(*cast.first); - if (sub_caster.load(src, convert)) { - value = cast.second(sub_caster.value); - return true; - } - } - return false; - } - bool try_direct_conversions(handle src) { - for (auto &converter : *typeinfo->direct_conversions) { - if (converter(src.ptr(), value)) - return true; - } - return false; - } - void check_holder_compat() {} - - PYBIND11_NOINLINE static void *local_load(PyObject *src, const type_info *ti) { - auto caster = type_caster_generic(ti); - if (caster.load(src, false)) - return caster.value; - return nullptr; - } - - /// Try to load with foreign typeinfo, if available. Used when there is no - /// native typeinfo, or when the native one wasn't able to produce a value. - PYBIND11_NOINLINE bool try_load_foreign_module_local(handle src) { - constexpr auto *local_key = PYBIND11_MODULE_LOCAL_ID; - const auto pytype = type::handle_of(src); - if (!hasattr(pytype, local_key)) - return false; - - type_info *foreign_typeinfo = reinterpret_borrow(getattr(pytype, local_key)); - // Only consider this foreign loader if actually foreign and is a loader of the correct cpp type - if (foreign_typeinfo->module_local_load == &local_load - || (cpptype && !same_type(*cpptype, *foreign_typeinfo->cpptype))) - return false; - - if (auto result = foreign_typeinfo->module_local_load(src.ptr(), foreign_typeinfo)) { - value = result; - return true; - } - return false; - } - - // Implementation of `load`; this takes the type of `this` so that it can dispatch the relevant - // bits of code between here and copyable_holder_caster where the two classes need different - // logic (without having to resort to virtual inheritance). - template - PYBIND11_NOINLINE bool load_impl(handle src, bool convert) { - if (!src) return false; - if (!typeinfo) return try_load_foreign_module_local(src); - if (src.is_none()) { - // Defer accepting None to other overloads (if we aren't in convert mode): - if (!convert) return false; - value = nullptr; - return true; - } - - auto &this_ = static_cast(*this); - this_.check_holder_compat(); - - PyTypeObject *srctype = Py_TYPE(src.ptr()); - - // Case 1: If src is an exact type match for the target type then we can reinterpret_cast - // the instance's value pointer to the target type: - if (srctype == typeinfo->type) { - this_.load_value(reinterpret_cast(src.ptr())->get_value_and_holder()); - return true; - } - // Case 2: We have a derived class - else if (PyType_IsSubtype(srctype, typeinfo->type)) { - auto &bases = all_type_info(srctype); - bool no_cpp_mi = typeinfo->simple_type; - - // Case 2a: the python type is a Python-inherited derived class that inherits from just - // one simple (no MI) pybind11 class, or is an exact match, so the C++ instance is of - // the right type and we can use reinterpret_cast. - // (This is essentially the same as case 2b, but because not using multiple inheritance - // is extremely common, we handle it specially to avoid the loop iterator and type - // pointer lookup overhead) - if (bases.size() == 1 && (no_cpp_mi || bases.front()->type == typeinfo->type)) { - this_.load_value(reinterpret_cast(src.ptr())->get_value_and_holder()); - return true; - } - // Case 2b: the python type inherits from multiple C++ bases. Check the bases to see if - // we can find an exact match (or, for a simple C++ type, an inherited match); if so, we - // can safely reinterpret_cast to the relevant pointer. - else if (bases.size() > 1) { - for (auto base : bases) { - if (no_cpp_mi ? PyType_IsSubtype(base->type, typeinfo->type) : base->type == typeinfo->type) { - this_.load_value(reinterpret_cast(src.ptr())->get_value_and_holder(base)); - return true; - } - } - } - - // Case 2c: C++ multiple inheritance is involved and we couldn't find an exact type match - // in the registered bases, above, so try implicit casting (needed for proper C++ casting - // when MI is involved). - if (this_.try_implicit_casts(src, convert)) - return true; - } - - // Perform an implicit conversion - if (convert) { - for (auto &converter : typeinfo->implicit_conversions) { - auto temp = reinterpret_steal(converter(src.ptr(), typeinfo->type)); - if (load_impl(temp, false)) { - loader_life_support::add_patient(temp); - return true; - } - } - if (this_.try_direct_conversions(src)) - return true; - } - - // Failed to match local typeinfo. Try again with global. - if (typeinfo->module_local) { - if (auto gtype = get_global_type_info(*typeinfo->cpptype)) { - typeinfo = gtype; - return load(src, false); - } - } - - // Global typeinfo has precedence over foreign module_local - return try_load_foreign_module_local(src); - } - - - // Called to do type lookup and wrap the pointer and type in a pair when a dynamic_cast - // isn't needed or can't be used. If the type is unknown, sets the error and returns a pair - // with .second = nullptr. (p.first = nullptr is not an error: it becomes None). - PYBIND11_NOINLINE static std::pair src_and_type( - const void *src, const std::type_info &cast_type, const std::type_info *rtti_type = nullptr) { - if (auto *tpi = get_type_info(cast_type)) - return {src, const_cast(tpi)}; - - // Not found, set error: - std::string tname = rtti_type ? rtti_type->name() : cast_type.name(); - detail::clean_type_id(tname); - std::string msg = "Unregistered type : " + tname; - PyErr_SetString(PyExc_TypeError, msg.c_str()); - return {nullptr, nullptr}; - } - - const type_info *typeinfo = nullptr; - const std::type_info *cpptype = nullptr; - void *value = nullptr; -}; - -/** - * Determine suitable casting operator for pointer-or-lvalue-casting type casters. The type caster - * needs to provide `operator T*()` and `operator T&()` operators. - * - * If the type supports moving the value away via an `operator T&&() &&` method, it should use - * `movable_cast_op_type` instead. - */ -template -using cast_op_type = - conditional_t>::value, - typename std::add_pointer>::type, - typename std::add_lvalue_reference>::type>; - -/** - * Determine suitable casting operator for a type caster with a movable value. Such a type caster - * needs to provide `operator T*()`, `operator T&()`, and `operator T&&() &&`. The latter will be - * called in appropriate contexts where the value can be moved rather than copied. - * - * These operator are automatically provided when using the PYBIND11_TYPE_CASTER macro. - */ -template -using movable_cast_op_type = - conditional_t::type>::value, - typename std::add_pointer>::type, - conditional_t::value, - typename std::add_rvalue_reference>::type, - typename std::add_lvalue_reference>::type>>; - -// std::is_copy_constructible isn't quite enough: it lets std::vector (and similar) through when -// T is non-copyable, but code containing such a copy constructor fails to actually compile. -template struct is_copy_constructible : std::is_copy_constructible {}; - -// Specialization for types that appear to be copy constructible but also look like stl containers -// (we specifically check for: has `value_type` and `reference` with `reference = value_type&`): if -// so, copy constructability depends on whether the value_type is copy constructible. -template struct is_copy_constructible, - std::is_same, - // Avoid infinite recursion - negation> - >::value>> : is_copy_constructible {}; - -// Likewise for std::pair -// (after C++17 it is mandatory that the copy constructor not exist when the two types aren't themselves -// copy constructible, but this can not be relied upon when T1 or T2 are themselves containers). -template struct is_copy_constructible> - : all_of, is_copy_constructible> {}; - -// The same problems arise with std::is_copy_assignable, so we use the same workaround. -template struct is_copy_assignable : std::is_copy_assignable {}; -template struct is_copy_assignable, - std::is_same - >::value>> : is_copy_assignable {}; -template struct is_copy_assignable> - : all_of, is_copy_assignable> {}; - -PYBIND11_NAMESPACE_END(detail) - -// polymorphic_type_hook::get(src, tinfo) determines whether the object pointed -// to by `src` actually is an instance of some class derived from `itype`. -// If so, it sets `tinfo` to point to the std::type_info representing that derived -// type, and returns a pointer to the start of the most-derived object of that type -// (in which `src` is a subobject; this will be the same address as `src` in most -// single inheritance cases). If not, or if `src` is nullptr, it simply returns `src` -// and leaves `tinfo` at its default value of nullptr. -// -// The default polymorphic_type_hook just returns src. A specialization for polymorphic -// types determines the runtime type of the passed object and adjusts the this-pointer -// appropriately via dynamic_cast. This is what enables a C++ Animal* to appear -// to Python as a Dog (if Dog inherits from Animal, Animal is polymorphic, Dog is -// registered with pybind11, and this Animal is in fact a Dog). -// -// You may specialize polymorphic_type_hook yourself for types that want to appear -// polymorphic to Python but do not use C++ RTTI. (This is a not uncommon pattern -// in performance-sensitive applications, used most notably in LLVM.) -// -// polymorphic_type_hook_base allows users to specialize polymorphic_type_hook with -// std::enable_if. User provided specializations will always have higher priority than -// the default implementation and specialization provided in polymorphic_type_hook_base. -template -struct polymorphic_type_hook_base -{ - static const void *get(const itype *src, const std::type_info*&) { return src; } -}; -template -struct polymorphic_type_hook_base::value>> -{ - static const void *get(const itype *src, const std::type_info*& type) { - type = src ? &typeid(*src) : nullptr; - return dynamic_cast(src); - } -}; -template -struct polymorphic_type_hook : public polymorphic_type_hook_base {}; - -PYBIND11_NAMESPACE_BEGIN(detail) - -/// Generic type caster for objects stored on the heap -template class type_caster_base : public type_caster_generic { - using itype = intrinsic_t; - -public: - static constexpr auto name = _(); - - type_caster_base() : type_caster_base(typeid(type)) { } - explicit type_caster_base(const std::type_info &info) : type_caster_generic(info) { } - - static handle cast(const itype &src, return_value_policy policy, handle parent) { - if (policy == return_value_policy::automatic || policy == return_value_policy::automatic_reference) - policy = return_value_policy::copy; - return cast(&src, policy, parent); - } - - static handle cast(itype &&src, return_value_policy, handle parent) { - return cast(&src, return_value_policy::move, parent); - } - - // Returns a (pointer, type_info) pair taking care of necessary type lookup for a - // polymorphic type (using RTTI by default, but can be overridden by specializing - // polymorphic_type_hook). If the instance isn't derived, returns the base version. - static std::pair src_and_type(const itype *src) { - auto &cast_type = typeid(itype); - const std::type_info *instance_type = nullptr; - const void *vsrc = polymorphic_type_hook::get(src, instance_type); - if (instance_type && !same_type(cast_type, *instance_type)) { - // This is a base pointer to a derived type. If the derived type is registered - // with pybind11, we want to make the full derived object available. - // In the typical case where itype is polymorphic, we get the correct - // derived pointer (which may be != base pointer) by a dynamic_cast to - // most derived type. If itype is not polymorphic, we won't get here - // except via a user-provided specialization of polymorphic_type_hook, - // and the user has promised that no this-pointer adjustment is - // required in that case, so it's OK to use static_cast. - if (const auto *tpi = get_type_info(*instance_type)) - return {vsrc, tpi}; - } - // Otherwise we have either a nullptr, an `itype` pointer, or an unknown derived pointer, so - // don't do a cast - return type_caster_generic::src_and_type(src, cast_type, instance_type); - } - - static handle cast(const itype *src, return_value_policy policy, handle parent) { - auto st = src_and_type(src); - return type_caster_generic::cast( - st.first, policy, parent, st.second, - make_copy_constructor(src), make_move_constructor(src)); - } - - static handle cast_holder(const itype *src, const void *holder) { - auto st = src_and_type(src); - return type_caster_generic::cast( - st.first, return_value_policy::take_ownership, {}, st.second, - nullptr, nullptr, holder); - } - - template using cast_op_type = detail::cast_op_type; - - operator itype*() { return (type *) value; } - operator itype&() { if (!value) throw reference_cast_error(); return *((itype *) value); } - -protected: - using Constructor = void *(*)(const void *); - - /* Only enabled when the types are {copy,move}-constructible *and* when the type - does not have a private operator new implementation. */ - template ::value>> - static auto make_copy_constructor(const T *x) -> decltype(new T(*x), Constructor{}) { - return [](const void *arg) -> void * { - return new T(*reinterpret_cast(arg)); - }; - } - - template ::value>> - static auto make_move_constructor(const T *x) -> decltype(new T(std::move(*const_cast(x))), Constructor{}) { - return [](const void *arg) -> void * { - return new T(std::move(*const_cast(reinterpret_cast(arg)))); - }; - } - - static Constructor make_copy_constructor(...) { return nullptr; } - static Constructor make_move_constructor(...) { return nullptr; } -}; - template class type_caster : public type_caster_base { }; template using make_caster = type_caster>; @@ -960,9 +47,14 @@ template class type_caster> { private: using caster_t = make_caster; caster_t subcaster; - using subcaster_cast_op_type = typename caster_t::template cast_op_type; - static_assert(std::is_same::type &, subcaster_cast_op_type>::value, - "std::reference_wrapper caster requires T to have a caster with an `T &` operator"); + using reference_t = type&; + using subcaster_cast_op_type = + typename caster_t::template cast_op_type; + + static_assert(std::is_same::type &, subcaster_cast_op_type>::value || + std::is_same::value, + "std::reference_wrapper caster requires T to have a caster with an " + "`operator T &()` or `operator const T &()`"); public: bool load(handle src, bool convert) { return subcaster.load(src, convert); } static constexpr auto name = caster_t::name; @@ -973,28 +65,31 @@ public: return caster_t::cast(&src.get(), policy, parent); } template using cast_op_type = std::reference_wrapper; - operator std::reference_wrapper() { return subcaster.operator subcaster_cast_op_type&(); } + explicit operator std::reference_wrapper() { return cast_op(subcaster); } }; -#define PYBIND11_TYPE_CASTER(type, py_name) \ - protected: \ - type value; \ - public: \ - static constexpr auto name = py_name; \ - template >::value, int> = 0> \ - static handle cast(T_ *src, return_value_policy policy, handle parent) { \ - if (!src) return none().release(); \ - if (policy == return_value_policy::take_ownership) { \ - auto h = cast(std::move(*src), policy, parent); delete src; return h; \ - } else { \ - return cast(*src, policy, parent); \ - } \ - } \ - operator type*() { return &value; } \ - operator type&() { return value; } \ - operator type&&() && { return std::move(value); } \ - template using cast_op_type = pybind11::detail::movable_cast_op_type - +#define PYBIND11_TYPE_CASTER(type, py_name) \ +protected: \ + type value; \ + \ +public: \ + static constexpr auto name = py_name; \ + template >::value, int> = 0> \ + static handle cast(T_ *src, return_value_policy policy, handle parent) { \ + if (!src) \ + return none().release(); \ + if (policy == return_value_policy::take_ownership) { \ + auto h = cast(std::move(*src), policy, parent); \ + delete src; \ + return h; \ + } \ + return cast(*src, policy, parent); \ + } \ + operator type *() { return &value; } /* NOLINT(bugprone-macro-parentheses) */ \ + operator type &() { return value; } /* NOLINT(bugprone-macro-parentheses) */ \ + operator type &&() && { return std::move(value); } /* NOLINT(bugprone-macro-parentheses) */ \ + template \ + using cast_op_type = pybind11::detail::movable_cast_op_type template using is_std_char_type = any_of< std::is_same, /* std::string */ @@ -1020,19 +115,46 @@ public: if (!src) return false; +#if !defined(PYPY_VERSION) + auto index_check = [](PyObject *o) { return PyIndex_Check(o); }; +#else + // In PyPy 7.3.3, `PyIndex_Check` is implemented by calling `__index__`, + // while CPython only considers the existence of `nb_index`/`__index__`. + auto index_check = [](PyObject *o) { return hasattr(o, "__index__"); }; +#endif + if (std::is_floating_point::value) { if (convert || PyFloat_Check(src.ptr())) py_value = (py_type) PyFloat_AsDouble(src.ptr()); else return false; - } else if (PyFloat_Check(src.ptr())) { + } else if (PyFloat_Check(src.ptr()) + || (!convert && !PYBIND11_LONG_CHECK(src.ptr()) && !index_check(src.ptr()))) { return false; - } else if (std::is_unsigned::value) { - py_value = as_unsigned(src.ptr()); - } else { // signed integer: - py_value = sizeof(T) <= sizeof(long) - ? (py_type) PyLong_AsLong(src.ptr()) - : (py_type) PYBIND11_LONG_AS_LONGLONG(src.ptr()); + } else { + handle src_or_index = src; + // PyPy: 7.3.7's 3.8 does not implement PyLong_*'s __index__ calls. +#if PY_VERSION_HEX < 0x03080000 || defined(PYPY_VERSION) + object index; + if (!PYBIND11_LONG_CHECK(src.ptr())) { // So: index_check(src.ptr()) + index = reinterpret_steal(PyNumber_Index(src.ptr())); + if (!index) { + PyErr_Clear(); + if (!convert) + return false; + } + else { + src_or_index = index; + } + } +#endif + if (std::is_unsigned::value) { + py_value = as_unsigned(src_or_index.ptr()); + } else { // signed integer: + py_value = sizeof(T) <= sizeof(long) + ? (py_type) PyLong_AsLong(src_or_index.ptr()) + : (py_type) PYBIND11_LONG_AS_LONGLONG(src_or_index.ptr()); + } } // Python API reported an error @@ -1041,15 +163,8 @@ public: // Check to see if the conversion is valid (integers should match exactly) // Signed/unsigned checks happen elsewhere if (py_err || (std::is_integral::value && sizeof(py_type) != sizeof(T) && py_value != (py_type) (T) py_value)) { - bool type_error = py_err && PyErr_ExceptionMatches( -#if PY_VERSION_HEX < 0x03000000 && !defined(PYPY_VERSION) - PyExc_SystemError -#else - PyExc_TypeError -#endif - ); PyErr_Clear(); - if (type_error && convert && PyNumber_Check(src.ptr())) { + if (py_err && convert && (PyNumber_Check(src.ptr()) != 0)) { auto tmp = reinterpret_steal(std::is_floating_point::value ? PyNumber_Float(src.ptr()) : PyNumber_Long(src.ptr())); @@ -1093,7 +208,7 @@ public: return PyLong_FromUnsignedLongLong((unsigned long long) src); } - PYBIND11_TYPE_CASTER(T, _::value>("int", "float")); + PYBIND11_TYPE_CASTER(T, const_name::value>("int", "float")); }; template struct void_caster { @@ -1106,7 +221,7 @@ public: static handle cast(T, return_value_policy /* policy */, handle /* parent */) { return none().inc_ref(); } - PYBIND11_TYPE_CASTER(T, _("None")); + PYBIND11_TYPE_CASTER(T, const_name("None")); }; template <> class type_caster : public void_caster {}; @@ -1118,7 +233,8 @@ public: bool load(handle h, bool) { if (!h) { return false; - } else if (h.is_none()) { + } + if (h.is_none()) { value = nullptr; return true; } @@ -1143,13 +259,12 @@ public: static handle cast(const void *ptr, return_value_policy /* policy */, handle /* parent */) { if (ptr) return capsule(ptr).release(); - else - return none().inc_ref(); + return none().inc_ref(); } template using cast_op_type = void*&; - operator void *&() { return value; } - static constexpr auto name = _("capsule"); + explicit operator void *&() { return value; } + static constexpr auto name = const_name("capsule"); private: void *value = nullptr; }; @@ -1160,9 +275,15 @@ template <> class type_caster { public: bool load(handle src, bool convert) { if (!src) return false; - else if (src.ptr() == Py_True) { value = true; return true; } - else if (src.ptr() == Py_False) { value = false; return true; } - else if (convert || !strcmp("numpy.bool_", Py_TYPE(src.ptr())->tp_name)) { + if (src.ptr() == Py_True) { + value = true; + return true; + } + if (src.ptr() == Py_False) { + value = false; + return true; + } + if (convert || (std::strcmp("numpy.bool_", Py_TYPE(src.ptr())->tp_name) == 0)) { // (allow non-implicit conversion for numpy booleans) Py_ssize_t res = -1; @@ -1184,18 +305,17 @@ public: } #endif if (res == 0 || res == 1) { - value = (bool) res; + value = (res != 0); return true; - } else { - PyErr_Clear(); } + PyErr_Clear(); } return false; } static handle cast(bool src, return_value_policy /* policy */, handle /* parent */) { return handle(src ? Py_True : Py_False).inc_ref(); } - PYBIND11_TYPE_CASTER(bool, _("bool")); + PYBIND11_TYPE_CASTER(bool, const_name("bool")); }; // Helper class for UTF-{8,16,32} C++ stl strings: @@ -1222,7 +342,8 @@ template struct string_caster { handle load_src = src; if (!src) { return false; - } else if (!PyUnicode_Check(load_src.ptr())) { + } + if (!PyUnicode_Check(load_src.ptr())) { #if PY_MAJOR_VERSION >= 3 return load_bytes(load_src); #else @@ -1240,13 +361,33 @@ template struct string_caster { #endif } - object utfNbytes = reinterpret_steal(PyUnicode_AsEncodedString( +#if PY_VERSION_HEX >= 0x03030000 + // On Python >= 3.3, for UTF-8 we avoid the need for a temporary `bytes` + // object by using `PyUnicode_AsUTF8AndSize`. + if (PYBIND11_SILENCE_MSVC_C4127(UTF_N == 8)) { + Py_ssize_t size = -1; + const auto *buffer + = reinterpret_cast(PyUnicode_AsUTF8AndSize(load_src.ptr(), &size)); + if (!buffer) { + PyErr_Clear(); + return false; + } + value = StringType(buffer, static_cast(size)); + return true; + } +#endif + + auto utfNbytes = reinterpret_steal(PyUnicode_AsEncodedString( load_src.ptr(), UTF_N == 8 ? "utf-8" : UTF_N == 16 ? "utf-16" : "utf-32", nullptr)); if (!utfNbytes) { PyErr_Clear(); return false; } const auto *buffer = reinterpret_cast(PYBIND11_BYTES_AS_STRING(utfNbytes.ptr())); size_t length = (size_t) PYBIND11_BYTES_SIZE(utfNbytes.ptr()) / sizeof(CharT); - if (UTF_N > 8) { buffer++; length--; } // Skip BOM for UTF-16/32 + // Skip BOM for UTF-16/32 + if (PYBIND11_SILENCE_MSVC_C4127(UTF_N > 8)) { + buffer++; + length--; + } value = StringType(buffer, length); // If we're loading a string_view we need to keep the encoded Python object alive: @@ -1264,7 +405,7 @@ template struct string_caster { return s; } - PYBIND11_TYPE_CASTER(StringType, _(PYBIND11_STRING_NAME)); + PYBIND11_TYPE_CASTER(StringType, const_name(PYBIND11_STRING_NAME)); private: static handle decode_utfN(const char *buffer, ssize_t nbytes) { @@ -1274,10 +415,8 @@ private: UTF_N == 16 ? PyUnicode_DecodeUTF16(buffer, nbytes, nullptr, nullptr) : PyUnicode_DecodeUTF32(buffer, nbytes, nullptr, nullptr); #else - // PyPy seems to have multiple problems related to PyUnicode_UTF*: the UTF8 version - // sometimes segfaults for unknown reasons, while the UTF16 and 32 versions require a - // non-const char * arguments, which is also a nuisance, so bypass the whole thing by just - // passing the encoding as a string value, which works properly: + // PyPy segfaults when on PyUnicode_DecodeUTF16 (and possibly on PyUnicode_DecodeUTF32 as well), + // so bypass the whole thing by just passing the encoding as a string value, which works properly: return PyUnicode_Decode(buffer, nbytes, UTF_N == 8 ? "utf-8" : UTF_N == 16 ? "utf-16" : "utf-32", nullptr); #endif } @@ -1348,8 +487,10 @@ public: return StringCaster::cast(StringType(1, src), policy, parent); } - operator CharT*() { return none ? nullptr : const_cast(static_cast(str_caster).c_str()); } - operator CharT&() { + explicit operator CharT *() { + return none ? nullptr : const_cast(static_cast(str_caster).c_str()); + } + explicit operator CharT &() { if (none) throw value_error("Cannot convert None to a character"); @@ -1363,12 +504,16 @@ public: // out how long the first encoded character is in bytes to distinguish between these two // errors. We also allow want to allow unicode characters U+0080 through U+00FF, as those // can fit into a single char value. - if (StringCaster::UTF_N == 8 && str_len > 1 && str_len <= 4) { + if (PYBIND11_SILENCE_MSVC_C4127(StringCaster::UTF_N == 8) && str_len > 1 && str_len <= 4) { auto v0 = static_cast(value[0]); - size_t char0_bytes = !(v0 & 0x80) ? 1 : // low bits only: 0-127 - (v0 & 0xE0) == 0xC0 ? 2 : // 0b110xxxxx - start of 2-byte sequence - (v0 & 0xF0) == 0xE0 ? 3 : // 0b1110xxxx - start of 3-byte sequence - 4; // 0b11110xxx - start of 4-byte sequence + // low bits only: 0-127 + // 0b110xxxxx - start of 2-byte sequence + // 0b1110xxxx - start of 3-byte sequence + // 0b11110xxx - start of 4-byte sequence + size_t char0_bytes = (v0 & 0x80) == 0 ? 1 + : (v0 & 0xE0) == 0xC0 ? 2 + : (v0 & 0xF0) == 0xE0 ? 3 + : 4; if (char0_bytes == str_len) { // If we have a 128-255 value, we can decode it into a single char: @@ -1384,7 +529,7 @@ public: // UTF-16 is much easier: we can only have a surrogate pair for values above U+FFFF, thus a // surrogate pair with total length 2 instantly indicates a range error (but not a "your // string was too long" error). - else if (StringCaster::UTF_N == 16 && str_len == 2) { + else if (PYBIND11_SILENCE_MSVC_C4127(StringCaster::UTF_N == 16) && str_len == 2) { one_char = static_cast(value[0]); if (one_char >= 0xD800 && one_char < 0xE000) throw value_error("Character code point not in range(0x10000)"); @@ -1397,7 +542,7 @@ public: return one_char; } - static constexpr auto name = _(PYBIND11_STRING_NAME); + static constexpr auto name = const_name(PYBIND11_STRING_NAME); template using cast_op_type = pybind11::detail::cast_op_type<_T>; }; @@ -1427,18 +572,19 @@ public: static handle cast(T *src, return_value_policy policy, handle parent) { if (!src) return none().release(); if (policy == return_value_policy::take_ownership) { - auto h = cast(std::move(*src), policy, parent); delete src; return h; - } else { - return cast(*src, policy, parent); + auto h = cast(std::move(*src), policy, parent); + delete src; + return h; } + return cast(*src, policy, parent); } - static constexpr auto name = _("Tuple[") + concat(make_caster::name...) + _("]"); + static constexpr auto name = const_name("Tuple[") + concat(make_caster::name...) + const_name("]"); template using cast_op_type = type; - operator type() & { return implicit_cast(indices{}); } - operator type() && { return std::move(*this).implicit_cast(indices{}); } + explicit operator type() & { return implicit_cast(indices{}); } + explicit operator type() && { return std::move(*this).implicit_cast(indices{}); } protected: template @@ -1464,6 +610,8 @@ protected: /* Implementation: Convert a C++ tuple into a Python tuple */ template static handle cast_impl(T &&src, return_value_policy policy, handle parent, index_sequence) { + PYBIND11_WORKAROUND_INCORRECT_MSVC_C4100(src, policy, parent); + PYBIND11_WORKAROUND_INCORRECT_GCC_UNUSED_BUT_SET_PARAMETER(policy, parent); std::array entries{{ reinterpret_steal(make_caster::cast(std::get(std::forward(src)), policy, parent))... }}; @@ -1494,7 +642,11 @@ struct holder_helper { }; /// Type caster for holder types like std::shared_ptr, etc. -template +/// The SFINAE hook is provided to help work around the current lack of support +/// for smart-pointer interoperability. Please consider it an implementation +/// detail that may change in the future, as formal support for smart-pointer +/// interoperability is added into pybind11. +template struct copyable_holder_caster : public type_caster_base { public: using base = type_caster_base; @@ -1514,14 +666,7 @@ public: // see issue #2180 explicit operator type&() { return *(static_cast(this->value)); } explicit operator holder_type*() { return std::addressof(holder); } - - // Workaround for Intel compiler bug - // see pybind11 issue 94 - #if defined(__ICC) || defined(__INTEL_COMPILER) - operator holder_type&() { return holder; } - #else explicit operator holder_type&() { return holder; } - #endif static handle cast(const holder_type &src, return_value_policy, handle) { const auto *ptr = holder_helper::get(src); @@ -1540,14 +685,14 @@ protected: value = v_h.value_ptr(); holder = v_h.template holder(); return true; - } else { - throw cast_error("Unable to cast from non-held to held instance (T& to Holder) " -#if defined(NDEBUG) - "(compile in debug mode for type information)"); -#else - "of type '" + type_id() + "''"); -#endif } + throw cast_error("Unable to cast from non-held to held instance (T& to Holder) " +#if defined(NDEBUG) + "(compile in debug mode for type information)"); +#else + "of type '" + + type_id() + "''"); +#endif } template ::value, int> = 0> @@ -1576,7 +721,10 @@ protected: template class type_caster> : public copyable_holder_caster> { }; -template +/// Type caster for holder types like std::unique_ptr. +/// Please consider the SFINAE hook an implementation detail, as explained +/// in the comment for the copyable_holder_caster. +template struct move_only_holder_caster { static_assert(std::is_base_of, type_caster>::value, "Holder classes are only supported for custom types"); @@ -1616,14 +764,16 @@ template struct is_holder_type : template struct is_holder_type> : std::true_type {}; -template struct handle_type_name { static constexpr auto name = _(); }; -template <> struct handle_type_name { static constexpr auto name = _(PYBIND11_BYTES_NAME); }; -template <> struct handle_type_name { static constexpr auto name = _("int"); }; -template <> struct handle_type_name { static constexpr auto name = _("Iterable"); }; -template <> struct handle_type_name { static constexpr auto name = _("Iterator"); }; -template <> struct handle_type_name { static constexpr auto name = _("None"); }; -template <> struct handle_type_name { static constexpr auto name = _("*args"); }; -template <> struct handle_type_name { static constexpr auto name = _("**kwargs"); }; +template struct handle_type_name { static constexpr auto name = const_name(); }; +template <> struct handle_type_name { static constexpr auto name = const_name("bool"); }; +template <> struct handle_type_name { static constexpr auto name = const_name(PYBIND11_BYTES_NAME); }; +template <> struct handle_type_name { static constexpr auto name = const_name("int"); }; +template <> struct handle_type_name { static constexpr auto name = const_name("Iterable"); }; +template <> struct handle_type_name { static constexpr auto name = const_name("Iterator"); }; +template <> struct handle_type_name { static constexpr auto name = const_name("float"); }; +template <> struct handle_type_name { static constexpr auto name = const_name("None"); }; +template <> struct handle_type_name { static constexpr auto name = const_name("*args"); }; +template <> struct handle_type_name { static constexpr auto name = const_name("**kwargs"); }; template struct pyobject_caster { @@ -1632,6 +782,17 @@ struct pyobject_caster { template ::value, int> = 0> bool load(handle src, bool /* convert */) { +#if PY_MAJOR_VERSION < 3 && !defined(PYBIND11_STR_LEGACY_PERMISSIVE) + // For Python 2, without this implicit conversion, Python code would + // need to be cluttered with six.ensure_text() or similar, only to be + // un-cluttered later after Python 2 support is dropped. + if (PYBIND11_SILENCE_MSVC_C4127(std::is_same::value) && isinstance(src)) { + PyObject *str_from_bytes = PyUnicode_FromEncodedObject(src.ptr(), "utf-8", nullptr); + if (!str_from_bytes) throw error_already_set(); + value = reinterpret_steal(str_from_bytes); + return true; + } +#endif if (!isinstance(src)) return false; value = reinterpret_borrow(src); @@ -1779,8 +940,7 @@ template detail::enable_if_t::value, T> cast template detail::enable_if_t::value, T> cast(object &&object) { if (object.ref_count() > 1) return cast(object); - else - return move(std::move(object)); + return move(std::move(object)); } template detail::enable_if_t::value, T> cast(object &&object) { return cast(object); @@ -1820,6 +980,21 @@ template <> inline void cast_safe(object &&) {} PYBIND11_NAMESPACE_END(detail) +// The overloads could coexist, i.e. the #if is not strictly speaking needed, +// but it is an easy minor optimization. +#if defined(NDEBUG) +inline cast_error cast_error_unable_to_convert_call_arg() { + return cast_error( + "Unable to convert call argument to Python object (compile in debug mode for details)"); +} +#else +inline cast_error cast_error_unable_to_convert_call_arg(const std::string &name, + const std::string &type) { + return cast_error("Unable to convert call argument '" + name + "' of type '" + type + + "' to Python object"); +} +#endif + template tuple make_tuple() { return tuple(0); } @@ -1833,11 +1008,10 @@ template argtypes { {type_id()...} }; - throw cast_error("make_tuple(): unable to convert argument of type '" + - argtypes[i] + "' to Python object"); + throw cast_error_unable_to_convert_call_arg(std::to_string(i), argtypes[i]); #endif } } @@ -1879,7 +1053,14 @@ private: #if !defined(NDEBUG) , type(type_id()) #endif - { } + { + // Workaround! See: + // https://github.com/pybind/pybind11/issues/2336 + // https://github.com/pybind/pybind11/pull/2685#issuecomment-731286700 + if (PyErr_Occurred()) { + PyErr_Clear(); + } + } public: /// Direct construction with name, default, and description @@ -1919,7 +1100,9 @@ struct kw_only {}; struct pos_only {}; template -arg_v arg::operator=(T &&value) const { return {std::move(*this), std::forward(value)}; } +arg_v arg::operator=(T &&value) const { + return {*this, std::forward(value)}; +} /// Alias for backward compatibility -- to be removed in version 2.0 template using arg_t = arg_v; @@ -1933,6 +1116,9 @@ constexpr arg operator"" _a(const char *name, size_t) { return arg(name); } PYBIND11_NAMESPACE_BEGIN(detail) +template using is_kw_only = std::is_same, kw_only>; +template using is_pos_only = std::is_same, pos_only>; + // forward declaration (definition in attr.h) struct function_record; @@ -1968,17 +1154,18 @@ class argument_loader { template using argument_is_args = std::is_same, args>; template using argument_is_kwargs = std::is_same, kwargs>; - // Get args/kwargs argument positions relative to the end of the argument list: - static constexpr auto args_pos = constexpr_first() - (int) sizeof...(Args), - kwargs_pos = constexpr_first() - (int) sizeof...(Args); + // Get kwargs argument position, or -1 if not present: + static constexpr auto kwargs_pos = constexpr_last(); - static constexpr bool args_kwargs_are_last = kwargs_pos >= - 1 && args_pos >= kwargs_pos - 1; - - static_assert(args_kwargs_are_last, "py::args/py::kwargs are only permitted as the last argument(s) of a function"); + static_assert(kwargs_pos == -1 || kwargs_pos == (int) sizeof...(Args) - 1, "py::kwargs is only permitted as the last argument of a function"); public: - static constexpr bool has_kwargs = kwargs_pos < 0; - static constexpr bool has_args = args_pos < 0; + static constexpr bool has_kwargs = kwargs_pos != -1; + + // py::args argument position; -1 if not present. + static constexpr int args_pos = constexpr_last(); + + static_assert(args_pos == -1 || args_pos == constexpr_first(), "py::args cannot be specified more than once"); static constexpr auto arg_names = concat(type_descr(make_caster::name)...); @@ -1987,13 +1174,14 @@ public: } template + // NOLINTNEXTLINE(readability-const-return-type) enable_if_t::value, Return> call(Func &&f) && { - return std::move(*this).template call_impl(std::forward(f), indices{}, Guard{}); + return std::move(*this).template call_impl>(std::forward(f), indices{}, Guard{}); } template enable_if_t::value, void_type> call(Func &&f) && { - std::move(*this).template call_impl(std::forward(f), indices{}, Guard{}); + std::move(*this).template call_impl>(std::forward(f), indices{}, Guard{}); return void_type(); } @@ -2057,8 +1245,8 @@ public: // Tuples aren't (easily) resizable so a list is needed for collection, // but the actual function call strictly requires a tuple. auto args_list = list(); - int _[] = { 0, (process(args_list, std::forward(values)), 0)... }; - ignore_unused(_); + using expander = int[]; + (void) expander{0, (process(args_list, std::forward(values)), 0)...}; m_args = std::move(args_list); } @@ -2083,16 +1271,17 @@ private: auto o = reinterpret_steal(detail::make_caster::cast(std::forward(x), policy, {})); if (!o) { #if defined(NDEBUG) - argument_cast_error(); + throw cast_error_unable_to_convert_call_arg(); #else - argument_cast_error(std::to_string(args_list.size()), type_id()); + throw cast_error_unable_to_convert_call_arg( + std::to_string(args_list.size()), type_id()); #endif } args_list.append(o); } void process(list &args_list, detail::args_proxy ap) { - for (const auto &a : ap) + for (auto a : ap) args_list.append(a); } @@ -2113,9 +1302,9 @@ private: } if (!a.value) { #if defined(NDEBUG) - argument_cast_error(); + throw cast_error_unable_to_convert_call_arg(); #else - argument_cast_error(a.name, a.type); + throw cast_error_unable_to_convert_call_arg(a.name, a.type); #endif } m_kwargs[a.name] = a.value; @@ -2124,7 +1313,7 @@ private: void process(list &/*args_list*/, detail::kwargs_proxy kp) { if (!kp) return; - for (const auto &k : reinterpret_borrow(kp)) { + for (auto k : reinterpret_borrow(kp)) { if (m_kwargs.contains(k.first)) { #if defined(NDEBUG) multiple_values_error(); @@ -2141,7 +1330,7 @@ private: "may be passed via py::arg() to a python function call. " "(compile in debug mode for details)"); } - [[noreturn]] static void nameless_argument_error(std::string type) { + [[noreturn]] static void nameless_argument_error(const std::string &type) { throw type_error("Got kwargs without a name of type '" + type + "'; only named " "arguments may be passed via py::arg() to a python function call. "); } @@ -2150,35 +1339,35 @@ private: "(compile in debug mode for details)"); } - [[noreturn]] static void multiple_values_error(std::string name) { + [[noreturn]] static void multiple_values_error(const std::string &name) { throw type_error("Got multiple values for keyword argument '" + name + "'"); } - [[noreturn]] static void argument_cast_error() { - throw cast_error("Unable to convert call argument to Python object " - "(compile in debug mode for details)"); - } - - [[noreturn]] static void argument_cast_error(std::string name, std::string type) { - throw cast_error("Unable to convert call argument '" + name - + "' of type '" + type + "' to Python object"); - } - private: tuple m_args; dict m_kwargs; }; +// [workaround(intel)] Separate function required here +// We need to put this into a separate function because the Intel compiler +// fails to compile enable_if_t...>::value> +// (tested with ICC 2021.1 Beta 20200827). +template +constexpr bool args_are_all_positional() +{ + return all_of...>::value; +} + /// Collect only positional arguments for a Python function call template ...>::value>> + typename = enable_if_t()>> simple_collector collect_arguments(Args &&...args) { return simple_collector(std::forward(args)...); } /// Collect all arguments, including keywords and unpacking (only instantiated when needed) template ...>::value>> + typename = enable_if_t()>> unpacking_collector collect_arguments(Args &&...args) { // Following argument order rules for generalized unpacking according to PEP 448 static_assert( @@ -2193,6 +1382,11 @@ unpacking_collector collect_arguments(Args &&...args) { template template object object_api::operator()(Args &&...args) const { +#if !defined(NDEBUG) && PY_VERSION_HEX >= 0x03060000 + if (!PyGILState_Check()) { + pybind11_fail("pybind11::object_api<>::operator() PyGILState_Check() failure."); + } +#endif return detail::collect_arguments(std::forward(args)...).call(derived().ptr()); } diff --git a/pybind11/include/pybind11/chrono.h b/pybind11/include/pybind11/chrono.h index cbe9acec3..460a28fa5 100644 --- a/pybind11/include/pybind11/chrono.h +++ b/pybind11/include/pybind11/chrono.h @@ -11,9 +11,12 @@ #pragma once #include "pybind11.h" + +#include #include #include -#include +#include + #include // Backport the PyDateTime_DELTA functions from Python3.3 if required @@ -32,10 +35,10 @@ PYBIND11_NAMESPACE_BEGIN(detail) template class duration_caster { public: - typedef typename type::rep rep; + using rep = typename type::rep; using period = typename type::period; - using days = std::chrono::duration>; + using days = std::chrono::duration>; // signed 25 bits required by the standard. bool load(handle src, bool) { using namespace std::chrono; @@ -53,11 +56,11 @@ public: return true; } // If invoked with a float we assume it is seconds and convert - else if (PyFloat_Check(src.ptr())) { + if (PyFloat_Check(src.ptr())) { value = type(duration_cast>(duration(PyFloat_AsDouble(src.ptr())))); return true; } - else return false; + return false; } // If this is a duration just return it back @@ -92,9 +95,25 @@ public: return PyDelta_FromDSU(dd.count(), ss.count(), us.count()); } - PYBIND11_TYPE_CASTER(type, _("datetime.timedelta")); + PYBIND11_TYPE_CASTER(type, const_name("datetime.timedelta")); }; +inline std::tm *localtime_thread_safe(const std::time_t *time, std::tm *buf) { +#if (defined(__STDC_LIB_EXT1__) && defined(__STDC_WANT_LIB_EXT1__)) || defined(_MSC_VER) + if (localtime_s(buf, time)) + return nullptr; + return buf; +#else + static std::mutex mtx; + std::lock_guard lock(mtx); + std::tm *tm_ptr = std::localtime(time); + if (tm_ptr != nullptr) { + *buf = *tm_ptr; + } + return tm_ptr; +#endif +} + // This is for casting times on the system clock into datetime.datetime instances template class type_caster> { public: @@ -161,10 +180,11 @@ public: // > If std::time_t has lower precision, it is implementation-defined whether the value is rounded or truncated. // (https://en.cppreference.com/w/cpp/chrono/system_clock/to_time_t) std::time_t tt = system_clock::to_time_t(time_point_cast(src - us)); - // this function uses static memory so it's best to copy it out asap just in case - // otherwise other code that is using localtime may break this (not just python code) - std::tm localtime = *std::localtime(&tt); + std::tm localtime; + std::tm *localtime_ptr = localtime_thread_safe(&tt, &localtime); + if (!localtime_ptr) + throw cast_error("Unable to represent system_clock in local time"); return PyDateTime_FromDateAndTime(localtime.tm_year + 1900, localtime.tm_mon + 1, localtime.tm_mday, @@ -173,7 +193,7 @@ public: localtime.tm_sec, us.count()); } - PYBIND11_TYPE_CASTER(type, _("datetime.datetime")); + PYBIND11_TYPE_CASTER(type, const_name("datetime.datetime")); }; // Other clocks that are not the system clock are not measured as datetime.datetime objects diff --git a/pybind11/include/pybind11/complex.h b/pybind11/include/pybind11/complex.h index f8327eb37..e1ecf4358 100644 --- a/pybind11/include/pybind11/complex.h +++ b/pybind11/include/pybind11/complex.h @@ -59,7 +59,7 @@ public: return PyComplex_FromDoubles((double) src.real(), (double) src.imag()); } - PYBIND11_TYPE_CASTER(std::complex, _("complex")); + PYBIND11_TYPE_CASTER(std::complex, const_name("complex")); }; PYBIND11_NAMESPACE_END(detail) PYBIND11_NAMESPACE_END(PYBIND11_NAMESPACE) diff --git a/pybind11/include/pybind11/detail/class.h b/pybind11/include/pybind11/detail/class.h index b4a11c0a0..cc1e40ce7 100644 --- a/pybind11/include/pybind11/detail/class.h +++ b/pybind11/include/pybind11/detail/class.h @@ -24,6 +24,18 @@ PYBIND11_NAMESPACE_BEGIN(detail) # define PYBIND11_SET_OLDPY_QUALNAME(obj, nameobj) setattr((PyObject *) obj, "__qualname__", nameobj) #endif +inline std::string get_fully_qualified_tp_name(PyTypeObject *type) { +#if !defined(PYPY_VERSION) + return type->tp_name; +#else + auto module_name = handle((PyObject *) type).attr("__module__").cast(); + if (module_name == PYBIND11_BUILTINS_MODULE) + return type->tp_name; + else + return std::move(module_name) + "." + type->tp_name; +#endif +} + inline PyTypeObject *type_incref(PyTypeObject *type) { Py_INCREF(type); return type; @@ -117,8 +129,9 @@ extern "C" inline int pybind11_meta_setattro(PyObject* obj, PyObject* name, PyOb // 2. `Type.static_prop = other_static_prop` --> setattro: replace existing `static_prop` // 3. `Type.regular_attribute = value` --> setattro: regular attribute assignment const auto static_prop = (PyObject *) get_internals().static_property_type; - const auto call_descr_set = descr && PyObject_IsInstance(descr, static_prop) - && !PyObject_IsInstance(value, static_prop); + const auto call_descr_set = (descr != nullptr) && (value != nullptr) + && (PyObject_IsInstance(descr, static_prop) != 0) + && (PyObject_IsInstance(value, static_prop) == 0); if (call_descr_set) { // Call `static_property.__set__()` instead of replacing the `static_property`. #if !defined(PYPY_VERSION) @@ -150,9 +163,7 @@ extern "C" inline PyObject *pybind11_meta_getattro(PyObject *obj, PyObject *name Py_INCREF(descr); return descr; } - else { - return PyType_Type.tp_getattro(obj, name); - } + return PyType_Type.tp_getattro(obj, name); } #endif @@ -172,7 +183,7 @@ extern "C" inline PyObject *pybind11_meta_call(PyObject *type, PyObject *args, P for (const auto &vh : values_and_holders(instance)) { if (!vh.holder_constructed()) { PyErr_Format(PyExc_TypeError, "%.200s.__init__() must be called when overriding __init__", - vh.type->type->tp_name); + get_fully_qualified_tp_name(vh.type->type).c_str()); Py_DECREF(self); return nullptr; } @@ -181,6 +192,44 @@ extern "C" inline PyObject *pybind11_meta_call(PyObject *type, PyObject *args, P return self; } +/// Cleanup the type-info for a pybind11-registered type. +extern "C" inline void pybind11_meta_dealloc(PyObject *obj) { + auto *type = (PyTypeObject *) obj; + auto &internals = get_internals(); + + // A pybind11-registered type will: + // 1) be found in internals.registered_types_py + // 2) have exactly one associated `detail::type_info` + auto found_type = internals.registered_types_py.find(type); + if (found_type != internals.registered_types_py.end() && + found_type->second.size() == 1 && + found_type->second[0]->type == type) { + + auto *tinfo = found_type->second[0]; + auto tindex = std::type_index(*tinfo->cpptype); + internals.direct_conversions.erase(tindex); + + if (tinfo->module_local) + get_local_internals().registered_types_cpp.erase(tindex); + else + internals.registered_types_cpp.erase(tindex); + internals.registered_types_py.erase(tinfo->type); + + // Actually just `std::erase_if`, but that's only available in C++20 + auto &cache = internals.inactive_override_cache; + for (auto it = cache.begin(), last = cache.end(); it != last; ) { + if (it->first == (PyObject *) tinfo->type) + it = cache.erase(it); + else + ++it; + } + + delete tinfo; + } + + PyType_Type.tp_dealloc(obj); +} + /** This metaclass is assigned by default to all pybind11 types and is required in order for static properties to function correctly. Users may override this using `py::metaclass`. Return value: New reference. */ @@ -213,6 +262,8 @@ inline PyTypeObject* make_default_metaclass() { type->tp_getattro = pybind11_meta_getattro; #endif + type->tp_dealloc = pybind11_meta_dealloc; + if (PyType_Ready(type) < 0) pybind11_fail("make_default_metaclass(): failure in PyType_Ready()!"); @@ -250,7 +301,7 @@ inline bool deregister_instance_impl(void *ptr, instance *self) { auto ®istered_instances = get_internals().registered_instances; auto range = registered_instances.equal_range(ptr); for (auto it = range.first; it != range.second; ++it) { - if (Py_TYPE(self) == Py_TYPE(it->second)) { + if (self == it->second) { registered_instances.erase(it); return true; } @@ -277,7 +328,7 @@ inline bool deregister_instance(instance *self, void *valptr, const type_info *t inline PyObject *make_new_instance(PyTypeObject *type) { #if defined(PYPY_VERSION) // PyPy gets tp_basicsize wrong (issue 2482) under multiple inheritance when the first inherited - // object is a a plain Python type (i.e. not derived from an extension type). Fix it. + // object is a plain Python type (i.e. not derived from an extension type). Fix it. ssize_t instance_size = static_cast(sizeof(instance)); if (type->tp_basicsize < instance_size) { type->tp_basicsize = instance_size; @@ -288,8 +339,6 @@ inline PyObject *make_new_instance(PyTypeObject *type) { // Allocate the value/holder internals: inst->allocate_layout(); - inst->owned = true; - return self; } @@ -304,12 +353,7 @@ extern "C" inline PyObject *pybind11_object_new(PyTypeObject *type, PyObject *, /// following default function will be used which simply throws an exception. extern "C" inline int pybind11_object_init(PyObject *self, PyObject *, PyObject *) { PyTypeObject *type = Py_TYPE(self); - std::string msg; -#if defined(PYPY_VERSION) - msg += handle((PyObject *) type).attr("__module__").cast() + "."; -#endif - msg += type->tp_name; - msg += ": No constructor defined!"; + std::string msg = get_fully_qualified_tp_name(type) + ": No constructor defined!"; PyErr_SetString(PyExc_TypeError, msg.c_str()); return -1; } @@ -448,7 +492,7 @@ extern "C" inline PyObject *pybind11_get_dict(PyObject *self, void *) { extern "C" inline int pybind11_set_dict(PyObject *self, PyObject *new_dict, void *) { if (!PyDict_Check(new_dict)) { PyErr_Format(PyExc_TypeError, "__dict__ must be set to a dictionary, not a '%.200s'", - Py_TYPE(new_dict)->tp_name); + get_fully_qualified_tp_name(Py_TYPE(new_dict)).c_str()); return -1; } PyObject *&dict = *_PyObject_GetDictPtr(self); @@ -475,11 +519,6 @@ extern "C" inline int pybind11_clear(PyObject *self) { /// Give instances of this type a `__dict__` and opt into garbage collection. inline void enable_dynamic_attributes(PyHeapTypeObject *heap_type) { auto type = &heap_type->ht_type; -#if defined(PYPY_VERSION) && (PYPY_VERSION_NUM < 0x06000000) - pybind11_fail(std::string(type->tp_name) + ": dynamic attributes are " - "currently not supported in " - "conjunction with PyPy!"); -#endif type->tp_flags |= Py_TPFLAGS_HAVE_GC; type->tp_dictoffset = type->tp_basicsize; // place dict at the end type->tp_basicsize += (ssize_t)sizeof(PyObject *); // and allocate enough space for it @@ -510,6 +549,12 @@ extern "C" inline int pybind11_getbuffer(PyObject *obj, Py_buffer *view, int fla } std::memset(view, 0, sizeof(Py_buffer)); buffer_info *info = tinfo->get_buffer(obj, tinfo->get_buffer_data); + if ((flags & PyBUF_WRITABLE) == PyBUF_WRITABLE && info->readonly) { + delete info; + // view->obj = nullptr; // Was just memset to 0, so not necessary + PyErr_SetString(PyExc_BufferError, "Writable buffer requested for readonly storage"); + return -1; + } view->obj = obj; view->ndim = 1; view->internal = info; @@ -518,13 +563,7 @@ extern "C" inline int pybind11_getbuffer(PyObject *obj, Py_buffer *view, int fla view->len = view->itemsize; for (auto s : info->shape) view->len *= s; - view->readonly = info->readonly; - if ((flags & PyBUF_WRITABLE) == PyBUF_WRITABLE && info->readonly) { - if (view) - view->obj = nullptr; - PyErr_SetString(PyExc_BufferError, "Writable buffer requested for readonly storage"); - return -1; - } + view->readonly = static_cast(info->readonly); if ((flags & PyBUF_FORMAT) == PyBUF_FORMAT) view->format = const_cast(info->format.c_str()); if ((flags & PyBUF_STRIDES) == PyBUF_STRIDES) { @@ -567,17 +606,17 @@ inline PyObject* make_new_python_type(const type_record &rec) { #endif } - object module; + object module_; if (rec.scope) { if (hasattr(rec.scope, "__module__")) - module = rec.scope.attr("__module__"); + module_ = rec.scope.attr("__module__"); else if (hasattr(rec.scope, "__name__")) - module = rec.scope.attr("__name__"); + module_ = rec.scope.attr("__name__"); } auto full_name = c_str( #if !defined(PYPY_VERSION) - module ? str(module).cast() + "." + rec.name : + module_ ? str(module_).cast() + "." + rec.name : #endif rec.name); @@ -585,9 +624,9 @@ inline PyObject* make_new_python_type(const type_record &rec) { if (rec.doc && options::show_user_defined_docstrings()) { /* Allocate memory for docstring (using PyObject_MALLOC, since Python will free this later on) */ - size_t size = strlen(rec.doc) + 1; + size_t size = std::strlen(rec.doc) + 1; tp_doc = (char *) PyObject_MALLOC(size); - memcpy((void *) tp_doc, rec.doc, size); + std::memcpy((void *) tp_doc, rec.doc, size); } auto &internals = get_internals(); @@ -644,11 +683,13 @@ inline PyObject* make_new_python_type(const type_record &rec) { if (rec.buffer_protocol) enable_buffer_protocol(heap_type); + if (rec.custom_type_setup_callback) + rec.custom_type_setup_callback(heap_type); + if (PyType_Ready(type) < 0) pybind11_fail(std::string(rec.name) + ": PyType_Ready failed (" + error_string() + ")!"); - assert(rec.dynamic_attr ? PyType_HasFeature(type, Py_TPFLAGS_HAVE_GC) - : !PyType_HasFeature(type, Py_TPFLAGS_HAVE_GC)); + assert(!rec.dynamic_attr || PyType_HasFeature(type, Py_TPFLAGS_HAVE_GC)); /* Register type with the parent scope */ if (rec.scope) @@ -656,8 +697,8 @@ inline PyObject* make_new_python_type(const type_record &rec) { else Py_INCREF(type); // Keep it alive forever (reference leak) - if (module) // Needed by pydoc - setattr((PyObject *) type, "__module__", module); + if (module_) // Needed by pydoc + setattr((PyObject *) type, "__module__", module_); PYBIND11_SET_OLDPY_QUALNAME(type, qualname); diff --git a/pybind11/include/pybind11/detail/common.h b/pybind11/include/pybind11/detail/common.h index 1f8390fba..5c59b4141 100644 --- a/pybind11/include/pybind11/detail/common.h +++ b/pybind11/include/pybind11/detail/common.h @@ -10,8 +10,12 @@ #pragma once #define PYBIND11_VERSION_MAJOR 2 -#define PYBIND11_VERSION_MINOR 6 -#define PYBIND11_VERSION_PATCH 0.dev1 +#define PYBIND11_VERSION_MINOR 9 +#define PYBIND11_VERSION_PATCH 1 + +// Similar to Python's convention: https://docs.python.org/3/c-api/apiabiversion.html +// Additional convention: 0xD = dev +#define PYBIND11_VERSION_HEX 0x02090100 #define PYBIND11_NAMESPACE_BEGIN(name) namespace name { #define PYBIND11_NAMESPACE_END(name) } @@ -27,11 +31,14 @@ # endif #endif -#if !(defined(_MSC_VER) && __cplusplus == 199711L) && !defined(__INTEL_COMPILER) +#if !(defined(_MSC_VER) && __cplusplus == 199711L) # if __cplusplus >= 201402L # define PYBIND11_CPP14 # if __cplusplus >= 201703L # define PYBIND11_CPP17 +# if __cplusplus >= 202002L +# define PYBIND11_CPP20 +# endif # endif # endif #elif defined(_MSC_VER) && __cplusplus == 199711L @@ -41,15 +48,23 @@ # define PYBIND11_CPP14 # if _MSVC_LANG > 201402L && _MSC_VER >= 1910 # define PYBIND11_CPP17 +# if _MSVC_LANG >= 202002L +# define PYBIND11_CPP20 +# endif # endif # endif #endif // Compiler version assertions #if defined(__INTEL_COMPILER) -# if __INTEL_COMPILER < 1700 -# error pybind11 requires Intel C++ compiler v17 or newer +# if __INTEL_COMPILER < 1800 +# error pybind11 requires Intel C++ compiler v18 or newer +# elif __INTEL_COMPILER < 1900 && defined(PYBIND11_CPP14) +# error pybind11 supports only C++11 with Intel C++ compiler v18. Use v19 or newer for C++14. # endif +/* The following pragma cannot be pop'ed: + https://community.intel.com/t5/Intel-C-Compiler/Inline-and-no-inline-warning/td-p/1216764 */ +# pragma warning disable 2196 // warning #2196: routine is both "inline" and "noinline" #elif defined(__clang__) && !defined(__apple_build_version__) # if __clang_major__ < 3 || (__clang_major__ == 3 && __clang_minor__ < 3) # error pybind11 requires clang 3.3 or newer @@ -80,13 +95,43 @@ # endif #endif -#if defined(_MSC_VER) -# define PYBIND11_NOINLINE __declspec(noinline) -#else -# define PYBIND11_NOINLINE __attribute__ ((noinline)) +#if !defined(PYBIND11_EXPORT_EXCEPTION) +# ifdef __MINGW32__ +// workaround for: +// error: 'dllexport' implies default visibility, but xxx has already been declared with a different visibility +# define PYBIND11_EXPORT_EXCEPTION +# else +# define PYBIND11_EXPORT_EXCEPTION PYBIND11_EXPORT +# endif #endif -#if defined(PYBIND11_CPP14) +// For CUDA, GCC7, GCC8: +// PYBIND11_NOINLINE_FORCED is incompatible with `-Wattributes -Werror`. +// When defining PYBIND11_NOINLINE_FORCED, it is best to also use `-Wno-attributes`. +// However, the measured shared-library size saving when using noinline are only +// 1.7% for CUDA, -0.2% for GCC7, and 0.0% for GCC8 (using -DCMAKE_BUILD_TYPE=MinSizeRel, +// the default under pybind11/tests). +#if !defined(PYBIND11_NOINLINE_FORCED) && \ + (defined(__CUDACC__) || (defined(__GNUC__) && (__GNUC__ == 7 || __GNUC__ == 8))) +# define PYBIND11_NOINLINE_DISABLED +#endif + +// The PYBIND11_NOINLINE macro is for function DEFINITIONS. +// In contrast, FORWARD DECLARATIONS should never use this macro: +// https://stackoverflow.com/questions/9317473/forward-declaration-of-inline-functions +#if defined(PYBIND11_NOINLINE_DISABLED) // Option for maximum portability and experimentation. +# define PYBIND11_NOINLINE inline +#elif defined(_MSC_VER) +# define PYBIND11_NOINLINE __declspec(noinline) inline +#else +# define PYBIND11_NOINLINE __attribute__ ((noinline)) inline +#endif + +#if defined(__MINGW32__) +// For unknown reasons all PYBIND11_DEPRECATED member trigger a warning when declared +// whether it is used or not +# define PYBIND11_DEPRECATED(reason) +#elif defined(PYBIND11_CPP14) # define PYBIND11_DEPRECATED(reason) [[deprecated(reason)]] #else # define PYBIND11_DEPRECATED(reason) __attribute__((deprecated(reason))) @@ -112,13 +157,61 @@ # define HAVE_ROUND 1 # endif # pragma warning(push) -# pragma warning(disable: 4510 4610 4512 4005) +// C4505: 'PySlice_GetIndicesEx': unreferenced local function has been removed (PyPy only) +# pragma warning(disable: 4505) # if defined(_DEBUG) && !defined(Py_DEBUG) +// Workaround for a VS 2022 issue. +// NOTE: This workaround knowingly violates the Python.h include order requirement: +// https://docs.python.org/3/c-api/intro.html#include-files +// See https://github.com/pybind/pybind11/pull/3497 for full context. +# include +# if _MSVC_STL_VERSION >= 143 +# include +# endif # define PYBIND11_DEBUG_MARKER # undef _DEBUG # endif #endif +// https://en.cppreference.com/w/c/chrono/localtime +#if defined(__STDC_LIB_EXT1__) && !defined(__STDC_WANT_LIB_EXT1__) +# define __STDC_WANT_LIB_EXT1__ +#endif + +#ifdef __has_include +// std::optional (but including it in c++14 mode isn't allowed) +# if defined(PYBIND11_CPP17) && __has_include() +# define PYBIND11_HAS_OPTIONAL 1 +# endif +// std::experimental::optional (but not allowed in c++11 mode) +# if defined(PYBIND11_CPP14) && (__has_include() && \ + !__has_include()) +# define PYBIND11_HAS_EXP_OPTIONAL 1 +# endif +// std::variant +# if defined(PYBIND11_CPP17) && __has_include() +# define PYBIND11_HAS_VARIANT 1 +# endif +#elif defined(_MSC_VER) && defined(PYBIND11_CPP17) +# define PYBIND11_HAS_OPTIONAL 1 +# define PYBIND11_HAS_VARIANT 1 +#endif + +#if defined(PYBIND11_CPP17) +# if defined(__has_include) +# if __has_include() +# define PYBIND11_HAS_STRING_VIEW +# endif +# elif defined(_MSC_VER) +# define PYBIND11_HAS_STRING_VIEW +# endif +#endif + +#if defined(__cpp_lib_char8_t) && __cpp_lib_char8_t >= 201811L +# define PYBIND11_HAS_U8STRING +#endif + + #include #include #include @@ -160,6 +253,24 @@ #include #include #include +#if defined(__has_include) +# if __has_include() +# include +# endif +#endif + +// #define PYBIND11_STR_LEGACY_PERMISSIVE +// If DEFINED, pybind11::str can hold PyUnicodeObject or PyBytesObject +// (probably surprising and never documented, but this was the +// legacy behavior until and including v2.6.x). As a side-effect, +// pybind11::isinstance() is true for both pybind11::str and +// pybind11::bytes. +// If UNDEFINED, pybind11::str can only hold PyUnicodeObject, and +// pybind11::isinstance() is true only for pybind11::str. +// However, for Python 2 only (!), the pybind11::str caster +// implicitly decodes bytes to PyUnicodeObject. This is to ease +// the transition from the legacy behavior to the non-permissive +// behavior. #if PY_MAJOR_VERSION >= 3 /// Compatibility macros for various Python versions #define PYBIND11_INSTANCE_METHOD_NEW(ptr, class_) PyInstanceMethod_New(ptr) @@ -173,8 +284,8 @@ #define PYBIND11_BYTES_SIZE PyBytes_Size #define PYBIND11_LONG_CHECK(o) PyLong_Check(o) #define PYBIND11_LONG_AS_LONGLONG(o) PyLong_AsLongLong(o) -#define PYBIND11_LONG_FROM_SIGNED(o) PyLong_FromSsize_t((ssize_t) o) -#define PYBIND11_LONG_FROM_UNSIGNED(o) PyLong_FromSize_t((size_t) o) +#define PYBIND11_LONG_FROM_SIGNED(o) PyLong_FromSsize_t((ssize_t) (o)) +#define PYBIND11_LONG_FROM_UNSIGNED(o) PyLong_FromSize_t((size_t) (o)) #define PYBIND11_BYTES_NAME "bytes" #define PYBIND11_STRING_NAME "str" #define PYBIND11_SLICE_OBJECT PyObject @@ -182,6 +293,7 @@ #define PYBIND11_STR_TYPE ::pybind11::str #define PYBIND11_BOOL_ATTR "__bool__" #define PYBIND11_NB_BOOL(ptr) ((ptr)->nb_bool) +#define PYBIND11_BUILTINS_MODULE "builtins" // Providing a separate declaration to make Clang's -Wmissing-prototypes happy. // See comment for PYBIND11_MODULE below for why this is marked "maybe unused". #define PYBIND11_PLUGIN_IMPL(name) \ @@ -209,6 +321,7 @@ #define PYBIND11_STR_TYPE ::pybind11::bytes #define PYBIND11_BOOL_ATTR "__nonzero__" #define PYBIND11_NB_BOOL(ptr) ((ptr)->nb_nonzero) +#define PYBIND11_BUILTINS_MODULE "__builtin__" // Providing a separate PyInit decl to make Clang's -Wmissing-prototypes happy. // See comment for PYBIND11_MODULE below for why this is marked "maybe unused". #define PYBIND11_PLUGIN_IMPL(name) \ @@ -250,6 +363,19 @@ extern "C" { } \ } +#if PY_VERSION_HEX >= 0x03030000 + +#define PYBIND11_CATCH_INIT_EXCEPTIONS \ + catch (pybind11::error_already_set &e) { \ + pybind11::raise_from(e, PyExc_ImportError, "initialization failed"); \ + return nullptr; \ + } catch (const std::exception &e) { \ + PyErr_SetString(PyExc_ImportError, e.what()); \ + return nullptr; \ + } \ + +#else + #define PYBIND11_CATCH_INIT_EXCEPTIONS \ catch (pybind11::error_already_set &e) { \ PyErr_SetString(PyExc_ImportError, e.what()); \ @@ -259,17 +385,19 @@ extern "C" { return nullptr; \ } \ +#endif + /** \rst ***Deprecated in favor of PYBIND11_MODULE*** This macro creates the entry point that will be invoked when the Python interpreter - imports a plugin library. Please create a `module` in the function body and return + imports a plugin library. Please create a `module_` in the function body and return the pointer to its underlying Python object at the end. .. code-block:: cpp PYBIND11_PLUGIN(example) { - pybind11::module m("example", "pybind11 example plugin"); + pybind11::module_ m("example", "pybind11 example plugin"); /// Set up bindings here return m.ptr(); } @@ -290,7 +418,7 @@ extern "C" { This macro creates the entry point that will be invoked when the Python interpreter imports an extension module. The module name is given as the fist argument and it should not be in quotes. The second macro argument defines a variable of type - `py::module` which can be used to initialize the module. + `py::module_` which can be used to initialize the module. The entry point is marked as "maybe unused" to aid dead-code detection analysis: since the entry point is typically only looked up at runtime and not referenced @@ -307,26 +435,35 @@ extern "C" { }); } \endrst */ -#define PYBIND11_MODULE(name, variable) \ - PYBIND11_MAYBE_UNUSED \ - static void PYBIND11_CONCAT(pybind11_init_, name)(pybind11::module &); \ - PYBIND11_PLUGIN_IMPL(name) { \ - PYBIND11_CHECK_PYTHON_VERSION \ - PYBIND11_ENSURE_INTERNALS_READY \ - auto m = pybind11::module(PYBIND11_TOSTRING(name)); \ - try { \ - PYBIND11_CONCAT(pybind11_init_, name)(m); \ - return m.ptr(); \ - } PYBIND11_CATCH_INIT_EXCEPTIONS \ - } \ - void PYBIND11_CONCAT(pybind11_init_, name)(pybind11::module &variable) - +#define PYBIND11_MODULE(name, variable) \ + static ::pybind11::module_::module_def PYBIND11_CONCAT(pybind11_module_def_, name) \ + PYBIND11_MAYBE_UNUSED; \ + PYBIND11_MAYBE_UNUSED \ + static void PYBIND11_CONCAT(pybind11_init_, name)(::pybind11::module_ &); \ + PYBIND11_PLUGIN_IMPL(name) { \ + PYBIND11_CHECK_PYTHON_VERSION \ + PYBIND11_ENSURE_INTERNALS_READY \ + auto m = ::pybind11::module_::create_extension_module( \ + PYBIND11_TOSTRING(name), nullptr, &PYBIND11_CONCAT(pybind11_module_def_, name)); \ + try { \ + PYBIND11_CONCAT(pybind11_init_, name)(m); \ + return m.ptr(); \ + } \ + PYBIND11_CATCH_INIT_EXCEPTIONS \ + } \ + void PYBIND11_CONCAT(pybind11_init_, name)(::pybind11::module_ & (variable)) PYBIND11_NAMESPACE_BEGIN(PYBIND11_NAMESPACE) using ssize_t = Py_ssize_t; using size_t = std::size_t; +template +inline ssize_t ssize_t_cast(const IntType &val) { + static_assert(sizeof(IntType) <= sizeof(ssize_t), "Implicit narrowing is not permitted."); + return static_cast(val); +} + /// Approach used to cast a previously unknown C++ instance into a Python object enum class return_value_policy : uint8_t { /** This is the default return value policy, which falls back to the policy @@ -481,6 +618,18 @@ template using remove_cv_t = typename std::remove_cv::type; template using remove_reference_t = typename std::remove_reference::type; #endif +#if defined(PYBIND11_CPP20) +using std::remove_cvref; +using std::remove_cvref_t; +#else +template +struct remove_cvref { + using type = remove_cv_t>; +}; +template +using remove_cvref_t = typename remove_cvref::type; +#endif + /// Index sequences #if defined(PYBIND11_CPP14) using std::index_sequence; @@ -488,7 +637,7 @@ using std::make_index_sequence; #else template struct index_sequence { }; template struct make_index_sequence_impl : make_index_sequence_impl { }; -template struct make_index_sequence_impl <0, S...> { typedef index_sequence type; }; +template struct make_index_sequence_impl <0, S...> { using type = index_sequence; }; template using make_index_sequence = typename make_index_sequence_impl::type; #endif @@ -502,10 +651,10 @@ template using select_indices = typename select_indices_impl using bool_constant = std::integral_constant; template struct negation : bool_constant { }; -// PGI cannot detect operator delete with the "compatible" void_t impl, so +// PGI/Intel cannot detect operator delete with the "compatible" void_t impl, so // using the new one (C++14 defect, so generally works on newer compilers, even // if not in C++17 mode) -#if defined(__PGIC__) +#if defined(__PGIC__) || defined(__INTEL_COMPILER) template using void_t = void; #else template struct void_t_impl { using type = void; }; @@ -618,8 +767,9 @@ template using is_strict_base_of = bool_consta /// Like is_base_of, but also requires that the base type is accessible (i.e. that a Derived pointer /// can be converted to a Base pointer) +/// For unions, `is_base_of::value` is False, so we need to check `is_same` as well. template using is_accessible_base_of = bool_constant< - std::is_base_of::value && std::is_convertible::value>; + (std::is_same::value || std::is_base_of::value) && std::is_convertible::value>; template class Base> struct is_template_base_of_impl { @@ -656,6 +806,10 @@ template using is_function_pointer = bool_constant< std::is_pointer::value && std::is_function::type>::value>; template struct strip_function_object { + // If you are encountering an + // 'error: name followed by "::" must be a class or namespace name' + // with the Intel compiler and a noexcept function here, + // try to use noexcept(true) instead of plain noexcept. using type = typename remove_class::type; }; @@ -677,11 +831,10 @@ using function_signature_t = conditional_t< template using is_lambda = satisfies_none_of, std::is_function, std::is_pointer, std::is_member_pointer>; -/// Ignore that a variable is unused in compiler warnings -inline void ignore_unused(const int *) { } - +// [workaround(intel)] Internal error on fold expression /// Apply a function over each element of a parameter pack -#ifdef __cpp_fold_expressions +#if defined(__cpp_fold_expressions) && !defined(__INTEL_COMPILER) +// Intel compiler produces an internal error on this fold expression (tested with ICC 19.0.2) #define PYBIND11_EXPAND_SIDE_EFFECTS(PATTERN) (((PATTERN), void()), ...) #else using expand_side_effects = bool[]; @@ -690,16 +843,23 @@ using expand_side_effects = bool[]; PYBIND11_NAMESPACE_END(detail) +#if defined(_MSC_VER) +# pragma warning(push) +# pragma warning(disable: 4275) // warning C4275: An exported class was derived from a class that wasn't exported. Can be ignored when derived from a STL class. +#endif /// C++ bindings of builtin Python exceptions -class builtin_exception : public std::runtime_error { +class PYBIND11_EXPORT_EXCEPTION builtin_exception : public std::runtime_error { public: using std::runtime_error::runtime_error; /// Set the error using the Python C API virtual void set_error() const = 0; }; +#if defined(_MSC_VER) +# pragma warning(pop) +#endif #define PYBIND11_RUNTIME_EXCEPTION(name, type) \ - class name : public builtin_exception { public: \ + class PYBIND11_EXPORT_EXCEPTION name : public builtin_exception { public: \ using builtin_exception::builtin_exception; \ name() : name("") { } \ void set_error() const override { PyErr_SetString(type, what()); } \ @@ -712,11 +872,12 @@ PYBIND11_RUNTIME_EXCEPTION(value_error, PyExc_ValueError) PYBIND11_RUNTIME_EXCEPTION(type_error, PyExc_TypeError) PYBIND11_RUNTIME_EXCEPTION(buffer_error, PyExc_BufferError) PYBIND11_RUNTIME_EXCEPTION(import_error, PyExc_ImportError) +PYBIND11_RUNTIME_EXCEPTION(attribute_error, PyExc_AttributeError) PYBIND11_RUNTIME_EXCEPTION(cast_error, PyExc_RuntimeError) /// Thrown when pybind11::cast or handle::call fail due to a type casting error PYBIND11_RUNTIME_EXCEPTION(reference_cast_error, PyExc_RuntimeError) /// Used internally -[[noreturn]] PYBIND11_NOINLINE inline void pybind11_fail(const char *reason) { throw std::runtime_error(reason); } -[[noreturn]] PYBIND11_NOINLINE inline void pybind11_fail(const std::string &reason) { throw std::runtime_error(reason); } +[[noreturn]] PYBIND11_NOINLINE void pybind11_fail(const char *reason) { throw std::runtime_error(reason); } +[[noreturn]] PYBIND11_NOINLINE void pybind11_fail(const std::string &reason) { throw std::runtime_error(reason); } template struct format_descriptor { }; @@ -761,7 +922,8 @@ struct nodelete { template void operator()(T*) { } }; PYBIND11_NAMESPACE_BEGIN(detail) template struct overload_cast_impl { - constexpr overload_cast_impl() {}; // NOLINT(modernize-use-equals-default): MSVC 2015 needs this + // NOLINTNEXTLINE(modernize-use-equals-default): MSVC 2015 needs this + constexpr overload_cast_impl() {} template constexpr auto operator()(Return (*pf)(Args...)) const noexcept @@ -817,6 +979,7 @@ public: // Implicit conversion constructor from any arbitrary container type with values convertible to T template ())), T>::value>> + // NOLINTNEXTLINE(google-explicit-constructor) any_container(const Container &c) : any_container(std::begin(c), std::end(c)) { } // initializer_list's aren't deducible, so don't get matched by the above template; we need this @@ -825,9 +988,11 @@ public: any_container(const std::initializer_list &c) : any_container(c.begin(), c.end()) { } // Avoid copying if given an rvalue vector of the correct type. + // NOLINTNEXTLINE(google-explicit-constructor) any_container(std::vector &&v) : v(std::move(v)) { } // Moves the vector out of an rvalue any_container + // NOLINTNEXTLINE(google-explicit-constructor) operator std::vector &&() && { return std::move(v); } // Dereferencing obtains a reference to the underlying vector @@ -839,8 +1004,60 @@ public: const std::vector *operator->() const { return &v; } }; +// Forward-declaration; see detail/class.h +std::string get_fully_qualified_tp_name(PyTypeObject*); + +template +inline static std::shared_ptr try_get_shared_from_this(std::enable_shared_from_this *holder_value_ptr) { +// Pre C++17, this code path exploits undefined behavior, but is known to work on many platforms. +// Use at your own risk! +// See also https://en.cppreference.com/w/cpp/memory/enable_shared_from_this, and in particular +// the `std::shared_ptr gp1 = not_so_good.getptr();` and `try`-`catch` parts of the example. +#if defined(__cpp_lib_enable_shared_from_this) && (!defined(_MSC_VER) || _MSC_VER >= 1912) + return holder_value_ptr->weak_from_this().lock(); +#else + try { + return holder_value_ptr->shared_from_this(); + } + catch (const std::bad_weak_ptr &) { + return nullptr; + } +#endif +} + +// For silencing "unused" compiler warnings in special situations. +template +#if defined(_MSC_VER) && _MSC_VER >= 1910 && _MSC_VER < 1920 // MSVC 2017 +constexpr +#endif +inline void silence_unused_warnings(Args &&...) {} + +// MSVC warning C4100: Unreferenced formal parameter +#if defined(_MSC_VER) && _MSC_VER <= 1916 +# define PYBIND11_WORKAROUND_INCORRECT_MSVC_C4100(...) \ + detail::silence_unused_warnings(__VA_ARGS__) +#else +# define PYBIND11_WORKAROUND_INCORRECT_MSVC_C4100(...) +#endif + +// GCC -Wunused-but-set-parameter All GCC versions (as of July 2021). +#if defined(__GNUG__) && !defined(__clang__) && !defined(__INTEL_COMPILER) +# define PYBIND11_WORKAROUND_INCORRECT_GCC_UNUSED_BUT_SET_PARAMETER(...) \ + detail::silence_unused_warnings(__VA_ARGS__) +#else +# define PYBIND11_WORKAROUND_INCORRECT_GCC_UNUSED_BUT_SET_PARAMETER(...) +#endif + +#if defined(_MSC_VER) // All versions (as of July 2021). + +// warning C4127: Conditional expression is constant +constexpr inline bool silence_msvc_c4127(bool cond) { return cond; } + +# define PYBIND11_SILENCE_MSVC_C4127(...) ::pybind11::detail::silence_msvc_c4127(__VA_ARGS__) + +#else +# define PYBIND11_SILENCE_MSVC_C4127(...) __VA_ARGS__ +#endif + PYBIND11_NAMESPACE_END(detail) - - - PYBIND11_NAMESPACE_END(PYBIND11_NAMESPACE) diff --git a/pybind11/include/pybind11/detail/descr.h b/pybind11/include/pybind11/detail/descr.h index 92720cd56..0f93e06b2 100644 --- a/pybind11/include/pybind11/detail/descr.h +++ b/pybind11/include/pybind11/detail/descr.h @@ -23,15 +23,17 @@ PYBIND11_NAMESPACE_BEGIN(detail) /* Concatenate type signatures at compile time */ template struct descr { - char text[N + 1]; + char text[N + 1]{'\0'}; - constexpr descr() : text{'\0'} { } + constexpr descr() = default; + // NOLINTNEXTLINE(google-explicit-constructor) constexpr descr(char const (&s)[N+1]) : descr(s, make_index_sequence()) { } template constexpr descr(char const (&s)[N+1], index_sequence) : text{s[Is]..., '\0'} { } template + // NOLINTNEXTLINE(google-explicit-constructor) constexpr descr(char c, Chars... cs) : text{c, static_cast(cs)..., '\0'} { } static constexpr std::array types() { @@ -42,6 +44,7 @@ struct descr { template constexpr descr plus_impl(const descr &a, const descr &b, index_sequence, index_sequence) { + PYBIND11_WORKAROUND_INCORRECT_MSVC_C4100(b); return {a.text[Is1]..., b.text[Is2]...}; } @@ -51,34 +54,64 @@ constexpr descr operator+(const descr &a, c } template -constexpr descr _(char const(&text)[N]) { return descr(text); } -constexpr descr<0> _(char const(&)[1]) { return {}; } +constexpr descr const_name(char const(&text)[N]) { return descr(text); } +constexpr descr<0> const_name(char const(&)[1]) { return {}; } template struct int_to_str : int_to_str { }; template struct int_to_str<0, Digits...> { + // WARNING: This only works with C++17 or higher. static constexpr auto digits = descr(('0' + Digits)...); }; // Ternary description (like std::conditional) template -constexpr enable_if_t> _(char const(&text1)[N1], char const(&)[N2]) { - return _(text1); +constexpr enable_if_t> const_name(char const(&text1)[N1], char const(&)[N2]) { + return const_name(text1); } template -constexpr enable_if_t> _(char const(&)[N1], char const(&text2)[N2]) { - return _(text2); +constexpr enable_if_t> const_name(char const(&)[N1], char const(&text2)[N2]) { + return const_name(text2); } template -constexpr enable_if_t _(const T1 &d, const T2 &) { return d; } +constexpr enable_if_t const_name(const T1 &d, const T2 &) { return d; } template -constexpr enable_if_t _(const T1 &, const T2 &d) { return d; } +constexpr enable_if_t const_name(const T1 &, const T2 &d) { return d; } -template auto constexpr _() -> decltype(int_to_str::digits) { +template +auto constexpr const_name() -> remove_cv_t::digits)> { return int_to_str::digits; } -template constexpr descr<1, Type> _() { return {'%'}; } +template constexpr descr<1, Type> const_name() { return {'%'}; } + +// If "_" is defined as a macro, py::detail::_ cannot be provided. +// It is therefore best to use py::detail::const_name universally. +// This block is for backward compatibility only. +// (The const_name code is repeated to avoid introducing a "_" #define ourselves.) +#ifndef _ +#define PYBIND11_DETAIL_UNDERSCORE_BACKWARD_COMPATIBILITY +template +constexpr descr _(char const(&text)[N]) { return const_name(text); } +template +constexpr enable_if_t> _(char const(&text1)[N1], char const(&text2)[N2]) { + return const_name(text1, text2); +} +template +constexpr enable_if_t> _(char const(&text1)[N1], char const(&text2)[N2]) { + return const_name(text1, text2); +} +template +constexpr enable_if_t _(const T1 &d1, const T2 &d2) { return const_name(d1, d2); } +template +constexpr enable_if_t _(const T1 &d1, const T2 &d2) { return const_name(d1, d2); } + +template +auto constexpr _() -> remove_cv_t::digits)> { + return const_name(); +} +template constexpr descr<1, Type> _() { return const_name(); } +#endif // #ifndef _ constexpr descr<0> concat() { return {}; } @@ -88,12 +121,12 @@ constexpr descr concat(const descr &descr) { return descr; } template constexpr auto concat(const descr &d, const Args &...args) -> decltype(std::declval>() + concat(args...)) { - return d + _(", ") + concat(args...); + return d + const_name(", ") + concat(args...); } template constexpr descr type_descr(const descr &descr) { - return _("{") + descr + _("}"); + return const_name("{") + descr + const_name("}"); } PYBIND11_NAMESPACE_END(detail) diff --git a/pybind11/include/pybind11/detail/init.h b/pybind11/include/pybind11/detail/init.h index 3ef78c117..eaaad5a07 100644 --- a/pybind11/include/pybind11/detail/init.h +++ b/pybind11/include/pybind11/detail/init.h @@ -23,8 +23,8 @@ public: } template using cast_op_type = value_and_holder &; - operator value_and_holder &() { return *value; } - static constexpr auto name = _(); + explicit operator value_and_holder &() { return *value; } + static constexpr auto name = const_name(); private: value_and_holder *value = nullptr; @@ -94,8 +94,9 @@ void construct(...) { // construct an Alias from the returned base instance. template void construct(value_and_holder &v_h, Cpp *ptr, bool need_alias) { + PYBIND11_WORKAROUND_INCORRECT_MSVC_C4100(need_alias); no_nullptr(ptr); - if (Class::has_alias && need_alias && !is_alias(ptr)) { + if (PYBIND11_SILENCE_MSVC_C4127(Class::has_alias) && need_alias && !is_alias(ptr)) { // We're going to try to construct an alias by moving the cpp type. Whether or not // that succeeds, we still need to destroy the original cpp pointer (either the // moved away leftover, if the alias construction works, or the value itself if we @@ -131,10 +132,11 @@ void construct(value_and_holder &v_h, Alias *alias_ptr, bool) { // derived type (through those holder's implicit conversion from derived class holder constructors). template void construct(value_and_holder &v_h, Holder holder, bool need_alias) { + PYBIND11_WORKAROUND_INCORRECT_MSVC_C4100(need_alias); auto *ptr = holder_helper>::get(holder); no_nullptr(ptr); // If we need an alias, check that the held pointer is actually an alias instance - if (Class::has_alias && need_alias && !is_alias(ptr)) + if (PYBIND11_SILENCE_MSVC_C4127(Class::has_alias) && need_alias && !is_alias(ptr)) throw type_error("pybind11::init(): construction failed: returned holder-wrapped instance " "is not an alias instance"); @@ -148,9 +150,10 @@ void construct(value_and_holder &v_h, Holder holder, bool need_alias) { // need it, we simply move-construct the cpp value into a new instance. template void construct(value_and_holder &v_h, Cpp &&result, bool need_alias) { + PYBIND11_WORKAROUND_INCORRECT_MSVC_C4100(need_alias); static_assert(std::is_move_constructible>::value, "pybind11::init() return-by-value factory function requires a movable class"); - if (Class::has_alias && need_alias) + if (PYBIND11_SILENCE_MSVC_C4127(Class::has_alias) && need_alias) construct_alias_from_cpp(is_alias_constructible{}, v_h, std::move(result)); else v_h.value_ptr() = new Cpp(std::move(result)); @@ -219,7 +222,8 @@ template struct factory { remove_reference_t class_factory; - factory(Func &&f) : class_factory(std::forward(f)) { } + // NOLINTNEXTLINE(google-explicit-constructor) + factory(Func &&f) : class_factory(std::forward(f)) {} // The given class either has no alias or has no separate alias factory; // this always constructs the class itself. If the class is registered with an alias @@ -293,7 +297,13 @@ template ::value, int> = 0> void setstate(value_and_holder &v_h, std::pair &&result, bool need_alias) { construct(v_h, std::move(result.first), need_alias); - setattr((PyObject *) v_h.inst, "__dict__", result.second); + auto d = handle(result.second); + if (PyDict_Check(d.ptr()) && PyDict_Size(d.ptr()) == 0) { + // Skipping setattr below, to not force use of py::dynamic_attr() for Class unnecessarily. + // See PR #2972 for details. + return; + } + setattr((PyObject *) v_h.inst, "__dict__", d); } /// Implementation for py::pickle(GetState, SetState) diff --git a/pybind11/include/pybind11/detail/internals.h b/pybind11/include/pybind11/detail/internals.h index 133d2f4c8..9edb9492e 100644 --- a/pybind11/include/pybind11/detail/internals.h +++ b/pybind11/include/pybind11/detail/internals.h @@ -10,9 +10,32 @@ #pragma once #include "../pytypes.h" +#include + +/// Tracks the `internals` and `type_info` ABI version independent of the main library version. +/// +/// Some portions of the code use an ABI that is conditional depending on this +/// version number. That allows ABI-breaking changes to be "pre-implemented". +/// Once the default version number is incremented, the conditional logic that +/// no longer applies can be removed. Additionally, users that need not +/// maintain ABI compatibility can increase the version number in order to take +/// advantage of any functionality/efficiency improvements that depend on the +/// newer ABI. +/// +/// WARNING: If you choose to manually increase the ABI version, note that +/// pybind11 may not be tested as thoroughly with a non-default ABI version, and +/// further ABI-incompatible changes may be made before the ABI is officially +/// changed to the new version. +#ifndef PYBIND11_INTERNALS_VERSION +# define PYBIND11_INTERNALS_VERSION 4 +#endif PYBIND11_NAMESPACE_BEGIN(PYBIND11_NAMESPACE) + +using ExceptionTranslator = void (*)(std::exception_ptr); + PYBIND11_NAMESPACE_BEGIN(detail) + // Forward declarations inline PyTypeObject *make_static_property_type(); inline PyTypeObject *make_default_metaclass(); @@ -21,30 +44,59 @@ inline PyObject *make_object_base_type(PyTypeObject *metaclass); // The old Python Thread Local Storage (TLS) API is deprecated in Python 3.7 in favor of the new // Thread Specific Storage (TSS) API. #if PY_VERSION_HEX >= 0x03070000 -# define PYBIND11_TLS_KEY_INIT(var) Py_tss_t *var = nullptr -# define PYBIND11_TLS_GET_VALUE(key) PyThread_tss_get((key)) -# define PYBIND11_TLS_REPLACE_VALUE(key, value) PyThread_tss_set((key), (value)) -# define PYBIND11_TLS_DELETE_VALUE(key) PyThread_tss_set((key), nullptr) -# define PYBIND11_TLS_FREE(key) PyThread_tss_free(key) -#else - // Usually an int but a long on Cygwin64 with Python 3.x -# define PYBIND11_TLS_KEY_INIT(var) decltype(PyThread_create_key()) var = 0 -# define PYBIND11_TLS_GET_VALUE(key) PyThread_get_key_value((key)) -# if PY_MAJOR_VERSION < 3 -# define PYBIND11_TLS_DELETE_VALUE(key) \ - PyThread_delete_key_value(key) -# define PYBIND11_TLS_REPLACE_VALUE(key, value) \ - do { \ - PyThread_delete_key_value((key)); \ - PyThread_set_key_value((key), (value)); \ - } while (false) +// Avoid unnecessary allocation of `Py_tss_t`, since we cannot use +// `Py_LIMITED_API` anyway. +# if PYBIND11_INTERNALS_VERSION > 4 +# define PYBIND11_TLS_KEY_REF Py_tss_t & +# ifdef __GNUC__ +// Clang on macOS warns due to `Py_tss_NEEDS_INIT` not specifying an initializer +// for every field. +# define PYBIND11_TLS_KEY_INIT(var) \ + _Pragma("GCC diagnostic push") /**/ \ + _Pragma("GCC diagnostic ignored \"-Wmissing-field-initializers\"") /**/ \ + Py_tss_t var \ + = Py_tss_NEEDS_INIT; \ + _Pragma("GCC diagnostic pop") +# else +# define PYBIND11_TLS_KEY_INIT(var) Py_tss_t var = Py_tss_NEEDS_INIT; +# endif +# define PYBIND11_TLS_KEY_CREATE(var) (PyThread_tss_create(&(var)) == 0) +# define PYBIND11_TLS_GET_VALUE(key) PyThread_tss_get(&(key)) +# define PYBIND11_TLS_REPLACE_VALUE(key, value) PyThread_tss_set(&(key), (value)) +# define PYBIND11_TLS_DELETE_VALUE(key) PyThread_tss_set(&(key), nullptr) +# define PYBIND11_TLS_FREE(key) PyThread_tss_delete(&(key)) # else -# define PYBIND11_TLS_DELETE_VALUE(key) \ - PyThread_set_key_value((key), nullptr) -# define PYBIND11_TLS_REPLACE_VALUE(key, value) \ - PyThread_set_key_value((key), (value)) +# define PYBIND11_TLS_KEY_REF Py_tss_t * +# define PYBIND11_TLS_KEY_INIT(var) Py_tss_t *var = nullptr; +# define PYBIND11_TLS_KEY_CREATE(var) \ + (((var) = PyThread_tss_alloc()) != nullptr && (PyThread_tss_create((var)) == 0)) +# define PYBIND11_TLS_GET_VALUE(key) PyThread_tss_get((key)) +# define PYBIND11_TLS_REPLACE_VALUE(key, value) PyThread_tss_set((key), (value)) +# define PYBIND11_TLS_DELETE_VALUE(key) PyThread_tss_set((key), nullptr) +# define PYBIND11_TLS_FREE(key) PyThread_tss_free(key) # endif -# define PYBIND11_TLS_FREE(key) (void)key +#else +// Usually an int but a long on Cygwin64 with Python 3.x +# define PYBIND11_TLS_KEY_REF decltype(PyThread_create_key()) +# define PYBIND11_TLS_KEY_INIT(var) PYBIND11_TLS_KEY_REF var = 0; +# define PYBIND11_TLS_KEY_CREATE(var) (((var) = PyThread_create_key()) != -1) +# define PYBIND11_TLS_GET_VALUE(key) PyThread_get_key_value((key)) +# if PY_MAJOR_VERSION < 3 || defined(PYPY_VERSION) +// On CPython < 3.4 and on PyPy, `PyThread_set_key_value` strangely does not set +// the value if it has already been set. Instead, it must first be deleted and +// then set again. +inline void tls_replace_value(PYBIND11_TLS_KEY_REF key, void *value) { + PyThread_delete_key_value(key); + PyThread_set_key_value(key, value); +} +# define PYBIND11_TLS_DELETE_VALUE(key) PyThread_delete_key_value(key) +# define PYBIND11_TLS_REPLACE_VALUE(key, value) \ + ::pybind11::detail::tls_replace_value((key), (value)) +# else +# define PYBIND11_TLS_DELETE_VALUE(key) PyThread_set_key_value((key), nullptr) +# define PYBIND11_TLS_REPLACE_VALUE(key, value) PyThread_set_key_value((key), (value)) +# endif +# define PYBIND11_TLS_FREE(key) (void) key #endif // Python loads modules by default with dlopen with the RTLD_LOCAL flag; under libc++ and possibly @@ -100,24 +152,33 @@ struct internals { std::unordered_set, override_hash> inactive_override_cache; type_map> direct_conversions; std::unordered_map> patients; - std::forward_list registered_exception_translators; + std::forward_list registered_exception_translators; std::unordered_map shared_data; // Custom data to be shared across extensions - std::vector loader_patient_stack; // Used by `loader_life_support` +#if PYBIND11_INTERNALS_VERSION == 4 + std::vector unused_loader_patient_stack_remove_at_v5; +#endif std::forward_list static_strings; // Stores the std::strings backing detail::c_str() PyTypeObject *static_property_type; PyTypeObject *default_metaclass; PyObject *instance_base; #if defined(WITH_THREAD) - PYBIND11_TLS_KEY_INIT(tstate); + PYBIND11_TLS_KEY_INIT(tstate) +# if PYBIND11_INTERNALS_VERSION > 4 + PYBIND11_TLS_KEY_INIT(loader_life_support_tls_key) +# endif // PYBIND11_INTERNALS_VERSION > 4 PyInterpreterState *istate = nullptr; ~internals() { +# if PYBIND11_INTERNALS_VERSION > 4 + PYBIND11_TLS_FREE(loader_life_support_tls_key); +# endif // PYBIND11_INTERNALS_VERSION > 4 + // This destructor is called *after* Py_Finalize() in finalize_interpreter(). - // That *SHOULD BE* fine. The following details what happens whe PyThread_tss_free is called. - // PYBIND11_TLS_FREE is PyThread_tss_free on python 3.7+. On older python, it does nothing. - // PyThread_tss_free calls PyThread_tss_delete and PyMem_RawFree. - // PyThread_tss_delete just calls TlsFree (on Windows) or pthread_key_delete (on *NIX). Neither - // of those have anything to do with CPython internals. - // PyMem_RawFree *requires* that the `tstate` be allocated with the CPython allocator. + // That *SHOULD BE* fine. The following details what happens when PyThread_tss_free is + // called. PYBIND11_TLS_FREE is PyThread_tss_free on python 3.7+. On older python, it does + // nothing. PyThread_tss_free calls PyThread_tss_delete and PyMem_RawFree. + // PyThread_tss_delete just calls TlsFree (on Windows) or pthread_key_delete (on *NIX). + // Neither of those have anything to do with CPython internals. PyMem_RawFree *requires* + // that the `tstate` be allocated with the CPython allocator. PYBIND11_TLS_FREE(tstate); } #endif @@ -139,7 +200,9 @@ struct type_info { void *get_buffer_data = nullptr; void *(*module_local_load)(PyObject *, const type_info *) = nullptr; /* A simple type never occurs as a (direct or indirect) parent - * of a class that makes use of multiple inheritance */ + * of a class that makes use of multiple inheritance. + * A type can be simple even if it has non-simple ancestors as long as it has no descendants. + */ bool simple_type : 1; /* True if there is no multiple inheritance in this type's inheritance tree */ bool simple_ancestors : 1; @@ -149,54 +212,62 @@ struct type_info { bool module_local : 1; }; -/// Tracks the `internals` and `type_info` ABI version independent of the main library version -#define PYBIND11_INTERNALS_VERSION 4 - /// On MSVC, debug and release builds are not ABI-compatible! #if defined(_MSC_VER) && defined(_DEBUG) -# define PYBIND11_BUILD_TYPE "_debug" +# define PYBIND11_BUILD_TYPE "_debug" #else -# define PYBIND11_BUILD_TYPE "" +# define PYBIND11_BUILD_TYPE "" #endif /// Let's assume that different compilers are ABI-incompatible. -#if defined(_MSC_VER) -# define PYBIND11_COMPILER_TYPE "_msvc" -#elif defined(__INTEL_COMPILER) -# define PYBIND11_COMPILER_TYPE "_icc" -#elif defined(__clang__) -# define PYBIND11_COMPILER_TYPE "_clang" -#elif defined(__PGI) -# define PYBIND11_COMPILER_TYPE "_pgi" -#elif defined(__MINGW32__) -# define PYBIND11_COMPILER_TYPE "_mingw" -#elif defined(__CYGWIN__) -# define PYBIND11_COMPILER_TYPE "_gcc_cygwin" -#elif defined(__GNUC__) -# define PYBIND11_COMPILER_TYPE "_gcc" -#else -# define PYBIND11_COMPILER_TYPE "_unknown" +/// A user can manually set this string if they know their +/// compiler is compatible. +#ifndef PYBIND11_COMPILER_TYPE +# if defined(_MSC_VER) +# define PYBIND11_COMPILER_TYPE "_msvc" +# elif defined(__INTEL_COMPILER) +# define PYBIND11_COMPILER_TYPE "_icc" +# elif defined(__clang__) +# define PYBIND11_COMPILER_TYPE "_clang" +# elif defined(__PGI) +# define PYBIND11_COMPILER_TYPE "_pgi" +# elif defined(__MINGW32__) +# define PYBIND11_COMPILER_TYPE "_mingw" +# elif defined(__CYGWIN__) +# define PYBIND11_COMPILER_TYPE "_gcc_cygwin" +# elif defined(__GNUC__) +# define PYBIND11_COMPILER_TYPE "_gcc" +# else +# define PYBIND11_COMPILER_TYPE "_unknown" +# endif #endif -#if defined(_LIBCPP_VERSION) -# define PYBIND11_STDLIB "_libcpp" -#elif defined(__GLIBCXX__) || defined(__GLIBCPP__) -# define PYBIND11_STDLIB "_libstdcpp" -#else -# define PYBIND11_STDLIB "" +/// Also standard libs +#ifndef PYBIND11_STDLIB +# if defined(_LIBCPP_VERSION) +# define PYBIND11_STDLIB "_libcpp" +# elif defined(__GLIBCXX__) || defined(__GLIBCPP__) +# define PYBIND11_STDLIB "_libstdcpp" +# else +# define PYBIND11_STDLIB "" +# endif #endif /// On Linux/OSX, changes in __GXX_ABI_VERSION__ indicate ABI incompatibility. -#if defined(__GXX_ABI_VERSION) -# define PYBIND11_BUILD_ABI "_cxxabi" PYBIND11_TOSTRING(__GXX_ABI_VERSION) -#else -# define PYBIND11_BUILD_ABI "" +#ifndef PYBIND11_BUILD_ABI +# if defined(__GXX_ABI_VERSION) +# define PYBIND11_BUILD_ABI "_cxxabi" PYBIND11_TOSTRING(__GXX_ABI_VERSION) +# else +# define PYBIND11_BUILD_ABI "" +# endif #endif -#if defined(WITH_THREAD) -# define PYBIND11_INTERNALS_KIND "" -#else -# define PYBIND11_INTERNALS_KIND "_without_thread" +#ifndef PYBIND11_INTERNALS_KIND +# if defined(WITH_THREAD) +# define PYBIND11_INTERNALS_KIND "" +# else +# define PYBIND11_INTERNALS_KIND "_without_thread" +# endif #endif #define PYBIND11_INTERNALS_ID "__pybind11_internals_v" \ @@ -212,21 +283,104 @@ inline internals **&get_internals_pp() { return internals_pp; } +#if PY_VERSION_HEX >= 0x03030000 +// forward decl +inline void translate_exception(std::exception_ptr); + +template >::value, int> = 0> +bool handle_nested_exception(const T &exc, const std::exception_ptr &p) { + std::exception_ptr nested = exc.nested_ptr(); + if (nested != nullptr && nested != p) { + translate_exception(nested); + return true; + } + return false; +} + +template >::value, int> = 0> +bool handle_nested_exception(const T &exc, const std::exception_ptr &p) { + if (auto *nep = dynamic_cast(std::addressof(exc))) { + return handle_nested_exception(*nep, p); + } + return false; +} + +#else + +template +bool handle_nested_exception(const T &, std::exception_ptr &) { + return false; +} +#endif + +inline bool raise_err(PyObject *exc_type, const char *msg) { +#if PY_VERSION_HEX >= 0x03030000 + if (PyErr_Occurred()) { + raise_from(exc_type, msg); + return true; + } +#endif + PyErr_SetString(exc_type, msg); + return false; +} + inline void translate_exception(std::exception_ptr p) { + if (!p) { + return; + } try { - if (p) std::rethrow_exception(p); - } catch (error_already_set &e) { e.restore(); return; - } catch (const builtin_exception &e) { e.set_error(); return; - } catch (const std::bad_alloc &e) { PyErr_SetString(PyExc_MemoryError, e.what()); return; - } catch (const std::domain_error &e) { PyErr_SetString(PyExc_ValueError, e.what()); return; - } catch (const std::invalid_argument &e) { PyErr_SetString(PyExc_ValueError, e.what()); return; - } catch (const std::length_error &e) { PyErr_SetString(PyExc_ValueError, e.what()); return; - } catch (const std::out_of_range &e) { PyErr_SetString(PyExc_IndexError, e.what()); return; - } catch (const std::range_error &e) { PyErr_SetString(PyExc_ValueError, e.what()); return; - } catch (const std::overflow_error &e) { PyErr_SetString(PyExc_OverflowError, e.what()); return; - } catch (const std::exception &e) { PyErr_SetString(PyExc_RuntimeError, e.what()); return; + std::rethrow_exception(p); + } catch (error_already_set &e) { + handle_nested_exception(e, p); + e.restore(); + return; + } catch (const builtin_exception &e) { + // Could not use template since it's an abstract class. + if (auto *nep = dynamic_cast(std::addressof(e))) { + handle_nested_exception(*nep, p); + } + e.set_error(); + return; + } catch (const std::bad_alloc &e) { + handle_nested_exception(e, p); + raise_err(PyExc_MemoryError, e.what()); + return; + } catch (const std::domain_error &e) { + handle_nested_exception(e, p); + raise_err(PyExc_ValueError, e.what()); + return; + } catch (const std::invalid_argument &e) { + handle_nested_exception(e, p); + raise_err(PyExc_ValueError, e.what()); + return; + } catch (const std::length_error &e) { + handle_nested_exception(e, p); + raise_err(PyExc_ValueError, e.what()); + return; + } catch (const std::out_of_range &e) { + handle_nested_exception(e, p); + raise_err(PyExc_IndexError, e.what()); + return; + } catch (const std::range_error &e) { + handle_nested_exception(e, p); + raise_err(PyExc_ValueError, e.what()); + return; + } catch (const std::overflow_error &e) { + handle_nested_exception(e, p); + raise_err(PyExc_OverflowError, e.what()); + return; + } catch (const std::exception &e) { + handle_nested_exception(e, p); + raise_err(PyExc_RuntimeError, e.what()); + return; + } catch (const std::nested_exception &e) { + handle_nested_exception(e, p); + raise_err(PyExc_RuntimeError, "Caught an unknown nested exception!"); + return; } catch (...) { - PyErr_SetString(PyExc_RuntimeError, "Caught an unknown exception!"); + raise_err(PyExc_RuntimeError, "Caught an unknown exception!"); return; } } @@ -242,7 +396,7 @@ inline void translate_local_exception(std::exception_ptr p) { #endif /// Return a reference to the current `internals` data -PYBIND11_NOINLINE inline internals &get_internals() { +PYBIND11_NOINLINE internals &get_internals() { auto **&internals_pp = get_internals_pp(); if (internals_pp && *internals_pp) return **internals_pp; @@ -255,7 +409,7 @@ PYBIND11_NOINLINE inline internals &get_internals() { const PyGILState_STATE state; } gil; - constexpr auto *id = PYBIND11_INTERNALS_ID; + PYBIND11_STR_TYPE id(PYBIND11_INTERNALS_ID); auto builtins = handle(PyEval_GetBuiltins()); if (builtins.contains(id) && isinstance(builtins[id])) { internals_pp = static_cast(capsule(builtins[id])); @@ -265,6 +419,8 @@ PYBIND11_NOINLINE inline internals &get_internals() { // initial exception translator, below, so add another for our local exception classes. // // libstdc++ doesn't require this (types there are identified only by name) + // libc++ with CPython doesn't require this (types are explicitly exported) + // libc++ with PyPy still need it, awaiting further investigation #if !defined(__GLIBCXX__) (*internals_pp)->registered_exception_translators.push_front(&translate_local_exception); #endif @@ -274,21 +430,21 @@ PYBIND11_NOINLINE inline internals &get_internals() { internals_ptr = new internals(); #if defined(WITH_THREAD) - #if PY_VERSION_HEX < 0x03090000 - PyEval_InitThreads(); - #endif +# if PY_VERSION_HEX < 0x03090000 + PyEval_InitThreads(); +# endif PyThreadState *tstate = PyThreadState_Get(); - #if PY_VERSION_HEX >= 0x03070000 - internals_ptr->tstate = PyThread_tss_alloc(); - if (!internals_ptr->tstate || PyThread_tss_create(internals_ptr->tstate)) - pybind11_fail("get_internals: could not successfully initialize the TSS key!"); - PyThread_tss_set(internals_ptr->tstate, tstate); - #else - internals_ptr->tstate = PyThread_create_key(); - if (internals_ptr->tstate == -1) - pybind11_fail("get_internals: could not successfully initialize the TLS key!"); - PyThread_set_key_value(internals_ptr->tstate, tstate); - #endif + if (!PYBIND11_TLS_KEY_CREATE(internals_ptr->tstate)) { + pybind11_fail("get_internals: could not successfully initialize the tstate TSS key!"); + } + PYBIND11_TLS_REPLACE_VALUE(internals_ptr->tstate, tstate); + +# if PYBIND11_INTERNALS_VERSION > 4 + if (!PYBIND11_TLS_KEY_CREATE(internals_ptr->loader_life_support_tls_key)) { + pybind11_fail("get_internals: could not successfully initialize the " + "loader_life_support TSS key!"); + } +# endif internals_ptr->istate = tstate->interp; #endif builtins[id] = capsule(internals_pp); @@ -300,12 +456,57 @@ PYBIND11_NOINLINE inline internals &get_internals() { return **internals_pp; } -/// Works like `internals.registered_types_cpp`, but for module-local registered types: -inline type_map ®istered_local_types_cpp() { - static type_map locals{}; - return locals; +// the internals struct (above) is shared between all the modules. local_internals are only +// for a single module. Any changes made to internals may require an update to +// PYBIND11_INTERNALS_VERSION, breaking backwards compatibility. local_internals is, by design, +// restricted to a single module. Whether a module has local internals or not should not +// impact any other modules, because the only things accessing the local internals is the +// module that contains them. +struct local_internals { + type_map registered_types_cpp; + std::forward_list registered_exception_translators; +#if defined(WITH_THREAD) && PYBIND11_INTERNALS_VERSION == 4 + + // For ABI compatibility, we can't store the loader_life_support TLS key in + // the `internals` struct directly. Instead, we store it in `shared_data` and + // cache a copy in `local_internals`. If we allocated a separate TLS key for + // each instance of `local_internals`, we could end up allocating hundreds of + // TLS keys if hundreds of different pybind11 modules are loaded (which is a + // plausible number). + PYBIND11_TLS_KEY_INIT(loader_life_support_tls_key) + + // Holds the shared TLS key for the loader_life_support stack. + struct shared_loader_life_support_data { + PYBIND11_TLS_KEY_INIT(loader_life_support_tls_key) + shared_loader_life_support_data() { + if (!PYBIND11_TLS_KEY_CREATE(loader_life_support_tls_key)) { + pybind11_fail("local_internals: could not successfully initialize the " + "loader_life_support TLS key!"); + } + } + // We can't help but leak the TLS key, because Python never unloads extension modules. + }; + + local_internals() { + auto &internals = get_internals(); + // Get or create the `loader_life_support_stack_key`. + auto &ptr = internals.shared_data["_life_support"]; + if (!ptr) { + ptr = new shared_loader_life_support_data; + } + loader_life_support_tls_key + = static_cast(ptr)->loader_life_support_tls_key; + } +#endif // defined(WITH_THREAD) && PYBIND11_INTERNALS_VERSION == 4 +}; + +/// Works like `get_internals`, but for things which are locally registered. +inline local_internals &get_local_internals() { + static local_internals locals; + return locals; } + /// Constructs a std::string with the given arguments, stores it in `internals`, and returns its /// `c_str()`. Such strings objects have a long storage duration -- the internal strings are only /// cleared when the program exits or after interpreter shutdown (when embedding), and so are @@ -322,14 +523,14 @@ PYBIND11_NAMESPACE_END(detail) /// Returns a named pointer that is shared among all extension modules (using the same /// pybind11 version) running in the current interpreter. Names starting with underscores /// are reserved for internal usage. Returns `nullptr` if no matching entry was found. -inline PYBIND11_NOINLINE void *get_shared_data(const std::string &name) { +PYBIND11_NOINLINE void *get_shared_data(const std::string &name) { auto &internals = detail::get_internals(); auto it = internals.shared_data.find(name); return it != internals.shared_data.end() ? it->second : nullptr; } /// Set the shared data that can be later recovered by `get_shared_data()`. -inline PYBIND11_NOINLINE void *set_shared_data(const std::string &name, void *data) { +PYBIND11_NOINLINE void *set_shared_data(const std::string &name, void *data) { detail::get_internals().shared_data[name] = data; return data; } diff --git a/pybind11/include/pybind11/detail/type_caster_base.h b/pybind11/include/pybind11/detail/type_caster_base.h new file mode 100644 index 000000000..48e218b2f --- /dev/null +++ b/pybind11/include/pybind11/detail/type_caster_base.h @@ -0,0 +1,985 @@ +/* + pybind11/detail/type_caster_base.h (originally first part of pybind11/cast.h) + + Copyright (c) 2016 Wenzel Jakob + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#pragma once + +#include "../pytypes.h" +#include "common.h" +#include "descr.h" +#include "internals.h" +#include "typeid.h" +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +PYBIND11_NAMESPACE_BEGIN(PYBIND11_NAMESPACE) +PYBIND11_NAMESPACE_BEGIN(detail) + +/// A life support system for temporary objects created by `type_caster::load()`. +/// Adding a patient will keep it alive up until the enclosing function returns. +class loader_life_support { +private: + loader_life_support* parent = nullptr; + std::unordered_set keep_alive; + +#if defined(WITH_THREAD) + // Store stack pointer in thread-local storage. + static PYBIND11_TLS_KEY_REF get_stack_tls_key() { +# if PYBIND11_INTERNALS_VERSION == 4 + return get_local_internals().loader_life_support_tls_key; +# else + return get_internals().loader_life_support_tls_key; +# endif + } + static loader_life_support *get_stack_top() { + return static_cast(PYBIND11_TLS_GET_VALUE(get_stack_tls_key())); + } + static void set_stack_top(loader_life_support *value) { + PYBIND11_TLS_REPLACE_VALUE(get_stack_tls_key(), value); + } +#else + // Use single global variable for stack. + static loader_life_support **get_stack_pp() { + static loader_life_support *global_stack = nullptr; + return global_stack; + } + static loader_life_support *get_stack_top() { return *get_stack_pp(); } + static void set_stack_top(loader_life_support *value) { *get_stack_pp() = value; } +#endif + +public: + /// A new patient frame is created when a function is entered + loader_life_support() { + parent = get_stack_top(); + set_stack_top(this); + } + + /// ... and destroyed after it returns + ~loader_life_support() { + if (get_stack_top() != this) + pybind11_fail("loader_life_support: internal error"); + set_stack_top(parent); + for (auto* item : keep_alive) + Py_DECREF(item); + } + + /// This can only be used inside a pybind11-bound function, either by `argument_loader` + /// at argument preparation time or by `py::cast()` at execution time. + PYBIND11_NOINLINE static void add_patient(handle h) { + loader_life_support *frame = get_stack_top(); + if (!frame) { + // NOTE: It would be nice to include the stack frames here, as this indicates + // use of pybind11::cast<> outside the normal call framework, finding such + // a location is challenging. Developers could consider printing out + // stack frame addresses here using something like __builtin_frame_address(0) + throw cast_error("When called outside a bound function, py::cast() cannot " + "do Python -> C++ conversions which require the creation " + "of temporary values"); + } + + if (frame->keep_alive.insert(h.ptr()).second) + Py_INCREF(h.ptr()); + } +}; + +// Gets the cache entry for the given type, creating it if necessary. The return value is the pair +// returned by emplace, i.e. an iterator for the entry and a bool set to `true` if the entry was +// just created. +inline std::pair all_type_info_get_cache(PyTypeObject *type); + +// Populates a just-created cache entry. +PYBIND11_NOINLINE void all_type_info_populate(PyTypeObject *t, std::vector &bases) { + std::vector check; + for (handle parent : reinterpret_borrow(t->tp_bases)) + check.push_back((PyTypeObject *) parent.ptr()); + + auto const &type_dict = get_internals().registered_types_py; + for (size_t i = 0; i < check.size(); i++) { + auto type = check[i]; + // Ignore Python2 old-style class super type: + if (!PyType_Check((PyObject *) type)) continue; + + // Check `type` in the current set of registered python types: + auto it = type_dict.find(type); + if (it != type_dict.end()) { + // We found a cache entry for it, so it's either pybind-registered or has pre-computed + // pybind bases, but we have to make sure we haven't already seen the type(s) before: we + // want to follow Python/virtual C++ rules that there should only be one instance of a + // common base. + for (auto *tinfo : it->second) { + // NB: Could use a second set here, rather than doing a linear search, but since + // having a large number of immediate pybind11-registered types seems fairly + // unlikely, that probably isn't worthwhile. + bool found = false; + for (auto *known : bases) { + if (known == tinfo) { found = true; break; } + } + if (!found) bases.push_back(tinfo); + } + } + else if (type->tp_bases) { + // It's some python type, so keep follow its bases classes to look for one or more + // registered types + if (i + 1 == check.size()) { + // When we're at the end, we can pop off the current element to avoid growing + // `check` when adding just one base (which is typical--i.e. when there is no + // multiple inheritance) + check.pop_back(); + i--; + } + for (handle parent : reinterpret_borrow(type->tp_bases)) + check.push_back((PyTypeObject *) parent.ptr()); + } + } +} + +/** + * Extracts vector of type_info pointers of pybind-registered roots of the given Python type. Will + * be just 1 pybind type for the Python type of a pybind-registered class, or for any Python-side + * derived class that uses single inheritance. Will contain as many types as required for a Python + * class that uses multiple inheritance to inherit (directly or indirectly) from multiple + * pybind-registered classes. Will be empty if neither the type nor any base classes are + * pybind-registered. + * + * The value is cached for the lifetime of the Python type. + */ +inline const std::vector &all_type_info(PyTypeObject *type) { + auto ins = all_type_info_get_cache(type); + if (ins.second) + // New cache entry: populate it + all_type_info_populate(type, ins.first->second); + + return ins.first->second; +} + +/** + * Gets a single pybind11 type info for a python type. Returns nullptr if neither the type nor any + * ancestors are pybind11-registered. Throws an exception if there are multiple bases--use + * `all_type_info` instead if you want to support multiple bases. + */ +PYBIND11_NOINLINE detail::type_info* get_type_info(PyTypeObject *type) { + auto &bases = all_type_info(type); + if (bases.empty()) + return nullptr; + if (bases.size() > 1) + pybind11_fail("pybind11::detail::get_type_info: type has multiple pybind11-registered bases"); + return bases.front(); +} + +inline detail::type_info *get_local_type_info(const std::type_index &tp) { + auto &locals = get_local_internals().registered_types_cpp; + auto it = locals.find(tp); + if (it != locals.end()) + return it->second; + return nullptr; +} + +inline detail::type_info *get_global_type_info(const std::type_index &tp) { + auto &types = get_internals().registered_types_cpp; + auto it = types.find(tp); + if (it != types.end()) + return it->second; + return nullptr; +} + +/// Return the type info for a given C++ type; on lookup failure can either throw or return nullptr. +PYBIND11_NOINLINE detail::type_info *get_type_info(const std::type_index &tp, + bool throw_if_missing = false) { + if (auto ltype = get_local_type_info(tp)) + return ltype; + if (auto gtype = get_global_type_info(tp)) + return gtype; + + if (throw_if_missing) { + std::string tname = tp.name(); + detail::clean_type_id(tname); + pybind11_fail("pybind11::detail::get_type_info: unable to find type info for \"" + tname + "\""); + } + return nullptr; +} + +PYBIND11_NOINLINE handle get_type_handle(const std::type_info &tp, bool throw_if_missing) { + detail::type_info *type_info = get_type_info(tp, throw_if_missing); + return handle(type_info ? ((PyObject *) type_info->type) : nullptr); +} + +// Searches the inheritance graph for a registered Python instance, using all_type_info(). +PYBIND11_NOINLINE handle find_registered_python_instance(void *src, + const detail::type_info *tinfo) { + auto it_instances = get_internals().registered_instances.equal_range(src); + for (auto it_i = it_instances.first; it_i != it_instances.second; ++it_i) { + for (auto instance_type : detail::all_type_info(Py_TYPE(it_i->second))) { + if (instance_type && same_type(*instance_type->cpptype, *tinfo->cpptype)) + return handle((PyObject *) it_i->second).inc_ref(); + } + } + return handle(); +} + +struct value_and_holder { + instance *inst = nullptr; + size_t index = 0u; + const detail::type_info *type = nullptr; + void **vh = nullptr; + + // Main constructor for a found value/holder: + value_and_holder(instance *i, const detail::type_info *type, size_t vpos, size_t index) : + inst{i}, index{index}, type{type}, + vh{inst->simple_layout ? inst->simple_value_holder : &inst->nonsimple.values_and_holders[vpos]} + {} + + // Default constructor (used to signal a value-and-holder not found by get_value_and_holder()) + value_and_holder() = default; + + // Used for past-the-end iterator + explicit value_and_holder(size_t index) : index{index} {} + + template V *&value_ptr() const { + return reinterpret_cast(vh[0]); + } + // True if this `value_and_holder` has a non-null value pointer + explicit operator bool() const { return value_ptr() != nullptr; } + + template H &holder() const { + return reinterpret_cast(vh[1]); + } + bool holder_constructed() const { + return inst->simple_layout + ? inst->simple_holder_constructed + : (inst->nonsimple.status[index] & instance::status_holder_constructed) != 0u; + } + // NOLINTNEXTLINE(readability-make-member-function-const) + void set_holder_constructed(bool v = true) { + if (inst->simple_layout) + inst->simple_holder_constructed = v; + else if (v) + inst->nonsimple.status[index] |= instance::status_holder_constructed; + else + inst->nonsimple.status[index] &= (std::uint8_t) ~instance::status_holder_constructed; + } + bool instance_registered() const { + return inst->simple_layout + ? inst->simple_instance_registered + : ((inst->nonsimple.status[index] & instance::status_instance_registered) != 0); + } + // NOLINTNEXTLINE(readability-make-member-function-const) + void set_instance_registered(bool v = true) { + if (inst->simple_layout) + inst->simple_instance_registered = v; + else if (v) + inst->nonsimple.status[index] |= instance::status_instance_registered; + else + inst->nonsimple.status[index] &= (std::uint8_t) ~instance::status_instance_registered; + } +}; + +// Container for accessing and iterating over an instance's values/holders +struct values_and_holders { +private: + instance *inst; + using type_vec = std::vector; + const type_vec &tinfo; + +public: + explicit values_and_holders(instance *inst) + : inst{inst}, tinfo(all_type_info(Py_TYPE(inst))) {} + + struct iterator { + private: + instance *inst = nullptr; + const type_vec *types = nullptr; + value_and_holder curr; + friend struct values_and_holders; + iterator(instance *inst, const type_vec *tinfo) + : inst{inst}, types{tinfo}, + curr(inst /* instance */, + types->empty() ? nullptr : (*types)[0] /* type info */, + 0, /* vpos: (non-simple types only): the first vptr comes first */ + 0 /* index */) + {} + // Past-the-end iterator: + explicit iterator(size_t end) : curr(end) {} + + public: + bool operator==(const iterator &other) const { return curr.index == other.curr.index; } + bool operator!=(const iterator &other) const { return curr.index != other.curr.index; } + iterator &operator++() { + if (!inst->simple_layout) + curr.vh += 1 + (*types)[curr.index]->holder_size_in_ptrs; + ++curr.index; + curr.type = curr.index < types->size() ? (*types)[curr.index] : nullptr; + return *this; + } + value_and_holder &operator*() { return curr; } + value_and_holder *operator->() { return &curr; } + }; + + iterator begin() { return iterator(inst, &tinfo); } + iterator end() { return iterator(tinfo.size()); } + + iterator find(const type_info *find_type) { + auto it = begin(), endit = end(); + while (it != endit && it->type != find_type) ++it; + return it; + } + + size_t size() { return tinfo.size(); } +}; + +/** + * Extracts C++ value and holder pointer references from an instance (which may contain multiple + * values/holders for python-side multiple inheritance) that match the given type. Throws an error + * if the given type (or ValueType, if omitted) is not a pybind11 base of the given instance. If + * `find_type` is omitted (or explicitly specified as nullptr) the first value/holder are returned, + * regardless of type (and the resulting .type will be nullptr). + * + * The returned object should be short-lived: in particular, it must not outlive the called-upon + * instance. + */ +PYBIND11_NOINLINE value_and_holder instance::get_value_and_holder(const type_info *find_type /*= nullptr default in common.h*/, bool throw_if_missing /*= true in common.h*/) { + // Optimize common case: + if (!find_type || Py_TYPE(this) == find_type->type) + return value_and_holder(this, find_type, 0, 0); + + detail::values_and_holders vhs(this); + auto it = vhs.find(find_type); + if (it != vhs.end()) + return *it; + + if (!throw_if_missing) + return value_and_holder(); + +#if defined(NDEBUG) + pybind11_fail("pybind11::detail::instance::get_value_and_holder: " + "type is not a pybind11 base of the given instance " + "(compile in debug mode for type details)"); +#else + pybind11_fail("pybind11::detail::instance::get_value_and_holder: `" + + get_fully_qualified_tp_name(find_type->type) + "' is not a pybind11 base of the given `" + + get_fully_qualified_tp_name(Py_TYPE(this)) + "' instance"); +#endif +} + +PYBIND11_NOINLINE void instance::allocate_layout() { + auto &tinfo = all_type_info(Py_TYPE(this)); + + const size_t n_types = tinfo.size(); + + if (n_types == 0) + pybind11_fail("instance allocation failed: new instance has no pybind11-registered base types"); + + simple_layout = + n_types == 1 && tinfo.front()->holder_size_in_ptrs <= instance_simple_holder_in_ptrs(); + + // Simple path: no python-side multiple inheritance, and a small-enough holder + if (simple_layout) { + simple_value_holder[0] = nullptr; + simple_holder_constructed = false; + simple_instance_registered = false; + } + else { // multiple base types or a too-large holder + // Allocate space to hold: [v1*][h1][v2*][h2]...[bb...] where [vN*] is a value pointer, + // [hN] is the (uninitialized) holder instance for value N, and [bb...] is a set of bool + // values that tracks whether each associated holder has been initialized. Each [block] is + // padded, if necessary, to an integer multiple of sizeof(void *). + size_t space = 0; + for (auto t : tinfo) { + space += 1; // value pointer + space += t->holder_size_in_ptrs; // holder instance + } + size_t flags_at = space; + space += size_in_ptrs(n_types); // status bytes (holder_constructed and instance_registered) + + // Allocate space for flags, values, and holders, and initialize it to 0 (flags and values, + // in particular, need to be 0). Use Python's memory allocation functions: in Python 3.6 + // they default to using pymalloc, which is designed to be efficient for small allocations + // like the one we're doing here; in earlier versions (and for larger allocations) they are + // just wrappers around malloc. +#if PY_VERSION_HEX >= 0x03050000 + nonsimple.values_and_holders = (void **) PyMem_Calloc(space, sizeof(void *)); + if (!nonsimple.values_and_holders) throw std::bad_alloc(); +#else + nonsimple.values_and_holders = (void **) PyMem_New(void *, space); + if (!nonsimple.values_and_holders) throw std::bad_alloc(); + std::memset(nonsimple.values_and_holders, 0, space * sizeof(void *)); +#endif + nonsimple.status = reinterpret_cast(&nonsimple.values_and_holders[flags_at]); + } + owned = true; +} + +// NOLINTNEXTLINE(readability-make-member-function-const) +PYBIND11_NOINLINE void instance::deallocate_layout() { + if (!simple_layout) + PyMem_Free(nonsimple.values_and_holders); +} + +PYBIND11_NOINLINE bool isinstance_generic(handle obj, const std::type_info &tp) { + handle type = detail::get_type_handle(tp, false); + if (!type) + return false; + return isinstance(obj, type); +} + +PYBIND11_NOINLINE std::string error_string() { + if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_RuntimeError, "Unknown internal error occurred"); + return "Unknown internal error occurred"; + } + + error_scope scope; // Preserve error state + + std::string errorString; + if (scope.type) { + errorString += handle(scope.type).attr("__name__").cast(); + errorString += ": "; + } + if (scope.value) + errorString += (std::string) str(scope.value); + + PyErr_NormalizeException(&scope.type, &scope.value, &scope.trace); + +#if PY_MAJOR_VERSION >= 3 + if (scope.trace != nullptr) + PyException_SetTraceback(scope.value, scope.trace); +#endif + +#if !defined(PYPY_VERSION) + if (scope.trace) { + auto *trace = (PyTracebackObject *) scope.trace; + + /* Get the deepest trace possible */ + while (trace->tb_next) + trace = trace->tb_next; + + PyFrameObject *frame = trace->tb_frame; + errorString += "\n\nAt:\n"; + while (frame) { +#if PY_VERSION_HEX >= 0x03090000 + PyCodeObject *f_code = PyFrame_GetCode(frame); +#else + PyCodeObject *f_code = frame->f_code; + Py_INCREF(f_code); +#endif + int lineno = PyFrame_GetLineNumber(frame); + errorString += + " " + handle(f_code->co_filename).cast() + + "(" + std::to_string(lineno) + "): " + + handle(f_code->co_name).cast() + "\n"; + frame = frame->f_back; + Py_DECREF(f_code); + } + } +#endif + + return errorString; +} + +PYBIND11_NOINLINE handle get_object_handle(const void *ptr, const detail::type_info *type ) { + auto &instances = get_internals().registered_instances; + auto range = instances.equal_range(ptr); + for (auto it = range.first; it != range.second; ++it) { + for (const auto &vh : values_and_holders(it->second)) { + if (vh.type == type) + return handle((PyObject *) it->second); + } + } + return handle(); +} + +inline PyThreadState *get_thread_state_unchecked() { +#if defined(PYPY_VERSION) + return PyThreadState_GET(); +#elif PY_VERSION_HEX < 0x03000000 + return _PyThreadState_Current; +#elif PY_VERSION_HEX < 0x03050000 + return (PyThreadState*) _Py_atomic_load_relaxed(&_PyThreadState_Current); +#elif PY_VERSION_HEX < 0x03050200 + return (PyThreadState*) _PyThreadState_Current.value; +#else + return _PyThreadState_UncheckedGet(); +#endif +} + +// Forward declarations +void keep_alive_impl(handle nurse, handle patient); +inline PyObject *make_new_instance(PyTypeObject *type); + +class type_caster_generic { +public: + PYBIND11_NOINLINE explicit type_caster_generic(const std::type_info &type_info) + : typeinfo(get_type_info(type_info)), cpptype(&type_info) {} + + explicit type_caster_generic(const type_info *typeinfo) + : typeinfo(typeinfo), cpptype(typeinfo ? typeinfo->cpptype : nullptr) {} + + bool load(handle src, bool convert) { + return load_impl(src, convert); + } + + PYBIND11_NOINLINE static handle cast(const void *_src, return_value_policy policy, handle parent, + const detail::type_info *tinfo, + void *(*copy_constructor)(const void *), + void *(*move_constructor)(const void *), + const void *existing_holder = nullptr) { + if (!tinfo) // no type info: error will be set already + return handle(); + + void *src = const_cast(_src); + if (src == nullptr) + return none().release(); + + if (handle registered_inst = find_registered_python_instance(src, tinfo)) + return registered_inst; + + auto inst = reinterpret_steal(make_new_instance(tinfo->type)); + auto wrapper = reinterpret_cast(inst.ptr()); + wrapper->owned = false; + void *&valueptr = values_and_holders(wrapper).begin()->value_ptr(); + + switch (policy) { + case return_value_policy::automatic: + case return_value_policy::take_ownership: + valueptr = src; + wrapper->owned = true; + break; + + case return_value_policy::automatic_reference: + case return_value_policy::reference: + valueptr = src; + wrapper->owned = false; + break; + + case return_value_policy::copy: + if (copy_constructor) + valueptr = copy_constructor(src); + else { +#if defined(NDEBUG) + throw cast_error("return_value_policy = copy, but type is " + "non-copyable! (compile in debug mode for details)"); +#else + std::string type_name(tinfo->cpptype->name()); + detail::clean_type_id(type_name); + throw cast_error("return_value_policy = copy, but type " + + type_name + " is non-copyable!"); +#endif + } + wrapper->owned = true; + break; + + case return_value_policy::move: + if (move_constructor) + valueptr = move_constructor(src); + else if (copy_constructor) + valueptr = copy_constructor(src); + else { +#if defined(NDEBUG) + throw cast_error("return_value_policy = move, but type is neither " + "movable nor copyable! " + "(compile in debug mode for details)"); +#else + std::string type_name(tinfo->cpptype->name()); + detail::clean_type_id(type_name); + throw cast_error("return_value_policy = move, but type " + + type_name + " is neither movable nor copyable!"); +#endif + } + wrapper->owned = true; + break; + + case return_value_policy::reference_internal: + valueptr = src; + wrapper->owned = false; + keep_alive_impl(inst, parent); + break; + + default: + throw cast_error("unhandled return_value_policy: should not happen!"); + } + + tinfo->init_instance(wrapper, existing_holder); + + return inst.release(); + } + + // Base methods for generic caster; there are overridden in copyable_holder_caster + void load_value(value_and_holder &&v_h) { + auto *&vptr = v_h.value_ptr(); + // Lazy allocation for unallocated values: + if (vptr == nullptr) { + auto *type = v_h.type ? v_h.type : typeinfo; + if (type->operator_new) { + vptr = type->operator_new(type->type_size); + } else { + #if defined(__cpp_aligned_new) && (!defined(_MSC_VER) || _MSC_VER >= 1912) + if (type->type_align > __STDCPP_DEFAULT_NEW_ALIGNMENT__) + vptr = ::operator new(type->type_size, + std::align_val_t(type->type_align)); + else + #endif + vptr = ::operator new(type->type_size); + } + } + value = vptr; + } + bool try_implicit_casts(handle src, bool convert) { + for (auto &cast : typeinfo->implicit_casts) { + type_caster_generic sub_caster(*cast.first); + if (sub_caster.load(src, convert)) { + value = cast.second(sub_caster.value); + return true; + } + } + return false; + } + bool try_direct_conversions(handle src) { + for (auto &converter : *typeinfo->direct_conversions) { + if (converter(src.ptr(), value)) + return true; + } + return false; + } + void check_holder_compat() {} + + PYBIND11_NOINLINE static void *local_load(PyObject *src, const type_info *ti) { + auto caster = type_caster_generic(ti); + if (caster.load(src, false)) + return caster.value; + return nullptr; + } + + /// Try to load with foreign typeinfo, if available. Used when there is no + /// native typeinfo, or when the native one wasn't able to produce a value. + PYBIND11_NOINLINE bool try_load_foreign_module_local(handle src) { + constexpr auto *local_key = PYBIND11_MODULE_LOCAL_ID; + const auto pytype = type::handle_of(src); + if (!hasattr(pytype, local_key)) + return false; + + type_info *foreign_typeinfo = reinterpret_borrow(getattr(pytype, local_key)); + // Only consider this foreign loader if actually foreign and is a loader of the correct cpp type + if (foreign_typeinfo->module_local_load == &local_load + || (cpptype && !same_type(*cpptype, *foreign_typeinfo->cpptype))) + return false; + + if (auto result = foreign_typeinfo->module_local_load(src.ptr(), foreign_typeinfo)) { + value = result; + return true; + } + return false; + } + + // Implementation of `load`; this takes the type of `this` so that it can dispatch the relevant + // bits of code between here and copyable_holder_caster where the two classes need different + // logic (without having to resort to virtual inheritance). + template + PYBIND11_NOINLINE bool load_impl(handle src, bool convert) { + if (!src) return false; + if (!typeinfo) return try_load_foreign_module_local(src); + + auto &this_ = static_cast(*this); + this_.check_holder_compat(); + + PyTypeObject *srctype = Py_TYPE(src.ptr()); + + // Case 1: If src is an exact type match for the target type then we can reinterpret_cast + // the instance's value pointer to the target type: + if (srctype == typeinfo->type) { + this_.load_value(reinterpret_cast(src.ptr())->get_value_and_holder()); + return true; + } + // Case 2: We have a derived class + if (PyType_IsSubtype(srctype, typeinfo->type)) { + auto &bases = all_type_info(srctype); + bool no_cpp_mi = typeinfo->simple_type; + + // Case 2a: the python type is a Python-inherited derived class that inherits from just + // one simple (no MI) pybind11 class, or is an exact match, so the C++ instance is of + // the right type and we can use reinterpret_cast. + // (This is essentially the same as case 2b, but because not using multiple inheritance + // is extremely common, we handle it specially to avoid the loop iterator and type + // pointer lookup overhead) + if (bases.size() == 1 && (no_cpp_mi || bases.front()->type == typeinfo->type)) { + this_.load_value(reinterpret_cast(src.ptr())->get_value_and_holder()); + return true; + } + // Case 2b: the python type inherits from multiple C++ bases. Check the bases to see if + // we can find an exact match (or, for a simple C++ type, an inherited match); if so, we + // can safely reinterpret_cast to the relevant pointer. + if (bases.size() > 1) { + for (auto base : bases) { + if (no_cpp_mi ? PyType_IsSubtype(base->type, typeinfo->type) : base->type == typeinfo->type) { + this_.load_value(reinterpret_cast(src.ptr())->get_value_and_holder(base)); + return true; + } + } + } + + // Case 2c: C++ multiple inheritance is involved and we couldn't find an exact type match + // in the registered bases, above, so try implicit casting (needed for proper C++ casting + // when MI is involved). + if (this_.try_implicit_casts(src, convert)) + return true; + } + + // Perform an implicit conversion + if (convert) { + for (auto &converter : typeinfo->implicit_conversions) { + auto temp = reinterpret_steal(converter(src.ptr(), typeinfo->type)); + if (load_impl(temp, false)) { + loader_life_support::add_patient(temp); + return true; + } + } + if (this_.try_direct_conversions(src)) + return true; + } + + // Failed to match local typeinfo. Try again with global. + if (typeinfo->module_local) { + if (auto gtype = get_global_type_info(*typeinfo->cpptype)) { + typeinfo = gtype; + return load(src, false); + } + } + + // Global typeinfo has precedence over foreign module_local + if (try_load_foreign_module_local(src)) { + return true; + } + + // Custom converters didn't take None, now we convert None to nullptr. + if (src.is_none()) { + // Defer accepting None to other overloads (if we aren't in convert mode): + if (!convert) return false; + value = nullptr; + return true; + } + + return false; + } + + + // Called to do type lookup and wrap the pointer and type in a pair when a dynamic_cast + // isn't needed or can't be used. If the type is unknown, sets the error and returns a pair + // with .second = nullptr. (p.first = nullptr is not an error: it becomes None). + PYBIND11_NOINLINE static std::pair src_and_type( + const void *src, const std::type_info &cast_type, const std::type_info *rtti_type = nullptr) { + if (auto *tpi = get_type_info(cast_type)) + return {src, const_cast(tpi)}; + + // Not found, set error: + std::string tname = rtti_type ? rtti_type->name() : cast_type.name(); + detail::clean_type_id(tname); + std::string msg = "Unregistered type : " + tname; + PyErr_SetString(PyExc_TypeError, msg.c_str()); + return {nullptr, nullptr}; + } + + const type_info *typeinfo = nullptr; + const std::type_info *cpptype = nullptr; + void *value = nullptr; +}; + +/** + * Determine suitable casting operator for pointer-or-lvalue-casting type casters. The type caster + * needs to provide `operator T*()` and `operator T&()` operators. + * + * If the type supports moving the value away via an `operator T&&() &&` method, it should use + * `movable_cast_op_type` instead. + */ +template +using cast_op_type = + conditional_t>::value, + typename std::add_pointer>::type, + typename std::add_lvalue_reference>::type>; + +/** + * Determine suitable casting operator for a type caster with a movable value. Such a type caster + * needs to provide `operator T*()`, `operator T&()`, and `operator T&&() &&`. The latter will be + * called in appropriate contexts where the value can be moved rather than copied. + * + * These operator are automatically provided when using the PYBIND11_TYPE_CASTER macro. + */ +template +using movable_cast_op_type = + conditional_t::type>::value, + typename std::add_pointer>::type, + conditional_t::value, + typename std::add_rvalue_reference>::type, + typename std::add_lvalue_reference>::type>>; + +// std::is_copy_constructible isn't quite enough: it lets std::vector (and similar) through when +// T is non-copyable, but code containing such a copy constructor fails to actually compile. +template struct is_copy_constructible : std::is_copy_constructible {}; + +// Specialization for types that appear to be copy constructible but also look like stl containers +// (we specifically check for: has `value_type` and `reference` with `reference = value_type&`): if +// so, copy constructability depends on whether the value_type is copy constructible. +template struct is_copy_constructible, + std::is_same, + // Avoid infinite recursion + negation> + >::value>> : is_copy_constructible {}; + +// Likewise for std::pair +// (after C++17 it is mandatory that the copy constructor not exist when the two types aren't themselves +// copy constructible, but this can not be relied upon when T1 or T2 are themselves containers). +template struct is_copy_constructible> + : all_of, is_copy_constructible> {}; + +// The same problems arise with std::is_copy_assignable, so we use the same workaround. +template struct is_copy_assignable : std::is_copy_assignable {}; +template struct is_copy_assignable, + std::is_same + >::value>> : is_copy_assignable {}; +template struct is_copy_assignable> + : all_of, is_copy_assignable> {}; + +PYBIND11_NAMESPACE_END(detail) + +// polymorphic_type_hook::get(src, tinfo) determines whether the object pointed +// to by `src` actually is an instance of some class derived from `itype`. +// If so, it sets `tinfo` to point to the std::type_info representing that derived +// type, and returns a pointer to the start of the most-derived object of that type +// (in which `src` is a subobject; this will be the same address as `src` in most +// single inheritance cases). If not, or if `src` is nullptr, it simply returns `src` +// and leaves `tinfo` at its default value of nullptr. +// +// The default polymorphic_type_hook just returns src. A specialization for polymorphic +// types determines the runtime type of the passed object and adjusts the this-pointer +// appropriately via dynamic_cast. This is what enables a C++ Animal* to appear +// to Python as a Dog (if Dog inherits from Animal, Animal is polymorphic, Dog is +// registered with pybind11, and this Animal is in fact a Dog). +// +// You may specialize polymorphic_type_hook yourself for types that want to appear +// polymorphic to Python but do not use C++ RTTI. (This is a not uncommon pattern +// in performance-sensitive applications, used most notably in LLVM.) +// +// polymorphic_type_hook_base allows users to specialize polymorphic_type_hook with +// std::enable_if. User provided specializations will always have higher priority than +// the default implementation and specialization provided in polymorphic_type_hook_base. +template +struct polymorphic_type_hook_base +{ + static const void *get(const itype *src, const std::type_info*&) { return src; } +}; +template +struct polymorphic_type_hook_base::value>> +{ + static const void *get(const itype *src, const std::type_info*& type) { + type = src ? &typeid(*src) : nullptr; + return dynamic_cast(src); + } +}; +template +struct polymorphic_type_hook : public polymorphic_type_hook_base {}; + +PYBIND11_NAMESPACE_BEGIN(detail) + +/// Generic type caster for objects stored on the heap +template class type_caster_base : public type_caster_generic { + using itype = intrinsic_t; + +public: + static constexpr auto name = const_name(); + + type_caster_base() : type_caster_base(typeid(type)) { } + explicit type_caster_base(const std::type_info &info) : type_caster_generic(info) { } + + static handle cast(const itype &src, return_value_policy policy, handle parent) { + if (policy == return_value_policy::automatic || policy == return_value_policy::automatic_reference) + policy = return_value_policy::copy; + return cast(&src, policy, parent); + } + + static handle cast(itype &&src, return_value_policy, handle parent) { + return cast(&src, return_value_policy::move, parent); + } + + // Returns a (pointer, type_info) pair taking care of necessary type lookup for a + // polymorphic type (using RTTI by default, but can be overridden by specializing + // polymorphic_type_hook). If the instance isn't derived, returns the base version. + static std::pair src_and_type(const itype *src) { + auto &cast_type = typeid(itype); + const std::type_info *instance_type = nullptr; + const void *vsrc = polymorphic_type_hook::get(src, instance_type); + if (instance_type && !same_type(cast_type, *instance_type)) { + // This is a base pointer to a derived type. If the derived type is registered + // with pybind11, we want to make the full derived object available. + // In the typical case where itype is polymorphic, we get the correct + // derived pointer (which may be != base pointer) by a dynamic_cast to + // most derived type. If itype is not polymorphic, we won't get here + // except via a user-provided specialization of polymorphic_type_hook, + // and the user has promised that no this-pointer adjustment is + // required in that case, so it's OK to use static_cast. + if (const auto *tpi = get_type_info(*instance_type)) + return {vsrc, tpi}; + } + // Otherwise we have either a nullptr, an `itype` pointer, or an unknown derived pointer, so + // don't do a cast + return type_caster_generic::src_and_type(src, cast_type, instance_type); + } + + static handle cast(const itype *src, return_value_policy policy, handle parent) { + auto st = src_and_type(src); + return type_caster_generic::cast( + st.first, policy, parent, st.second, + make_copy_constructor(src), make_move_constructor(src)); + } + + static handle cast_holder(const itype *src, const void *holder) { + auto st = src_and_type(src); + return type_caster_generic::cast( + st.first, return_value_policy::take_ownership, {}, st.second, + nullptr, nullptr, holder); + } + + template using cast_op_type = detail::cast_op_type; + + // NOLINTNEXTLINE(google-explicit-constructor) + operator itype*() { return (type *) value; } + // NOLINTNEXTLINE(google-explicit-constructor) + operator itype&() { if (!value) throw reference_cast_error(); return *((itype *) value); } + +protected: + using Constructor = void *(*)(const void *); + + /* Only enabled when the types are {copy,move}-constructible *and* when the type + does not have a private operator new implementation. A comma operator is used in the decltype + argument to apply SFINAE to the public copy/move constructors.*/ + template ::value>> + static auto make_copy_constructor(const T *) -> decltype(new T(std::declval()), Constructor{}) { + return [](const void *arg) -> void * { + return new T(*reinterpret_cast(arg)); + }; + } + + template ::value>> + static auto make_move_constructor(const T *) -> decltype(new T(std::declval()), Constructor{}) { + return [](const void *arg) -> void * { + return new T(std::move(*const_cast(reinterpret_cast(arg)))); + }; + } + + static Constructor make_copy_constructor(...) { return nullptr; } + static Constructor make_move_constructor(...) { return nullptr; } +}; + +PYBIND11_NAMESPACE_END(detail) +PYBIND11_NAMESPACE_END(PYBIND11_NAMESPACE) diff --git a/pybind11/include/pybind11/detail/typeid.h b/pybind11/include/pybind11/detail/typeid.h index 148889ffe..39ba8ce0f 100644 --- a/pybind11/include/pybind11/detail/typeid.h +++ b/pybind11/include/pybind11/detail/typeid.h @@ -29,7 +29,7 @@ inline void erase_all(std::string &string, const std::string &search) { } } -PYBIND11_NOINLINE inline void clean_type_id(std::string &name) { +PYBIND11_NOINLINE void clean_type_id(std::string &name) { #if defined(__GNUG__) int status = 0; std::unique_ptr res { diff --git a/pybind11/include/pybind11/eigen.h b/pybind11/include/pybind11/eigen.h index 12ce9bd3e..696099fa6 100644 --- a/pybind11/include/pybind11/eigen.h +++ b/pybind11/include/pybind11/eigen.h @@ -9,33 +9,31 @@ #pragma once +/* HINT: To suppress warnings originating from the Eigen headers, use -isystem. + See also: + https://stackoverflow.com/questions/2579576/i-dir-vs-isystem-dir + https://stackoverflow.com/questions/1741816/isystem-for-ms-visual-studio-c-compiler +*/ + #include "numpy.h" -#if defined(__INTEL_COMPILER) -# pragma warning(disable: 1682) // implicit conversion of a 64-bit integral type to a smaller integral type (potential portability problem) -#elif defined(__GNUG__) || defined(__clang__) -# pragma GCC diagnostic push -# pragma GCC diagnostic ignored "-Wconversion" -# pragma GCC diagnostic ignored "-Wdeprecated-declarations" -# ifdef __clang__ -// Eigen generates a bunch of implicit-copy-constructor-is-deprecated warnings with -Wdeprecated -// under Clang, so disable that warning here: -# pragma GCC diagnostic ignored "-Wdeprecated" -# endif -# if __GNUC__ >= 7 -# pragma GCC diagnostic ignored "-Wint-in-bool-context" -# endif -#endif - +// The C4127 suppression was introduced for Eigen 3.4.0. In theory we could +// make it version specific, or even remove it later, but considering that +// 1. C4127 is generally far more distracting than useful for modern template code, and +// 2. we definitely want to ignore any MSVC warnings originating from Eigen code, +// it is probably best to keep this around indefinitely. #if defined(_MSC_VER) # pragma warning(push) -# pragma warning(disable: 4127) // warning C4127: Conditional expression is constant -# pragma warning(disable: 4996) // warning C4996: std::unary_negate is deprecated in C++17 +# pragma warning(disable: 4127) // C4127: conditional expression is constant #endif #include #include +#if defined(_MSC_VER) +# pragma warning(pop) +#endif + // Eigen prior to 3.2.7 doesn't have proper move constructors--but worse, some classes get implicit // move constructors that break things. We could detect this an explicitly copy, but an extra copy // of matrices seems highly undesirable. @@ -52,8 +50,12 @@ PYBIND11_NAMESPACE_BEGIN(detail) #if EIGEN_VERSION_AT_LEAST(3,3,0) using EigenIndex = Eigen::Index; +template +using EigenMapSparseMatrix = Eigen::Map>; #else using EigenIndex = EIGEN_DEFAULT_DENSE_INDEX_TYPE; +template +using EigenMapSparseMatrix = Eigen::MappedSparseMatrix; #endif // Matches Eigen::Map, Eigen::Ref, blocks, etc: @@ -77,18 +79,17 @@ template struct EigenConformable { EigenDStride stride{0, 0}; // Only valid if negativestrides is false! bool negativestrides = false; // If true, do not use stride! + // NOLINTNEXTLINE(google-explicit-constructor) EigenConformable(bool fits = false) : conformable{fits} {} // Matrix type: EigenConformable(EigenIndex r, EigenIndex c, EigenIndex rstride, EigenIndex cstride) : - conformable{true}, rows{r}, cols{c} { - // TODO: when Eigen bug #747 is fixed, remove the tests for non-negativity. http://eigen.tuxfamily.org/bz/show_bug.cgi?id=747 - if (rstride < 0 || cstride < 0) { - negativestrides = true; - } else { - stride = {EigenRowMajor ? rstride : cstride /* outer stride */, - EigenRowMajor ? cstride : rstride /* inner stride */ }; - } + conformable{true}, rows{r}, cols{c}, + //TODO: when Eigen bug #747 is fixed, remove the tests for non-negativity. http://eigen.tuxfamily.org/bz/show_bug.cgi?id=747 + stride{EigenRowMajor ? (rstride > 0 ? rstride : 0) : (cstride > 0 ? cstride : 0) /* outer stride */, + EigenRowMajor ? (cstride > 0 ? cstride : 0) : (rstride > 0 ? rstride : 0) /* inner stride */ }, + negativestrides{rstride < 0 || cstride < 0} { + } // Vector type: EigenConformable(EigenIndex r, EigenIndex c, EigenIndex stride) @@ -104,6 +105,7 @@ template struct EigenConformable { (props::outer_stride == Eigen::Dynamic || props::outer_stride == stride.outer() || (EigenRowMajor ? rows : cols) == 1); } + // NOLINTNEXTLINE(google-explicit-constructor) operator bool() const { return conformable; } }; @@ -153,7 +155,8 @@ template struct EigenProps { np_cols = a.shape(1), np_rstride = a.strides(0) / static_cast(sizeof(Scalar)), np_cstride = a.strides(1) / static_cast(sizeof(Scalar)); - if ((fixed_rows && np_rows != rows) || (fixed_cols && np_cols != cols)) + if ((PYBIND11_SILENCE_MSVC_C4127(fixed_rows) && np_rows != rows) || + (PYBIND11_SILENCE_MSVC_C4127(fixed_cols) && np_cols != cols)) return false; return {np_rows, np_cols, np_rstride, np_cstride}; @@ -165,25 +168,22 @@ template struct EigenProps { stride = a.strides(0) / static_cast(sizeof(Scalar)); if (vector) { // Eigen type is a compile-time vector - if (fixed && size != n) + if (PYBIND11_SILENCE_MSVC_C4127(fixed) && size != n) return false; // Vector size mismatch return {rows == 1 ? 1 : n, cols == 1 ? 1 : n, stride}; } - else if (fixed) { + if (fixed) { // The type has a fixed size, but is not a vector: abort return false; } - else if (fixed_cols) { + if (fixed_cols) { // Since this isn't a vector, cols must be != 1. We allow this only if it exactly // equals the number of elements (rows is Dynamic, and so 1 row is allowed). if (cols != n) return false; return {1, n, stride}; - } - else { - // Otherwise it's either fully dynamic, or column dynamic; both become a column vector - if (fixed_rows && rows != n) return false; + } // Otherwise it's either fully dynamic, or column dynamic; both become a column vector + if (PYBIND11_SILENCE_MSVC_C4127(fixed_rows) && rows != n) return false; return {n, 1, stride}; - } } static constexpr bool show_writeable = is_eigen_dense_map::value && is_eigen_mutable_map::value; @@ -192,20 +192,20 @@ template struct EigenProps { static constexpr bool show_f_contiguous = !show_c_contiguous && show_order && requires_col_major; static constexpr auto descriptor = - _("numpy.ndarray[") + npy_format_descriptor::name + - _("[") + _(_<(size_t) rows>(), _("m")) + - _(", ") + _(_<(size_t) cols>(), _("n")) + - _("]") + + const_name("numpy.ndarray[") + npy_format_descriptor::name + + const_name("[") + const_name(const_name<(size_t) rows>(), const_name("m")) + + const_name(", ") + const_name(const_name<(size_t) cols>(), const_name("n")) + + const_name("]") + // For a reference type (e.g. Ref) we have other constraints that might need to be // satisfied: writeable=True (for a mutable reference), and, depending on the map's stride // options, possibly f_contiguous or c_contiguous. We include them in the descriptor output // to provide some hint as to why a TypeError is occurring (otherwise it can be confusing to // see that a function accepts a 'numpy.ndarray[float64[3,2]]' and an error message that you // *gave* a numpy.ndarray of the right type and dimensions. - _(", flags.writeable", "") + - _(", flags.c_contiguous", "") + - _(", flags.f_contiguous", "") + - _("]"); + const_name(", flags.writeable", "") + + const_name(", flags.c_contiguous", "") + + const_name(", flags.f_contiguous", "") + + const_name("]"); }; // Casts an Eigen type to numpy array. If given a base, the numpy array references the src data, @@ -344,8 +344,11 @@ public: static constexpr auto name = props::descriptor; + // NOLINTNEXTLINE(google-explicit-constructor) operator Type*() { return &value; } + // NOLINTNEXTLINE(google-explicit-constructor) operator Type&() { return value; } + // NOLINTNEXTLINE(google-explicit-constructor) operator Type&&() && { return std::move(value); } template using cast_op_type = movable_cast_op_type; @@ -432,7 +435,7 @@ public: if (!need_copy) { // We don't need a converting copy, but we also need to check whether the strides are // compatible with the Ref's stride requirements - Array aref = reinterpret_borrow(src); + auto aref = reinterpret_borrow(src); if (aref && (!need_writeable || aref.writeable())) { fits = props::conformable(aref); @@ -469,7 +472,9 @@ public: return true; } + // NOLINTNEXTLINE(google-explicit-constructor) operator Type*() { return ref.get(); } + // NOLINTNEXTLINE(google-explicit-constructor) operator Type&() { return *ref; } template using cast_op_type = pybind11::detail::cast_op_type<_T>; @@ -539,9 +544,9 @@ public: template struct type_caster::value>> { - typedef typename Type::Scalar Scalar; - typedef remove_reference_t().outerIndexPtr())> StorageIndex; - typedef typename Type::Index Index; + using Scalar = typename Type::Scalar; + using StorageIndex = remove_reference_t().outerIndexPtr())>; + using Index = typename Type::Index; static constexpr bool rowMajor = Type::IsRowMajor; bool load(handle src, bool) { @@ -549,7 +554,7 @@ struct type_caster::value>> { return false; auto obj = reinterpret_borrow(src); - object sparse_module = module::import("scipy.sparse"); + object sparse_module = module_::import("scipy.sparse"); object matrix_type = sparse_module.attr( rowMajor ? "csr_matrix" : "csc_matrix"); @@ -570,7 +575,9 @@ struct type_caster::value>> { if (!values || !innerIndices || !outerIndices) return false; - value = Eigen::MappedSparseMatrix( + value = EigenMapSparseMatrix( shape[0].cast(), shape[1].cast(), nnz, outerIndices.mutable_data(), innerIndices.mutable_data(), values.mutable_data()); @@ -580,7 +587,7 @@ struct type_caster::value>> { static handle cast(const Type &src, return_value_policy /* policy */, handle /* parent */) { const_cast(src).makeCompressed(); - object matrix_type = module::import("scipy.sparse").attr( + object matrix_type = module_::import("scipy.sparse").attr( rowMajor ? "csr_matrix" : "csc_matrix"); array data(src.nonZeros(), src.valuePtr()); @@ -593,15 +600,9 @@ struct type_caster::value>> { ).release(); } - PYBIND11_TYPE_CASTER(Type, _<(Type::IsRowMajor) != 0>("scipy.sparse.csr_matrix[", "scipy.sparse.csc_matrix[") - + npy_format_descriptor::name + _("]")); + PYBIND11_TYPE_CASTER(Type, const_name<(Type::IsRowMajor) != 0>("scipy.sparse.csr_matrix[", "scipy.sparse.csc_matrix[") + + npy_format_descriptor::name + const_name("]")); }; PYBIND11_NAMESPACE_END(detail) PYBIND11_NAMESPACE_END(PYBIND11_NAMESPACE) - -#if defined(__GNUG__) || defined(__clang__) -# pragma GCC diagnostic pop -#elif defined(_MSC_VER) -# pragma warning(pop) -#endif diff --git a/pybind11/include/pybind11/embed.h b/pybind11/include/pybind11/embed.h index eae86c714..9ab1ce9c0 100644 --- a/pybind11/include/pybind11/embed.h +++ b/pybind11/include/pybind11/embed.h @@ -12,6 +12,9 @@ #include "pybind11.h" #include "eval.h" +#include +#include + #if defined(PYPY_VERSION) # error Embedding the interpreter is not supported with PyPy #endif @@ -45,27 +48,23 @@ }); } \endrst */ -#define PYBIND11_EMBEDDED_MODULE(name, variable) \ - static void PYBIND11_CONCAT(pybind11_init_, name)(pybind11::module &); \ - static PyObject PYBIND11_CONCAT(*pybind11_init_wrapper_, name)() { \ - auto m = pybind11::module(PYBIND11_TOSTRING(name)); \ - try { \ - PYBIND11_CONCAT(pybind11_init_, name)(m); \ - return m.ptr(); \ - } catch (pybind11::error_already_set &e) { \ - PyErr_SetString(PyExc_ImportError, e.what()); \ - return nullptr; \ - } catch (const std::exception &e) { \ - PyErr_SetString(PyExc_ImportError, e.what()); \ - return nullptr; \ - } \ - } \ - PYBIND11_EMBEDDED_MODULE_IMPL(name) \ - pybind11::detail::embedded_module PYBIND11_CONCAT(pybind11_module_, name) \ - (PYBIND11_TOSTRING(name), \ - PYBIND11_CONCAT(pybind11_init_impl_, name)); \ - void PYBIND11_CONCAT(pybind11_init_, name)(pybind11::module &variable) - +#define PYBIND11_EMBEDDED_MODULE(name, variable) \ + static ::pybind11::module_::module_def PYBIND11_CONCAT(pybind11_module_def_, name); \ + static void PYBIND11_CONCAT(pybind11_init_, name)(::pybind11::module_ &); \ + static PyObject PYBIND11_CONCAT(*pybind11_init_wrapper_, name)() { \ + auto m = ::pybind11::module_::create_extension_module( \ + PYBIND11_TOSTRING(name), nullptr, &PYBIND11_CONCAT(pybind11_module_def_, name)); \ + try { \ + PYBIND11_CONCAT(pybind11_init_, name)(m); \ + return m.ptr(); \ + } \ + PYBIND11_CATCH_INIT_EXCEPTIONS \ + } \ + PYBIND11_EMBEDDED_MODULE_IMPL(name) \ + ::pybind11::detail::embedded_module PYBIND11_CONCAT(pybind11_module_, name)( \ + PYBIND11_TOSTRING(name), PYBIND11_CONCAT(pybind11_init_impl_, name)); \ + void PYBIND11_CONCAT(pybind11_init_, name)(::pybind11::module_ \ + & variable) // NOLINT(bugprone-macro-parentheses) PYBIND11_NAMESPACE_BEGIN(PYBIND11_NAMESPACE) PYBIND11_NAMESPACE_BEGIN(detail) @@ -78,7 +77,7 @@ struct embedded_module { using init_t = void (*)(); #endif embedded_module(const char *name, init_t init) { - if (Py_IsInitialized()) + if (Py_IsInitialized() != 0) pybind11_fail("Can't add new modules after the interpreter has been initialized"); auto result = PyImport_AppendInittab(name, init); @@ -87,29 +86,118 @@ struct embedded_module { } }; +struct wide_char_arg_deleter { + void operator()(wchar_t *ptr) const { +#if PY_VERSION_HEX >= 0x030500f0 + // API docs: https://docs.python.org/3/c-api/sys.html#c.Py_DecodeLocale + PyMem_RawFree(ptr); +#else + delete[] ptr; +#endif + } +}; + +inline wchar_t *widen_chars(const char *safe_arg) { +#if PY_VERSION_HEX >= 0x030500f0 + wchar_t *widened_arg = Py_DecodeLocale(safe_arg, nullptr); +#else + wchar_t *widened_arg = nullptr; + +// warning C4996: 'mbstowcs': This function or variable may be unsafe. +#if defined(_MSC_VER) +#pragma warning(push) +#pragma warning(disable:4996) +#endif + +# if defined(HAVE_BROKEN_MBSTOWCS) && HAVE_BROKEN_MBSTOWCS + size_t count = std::strlen(safe_arg); +# else + size_t count = std::mbstowcs(nullptr, safe_arg, 0); +# endif + if (count != static_cast(-1)) { + widened_arg = new wchar_t[count + 1]; + std::mbstowcs(widened_arg, safe_arg, count + 1); + } + +#if defined(_MSC_VER) +#pragma warning(pop) +#endif + +#endif + return widened_arg; +} + +/// Python 2.x/3.x-compatible version of `PySys_SetArgv` +inline void set_interpreter_argv(int argc, const char *const *argv, bool add_program_dir_to_path) { + // Before it was special-cased in python 3.8, passing an empty or null argv + // caused a segfault, so we have to reimplement the special case ourselves. + bool special_case = (argv == nullptr || argc <= 0); + + const char *const empty_argv[]{"\0"}; + const char *const *safe_argv = special_case ? empty_argv : argv; + if (special_case) + argc = 1; + + auto argv_size = static_cast(argc); +#if PY_MAJOR_VERSION >= 3 + // SetArgv* on python 3 takes wchar_t, so we have to convert. + std::unique_ptr widened_argv(new wchar_t *[argv_size]); + std::vector> widened_argv_entries; + widened_argv_entries.reserve(argv_size); + for (size_t ii = 0; ii < argv_size; ++ii) { + widened_argv_entries.emplace_back(widen_chars(safe_argv[ii])); + if (!widened_argv_entries.back()) { + // A null here indicates a character-encoding failure or the python + // interpreter out of memory. Give up. + return; + } + widened_argv[ii] = widened_argv_entries.back().get(); + } + + auto pysys_argv = widened_argv.get(); +#else + // python 2.x + std::vector strings{safe_argv, safe_argv + argv_size}; + std::vector char_strings{argv_size}; + for (std::size_t i = 0; i < argv_size; ++i) + char_strings[i] = &strings[i][0]; + char **pysys_argv = char_strings.data(); +#endif + + PySys_SetArgvEx(argc, pysys_argv, static_cast(add_program_dir_to_path)); +} + PYBIND11_NAMESPACE_END(detail) /** \rst Initialize the Python interpreter. No other pybind11 or CPython API functions can be called before this is done; with the exception of `PYBIND11_EMBEDDED_MODULE`. The - optional parameter can be used to skip the registration of signal handlers (see the - `Python documentation`_ for details). Calling this function again after the interpreter - has already been initialized is a fatal error. + optional `init_signal_handlers` parameter can be used to skip the registration of + signal handlers (see the `Python documentation`_ for details). Calling this function + again after the interpreter has already been initialized is a fatal error. If initializing the Python interpreter fails, then the program is terminated. (This is controlled by the CPython runtime and is an exception to pybind11's normal behavior of throwing exceptions on errors.) + The remaining optional parameters, `argc`, `argv`, and `add_program_dir_to_path` are + used to populate ``sys.argv`` and ``sys.path``. + See the |PySys_SetArgvEx documentation|_ for details. + .. _Python documentation: https://docs.python.org/3/c-api/init.html#c.Py_InitializeEx + .. |PySys_SetArgvEx documentation| replace:: ``PySys_SetArgvEx`` documentation + .. _PySys_SetArgvEx documentation: https://docs.python.org/3/c-api/init.html#c.PySys_SetArgvEx \endrst */ -inline void initialize_interpreter(bool init_signal_handlers = true) { - if (Py_IsInitialized()) +inline void initialize_interpreter(bool init_signal_handlers = true, + int argc = 0, + const char *const *argv = nullptr, + bool add_program_dir_to_path = true) { + if (Py_IsInitialized() != 0) pybind11_fail("The interpreter is already running"); Py_InitializeEx(init_signal_handlers ? 1 : 0); - // Make .py files in the working directory available by default - module::import("sys").attr("path").cast().append("."); + detail::set_interpreter_argv(argc, argv, add_program_dir_to_path); } /** \rst @@ -171,6 +259,8 @@ inline void finalize_interpreter() { Scope guard version of `initialize_interpreter` and `finalize_interpreter`. This a move-only guard and only a single instance can exist. + See `initialize_interpreter` for a discussion of its constructor arguments. + .. code-block:: cpp #include @@ -182,8 +272,11 @@ inline void finalize_interpreter() { \endrst */ class scoped_interpreter { public: - scoped_interpreter(bool init_signal_handlers = true) { - initialize_interpreter(init_signal_handlers); + explicit scoped_interpreter(bool init_signal_handlers = true, + int argc = 0, + const char *const *argv = nullptr, + bool add_program_dir_to_path = true) { + initialize_interpreter(init_signal_handlers, argc, argv, add_program_dir_to_path); } scoped_interpreter(const scoped_interpreter &) = delete; diff --git a/pybind11/include/pybind11/eval.h b/pybind11/include/pybind11/eval.h index ba82cf42a..4248551e9 100644 --- a/pybind11/include/pybind11/eval.h +++ b/pybind11/include/pybind11/eval.h @@ -1,5 +1,5 @@ /* - pybind11/exec.h: Support for evaluating Python expressions and statements + pybind11/eval.h: Support for evaluating Python expressions and statements from strings and files Copyright (c) 2016 Klemens Morgenstern and @@ -11,9 +11,27 @@ #pragma once +#include + #include "pybind11.h" PYBIND11_NAMESPACE_BEGIN(PYBIND11_NAMESPACE) +PYBIND11_NAMESPACE_BEGIN(detail) + +inline void ensure_builtins_in_globals(object &global) { + #if defined(PYPY_VERSION) || PY_VERSION_HEX < 0x03080000 + // Running exec and eval on Python 2 and 3 adds `builtins` module under + // `__builtins__` key to globals if not yet present. + // Python 3.8 made PyRun_String behave similarly. Let's also do that for + // older versions, for consistency. This was missing from PyPy3.8 7.3.7. + if (!global.contains("__builtins__")) + global["__builtins__"] = module_::import(PYBIND11_BUILTINS_MODULE); + #else + (void) global; + #endif +} + +PYBIND11_NAMESPACE_END(detail) enum eval_mode { /// Evaluate a string containing an isolated expression @@ -27,15 +45,17 @@ enum eval_mode { }; template -object eval(str expr, object global = globals(), object local = object()) { +object eval(const str &expr, object global = globals(), object local = object()) { if (!local) local = global; + detail::ensure_builtins_in_globals(global); + /* PyRun_String does not accept a PyObject / encoding specifier, this seems to be the only alternative */ std::string buffer = "# -*- coding: utf-8 -*-\n" + (std::string) expr; - int start; + int start = 0; switch (mode) { case eval_expr: start = Py_eval_input; break; case eval_single_statement: start = Py_single_input; break; @@ -52,13 +72,13 @@ object eval(str expr, object global = globals(), object local = object()) { template object eval(const char (&s)[N], object global = globals(), object local = object()) { /* Support raw string literals by removing common leading whitespace */ - auto expr = (s[0] == '\n') ? str(module::import("textwrap").attr("dedent")(s)) + auto expr = (s[0] == '\n') ? str(module_::import("textwrap").attr("dedent")(s)) : str(s); return eval(expr, global, local); } -inline void exec(str expr, object global = globals(), object local = object()) { - eval(expr, global, local); +inline void exec(const str &expr, object global = globals(), object local = object()) { + eval(expr, std::move(global), std::move(local)); } template @@ -66,7 +86,7 @@ void exec(const char (&s)[N], object global = globals(), object local = object() eval(s, global, local); } -#if defined(PYPY_VERSION) && PY_VERSION_HEX >= 0x3000000 +#if defined(PYPY_VERSION) && PY_VERSION_HEX >= 0x03000000 template object eval_file(str, object, object) { pybind11_fail("eval_file not supported in PyPy3. Use eval"); @@ -85,7 +105,9 @@ object eval_file(str fname, object global = globals(), object local = object()) if (!local) local = global; - int start; + detail::ensure_builtins_in_globals(global); + + int start = 0; switch (mode) { case eval_expr: start = Py_eval_input; break; case eval_single_statement: start = Py_single_input; break; @@ -114,6 +136,15 @@ object eval_file(str fname, object global = globals(), object local = object()) pybind11_fail("File \"" + fname_str + "\" could not be opened!"); } + // In Python2, this should be encoded by getfilesystemencoding. + // We don't boher setting it since Python2 is past EOL anyway. + // See PR#3233 +#if PY_VERSION_HEX >= 0x03000000 + if (!global.contains("__file__")) { + global["__file__"] = std::move(fname); + } +#endif + #if PY_VERSION_HEX < 0x03000000 && defined(PYPY_VERSION) PyObject *result = PyRun_File(f, fname_str.c_str(), start, global.ptr(), local.ptr()); diff --git a/pybind11/include/pybind11/functional.h b/pybind11/include/pybind11/functional.h index 57b6cd210..7912aef17 100644 --- a/pybind11/include/pybind11/functional.h +++ b/pybind11/include/pybind11/functional.h @@ -43,22 +43,43 @@ public: captured variables), in which case the roundtrip can be avoided. */ if (auto cfunc = func.cpp_function()) { - auto c = reinterpret_borrow(PyCFunction_GET_SELF(cfunc.ptr())); - auto rec = (function_record *) c; + auto cfunc_self = PyCFunction_GET_SELF(cfunc.ptr()); + if (isinstance(cfunc_self)) { + auto c = reinterpret_borrow(cfunc_self); + auto rec = (function_record *) c; - if (rec && rec->is_stateless && - same_type(typeid(function_type), *reinterpret_cast(rec->data[1]))) { - struct capture { function_type f; }; - value = ((capture *) &rec->data)->f; - return true; + while (rec != nullptr) { + if (rec->is_stateless + && same_type(typeid(function_type), + *reinterpret_cast(rec->data[1]))) { + struct capture { + function_type f; + }; + value = ((capture *) &rec->data)->f; + return true; + } + rec = rec->next; + } } + // PYPY segfaults here when passing builtin function like sum. + // Raising an fail exception here works to prevent the segfault, but only on gcc. + // See PR #1413 for full details } // ensure GIL is held during functor destruction struct func_handle { function f; - func_handle(function&& f_) : f(std::move(f_)) {} - func_handle(const func_handle&) = default; +#if !(defined(_MSC_VER) && _MSC_VER == 1916 && defined(PYBIND11_CPP17)) + // This triggers a syntax error under very special conditions (very weird indeed). + explicit +#endif + func_handle(function &&f_) noexcept : f(std::move(f_)) {} + func_handle(const func_handle &f_) { operator=(f_); } + func_handle &operator=(const func_handle &f_) { + gil_scoped_acquire acq; + f = f_.f; + return *this; + } ~func_handle() { gil_scoped_acquire acq; function kill_f(std::move(f)); @@ -68,7 +89,7 @@ public: // to emulate 'move initialization capture' in C++11 struct func_wrapper { func_handle hfunc; - func_wrapper(func_handle&& hf): hfunc(std::move(hf)) {} + explicit func_wrapper(func_handle &&hf) noexcept : hfunc(std::move(hf)) {} Return operator()(Args... args) const { gil_scoped_acquire acq; object retval(hfunc.f(std::forward(args)...)); @@ -89,12 +110,11 @@ public: auto result = f_.template target(); if (result) return cpp_function(*result, policy).release(); - else - return cpp_function(std::forward(f_), policy).release(); + return cpp_function(std::forward(f_), policy).release(); } - PYBIND11_TYPE_CASTER(type, _("Callable[[") + concat(make_caster::name...) + _("], ") - + make_caster::name + _("]")); + PYBIND11_TYPE_CASTER(type, const_name("Callable[[") + concat(make_caster::name...) + const_name("], ") + + make_caster::name + const_name("]")); }; PYBIND11_NAMESPACE_END(detail) diff --git a/pybind11/include/pybind11/gil.h b/pybind11/include/pybind11/gil.h new file mode 100644 index 000000000..b73aaa3f5 --- /dev/null +++ b/pybind11/include/pybind11/gil.h @@ -0,0 +1,193 @@ +/* + pybind11/gil.h: RAII helpers for managing the GIL + + Copyright (c) 2016 Wenzel Jakob + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#pragma once + +#include "detail/common.h" +#include "detail/internals.h" + +PYBIND11_NAMESPACE_BEGIN(PYBIND11_NAMESPACE) + + +PYBIND11_NAMESPACE_BEGIN(detail) + +// forward declarations +PyThreadState *get_thread_state_unchecked(); + +PYBIND11_NAMESPACE_END(detail) + + +#if defined(WITH_THREAD) && !defined(PYPY_VERSION) + +/* The functions below essentially reproduce the PyGILState_* API using a RAII + * pattern, but there are a few important differences: + * + * 1. When acquiring the GIL from an non-main thread during the finalization + * phase, the GILState API blindly terminates the calling thread, which + * is often not what is wanted. This API does not do this. + * + * 2. The gil_scoped_release function can optionally cut the relationship + * of a PyThreadState and its associated thread, which allows moving it to + * another thread (this is a fairly rare/advanced use case). + * + * 3. The reference count of an acquired thread state can be controlled. This + * can be handy to prevent cases where callbacks issued from an external + * thread would otherwise constantly construct and destroy thread state data + * structures. + * + * See the Python bindings of NanoGUI (http://github.com/wjakob/nanogui) for an + * example which uses features 2 and 3 to migrate the Python thread of + * execution to another thread (to run the event loop on the original thread, + * in this case). + */ + +class gil_scoped_acquire { +public: + PYBIND11_NOINLINE gil_scoped_acquire() { + auto &internals = detail::get_internals(); + tstate = (PyThreadState *) PYBIND11_TLS_GET_VALUE(internals.tstate); + + if (!tstate) { + /* Check if the GIL was acquired using the PyGILState_* API instead (e.g. if + calling from a Python thread). Since we use a different key, this ensures + we don't create a new thread state and deadlock in PyEval_AcquireThread + below. Note we don't save this state with internals.tstate, since we don't + create it we would fail to clear it (its reference count should be > 0). */ + tstate = PyGILState_GetThisThreadState(); + } + + if (!tstate) { + tstate = PyThreadState_New(internals.istate); + #if !defined(NDEBUG) + if (!tstate) + pybind11_fail("scoped_acquire: could not create thread state!"); + #endif + tstate->gilstate_counter = 0; + PYBIND11_TLS_REPLACE_VALUE(internals.tstate, tstate); + } else { + release = detail::get_thread_state_unchecked() != tstate; + } + + if (release) { + PyEval_AcquireThread(tstate); + } + + inc_ref(); + } + + void inc_ref() { + ++tstate->gilstate_counter; + } + + PYBIND11_NOINLINE void dec_ref() { + --tstate->gilstate_counter; + #if !defined(NDEBUG) + if (detail::get_thread_state_unchecked() != tstate) + pybind11_fail("scoped_acquire::dec_ref(): thread state must be current!"); + if (tstate->gilstate_counter < 0) + pybind11_fail("scoped_acquire::dec_ref(): reference count underflow!"); + #endif + if (tstate->gilstate_counter == 0) { + #if !defined(NDEBUG) + if (!release) + pybind11_fail("scoped_acquire::dec_ref(): internal error!"); + #endif + PyThreadState_Clear(tstate); + if (active) + PyThreadState_DeleteCurrent(); + PYBIND11_TLS_DELETE_VALUE(detail::get_internals().tstate); + release = false; + } + } + + /// This method will disable the PyThreadState_DeleteCurrent call and the + /// GIL won't be acquired. This method should be used if the interpreter + /// could be shutting down when this is called, as thread deletion is not + /// allowed during shutdown. Check _Py_IsFinalizing() on Python 3.7+, and + /// protect subsequent code. + PYBIND11_NOINLINE void disarm() { + active = false; + } + + PYBIND11_NOINLINE ~gil_scoped_acquire() { + dec_ref(); + if (release) + PyEval_SaveThread(); + } +private: + PyThreadState *tstate = nullptr; + bool release = true; + bool active = true; +}; + +class gil_scoped_release { +public: + explicit gil_scoped_release(bool disassoc = false) : disassoc(disassoc) { + // `get_internals()` must be called here unconditionally in order to initialize + // `internals.tstate` for subsequent `gil_scoped_acquire` calls. Otherwise, an + // initialization race could occur as multiple threads try `gil_scoped_acquire`. + auto &internals = detail::get_internals(); + tstate = PyEval_SaveThread(); + if (disassoc) { + auto key = internals.tstate; + PYBIND11_TLS_DELETE_VALUE(key); + } + } + + /// This method will disable the PyThreadState_DeleteCurrent call and the + /// GIL won't be acquired. This method should be used if the interpreter + /// could be shutting down when this is called, as thread deletion is not + /// allowed during shutdown. Check _Py_IsFinalizing() on Python 3.7+, and + /// protect subsequent code. + PYBIND11_NOINLINE void disarm() { + active = false; + } + + ~gil_scoped_release() { + if (!tstate) + return; + // `PyEval_RestoreThread()` should not be called if runtime is finalizing + if (active) + PyEval_RestoreThread(tstate); + if (disassoc) { + auto key = detail::get_internals().tstate; + PYBIND11_TLS_REPLACE_VALUE(key, tstate); + } + } +private: + PyThreadState *tstate; + bool disassoc; + bool active = true; +}; +#elif defined(PYPY_VERSION) +class gil_scoped_acquire { + PyGILState_STATE state; +public: + gil_scoped_acquire() { state = PyGILState_Ensure(); } + ~gil_scoped_acquire() { PyGILState_Release(state); } + void disarm() {} +}; + +class gil_scoped_release { + PyThreadState *state; +public: + gil_scoped_release() { state = PyEval_SaveThread(); } + ~gil_scoped_release() { PyEval_RestoreThread(state); } + void disarm() {} +}; +#else +class gil_scoped_acquire { + void disarm() {} +}; +class gil_scoped_release { + void disarm() {} +}; +#endif + +PYBIND11_NAMESPACE_END(PYBIND11_NAMESPACE) diff --git a/pybind11/include/pybind11/iostream.h b/pybind11/include/pybind11/iostream.h index 48479f2d1..95449a07b 100644 --- a/pybind11/include/pybind11/iostream.h +++ b/pybind11/include/pybind11/iostream.h @@ -5,17 +5,31 @@ All rights reserved. Use of this source code is governed by a BSD-style license that can be found in the LICENSE file. + + WARNING: The implementation in this file is NOT thread safe. Multiple + threads writing to a redirected ostream concurrently cause data races + and potentially buffer overflows. Therefore it is currently a requirement + that all (possibly) concurrent redirected ostream writes are protected by + a mutex. + #HelpAppreciated: Work on iostream.h thread safety. + For more background see the discussions under + https://github.com/pybind/pybind11/pull/2982 and + https://github.com/pybind/pybind11/pull/2995. */ #pragma once #include "pybind11.h" -#include -#include -#include -#include +#include +#include #include +#include +#include +#include +#include +#include +#include PYBIND11_NAMESPACE_BEGIN(PYBIND11_NAMESPACE) PYBIND11_NAMESPACE_BEGIN(detail) @@ -38,21 +52,68 @@ private: return sync() == 0 ? traits_type::not_eof(c) : traits_type::eof(); } - // This function must be non-virtual to be called in a destructor. If the - // rare MSVC test failure shows up with this version, then this should be - // simplified to a fully qualified call. - int _sync() { - if (pbase() != pptr()) { - // This subtraction cannot be negative, so dropping the sign - str line(pbase(), static_cast(pptr() - pbase())); + // Computes how many bytes at the end of the buffer are part of an + // incomplete sequence of UTF-8 bytes. + // Precondition: pbase() < pptr() + size_t utf8_remainder() const { + const auto rbase = std::reverse_iterator(pbase()); + const auto rpptr = std::reverse_iterator(pptr()); + auto is_ascii = [](char c) { + return (static_cast(c) & 0x80) == 0x00; + }; + auto is_leading = [](char c) { + return (static_cast(c) & 0xC0) == 0xC0; + }; + auto is_leading_2b = [](char c) { + return static_cast(c) <= 0xDF; + }; + auto is_leading_3b = [](char c) { + return static_cast(c) <= 0xEF; + }; + // If the last character is ASCII, there are no incomplete code points + if (is_ascii(*rpptr)) + return 0; + // Otherwise, work back from the end of the buffer and find the first + // UTF-8 leading byte + const auto rpend = rbase - rpptr >= 3 ? rpptr + 3 : rbase; + const auto leading = std::find_if(rpptr, rpend, is_leading); + if (leading == rbase) + return 0; + const auto dist = static_cast(leading - rpptr); + size_t remainder = 0; - { - gil_scoped_acquire tmp; + if (dist == 0) + remainder = 1; // 1-byte code point is impossible + else if (dist == 1) + remainder = is_leading_2b(*leading) ? 0 : dist + 1; + else if (dist == 2) + remainder = is_leading_3b(*leading) ? 0 : dist + 1; + // else if (dist >= 3), at least 4 bytes before encountering an UTF-8 + // leading byte, either no remainder or invalid UTF-8. + // Invalid UTF-8 will cause an exception later when converting + // to a Python string, so that's not handled here. + return remainder; + } + + // This function must be non-virtual to be called in a destructor. + int _sync() { + if (pbase() != pptr()) { // If buffer is not empty + gil_scoped_acquire tmp; + // This subtraction cannot be negative, so dropping the sign. + auto size = static_cast(pptr() - pbase()); + size_t remainder = utf8_remainder(); + + if (size > remainder) { + str line(pbase(), size - remainder); pywrite(line); pyflush(); } + // Copy the remainder at the end of the buffer to the beginning: + if (remainder > 0) + std::memmove(pbase(), pptr() - remainder, remainder); setp(pbase(), epptr()); + pbump(static_cast(remainder)); } return 0; } @@ -62,11 +123,8 @@ private: } public: - - pythonbuf(object pyostream, size_t buffer_size = 1024) - : buf_size(buffer_size), - d_buffer(new char[buf_size]), - pywrite(pyostream.attr("write")), + explicit pythonbuf(const object &pyostream, size_t buffer_size = 1024) + : buf_size(buffer_size), d_buffer(new char[buf_size]), pywrite(pyostream.attr("write")), pyflush(pyostream.attr("flush")) { setp(d_buffer.get(), d_buffer.get() + buf_size - 1); } @@ -103,7 +161,7 @@ PYBIND11_NAMESPACE_END(detail) { py::scoped_ostream_redirect output{std::cerr, py::module::import("sys").attr("stderr")}; - std::cerr << "Hello, World!"; + std::cout << "Hello, World!"; } \endrst */ class scoped_ostream_redirect { @@ -113,9 +171,9 @@ protected: detail::pythonbuf buffer; public: - scoped_ostream_redirect( - std::ostream &costream = std::cout, - object pyostream = module::import("sys").attr("stdout")) + explicit scoped_ostream_redirect(std::ostream &costream = std::cout, + const object &pyostream + = module_::import("sys").attr("stdout")) : costream(costream), buffer(pyostream) { old = costream.rdbuf(&buffer); } @@ -144,10 +202,10 @@ public: \endrst */ class scoped_estream_redirect : public scoped_ostream_redirect { public: - scoped_estream_redirect( - std::ostream &costream = std::cerr, - object pyostream = module::import("sys").attr("stderr")) - : scoped_ostream_redirect(costream,pyostream) {} + explicit scoped_estream_redirect(std::ostream &costream = std::cerr, + const object &pyostream + = module_::import("sys").attr("stderr")) + : scoped_ostream_redirect(costream, pyostream) {} }; @@ -161,7 +219,7 @@ class OstreamRedirect { std::unique_ptr redirect_stderr; public: - OstreamRedirect(bool do_stdout = true, bool do_stderr = true) + explicit OstreamRedirect(bool do_stdout = true, bool do_stderr = true) : do_stdout_(do_stdout), do_stderr_(do_stderr) {} void enter() { @@ -206,11 +264,12 @@ PYBIND11_NAMESPACE_END(detail) m.noisy_function_with_error_printing() \endrst */ -inline class_ add_ostream_redirect(module m, std::string name = "ostream_redirect") { - return class_(m, name.c_str(), module_local()) - .def(init(), arg("stdout")=true, arg("stderr")=true) +inline class_ +add_ostream_redirect(module_ m, const std::string &name = "ostream_redirect") { + return class_(std::move(m), name.c_str(), module_local()) + .def(init(), arg("stdout") = true, arg("stderr") = true) .def("__enter__", &detail::OstreamRedirect::enter) - .def("__exit__", [](detail::OstreamRedirect &self_, args) { self_.exit(); }); + .def("__exit__", [](detail::OstreamRedirect &self_, const args &) { self_.exit(); }); } PYBIND11_NAMESPACE_END(PYBIND11_NAMESPACE) diff --git a/pybind11/include/pybind11/numpy.h b/pybind11/include/pybind11/numpy.h index 03e1ed61e..95a743ace 100644 --- a/pybind11/include/pybind11/numpy.h +++ b/pybind11/include/pybind11/numpy.h @@ -20,20 +20,18 @@ #include #include #include +#include #include #include #include -#if defined(_MSC_VER) -# pragma warning(push) -# pragma warning(disable: 4127) // warning C4127: Conditional expression is constant -#endif - /* This will be true on all flat address space platforms and allows us to reduce the whole npy_intp / ssize_t / Py_intptr_t business down to just ssize_t for all size and dimension types (e.g. shape, strides, indexing), instead of inflicting this upon the library user. */ -static_assert(sizeof(ssize_t) == sizeof(Py_intptr_t), "ssize_t != Py_intptr_t"); +static_assert(sizeof(::pybind11::ssize_t) == sizeof(Py_intptr_t), "ssize_t != Py_intptr_t"); +static_assert(std::is_signed::value, "Py_intptr_t must be signed"); +// We now can reinterpret_cast between py::ssize_t and Py_intptr_t (MSVC + PyPy cares) PYBIND11_NAMESPACE_BEGIN(PYBIND11_NAMESPACE) @@ -41,7 +39,7 @@ class array; // Forward declaration PYBIND11_NAMESPACE_BEGIN(detail) -template <> struct handle_type_name { static constexpr auto name = _("numpy.ndarray"); }; +template <> struct handle_type_name { static constexpr auto name = const_name("numpy.ndarray"); }; template struct npy_format_descriptor; @@ -101,7 +99,7 @@ struct numpy_internals { } }; -inline PYBIND11_NOINLINE void load_numpy_internals(numpy_internals* &ptr) { +PYBIND11_NOINLINE void load_numpy_internals(numpy_internals* &ptr) { ptr = &get_or_create_shared_data("_numpy_internals"); } @@ -161,10 +159,10 @@ struct npy_api { NPY_ULONG_, NPY_ULONGLONG_, NPY_UINT_), }; - typedef struct { + struct PyArray_Dims { Py_intptr_t *ptr; int len; - } PyArray_Dims; + }; static npy_api& get() { static npy_api api = lookup(); @@ -172,10 +170,10 @@ struct npy_api { } bool PyArray_Check_(PyObject *obj) const { - return (bool) PyObject_TypeCheck(obj, PyArray_Type_); + return PyObject_TypeCheck(obj, PyArray_Type_) != 0; } bool PyArrayDescr_Check_(PyObject *obj) const { - return (bool) PyObject_TypeCheck(obj, PyArrayDescr_Type_); + return PyObject_TypeCheck(obj, PyArrayDescr_Type_) != 0; } unsigned int (*PyArray_GetNDArrayCFeatureVersion_)(); @@ -200,6 +198,9 @@ struct npy_api { // Unused. Not removed because that affects ABI of the class. int (*PyArray_SetBaseObject_)(PyObject *, PyObject *); PyObject* (*PyArray_Resize_)(PyObject*, PyArray_Dims*, int, int); + PyObject* (*PyArray_Newshape_)(PyObject*, PyArray_Dims*, int); + PyObject* (*PyArray_View_)(PyObject*, PyObject*, PyObject*); + private: enum functions { API_PyArray_GetNDArrayCFeatureVersion = 211, @@ -214,15 +215,17 @@ private: API_PyArray_NewCopy = 85, API_PyArray_NewFromDescr = 94, API_PyArray_DescrNewFromType = 96, + API_PyArray_Newshape = 135, + API_PyArray_Squeeze = 136, + API_PyArray_View = 137, API_PyArray_DescrConverter = 174, API_PyArray_EquivTypes = 182, API_PyArray_GetArrayParamsFromObject = 278, - API_PyArray_Squeeze = 136, API_PyArray_SetBaseObject = 282 }; static npy_api lookup() { - module_ m = module::import("numpy.core.multiarray"); + module_ m = module_::import("numpy.core.multiarray"); auto c = m.attr("_ARRAY_API"); #if PY_MAJOR_VERSION >= 3 void **api_ptr = (void **) PyCapsule_GetPointer(c.ptr(), NULL); @@ -245,11 +248,14 @@ private: DECL_NPY_API(PyArray_NewCopy); DECL_NPY_API(PyArray_NewFromDescr); DECL_NPY_API(PyArray_DescrNewFromType); + DECL_NPY_API(PyArray_Newshape); + DECL_NPY_API(PyArray_Squeeze); + DECL_NPY_API(PyArray_View); DECL_NPY_API(PyArray_DescrConverter); DECL_NPY_API(PyArray_EquivTypes); DECL_NPY_API(PyArray_GetArrayParamsFromObject); - DECL_NPY_API(PyArray_Squeeze); DECL_NPY_API(PyArray_SetBaseObject); + #undef DECL_NPY_API return api; } @@ -284,7 +290,7 @@ template struct array_info_scalar { using type = T; static constexpr bool is_array = false; static constexpr bool is_empty = false; - static constexpr auto extents = _(""); + static constexpr auto extents = const_name(""); static void append_extents(list& /* shape */) { } }; // Computes underlying type and a comma-separated list of extents for array @@ -303,8 +309,8 @@ template struct array_info> { array_info::append_extents(shape); } - static constexpr auto extents = _::is_array>( - concat(_(), array_info::extents), _() + static constexpr auto extents = const_name::is_array>( + concat(const_name(), array_info::extents), const_name() ); }; // For numpy we have special handling for arrays of characters, so we don't include @@ -316,18 +322,23 @@ template using remove_all_extents_t = typename array_info::type; template using is_pod_struct = all_of< std::is_standard_layout, // since we're accessing directly in memory we need a standard layout type -#if !defined(__GNUG__) || defined(_LIBCPP_VERSION) || defined(_GLIBCXX_USE_CXX11_ABI) - // _GLIBCXX_USE_CXX11_ABI indicates that we're using libstdc++ from GCC 5 or newer, independent - // of the actual compiler (Clang can also use libstdc++, but it always defines __GNUC__ == 4). - std::is_trivially_copyable, -#else - // GCC 4 doesn't implement is_trivially_copyable, so approximate it +#if defined(__GLIBCXX__) && (__GLIBCXX__ < 20150422 || __GLIBCXX__ == 20150426 || __GLIBCXX__ == 20150623 || __GLIBCXX__ == 20150626 || __GLIBCXX__ == 20160803) + // libstdc++ < 5 (including versions 4.8.5, 4.9.3 and 4.9.4 which were released after 5) + // don't implement is_trivially_copyable, so approximate it std::is_trivially_destructible, satisfies_any_of, +#else + std::is_trivially_copyable, #endif satisfies_none_of >; +// Replacement for std::is_pod (deprecated in C++20) +template using is_pod = all_of< + std::is_standard_layout, + std::is_trivial +>; + template ssize_t byte_offset_unsafe(const Strides &) { return 0; } template ssize_t byte_offset_unsafe(const Strides &strides, ssize_t i, Ix... index) { @@ -419,6 +430,10 @@ class unchecked_mutable_reference : public unchecked_reference { using ConstBase::ConstBase; using ConstBase::Dynamic; public: + // Bring in const-qualified versions from base class + using ConstBase::operator(); + using ConstBase::operator[]; + /// Mutable, unchecked access to data at the given indices. template T& operator()(Ix... index) { static_assert(ssize_t{sizeof...(Ix)} == Dims || Dynamic, @@ -453,28 +468,30 @@ public: explicit dtype(const buffer_info &info) { dtype descr(_dtype_from_pep3118()(PYBIND11_STR_TYPE(info.format))); // If info.itemsize == 0, use the value calculated from the format string - m_ptr = descr.strip_padding(info.itemsize ? info.itemsize : descr.itemsize()).release().ptr(); + m_ptr = descr.strip_padding(info.itemsize != 0 ? info.itemsize : descr.itemsize()) + .release() + .ptr(); } explicit dtype(const std::string &format) { m_ptr = from_args(pybind11::str(format)).release().ptr(); } - dtype(const char *format) : dtype(std::string(format)) { } + explicit dtype(const char *format) : dtype(std::string(format)) {} dtype(list names, list formats, list offsets, ssize_t itemsize) { dict args; - args["names"] = names; - args["formats"] = formats; - args["offsets"] = offsets; + args["names"] = std::move(names); + args["formats"] = std::move(formats); + args["offsets"] = std::move(offsets); args["itemsize"] = pybind11::int_(itemsize); - m_ptr = from_args(args).release().ptr(); + m_ptr = from_args(std::move(args)).release().ptr(); } /// This is essentially the same as calling numpy.dtype(args) in Python. static dtype from_args(object args) { PyObject *ptr = nullptr; - if (!detail::npy_api::get().PyArray_DescrConverter_(args.ptr(), &ptr) || !ptr) + if ((detail::npy_api::get().PyArray_DescrConverter_(args.ptr(), &ptr) == 0) || !ptr) throw error_already_set(); return reinterpret_steal(ptr); } @@ -494,14 +511,24 @@ public: return detail::array_descriptor_proxy(m_ptr)->names != nullptr; } - /// Single-character type code. + /// Single-character code for dtype's kind. + /// For example, floating point types are 'f' and integral types are 'i'. char kind() const { return detail::array_descriptor_proxy(m_ptr)->kind; } + /// Single-character for dtype's type. + /// For example, ``float`` is 'f', ``double`` 'd', ``int`` 'i', and ``long`` 'l'. + char char_() const { + // Note: The signature, `dtype::char_` follows the naming of NumPy's + // public Python API (i.e., ``dtype.char``), rather than its internal + // C API (``PyArray_Descr::type``). + return detail::array_descriptor_proxy(m_ptr)->type; + } + private: static object _dtype_from_pep3118() { - static PyObject *obj = module::import("numpy.core._internal") + static PyObject *obj = module_::import("numpy.core._internal") .attr("_dtype_from_pep3118").cast().release().ptr(); return reinterpret_borrow(obj); } @@ -520,7 +547,7 @@ private: auto name = spec[0].cast(); auto format = spec[1].cast()[0].cast(); auto offset = spec[1].cast()[1].cast(); - if (!len(name) && format.kind() == 'V') + if ((len(name) == 0u) && format.kind() == 'V') continue; field_descriptors.push_back({(PYBIND11_STR_TYPE) name, format.strip_padding(format.itemsize()), offset}); } @@ -536,7 +563,7 @@ private: formats.append(descr.format); offsets.append(descr.offset); } - return dtype(names, formats, offsets, itemsize); + return dtype(std::move(names), std::move(formats), std::move(offsets), itemsize); } }; @@ -560,7 +587,7 @@ public: const void *ptr = nullptr, handle base = handle()) { if (strides->empty()) - *strides = c_strides(*shape, dt.itemsize()); + *strides = detail::c_strides(*shape, dt.itemsize()); auto ndim = shape->size(); if (ndim != strides->size()) @@ -579,7 +606,10 @@ public: auto &api = detail::npy_api::get(); auto tmp = reinterpret_steal(api.PyArray_NewFromDescr_( - api.PyArray_Type_, descr.release().ptr(), (int) ndim, shape->data(), strides->data(), + api.PyArray_Type_, descr.release().ptr(), (int) ndim, + // Use reinterpret_cast for PyPy on Windows (remove if fixed, checked on 7.3.1) + reinterpret_cast(shape->data()), + reinterpret_cast(strides->data()), const_cast(ptr), flags, nullptr)); if (!tmp) throw error_already_set(); @@ -720,7 +750,7 @@ public: * and the caller must take care not to access invalid dimensions or dimension indices. */ template detail::unchecked_mutable_reference mutable_unchecked() & { - if (Dims >= 0 && ndim() != Dims) + if (PYBIND11_SILENCE_MSVC_C4127(Dims >= 0) && ndim() != Dims) throw std::domain_error("array has incorrect number of dimensions: " + std::to_string(ndim()) + "; expected " + std::to_string(Dims)); return detail::unchecked_mutable_reference(mutable_data(), shape(), strides(), ndim()); @@ -734,7 +764,7 @@ public: * invalid dimensions or dimension indices. */ template detail::unchecked_reference unchecked() const & { - if (Dims >= 0 && ndim() != Dims) + if (PYBIND11_SILENCE_MSVC_C4127(Dims >= 0) && ndim() != Dims) throw std::domain_error("array has incorrect number of dimensions: " + std::to_string(ndim()) + "; expected " + std::to_string(Dims)); return detail::unchecked_reference(data(), shape(), strides(), ndim()); @@ -751,16 +781,45 @@ public: /// then resize will succeed only if it makes a reshape, i.e. original size doesn't change void resize(ShapeContainer new_shape, bool refcheck = true) { detail::npy_api::PyArray_Dims d = { - new_shape->data(), int(new_shape->size()) + // Use reinterpret_cast for PyPy on Windows (remove if fixed, checked on 7.3.1) + reinterpret_cast(new_shape->data()), + int(new_shape->size()) }; // try to resize, set ordering param to -1 cause it's not used anyway - object new_array = reinterpret_steal( + auto new_array = reinterpret_steal( detail::npy_api::get().PyArray_Resize_(m_ptr, &d, int(refcheck), -1) ); if (!new_array) throw error_already_set(); if (isinstance(new_array)) { *this = std::move(new_array); } } + /// Optional `order` parameter omitted, to be added as needed. + array reshape(ShapeContainer new_shape) { + detail::npy_api::PyArray_Dims d + = {reinterpret_cast(new_shape->data()), int(new_shape->size())}; + auto new_array + = reinterpret_steal(detail::npy_api::get().PyArray_Newshape_(m_ptr, &d, 0)); + if (!new_array) { + throw error_already_set(); + } + return new_array; + } + + /// Create a view of an array in a different data type. + /// This function may fundamentally reinterpret the data in the array. + /// It is the responsibility of the caller to ensure that this is safe. + /// Only supports the `dtype` argument, the `type` argument is omitted, + /// to be added as needed. + array view(const std::string &dtype) { + auto &api = detail::npy_api::get(); + auto new_view = reinterpret_steal(api.PyArray_View_( + m_ptr, dtype::from_args(pybind11::str(dtype)).release().ptr(), nullptr)); + if (!new_view) { + throw error_already_set(); + } + return new_view; + } + /// Ensure that the argument is a NumPy array /// In case of an error, nullptr is returned and the Python error is cleared. static array ensure(handle h, int ExtraFlags = 0) { @@ -788,25 +847,6 @@ protected: throw std::domain_error("array is not writeable"); } - // Default, C-style strides - static std::vector c_strides(const std::vector &shape, ssize_t itemsize) { - auto ndim = shape.size(); - std::vector strides(ndim, itemsize); - if (ndim > 0) - for (size_t i = ndim - 1; i > 0; --i) - strides[i - 1] = strides[i] * shape[i]; - return strides; - } - - // F-style strides; default when constructing an array_t with `ExtraFlags & f_style` - static std::vector f_strides(const std::vector &shape, ssize_t itemsize) { - auto ndim = shape.size(); - std::vector strides(ndim, itemsize); - for (size_t i = 1; i < ndim; ++i) - strides[i] = strides[i - 1] * shape[i - 1]; - return strides; - } - template void check_dimensions(Ix... index) const { check_dimensions_impl(ssize_t(0), shape(), ssize_t(index)...); } @@ -854,6 +894,7 @@ public: if (!is_borrowed) Py_XDECREF(h.ptr()); } + // NOLINTNEXTLINE(google-explicit-constructor) array_t(const object &o) : array(raw_array_t(o.ptr()), stolen_t{}) { if (!m_ptr) throw error_already_set(); } @@ -864,9 +905,12 @@ public: : array(std::move(shape), std::move(strides), ptr, base) { } explicit array_t(ShapeContainer shape, const T *ptr = nullptr, handle base = handle()) - : array_t(private_ctor{}, std::move(shape), - ExtraFlags & f_style ? f_strides(*shape, itemsize()) : c_strides(*shape, itemsize()), - ptr, base) { } + : array_t(private_ctor{}, + std::move(shape), + (ExtraFlags & f_style) != 0 ? detail::f_strides(*shape, itemsize()) + : detail::c_strides(*shape, itemsize()), + ptr, + base) {} explicit array_t(ssize_t count, const T *ptr = nullptr, handle base = handle()) : array({count}, {}, ptr, base) { } @@ -977,7 +1021,7 @@ template struct format_descriptor::is_array>> { static std::string format() { using namespace detail; - static constexpr auto extents = _("(") + array_info::extents + _(")"); + static constexpr auto extents = const_name("(") + array_info::extents + const_name(")"); return extents.text + format_descriptor>::format(); } }; @@ -1012,23 +1056,28 @@ struct npy_format_descriptor_name; template struct npy_format_descriptor_name::value>> { - static constexpr auto name = _::value>( - _("bool"), _::value>("numpy.int", "numpy.uint") + _() + static constexpr auto name = const_name::value>( + const_name("bool"), const_name::value>("numpy.int", "numpy.uint") + const_name() ); }; template struct npy_format_descriptor_name::value>> { - static constexpr auto name = _::value || std::is_same::value>( - _("numpy.float") + _(), _("numpy.longdouble") + static constexpr auto name = const_name::value + || std::is_same::value + || std::is_same::value + || std::is_same::value>( + const_name("numpy.float") + const_name(), const_name("numpy.longdouble") ); }; template struct npy_format_descriptor_name::value>> { - static constexpr auto name = _::value - || std::is_same::value>( - _("numpy.complex") + _(), _("numpy.longcomplex") + static constexpr auto name = const_name::value + || std::is_same::value + || std::is_same::value + || std::is_same::value>( + const_name("numpy.complex") + const_name(), const_name("numpy.longcomplex") ); }; @@ -1056,7 +1105,7 @@ public: }; #define PYBIND11_DECL_CHAR_FMT \ - static constexpr auto name = _("S") + _(); \ + static constexpr auto name = const_name("S") + const_name(); \ static pybind11::dtype dtype() { return pybind11::dtype(std::string("S") + std::to_string(N)); } template struct npy_format_descriptor { PYBIND11_DECL_CHAR_FMT }; template struct npy_format_descriptor> { PYBIND11_DECL_CHAR_FMT }; @@ -1068,7 +1117,7 @@ private: public: static_assert(!array_info::is_empty, "Zero-sized arrays are not supported"); - static constexpr auto name = _("(") + array_info::extents + _(")") + base_descr::name; + static constexpr auto name = const_name("(") + array_info::extents + const_name(")") + base_descr::name; static pybind11::dtype dtype() { list shape; array_info::append_extents(shape); @@ -1092,7 +1141,7 @@ struct field_descriptor { dtype descr; }; -inline PYBIND11_NOINLINE void register_structured_dtype( +PYBIND11_NOINLINE void register_structured_dtype( any_container fields, const std::type_info& tinfo, ssize_t itemsize, bool (*direct_converter)(PyObject *, void *&)) { @@ -1116,7 +1165,10 @@ inline PYBIND11_NOINLINE void register_structured_dtype( formats.append(field.descr); offsets.append(pybind11::int_(field.offset)); } - auto dtype_ptr = pybind11::dtype(names, formats, offsets, itemsize).release().ptr(); + auto dtype_ptr + = pybind11::dtype(std::move(names), std::move(formats), std::move(offsets), itemsize) + .release() + .ptr(); // There is an existing bug in NumPy (as of v1.11): trailing bytes are // not encoded explicitly into the format string. This will supposedly @@ -1270,26 +1322,13 @@ private: #endif // __CLION_IDE__ -template -using array_iterator = typename std::add_pointer::type; - -template -array_iterator array_begin(const buffer_info& buffer) { - return array_iterator(reinterpret_cast(buffer.ptr)); -} - -template -array_iterator array_end(const buffer_info& buffer) { - return array_iterator(reinterpret_cast(buffer.ptr) + buffer.size); -} - class common_iterator { public: using container_type = std::vector; using value_type = container_type::value_type; using size_type = container_type::size_type; - common_iterator() : p_ptr(0), m_strides() {} + common_iterator() : m_strides() {} common_iterator(void* ptr, const container_type& strides, const container_type& shape) : p_ptr(reinterpret_cast(ptr)), m_strides(strides.size()) { @@ -1310,7 +1349,7 @@ public: } private: - char* p_ptr; + char *p_ptr{0}; container_type m_strides; }; @@ -1338,9 +1377,8 @@ public: if (++m_index[i] != m_shape[i]) { increment_common_iterator(i); break; - } else { - m_index[i] = 0; } + m_index[i] = 0; } return *this; } @@ -1474,7 +1512,7 @@ struct vectorize_arg { using call_type = remove_reference_t; // Is this a vectorized argument? static constexpr bool vectorize = - satisfies_any_of::value && + satisfies_any_of::value && satisfies_none_of::value && (!std::is_reference::value || (std::is_lvalue_reference::value && std::is_const::value)); @@ -1482,6 +1520,55 @@ struct vectorize_arg { using type = conditional_t, array::forcecast>, T>; }; + +// py::vectorize when a return type is present +template +struct vectorize_returned_array { + using Type = array_t; + + static Type create(broadcast_trivial trivial, const std::vector &shape) { + if (trivial == broadcast_trivial::f_trivial) + return array_t(shape); + return array_t(shape); + } + + static Return *mutable_data(Type &array) { + return array.mutable_data(); + } + + static Return call(Func &f, Args &... args) { + return f(args...); + } + + static void call(Return *out, size_t i, Func &f, Args &... args) { + out[i] = f(args...); + } +}; + +// py::vectorize when a return type is not present +template +struct vectorize_returned_array { + using Type = none; + + static Type create(broadcast_trivial, const std::vector &) { + return none(); + } + + static void *mutable_data(Type &) { + return nullptr; + } + + static detail::void_type call(Func &f, Args &... args) { + f(args...); + return {}; + } + + static void call(void *, size_t, Func &f, Args &... args) { + f(args...); + } +}; + + template struct vectorize_helper { @@ -1498,8 +1585,11 @@ private: "pybind11::vectorize(...) requires a function with at least one vectorizable argument"); public: - template - explicit vectorize_helper(T &&f) : f(std::forward(f)) { } + template ::type>::value>> + explicit vectorize_helper(T &&f) : f(std::forward(f)) {} object operator()(typename vectorize_arg::type... args) { return run(args..., @@ -1516,6 +1606,8 @@ private: using arg_call_types = std::tuple::call_type...>; template using param_n_t = typename std::tuple_element::type; + using returned_array = vectorize_returned_array; + // Runs a vectorized function given arguments tuple and three index sequences: // - Index is the full set of 0 ... (N-1) argument indices; // - VIndex is the subset of argument indices with vectorized parameters, letting us access @@ -1547,20 +1639,19 @@ private: // not wrapped in an array). if (size == 1 && ndim == 0) { PYBIND11_EXPAND_SIDE_EFFECTS(params[VIndex] = buffers[BIndex].ptr); - return cast(f(*reinterpret_cast *>(params[Index])...)); + return cast(returned_array::call(f, *reinterpret_cast *>(params[Index])...)); } - array_t result; - if (trivial == broadcast_trivial::f_trivial) result = array_t(shape); - else result = array_t(shape); + auto result = returned_array::create(trivial, shape); if (size == 0) return std::move(result); /* Call the function */ + auto mutable_data = returned_array::mutable_data(result); if (trivial == broadcast_trivial::non_trivial) - apply_broadcast(buffers, params, result, i_seq, vi_seq, bi_seq); + apply_broadcast(buffers, params, mutable_data, size, shape, i_seq, vi_seq, bi_seq); else - apply_trivial(buffers, params, result.mutable_data(), size, i_seq, vi_seq, bi_seq); + apply_trivial(buffers, params, mutable_data, size, i_seq, vi_seq, bi_seq); return std::move(result); } @@ -1583,7 +1674,7 @@ private: }}; for (size_t i = 0; i < size; ++i) { - out[i] = f(*reinterpret_cast *>(params[Index])...); + returned_array::call(out, i, f, *reinterpret_cast *>(params[Index])...); for (auto &x : vecparams) x.first += x.second; } } @@ -1591,19 +1682,18 @@ private: template void apply_broadcast(std::array &buffers, std::array ¶ms, - array_t &output_array, + Return *out, + size_t size, + const std::vector &output_shape, index_sequence, index_sequence, index_sequence) { - buffer_info output = output_array.request(); - multi_array_iterator input_iter(buffers, output.shape); + multi_array_iterator input_iter(buffers, output_shape); - for (array_iterator iter = array_begin(output), end = array_end(output); - iter != end; - ++iter, ++input_iter) { + for (size_t i = 0; i < size; ++i, ++input_iter) { PYBIND11_EXPAND_SIDE_EFFECTS(( params[VIndex] = input_iter.template data() )); - *iter = f(*reinterpret_cast *>(std::get(params))...); + returned_array::call(out, i, f, *reinterpret_cast *>(std::get(params))...); } } }; @@ -1615,7 +1705,7 @@ vectorize_extractor(const Func &f, Return (*) (Args ...)) { } template struct handle_type_name> { - static constexpr auto name = _("numpy.ndarray[") + npy_format_descriptor::name + _("]"); + static constexpr auto name = const_name("numpy.ndarray[") + npy_format_descriptor::name + const_name("]"); }; PYBIND11_NAMESPACE_END(detail) @@ -1649,7 +1739,3 @@ Helper vectorize(Return (Class::*f)(Args...) const) { } PYBIND11_NAMESPACE_END(PYBIND11_NAMESPACE) - -#if defined(_MSC_VER) -#pragma warning(pop) -#endif diff --git a/pybind11/include/pybind11/operators.h b/pybind11/include/pybind11/operators.h index 086cb4cfd..2a6153158 100644 --- a/pybind11/include/pybind11/operators.h +++ b/pybind11/include/pybind11/operators.h @@ -11,13 +11,6 @@ #include "pybind11.h" -#if defined(__clang__) && !defined(__INTEL_COMPILER) -# pragma clang diagnostic ignored "-Wunsequenced" // multiple unsequenced modifications to 'self' (when using def(py::self OP Type())) -#elif defined(_MSC_VER) -# pragma warning(push) -# pragma warning(disable: 4127) // warning C4127: Conditional expression is constant -#endif - PYBIND11_NAMESPACE_BEGIN(PYBIND11_NAMESPACE) PYBIND11_NAMESPACE_BEGIN(detail) @@ -58,7 +51,8 @@ template struct op_ { using op = op_impl; cl.def(op::name(), &op::execute, is_operator(), extra...); #if PY_MAJOR_VERSION < 3 - if (id == op_truediv || id == op_itruediv) + if (PYBIND11_SILENCE_MSVC_C4127(id == op_truediv) || + PYBIND11_SILENCE_MSVC_C4127(id == op_itruediv)) cl.def(id == op_itruediv ? "__idiv__" : ot == op_l ? "__div__" : "__rdiv__", &op::execute, is_operator(), extra...); #endif @@ -167,7 +161,3 @@ using detail::self; using detail::hash; PYBIND11_NAMESPACE_END(PYBIND11_NAMESPACE) - -#if defined(_MSC_VER) -# pragma warning(pop) -#endif diff --git a/pybind11/include/pybind11/pybind11.h b/pybind11/include/pybind11/pybind11.h index f6dba4ed2..7aa93bb5a 100644 --- a/pybind11/include/pybind11/pybind11.h +++ b/pybind11/include/pybind11/pybind11.h @@ -10,56 +10,84 @@ #pragma once -#if defined(__INTEL_COMPILER) -# pragma warning push -# pragma warning disable 68 // integer conversion resulted in a change of sign -# pragma warning disable 186 // pointless comparison of unsigned integer with zero -# pragma warning disable 878 // incompatible exception specifications -# pragma warning disable 1334 // the "template" keyword used for syntactic disambiguation may only be used within a template -# pragma warning disable 1682 // implicit conversion of a 64-bit integral type to a smaller integral type (potential portability problem) -# pragma warning disable 1786 // function "strdup" was declared deprecated -# pragma warning disable 1875 // offsetof applied to non-POD (Plain Old Data) types is nonstandard -# pragma warning disable 2196 // warning #2196: routine is both "inline" and "noinline" -#elif defined(_MSC_VER) -# pragma warning(push) -# pragma warning(disable: 4100) // warning C4100: Unreferenced formal parameter -# pragma warning(disable: 4127) // warning C4127: Conditional expression is constant -# pragma warning(disable: 4512) // warning C4512: Assignment operator was implicitly defined as deleted -# pragma warning(disable: 4800) // warning C4800: 'int': forcing value to bool 'true' or 'false' (performance warning) -# pragma warning(disable: 4996) // warning C4996: The POSIX name for this item is deprecated. Instead, use the ISO C and C++ conformant name -# pragma warning(disable: 4702) // warning C4702: unreachable code -# pragma warning(disable: 4522) // warning C4522: multiple assignment operators specified -#elif defined(__GNUG__) && !defined(__clang__) -# pragma GCC diagnostic push -# pragma GCC diagnostic ignored "-Wunused-but-set-parameter" -# pragma GCC diagnostic ignored "-Wunused-but-set-variable" -# pragma GCC diagnostic ignored "-Wmissing-field-initializers" -# pragma GCC diagnostic ignored "-Wstrict-aliasing" -# pragma GCC diagnostic ignored "-Wattributes" -# if __GNUC__ >= 7 -# pragma GCC diagnostic ignored "-Wnoexcept-type" -# endif -#endif - #include "attr.h" +#include "gil.h" #include "options.h" #include "detail/class.h" #include "detail/init.h" +#include +#include +#include +#include +#include +#include + +#include + +#if defined(__cpp_lib_launder) && !(defined(_MSC_VER) && (_MSC_VER < 1914)) +# define PYBIND11_STD_LAUNDER std::launder +# define PYBIND11_HAS_STD_LAUNDER 1 +#else +# define PYBIND11_STD_LAUNDER +# define PYBIND11_HAS_STD_LAUNDER 0 +#endif #if defined(__GNUG__) && !defined(__clang__) # include #endif +/* https://stackoverflow.com/questions/46798456/handling-gccs-noexcept-type-warning + This warning is about ABI compatibility, not code health. + It is only actually needed in a couple places, but apparently GCC 7 "generates this warning if + and only if the first template instantiation ... involves noexcept" [stackoverflow], therefore + it could get triggered from seemingly random places, depending on user code. + No other GCC version generates this warning. + */ +#if defined(__GNUC__) && __GNUC__ == 7 +# pragma GCC diagnostic push +# pragma GCC diagnostic ignored "-Wnoexcept-type" +#endif + PYBIND11_NAMESPACE_BEGIN(PYBIND11_NAMESPACE) +PYBIND11_NAMESPACE_BEGIN(detail) + +// Apply all the extensions translators from a list +// Return true if one of the translators completed without raising an exception +// itself. Return of false indicates that if there are other translators +// available, they should be tried. +inline bool apply_exception_translators(std::forward_list& translators) { + auto last_exception = std::current_exception(); + + for (auto &translator : translators) { + try { + translator(last_exception); + return true; + } catch (...) { + last_exception = std::current_exception(); + } + } + return false; +} + +#if defined(_MSC_VER) +# define PYBIND11_COMPAT_STRDUP _strdup +#else +# define PYBIND11_COMPAT_STRDUP strdup +#endif + +PYBIND11_NAMESPACE_END(detail) + /// Wraps an arbitrary C++ function/method/lambda function/.. into a callable Python object class cpp_function : public function { public: cpp_function() = default; + // NOLINTNEXTLINE(google-explicit-constructor) cpp_function(std::nullptr_t) { } /// Construct a cpp_function from a vanilla function pointer template + // NOLINTNEXTLINE(google-explicit-constructor) cpp_function(Return (*f)(Args...), const Extra&... extra) { initialize(f, f, extra...); } @@ -67,6 +95,7 @@ public: /// Construct a cpp_function from a lambda function (possibly with internal state) template ::value>> + // NOLINTNEXTLINE(google-explicit-constructor) cpp_function(Func &&f, const Extra&... extra) { initialize(std::forward(f), (detail::function_signature_t *) nullptr, extra...); @@ -74,6 +103,7 @@ public: /// Construct a cpp_function from a class method (non-const, no ref-qualifier) template + // NOLINTNEXTLINE(google-explicit-constructor) cpp_function(Return (Class::*f)(Arg...), const Extra&... extra) { initialize([f](Class *c, Arg... args) -> Return { return (c->*f)(std::forward(args)...); }, (Return (*) (Class *, Arg...)) nullptr, extra...); @@ -83,13 +113,15 @@ public: /// A copy of the overload for non-const functions without explicit ref-qualifier /// but with an added `&`. template + // NOLINTNEXTLINE(google-explicit-constructor) cpp_function(Return (Class::*f)(Arg...)&, const Extra&... extra) { - initialize([f](Class *c, Arg... args) -> Return { return (c->*f)(args...); }, + initialize([f](Class *c, Arg... args) -> Return { return (c->*f)(std::forward(args)...); }, (Return (*) (Class *, Arg...)) nullptr, extra...); } /// Construct a cpp_function from a class method (const, no ref-qualifier) template + // NOLINTNEXTLINE(google-explicit-constructor) cpp_function(Return (Class::*f)(Arg...) const, const Extra&... extra) { initialize([f](const Class *c, Arg... args) -> Return { return (c->*f)(std::forward(args)...); }, (Return (*)(const Class *, Arg ...)) nullptr, extra...); @@ -99,8 +131,9 @@ public: /// A copy of the overload for const functions without explicit ref-qualifier /// but with an added `&`. template + // NOLINTNEXTLINE(google-explicit-constructor) cpp_function(Return (Class::*f)(Arg...) const&, const Extra&... extra) { - initialize([f](const Class *c, Arg... args) -> Return { return (c->*f)(args...); }, + initialize([f](const Class *c, Arg... args) -> Return { return (c->*f)(std::forward(args)...); }, (Return (*)(const Class *, Arg ...)) nullptr, extra...); } @@ -108,9 +141,16 @@ public: object name() const { return attr("__name__"); } protected: + struct InitializingFunctionRecordDeleter { + // `destruct(function_record, false)`: `initialize_generic` copies strings and + // takes care of cleaning up in case of exceptions. So pass `false` to `free_strings`. + void operator()(detail::function_record * rec) { destruct(rec, false); } + }; + using unique_function_record = std::unique_ptr; + /// Space optimization: don't inline this frequently instantiated fragment - PYBIND11_NOINLINE detail::function_record *make_function_record() { - return new detail::function_record(); + PYBIND11_NOINLINE unique_function_record make_function_record() { + return unique_function_record(new detail::function_record()); } /// Special internal constructor for functors, lambda functions, etc. @@ -120,23 +160,38 @@ protected: struct capture { remove_reference_t f; }; /* Store the function including any extra state it might have (e.g. a lambda capture object) */ - auto rec = make_function_record(); + // The unique_ptr makes sure nothing is leaked in case of an exception. + auto unique_rec = make_function_record(); + auto rec = unique_rec.get(); /* Store the capture object directly in the function record if there is enough space */ - if (sizeof(capture) <= sizeof(rec->data)) { + if (PYBIND11_SILENCE_MSVC_C4127(sizeof(capture) <= sizeof(rec->data))) { /* Without these pragmas, GCC warns that there might not be enough space to use the placement new operator. However, the 'if' statement above ensures that this is the case. */ -#if defined(__GNUG__) && !defined(__clang__) && __GNUC__ >= 6 +#if defined(__GNUG__) && __GNUC__ >= 6 && !defined(__clang__) && !defined(__INTEL_COMPILER) # pragma GCC diagnostic push # pragma GCC diagnostic ignored "-Wplacement-new" #endif new ((capture *) &rec->data) capture { std::forward(f) }; -#if defined(__GNUG__) && !defined(__clang__) && __GNUC__ >= 6 +#if defined(__GNUG__) && __GNUC__ >= 6 && !defined(__clang__) && !defined(__INTEL_COMPILER) +# pragma GCC diagnostic pop +#endif +#if defined(__GNUG__) && !PYBIND11_HAS_STD_LAUNDER && !defined(__INTEL_COMPILER) +# pragma GCC diagnostic push +# pragma GCC diagnostic ignored "-Wstrict-aliasing" +#endif + // UB without std::launder, but without breaking ABI and/or + // a significant refactoring it's "impossible" to solve. + if (!std::is_trivially_destructible::value) + rec->free_data = [](function_record *r) { + auto data = PYBIND11_STD_LAUNDER((capture *) &r->data); + (void) data; + data->~capture(); + }; +#if defined(__GNUG__) && !PYBIND11_HAS_STD_LAUNDER && !defined(__INTEL_COMPILER) # pragma GCC diagnostic pop #endif - if (!std::is_trivially_destructible::value) - rec->free_data = [](function_record *r) { ((capture *) &r->data)->~capture(); }; } else { rec->data[0] = new capture { std::forward(f) }; rec->free_data = [](function_record *r) { delete ((capture *) r->data[0]); }; @@ -148,7 +203,7 @@ protected: conditional_t::value, void_type, Return> >; - static_assert(expected_num_args(sizeof...(Args), cast_in::has_args, cast_in::has_kwargs), + static_assert(expected_num_args(sizeof...(Args), cast_in::args_pos >= 0, cast_in::has_kwargs), "The number of argument annotations does not match the number of function arguments"); /* Dispatch code which converts function arguments and performs the actual function call */ @@ -183,28 +238,36 @@ protected: return result; }; + rec->nargs_pos = cast_in::args_pos >= 0 + ? static_cast(cast_in::args_pos) + : sizeof...(Args) - cast_in::has_kwargs; // Will get reduced more if we have a kw_only + rec->has_args = cast_in::args_pos >= 0; + rec->has_kwargs = cast_in::has_kwargs; + /* Process any user-provided function attributes */ process_attributes::init(extra..., rec); { constexpr bool has_kw_only_args = any_of...>::value, has_pos_only_args = any_of...>::value, - has_args = any_of...>::value, has_arg_annotations = any_of...>::value; static_assert(has_arg_annotations || !has_kw_only_args, "py::kw_only requires the use of argument annotations"); static_assert(has_arg_annotations || !has_pos_only_args, "py::pos_only requires the use of argument annotations (for docstrings and aligning the annotations to the argument)"); - static_assert(!(has_args && has_kw_only_args), "py::kw_only cannot be combined with a py::args argument"); + + static_assert(constexpr_sum(is_kw_only::value...) <= 1, "py::kw_only may be specified only once"); + static_assert(constexpr_sum(is_pos_only::value...) <= 1, "py::pos_only may be specified only once"); + constexpr auto kw_only_pos = constexpr_first(); + constexpr auto pos_only_pos = constexpr_first(); + static_assert(!(has_kw_only_args && has_pos_only_args) || pos_only_pos < kw_only_pos, "py::pos_only must come before py::kw_only"); } /* Generate a readable signature describing the function's arguments and return value types */ - static constexpr auto signature = _("(") + cast_in::arg_names + _(") -> ") + cast_out::name; + static constexpr auto signature = const_name("(") + cast_in::arg_names + const_name(") -> ") + cast_out::name; PYBIND11_DESCR_CONSTEXPR auto types = decltype(signature)::types(); /* Register the function with Python from generic (non-templated) code */ - initialize_generic(rec, signature.text, types.data(), sizeof...(Args)); - - if (cast_in::has_args) rec->has_args = true; - if (cast_in::has_kwargs) rec->has_kwargs = true; + // Pass on the ownership over the `unique_rec` to `initialize_generic`. `rec` stays valid. + initialize_generic(std::move(unique_rec), signature.text, types.data(), sizeof...(Args)); /* Stash some additional information used by an important optimization in 'functional.h' */ using FunctionType = Return (*)(Args...); @@ -217,27 +280,59 @@ protected: } } + // Utility class that keeps track of all duplicated strings, and cleans them up in its destructor, + // unless they are released. Basically a RAII-solution to deal with exceptions along the way. + class strdup_guard { + public: + ~strdup_guard() { + for (auto s : strings) + std::free(s); + } + char *operator()(const char *s) { + auto t = PYBIND11_COMPAT_STRDUP(s); + strings.push_back(t); + return t; + } + void release() { + strings.clear(); + } + private: + std::vector strings; + }; + /// Register a function call with Python (generic non-templated code goes here) - void initialize_generic(detail::function_record *rec, const char *text, + void initialize_generic(unique_function_record &&unique_rec, const char *text, const std::type_info *const *types, size_t args) { + // Do NOT receive `unique_rec` by value. If this function fails to move out the unique_ptr, + // we do not want this to destuct the pointer. `initialize` (the caller) still relies on the + // pointee being alive after this call. Only move out if a `capsule` is going to keep it alive. + auto rec = unique_rec.get(); + + // Keep track of strdup'ed strings, and clean them up as long as the function's capsule + // has not taken ownership yet (when `unique_rec.release()` is called). + // Note: This cannot easily be fixed by a `unique_ptr` with custom deleter, because the strings + // are only referenced before strdup'ing. So only *after* the following block could `destruct` + // safely be called, but even then, `repr` could still throw in the middle of copying all strings. + strdup_guard guarded_strdup; /* Create copies of all referenced C-style strings */ - rec->name = strdup(rec->name ? rec->name : ""); - if (rec->doc) rec->doc = strdup(rec->doc); + rec->name = guarded_strdup(rec->name ? rec->name : ""); + if (rec->doc) rec->doc = guarded_strdup(rec->doc); for (auto &a: rec->args) { if (a.name) - a.name = strdup(a.name); + a.name = guarded_strdup(a.name); if (a.descr) - a.descr = strdup(a.descr); + a.descr = guarded_strdup(a.descr); else if (a.value) - a.descr = strdup(repr(a.value).cast().c_str()); + a.descr = guarded_strdup(repr(a.value).cast().c_str()); } - rec->is_constructor = !strcmp(rec->name, "__init__") || !strcmp(rec->name, "__setstate__"); + rec->is_constructor = (std::strcmp(rec->name, "__init__") == 0) + || (std::strcmp(rec->name, "__setstate__") == 0); #if !defined(NDEBUG) && !defined(PYBIND11_DISABLE_NEW_STYLE_INIT_WARNING) if (rec->is_constructor && !rec->is_new_style_constructor) { - const auto class_name = std::string(((PyTypeObject *) rec->scope.ptr())->tp_name); + const auto class_name = detail::get_fully_qualified_tp_name((PyTypeObject *) rec->scope.ptr()); const auto func_name = std::string(rec->name); PyErr_WarnEx( PyExc_FutureWarning, @@ -252,16 +347,18 @@ protected: /* Generate a proper function signature */ std::string signature; size_t type_index = 0, arg_index = 0; + bool is_starred = false; for (auto *pc = text; *pc != '\0'; ++pc) { const auto c = *pc; if (c == '{') { // Write arg name for everything except *args and **kwargs. - if (*(pc + 1) == '*') + is_starred = *(pc + 1) == '*'; + if (is_starred) continue; // Separator for keyword-only arguments, placed before the kw - // arguments start - if (rec->nargs_kw_only > 0 && arg_index + rec->nargs_kw_only == args) + // arguments start (unless we are already putting an *args) + if (!rec->has_args && arg_index == rec->nargs_pos) signature += "*, "; if (arg_index < rec->args.size() && rec->args[arg_index].name) { signature += rec->args[arg_index].name; @@ -273,7 +370,7 @@ protected: signature += ": "; } else if (c == '}') { // Write default value if available. - if (arg_index < rec->args.size() && rec->args[arg_index].descr) { + if (!is_starred && arg_index < rec->args.size() && rec->args[arg_index].descr) { signature += " = "; signature += rec->args[arg_index].descr; } @@ -281,7 +378,8 @@ protected: // argument, rather than before like * if (rec->nargs_pos_only > 0 && (arg_index + 1) == rec->nargs_pos_only) signature += ", /"; - arg_index++; + if (!is_starred) + arg_index++; } else if (c == '%') { const std::type_info *t = types[type_index++]; if (!t) @@ -307,19 +405,19 @@ protected: } } - if (arg_index != args || types[type_index] != nullptr) + if (arg_index != args - rec->has_args - rec->has_kwargs || types[type_index] != nullptr) pybind11_fail("Internal error while parsing type signature (2)"); #if PY_MAJOR_VERSION < 3 - if (strcmp(rec->name, "__next__") == 0) { + if (std::strcmp(rec->name, "__next__") == 0) { std::free(rec->name); - rec->name = strdup("next"); - } else if (strcmp(rec->name, "__bool__") == 0) { + rec->name = guarded_strdup("next"); + } else if (std::strcmp(rec->name, "__bool__") == 0) { std::free(rec->name); - rec->name = strdup("__nonzero__"); + rec->name = guarded_strdup("__nonzero__"); } #endif - rec->signature = strdup(signature.c_str()); + rec->signature = guarded_strdup(signature.c_str()); rec->args.shrink_to_fit(); rec->nargs = (std::uint16_t) args; @@ -329,7 +427,8 @@ protected: detail::function_record *chain = nullptr, *chain_start = rec; if (rec->sibling) { if (PyCFunction_Check(rec->sibling.ptr())) { - auto rec_capsule = reinterpret_borrow(PyCFunction_GET_SELF(rec->sibling.ptr())); + auto *self = PyCFunction_GET_SELF(rec->sibling.ptr()); + capsule rec_capsule = isinstance(self) ? reinterpret_borrow(self) : capsule(self); chain = (detail::function_record *) rec_capsule; /* Never append a method to an overload chain of a parent class; instead, hide the parent's overloads in this case */ @@ -347,12 +446,14 @@ protected: rec->def = new PyMethodDef(); std::memset(rec->def, 0, sizeof(PyMethodDef)); rec->def->ml_name = rec->name; - rec->def->ml_meth = reinterpret_cast(reinterpret_cast(*dispatcher)); + rec->def->ml_meth + = reinterpret_cast(reinterpret_cast(dispatcher)); rec->def->ml_flags = METH_VARARGS | METH_KEYWORDS; - capsule rec_capsule(rec, [](void *ptr) { + capsule rec_capsule(unique_rec.release(), [](void *ptr) { destruct((detail::function_record *) ptr); }); + guarded_strdup.release(); object scope_module; if (rec->scope) { @@ -367,10 +468,9 @@ protected: if (!m_ptr) pybind11_fail("cpp_function::cpp_function(): Could not allocate function object"); } else { - /* Append at the end of the overload chain */ + /* Append at the beginning or end of the overload chain */ m_ptr = rec->sibling.ptr(); inc_ref(); - chain_start = chain; if (chain->is_method != rec->is_method) pybind11_fail("overloading a method with both static and instance methods is not supported; " #if defined(NDEBUG) @@ -380,9 +480,24 @@ protected: std::string(pybind11::str(rec->scope.attr("__name__"))) + "." + std::string(rec->name) + signature #endif ); - while (chain->next) - chain = chain->next; - chain->next = rec; + + if (rec->prepend) { + // Beginning of chain; we need to replace the capsule's current head-of-the-chain + // pointer with this one, then make this one point to the previous head of the + // chain. + chain_start = rec; + rec->next = chain; + auto rec_capsule = reinterpret_borrow(((PyCFunctionObject *) m_ptr)->m_self); + rec_capsule.set_pointer(unique_rec.release()); + guarded_strdup.release(); + } else { + // Or end of chain (normal behavior) + chain_start = chain; + while (chain->next) + chain = chain->next; + chain->next = unique_rec.release(); + guarded_strdup.release(); + } } std::string signatures; @@ -406,7 +521,7 @@ protected: signatures += it->signature; signatures += "\n"; } - if (it->doc && strlen(it->doc) > 0 && options::show_user_defined_docstrings()) { + if (it->doc && it->doc[0] != '\0' && options::show_user_defined_docstrings()) { // If we're appending another docstring, and aren't printing function signatures, we // need to append a newline first: if (!options::show_function_signatures()) { @@ -421,9 +536,10 @@ protected: /* Install docstring */ auto *func = (PyCFunctionObject *) m_ptr; - if (func->m_ml->ml_doc) - std::free(const_cast(func->m_ml->ml_doc)); - func->m_ml->ml_doc = strdup(signatures.c_str()); + std::free(const_cast(func->m_ml->ml_doc)); + // Install docstring if it's non-empty (when at least one option is enabled) + func->m_ml->ml_doc + = signatures.empty() ? nullptr : PYBIND11_COMPAT_STRDUP(signatures.c_str()); if (rec->is_method) { m_ptr = PYBIND11_INSTANCE_METHOD_NEW(m_ptr, rec->scope.ptr()); @@ -434,28 +550,49 @@ protected: } /// When a cpp_function is GCed, release any memory allocated by pybind11 - static void destruct(detail::function_record *rec) { + static void destruct(detail::function_record *rec, bool free_strings = true) { + // If on Python 3.9, check the interpreter "MICRO" (patch) version. + // If this is running on 3.9.0, we have to work around a bug. + #if !defined(PYPY_VERSION) && PY_MAJOR_VERSION == 3 && PY_MINOR_VERSION == 9 + static bool is_zero = Py_GetVersion()[4] == '0'; + #endif + while (rec) { detail::function_record *next = rec->next; if (rec->free_data) rec->free_data(rec); - std::free((char *) rec->name); - std::free((char *) rec->doc); - std::free((char *) rec->signature); - for (auto &arg: rec->args) { - std::free(const_cast(arg.name)); - std::free(const_cast(arg.descr)); - arg.value.dec_ref(); + // During initialization, these strings might not have been copied yet, + // so they cannot be freed. Once the function has been created, they can. + // Check `make_function_record` for more details. + if (free_strings) { + std::free((char *) rec->name); + std::free((char *) rec->doc); + std::free((char *) rec->signature); + for (auto &arg: rec->args) { + std::free(const_cast(arg.name)); + std::free(const_cast(arg.descr)); + } } + for (auto &arg: rec->args) + arg.value.dec_ref(); if (rec->def) { std::free(const_cast(rec->def->ml_doc)); - delete rec->def; + // Python 3.9.0 decref's these in the wrong order; rec->def + // If loaded on 3.9.0, let these leak (use Python 3.9.1 at runtime to fix) + // See https://github.com/python/cpython/pull/22670 + #if !defined(PYPY_VERSION) && PY_MAJOR_VERSION == 3 && PY_MINOR_VERSION == 9 + if (!is_zero) + delete rec->def; + #else + delete rec->def; + #endif } delete rec; rec = next; } } + /// Main dispatch logic for calls to functions bound using pybind11 static PyObject *dispatcher(PyObject *self, PyObject *args_in, PyObject *kwargs_in) { using namespace detail; @@ -472,15 +609,15 @@ protected: auto self_value_and_holder = value_and_holder(); if (overloads->is_constructor) { - const auto tinfo = get_type_info((PyTypeObject *) overloads->scope.ptr()); - const auto pi = reinterpret_cast(parent.ptr()); - self_value_and_holder = pi->get_value_and_holder(tinfo, false); - - if (!self_value_and_holder.type || !self_value_and_holder.inst) { - PyErr_SetString(PyExc_TypeError, "__init__(self, ...) called with invalid `self` argument"); + if (!parent || !PyObject_TypeCheck(parent.ptr(), (PyTypeObject *) overloads->scope.ptr())) { + PyErr_SetString(PyExc_TypeError, "__init__(self, ...) called with invalid or missing `self` argument"); return nullptr; } + const auto tinfo = get_type_info((PyTypeObject *) overloads->scope.ptr()); + const auto pi = reinterpret_cast(parent.ptr()); + self_value_and_holder = pi->get_value_and_holder(tinfo, true); + // If this value is already registered it must mean __init__ is invoked multiple times; // we really can't support that in C++, so just ignore the second __init__. if (self_value_and_holder.instance_registered()) @@ -504,7 +641,7 @@ protected: named positional arguments weren't *also* specified via kwarg. 2. If we weren't given enough, try to make up the omitted ones by checking whether they were provided by a kwarg matching the `py::arg("name")` name. If - so, use it (and remove it from kwargs; if not, see if the function binding + so, use it (and remove it from kwargs); if not, see if the function binding provided a default that we can use. 3. Ensure that either all keyword arguments were "consumed", or that the function takes a kwargs argument to accept unconsumed kwargs. @@ -522,7 +659,7 @@ protected: size_t num_args = func.nargs; // Number of positional arguments that we need if (func.has_args) --num_args; // (but don't count py::args if (func.has_kwargs) --num_args; // or py::kwargs) - size_t pos_args = num_args - func.nargs_kw_only; + size_t pos_args = func.nargs_pos; if (!func.has_args && n_args_in > pos_args) continue; // Too many positional arguments for this overload @@ -552,7 +689,7 @@ protected: bool bad_arg = false; for (; args_copied < args_to_copy; ++args_copied) { const argument_record *arg_rec = args_copied < func.args.size() ? &func.args[args_copied] : nullptr; - if (kwargs_in && arg_rec && arg_rec->name && PyDict_GetItemString(kwargs_in, arg_rec->name)) { + if (kwargs_in && arg_rec && arg_rec->name && dict_getitemstring(kwargs_in, arg_rec->name)) { bad_arg = true; break; } @@ -568,21 +705,25 @@ protected: if (bad_arg) continue; // Maybe it was meant for another overload (issue #688) + // Keep track of how many position args we copied out in case we need to come back + // to copy the rest into a py::args argument. + size_t positional_args_copied = args_copied; + // We'll need to copy this if we steal some kwargs for defaults dict kwargs = reinterpret_borrow(kwargs_in); // 1.5. Fill in any missing pos_only args from defaults if they exist if (args_copied < func.nargs_pos_only) { for (; args_copied < func.nargs_pos_only; ++args_copied) { - const auto &arg = func.args[args_copied]; + const auto &arg_rec = func.args[args_copied]; handle value; - if (arg.value) { - value = arg.value; + if (arg_rec.value) { + value = arg_rec.value; } if (value) { call.args.push_back(value); - call.args_convert.push_back(arg.convert); + call.args_convert.push_back(arg_rec.convert); } else break; } @@ -596,11 +737,11 @@ protected: bool copied_kwargs = false; for (; args_copied < num_args; ++args_copied) { - const auto &arg = func.args[args_copied]; + const auto &arg_rec = func.args[args_copied]; handle value; - if (kwargs_in && arg.name) - value = PyDict_GetItemString(kwargs.ptr(), arg.name); + if (kwargs_in && arg_rec.name) + value = dict_getitemstring(kwargs.ptr(), arg_rec.name); if (value) { // Consume a kwargs value @@ -608,14 +749,24 @@ protected: kwargs = reinterpret_steal(PyDict_Copy(kwargs.ptr())); copied_kwargs = true; } - PyDict_DelItemString(kwargs.ptr(), arg.name); - } else if (arg.value) { - value = arg.value; + if (PyDict_DelItemString(kwargs.ptr(), arg_rec.name) == -1) { + throw error_already_set(); + } + } else if (arg_rec.value) { + value = arg_rec.value; + } + + if (!arg_rec.none && value.is_none()) { + break; } if (value) { + // If we're at the py::args index then first insert a stub for it to be replaced later + if (func.has_args && call.args.size() == func.nargs_pos) + call.args.push_back(none()); + call.args.push_back(value); - call.args_convert.push_back(arg.convert); + call.args_convert.push_back(arg_rec.convert); } else break; @@ -636,16 +787,19 @@ protected: // We didn't copy out any position arguments from the args_in tuple, so we // can reuse it directly without copying: extra_args = reinterpret_borrow(args_in); - } else if (args_copied >= n_args_in) { + } else if (positional_args_copied >= n_args_in) { extra_args = tuple(0); } else { - size_t args_size = n_args_in - args_copied; + size_t args_size = n_args_in - positional_args_copied; extra_args = tuple(args_size); for (size_t i = 0; i < args_size; ++i) { - extra_args[i] = PyTuple_GET_ITEM(args_in, args_copied + i); + extra_args[i] = PyTuple_GET_ITEM(args_in, positional_args_copied + i); } } - call.args.push_back(extra_args); + if (call.args.size() <= func.nargs_pos) + call.args.push_back(extra_args); + else + call.args[func.nargs_pos] = extra_args; call.args_convert.push_back(false); call.args_ref = std::move(extra_args); } @@ -724,14 +878,18 @@ protected: } catch (error_already_set &e) { e.restore(); return nullptr; -#if defined(__GNUG__) && !defined(__clang__) +#ifdef __GLIBCXX__ } catch ( abi::__forced_unwind& ) { throw; #endif } catch (...) { /* When an exception is caught, give each registered exception - translator a chance to translate it to a Python exception - in reverse order of registration. + translator a chance to translate it to a Python exception. First + all module-local translators will be tried in reverse order of + registration. If none of the module-locale translators handle + the exception (or there are no module-locale translators) then + the global translators will be tried, also in reverse order of + registration. A translator may choose to do one of the following: @@ -740,17 +898,15 @@ protected: - do nothing and let the exception fall through to the next translator, or - delegate translation to the next translator by throwing a new type of exception. */ - auto last_exception = std::current_exception(); - auto ®istered_exception_translators = get_internals().registered_exception_translators; - for (auto& translator : registered_exception_translators) { - try { - translator(last_exception); - } catch (...) { - last_exception = std::current_exception(); - continue; - } + auto &local_exception_translators = get_local_internals().registered_exception_translators; + if (detail::apply_exception_translators(local_exception_translators)) { return nullptr; } + auto &exception_translators = get_internals().registered_exception_translators; + if (detail::apply_exception_translators(exception_translators)) { + return nullptr; + } + PyErr_SetString(PyExc_SystemError, "Exception escaped from default exception translator!"); return nullptr; } @@ -832,47 +988,54 @@ protected: } append_note_if_missing_header_is_suspected(msg); +#if PY_VERSION_HEX >= 0x03030000 + // Attach additional error info to the exception if supported + if (PyErr_Occurred()) { + // #HelpAppreciated: unit test coverage for this branch. + raise_from(PyExc_TypeError, msg.c_str()); + return nullptr; + } +#endif PyErr_SetString(PyExc_TypeError, msg.c_str()); return nullptr; - } else if (!result) { + } + if (!result) { std::string msg = "Unable to convert function return value to a " "Python type! The signature was\n\t"; msg += it->signature; append_note_if_missing_header_is_suspected(msg); +#if PY_VERSION_HEX >= 0x03030000 + // Attach additional error info to the exception if supported + if (PyErr_Occurred()) { + raise_from(PyExc_TypeError, msg.c_str()); + return nullptr; + } +#endif PyErr_SetString(PyExc_TypeError, msg.c_str()); return nullptr; - } else { - if (overloads->is_constructor && !self_value_and_holder.holder_constructed()) { - auto *pi = reinterpret_cast(parent.ptr()); - self_value_and_holder.type->init_instance(pi, nullptr); - } - return result.ptr(); } + if (overloads->is_constructor && !self_value_and_holder.holder_constructed()) { + auto *pi = reinterpret_cast(parent.ptr()); + self_value_and_holder.type->init_instance(pi, nullptr); + } + return result.ptr(); } }; + /// Wrapper for Python extension modules class module_ : public object { public: PYBIND11_OBJECT_DEFAULT(module_, object, PyModule_Check) /// Create a new top-level Python module with the given name and docstring + PYBIND11_DEPRECATED("Use PYBIND11_MODULE or module_::create_extension_module instead") explicit module_(const char *name, const char *doc = nullptr) { - if (!options::show_user_defined_docstrings()) doc = nullptr; #if PY_MAJOR_VERSION >= 3 - auto *def = new PyModuleDef(); - std::memset(def, 0, sizeof(PyModuleDef)); - def->m_name = name; - def->m_doc = doc; - def->m_size = -1; - Py_INCREF(def); - m_ptr = PyModule_Create(def); + *this = create_extension_module(name, doc, new PyModuleDef()); #else - m_ptr = Py_InitModule3(name, nullptr, doc); + *this = create_extension_module(name, doc, nullptr); #endif - if (m_ptr == nullptr) - pybind11_fail("Internal error in module_::module_()"); - inc_ref(); } /** \rst @@ -896,9 +1059,9 @@ public: .. code-block:: cpp - py::module m("example", "pybind11 example plugin"); - py::module m2 = m.def_submodule("sub", "A submodule of 'example'"); - py::module m3 = m2.def_submodule("subsub", "A submodule of 'example.sub'"); + py::module_ m("example", "pybind11 example plugin"); + py::module_ m2 = m.def_submodule("sub", "A submodule of 'example'"); + py::module_ m3 = m2.def_submodule("subsub", "A submodule of 'example.sub'"); \endrst */ module_ def_submodule(const char *name, const char *doc = nullptr) { std::string full_name = std::string(PyModule_GetName(m_ptr)) @@ -926,11 +1089,13 @@ public: *this = reinterpret_steal(obj); } - // Adds an object to the module using the given name. Throws if an object with the given name - // already exists. - // - // overwrite should almost always be false: attempting to overwrite objects that pybind11 has - // established will, in most cases, break things. + /** \rst + Adds an object to the module using the given name. Throws if an object with the given name + already exists. + + ``overwrite`` should almost always be false: attempting to overwrite objects that pybind11 has + established will, in most cases, break things. + \endrst */ PYBIND11_NOINLINE void add_object(const char *name, handle obj, bool overwrite = false) { if (!overwrite && hasattr(*this, name)) pybind11_fail("Error during initialization: multiple incompatible definitions with name \"" + @@ -938,8 +1103,53 @@ public: PyModule_AddObject(ptr(), name, obj.inc_ref().ptr() /* steals a reference */); } + +#if PY_MAJOR_VERSION >= 3 + using module_def = PyModuleDef; +#else + struct module_def {}; +#endif + + /** \rst + Create a new top-level module that can be used as the main module of a C extension. + + For Python 3, ``def`` should point to a statically allocated module_def. + For Python 2, ``def`` can be a nullptr and is completely ignored. + \endrst */ + static module_ create_extension_module(const char *name, const char *doc, module_def *def) { +#if PY_MAJOR_VERSION >= 3 + // module_def is PyModuleDef + def = new (def) PyModuleDef { // Placement new (not an allocation). + /* m_base */ PyModuleDef_HEAD_INIT, + /* m_name */ name, + /* m_doc */ options::show_user_defined_docstrings() ? doc : nullptr, + /* m_size */ -1, + /* m_methods */ nullptr, + /* m_slots */ nullptr, + /* m_traverse */ nullptr, + /* m_clear */ nullptr, + /* m_free */ nullptr + }; + auto m = PyModule_Create(def); +#else + // Ignore module_def *def; only necessary for Python 3 + (void) def; + auto m = Py_InitModule3(name, nullptr, options::show_user_defined_docstrings() ? doc : nullptr); +#endif + if (m == nullptr) { + if (PyErr_Occurred()) + throw error_already_set(); + pybind11_fail("Internal error in module_::create_extension_module()"); + } + // TODO: Should be reinterpret_steal for Python 3, but Python also steals it again when returned from PyInit_... + // For Python 2, reinterpret_borrow is correct. + return reinterpret_borrow(m); + } }; +// When inside a namespace (or anywhere as long as it's not the first item on a line), +// C++20 allows "module" to be used. This is provided for backward compatibility, and for +// simplicity, if someone wants to use py::module for example, that is perfectly safe. using module = module_; /// \ingroup python_builtins @@ -947,22 +1157,31 @@ using module = module_; /// or ``__main__.__dict__`` if there is no frame (usually when the interpreter is embedded). inline dict globals() { PyObject *p = PyEval_GetGlobals(); - return reinterpret_borrow(p ? p : module::import("__main__").attr("__dict__").ptr()); + return reinterpret_borrow(p ? p : module_::import("__main__").attr("__dict__").ptr()); } +#if PY_VERSION_HEX >= 0x03030000 +template ()>> +PYBIND11_DEPRECATED("make_simple_namespace should be replaced with py::module_::import(\"types\").attr(\"SimpleNamespace\") ") +object make_simple_namespace(Args&&... args_) { + return module_::import("types").attr("SimpleNamespace")(std::forward(args_)...); +} +#endif + PYBIND11_NAMESPACE_BEGIN(detail) /// Generic support for creating new Python heap types class generic_type : public object { - template friend class class_; public: PYBIND11_OBJECT_DEFAULT(generic_type, object, PyType_Check) protected: void initialize(const type_record &rec) { - if (rec.scope && hasattr(rec.scope, rec.name)) + if (rec.scope && hasattr(rec.scope, "__dict__") && rec.scope.attr("__dict__").contains(rec.name)) pybind11_fail("generic_type: cannot initialize type \"" + std::string(rec.name) + "\": an object with that name is already defined"); - if (rec.module_local ? get_local_type_info(*rec.type) : get_global_type_info(*rec.type)) + if ((rec.module_local ? get_local_type_info(*rec.type) : get_global_type_info(*rec.type)) + != nullptr) pybind11_fail("generic_type: type \"" + std::string(rec.name) + "\" is already registered!"); @@ -987,7 +1206,7 @@ protected: auto tindex = std::type_index(*rec.type); tinfo->direct_conversions = &internals.direct_conversions[tindex]; if (rec.module_local) - registered_local_types_cpp()[tindex] = tinfo; + get_local_internals().registered_types_cpp[tindex] = tinfo; else internals.registered_types_cpp[tindex] = tinfo; internals.registered_types_py[(PyTypeObject *) m_ptr] = { tinfo }; @@ -997,8 +1216,12 @@ protected: tinfo->simple_ancestors = false; } else if (rec.bases.size() == 1) { - auto parent_tinfo = get_type_info((PyTypeObject *) rec.bases[0].ptr()); - tinfo->simple_ancestors = parent_tinfo->simple_ancestors; + auto *parent_tinfo = get_type_info((PyTypeObject *) rec.bases[0].ptr()); + assert(parent_tinfo != nullptr); + bool parent_simple_ancestors = parent_tinfo->simple_ancestors; + tinfo->simple_ancestors = parent_simple_ancestors; + // The parent can no longer be a simple type if it has MI and has a child + parent_tinfo->simple_type = parent_tinfo->simple_type && parent_simple_ancestors; } if (rec.module_local) { @@ -1028,7 +1251,7 @@ protected: if (!type->ht_type.tp_as_buffer) pybind11_fail( "To be able to register buffer protocol support for the type '" + - std::string(tinfo->type->tp_name) + + get_fully_qualified_tp_name(tinfo->type) + "' the associated class<>(..) invocation must " "include the pybind11::buffer_protocol() annotation!"); @@ -1040,8 +1263,9 @@ protected: void def_property_static_impl(const char *name, handle fget, handle fset, detail::function_record *rec_func) { - const auto is_static = rec_func && !(rec_func->is_method && rec_func->scope); - const auto has_doc = rec_func && rec_func->doc && pybind11::options::show_user_defined_docstrings(); + const auto is_static = (rec_func != nullptr) && !(rec_func->is_method && rec_func->scope); + const auto has_doc = (rec_func != nullptr) && (rec_func->doc != nullptr) + && pybind11::options::show_user_defined_docstrings(); auto property = handle((PyObject *) (is_static ? get_internals().static_property_type : &PyProperty_Type)); attr(name) = property(fget.ptr() ? fget : none(), @@ -1090,8 +1314,8 @@ inline void call_operator_delete(void *p, size_t s, size_t a) { inline void add_class_method(object& cls, const char *name_, const cpp_function &cf) { cls.attr(cf.name()) = cf; - if (strcmp(name_, "__eq__") == 0 && !cls.attr("__dict__").contains("__hash__")) { - cls.attr("__hash__") = none(); + if (std::strcmp(name_, "__eq__") == 0 && !cls.attr("__dict__").contains("__hash__")) { + cls.attr("__hash__") = none(); } } @@ -1173,7 +1397,7 @@ public: generic_type::initialize(record); if (has_alias) { - auto &instances = record.module_local ? registered_local_types_cpp() : get_internals().registered_types_cpp; + auto &instances = record.module_local ? get_local_internals().registered_types_cpp : get_internals().registered_types_cpp; instances[std::type_index(typeid(type_alias))] = instances[std::type_index(typeid(type))]; } } @@ -1220,12 +1444,14 @@ public: template class_ &def(const detail::initimpl::constructor &init, const Extra&... extra) { + PYBIND11_WORKAROUND_INCORRECT_MSVC_C4100(init); init.execute(*this, extra...); return *this; } template class_ &def(const detail::initimpl::alias_constructor &init, const Extra&... extra) { + PYBIND11_WORKAROUND_INCORRECT_MSVC_C4100(init); init.execute(*this, extra...); return *this; } @@ -1242,7 +1468,8 @@ public: return *this; } - template class_& def_buffer(Func &&func) { + template + class_& def_buffer(Func &&func) { struct capture { Func func; }; auto *ptr = new capture { std::forward(func) }; install_buffer_funcs([](PyObject *obj, void *ptr) -> buffer_info* { @@ -1251,6 +1478,10 @@ public: return nullptr; return new buffer_info(((capture *) ptr)->func(caster)); }, ptr); + weakref(m_ptr, cpp_function([ptr](handle wr) { + delete ptr; + wr.dec_ref(); + })).release(); return *this; } @@ -1283,15 +1514,15 @@ public: template class_ &def_readwrite_static(const char *name, D *pm, const Extra& ...extra) { - cpp_function fget([pm](object) -> const D &{ return *pm; }, scope(*this)), - fset([pm](object, const D &value) { *pm = value; }, scope(*this)); + cpp_function fget([pm](const object &) -> const D & { return *pm; }, scope(*this)), + fset([pm](const object &, const D &value) { *pm = value; }, scope(*this)); def_property_static(name, fget, fset, return_value_policy::reference, extra...); return *this; } template class_ &def_readonly_static(const char *name, const D *pm, const Extra& ...extra) { - cpp_function fget([pm](object) -> const D &{ return *pm; }, scope(*this)); + cpp_function fget([pm](const object &) -> const D & { return *pm; }, scope(*this)); def_property_readonly_static(name, fget, return_value_policy::reference, extra...); return *this; } @@ -1355,16 +1586,16 @@ public: char *doc_prev = rec_fget->doc; /* 'extra' field may include a property-specific documentation string */ detail::process_attributes::init(extra..., rec_fget); if (rec_fget->doc && rec_fget->doc != doc_prev) { - free(doc_prev); - rec_fget->doc = strdup(rec_fget->doc); + std::free(doc_prev); + rec_fget->doc = PYBIND11_COMPAT_STRDUP(rec_fget->doc); } } if (rec_fset) { char *doc_prev = rec_fset->doc; detail::process_attributes::init(extra..., rec_fset); if (rec_fset->doc && rec_fset->doc != doc_prev) { - free(doc_prev); - rec_fset->doc = strdup(rec_fset->doc); + std::free(doc_prev); + rec_fset->doc = PYBIND11_COMPAT_STRDUP(rec_fset->doc); } if (! rec_active) rec_active = rec_fset; } @@ -1377,14 +1608,13 @@ private: template static void init_holder(detail::instance *inst, detail::value_and_holder &v_h, const holder_type * /* unused */, const std::enable_shared_from_this * /* dummy */) { - try { - auto sh = std::dynamic_pointer_cast( - v_h.value_ptr()->shared_from_this()); - if (sh) { - new (std::addressof(v_h.holder())) holder_type(std::move(sh)); - v_h.set_holder_constructed(); - } - } catch (const std::bad_weak_ptr &) {} + + auto sh = std::dynamic_pointer_cast( + detail::try_get_shared_from_this(v_h.value_ptr())); + if (sh) { + new (std::addressof(v_h.holder())) holder_type(std::move(sh)); + v_h.set_holder_constructed(); + } if (!v_h.holder_constructed() && inst->owned) { new (std::addressof(v_h.holder())) holder_type(v_h.value_ptr()); @@ -1481,8 +1711,18 @@ detail::initimpl::pickle_factory pickle(GetState &&g, SetSta } PYBIND11_NAMESPACE_BEGIN(detail) + +inline str enum_name(handle arg) { + dict entries = arg.get_type().attr("__entries"); + for (auto kv : entries) { + if (handle(kv.second[int_(0)]).equal(arg)) + return pybind11::str(kv.first); + } + return "???"; +} + struct enum_base { - enum_base(handle base, handle parent) : m_base(base), m_parent(parent) { } + enum_base(const handle &base, const handle &parent) : m_base(base), m_parent(parent) { } PYBIND11_NOINLINE void init(bool is_arithmetic, bool is_convertible) { m_base.attr("__entries") = dict(); @@ -1490,29 +1730,22 @@ struct enum_base { auto static_property = handle((PyObject *) get_internals().static_property_type); m_base.attr("__repr__") = cpp_function( - [](handle arg) -> str { + [](const object &arg) -> str { handle type = type::handle_of(arg); object type_name = type.attr("__name__"); - dict entries = type.attr("__entries"); - for (const auto &kv : entries) { - object other = kv.second[int_(0)]; - if (other.equal(arg)) - return pybind11::str("{}.{}").format(type_name, kv.first); - } - return pybind11::str("{}.???").format(type_name); - }, name("__repr__"), is_method(m_base) - ); + return pybind11::str("<{}.{}: {}>").format(type_name, enum_name(arg), int_(arg)); + }, + name("__repr__"), + is_method(m_base)); - m_base.attr("name") = property(cpp_function( + m_base.attr("name") = property(cpp_function(&enum_name, name("name"), is_method(m_base))); + + m_base.attr("__str__") = cpp_function( [](handle arg) -> str { - dict entries = type::handle_of(arg).attr("__entries"); - for (const auto &kv : entries) { - if (handle(kv.second[int_(0)]).equal(arg)) - return pybind11::str(kv.first); - } - return "???"; + object type_name = type::handle_of(arg).attr("__name__"); + return pybind11::str("{}.{}").format(type_name, enum_name(arg)); }, name("name"), is_method(m_base) - )); + ); m_base.attr("__doc__") = static_property(cpp_function( [](handle arg) -> std::string { @@ -1521,7 +1754,7 @@ struct enum_base { if (((PyTypeObject *) arg.ptr())->tp_doc) docstring += std::string(((PyTypeObject *) arg.ptr())->tp_doc) + "\n\n"; docstring += "Members:"; - for (const auto &kv : entries) { + for (auto kv : entries) { auto key = std::string(pybind11::str(kv.first)); auto comment = kv.second[int_(1)]; docstring += "\n\n " + key; @@ -1535,36 +1768,42 @@ struct enum_base { m_base.attr("__members__") = static_property(cpp_function( [](handle arg) -> dict { dict entries = arg.attr("__entries"), m; - for (const auto &kv : entries) + for (auto kv : entries) m[kv.first] = kv.second[int_(0)]; return m; }, name("__members__")), none(), none(), "" ); - #define PYBIND11_ENUM_OP_STRICT(op, expr, strict_behavior) \ - m_base.attr(op) = cpp_function( \ - [](object a, object b) { \ - if (!type::handle_of(a).is(type::handle_of(b))) \ - strict_behavior; \ - return expr; \ - }, \ - name(op), is_method(m_base)) +#define PYBIND11_ENUM_OP_STRICT(op, expr, strict_behavior) \ + m_base.attr(op) = cpp_function( \ + [](const object &a, const object &b) { \ + if (!type::handle_of(a).is(type::handle_of(b))) \ + strict_behavior; /* NOLINT(bugprone-macro-parentheses) */ \ + return expr; \ + }, \ + name(op), \ + is_method(m_base), \ + arg("other")) - #define PYBIND11_ENUM_OP_CONV(op, expr) \ - m_base.attr(op) = cpp_function( \ - [](object a_, object b_) { \ - int_ a(a_), b(b_); \ - return expr; \ - }, \ - name(op), is_method(m_base)) +#define PYBIND11_ENUM_OP_CONV(op, expr) \ + m_base.attr(op) = cpp_function( \ + [](const object &a_, const object &b_) { \ + int_ a(a_), b(b_); \ + return expr; \ + }, \ + name(op), \ + is_method(m_base), \ + arg("other")) - #define PYBIND11_ENUM_OP_CONV_LHS(op, expr) \ - m_base.attr(op) = cpp_function( \ - [](object a_, object b) { \ - int_ a(a_); \ - return expr; \ - }, \ - name(op), is_method(m_base)) +#define PYBIND11_ENUM_OP_CONV_LHS(op, expr) \ + m_base.attr(op) = cpp_function( \ + [](const object &a_, const object &b) { \ + int_ a(a_); \ + return expr; \ + }, \ + name(op), \ + is_method(m_base), \ + arg("other")) if (is_convertible) { PYBIND11_ENUM_OP_CONV_LHS("__eq__", !b.is_none() && a.equal(b)); @@ -1581,8 +1820,10 @@ struct enum_base { PYBIND11_ENUM_OP_CONV("__ror__", a | b); PYBIND11_ENUM_OP_CONV("__xor__", a ^ b); PYBIND11_ENUM_OP_CONV("__rxor__", a ^ b); - m_base.attr("__invert__") = cpp_function( - [](object arg) { return ~(int_(arg)); }, name("__invert__"), is_method(m_base)); + m_base.attr("__invert__") + = cpp_function([](const object &arg) { return ~(int_(arg)); }, + name("__invert__"), + is_method(m_base)); } } else { PYBIND11_ENUM_OP_STRICT("__eq__", int_(a).equal(int_(b)), return false); @@ -1603,10 +1844,10 @@ struct enum_base { #undef PYBIND11_ENUM_OP_STRICT m_base.attr("__getstate__") = cpp_function( - [](object arg) { return int_(arg); }, name("__getstate__"), is_method(m_base)); + [](const object &arg) { return int_(arg); }, name("__getstate__"), is_method(m_base)); m_base.attr("__hash__") = cpp_function( - [](object arg) { return int_(arg); }, name("__hash__"), is_method(m_base)); + [](const object &arg) { return int_(arg); }, name("__hash__"), is_method(m_base)); } PYBIND11_NOINLINE void value(char const* name_, object value, const char *doc = nullptr) { @@ -1623,7 +1864,7 @@ struct enum_base { PYBIND11_NOINLINE void export_values() { dict entries = m_base.attr("__entries"); - for (const auto &kv : entries) + for (auto kv : entries) m_parent.attr(kv.first) = kv.second[int_(0)]; } @@ -1631,6 +1872,19 @@ struct enum_base { handle m_parent; }; +template struct equivalent_integer {}; +template <> struct equivalent_integer { using type = int8_t; }; +template <> struct equivalent_integer { using type = uint8_t; }; +template <> struct equivalent_integer { using type = int16_t; }; +template <> struct equivalent_integer { using type = uint16_t; }; +template <> struct equivalent_integer { using type = int32_t; }; +template <> struct equivalent_integer { using type = uint32_t; }; +template <> struct equivalent_integer { using type = int64_t; }; +template <> struct equivalent_integer { using type = uint64_t; }; + +template +using equivalent_integer_t = typename equivalent_integer::value, sizeof(IntLike)>::type; + PYBIND11_NAMESPACE_END(detail) /// Binds C++ enumerations and enumeration classes to Python @@ -1641,16 +1895,21 @@ public: using Base::attr; using Base::def_property_readonly; using Base::def_property_readonly_static; - using Scalar = typename std::underlying_type::type; + using Underlying = typename std::underlying_type::type; + // Scalar is the integer representation of underlying type + using Scalar = detail::conditional_t, std::is_same + >::value, detail::equivalent_integer_t, Underlying>; template enum_(const handle &scope, const char *name, const Extra&... extra) : class_(scope, name, extra...), m_base(*this, scope) { constexpr bool is_arithmetic = detail::any_of...>::value; - constexpr bool is_convertible = std::is_convertible::value; + constexpr bool is_convertible = std::is_convertible::value; m_base.init(is_arithmetic, is_convertible); - def(init([](Scalar i) { return static_cast(i); })); + def(init([](Scalar i) { return static_cast(i); }), arg("value")); + def_property_readonly("value", [](Type value) { return (Scalar) value; }); def("__int__", [](Type value) { return (Scalar) value; }); #if PY_MAJOR_VERSION < 3 def("__long__", [](Type value) { return (Scalar) value; }); @@ -1664,7 +1923,7 @@ public: detail::initimpl::setstate(v_h, static_cast(arg), Py_TYPE(v_h.inst) != v_h.type->type); }, detail::is_new_style_constructor(), - pybind11::name("__setstate__"), is_method(*this)); + pybind11::name("__setstate__"), is_method(*this), arg("state")); } /// Export enumeration entries into the parent scope @@ -1686,7 +1945,7 @@ private: PYBIND11_NAMESPACE_BEGIN(detail) -inline void keep_alive_impl(handle nurse, handle patient) { +PYBIND11_NOINLINE void keep_alive_impl(handle nurse, handle patient) { if (!nurse || !patient) pybind11_fail("Could not activate keep_alive!"); @@ -1713,13 +1972,13 @@ inline void keep_alive_impl(handle nurse, handle patient) { } } -PYBIND11_NOINLINE inline void keep_alive_impl(size_t Nurse, size_t Patient, function_call &call, handle ret) { +PYBIND11_NOINLINE void keep_alive_impl(size_t Nurse, size_t Patient, function_call &call, handle ret) { auto get_arg = [&](size_t n) { if (n == 0) return ret; - else if (n == 1 && call.init_self) + if (n == 1 && call.init_self) return call.init_self; - else if (n <= call.args.size()) + if (n <= call.args.size()) return call.args[n - 1]; return handle(); }; @@ -1739,6 +1998,16 @@ inline std::pair all_t // gets destroyed: weakref((PyObject *) type, cpp_function([type](handle wr) { get_internals().registered_types_py.erase(type); + + // TODO consolidate the erasure code in pybind11_meta_dealloc() in class.h + auto &cache = get_internals().inactive_override_cache; + for (auto it = cache.begin(), last = cache.end(); it != last; ) { + if (it->first == reinterpret_cast(type)) + it = cache.erase(it); + else + ++it; + } + wr.dec_ref(); })).release(); } @@ -1746,23 +2015,79 @@ inline std::pair all_t return res; } -template +/* There are a large number of apparently unused template arguments because + * each combination requires a separate py::class_ registration. + */ +template struct iterator_state { Iterator it; Sentinel end; bool first_or_done; }; -PYBIND11_NAMESPACE_END(detail) +// Note: these helpers take the iterator by non-const reference because some +// iterators in the wild can't be dereferenced when const. The & after Iterator +// is required for MSVC < 16.9. SFINAE cannot be reused for result_type due to +// bugs in ICC, NVCC, and PGI compilers. See PR #3293. +template ())> +struct iterator_access { + using result_type = decltype(*std::declval()); + // NOLINTNEXTLINE(readability-const-return-type) // PR #3263 + result_type operator()(Iterator &it) const { + return *it; + } +}; -/// Makes a python iterator from a first and past-the-end C++ InputIterator. -template ()).first) > +class iterator_key_access { +private: + using pair_type = decltype(*std::declval()); + +public: + /* If either the pair itself or the element of the pair is a reference, we + * want to return a reference, otherwise a value. When the decltype + * expression is parenthesized it is based on the value category of the + * expression; otherwise it is the declared type of the pair member. + * The use of declval in the second branch rather than directly + * using *std::declval() is a workaround for nvcc + * (it's not used in the first branch because going via decltype and back + * through declval does not perfectly preserve references). + */ + using result_type = conditional_t< + std::is_reference())>::value, + decltype(((*std::declval()).first)), + decltype(std::declval().first) + >; + result_type operator()(Iterator &it) const { + return (*it).first; + } +}; + +template ()).second)> +class iterator_value_access { +private: + using pair_type = decltype(*std::declval()); + +public: + using result_type = conditional_t< + std::is_reference())>::value, + decltype(((*std::declval()).second)), + decltype(std::declval().second) + >; + result_type operator()(Iterator &it) const { + return (*it).second; + } +}; + +template ()), + typename ValueType, typename... Extra> -iterator make_iterator(Iterator first, Sentinel last, Extra &&... extra) { - typedef detail::iterator_state state; +iterator make_iterator_impl(Iterator first, Sentinel last, Extra &&... extra) { + using state = detail::iterator_state; + // TODO: state captures only the types of Extra, not the values if (!detail::get_type_info(typeid(state), false)) { class_(handle(), "iterator", pybind11::module_local()) @@ -1776,40 +2101,63 @@ iterator make_iterator(Iterator first, Sentinel last, Extra &&... extra) { s.first_or_done = true; throw stop_iteration(); } - return *s.it; + return Access()(s.it); + // NOLINTNEXTLINE(readability-const-return-type) // PR #3263 }, std::forward(extra)..., Policy); } return cast(state{first, last, true}); } -/// Makes an python iterator over the keys (`.first`) of a iterator over pairs from a +PYBIND11_NAMESPACE_END(detail) + +/// Makes a python iterator from a first and past-the-end C++ InputIterator. +template ::result_type, + typename... Extra> +iterator make_iterator(Iterator first, Sentinel last, Extra &&... extra) { + return detail::make_iterator_impl< + detail::iterator_access, + Policy, + Iterator, + Sentinel, + ValueType, + Extra...>(first, last, std::forward(extra)...); +} + +/// Makes a python iterator over the keys (`.first`) of a iterator over pairs from a /// first and past-the-end InputIterator. template ()).first), + typename KeyType = typename detail::iterator_key_access::result_type, typename... Extra> -iterator make_key_iterator(Iterator first, Sentinel last, Extra &&... extra) { - using state = detail::iterator_state; +iterator make_key_iterator(Iterator first, Sentinel last, Extra &&...extra) { + return detail::make_iterator_impl< + detail::iterator_key_access, + Policy, + Iterator, + Sentinel, + KeyType, + Extra...>(first, last, std::forward(extra)...); +} - if (!detail::get_type_info(typeid(state), false)) { - class_(handle(), "iterator", pybind11::module_local()) - .def("__iter__", [](state &s) -> state& { return s; }) - .def("__next__", [](state &s) -> KeyType { - if (!s.first_or_done) - ++s.it; - else - s.first_or_done = false; - if (s.it == s.end) { - s.first_or_done = true; - throw stop_iteration(); - } - return (*s.it).first; - }, std::forward(extra)..., Policy); - } - - return cast(state{first, last, true}); +/// Makes a python iterator over the values (`.second`) of a iterator over pairs from a +/// first and past-the-end InputIterator. +template ::result_type, + typename... Extra> +iterator make_value_iterator(Iterator first, Sentinel last, Extra &&...extra) { + return detail::make_iterator_impl< + detail::iterator_value_access, + Policy, Iterator, + Sentinel, + ValueType, + Extra...>(first, last, std::forward(extra)...); } /// Makes an iterator over values of an stl container or other container supporting @@ -1826,10 +2174,17 @@ template (std::begin(value), std::end(value), extra...); } +/// Makes an iterator over the values (`.second`) of a stl map-like container supporting +/// `std::begin()`/`std::end()` +template iterator make_value_iterator(Type &value, Extra&&... extra) { + return make_value_iterator(std::begin(value), std::end(value), extra...); +} + template void implicitly_convertible() { struct set_flag { bool &flag; - set_flag(bool &flag) : flag(flag) { flag = true; } + explicit set_flag(bool &flag_) : flag(flag_) { flag_ = true; } ~set_flag() { flag = false; } }; auto implicit_caster = [](PyObject *obj, PyTypeObject *type) -> PyObject * { @@ -1853,12 +2208,24 @@ template void implicitly_convertible() pybind11_fail("implicitly_convertible: Unable to find type " + type_id()); } -template -void register_exception_translator(ExceptionTranslator&& translator) { + +inline void register_exception_translator(ExceptionTranslator &&translator) { detail::get_internals().registered_exception_translators.push_front( std::forward(translator)); } + +/** + * Add a new module-local exception translator. Locally registered functions + * will be tried before any globally registered exception translators, which + * will only be invoked if the module-local handlers do not deal with + * the exception. + */ +inline void register_local_exception_translator(ExceptionTranslator &&translator) { + detail::get_local_internals().registered_exception_translators.push_front( + std::forward(translator)); +} + /** * Wrapper to generate a new Python exception type. * @@ -1874,7 +2241,7 @@ public: std::string full_name = scope.attr("__name__").cast() + std::string(".") + name; m_ptr = PyErr_NewException(const_cast(full_name.c_str()), base.ptr(), NULL); - if (hasattr(scope, name)) + if (hasattr(scope, "__dict__") && scope.attr("__dict__").contains(name)) pybind11_fail("Error during initialization: multiple incompatible " "definitions with name \"" + std::string(name) + "\""); scope.attr(name) = *this; @@ -1892,22 +2259,20 @@ PYBIND11_NAMESPACE_BEGIN(detail) // directly in register_exception, but that makes clang <3.5 segfault - issue #1349). template exception &get_exception_object() { static exception ex; return ex; } -PYBIND11_NAMESPACE_END(detail) -/** - * Registers a Python exception in `m` of the given `name` and installs an exception translator to - * translate the C++ exception to the created Python exception using the exceptions what() method. - * This is intended for simple exception translations; for more complex translation, register the - * exception object and translator directly. - */ +// Helper function for register_exception and register_local_exception template -exception ®ister_exception(handle scope, - const char *name, - handle base = PyExc_Exception) { +exception ®ister_exception_impl(handle scope, + const char *name, + handle base, + bool isLocal) { auto &ex = detail::get_exception_object(); if (!ex) ex = exception(scope, name, base); - register_exception_translator([](std::exception_ptr p) { + auto register_func = isLocal ? ®ister_local_exception_translator + : ®ister_exception_translator; + + register_func([](std::exception_ptr p) { if (!p) return; try { std::rethrow_exception(p); @@ -1918,8 +2283,38 @@ exception ®ister_exception(handle scope, return ex; } +PYBIND11_NAMESPACE_END(detail) + +/** + * Registers a Python exception in `m` of the given `name` and installs a translator to + * translate the C++ exception to the created Python exception using the what() method. + * This is intended for simple exception translations; for more complex translation, register the + * exception object and translator directly. + */ +template +exception ®ister_exception(handle scope, + const char *name, + handle base = PyExc_Exception) { + return detail::register_exception_impl(scope, name, base, false /* isLocal */); +} + +/** + * Registers a Python exception in `m` of the given `name` and installs a translator to + * translate the C++ exception to the created Python exception using the what() method. + * This translator will only be used for exceptions that are thrown in this module and will be + * tried before global exception translators, including those registered with register_exception. + * This is intended for simple exception translations; for more complex translation, register the + * exception object and translator directly. + */ +template +exception ®ister_local_exception(handle scope, + const char *name, + handle base = PyExc_Exception) { + return detail::register_exception_impl(scope, name, base, true /* isLocal */); +} + PYBIND11_NAMESPACE_BEGIN(detail) -PYBIND11_NOINLINE inline void print(tuple args, dict kwargs) { +PYBIND11_NOINLINE void print(const tuple &args, const dict &kwargs) { auto strings = tuple(args.size()); for (size_t i = 0; i < args.size(); ++i) { strings[i] = str(args[i]); @@ -1932,7 +2327,7 @@ PYBIND11_NOINLINE inline void print(tuple args, dict kwargs) { file = kwargs["file"].cast(); } else { try { - file = module::import("sys").attr("stdout"); + file = module_::import("sys").attr("stdout"); } catch (const error_already_set &) { /* If print() is called from code that is executed as part of garbage collection during interpreter shutdown, @@ -1957,151 +2352,6 @@ void print(Args &&...args) { detail::print(c.args(), c.kwargs()); } -#if defined(WITH_THREAD) && !defined(PYPY_VERSION) - -/* The functions below essentially reproduce the PyGILState_* API using a RAII - * pattern, but there are a few important differences: - * - * 1. When acquiring the GIL from an non-main thread during the finalization - * phase, the GILState API blindly terminates the calling thread, which - * is often not what is wanted. This API does not do this. - * - * 2. The gil_scoped_release function can optionally cut the relationship - * of a PyThreadState and its associated thread, which allows moving it to - * another thread (this is a fairly rare/advanced use case). - * - * 3. The reference count of an acquired thread state can be controlled. This - * can be handy to prevent cases where callbacks issued from an external - * thread would otherwise constantly construct and destroy thread state data - * structures. - * - * See the Python bindings of NanoGUI (http://github.com/wjakob/nanogui) for an - * example which uses features 2 and 3 to migrate the Python thread of - * execution to another thread (to run the event loop on the original thread, - * in this case). - */ - -class gil_scoped_acquire { -public: - PYBIND11_NOINLINE gil_scoped_acquire() { - auto const &internals = detail::get_internals(); - tstate = (PyThreadState *) PYBIND11_TLS_GET_VALUE(internals.tstate); - - if (!tstate) { - /* Check if the GIL was acquired using the PyGILState_* API instead (e.g. if - calling from a Python thread). Since we use a different key, this ensures - we don't create a new thread state and deadlock in PyEval_AcquireThread - below. Note we don't save this state with internals.tstate, since we don't - create it we would fail to clear it (its reference count should be > 0). */ - tstate = PyGILState_GetThisThreadState(); - } - - if (!tstate) { - tstate = PyThreadState_New(internals.istate); - #if !defined(NDEBUG) - if (!tstate) - pybind11_fail("scoped_acquire: could not create thread state!"); - #endif - tstate->gilstate_counter = 0; - PYBIND11_TLS_REPLACE_VALUE(internals.tstate, tstate); - } else { - release = detail::get_thread_state_unchecked() != tstate; - } - - if (release) { - /* Work around an annoying assertion in PyThreadState_Swap */ - #if defined(Py_DEBUG) - PyInterpreterState *interp = tstate->interp; - tstate->interp = nullptr; - #endif - PyEval_AcquireThread(tstate); - #if defined(Py_DEBUG) - tstate->interp = interp; - #endif - } - - inc_ref(); - } - - void inc_ref() { - ++tstate->gilstate_counter; - } - - PYBIND11_NOINLINE void dec_ref() { - --tstate->gilstate_counter; - #if !defined(NDEBUG) - if (detail::get_thread_state_unchecked() != tstate) - pybind11_fail("scoped_acquire::dec_ref(): thread state must be current!"); - if (tstate->gilstate_counter < 0) - pybind11_fail("scoped_acquire::dec_ref(): reference count underflow!"); - #endif - if (tstate->gilstate_counter == 0) { - #if !defined(NDEBUG) - if (!release) - pybind11_fail("scoped_acquire::dec_ref(): internal error!"); - #endif - PyThreadState_Clear(tstate); - PyThreadState_DeleteCurrent(); - PYBIND11_TLS_DELETE_VALUE(detail::get_internals().tstate); - release = false; - } - } - - PYBIND11_NOINLINE ~gil_scoped_acquire() { - dec_ref(); - if (release) - PyEval_SaveThread(); - } -private: - PyThreadState *tstate = nullptr; - bool release = true; -}; - -class gil_scoped_release { -public: - explicit gil_scoped_release(bool disassoc = false) : disassoc(disassoc) { - // `get_internals()` must be called here unconditionally in order to initialize - // `internals.tstate` for subsequent `gil_scoped_acquire` calls. Otherwise, an - // initialization race could occur as multiple threads try `gil_scoped_acquire`. - const auto &internals = detail::get_internals(); - tstate = PyEval_SaveThread(); - if (disassoc) { - auto key = internals.tstate; - PYBIND11_TLS_DELETE_VALUE(key); - } - } - ~gil_scoped_release() { - if (!tstate) - return; - PyEval_RestoreThread(tstate); - if (disassoc) { - auto key = detail::get_internals().tstate; - PYBIND11_TLS_REPLACE_VALUE(key, tstate); - } - } -private: - PyThreadState *tstate; - bool disassoc; -}; -#elif defined(PYPY_VERSION) -class gil_scoped_acquire { - PyGILState_STATE state; -public: - gil_scoped_acquire() { state = PyGILState_Ensure(); } - ~gil_scoped_acquire() { PyGILState_Release(state); } -}; - -class gil_scoped_release { - PyThreadState *state; -public: - gil_scoped_release() { state = PyEval_SaveThread(); } - ~gil_scoped_release() { PyEval_RestoreThread(state); } -}; -#else -class gil_scoped_acquire { }; -class gil_scoped_release { }; -#endif - error_already_set::~error_already_set() { if (m_type) { gil_scoped_acquire gil; @@ -2134,16 +2384,42 @@ inline function get_type_override(const void *this_ptr, const type_info *this_ty /* Don't call dispatch code if invoked from overridden function. Unfortunately this doesn't work on PyPy. */ -#if !defined(PYPY_VERSION) +#if !defined(PYPY_VERSION) && PY_VERSION_HEX < 0x030B0000 + // TODO: Remove PyPy workaround for Python 3.11. + // Current API fails on 3.11 since co_varnames can be null. +#if PY_VERSION_HEX >= 0x03090000 + PyFrameObject *frame = PyThreadState_GetFrame(PyThreadState_Get()); + if (frame != nullptr) { + PyCodeObject *f_code = PyFrame_GetCode(frame); + // f_code is guaranteed to not be NULL + if ((std::string) str(f_code->co_name) == name && f_code->co_argcount > 0) { + PyObject* locals = PyEval_GetLocals(); + if (locals != nullptr && f_code->co_varnames != nullptr) { + PyObject *self_caller = dict_getitem( + locals, PyTuple_GET_ITEM(f_code->co_varnames, 0) + ); + if (self_caller == self.ptr()) { + Py_DECREF(f_code); + Py_DECREF(frame); + return function(); + } + } + } + Py_DECREF(f_code); + Py_DECREF(frame); + } +#else PyFrameObject *frame = PyThreadState_Get()->frame; - if (frame && (std::string) str(frame->f_code->co_name) == name && - frame->f_code->co_argcount > 0) { + if (frame != nullptr && (std::string) str(frame->f_code->co_name) == name + && frame->f_code->co_argcount > 0) { PyFrame_FastToLocals(frame); - PyObject *self_caller = PyDict_GetItem( + PyObject *self_caller = dict_getitem( frame->f_locals, PyTuple_GET_ITEM(frame->f_code->co_varnames, 0)); if (self_caller == self.ptr()) return function(); } +#endif + #else /* PyPy currently doesn't provide a detailed cpyext emulation of frame objects, so we have to emulate this using Python. This @@ -2174,7 +2450,7 @@ PYBIND11_NAMESPACE_END(detail) /** \rst Try to retrieve a python method by the provided name from the instance pointed to by the this_ptr. - :this_ptr: The pointer to the object the overriden method should be retrieved for. This should be + :this_ptr: The pointer to the object the overridden method should be retrieved for. This should be the first non-trampoline class encountered in the inheritance chain. :name: The name of the overridden Python method to retrieve. :return: The Python method by this name from the object or an empty function wrapper. @@ -2184,18 +2460,19 @@ template function get_override(const T *this_ptr, const char *name) { return tinfo ? detail::get_type_override(this_ptr, tinfo, name) : function(); } -#define PYBIND11_OVERRIDE_IMPL(ret_type, cname, name, ...) \ - do { \ - pybind11::gil_scoped_acquire gil; \ - pybind11::function override = pybind11::get_override(static_cast(this), name); \ - if (override) { \ - auto o = override(__VA_ARGS__); \ - if (pybind11::detail::cast_is_temporary_value_reference::value) { \ - static pybind11::detail::override_caster_t caster; \ - return pybind11::detail::cast_ref(std::move(o), caster); \ - } \ - else return pybind11::detail::cast_safe(std::move(o)); \ - } \ +#define PYBIND11_OVERRIDE_IMPL(ret_type, cname, name, ...) \ + do { \ + pybind11::gil_scoped_acquire gil; \ + pybind11::function override \ + = pybind11::get_override(static_cast(this), name); \ + if (override) { \ + auto o = override(__VA_ARGS__); \ + if (pybind11::detail::cast_is_temporary_value_reference::value) { \ + static pybind11::detail::override_caster_t caster; \ + return pybind11::detail::cast_ref(std::move(o), caster); \ + } \ + return pybind11::detail::cast_safe(std::move(o)); \ + } \ } while (false) /** \rst @@ -2291,8 +2568,6 @@ inline function get_overload(const T *this_ptr, const char *name) { PYBIND11_NAMESPACE_END(PYBIND11_NAMESPACE) -#if defined(_MSC_VER) && !defined(__INTEL_COMPILER) -# pragma warning(pop) -#elif defined(__GNUG__) && !defined(__clang__) -# pragma GCC diagnostic pop +#if defined(__GNUC__) && __GNUC__ == 7 +# pragma GCC diagnostic pop // -Wnoexcept-type #endif diff --git a/pybind11/include/pybind11/pytypes.h b/pybind11/include/pybind11/pytypes.h index a2f7cec48..902fb1f07 100644 --- a/pybind11/include/pybind11/pytypes.h +++ b/pybind11/include/pybind11/pytypes.h @@ -14,6 +14,14 @@ #include #include +#if defined(PYBIND11_HAS_OPTIONAL) +# include +#endif + +#ifdef PYBIND11_HAS_STRING_VIEW +# include +#endif + PYBIND11_NAMESPACE_BEGIN(PYBIND11_NAMESPACE) /* A few forward declarations */ @@ -24,7 +32,7 @@ struct arg; struct arg_v; PYBIND11_NAMESPACE_BEGIN(detail) class args_proxy; -inline bool isinstance_generic(handle obj, const std::type_info &tp); +bool isinstance_generic(handle obj, const std::type_info &tp); // Accessor forward declarations template class accessor; @@ -153,7 +161,7 @@ public: /// Return the object's current reference count int ref_count() const { return static_cast(Py_REFCNT(derived().ptr())); } - PYBIND11_DEPRECATED("Call py::type::handle_of(h) or py::type::of(h) instead of h.get_type()") + // TODO PYBIND11_DEPRECATED("Call py::type::handle_of(h) or py::type::of(h) instead of h.get_type()") handle get_type() const; private: @@ -178,6 +186,7 @@ public: /// The default constructor creates a handle with a ``nullptr``-valued pointer handle() = default; /// Creates a ``handle`` from the given raw Python object pointer + // NOLINTNEXTLINE(google-explicit-constructor) handle(PyObject *ptr) : m_ptr(ptr) { } // Allow implicit conversion from PyObject* /// Return the underlying ``PyObject *`` pointer @@ -254,8 +263,11 @@ public: object& operator=(const object &other) { other.inc_ref(); - dec_ref(); + // Use temporary variable to ensure `*this` remains valid while + // `Py_XDECREF` executes, in case `*this` is accessible from Python. + handle temp(m_ptr); m_ptr = other.m_ptr; + temp.dec_ref(); return *this; } @@ -279,8 +291,10 @@ protected: struct borrowed_t { }; struct stolen_t { }; + /// @cond BROKEN template friend T reinterpret_borrow(handle); template friend T reinterpret_steal(handle); + /// @endcond public: // Only accessible from derived classes and the reinterpret_* functions @@ -314,14 +328,18 @@ template T reinterpret_borrow(handle h) { return {h, object::borrow template T reinterpret_steal(handle h) { return {h, object::stolen_t{}}; } PYBIND11_NAMESPACE_BEGIN(detail) -inline std::string error_string(); +std::string error_string(); PYBIND11_NAMESPACE_END(detail) +#if defined(_MSC_VER) +# pragma warning(push) +# pragma warning(disable: 4275 4251) // warning C4275: An exported class was derived from a class that wasn't exported. Can be ignored when derived from a STL class. +#endif /// Fetch and hold an error which was already set in Python. An instance of this is typically /// thrown to propagate python-side errors back through C++ which can either be caught manually or /// else falls back to the function dispatcher (which then raises the captured error back to /// python). -class error_already_set : public std::runtime_error { +class PYBIND11_EXPORT_EXCEPTION error_already_set : public std::runtime_error { public: /// Constructs a new exception from the current Python error indicator, if any. The current /// Python error indicator will be cleared. @@ -339,16 +357,17 @@ public: /// error variables (but the `.what()` string is still available). void restore() { PyErr_Restore(m_type.release().ptr(), m_value.release().ptr(), m_trace.release().ptr()); } - /// If it is impossible to raise the currently-held error, such as in destructor, we can write - /// it out using Python's unraisable hook (sys.unraisablehook). The error context should be - /// some object whose repr() helps identify the location of the error. Python already knows the - /// type and value of the error, so there is no need to repeat that. For example, __func__ could - /// be helpful. After this call, the current object no longer stores the error variables, - /// and neither does Python. + /// If it is impossible to raise the currently-held error, such as in a destructor, we can write + /// it out using Python's unraisable hook (`sys.unraisablehook`). The error context should be + /// some object whose `repr()` helps identify the location of the error. Python already knows the + /// type and value of the error, so there is no need to repeat that. After this call, the current + /// object no longer stores the error variables, and neither does Python. void discard_as_unraisable(object err_context) { restore(); PyErr_WriteUnraisable(err_context.ptr()); } + /// An alternate version of `discard_as_unraisable()`, where a string provides information on the + /// location of the error. For example, `__func__` could be helpful. void discard_as_unraisable(const char *err_context) { discard_as_unraisable(reinterpret_steal(PYBIND11_FROM_STRING(err_context))); } @@ -360,7 +379,9 @@ public: /// Check if the currently trapped error type matches the given Python exception class (or a /// subclass thereof). May also be passed a tuple to search for any exception class matches in /// the given tuple. - bool matches(handle exc) const { return PyErr_GivenExceptionMatches(m_type.ptr(), exc.ptr()); } + bool matches(handle exc) const { + return (PyErr_GivenExceptionMatches(m_type.ptr(), exc.ptr()) != 0); + } const object& type() const { return m_type; } const object& value() const { return m_value; } @@ -369,8 +390,52 @@ public: private: object m_type, m_value, m_trace; }; +#if defined(_MSC_VER) +# pragma warning(pop) +#endif -/** \defgroup python_builtins _ +#if PY_VERSION_HEX >= 0x03030000 + +/// Replaces the current Python error indicator with the chosen error, performing a +/// 'raise from' to indicate that the chosen error was caused by the original error. +inline void raise_from(PyObject *type, const char *message) { + // Based on _PyErr_FormatVFromCause: + // https://github.com/python/cpython/blob/467ab194fc6189d9f7310c89937c51abeac56839/Python/errors.c#L405 + // See https://github.com/pybind/pybind11/pull/2112 for details. + PyObject *exc = nullptr, *val = nullptr, *val2 = nullptr, *tb = nullptr; + + assert(PyErr_Occurred()); + PyErr_Fetch(&exc, &val, &tb); + PyErr_NormalizeException(&exc, &val, &tb); + if (tb != nullptr) { + PyException_SetTraceback(val, tb); + Py_DECREF(tb); + } + Py_DECREF(exc); + assert(!PyErr_Occurred()); + + PyErr_SetString(type, message); + + PyErr_Fetch(&exc, &val2, &tb); + PyErr_NormalizeException(&exc, &val2, &tb); + Py_INCREF(val); + PyException_SetCause(val2, val); + PyException_SetContext(val2, val); + PyErr_Restore(exc, val2, tb); +} + +/// Sets the current Python error indicator with the chosen error, performing a 'raise from' +/// from the error contained in error_already_set to indicate that the chosen error was +/// caused by the original error. After this function is called error_already_set will +/// no longer contain an error. +inline void raise_from(error_already_set& err, PyObject *type, const char *message) { + err.restore(); + raise_from(type, message); +} + +#endif + +/** \defgroup python_builtins const_name Unless stated otherwise, the following C++ functions behave the same as their Python counterparts. */ @@ -431,19 +496,17 @@ inline object getattr(handle obj, const char *name) { inline object getattr(handle obj, handle name, handle default_) { if (PyObject *result = PyObject_GetAttr(obj.ptr(), name.ptr())) { return reinterpret_steal(result); - } else { - PyErr_Clear(); - return reinterpret_borrow(default_); } + PyErr_Clear(); + return reinterpret_borrow(default_); } inline object getattr(handle obj, const char *name, handle default_) { if (PyObject *result = PyObject_GetAttrString(obj.ptr(), name)) { return reinterpret_steal(result); - } else { - PyErr_Clear(); - return reinterpret_borrow(default_); } + PyErr_Clear(); + return reinterpret_borrow(default_); } inline void setattr(handle obj, handle name, handle value) { @@ -476,6 +539,43 @@ inline handle get_function(handle value) { return value; } +// Reimplementation of python's dict helper functions to ensure that exceptions +// aren't swallowed (see #2862) + +// copied from cpython _PyDict_GetItemStringWithError +inline PyObject * dict_getitemstring(PyObject *v, const char *key) +{ +#if PY_MAJOR_VERSION >= 3 + PyObject *kv = nullptr, *rv = nullptr; + kv = PyUnicode_FromString(key); + if (kv == NULL) { + throw error_already_set(); + } + + rv = PyDict_GetItemWithError(v, kv); + Py_DECREF(kv); + if (rv == NULL && PyErr_Occurred()) { + throw error_already_set(); + } + return rv; +#else + return PyDict_GetItemString(v, key); +#endif +} + +inline PyObject * dict_getitem(PyObject *v, PyObject *key) +{ +#if PY_MAJOR_VERSION >= 3 + PyObject *rv = PyDict_GetItemWithError(v, key); + if (rv == NULL && PyErr_Occurred()) { + throw error_already_set(); + } + return rv; +#else + return PyDict_GetItem(v, key); +#endif +} + // Helper aliases/functions to support implicit casting of values given to python accessors/methods. // When given a pyobject, this simply returns the pyobject as-is; for other C++ type, the value goes // through pybind11::cast(obj) to convert it to an `object`. @@ -487,6 +587,10 @@ object object_or_cast(T &&o); // Match a PyObject*, which we want to convert directly to handle via its converting constructor inline handle object_or_cast(PyObject *ptr) { return ptr; } +#if defined(_MSC_VER) && _MSC_VER < 1920 +# pragma warning(push) +# pragma warning(disable: 4522) // warning C4522: multiple assignment operators specified +#endif template class accessor : public object_api> { using key_type = typename Policy::key_type; @@ -494,7 +598,7 @@ class accessor : public object_api> { public: accessor(handle obj, key_type key) : obj(obj), key(std::move(key)) { } accessor(const accessor &) = default; - accessor(accessor &&) = default; + accessor(accessor &&) noexcept = default; // accessor overload required to override default assignment operator (templates are not allowed // to replace default compiler-generated assignments). @@ -520,6 +624,7 @@ public: return obj.contains(key); } + // NOLINTNEXTLINE(google-explicit-constructor) operator object() const { return get_cache(); } PyObject *ptr() const { return get_cache().ptr(); } template T cast() const { return get_cache().template cast(); } @@ -535,6 +640,9 @@ private: key_type key; mutable object cache; }; +#if defined(_MSC_VER) && _MSC_VER < 1920 +# pragma warning(pop) +#endif PYBIND11_NAMESPACE_BEGIN(accessor_policies) struct obj_attr { @@ -566,15 +674,17 @@ struct generic_item { struct sequence_item { using key_type = size_t; - static object get(handle obj, size_t index) { - PyObject *result = PySequence_GetItem(obj.ptr(), static_cast(index)); + template ::value, int> = 0> + static object get(handle obj, const IdxType &index) { + PyObject *result = PySequence_GetItem(obj.ptr(), ssize_t_cast(index)); if (!result) { throw error_already_set(); } return reinterpret_steal(result); } - static void set(handle obj, size_t index, handle val) { + template ::value, int> = 0> + static void set(handle obj, const IdxType &index, handle val) { // PySequence_SetItem does not steal a reference to 'val' - if (PySequence_SetItem(obj.ptr(), static_cast(index), val.ptr()) != 0) { + if (PySequence_SetItem(obj.ptr(), ssize_t_cast(index), val.ptr()) != 0) { throw error_already_set(); } } @@ -583,15 +693,17 @@ struct sequence_item { struct list_item { using key_type = size_t; - static object get(handle obj, size_t index) { - PyObject *result = PyList_GetItem(obj.ptr(), static_cast(index)); + template ::value, int> = 0> + static object get(handle obj, const IdxType &index) { + PyObject *result = PyList_GetItem(obj.ptr(), ssize_t_cast(index)); if (!result) { throw error_already_set(); } return reinterpret_borrow(result); } - static void set(handle obj, size_t index, handle val) { + template ::value, int> = 0> + static void set(handle obj, const IdxType &index, handle val) { // PyList_SetItem steals a reference to 'val' - if (PyList_SetItem(obj.ptr(), static_cast(index), val.inc_ref().ptr()) != 0) { + if (PyList_SetItem(obj.ptr(), ssize_t_cast(index), val.inc_ref().ptr()) != 0) { throw error_already_set(); } } @@ -600,15 +712,17 @@ struct list_item { struct tuple_item { using key_type = size_t; - static object get(handle obj, size_t index) { - PyObject *result = PyTuple_GetItem(obj.ptr(), static_cast(index)); + template ::value, int> = 0> + static object get(handle obj, const IdxType &index) { + PyObject *result = PyTuple_GetItem(obj.ptr(), ssize_t_cast(index)); if (!result) { throw error_already_set(); } return reinterpret_borrow(result); } - static void set(handle obj, size_t index, handle val) { + template ::value, int> = 0> + static void set(handle obj, const IdxType &index, handle val) { // PyTuple_SetItem steals a reference to 'val' - if (PyTuple_SetItem(obj.ptr(), static_cast(index), val.inc_ref().ptr()) != 0) { + if (PyTuple_SetItem(obj.ptr(), ssize_t_cast(index), val.inc_ref().ptr()) != 0) { throw error_already_set(); } } @@ -630,7 +744,9 @@ public: generic_iterator() = default; generic_iterator(handle seq, ssize_t index) : Policy(seq, index) { } + // NOLINTNEXTLINE(readability-const-return-type) // PR #3263 reference operator*() const { return Policy::dereference(); } + // NOLINTNEXTLINE(readability-const-return-type) // PR #3263 reference operator[](difference_type n) const { return *(*this + n); } pointer operator->() const { return **this; } @@ -660,7 +776,8 @@ template struct arrow_proxy { T value; - arrow_proxy(T &&value) : value(std::move(value)) { } + // NOLINTNEXTLINE(google-explicit-constructor) + arrow_proxy(T &&value) noexcept : value(std::move(value)) { } T *operator->() const { return &value; } }; @@ -669,11 +786,12 @@ class sequence_fast_readonly { protected: using iterator_category = std::random_access_iterator_tag; using value_type = handle; - using reference = const handle; + using reference = const handle; // PR #3263 using pointer = arrow_proxy; sequence_fast_readonly(handle obj, ssize_t n) : ptr(PySequence_Fast_ITEMS(obj.ptr()) + n) { } + // NOLINTNEXTLINE(readability-const-return-type) // PR #3263 reference dereference() const { return *ptr; } void increment() { ++ptr; } void decrement() { --ptr; } @@ -712,14 +830,19 @@ class dict_readonly { protected: using iterator_category = std::forward_iterator_tag; using value_type = std::pair; - using reference = const value_type; + using reference = const value_type; // PR #3263 using pointer = arrow_proxy; dict_readonly() = default; dict_readonly(handle obj, ssize_t pos) : obj(obj), pos(pos) { increment(); } + // NOLINTNEXTLINE(readability-const-return-type) // PR #3263 reference dereference() const { return {key, value}; } - void increment() { if (!PyDict_Next(obj.ptr(), &pos, &key, &value)) { pos = -1; } } + void increment() { + if (PyDict_Next(obj.ptr(), &pos, &key, &value) == 0) { + pos = -1; + } + } bool equal(const dict_readonly &b) const { return pos == b.pos; } private: @@ -745,16 +868,20 @@ inline bool PyIterable_Check(PyObject *obj) { if (iter) { Py_DECREF(iter); return true; - } else { - PyErr_Clear(); - return false; } + PyErr_Clear(); + return false; } inline bool PyNone_Check(PyObject *o) { return o == Py_None; } inline bool PyEllipsis_Check(PyObject *o) { return o == Py_Ellipsis; } +#ifdef PYBIND11_STR_LEGACY_PERMISSIVE inline bool PyUnicode_Check_Permissive(PyObject *o) { return PyUnicode_Check(o) || PYBIND11_BYTES_CHECK(o); } +#define PYBIND11_STR_CHECK_FUN detail::PyUnicode_Check_Permissive +#else +#define PYBIND11_STR_CHECK_FUN PyUnicode_Check +#endif inline bool PyStaticMethod_Check(PyObject *o) { return o->ob_type == &PyStaticMethod_Type; } @@ -797,26 +924,42 @@ PYBIND11_NAMESPACE_END(detail) Name(handle h, borrowed_t) : Parent(h, borrowed_t{}) { } \ Name(handle h, stolen_t) : Parent(h, stolen_t{}) { } \ PYBIND11_DEPRECATED("Use py::isinstance(obj) instead") \ - bool check() const { return m_ptr != nullptr && (bool) CheckFun(m_ptr); } \ + bool check() const { return m_ptr != nullptr && (CheckFun(m_ptr) != 0); } \ static bool check_(handle h) { return h.ptr() != nullptr && CheckFun(h.ptr()); } \ template \ + /* NOLINTNEXTLINE(google-explicit-constructor) */ \ Name(const ::pybind11::detail::accessor &a) : Name(object(a)) { } #define PYBIND11_OBJECT_CVT(Name, Parent, CheckFun, ConvertFun) \ PYBIND11_OBJECT_COMMON(Name, Parent, CheckFun) \ /* This is deliberately not 'explicit' to allow implicit conversion from object: */ \ + /* NOLINTNEXTLINE(google-explicit-constructor) */ \ Name(const object &o) \ : Parent(check_(o) ? o.inc_ref().ptr() : ConvertFun(o.ptr()), stolen_t{}) \ { if (!m_ptr) throw error_already_set(); } \ + /* NOLINTNEXTLINE(google-explicit-constructor) */ \ Name(object &&o) \ : Parent(check_(o) ? o.release().ptr() : ConvertFun(o.ptr()), stolen_t{}) \ { if (!m_ptr) throw error_already_set(); } +#define PYBIND11_OBJECT_CVT_DEFAULT(Name, Parent, CheckFun, ConvertFun) \ + PYBIND11_OBJECT_CVT(Name, Parent, CheckFun, ConvertFun) \ + Name() : Parent() { } + +#define PYBIND11_OBJECT_CHECK_FAILED(Name, o_ptr) \ + ::pybind11::type_error("Object of type '" + \ + ::pybind11::detail::get_fully_qualified_tp_name(Py_TYPE(o_ptr)) + \ + "' is not an instance of '" #Name "'") + #define PYBIND11_OBJECT(Name, Parent, CheckFun) \ PYBIND11_OBJECT_COMMON(Name, Parent, CheckFun) \ /* This is deliberately not 'explicit' to allow implicit conversion from object: */ \ - Name(const object &o) : Parent(o) { } \ - Name(object &&o) : Parent(std::move(o)) { } + /* NOLINTNEXTLINE(google-explicit-constructor) */ \ + Name(const object &o) : Parent(o) \ + { if (m_ptr && !check_(m_ptr)) throw PYBIND11_OBJECT_CHECK_FAILED(Name, m_ptr); } \ + /* NOLINTNEXTLINE(google-explicit-constructor) */ \ + Name(object &&o) : Parent(std::move(o)) \ + { if (m_ptr && !check_(m_ptr)) throw PYBIND11_OBJECT_CHECK_FAILED(Name, m_ptr); } #define PYBIND11_OBJECT_DEFAULT(Name, Parent, CheckFun) \ PYBIND11_OBJECT(Name, Parent, CheckFun) \ @@ -838,7 +981,7 @@ public: using iterator_category = std::input_iterator_tag; using difference_type = ssize_t; using value_type = handle; - using reference = const handle; + using reference = const handle; // PR #3263 using pointer = const handle *; PYBIND11_OBJECT_DEFAULT(iterator, object, PyIter_Check) @@ -854,6 +997,7 @@ public: return rv; } + // NOLINTNEXTLINE(readability-const-return-type) // PR #3263 reference operator*() const { if (m_ptr && !value.ptr()) { auto& self = const_cast(*this); @@ -927,21 +1071,38 @@ class bytes; class str : public object { public: - PYBIND11_OBJECT_CVT(str, object, detail::PyUnicode_Check_Permissive, raw_str) + PYBIND11_OBJECT_CVT(str, object, PYBIND11_STR_CHECK_FUN, raw_str) - str(const char *c, size_t n) - : object(PyUnicode_FromStringAndSize(c, (ssize_t) n), stolen_t{}) { + template ::value, int> = 0> + str(const char *c, const SzType &n) + : object(PyUnicode_FromStringAndSize(c, ssize_t_cast(n)), stolen_t{}) { if (!m_ptr) pybind11_fail("Could not allocate string object!"); } // 'explicit' is explicitly omitted from the following constructors to allow implicit conversion to py::str from C++ string-like objects + // NOLINTNEXTLINE(google-explicit-constructor) str(const char *c = "") : object(PyUnicode_FromString(c), stolen_t{}) { if (!m_ptr) pybind11_fail("Could not allocate string object!"); } + // NOLINTNEXTLINE(google-explicit-constructor) str(const std::string &s) : str(s.data(), s.size()) { } +#ifdef PYBIND11_HAS_STRING_VIEW + // enable_if is needed to avoid "ambiguous conversion" errors (see PR #3521). + template ::value, int> = 0> + // NOLINTNEXTLINE(google-explicit-constructor) + str(T s) : str(s.data(), s.size()) { } + +# ifdef PYBIND11_HAS_U8STRING + // reinterpret_cast here is safe (C++20 guarantees char8_t has the same size/alignment as char) + // NOLINTNEXTLINE(google-explicit-constructor) + str(std::u8string_view s) : str(reinterpret_cast(s.data()), s.size()) { } +# endif + +#endif + explicit str(const bytes &b); /** \rst @@ -950,15 +1111,16 @@ public: \endrst */ explicit str(handle h) : object(raw_str(h.ptr()), stolen_t{}) { if (!m_ptr) throw error_already_set(); } + // NOLINTNEXTLINE(google-explicit-constructor) operator std::string() const { object temp = *this; if (PyUnicode_Check(m_ptr)) { temp = reinterpret_steal(PyUnicode_AsUTF8String(m_ptr)); if (!temp) - pybind11_fail("Unable to extract string contents! (encoding issue)"); + throw error_already_set(); } - char *buffer; - ssize_t length; + char *buffer = nullptr; + ssize_t length = 0; if (PYBIND11_BYTES_AS_STRING_AND_SIZE(temp.ptr(), &buffer, &length)) pybind11_fail("Unable to extract string contents! (invalid type)"); return std::string(buffer, (size_t) length); @@ -997,28 +1159,52 @@ public: PYBIND11_OBJECT(bytes, object, PYBIND11_BYTES_CHECK) // Allow implicit conversion: + // NOLINTNEXTLINE(google-explicit-constructor) bytes(const char *c = "") : object(PYBIND11_BYTES_FROM_STRING(c), stolen_t{}) { if (!m_ptr) pybind11_fail("Could not allocate bytes object!"); } - bytes(const char *c, size_t n) - : object(PYBIND11_BYTES_FROM_STRING_AND_SIZE(c, (ssize_t) n), stolen_t{}) { + template ::value, int> = 0> + bytes(const char *c, const SzType &n) + : object(PYBIND11_BYTES_FROM_STRING_AND_SIZE(c, ssize_t_cast(n)), stolen_t{}) { if (!m_ptr) pybind11_fail("Could not allocate bytes object!"); } // Allow implicit conversion: + // NOLINTNEXTLINE(google-explicit-constructor) bytes(const std::string &s) : bytes(s.data(), s.size()) { } explicit bytes(const pybind11::str &s); + // NOLINTNEXTLINE(google-explicit-constructor) operator std::string() const { - char *buffer; - ssize_t length; + char *buffer = nullptr; + ssize_t length = 0; if (PYBIND11_BYTES_AS_STRING_AND_SIZE(m_ptr, &buffer, &length)) pybind11_fail("Unable to extract bytes contents!"); return std::string(buffer, (size_t) length); } + +#ifdef PYBIND11_HAS_STRING_VIEW + // enable_if is needed to avoid "ambiguous conversion" errors (see PR #3521). + template ::value, int> = 0> + // NOLINTNEXTLINE(google-explicit-constructor) + bytes(T s) : bytes(s.data(), s.size()) { } + + // Obtain a string view that views the current `bytes` buffer value. Note that this is only + // valid so long as the `bytes` instance remains alive and so generally should not outlive the + // lifetime of the `bytes` instance. + // NOLINTNEXTLINE(google-explicit-constructor) + operator std::string_view() const { + char *buffer = nullptr; + ssize_t length = 0; + if (PYBIND11_BYTES_AS_STRING_AND_SIZE(m_ptr, &buffer, &length)) + pybind11_fail("Unable to extract bytes contents!"); + return {buffer, static_cast(length)}; + } +#endif + }; // Note: breathe >= 4.17.0 will fail to build docs if the below two constructors // are included in the doxygen group; close here and reopen after as a workaround @@ -1031,8 +1217,8 @@ inline bytes::bytes(const pybind11::str &s) { if (!temp) pybind11_fail("Unable to extract string contents! (encoding issue)"); } - char *buffer; - ssize_t length; + char *buffer = nullptr; + ssize_t length = 0; if (PYBIND11_BYTES_AS_STRING_AND_SIZE(temp.ptr(), &buffer, &length)) pybind11_fail("Unable to extract string contents! (invalid type)"); auto obj = reinterpret_steal(PYBIND11_BYTES_FROM_STRING_AND_SIZE(buffer, length)); @@ -1042,16 +1228,45 @@ inline bytes::bytes(const pybind11::str &s) { } inline str::str(const bytes& b) { - char *buffer; - ssize_t length; + char *buffer = nullptr; + ssize_t length = 0; if (PYBIND11_BYTES_AS_STRING_AND_SIZE(b.ptr(), &buffer, &length)) pybind11_fail("Unable to extract bytes contents!"); - auto obj = reinterpret_steal(PyUnicode_FromStringAndSize(buffer, (ssize_t) length)); + auto obj = reinterpret_steal(PyUnicode_FromStringAndSize(buffer, length)); if (!obj) pybind11_fail("Could not allocate string object!"); m_ptr = obj.release().ptr(); } +/// \addtogroup pytypes +/// @{ +class bytearray : public object { +public: + PYBIND11_OBJECT_CVT(bytearray, object, PyByteArray_Check, PyByteArray_FromObject) + + template ::value, int> = 0> + bytearray(const char *c, const SzType &n) + : object(PyByteArray_FromStringAndSize(c, ssize_t_cast(n)), stolen_t{}) { + if (!m_ptr) pybind11_fail("Could not allocate bytearray object!"); + } + + bytearray() + : bytearray("", 0) {} + + explicit bytearray(const std::string &s) : bytearray(s.data(), s.size()) { } + + size_t size() const { return static_cast(PyByteArray_Size(m_ptr)); } + + explicit operator std::string() const { + char *buffer = PyByteArray_AS_STRING(m_ptr); + ssize_t size = PyByteArray_GET_SIZE(m_ptr); + return std::string(buffer, static_cast(size)); + } +}; +// Note: breathe >= 4.17.0 will fail to build docs if the below two constructors +// are included in the doxygen group; close here and reopen after as a workaround +/// @} pytypes + /// \addtogroup pytypes /// @{ class none : public object { @@ -1071,15 +1286,17 @@ public: PYBIND11_OBJECT_CVT(bool_, object, PyBool_Check, raw_bool) bool_() : object(Py_False, borrowed_t{}) { } // Allow implicit conversion from and to `bool`: + // NOLINTNEXTLINE(google-explicit-constructor) bool_(bool value) : object(value ? Py_True : Py_False, borrowed_t{}) { } - operator bool() const { return m_ptr && PyLong_AsLong(m_ptr) != 0; } + // NOLINTNEXTLINE(google-explicit-constructor) + operator bool() const { return (m_ptr != nullptr) && PyLong_AsLong(m_ptr) != 0; } private: /// Return the truth value of an object -- always returns a new reference static PyObject *raw_bool(PyObject *op) { const auto value = PyObject_IsTrue(op); if (value == -1) return nullptr; - return handle(value ? Py_True : Py_False).inc_ref().ptr(); + return handle(value != 0 ? Py_True : Py_False).inc_ref().ptr(); } }; @@ -1090,18 +1307,16 @@ PYBIND11_NAMESPACE_BEGIN(detail) // unsigned type: (A)-1 != (B)-1 when A and B are unsigned types of different sizes). template Unsigned as_unsigned(PyObject *o) { - if (sizeof(Unsigned) <= sizeof(unsigned long) + if (PYBIND11_SILENCE_MSVC_C4127(sizeof(Unsigned) <= sizeof(unsigned long)) #if PY_VERSION_HEX < 0x03000000 - || PyInt_Check(o) + || PyInt_Check(o) #endif ) { unsigned long v = PyLong_AsUnsignedLong(o); return v == (unsigned long) -1 && PyErr_Occurred() ? (Unsigned) -1 : (Unsigned) v; } - else { - unsigned long long v = PyLong_AsUnsignedLongLong(o); - return v == (unsigned long long) -1 && PyErr_Occurred() ? (Unsigned) -1 : (Unsigned) v; - } + unsigned long long v = PyLong_AsUnsignedLongLong(o); + return v == (unsigned long long) -1 && PyErr_Occurred() ? (Unsigned) -1 : (Unsigned) v; } PYBIND11_NAMESPACE_END(detail) @@ -1112,8 +1327,9 @@ public: // Allow implicit conversion from C++ integral types: template ::value, int> = 0> + // NOLINTNEXTLINE(google-explicit-constructor) int_(T value) { - if (sizeof(T) <= sizeof(long)) { + if (PYBIND11_SILENCE_MSVC_C4127(sizeof(T) <= sizeof(long))) { if (std::is_signed::value) m_ptr = PyLong_FromLong((long) value); else @@ -1129,6 +1345,7 @@ public: template ::value, int> = 0> + // NOLINTNEXTLINE(google-explicit-constructor) operator T() const { return std::is_unsigned::value ? detail::as_unsigned(m_ptr) @@ -1142,33 +1359,51 @@ class float_ : public object { public: PYBIND11_OBJECT_CVT(float_, object, PyFloat_Check, PyNumber_Float) // Allow implicit conversion from float/double: + // NOLINTNEXTLINE(google-explicit-constructor) float_(float value) : object(PyFloat_FromDouble((double) value), stolen_t{}) { if (!m_ptr) pybind11_fail("Could not allocate float object!"); } + // NOLINTNEXTLINE(google-explicit-constructor) float_(double value = .0) : object(PyFloat_FromDouble((double) value), stolen_t{}) { if (!m_ptr) pybind11_fail("Could not allocate float object!"); } + // NOLINTNEXTLINE(google-explicit-constructor) operator float() const { return (float) PyFloat_AsDouble(m_ptr); } + // NOLINTNEXTLINE(google-explicit-constructor) operator double() const { return (double) PyFloat_AsDouble(m_ptr); } }; class weakref : public object { public: - PYBIND11_OBJECT_DEFAULT(weakref, object, PyWeakref_Check) + PYBIND11_OBJECT_CVT_DEFAULT(weakref, object, PyWeakref_Check, raw_weakref) explicit weakref(handle obj, handle callback = {}) : object(PyWeakref_NewRef(obj.ptr(), callback.ptr()), stolen_t{}) { if (!m_ptr) pybind11_fail("Could not allocate weak reference!"); } + +private: + static PyObject *raw_weakref(PyObject *o) { + return PyWeakref_NewRef(o, nullptr); + } }; class slice : public object { public: PYBIND11_OBJECT_DEFAULT(slice, object, PySlice_Check) - slice(ssize_t start_, ssize_t stop_, ssize_t step_) { - int_ start(start_), stop(stop_), step(step_); + slice(handle start, handle stop, handle step) { m_ptr = PySlice_New(start.ptr(), stop.ptr(), step.ptr()); - if (!m_ptr) pybind11_fail("Could not allocate slice object!"); + if (!m_ptr) + pybind11_fail("Could not allocate slice object!"); } + +#ifdef PYBIND11_HAS_OPTIONAL + slice(std::optional start, std::optional stop, std::optional step) + : slice(index_to_object(start), index_to_object(stop), index_to_object(step)) {} +#else + slice(ssize_t start_, ssize_t stop_, ssize_t step_) + : slice(int_(start_), int_(stop_), int_(step_)) {} +#endif + bool compute(size_t length, size_t *start, size_t *stop, size_t *step, size_t *slicelength) const { return PySlice_GetIndicesEx((PYBIND11_SLICE_OBJECT *) m_ptr, @@ -1183,6 +1418,12 @@ public: stop, step, slicelength) == 0; } + +private: + template + static object index_to_object(T index) { + return index ? object(int_(*index)) : object(none()); + } }; class capsule : public object { @@ -1218,7 +1459,7 @@ public: pybind11_fail("Could not set capsule context!"); } - capsule(void (*destructor)()) { + explicit capsule(void (*destructor)()) { m_ptr = PyCapsule_New(reinterpret_cast(destructor), nullptr, [](PyObject *o) { auto destructor = reinterpret_cast(PyCapsule_GetPointer(o, nullptr)); destructor(); @@ -1228,20 +1469,41 @@ public: pybind11_fail("Could not allocate capsule object!"); } + // NOLINTNEXTLINE(google-explicit-constructor) template operator T *() const { + return get_pointer(); + } + + /// Get the pointer the capsule holds. + template + T* get_pointer() const { auto name = this->name(); - T * result = static_cast(PyCapsule_GetPointer(m_ptr, name)); - if (!result) pybind11_fail("Unable to extract capsule contents!"); + T *result = static_cast(PyCapsule_GetPointer(m_ptr, name)); + if (!result) { + PyErr_Clear(); + pybind11_fail("Unable to extract capsule contents!"); + } return result; } + /// Replaces a capsule's pointer *without* calling the destructor on the existing one. + void set_pointer(const void *value) { + if (PyCapsule_SetPointer(m_ptr, const_cast(value)) != 0) { + PyErr_Clear(); + pybind11_fail("Could not set capsule pointer"); + } + } + const char *name() const { return PyCapsule_GetName(m_ptr); } }; class tuple : public object { public: PYBIND11_OBJECT_CVT(tuple, object, PyTuple_Check, PySequence_Tuple) - explicit tuple(size_t size = 0) : object(PyTuple_New((ssize_t) size), stolen_t{}) { + template ::value, int> = 0> + // Some compilers generate link errors when using `const SzType &` here: + explicit tuple(SzType size = 0) : object(PyTuple_New(ssize_t_cast(size)), stolen_t{}) { if (!m_ptr) pybind11_fail("Could not allocate tuple object!"); } size_t size() const { return (size_t) PyTuple_Size(m_ptr); } @@ -1252,6 +1514,15 @@ public: detail::tuple_iterator end() const { return {*this, PyTuple_GET_SIZE(m_ptr)}; } }; +// We need to put this into a separate function because the Intel compiler +// fails to compile enable_if_t...>::value> part below +// (tested with ICC 2021.1 Beta 20200827). +template +constexpr bool args_are_all_keyword_or_ds() +{ + return detail::all_of...>::value; +} + class dict : public object { public: PYBIND11_OBJECT_CVT(dict, object, PyDict_Check, raw_dict) @@ -1259,7 +1530,7 @@ public: if (!m_ptr) pybind11_fail("Could not allocate dict object!"); } template ...>::value>, + typename = detail::enable_if_t()>, // MSVC workaround: it can't compile an out-of-line definition, so defer the collector typename collector = detail::deferred_t, Args...>> explicit dict(Args &&...args) : dict(collector(std::forward(args)...).kwargs()) { } @@ -1268,7 +1539,7 @@ public: bool empty() const { return size() == 0; } detail::dict_iterator begin() const { return {*this, 0}; } detail::dict_iterator end() const { return {}; } - void clear() const { PyDict_Clear(ptr()); } + void clear() /* py-non-const */ { PyDict_Clear(ptr()); } template bool contains(T &&key) const { return PyDict_Contains(m_ptr, detail::object_or_cast(std::forward(key)).ptr()) == 1; } @@ -1301,7 +1572,10 @@ public: class list : public object { public: PYBIND11_OBJECT_CVT(list, object, PyList_Check, PySequence_List) - explicit list(size_t size = 0) : object(PyList_New((ssize_t) size), stolen_t{}) { + template ::value, int> = 0> + // Some compilers generate link errors when using `const SzType &` here: + explicit list(SzType size = 0) : object(PyList_New(ssize_t_cast(size)), stolen_t{}) { if (!m_ptr) pybind11_fail("Could not allocate list object!"); } size_t size() const { return (size_t) PyList_Size(m_ptr); } @@ -1310,12 +1584,15 @@ public: detail::item_accessor operator[](handle h) const { return object::operator[](h); } detail::list_iterator begin() const { return {*this, 0}; } detail::list_iterator end() const { return {*this, PyList_GET_SIZE(m_ptr)}; } - template void append(T &&val) const { + template void append(T &&val) /* py-non-const */ { PyList_Append(m_ptr, detail::object_or_cast(std::forward(val)).ptr()); } - template void insert(size_t index, T &&val) const { - PyList_Insert(m_ptr, static_cast(index), - detail::object_or_cast(std::forward(val)).ptr()); + template ::value, int> = 0> + void insert(const IdxType &index, ValType &&val) /* py-non-const */ { + PyList_Insert( + m_ptr, ssize_t_cast(index), detail::object_or_cast(std::forward(val)).ptr()); } }; @@ -1330,10 +1607,10 @@ public: } size_t size() const { return (size_t) PySet_Size(m_ptr); } bool empty() const { return size() == 0; } - template bool add(T &&val) const { + template bool add(T &&val) /* py-non-const */ { return PySet_Add(m_ptr, detail::object_or_cast(std::forward(val)).ptr()) == 0; } - void clear() const { PySet_Clear(m_ptr); } + void clear() /* py-non-const */ { PySet_Clear(m_ptr); } template bool contains(T &&val) const { return PySet_Contains(m_ptr, detail::object_or_cast(std::forward(val)).ptr()) == 1; } @@ -1429,7 +1706,7 @@ public: detail::any_container shape, detail::any_container strides) { return memoryview::from_buffer( - const_cast(ptr), itemsize, format, shape, strides, true); + const_cast(ptr), itemsize, format, std::move(shape), std::move(strides), true); } template @@ -1475,10 +1752,17 @@ public: static memoryview from_memory(const void *mem, ssize_t size) { return memoryview::from_memory(const_cast(mem), size, true); } + +#ifdef PYBIND11_HAS_STRING_VIEW + static memoryview from_memory(std::string_view mem) { + return from_memory(const_cast(mem.data()), static_cast(mem.size()), true); + } +#endif + #endif }; -#ifndef DOXYGEN_SHOULD_SKIP_THIS +/// @cond DUPLICATE inline memoryview memoryview::from_buffer( void *ptr, ssize_t itemsize, const char* format, detail::any_container shape, @@ -1486,7 +1770,7 @@ inline memoryview memoryview::from_buffer( size_t ndim = shape->size(); if (ndim != strides->size()) pybind11_fail("memoryview: shape length doesn't match strides length"); - ssize_t size = ndim ? 1 : 0; + ssize_t size = ndim != 0u ? 1 : 0; for (size_t i = 0; i < ndim; ++i) size *= (*shape)[i]; Py_buffer view; @@ -1506,18 +1790,22 @@ inline memoryview memoryview::from_buffer( throw error_already_set(); return memoryview(object(obj, stolen_t{})); } -#endif // DOXYGEN_SHOULD_SKIP_THIS +/// @endcond /// @} pytypes /// \addtogroup python_builtins /// @{ + +/// Get the length of a Python object. inline size_t len(handle h) { ssize_t result = PyObject_Length(h.ptr()); if (result < 0) - pybind11_fail("Unable to compute length of object"); + throw error_already_set(); return (size_t) result; } +/// Get the length hint of a Python object. +/// Returns 0 when this cannot be determined. inline size_t len_hint(handle h) { #if PY_VERSION_HEX >= 0x03040000 ssize_t result = PyObject_LengthHint(h.ptr(), 0); @@ -1580,8 +1868,7 @@ template str_attr_accessor object_api::doc() const { return attr("__doc__"); } template -PYBIND11_DEPRECATED("Use py::type::of(h) instead of h.get_type()") -handle object_api::get_type() const { return type::handle_of(*this); } +handle object_api::get_type() const { return type::handle_of(derived()); } template bool object_api::rich_compare(object_api const &other, int value) const { diff --git a/pybind11/include/pybind11/stl.h b/pybind11/include/pybind11/stl.h index 721bb669f..430349482 100644 --- a/pybind11/include/pybind11/stl.h +++ b/pybind11/include/pybind11/stl.h @@ -9,6 +9,7 @@ #pragma once +#include "detail/common.h" #include "pybind11.h" #include #include @@ -19,33 +20,15 @@ #include #include -#if defined(_MSC_VER) -#pragma warning(push) -#pragma warning(disable: 4127) // warning C4127: Conditional expression is constant +// See `detail/common.h` for implementation of these guards. +#if defined(PYBIND11_HAS_OPTIONAL) +# include +#elif defined(PYBIND11_HAS_EXP_OPTIONAL) +# include #endif -#ifdef __has_include -// std::optional (but including it in c++14 mode isn't allowed) -# if defined(PYBIND11_CPP17) && __has_include() -# include -# define PYBIND11_HAS_OPTIONAL 1 -# endif -// std::experimental::optional (but not allowed in c++11 mode) -# if defined(PYBIND11_CPP14) && (__has_include() && \ - !__has_include()) -# include -# define PYBIND11_HAS_EXP_OPTIONAL 1 -# endif -// std::variant -# if defined(PYBIND11_CPP17) && __has_include() -# include -# define PYBIND11_HAS_VARIANT 1 -# endif -#elif defined(_MSC_VER) && defined(PYBIND11_CPP17) -# include +#if defined(PYBIND11_HAS_VARIANT) # include -# define PYBIND11_HAS_OPTIONAL 1 -# define PYBIND11_HAS_VARIANT 1 #endif PYBIND11_NAMESPACE_BEGIN(PYBIND11_NAMESPACE) @@ -95,7 +78,7 @@ template struct set_caster { return s.release(); } - PYBIND11_TYPE_CASTER(type, _("Set[") + key_conv::name + _("]")); + PYBIND11_TYPE_CASTER(type, const_name("Set[") + key_conv::name + const_name("]")); }; template struct map_caster { @@ -137,14 +120,14 @@ template struct map_caster { return d.release(); } - PYBIND11_TYPE_CASTER(Type, _("Dict[") + key_conv::name + _(", ") + value_conv::name + _("]")); + PYBIND11_TYPE_CASTER(Type, const_name("Dict[") + key_conv::name + const_name(", ") + value_conv::name + const_name("]")); }; template struct list_caster { using value_conv = make_caster; bool load(handle src, bool convert) { - if (!isinstance(src) || isinstance(src)) + if (!isinstance(src) || isinstance(src) || isinstance(src)) return false; auto s = reinterpret_borrow(src); value.clear(); @@ -159,10 +142,13 @@ template struct list_caster { } private: - template ().reserve(0)), void>::value, int> = 0> - void reserve_maybe(sequence s, Type *) { value.reserve(s.size()); } - void reserve_maybe(sequence, void *) { } + template < + typename T = Type, + enable_if_t().reserve(0)), void>::value, int> = 0> + void reserve_maybe(const sequence &s, Type *) { + value.reserve(s.size()); + } + void reserve_maybe(const sequence &, void *) {} public: template @@ -170,17 +156,17 @@ public: if (!std::is_lvalue_reference::value) policy = return_value_policy_override::policy(policy); list l(src.size()); - size_t index = 0; + ssize_t index = 0; for (auto &&value : src) { auto value_ = reinterpret_steal(value_conv::cast(forward_like(value), policy, parent)); if (!value_) return handle(); - PyList_SET_ITEM(l.ptr(), (ssize_t) index++, value_.release().ptr()); // steals a reference + PyList_SET_ITEM(l.ptr(), index++, value_.release().ptr()); // steals a reference } return l.release(); } - PYBIND11_TYPE_CASTER(Type, _("List[") + value_conv::name + _("]")); + PYBIND11_TYPE_CASTER(Type, const_name("List[") + value_conv::name + const_name("]")); }; template struct type_caster> @@ -227,17 +213,17 @@ public: template static handle cast(T &&src, return_value_policy policy, handle parent) { list l(src.size()); - size_t index = 0; + ssize_t index = 0; for (auto &&value : src) { auto value_ = reinterpret_steal(value_conv::cast(forward_like(value), policy, parent)); if (!value_) return handle(); - PyList_SET_ITEM(l.ptr(), (ssize_t) index++, value_.release().ptr()); // steals a reference + PyList_SET_ITEM(l.ptr(), index++, value_.release().ptr()); // steals a reference } return l.release(); } - PYBIND11_TYPE_CASTER(ArrayType, _("List[") + value_conv::name + _(_(""), _("[") + _() + _("]")) + _("]")); + PYBIND11_TYPE_CASTER(ArrayType, const_name("List[") + value_conv::name + const_name(const_name(""), const_name("[") + const_name() + const_name("]")) + const_name("]")); }; template struct type_caster> @@ -259,34 +245,35 @@ template , Key, Value> { }; // This type caster is intended to be used for std::optional and std::experimental::optional -template struct optional_caster { - using value_conv = make_caster; +template struct optional_caster { + using value_conv = make_caster; - template - static handle cast(T_ &&src, return_value_policy policy, handle parent) { + template + static handle cast(T &&src, return_value_policy policy, handle parent) { if (!src) return none().inc_ref(); if (!std::is_lvalue_reference::value) { - policy = return_value_policy_override::policy(policy); + policy = return_value_policy_override::policy(policy); } - return value_conv::cast(*std::forward(src), policy, parent); + return value_conv::cast(*std::forward(src), policy, parent); } bool load(handle src, bool convert) { if (!src) { return false; - } else if (src.is_none()) { + } + if (src.is_none()) { return true; // default-constructed value is already empty } value_conv inner_caster; if (!inner_caster.load(src, convert)) return false; - value.emplace(cast_op(std::move(inner_caster))); + value.emplace(cast_op(std::move(inner_caster))); return true; } - PYBIND11_TYPE_CASTER(T, _("Optional[") + value_conv::name + _("]")); + PYBIND11_TYPE_CASTER(Type, const_name("Optional[") + value_conv::name + const_name("]")); }; #if defined(PYBIND11_HAS_OPTIONAL) @@ -366,7 +353,7 @@ struct variant_caster> { } using Type = V; - PYBIND11_TYPE_CASTER(Type, _("Union[") + detail::concat(make_caster::name...) + _("]")); + PYBIND11_TYPE_CASTER(Type, const_name("Union[") + detail::concat(make_caster::name...) + const_name("]")); }; #if defined(PYBIND11_HAS_VARIANT) @@ -377,12 +364,12 @@ struct type_caster> : variant_caster> { PYBIND11_NAMESPACE_END(detail) inline std::ostream &operator<<(std::ostream &os, const handle &obj) { +#ifdef PYBIND11_HAS_STRING_VIEW + os << str(obj).cast(); +#else os << (std::string) str(obj); +#endif return os; } PYBIND11_NAMESPACE_END(PYBIND11_NAMESPACE) - -#if defined(_MSC_VER) -#pragma warning(pop) -#endif diff --git a/pybind11/include/pybind11/stl/filesystem.h b/pybind11/include/pybind11/stl/filesystem.h new file mode 100644 index 000000000..a9a6c8512 --- /dev/null +++ b/pybind11/include/pybind11/stl/filesystem.h @@ -0,0 +1,103 @@ +// Copyright (c) 2021 The Pybind Development Team. +// All rights reserved. Use of this source code is governed by a +// BSD-style license that can be found in the LICENSE file. + +#pragma once + +#include "../cast.h" +#include "../pybind11.h" +#include "../pytypes.h" + +#include "../detail/common.h" +#include "../detail/descr.h" + +#include + +#ifdef __has_include +# if defined(PYBIND11_CPP17) && __has_include() && \ + PY_VERSION_HEX >= 0x03060000 +# include +# define PYBIND11_HAS_FILESYSTEM 1 +# endif +#endif + +#if !defined(PYBIND11_HAS_FILESYSTEM) && !defined(PYBIND11_HAS_FILESYSTEM_IS_OPTIONAL) +# error \ + "#include is not available. (Use -DPYBIND11_HAS_FILESYSTEM_IS_OPTIONAL to ignore.)" +#endif + +PYBIND11_NAMESPACE_BEGIN(PYBIND11_NAMESPACE) +PYBIND11_NAMESPACE_BEGIN(detail) + +#if defined(PYBIND11_HAS_FILESYSTEM) +template struct path_caster { + +private: + static PyObject* unicode_from_fs_native(const std::string& w) { +#if !defined(PYPY_VERSION) + return PyUnicode_DecodeFSDefaultAndSize(w.c_str(), ssize_t(w.size())); +#else + // PyPy mistakenly declares the first parameter as non-const. + return PyUnicode_DecodeFSDefaultAndSize( + const_cast(w.c_str()), ssize_t(w.size())); +#endif + } + + static PyObject* unicode_from_fs_native(const std::wstring& w) { + return PyUnicode_FromWideChar(w.c_str(), ssize_t(w.size())); + } + +public: + static handle cast(const T& path, return_value_policy, handle) { + if (auto py_str = unicode_from_fs_native(path.native())) { + return module_::import("pathlib").attr("Path")(reinterpret_steal(py_str)) + .release(); + } + return nullptr; + } + + bool load(handle handle, bool) { + // PyUnicode_FSConverter and PyUnicode_FSDecoder normally take care of + // calling PyOS_FSPath themselves, but that's broken on PyPy (PyPy + // issue #3168) so we do it ourselves instead. + PyObject* buf = PyOS_FSPath(handle.ptr()); + if (!buf) { + PyErr_Clear(); + return false; + } + PyObject* native = nullptr; + if constexpr (std::is_same_v) { + if (PyUnicode_FSConverter(buf, &native) != 0) { + if (auto c_str = PyBytes_AsString(native)) { + // AsString returns a pointer to the internal buffer, which + // must not be free'd. + value = c_str; + } + } + } else if constexpr (std::is_same_v) { + if (PyUnicode_FSDecoder(buf, &native) != 0) { + if (auto c_str = PyUnicode_AsWideCharString(native, nullptr)) { + // AsWideCharString returns a new string that must be free'd. + value = c_str; // Copies the string. + PyMem_Free(c_str); + } + } + } + Py_XDECREF(native); + Py_DECREF(buf); + if (PyErr_Occurred()) { + PyErr_Clear(); + return false; + } + return true; + } + + PYBIND11_TYPE_CASTER(T, const_name("os.PathLike")); +}; + +template<> struct type_caster + : public path_caster {}; +#endif // PYBIND11_HAS_FILESYSTEM + +PYBIND11_NAMESPACE_END(detail) +PYBIND11_NAMESPACE_END(PYBIND11_NAMESPACE) diff --git a/pybind11/include/pybind11/stl_bind.h b/pybind11/include/pybind11/stl_bind.h index 9d8ed0c82..050be83cc 100644 --- a/pybind11/include/pybind11/stl_bind.h +++ b/pybind11/include/pybind11/stl_bind.h @@ -128,11 +128,11 @@ void vector_modifiers(enable_if_t(new Vector()); v->reserve(len_hint(it)); for (handle h : it) - v->push_back(h.cast()); + v->push_back(h.cast()); return v.release(); })); @@ -151,27 +151,28 @@ void vector_modifiers(enable_if_t()); - } - } catch (const cast_error &) { - v.erase(v.begin() + static_cast(old_size), v.end()); - try { - v.shrink_to_fit(); - } catch (const std::exception &) { - // Do nothing - } - throw; - } - }, - arg("L"), - "Extend the list by appending all the items in the given list" - ); + cl.def( + "extend", + [](Vector &v, const iterable &it) { + const size_t old_size = v.size(); + v.reserve(old_size + len_hint(it)); + try { + for (handle h : it) { + v.push_back(h.cast()); + } + } catch (const cast_error &) { + v.erase(v.begin() + static_cast(old_size), + v.end()); + try { + v.shrink_to_fit(); + } catch (const std::exception &) { + // Do nothing + } + throw; + } + }, + arg("L"), + "Extend the list by appending all the items in the given list"); cl.def("insert", [](Vector &v, DiffType i, const T &x) { @@ -190,7 +191,7 @@ void vector_modifiers(enable_if_t Vector * { - size_t start, stop, step, slicelength; + size_t start = 0, stop = 0, step = 0, slicelength = 0; if (!slice.compute(v.size(), &start, &stop, &step, &slicelength)) throw error_already_set(); @@ -233,12 +235,12 @@ void vector_modifiers(enable_if_t), @@ -375,10 +375,20 @@ struct vector_has_data_and_format : std::false_type {}; template struct vector_has_data_and_format::format(), std::declval().data()), typename Vector::value_type*>::value>> : std::true_type {}; +// [workaround(intel)] Separate function required here +// Workaround as the Intel compiler does not compile the enable_if_t part below +// (tested with icc (ICC) 2021.1 Beta 20200827) +template +constexpr bool args_any_are_buffer() { + return detail::any_of...>::value; +} + +// [workaround(intel)] Separate function required here +// [workaround(msvc)] Can't use constexpr bool in return type + // Add the buffer interface to a vector template -enable_if_t...>::value> -vector_buffer(Class_& cl) { +void vector_buffer_impl(Class_& cl, std::true_type) { using T = typename Vector::value_type; static_assert(vector_has_data_and_format::value, "There is not an appropriate format descriptor for this vector"); @@ -390,7 +400,7 @@ vector_buffer(Class_& cl) { return buffer_info(v.data(), static_cast(sizeof(T)), format_descriptor::format(), 1, {v.size()}, {sizeof(T)}); }); - cl.def(init([](buffer buf) { + cl.def(init([](const buffer &buf) { auto info = buf.request(); if (info.ndim != 1 || info.strides[0] % static_cast(sizeof(T))) throw type_error("Only valid 1D buffers can be copied to a vector"); @@ -403,20 +413,24 @@ vector_buffer(Class_& cl) { if (step == 1) { return Vector(p, end); } - else { - Vector vec; - vec.reserve((size_t) info.shape[0]); - for (; p != end; p += step) - vec.push_back(*p); - return vec; - } + Vector vec; + vec.reserve((size_t) info.shape[0]); + for (; p != end; p += step) + vec.push_back(*p); + return vec; + })); return; } template -enable_if_t...>::value> vector_buffer(Class_&) {} +void vector_buffer_impl(Class_&, std::false_type) {} + +template +void vector_buffer(Class_& cl) { + vector_buffer_impl(cl, detail::any_of...>{}); +} PYBIND11_NAMESPACE_END(detail) @@ -581,6 +595,23 @@ template auto map_if_insertion_operator(Class_ & ); } +template +struct keys_view +{ + Map ↦ +}; + +template +struct values_view +{ + Map ↦ +}; + +template +struct items_view +{ + Map ↦ +}; PYBIND11_NAMESPACE_END(detail) @@ -588,6 +619,9 @@ template , typename... class_ bind_map(handle scope, const std::string &name, Args&&... args) { using KeyType = typename Map::key_type; using MappedType = typename Map::mapped_type; + using KeysView = detail::keys_view; + using ValuesView = detail::values_view; + using ItemsView = detail::items_view; using Class_ = class_; // If either type is a non-module-local bound type then make the map binding non-local as well; @@ -601,6 +635,12 @@ class_ bind_map(handle scope, const std::string &name, Args&&. } Class_ cl(scope, name.c_str(), pybind11::module_local(local), std::forward(args)...); + class_ keys_view( + scope, ("KeysView[" + name + "]").c_str(), pybind11::module_local(local)); + class_ values_view( + scope, ("ValuesView[" + name + "]").c_str(), pybind11::module_local(local)); + class_ items_view( + scope, ("ItemsView[" + name + "]").c_str(), pybind11::module_local(local)); cl.def(init<>()); @@ -614,12 +654,22 @@ class_ bind_map(handle scope, const std::string &name, Args&&. cl.def("__iter__", [](Map &m) { return make_key_iterator(m.begin(), m.end()); }, - keep_alive<0, 1>() /* Essential: keep list alive while iterator exists */ + keep_alive<0, 1>() /* Essential: keep map alive while iterator exists */ + ); + + cl.def("keys", + [](Map &m) { return KeysView{m}; }, + keep_alive<0, 1>() /* Essential: keep map alive while view exists */ + ); + + cl.def("values", + [](Map &m) { return ValuesView{m}; }, + keep_alive<0, 1>() /* Essential: keep map alive while view exists */ ); cl.def("items", - [](Map &m) { return make_iterator(m.begin(), m.end()); }, - keep_alive<0, 1>() /* Essential: keep list alive while iterator exists */ + [](Map &m) { return ItemsView{m}; }, + keep_alive<0, 1>() /* Essential: keep map alive while view exists */ ); cl.def("__getitem__", @@ -640,6 +690,8 @@ class_ bind_map(handle scope, const std::string &name, Args&&. return true; } ); + // Fallback for when the object is not of the key type + cl.def("__contains__", [](Map &, const object &) -> bool { return false; }); // Assignment provided only if the type is copyable detail::map_assignment(cl); @@ -655,6 +707,40 @@ class_ bind_map(handle scope, const std::string &name, Args&&. cl.def("__len__", &Map::size); + keys_view.def("__len__", [](KeysView &view) { return view.map.size(); }); + keys_view.def("__iter__", + [](KeysView &view) { + return make_key_iterator(view.map.begin(), view.map.end()); + }, + keep_alive<0, 1>() /* Essential: keep view alive while iterator exists */ + ); + keys_view.def("__contains__", + [](KeysView &view, const KeyType &k) -> bool { + auto it = view.map.find(k); + if (it == view.map.end()) + return false; + return true; + } + ); + // Fallback for when the object is not of the key type + keys_view.def("__contains__", [](KeysView &, const object &) -> bool { return false; }); + + values_view.def("__len__", [](ValuesView &view) { return view.map.size(); }); + values_view.def("__iter__", + [](ValuesView &view) { + return make_value_iterator(view.map.begin(), view.map.end()); + }, + keep_alive<0, 1>() /* Essential: keep view alive while iterator exists */ + ); + + items_view.def("__len__", [](ItemsView &view) { return view.map.size(); }); + items_view.def("__iter__", + [](ItemsView &view) { + return make_iterator(view.map.begin(), view.map.end()); + }, + keep_alive<0, 1>() /* Essential: keep view alive while iterator exists */ + ); + return cl; } diff --git a/pybind11/noxfile.py b/pybind11/noxfile.py new file mode 100644 index 000000000..4adffac2e --- /dev/null +++ b/pybind11/noxfile.py @@ -0,0 +1,93 @@ +import nox + +nox.options.sessions = ["lint", "tests", "tests_packaging"] + +PYTHON_VERISONS = ["2.7", "3.5", "3.6", "3.7", "3.8", "3.9", "3.10", "3.11"] + + +@nox.session(reuse_venv=True) +def lint(session: nox.Session) -> None: + """ + Lint the codebase (except for clang-format/tidy). + """ + session.install("pre-commit") + session.run("pre-commit", "run", "-a") + + +@nox.session(python=PYTHON_VERISONS) +def tests(session: nox.Session) -> None: + """ + Run the tests (requires a compiler). + """ + tmpdir = session.create_tmp() + session.install("cmake") + session.install("-r", "tests/requirements.txt") + session.run( + "cmake", + "-S", + ".", + "-B", + tmpdir, + "-DPYBIND11_WERROR=ON", + "-DDOWNLOAD_CATCH=ON", + "-DDOWNLOAD_EIGEN=ON", + *session.posargs + ) + session.run("cmake", "--build", tmpdir) + session.run("cmake", "--build", tmpdir, "--config=Release", "--target", "check") + + +@nox.session +def tests_packaging(session: nox.Session) -> None: + """ + Run the packaging tests. + """ + + session.install("-r", "tests/requirements.txt", "--prefer-binary") + session.run("pytest", "tests/extra_python_package") + + +@nox.session(reuse_venv=True) +def docs(session: nox.Session) -> None: + """ + Build the docs. Pass "serve" to serve. + """ + + session.install("-r", "docs/requirements.txt") + session.chdir("docs") + + if "pdf" in session.posargs: + session.run("sphinx-build", "-b", "latexpdf", ".", "_build") + return + + session.run("sphinx-build", "-b", "html", ".", "_build") + + if "serve" in session.posargs: + session.log("Launching docs at http://localhost:8000/ - use Ctrl-C to quit") + session.run("python", "-m", "http.server", "8000", "-d", "_build/html") + elif session.posargs: + session.error("Unsupported argument to docs") + + +@nox.session(reuse_venv=True) +def make_changelog(session: nox.Session) -> None: + """ + Inspect the closed issues and make entries for a changelog. + """ + session.install("ghapi", "rich") + session.run("python", "tools/make_changelog.py") + + +@nox.session(reuse_venv=True) +def build(session: nox.Session) -> None: + """ + Build SDists and wheels. + """ + + session.install("build") + session.log("Building normal files") + session.run("python", "-m", "build", *session.posargs) + session.log("Building pybind11-global files (PYBIND11_GLOBAL_SDIST=1)") + session.run( + "python", "-m", "build", *session.posargs, env={"PYBIND11_GLOBAL_SDIST": "1"} + ) diff --git a/pybind11/pybind11/__init__.py b/pybind11/pybind11/__init__.py index ad6542089..64e999ba0 100644 --- a/pybind11/pybind11/__init__.py +++ b/pybind11/pybind11/__init__.py @@ -1,8 +1,7 @@ # -*- coding: utf-8 -*- -from ._version import version_info, __version__ -from .commands import get_include, get_cmake_dir - +from ._version import __version__, version_info +from .commands import get_cmake_dir, get_include __all__ = ( "version_info", diff --git a/pybind11/pybind11/__main__.py b/pybind11/pybind11/__main__.py index f4d543783..3235747be 100644 --- a/pybind11/pybind11/__main__.py +++ b/pybind11/pybind11/__main__.py @@ -5,10 +5,11 @@ import argparse import sys import sysconfig -from .commands import get_include, get_cmake_dir +from .commands import get_cmake_dir, get_include def print_includes(): + # type: () -> None dirs = [ sysconfig.get_path("include"), sysconfig.get_path("platinclude"), @@ -18,13 +19,15 @@ def print_includes(): # Make unique but preserve order unique_dirs = [] for d in dirs: - if d not in unique_dirs: + if d and d not in unique_dirs: unique_dirs.append(d) print(" ".join("-I" + d for d in unique_dirs)) def main(): + # type: () -> None + parser = argparse.ArgumentParser() parser.add_argument( "--includes", diff --git a/pybind11/pybind11/_version.py b/pybind11/pybind11/_version.py index ca84c262c..9d39b77a4 100644 --- a/pybind11/pybind11/_version.py +++ b/pybind11/pybind11/_version.py @@ -8,5 +8,5 @@ def _to_int(s): return s -__version__ = "2.6.0.dev1" +__version__ = "2.9.1" version_info = tuple(_to_int(s) for s in __version__.split(".")) diff --git a/pybind11/pybind11/_version.pyi b/pybind11/pybind11/_version.pyi new file mode 100644 index 000000000..d45e5dc90 --- /dev/null +++ b/pybind11/pybind11/_version.pyi @@ -0,0 +1,6 @@ +from typing import Tuple, Union + +def _to_int(s: str) -> Union[int, str]: ... + +__version__: str +version_info: Tuple[Union[int, str], ...] diff --git a/pybind11/pybind11/commands.py b/pybind11/pybind11/commands.py index fa7eac3cc..11f81d2d6 100644 --- a/pybind11/pybind11/commands.py +++ b/pybind11/pybind11/commands.py @@ -1,17 +1,18 @@ # -*- coding: utf-8 -*- import os - DIR = os.path.abspath(os.path.dirname(__file__)) def get_include(user=False): + # type: (bool) -> str installed_path = os.path.join(DIR, "include") source_path = os.path.join(os.path.dirname(DIR), "include") return installed_path if os.path.exists(installed_path) else source_path def get_cmake_dir(): + # type: () -> str cmake_installed_path = os.path.join(DIR, "share", "cmake", "pybind11") if os.path.exists(cmake_installed_path): return cmake_installed_path diff --git a/pybind11/pybind11/py.typed b/pybind11/pybind11/py.typed new file mode 100644 index 000000000..e69de29bb diff --git a/pybind11/pybind11/setup_helpers.py b/pybind11/pybind11/setup_helpers.py index 041e22689..5b7c9aab1 100644 --- a/pybind11/pybind11/setup_helpers.py +++ b/pybind11/pybind11/setup_helpers.py @@ -33,25 +33,34 @@ OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. """ +# IMPORTANT: If you change this file in the pybind11 repo, also review +# setup_helpers.pyi for matching changes. +# +# If you copy this file in, you don't +# need the .pyi file; it's just an interface file for static type checkers. + import contextlib import os +import platform +import shlex import shutil import sys +import sysconfig import tempfile import threading import warnings try: - from setuptools.command.build_ext import build_ext as _build_ext from setuptools import Extension as _Extension + from setuptools.command.build_ext import build_ext as _build_ext except ImportError: from distutils.command.build_ext import build_ext as _build_ext from distutils.extension import Extension as _Extension +import distutils.ccompiler import distutils.errors - -WIN = sys.platform.startswith("win32") +WIN = sys.platform.startswith("win32") and "mingw" not in sysconfig.get_platform() PY2 = sys.version_info[0] < 3 MACOS = sys.platform.startswith("darwin") STD_TMPL = "/std:c++{}" if WIN else "-std=c++{}" @@ -76,7 +85,7 @@ class Pybind11Extension(_Extension): * ``stdlib=libc++`` on macOS * ``visibility=hidden`` and ``-g0`` on Unix - Finally, you can set ``cxx_std`` via constructor or afterwords to enable + Finally, you can set ``cxx_std`` via constructor or afterwards to enable flags for C++ std, and a few extra helper flags related to the C++ standard level. It is _highly_ recommended you either set this, or use the provided ``build_ext``, which will search for the highest supported extension for @@ -91,15 +100,14 @@ class Pybind11Extension(_Extension): this is an ugly old-style class due to Distutils. """ - def _add_cflags(self, *flags): - for flag in flags: - if flag not in self.extra_compile_args: - self.extra_compile_args.append(flag) + # flags are prepended, so that they can be further overridden, e.g. by + # ``extra_compile_args=["-g"]``. - def _add_lflags(self, *flags): - for flag in flags: - if flag not in self.extra_compile_args: - self.extra_link_args.append(flag) + def _add_cflags(self, flags): + self.extra_compile_args[:0] = flags + + def _add_ldflags(self, flags): + self.extra_link_args[:0] = flags def __init__(self, *args, **kwargs): @@ -131,13 +139,22 @@ class Pybind11Extension(_Extension): # Have to use the accessor manually to support Python 2 distutils Pybind11Extension.cxx_std.__set__(self, cxx_std) + cflags = [] + ldflags = [] if WIN: - self._add_cflags("/EHsc", "/bigobj") + cflags += ["/EHsc", "/bigobj"] else: - self._add_cflags("-fvisibility=hidden", "-g0") + cflags += ["-fvisibility=hidden"] + env_cflags = os.environ.get("CFLAGS", "") + env_cppflags = os.environ.get("CPPFLAGS", "") + c_cpp_flags = shlex.split(env_cflags) + shlex.split(env_cppflags) + if not any(opt.startswith("-g") for opt in c_cpp_flags): + cflags += ["-g0"] if MACOS: - self._add_cflags("-stdlib=libc++") - self._add_lflags("-stdlib=libc++") + cflags += ["-stdlib=libc++"] + ldflags += ["-stdlib=libc++"] + self._add_cflags(cflags) + self._add_ldflags(ldflags) @property def cxx_std(self): @@ -156,7 +173,8 @@ class Pybind11Extension(_Extension): if self._cxx_level: warnings.warn("You cannot safely change the cxx_level after setting it!") - # MSVC 2015 Update 3 and later only have 14 (and later 17) modes + # MSVC 2015 Update 3 and later only have 14 (and later 17) modes, so + # force a valid flag here. if WIN and level == 11: level = 14 @@ -165,19 +183,34 @@ class Pybind11Extension(_Extension): if not level: return - self.extra_compile_args.append(STD_TMPL.format(level)) + cflags = [STD_TMPL.format(level)] + ldflags = [] if MACOS and "MACOSX_DEPLOYMENT_TARGET" not in os.environ: - # C++17 requires a higher min version of macOS - macosx_min = "-mmacosx-version-min=" + ("10.9" if level < 17 else "10.14") - self.extra_compile_args.append(macosx_min) - self.extra_link_args.append(macosx_min) + # C++17 requires a higher min version of macOS. An earlier version + # (10.12 or 10.13) can be set manually via environment variable if + # you are careful in your feature usage, but 10.14 is the safest + # setting for general use. However, never set higher than the + # current macOS version! + current_macos = tuple(int(x) for x in platform.mac_ver()[0].split(".")[:2]) + desired_macos = (10, 9) if level < 17 else (10, 14) + macos_string = ".".join(str(x) for x in min(current_macos, desired_macos)) + macosx_min = "-mmacosx-version-min=" + macos_string + cflags += [macosx_min] + ldflags += [macosx_min] if PY2: - if level >= 17: - self.extra_compile_args.append("/wd503" if WIN else "-Wno-register") - elif not WIN and level >= 14: - self.extra_compile_args.append("-Wno-deprecated-register") + if WIN: + # Will be ignored on MSVC 2015, where C++17 is not supported so + # this flag is not valid. + cflags += ["/wd5033"] + elif level >= 17: + cflags += ["-Wno-register"] + elif level >= 14: + cflags += ["-Wno-deprecated-register"] + + self._add_cflags(cflags) + self._add_ldflags(ldflags) # Just in case someone clever tries to multithread @@ -212,7 +245,8 @@ def has_flag(compiler, flag): with tmp_chdir(): fname = "flagcheck.cpp" with open(fname, "w") as f: - f.write("int main (int argc, char **argv) { return 0; }") + # Don't trigger -Wunused-parameter. + f.write("int main (int, char **) { return 0; }") try: compiler.compile([fname], extra_postargs=[flag]) @@ -227,9 +261,12 @@ cpp_flag_cache = None def auto_cpp_level(compiler): """ - Return the max supported C++ std level (17, 14, or 11). + Return the max supported C++ std level (17, 14, or 11). Returns latest on Windows. """ + if WIN: + return "latest" + global cpp_flag_cache # If this has been previously calculated with the same args, return that @@ -237,7 +274,7 @@ def auto_cpp_level(compiler): if cpp_flag_cache: return cpp_flag_cache - levels = [17, 14] + ([] if WIN else [11]) + levels = [17, 14, 11] for level in levels: if has_flag(compiler, STD_TMPL.format(level)): @@ -252,7 +289,8 @@ def auto_cpp_level(compiler): class build_ext(_build_ext): # noqa: N801 """ Customized build_ext that allows an auto-search for the highest supported - C++ level for Pybind11Extension. + C++ level for Pybind11Extension. This is only needed for the auto-search + for now, and is completely optional otherwise. """ def build_extensions(self): @@ -268,3 +306,189 @@ class build_ext(_build_ext): # noqa: N801 # Python 2 doesn't allow super here, since distutils uses old-style # classes! _build_ext.build_extensions(self) + + +def intree_extensions(paths, package_dir=None): + """ + Generate Pybind11Extensions from source files directly located in a Python + source tree. + + ``package_dir`` behaves as in ``setuptools.setup``. If unset, the Python + package root parent is determined as the first parent directory that does + not contain an ``__init__.py`` file. + """ + exts = [] + for path in paths: + if package_dir is None: + parent, _ = os.path.split(path) + while os.path.exists(os.path.join(parent, "__init__.py")): + parent, _ = os.path.split(parent) + relname, _ = os.path.splitext(os.path.relpath(path, parent)) + qualified_name = relname.replace(os.path.sep, ".") + exts.append(Pybind11Extension(qualified_name, [path])) + else: + found = False + for prefix, parent in package_dir.items(): + if path.startswith(parent): + found = True + relname, _ = os.path.splitext(os.path.relpath(path, parent)) + qualified_name = relname.replace(os.path.sep, ".") + if prefix: + qualified_name = prefix + "." + qualified_name + exts.append(Pybind11Extension(qualified_name, [path])) + if not found: + raise ValueError( + "path {} is not a child of any of the directories listed " + "in 'package_dir' ({})".format(path, package_dir) + ) + return exts + + +def naive_recompile(obj, src): + """ + This will recompile only if the source file changes. It does not check + header files, so a more advanced function or Ccache is better if you have + editable header files in your package. + """ + return os.stat(obj).st_mtime < os.stat(src).st_mtime + + +def no_recompile(obg, src): + """ + This is the safest but slowest choice (and is the default) - will always + recompile sources. + """ + return True + + +# Optional parallel compile utility +# inspired by: http://stackoverflow.com/questions/11013851/speeding-up-build-process-with-distutils +# and: https://github.com/tbenthompson/cppimport/blob/stable/cppimport/build_module.py +# and NumPy's parallel distutils module: +# https://github.com/numpy/numpy/blob/master/numpy/distutils/ccompiler.py +class ParallelCompile(object): + """ + Make a parallel compile function. Inspired by + numpy.distutils.ccompiler.CCompiler_compile and cppimport. + + This takes several arguments that allow you to customize the compile + function created: + + envvar: + Set an environment variable to control the compilation threads, like + NPY_NUM_BUILD_JOBS + default: + 0 will automatically multithread, or 1 will only multithread if the + envvar is set. + max: + The limit for automatic multithreading if non-zero + needs_recompile: + A function of (obj, src) that returns True when recompile is needed. No + effect in isolated mode; use ccache instead, see + https://github.com/matplotlib/matplotlib/issues/1507/ + + To use:: + + ParallelCompile("NPY_NUM_BUILD_JOBS").install() + + or:: + + with ParallelCompile("NPY_NUM_BUILD_JOBS"): + setup(...) + + By default, this assumes all files need to be recompiled. A smarter + function can be provided via needs_recompile. If the output has not yet + been generated, the compile will always run, and this function is not + called. + """ + + __slots__ = ("envvar", "default", "max", "_old", "needs_recompile") + + def __init__(self, envvar=None, default=0, max=0, needs_recompile=no_recompile): + self.envvar = envvar + self.default = default + self.max = max + self.needs_recompile = needs_recompile + self._old = [] + + def function(self): + """ + Builds a function object usable as distutils.ccompiler.CCompiler.compile. + """ + + def compile_function( + compiler, + sources, + output_dir=None, + macros=None, + include_dirs=None, + debug=0, + extra_preargs=None, + extra_postargs=None, + depends=None, + ): + + # These lines are directly from distutils.ccompiler.CCompiler + macros, objects, extra_postargs, pp_opts, build = compiler._setup_compile( + output_dir, macros, include_dirs, sources, depends, extra_postargs + ) + cc_args = compiler._get_cc_args(pp_opts, debug, extra_preargs) + + # The number of threads; start with default. + threads = self.default + + # Determine the number of compilation threads, unless set by an environment variable. + if self.envvar is not None: + threads = int(os.environ.get(self.envvar, self.default)) + + def _single_compile(obj): + try: + src, ext = build[obj] + except KeyError: + return + + if not os.path.exists(obj) or self.needs_recompile(obj, src): + compiler._compile(obj, src, ext, cc_args, extra_postargs, pp_opts) + + try: + # Importing .synchronize checks for platforms that have some multiprocessing + # capabilities but lack semaphores, such as AWS Lambda and Android Termux. + import multiprocessing.synchronize + from multiprocessing.pool import ThreadPool + except ImportError: + threads = 1 + + if threads == 0: + try: + threads = multiprocessing.cpu_count() + threads = self.max if self.max and self.max < threads else threads + except NotImplementedError: + threads = 1 + + if threads > 1: + pool = ThreadPool(threads) + # In Python 2, ThreadPool can't be used as a context manager. + # Once we are no longer supporting it, this can be 'with pool:' + try: + for _ in pool.imap_unordered(_single_compile, objects): + pass + finally: + pool.terminate() + else: + for ob in objects: + _single_compile(ob) + + return objects + + return compile_function + + def install(self): + distutils.ccompiler.CCompiler.compile = self.function() + return self + + def __enter__(self): + self._old.append(distutils.ccompiler.CCompiler.compile) + return self.install() + + def __exit__(self, *args): + distutils.ccompiler.CCompiler.compile = self._old.pop() diff --git a/pybind11/pybind11/setup_helpers.pyi b/pybind11/pybind11/setup_helpers.pyi new file mode 100644 index 000000000..074744eb8 --- /dev/null +++ b/pybind11/pybind11/setup_helpers.pyi @@ -0,0 +1,63 @@ +# IMPORTANT: Should stay in sync with setup_helpers.py (mostly checked by CI / +# pre-commit). + +import contextlib +import distutils.ccompiler +from distutils.command.build_ext import build_ext as _build_ext # type: ignore +from distutils.extension import Extension as _Extension +from types import TracebackType +from typing import Any, Callable, Dict, Iterator, List, Optional, Type, TypeVar, Union + +WIN: bool +PY2: bool +MACOS: bool +STD_TMPL: str + +class Pybind11Extension(_Extension): + def _add_cflags(self, *flags: str) -> None: ... + def _add_lflags(self, *flags: str) -> None: ... + def __init__( + self, *args: Any, cxx_std: int = 0, language: str = "c++", **kwargs: Any + ) -> None: ... + @property + def cxx_std(self) -> int: ... + @cxx_std.setter + def cxx_std(self, level: int) -> None: ... + +@contextlib.contextmanager +def tmp_chdir() -> Iterator[str]: ... +def has_flag(compiler: distutils.ccompiler.CCompiler, flag: str) -> bool: ... +def auto_cpp_level(compiler: distutils.ccompiler.CCompiler) -> Union[int, str]: ... + +class build_ext(_build_ext): # type: ignore + def build_extensions(self) -> None: ... + +def intree_extensions( + paths: Iterator[str], package_dir: Optional[Dict[str, str]] = None +) -> List[Pybind11Extension]: ... +def no_recompile(obj: str, src: str) -> bool: ... +def naive_recompile(obj: str, src: str) -> bool: ... + +T = TypeVar("T", bound="ParallelCompile") + +class ParallelCompile: + envvar: Optional[str] + default: int + max: int + needs_recompile: Callable[[str, str], bool] + def __init__( + self, + envvar: Optional[str] = None, + default: int = 0, + max: int = 0, + needs_recompile: Callable[[str, str], bool] = no_recompile, + ) -> None: ... + def function(self) -> Any: ... + def install(self: T) -> T: ... + def __enter__(self: T) -> T: ... + def __exit__( + self, + exc_type: Optional[Type[BaseException]], + exc_value: Optional[BaseException], + traceback: Optional[TracebackType], + ) -> None: ... diff --git a/pybind11/pyproject.toml b/pybind11/pyproject.toml index 3bab1c1a2..7d7a1c821 100644 --- a/pybind11/pyproject.toml +++ b/pybind11/pyproject.toml @@ -1,3 +1,41 @@ [build-system] -requires = ["setuptools", "wheel", "cmake==3.18.0", "ninja"] +requires = ["setuptools>=42", "wheel", "cmake>=3.18", "ninja"] build-backend = "setuptools.build_meta" + +[tool.check-manifest] +ignore = [ + "tests/**", + "docs/**", + "tools/**", + "include/**", + ".*", + "pybind11/include/**", + "pybind11/share/**", + "CMakeLists.txt", + "noxfile.py", +] + +[tool.isort] +# Needs the compiled .so modules and env.py from tests +known_first_party = "env,pybind11_cross_module_tests,pybind11_tests," +# For black compatibility +profile = "black" + +[tool.mypy] +files = "pybind11" +python_version = "2.7" +warn_unused_configs = true + +disallow_any_generics = true +disallow_subclassing_any = true +disallow_untyped_calls = true +disallow_untyped_defs = true +disallow_incomplete_defs = true +check_untyped_defs = true +disallow_untyped_decorators = true +no_implicit_optional = true +warn_redundant_casts = true +warn_unused_ignores = true +warn_return_any = true +no_implicit_reexport = true +strict_equality = true diff --git a/pybind11/setup.cfg b/pybind11/setup.cfg index ca0d59a4d..317c44bbf 100644 --- a/pybind11/setup.cfg +++ b/pybind11/setup.cfg @@ -1,10 +1,10 @@ [metadata] -long_description = file: README.md -long_description_content_type = text/markdown +long_description = file: README.rst +long_description_content_type = text/x-rst description = Seamless operability between C++11 and Python author = Wenzel Jakob -author_email = "wenzel.jakob@epfl.ch" -url = "https://github.com/pybind/pybind11" +author_email = wenzel.jakob@epfl.ch +url = https://github.com/pybind/pybind11 license = BSD classifiers = @@ -19,6 +19,8 @@ classifiers = Programming Language :: Python :: 3.6 Programming Language :: Python :: 3.7 Programming Language :: Python :: 3.8 + Programming Language :: Python :: 3.9 + Programming Language :: Python :: 3.10 License :: OSI Approved :: BSD License Programming Language :: Python :: Implementation :: PyPy Programming Language :: Python :: Implementation :: CPython @@ -29,29 +31,20 @@ keywords = C++11 Python bindings +project_urls = + Documentation = https://pybind11.readthedocs.io/ + Bug Tracker = https://github.com/pybind/pybind11/issues + Discussions = https://github.com/pybind/pybind11/discussions + Changelog = https://pybind11.readthedocs.io/en/latest/changelog.html + Chat = https://gitter.im/pybind/Lobby + [options] -python_requires = >=2.7, !=3.0, !=3.1, !=3.2, !=3.3, !=3.4 +python_requires = >=2.7, !=3.0.*, !=3.1.*, !=3.2.*, !=3.3.*, !=3.4.* zip_safe = False [bdist_wheel] universal=1 -[check-manifest] -ignore = - tests/** - docs/** - tools/** - include/** - .appveyor.yml - .cmake-format.yaml - .gitmodules - .pre-commit-config.yaml - .readthedocs.yml - .clang-tidy - pybind11/include/** - pybind11/share/** - CMakeLists.txt - [flake8] max-line-length = 99 @@ -64,3 +57,7 @@ ignore = N813 # Black conflict W503, E203 + + +[tool:pytest] +timeout = 300 diff --git a/pybind11/setup.py b/pybind11/setup.py index c9ba77d6d..0e7348982 100644 --- a/pybind11/setup.py +++ b/pybind11/setup.py @@ -4,6 +4,7 @@ # Setup script for PyPI; use CMakeFile.txt to build extension modules import contextlib +import io import os import re import shutil @@ -19,6 +20,36 @@ VERSION_REGEX = re.compile( r"^\s*#\s*define\s+PYBIND11_VERSION_([A-Z]+)\s+(.*)$", re.MULTILINE ) + +def build_expected_version_hex(matches): + patch_level_serial = matches["PATCH"] + serial = None + try: + major = int(matches["MAJOR"]) + minor = int(matches["MINOR"]) + flds = patch_level_serial.split(".") + if flds: + patch = int(flds[0]) + level = None + if len(flds) == 1: + level = "0" + serial = 0 + elif len(flds) == 2: + level_serial = flds[1] + for level in ("a", "b", "c", "dev"): + if level_serial.startswith(level): + serial = int(level_serial[len(level) :]) + break + except ValueError: + pass + if serial is None: + msg = 'Invalid PYBIND11_VERSION_PATCH: "{}"'.format(patch_level_serial) + raise RuntimeError(msg) + return "0x{:02x}{:02x}{:02x}{}{:x}".format( + major, minor, patch, level[:1].upper(), serial + ) + + # PYBIND11_GLOBAL_SDIST will build a different sdist, with the python-headers # files, and the sys.prefix files (CMake and headers). @@ -35,12 +66,12 @@ to_src = ( # Read the listed version with open("pybind11/_version.py") as f: code = compile(f.read(), "pybind11/_version.py", "exec") - loc = {} - exec(code, loc) - version = loc["__version__"] +loc = {} +exec(code, loc) +version = loc["__version__"] # Verify that the version matches the one in C++ -with open("include/pybind11/detail/common.h") as f: +with io.open("include/pybind11/detail/common.h", encoding="utf8") as f: matches = dict(VERSION_REGEX.findall(f.read())) cpp_version = "{MAJOR}.{MINOR}.{PATCH}".format(**matches) if version != cpp_version: @@ -49,6 +80,15 @@ if version != cpp_version: ) raise RuntimeError(msg) +version_hex = matches.get("HEX", "MISSING") +expected_version_hex = build_expected_version_hex(matches) +if version_hex != expected_version_hex: + msg = "PYBIND11_VERSION_HEX {} does not match expected value {}!".format( + version_hex, + expected_version_hex, + ) + raise RuntimeError(msg) + def get_and_replace(filename, binary=False, **opts): with open(filename, "rb" if binary else "r") as f: @@ -106,6 +146,13 @@ with remove_output("pybind11/include", "pybind11/share"): "-DBUILD_TESTING=OFF", "-DPYBIND11_NOPYTHON=ON", ] + if "CMAKE_ARGS" in os.environ: + fcommand = [ + c + for c in os.environ["CMAKE_ARGS"].split() + if "DCMAKE_INSTALL_PREFIX" not in c + ] + cmd += fcommand cmake_opts = dict(cwd=DIR, stdout=sys.stdout, stderr=sys.stderr) subprocess.check_call(cmd, **cmake_opts) subprocess.check_call(["cmake", "--install", tmpdir], **cmake_opts) diff --git a/pybind11/tests/CMakeLists.txt b/pybind11/tests/CMakeLists.txt index 45e094b08..9040cf8c0 100644 --- a/pybind11/tests/CMakeLists.txt +++ b/pybind11/tests/CMakeLists.txt @@ -10,27 +10,34 @@ cmake_minimum_required(VERSION 3.4) # The `cmake_minimum_required(VERSION 3.4...3.18)` syntax does not work with # some versions of VS that have a patched CMake 3.11. This forces us to emulate # the behavior using the following workaround: -if(${CMAKE_VERSION} VERSION_LESS 3.18) +if(${CMAKE_VERSION} VERSION_LESS 3.21) cmake_policy(VERSION ${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION}) else() - cmake_policy(VERSION 3.18) + cmake_policy(VERSION 3.21) endif() # Only needed for CMake < 3.5 support include(CMakeParseArguments) -# Filter out items; print an optional message if any items filtered +# Filter out items; print an optional message if any items filtered. This ignores extensions. # # Usage: # pybind11_filter_tests(LISTNAME file1.cpp file2.cpp ... MESSAGE "") # -macro(PYBIND11_FILTER_TESTS LISTNAME) +macro(pybind11_filter_tests LISTNAME) cmake_parse_arguments(ARG "" "MESSAGE" "" ${ARGN}) set(PYBIND11_FILTER_TESTS_FOUND OFF) + # Make a list of the test without any extensions, for easier filtering. + set(_TMP_ACTUAL_LIST "${${LISTNAME}};") # enforce ';' at the end to allow matching last item. + string(REGEX REPLACE "\\.[^.;]*;" ";" LIST_WITHOUT_EXTENSIONS "${_TMP_ACTUAL_LIST}") foreach(filename IN LISTS ARG_UNPARSED_ARGUMENTS) - list(FIND ${LISTNAME} ${filename} _FILE_FOUND) + string(REGEX REPLACE "\\.[^.]*$" "" filename_no_ext ${filename}) + # Search in the list without extensions. + list(FIND LIST_WITHOUT_EXTENSIONS ${filename_no_ext} _FILE_FOUND) if(_FILE_FOUND GREATER -1) - list(REMOVE_AT ${LISTNAME} ${_FILE_FOUND}) + list(REMOVE_AT ${LISTNAME} ${_FILE_FOUND}) # And remove from the list with extensions. + list(REMOVE_AT LIST_WITHOUT_EXTENSIONS ${_FILE_FOUND} + )# And our search list, to ensure it is in sync. set(PYBIND11_FILTER_TESTS_FOUND ON) endif() endforeach() @@ -39,6 +46,26 @@ macro(PYBIND11_FILTER_TESTS LISTNAME) endif() endmacro() +macro(possibly_uninitialized) + foreach(VARNAME ${ARGN}) + if(NOT DEFINED "${VARNAME}") + set("${VARNAME}" "") + endif() + endforeach() +endmacro() + +# Function to add additional targets if any of the provided tests are found. +# Needles; Specifies the test names to look for. +# Additions; Specifies the additional test targets to add when any of the needles are found. +macro(tests_extra_targets needles additions) + # Add the index for this relation to the index extra targets map. + list(LENGTH PYBIND11_TEST_EXTRA_TARGETS PYBIND11_TEST_EXTRA_TARGETS_LEN) + list(APPEND PYBIND11_TEST_EXTRA_TARGETS ${PYBIND11_TEST_EXTRA_TARGETS_LEN}) + # Add the test names to look for, and the associated test target additions. + set(PYBIND11_TEST_EXTRA_TARGETS_NEEDLES_${PYBIND11_TEST_EXTRA_TARGETS_LEN} ${needles}) + set(PYBIND11_TEST_EXTRA_TARGETS_ADDITION_${PYBIND11_TEST_EXTRA_TARGETS_LEN} ${additions}) +endmacro() + # New Python support if(DEFINED Python_EXECUTABLE) set(PYTHON_EXECUTABLE "${Python_EXECUTABLE}") @@ -67,7 +94,7 @@ if(CMAKE_CURRENT_SOURCE_DIR STREQUAL CMAKE_SOURCE_DIR) find_package(pybind11 REQUIRED CONFIG) endif() -if(NOT CMAKE_BUILD_TYPE AND NOT CMAKE_CONFIGURATION_TYPES) +if(NOT CMAKE_BUILD_TYPE AND NOT DEFINED CMAKE_CONFIGURATION_TYPES) message(STATUS "Setting tests build type to MinSizeRel as none was specified") set(CMAKE_BUILD_TYPE MinSizeRel @@ -84,52 +111,67 @@ if(PYBIND11_CUDA_TESTS) set(CMAKE_CUDA_STANDARD_REQUIRED ON) endif() -# Full set of test files (you can override these; see below) +# Full set of test files (you can override these; see below, overrides ignore extension) +# Any test that has no extension is both .py and .cpp, so 'foo' will add 'foo.cpp' and 'foo.py'. +# Any test that has an extension is exclusively that and handled as such. set(PYBIND11_TEST_FILES - test_async.cpp - test_buffers.cpp - test_builtin_casters.cpp - test_call_policies.cpp - test_callbacks.cpp - test_chrono.cpp - test_class.cpp - test_constants_and_functions.cpp - test_copy_move.cpp - test_custom_type_casters.cpp - test_docstring_options.cpp - test_eigen.cpp - test_enum.cpp - test_eval.cpp - test_exceptions.cpp - test_factory_constructors.cpp - test_gil_scoped.cpp - test_iostream.cpp - test_kwargs_and_defaults.cpp - test_local_bindings.cpp - test_methods_and_attributes.cpp - test_modules.cpp - test_multiple_inheritance.cpp - test_numpy_array.cpp - test_numpy_dtypes.cpp - test_numpy_vectorize.cpp - test_opaque_types.cpp - test_operator_overloading.cpp - test_pickling.cpp - test_pytypes.cpp - test_sequences_and_iterators.cpp - test_smart_ptr.cpp - test_stl.cpp - test_stl_binders.cpp - test_tagbased_polymorphic.cpp - test_union.cpp - test_virtual_functions.cpp) + test_async + test_buffers + test_builtin_casters + test_call_policies + test_callbacks + test_chrono + test_class + test_const_name + test_constants_and_functions + test_copy_move + test_custom_type_casters + test_custom_type_setup + test_docstring_options + test_eigen + test_enum + test_eval + test_exceptions + test_factory_constructors + test_gil_scoped + test_iostream + test_kwargs_and_defaults + test_local_bindings + test_methods_and_attributes + test_modules + test_multiple_inheritance + test_numpy_array + test_numpy_dtypes + test_numpy_vectorize + test_opaque_types + test_operator_overloading + test_pickling + test_pytypes + test_sequences_and_iterators + test_smart_ptr + test_stl + test_stl_binders + test_tagbased_polymorphic + test_thread + test_union + test_virtual_functions) # Invoking cmake with something like: # cmake -DPYBIND11_TEST_OVERRIDE="test_callbacks.cpp;test_pickling.cpp" .. # lets you override the tests that get compiled and run. You can restore to all tests with: # cmake -DPYBIND11_TEST_OVERRIDE= .. if(PYBIND11_TEST_OVERRIDE) - set(PYBIND11_TEST_FILES ${PYBIND11_TEST_OVERRIDE}) + # Instead of doing a direct override here, we iterate over the overrides without extension and + # match them against entries from the PYBIND11_TEST_FILES, anything that not matches goes into the filter list. + string(REGEX REPLACE "\\.[^.;]*;" ";" TEST_OVERRIDE_NO_EXT "${PYBIND11_TEST_OVERRIDE};") + string(REGEX REPLACE "\\.[^.;]*;" ";" TEST_FILES_NO_EXT "${PYBIND11_TEST_FILES};") + # This allows the override to be done with extensions, preserving backwards compatibility. + foreach(test_name ${TEST_FILES_NO_EXT}) + if(NOT ${test_name} IN_LIST TEST_OVERRIDE_NO_EXT + )# If not in the whitelist, add to be filtered out. + list(APPEND PYBIND11_TEST_FILTER ${test_name}) + endif() + endforeach() endif() # You can also filter tests: @@ -151,15 +193,46 @@ if(PYBIND11_CUDA_TESTS) "Skipping test_constants_and_functions due to incompatible exception specifications") endif() -string(REPLACE ".cpp" ".py" PYBIND11_PYTEST_FILES "${PYBIND11_TEST_FILES}") +# Now that the test filtering is complete, we need to split the list into the test for PYTEST +# and the list for the cpp targets. +set(PYBIND11_CPPTEST_FILES "") +set(PYBIND11_PYTEST_FILES "") + +foreach(test_name ${PYBIND11_TEST_FILES}) + if(test_name MATCHES "\\.py$") # Ends in .py, purely python test. + list(APPEND PYBIND11_PYTEST_FILES ${test_name}) + elseif(test_name MATCHES "\\.cpp$") # Ends in .cpp, purely cpp test. + list(APPEND PYBIND11_CPPTEST_FILES ${test_name}) + elseif(NOT test_name MATCHES "\\.") # No extension specified, assume both, add extension. + list(APPEND PYBIND11_PYTEST_FILES ${test_name}.py) + list(APPEND PYBIND11_CPPTEST_FILES ${test_name}.cpp) + else() + message(WARNING "Unhanded test extension in test: ${test_name}") + endif() +endforeach() +set(PYBIND11_TEST_FILES ${PYBIND11_CPPTEST_FILES}) +list(SORT PYBIND11_PYTEST_FILES) # Contains the set of test files that require pybind11_cross_module_tests to be # built; if none of these are built (i.e. because TEST_OVERRIDE is used and # doesn't include them) the second module doesn't get built. -set(PYBIND11_CROSS_MODULE_TESTS test_exceptions.py test_local_bindings.py test_stl.py - test_stl_binders.py) +tests_extra_targets("test_exceptions.py;test_local_bindings.py;test_stl.py;test_stl_binders.py" + "pybind11_cross_module_tests") -set(PYBIND11_CROSS_MODULE_GIL_TESTS test_gil_scoped.py) +# And add additional targets for other tests. +tests_extra_targets("test_gil_scoped.py" "cross_module_gil_utils") + +set(PYBIND11_EIGEN_REPO + "https://gitlab.com/libeigen/eigen.git" + CACHE STRING "Eigen repository to use for tests") +# Always use a hash for reconfigure speed and security reasons +# Include the version number for pretty printing (keep in sync) +set(PYBIND11_EIGEN_VERSION_AND_HASH + "3.4.0;929bc0e191d0927b1735b9a1ddc0e8b77e3a25ec" + CACHE STRING "Eigen version to use for tests, format: VERSION;HASH") + +list(GET PYBIND11_EIGEN_VERSION_AND_HASH 0 PYBIND11_EIGEN_VERSION_STRING) +list(GET PYBIND11_EIGEN_VERSION_AND_HASH 1 PYBIND11_EIGEN_VERSION_HASH) # Check if Eigen is available; if not, remove from PYBIND11_TEST_FILES (but # keep it in PYBIND11_PYTEST_FILES, so that we get the "eigen is not installed" @@ -174,22 +247,26 @@ if(PYBIND11_TEST_FILES_EIGEN_I GREATER -1) message(FATAL_ERROR "CMake 3.11+ required when using DOWNLOAD_EIGEN") endif() - set(EIGEN3_VERSION_STRING "3.3.7") - include(FetchContent) FetchContent_Declare( eigen - GIT_REPOSITORY https://gitlab.com/libeigen/eigen.git - GIT_TAG ${EIGEN3_VERSION_STRING}) + GIT_REPOSITORY "${PYBIND11_EIGEN_REPO}" + GIT_TAG "${PYBIND11_EIGEN_VERSION_HASH}") FetchContent_GetProperties(eigen) if(NOT eigen_POPULATED) - message(STATUS "Downloading Eigen") + message( + STATUS + "Downloading Eigen ${PYBIND11_EIGEN_VERSION_STRING} (${PYBIND11_EIGEN_VERSION_HASH}) from ${PYBIND11_EIGEN_REPO}" + ) FetchContent_Populate(eigen) endif() set(EIGEN3_INCLUDE_DIR ${eigen_SOURCE_DIR}) set(EIGEN3_FOUND TRUE) + # When getting locally, the version is not visible from a superprojet, + # so just force it. + set(EIGEN3_VERSION "${PYBIND11_EIGEN_VERSION_STRING}") else() find_package(Eigen3 3.2.7 QUIET CONFIG) @@ -217,7 +294,8 @@ if(PYBIND11_TEST_FILES_EIGEN_I GREATER -1) message(STATUS "Building tests with Eigen v${EIGEN3_VERSION}") else() list(REMOVE_AT PYBIND11_TEST_FILES ${PYBIND11_TEST_FILES_EIGEN_I}) - message(STATUS "Building tests WITHOUT Eigen, use -DDOWNLOAD_EIGEN on CMake 3.11+ to download") + message( + STATUS "Building tests WITHOUT Eigen, use -DDOWNLOAD_EIGEN=ON on CMake 3.11+ to download") endif() endif() @@ -226,25 +304,69 @@ find_package(Boost 1.56) if(Boost_FOUND) if(NOT TARGET Boost::headers) + add_library(Boost::headers IMPORTED INTERFACE) if(TARGET Boost::boost) # Classic FindBoost - add_library(Boost::headers ALIAS Boost::boost) + set_property(TARGET Boost::boost PROPERTY INTERFACE_LINK_LIBRARIES Boost::boost) else() # Very old FindBoost, or newer Boost than CMake in older CMakes - add_library(Boost::headers IMPORTED INTERFACE) set_property(TARGET Boost::headers PROPERTY INTERFACE_INCLUDE_DIRECTORIES ${Boost_INCLUDE_DIRS}) endif() endif() endif() +# Check if we need to add -lstdc++fs or -lc++fs or nothing +if(DEFINED CMAKE_CXX_STANDARD AND CMAKE_CXX_STANDARD LESS 17) + set(STD_FS_NO_LIB_NEEDED TRUE) +elseif(MSVC) + set(STD_FS_NO_LIB_NEEDED TRUE) +else() + file( + WRITE ${CMAKE_CURRENT_BINARY_DIR}/main.cpp + "#include \nint main(int argc, char ** argv) {\n std::filesystem::path p(argv[0]);\n return p.string().length();\n}" + ) + try_compile( + STD_FS_NO_LIB_NEEDED ${CMAKE_CURRENT_BINARY_DIR} + SOURCES ${CMAKE_CURRENT_BINARY_DIR}/main.cpp + COMPILE_DEFINITIONS -std=c++17) + try_compile( + STD_FS_NEEDS_STDCXXFS ${CMAKE_CURRENT_BINARY_DIR} + SOURCES ${CMAKE_CURRENT_BINARY_DIR}/main.cpp + COMPILE_DEFINITIONS -std=c++17 + LINK_LIBRARIES stdc++fs) + try_compile( + STD_FS_NEEDS_CXXFS ${CMAKE_CURRENT_BINARY_DIR} + SOURCES ${CMAKE_CURRENT_BINARY_DIR}/main.cpp + COMPILE_DEFINITIONS -std=c++17 + LINK_LIBRARIES c++fs) +endif() + +if(${STD_FS_NEEDS_STDCXXFS}) + set(STD_FS_LIB stdc++fs) +elseif(${STD_FS_NEEDS_CXXFS}) + set(STD_FS_LIB c++fs) +elseif(${STD_FS_NO_LIB_NEEDED}) + set(STD_FS_LIB "") +else() + message(WARNING "Unknown C++17 compiler - not passing -lstdc++fs") + set(STD_FS_LIB "") +endif() + # Compile with compiler warnings turned on function(pybind11_enable_warnings target_name) if(MSVC) target_compile_options(${target_name} PRIVATE /W4) elseif(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Intel|Clang)" AND NOT PYBIND11_CUDA_TESTS) - target_compile_options(${target_name} PRIVATE -Wall -Wextra -Wconversion -Wcast-qual - -Wdeprecated -Wundef) + target_compile_options( + ${target_name} + PRIVATE -Wall + -Wextra + -Wconversion + -Wcast-qual + -Wdeprecated + -Wundef + -Wnon-virtual-dtor) endif() if(PYBIND11_WERROR) @@ -252,12 +374,22 @@ function(pybind11_enable_warnings target_name) target_compile_options(${target_name} PRIVATE /WX) elseif(PYBIND11_CUDA_TESTS) target_compile_options(${target_name} PRIVATE "SHELL:-Werror all-warnings") - elseif(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Intel|Clang)") + elseif(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang|IntelLLVM)") target_compile_options(${target_name} PRIVATE -Werror) + elseif(CMAKE_CXX_COMPILER_ID STREQUAL "Intel") + if(CMAKE_CXX_STANDARD EQUAL 17) # See PR #3570 + target_compile_options(${target_name} PRIVATE -Wno-conversion) + endif() + target_compile_options( + ${target_name} + PRIVATE + -Werror-all + # "Inlining inhibited by limit max-size", "Inlining inhibited by limit max-total-size" + -diag-disable 11074,11076) endif() endif() - # Needs to be readded since the ordering requires these to be after the ones above + # Needs to be re-added since the ordering requires these to be after the ones above if(CMAKE_CXX_STANDARD AND CMAKE_CXX_COMPILER_ID MATCHES "Clang" AND PYTHON_VERSION VERSION_LESS 3.0) @@ -271,21 +403,17 @@ endfunction() set(test_targets pybind11_tests) -# Build pybind11_cross_module_tests if any test_whatever.py are being built that require it -foreach(t ${PYBIND11_CROSS_MODULE_TESTS}) - list(FIND PYBIND11_PYTEST_FILES ${t} i) - if(i GREATER -1) - list(APPEND test_targets pybind11_cross_module_tests) - break() - endif() -endforeach() - -foreach(t ${PYBIND11_CROSS_MODULE_GIL_TESTS}) - list(FIND PYBIND11_PYTEST_FILES ${t} i) - if(i GREATER -1) - list(APPEND test_targets cross_module_gil_utils) - break() - endif() +# Check if any tests need extra targets by iterating through the mappings registered. +foreach(i ${PYBIND11_TEST_EXTRA_TARGETS}) + foreach(needle ${PYBIND11_TEST_EXTRA_TARGETS_NEEDLES_${i}}) + if(needle IN_LIST PYBIND11_PYTEST_FILES) + # Add all the additional targets to the test list. List join in newer cmake. + foreach(extra_target ${PYBIND11_TEST_EXTRA_TARGETS_ADDITION_${i}}) + list(APPEND test_targets ${extra_target}) + endforeach() + break() # Breaks out of the needle search, continues with the next mapping. + endif() + endforeach() endforeach() # Support CUDA testing by forcing the target file to compile with NVCC @@ -334,38 +462,34 @@ foreach(target ${test_targets}) target_compile_definitions(${target} PRIVATE -DPYBIND11_TEST_BOOST) endif() + target_link_libraries(${target} PRIVATE ${STD_FS_LIB}) + # Always write the output file directly into the 'tests' directory (even on MSVC) if(NOT CMAKE_LIBRARY_OUTPUT_DIRECTORY) set_target_properties(${target} PROPERTIES LIBRARY_OUTPUT_DIRECTORY "${CMAKE_CURRENT_BINARY_DIR}") - foreach(config ${CMAKE_CONFIGURATION_TYPES}) - string(TOUPPER ${config} config) - set_target_properties(${target} PROPERTIES LIBRARY_OUTPUT_DIRECTORY_${config} - "${CMAKE_CURRENT_BINARY_DIR}") - endforeach() + + if(DEFINED CMAKE_CONFIGURATION_TYPES) + foreach(config ${CMAKE_CONFIGURATION_TYPES}) + string(TOUPPER ${config} config) + set_target_properties(${target} PROPERTIES LIBRARY_OUTPUT_DIRECTORY_${config} + "${CMAKE_CURRENT_BINARY_DIR}") + endforeach() + endif() endif() endforeach() -# Make sure pytest is found or produce a warning -if(NOT PYBIND11_PYTEST_FOUND) - execute_process( - COMMAND ${PYTHON_EXECUTABLE} -c "import pytest; print(pytest.__version__)" - RESULT_VARIABLE pytest_not_found - OUTPUT_VARIABLE pytest_version - ERROR_QUIET) - if(pytest_not_found) - message(WARNING "Running the tests requires pytest. Please install it manually" - " (try: ${PYTHON_EXECUTABLE} -m pip install pytest)") - elseif(pytest_version VERSION_LESS 3.1) - message(WARNING "Running the tests requires pytest >= 3.1. Found: ${pytest_version}" - "Please update it (try: ${PYTHON_EXECUTABLE} -m pip install -U pytest)") - else() - set(PYBIND11_PYTEST_FOUND - TRUE - CACHE INTERNAL "") - endif() +# Provide nice organisation in IDEs +if(NOT CMAKE_VERSION VERSION_LESS 3.8) + source_group( + TREE "${CMAKE_CURRENT_SOURCE_DIR}/../include" + PREFIX "Header Files" + FILES ${PYBIND11_HEADERS}) endif() +# Make sure pytest is found or produce a warning +pybind11_find_import(pytest VERSION 3.1) + if(NOT CMAKE_CURRENT_SOURCE_DIR STREQUAL CMAKE_CURRENT_BINARY_DIR) # This is not used later in the build, so it's okay to regenerate each time. configure_file("${CMAKE_CURRENT_SOURCE_DIR}/pytest.ini" "${CMAKE_CURRENT_BINARY_DIR}/pytest.ini" @@ -377,15 +501,20 @@ endif() # cmake 3.12 added list(transform prepend # but we can't use it yet -string(REPLACE "test_" "${CMAKE_CURRENT_BINARY_DIR}/test_" PYBIND11_BINARY_TEST_FILES +string(REPLACE "test_" "${CMAKE_CURRENT_SOURCE_DIR}/test_" PYBIND11_ABS_PYTEST_FILES "${PYBIND11_PYTEST_FILES}") +set(PYBIND11_TEST_PREFIX_COMMAND + "" + CACHE STRING "Put this before pytest, use for checkers and such") + # A single command to compile and run the tests add_custom_target( pytest - COMMAND ${PYTHON_EXECUTABLE} -m pytest ${PYBIND11_BINARY_PYTEST_FILES} + COMMAND ${PYBIND11_TEST_PREFIX_COMMAND} ${PYTHON_EXECUTABLE} -m pytest + ${PYBIND11_ABS_PYTEST_FILES} DEPENDS ${test_targets} - WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR} + WORKING_DIRECTORY "${CMAKE_CURRENT_BINARY_DIR}" USES_TERMINAL) if(PYBIND11_TEST_OVERRIDE) @@ -396,6 +525,27 @@ if(PYBIND11_TEST_OVERRIDE) "Note: not all tests run: -DPYBIND11_TEST_OVERRIDE is in effect") endif() +# cmake-format: off +add_custom_target( + memcheck + COMMAND + PYTHONMALLOC=malloc + valgrind + --leak-check=full + --show-leak-kinds=definite,indirect + --errors-for-leak-kinds=definite,indirect + --error-exitcode=1 + --read-var-info=yes + --track-origins=yes + --suppressions="${CMAKE_CURRENT_SOURCE_DIR}/valgrind-python.supp" + --suppressions="${CMAKE_CURRENT_SOURCE_DIR}/valgrind-numpy-scipy.supp" + --gen-suppressions=all + ${PYTHON_EXECUTABLE} -m pytest ${PYBIND11_ABS_PYTEST_FILES} + DEPENDS ${test_targets} + WORKING_DIRECTORY "${CMAKE_CURRENT_BINARY_DIR}" + USES_TERMINAL) +# cmake-format: on + # Add a check target to run all the tests, starting with pytest (we add dependencies to this below) add_custom_target(check DEPENDS pytest) diff --git a/pybind11/tests/conftest.py b/pybind11/tests/conftest.py index a2350d041..362eb8069 100644 --- a/pybind11/tests/conftest.py +++ b/pybind11/tests/conftest.py @@ -18,9 +18,9 @@ import env # Early diagnostic for failed imports import pybind11_tests # noqa: F401 -_unicode_marker = re.compile(r'u(\'[^\']*\')') -_long_marker = re.compile(r'([0-9])L') -_hexadecimal = re.compile(r'0x[0-9a-fA-F]+') +_unicode_marker = re.compile(r"u(\'[^\']*\')") +_long_marker = re.compile(r"([0-9])L") +_hexadecimal = re.compile(r"0x[0-9a-fA-F]+") # Avoid collecting Python3 only files collect_ignore = [] @@ -30,7 +30,7 @@ if env.PY2: def _strip_and_dedent(s): """For triple-quote strings""" - return textwrap.dedent(s.lstrip('\n').rstrip()) + return textwrap.dedent(s.lstrip("\n").rstrip()) def _split_and_sort(s): @@ -40,11 +40,14 @@ def _split_and_sort(s): def _make_explanation(a, b): """Explanation for a failed assert -- the a and b arguments are List[str]""" - return ["--- actual / +++ expected"] + [line.strip('\n') for line in difflib.ndiff(a, b)] + return ["--- actual / +++ expected"] + [ + line.strip("\n") for line in difflib.ndiff(a, b) + ] class Output(object): """Basic output post-processing and comparison""" + def __init__(self, string): self.string = string self.explanation = [] @@ -54,7 +57,11 @@ class Output(object): def __eq__(self, other): # Ignore constructor/destructor output which is prefixed with "###" - a = [line for line in self.string.strip().splitlines() if not line.startswith("###")] + a = [ + line + for line in self.string.strip().splitlines() + if not line.startswith("###") + ] b = _strip_and_dedent(other).splitlines() if a == b: return True @@ -65,6 +72,7 @@ class Output(object): class Unordered(Output): """Custom comparison for output without strict line ordering""" + def __eq__(self, other): a = _split_and_sort(self.string) b = _split_and_sort(other) @@ -175,7 +183,7 @@ def msg(): # noinspection PyUnusedLocal def pytest_assertrepr_compare(op, left, right): """Hook to insert custom failure explanation""" - if hasattr(left, 'explanation'): + if hasattr(left, "explanation"): return left.explanation @@ -189,8 +197,8 @@ def suppress(exception): def gc_collect(): - ''' Run the garbage collector twice (needed when running - reference counting tests with PyPy) ''' + """Run the garbage collector twice (needed when running + reference counting tests with PyPy)""" gc.collect() gc.collect() diff --git a/pybind11/tests/constructor_stats.h b/pybind11/tests/constructor_stats.h index abfaf9161..805968a09 100644 --- a/pybind11/tests/constructor_stats.h +++ b/pybind11/tests/constructor_stats.h @@ -120,7 +120,7 @@ public: throw py::error_already_set(); Py_DECREF(result); #else - py::module::import("gc").attr("collect")(); + py::module_::import("gc").attr("collect")(); #endif } diff --git a/pybind11/tests/env.py b/pybind11/tests/env.py index 5cded4412..6172b451b 100644 --- a/pybind11/tests/env.py +++ b/pybind11/tests/env.py @@ -2,6 +2,8 @@ import platform import sys +import pytest + LINUX = sys.platform.startswith("linux") MACOS = sys.platform.startswith("darwin") WIN = sys.platform.startswith("win32") or sys.platform.startswith("cygwin") @@ -12,3 +14,20 @@ PYPY = platform.python_implementation() == "PyPy" PY2 = sys.version_info.major == 2 PY = sys.version_info + + +def deprecated_call(): + """ + pytest.deprecated_call() seems broken in pytest<3.9.x; concretely, it + doesn't work on CPython 3.8.0 with pytest==3.3.2 on Ubuntu 18.04 (#2922). + + This is a narrowed reimplementation of the following PR :( + https://github.com/pytest-dev/pytest/pull/4104 + """ + # TODO: Remove this when testing requires pytest>=3.9. + pieces = pytest.__version__.split(".") + pytest_major_minor = (int(pieces[0]), int(pieces[1])) + if pytest_major_minor < (3, 9): + return pytest.warns((DeprecationWarning, PendingDeprecationWarning)) + else: + return pytest.deprecated_call() diff --git a/pybind11/tests/extra_python_package/test_files.py b/pybind11/tests/extra_python_package/test_files.py index ac8ca1f97..337a72dfe 100644 --- a/pybind11/tests/extra_python_package/test_files.py +++ b/pybind11/tests/extra_python_package/test_files.py @@ -25,6 +25,7 @@ main_headers = { "include/pybind11/embed.h", "include/pybind11/eval.h", "include/pybind11/functional.h", + "include/pybind11/gil.h", "include/pybind11/iostream.h", "include/pybind11/numpy.h", "include/pybind11/operators.h", @@ -41,9 +42,14 @@ detail_headers = { "include/pybind11/detail/descr.h", "include/pybind11/detail/init.h", "include/pybind11/detail/internals.h", + "include/pybind11/detail/type_caster_base.h", "include/pybind11/detail/typeid.h", } +stl_headers = { + "include/pybind11/stl/filesystem.h", +} + cmake_files = { "share/cmake/pybind11/FindPythonLibsNew.cmake", "share/cmake/pybind11/pybind11Common.cmake", @@ -58,11 +64,14 @@ py_files = { "__init__.py", "__main__.py", "_version.py", + "_version.pyi", "commands.py", + "py.typed", "setup_helpers.py", + "setup_helpers.pyi", } -headers = main_headers | detail_headers +headers = main_headers | detail_headers | stl_headers src_files = headers | cmake_files all_files = src_files | py_files @@ -72,6 +81,7 @@ sdist_files = { "pybind11/include", "pybind11/include/pybind11", "pybind11/include/pybind11/detail", + "pybind11/include/pybind11/stl", "pybind11/share", "pybind11/share/cmake", "pybind11/share/cmake/pybind11", @@ -80,7 +90,7 @@ sdist_files = { "setup.py", "LICENSE", "MANIFEST.in", - "README.md", + "README.rst", "PKG-INFO", } @@ -116,7 +126,7 @@ def test_build_sdist(monkeypatch, tmpdir): with tarfile.open(str(sdist)) as tar: start = tar.getnames()[0] + "/" version = start[9:-1] - simpler = set(n.split("/", 1)[-1] for n in tar.getnames()[1:]) + simpler = {n.split("/", 1)[-1] for n in tar.getnames()[1:]} with contextlib.closing( tar.extractfile(tar.getmember(start + "setup.py")) @@ -128,9 +138,19 @@ def test_build_sdist(monkeypatch, tmpdir): ) as f: pyproject_toml = f.read() - files = set("pybind11/{}".format(n) for n in all_files) + with contextlib.closing( + tar.extractfile( + tar.getmember( + start + "pybind11/share/cmake/pybind11/pybind11Config.cmake" + ) + ) + ) as f: + contents = f.read().decode("utf8") + assert 'set(pybind11_INCLUDE_DIR "${PACKAGE_PREFIX_DIR}/include")' in contents + + files = {"pybind11/{}".format(n) for n in all_files} files |= sdist_files - files |= set("pybind11{}".format(n) for n in local_sdist_files) + files |= {"pybind11{}".format(n) for n in local_sdist_files} files.add("pybind11.egg-info/entry_points.txt") files.add("pybind11.egg-info/requires.txt") assert simpler == files @@ -141,11 +161,11 @@ def test_build_sdist(monkeypatch, tmpdir): .substitute(version=version, extra_cmd="") .encode() ) - assert setup_py == contents + assert setup_py == contents with open(os.path.join(MAIN_DIR, "tools", "pyproject.toml"), "rb") as f: contents = f.read() - assert pyproject_toml == contents + assert pyproject_toml == contents def test_build_global_dist(monkeypatch, tmpdir): @@ -171,7 +191,7 @@ def test_build_global_dist(monkeypatch, tmpdir): with tarfile.open(str(sdist)) as tar: start = tar.getnames()[0] + "/" version = start[16:-1] - simpler = set(n.split("/", 1)[-1] for n in tar.getnames()[1:]) + simpler = {n.split("/", 1)[-1] for n in tar.getnames()[1:]} with contextlib.closing( tar.extractfile(tar.getmember(start + "setup.py")) @@ -183,9 +203,9 @@ def test_build_global_dist(monkeypatch, tmpdir): ) as f: pyproject_toml = f.read() - files = set("pybind11/{}".format(n) for n in all_files) + files = {"pybind11/{}".format(n) for n in all_files} files |= sdist_files - files |= set("pybind11_global{}".format(n) for n in local_sdist_files) + files |= {"pybind11_global{}".format(n) for n in local_sdist_files} assert simpler == files with open(os.path.join(MAIN_DIR, "tools", "setup_global.py.in"), "rb") as f: @@ -210,7 +230,7 @@ def tests_build_wheel(monkeypatch, tmpdir): (wheel,) = tmpdir.visit("*.whl") - files = set("pybind11/{}".format(n) for n in all_files) + files = {"pybind11/{}".format(n) for n in all_files} files |= { "dist-info/LICENSE", "dist-info/METADATA", @@ -223,10 +243,10 @@ def tests_build_wheel(monkeypatch, tmpdir): with zipfile.ZipFile(str(wheel)) as z: names = z.namelist() - trimmed = set(n for n in names if "dist-info" not in n) - trimmed |= set( + trimmed = {n for n in names if "dist-info" not in n} + trimmed |= { "dist-info/{}".format(n.split("/", 1)[-1]) for n in names if "dist-info" in n - ) + } assert files == trimmed @@ -240,8 +260,8 @@ def tests_build_global_wheel(monkeypatch, tmpdir): (wheel,) = tmpdir.visit("*.whl") - files = set("data/data/{}".format(n) for n in src_files) - files |= set("data/headers/{}".format(n[8:]) for n in headers) + files = {"data/data/{}".format(n) for n in src_files} + files |= {"data/headers/{}".format(n[8:]) for n in headers} files |= { "dist-info/LICENSE", "dist-info/METADATA", @@ -254,6 +274,6 @@ def tests_build_global_wheel(monkeypatch, tmpdir): names = z.namelist() beginning = names[0].split("/", 1)[0].rsplit(".", 1)[0] - trimmed = set(n[len(beginning) + 1 :] for n in names) + trimmed = {n[len(beginning) + 1 :] for n in names} assert files == trimmed diff --git a/pybind11/tests/extra_setuptools/test_setuphelper.py b/pybind11/tests/extra_setuptools/test_setuphelper.py index de0b516a9..788f368b1 100644 --- a/pybind11/tests/extra_setuptools/test_setuphelper.py +++ b/pybind11/tests/extra_setuptools/test_setuphelper.py @@ -1,17 +1,19 @@ # -*- coding: utf-8 -*- import os -import sys import subprocess +import sys from textwrap import dedent import pytest DIR = os.path.abspath(os.path.dirname(__file__)) MAIN_DIR = os.path.dirname(os.path.dirname(DIR)) +WIN = sys.platform.startswith("win32") or sys.platform.startswith("cygwin") +@pytest.mark.parametrize("parallel", [False, True]) @pytest.mark.parametrize("std", [11, 0]) -def test_simple_setup_py(monkeypatch, tmpdir, std): +def test_simple_setup_py(monkeypatch, tmpdir, parallel, std): monkeypatch.chdir(tmpdir) monkeypatch.syspath_prepend(MAIN_DIR) @@ -39,13 +41,18 @@ def test_simple_setup_py(monkeypatch, tmpdir, std): cmdclass["build_ext"] = build_ext + parallel = {parallel} + if parallel: + from pybind11.setup_helpers import ParallelCompile + ParallelCompile().install() + setup( name="simple_setup_package", cmdclass=cmdclass, ext_modules=ext_modules, ) """ - ).format(MAIN_DIR=MAIN_DIR, std=std), + ).format(MAIN_DIR=MAIN_DIR, std=std, parallel=parallel), encoding="ascii", ) @@ -65,13 +72,20 @@ def test_simple_setup_py(monkeypatch, tmpdir, std): encoding="ascii", ) - subprocess.check_call( + out = subprocess.check_output( [sys.executable, "setup.py", "build_ext", "--inplace"], - stdout=sys.stdout, - stderr=sys.stderr, ) + if not WIN: + assert b"-g0" in out + out = subprocess.check_output( + [sys.executable, "setup.py", "build_ext", "--inplace", "--force"], + env=dict(os.environ, CFLAGS="-g"), + ) + if not WIN: + assert b"-g0" not in out # Debug helper printout, normally hidden + print(out) for item in tmpdir.listdir(): print(item.basename) @@ -93,3 +107,45 @@ def test_simple_setup_py(monkeypatch, tmpdir, std): subprocess.check_call( [sys.executable, "test.py"], stdout=sys.stdout, stderr=sys.stderr ) + + +def test_intree_extensions(monkeypatch, tmpdir): + monkeypatch.syspath_prepend(MAIN_DIR) + + from pybind11.setup_helpers import intree_extensions + + monkeypatch.chdir(tmpdir) + root = tmpdir + root.ensure_dir() + subdir = root / "dir" + subdir.ensure_dir() + src = subdir / "ext.cpp" + src.ensure() + (ext,) = intree_extensions([src.relto(tmpdir)]) + assert ext.name == "ext" + subdir.ensure("__init__.py") + (ext,) = intree_extensions([src.relto(tmpdir)]) + assert ext.name == "dir.ext" + + +def test_intree_extensions_package_dir(monkeypatch, tmpdir): + monkeypatch.syspath_prepend(MAIN_DIR) + + from pybind11.setup_helpers import intree_extensions + + monkeypatch.chdir(tmpdir) + root = tmpdir / "src" + root.ensure_dir() + subdir = root / "dir" + subdir.ensure_dir() + src = subdir / "ext.cpp" + src.ensure() + (ext,) = intree_extensions([src.relto(tmpdir)], package_dir={"": "src"}) + assert ext.name == "dir.ext" + (ext,) = intree_extensions([src.relto(tmpdir)], package_dir={"foo": "src"}) + assert ext.name == "foo.dir.ext" + subdir.ensure("__init__.py") + (ext,) = intree_extensions([src.relto(tmpdir)], package_dir={"": "src"}) + assert ext.name == "dir.ext" + (ext,) = intree_extensions([src.relto(tmpdir)], package_dir={"foo": "src"}) + assert ext.name == "foo.dir.ext" diff --git a/pybind11/tests/local_bindings.h b/pybind11/tests/local_bindings.h index 22537b13a..4c936c19a 100644 --- a/pybind11/tests/local_bindings.h +++ b/pybind11/tests/local_bindings.h @@ -1,10 +1,12 @@ #pragma once +#include + #include "pybind11_tests.h" /// Simple class used to test py::local: template class LocalBase { public: - LocalBase(int i) : i(i) { } + explicit LocalBase(int i) : i(i) { } int i = -1; }; @@ -33,6 +35,25 @@ using NonLocalVec2 = std::vector; using NonLocalMap = std::unordered_map; using NonLocalMap2 = std::unordered_map; + +// Exception that will be caught via the module local translator. +class LocalException : public std::exception { +public: + explicit LocalException(const char * m) : message{m} {} + const char * what() const noexcept override {return message.c_str();} +private: + std::string message = ""; +}; + +// Exception that will be registered with register_local_exception_translator +class LocalSimpleException : public std::exception { +public: + explicit LocalSimpleException(const char * m) : message{m} {} + const char * what() const noexcept override {return message.c_str();} +private: + std::string message = ""; +}; + PYBIND11_MAKE_OPAQUE(LocalVec); PYBIND11_MAKE_OPAQUE(LocalVec2); PYBIND11_MAKE_OPAQUE(LocalMap); @@ -54,11 +75,11 @@ py::class_ bind_local(Args && ...args) { namespace pets { class Pet { public: - Pet(std::string name) : name_(name) {} + explicit Pet(std::string name) : name_(std::move(name)) {} std::string name_; - const std::string &name() { return name_; } + const std::string &name() const { return name_; } }; } // namespace pets -struct MixGL { int i; MixGL(int i) : i{i} {} }; -struct MixGL2 { int i; MixGL2(int i) : i{i} {} }; +struct MixGL { int i; explicit MixGL(int i) : i{i} {} }; +struct MixGL2 { int i; explicit MixGL2(int i) : i{i} {} }; diff --git a/pybind11/tests/object.h b/pybind11/tests/object.h index 9235f19c2..be21bf631 100644 --- a/pybind11/tests/object.h +++ b/pybind11/tests/object.h @@ -65,7 +65,7 @@ public: ref() : m_ptr(nullptr) { print_default_created(this); track_default_created((ref_tag*) this); } /// Construct a reference from a pointer - ref(T *ptr) : m_ptr(ptr) { + explicit ref(T *ptr) : m_ptr(ptr) { if (m_ptr) ((Object *) m_ptr)->incRef(); print_created(this, "from pointer", m_ptr); track_created((ref_tag*) this, "from pointer"); @@ -81,7 +81,7 @@ public: } /// Move constructor - ref(ref &&r) : m_ptr(r.m_ptr) { + ref(ref &&r) noexcept : m_ptr(r.m_ptr) { r.m_ptr = nullptr; print_move_created(this, "with pointer", m_ptr); track_move_created((ref_tag*) this); @@ -96,7 +96,7 @@ public: } /// Move another reference into the current one - ref& operator=(ref&& r) { + ref &operator=(ref &&r) noexcept { print_move_assigned(this, "pointer", r.m_ptr); track_move_assigned((ref_tag*) this); if (*this == r) @@ -110,7 +110,11 @@ public: /// Overwrite this reference with another reference ref& operator=(const ref& r) { - print_copy_assigned(this, "pointer", r.m_ptr); track_copy_assigned((ref_tag*) this); + if (this == &r) { + return *this; + } + print_copy_assigned(this, "pointer", r.m_ptr); + track_copy_assigned((ref_tag *) this); if (m_ptr == r.m_ptr) return *this; @@ -161,7 +165,7 @@ public: const T& operator*() const { return *m_ptr; } /// Return a pointer to the referenced object - operator T* () { return m_ptr; } + explicit operator T* () { return m_ptr; } /// Return a const pointer to the referenced object T* get_ptr() { return m_ptr; } diff --git a/pybind11/tests/pybind11_cross_module_tests.cpp b/pybind11/tests/pybind11_cross_module_tests.cpp index f705e3106..5838cb274 100644 --- a/pybind11/tests/pybind11_cross_module_tests.cpp +++ b/pybind11/tests/pybind11_cross_module_tests.cpp @@ -9,8 +9,12 @@ #include "pybind11_tests.h" #include "local_bindings.h" +#include "test_exceptions.h" + #include + #include +#include PYBIND11_MODULE(pybind11_cross_module_tests, m) { m.doc() = "pybind11 cross-module test module"; @@ -25,11 +29,32 @@ PYBIND11_MODULE(pybind11_cross_module_tests, m) { bind_local(m, "ExternalType2", py::module_local()); // test_exceptions.py + py::register_local_exception(m, "LocalSimpleException"); m.def("raise_runtime_error", []() { PyErr_SetString(PyExc_RuntimeError, "My runtime error"); throw py::error_already_set(); }); m.def("raise_value_error", []() { PyErr_SetString(PyExc_ValueError, "My value error"); throw py::error_already_set(); }); m.def("throw_pybind_value_error", []() { throw py::value_error("pybind11 value error"); }); m.def("throw_pybind_type_error", []() { throw py::type_error("pybind11 type error"); }); m.def("throw_stop_iteration", []() { throw py::stop_iteration(); }); + m.def("throw_local_error", []() { throw LocalException("just local"); }); + m.def("throw_local_simple_error", []() { throw LocalSimpleException("external mod"); }); + py::register_exception_translator([](std::exception_ptr p) { + try { + if (p) std::rethrow_exception(p); + } catch (const shared_exception &e) { + PyErr_SetString(PyExc_KeyError, e.what()); + } + }); + + // translate the local exception into a key error but only in this module + py::register_local_exception_translator([](std::exception_ptr p) { + try { + if (p) { + std::rethrow_exception(p); + } + } catch (const LocalException &e) { + PyErr_SetString(PyExc_KeyError, e.what()); + } + }); // test_local_bindings.py // Local to both: @@ -83,7 +108,7 @@ PYBIND11_MODULE(pybind11_cross_module_tests, m) { m.def("get_mixed_lg", [](int i) { return MixedLocalGlobal(i); }); // test_internal_locals_differ - m.def("local_cpp_types_addr", []() { return (uintptr_t) &py::detail::registered_local_types_cpp(); }); + m.def("local_cpp_types_addr", []() { return (uintptr_t) &py::detail::get_local_internals().registered_types_cpp; }); // test_stl_caster_vs_stl_bind py::bind_vector>(m, "VectorInt"); @@ -96,7 +121,10 @@ PYBIND11_MODULE(pybind11_cross_module_tests, m) { m.def("return_self", [](LocalVec *v) { return v; }); m.def("return_copy", [](const LocalVec &v) { return LocalVec(v); }); - class Dog : public pets::Pet { public: Dog(std::string name) : Pet(name) {}; }; + class Dog : public pets::Pet { + public: + explicit Dog(std::string name) : Pet(std::move(name)) {} + }; py::class_(m, "Pet", py::module_local()) .def("name", &pets::Pet::name); // Binding for local extending class: @@ -118,6 +146,6 @@ PYBIND11_MODULE(pybind11_cross_module_tests, m) { // test_missing_header_message // The main module already includes stl.h, but we need to test the error message // which appears when this header is missing. - m.def("missing_header_arg", [](std::vector) { }); + m.def("missing_header_arg", [](const std::vector &) {}); m.def("missing_header_return", []() { return std::vector(); }); } diff --git a/pybind11/tests/pybind11_tests.cpp b/pybind11/tests/pybind11_tests.cpp index 24b65df6f..439cd4012 100644 --- a/pybind11/tests/pybind11_tests.cpp +++ b/pybind11/tests/pybind11_tests.cpp @@ -26,8 +26,8 @@ productively. Instead, see the "How can I reduce the build time?" question in the "Frequently asked questions" section of the documentation for good practice on splitting binding code over multiple files. */ -std::list> &initializers() { - static std::list> inits; +std::list> &initializers() { + static std::list> inits; return inits; } @@ -36,13 +36,13 @@ test_initializer::test_initializer(Initializer init) { } test_initializer::test_initializer(const char *submodule_name, Initializer init) { - initializers().emplace_back([=](py::module &parent) { + initializers().emplace_back([=](py::module_ &parent) { auto m = parent.def_submodule(submodule_name); init(m); }); } -void bind_ConstructorStats(py::module &m) { +void bind_ConstructorStats(py::module_ &m) { py::class_(m, "ConstructorStats") .def("alive", &ConstructorStats::alive) .def("values", &ConstructorStats::values) diff --git a/pybind11/tests/pybind11_tests.h b/pybind11/tests/pybind11_tests.h index 1e4741627..9b9992323 100644 --- a/pybind11/tests/pybind11_tests.h +++ b/pybind11/tests/pybind11_tests.h @@ -1,27 +1,29 @@ #pragma once + #include +#include #if defined(_MSC_VER) && _MSC_VER < 1910 // We get some really long type names here which causes MSVC 2015 to emit warnings -# pragma warning(disable: 4503) // warning C4503: decorated name length exceeded, name was truncated +# pragma warning( \ + disable : 4503) // warning C4503: decorated name length exceeded, name was truncated #endif namespace py = pybind11; using namespace pybind11::literals; class test_initializer { - using Initializer = void (*)(py::module &); + using Initializer = void (*)(py::module_ &); public: - test_initializer(Initializer init); + explicit test_initializer(Initializer init); test_initializer(const char *submodule_name, Initializer init); }; -#define TEST_SUBMODULE(name, variable) \ - void test_submodule_##name(py::module &); \ - test_initializer name(#name, test_submodule_##name); \ - void test_submodule_##name(py::module &variable) - +#define TEST_SUBMODULE(name, variable) \ + void test_submodule_##name(py::module_ &); \ + test_initializer name(#name, test_submodule_##name); \ + void test_submodule_##name(py::module_ &(variable)) /// Dummy type which is not exported anywhere -- something to trigger a conversion error struct UnregisteredType { }; @@ -30,7 +32,7 @@ struct UnregisteredType { }; class UserType { public: UserType() = default; - UserType(int i) : i(i) { } + explicit UserType(int i) : i(i) { } int value() const { return i; } void set(int set) { i = set; } @@ -50,6 +52,12 @@ public: IncType &operator=(IncType &&) = delete; }; +/// A simple union for basic testing +union IntFloat { + int i; + float f; +}; + /// Custom cast-only type that casts to a string "rvalue" or "lvalue" depending on the cast context. /// Used to test recursive casters (e.g. std::tuple, stl containers). struct RValueCaster {}; @@ -57,9 +65,21 @@ PYBIND11_NAMESPACE_BEGIN(pybind11) PYBIND11_NAMESPACE_BEGIN(detail) template<> class type_caster { public: - PYBIND11_TYPE_CASTER(RValueCaster, _("RValueCaster")); + PYBIND11_TYPE_CASTER(RValueCaster, const_name("RValueCaster")); static handle cast(RValueCaster &&, return_value_policy, handle) { return py::str("rvalue").release(); } static handle cast(const RValueCaster &, return_value_policy, handle) { return py::str("lvalue").release(); } }; PYBIND11_NAMESPACE_END(detail) PYBIND11_NAMESPACE_END(pybind11) + +template +void ignoreOldStyleInitWarnings(F &&body) { + py::exec(R"( + message = "pybind11-bound class '.+' is using an old-style placement-new '(?:__init__|__setstate__)' which has been deprecated" + + import warnings + with warnings.catch_warnings(): + warnings.filterwarnings("ignore", message=message, category=FutureWarning) + body() + )", py::dict(py::arg("body") = py::cpp_function(body))); +} diff --git a/pybind11/tests/pytest.ini b/pybind11/tests/pytest.ini index c47cbe9c1..a3871d6c3 100644 --- a/pybind11/tests/pytest.ini +++ b/pybind11/tests/pytest.ini @@ -7,11 +7,11 @@ addopts = -rs # capture only Python print and C++ py::print, but not C output (low-level Python errors) --capture=sys - # enable all warnings - -Wa filterwarnings = # make warnings into errors but ignore certain third-party extension issues error + # somehow, some DeprecationWarnings do not get turned into errors + always::DeprecationWarning # importing scipy submodules on some version of Python ignore::ImportWarning # bogus numpy ABI warning (see numpy/#432) diff --git a/pybind11/tests/requirements.txt b/pybind11/tests/requirements.txt index 39bd57a1c..98ca46d28 100644 --- a/pybind11/tests/requirements.txt +++ b/pybind11/tests/requirements.txt @@ -1,8 +1,12 @@ ---extra-index-url https://antocuni.github.io/pypy-wheels/manylinux2010/ -numpy==1.16.6; python_version<"3.6" -numpy==1.18.0; platform_python_implementation=="PyPy" and sys_platform=="darwin" and python_version>="3.6" -numpy==1.19.1; (platform_python_implementation!="PyPy" or sys_platform!="darwin") and python_version>="3.6" and python_version<"3.9" +numpy==1.16.6; python_version<"3.6" and sys_platform!="win32" and platform_python_implementation!="PyPy" +numpy==1.19.0; platform_python_implementation=="PyPy" and sys_platform=="linux" and python_version=="3.6" +numpy==1.20.0; platform_python_implementation=="PyPy" and sys_platform=="linux" and python_version=="3.7" +numpy==1.19.3; platform_python_implementation!="PyPy" and python_version=="3.6" +numpy==1.21.3; platform_python_implementation!="PyPy" and python_version>="3.7" and python_version<"3.11" +py @ git+https://github.com/pytest-dev/py; python_version>="3.11" pytest==4.6.9; python_version<"3.5" -pytest==5.4.3; python_version>="3.5" -scipy==1.2.3; (platform_python_implementation!="PyPy" or sys_platform!="darwin") and python_version<"3.6" -scipy==1.5.2; (platform_python_implementation!="PyPy" or sys_platform!="darwin") and python_version>="3.6" and python_version<"3.9" +pytest==6.1.2; python_version=="3.5" +pytest==6.2.4; python_version>="3.6" +pytest-timeout +scipy==1.2.3; platform_python_implementation!="PyPy" and python_version<"3.6" +scipy==1.5.4; platform_python_implementation!="PyPy" and python_version>="3.6" and python_version<"3.10" diff --git a/pybind11/tests/test_async.cpp b/pybind11/tests/test_async.cpp index f0ad0d535..e6e01d72c 100644 --- a/pybind11/tests/test_async.cpp +++ b/pybind11/tests/test_async.cpp @@ -18,7 +18,7 @@ TEST_SUBMODULE(async_module, m) { .def(py::init<>()) .def("__await__", [](const SupportsAsync& self) -> py::object { static_cast(self); - py::object loop = py::module::import("asyncio.events").attr("get_event_loop")(); + py::object loop = py::module_::import("asyncio.events").attr("get_event_loop")(); py::object f = loop.attr("create_future")(); f.attr("set_result")(5); return f.attr("__await__")(); diff --git a/pybind11/tests/test_buffers.cpp b/pybind11/tests/test_buffers.cpp index 1bc67ff7b..3a8e3e7b7 100644 --- a/pybind11/tests/test_buffers.cpp +++ b/pybind11/tests/test_buffers.cpp @@ -9,12 +9,13 @@ #include "pybind11_tests.h" #include "constructor_stats.h" +#include TEST_SUBMODULE(buffers, m) { // test_from_python / test_to_python: class Matrix { public: - Matrix(ssize_t rows, ssize_t cols) : m_rows(rows), m_cols(cols) { + Matrix(py::ssize_t rows, py::ssize_t cols) : m_rows(rows), m_cols(cols) { print_created(this, std::to_string(m_rows) + "x" + std::to_string(m_cols) + " matrix"); m_data = new float[(size_t) (rows*cols)]; memset(m_data, 0, sizeof(float) * (size_t) (rows * cols)); @@ -26,7 +27,7 @@ TEST_SUBMODULE(buffers, m) { memcpy(m_data, s.m_data, sizeof(float) * (size_t) (m_rows * m_cols)); } - Matrix(Matrix &&s) : m_rows(s.m_rows), m_cols(s.m_cols), m_data(s.m_data) { + Matrix(Matrix &&s) noexcept : m_rows(s.m_rows), m_cols(s.m_cols), m_data(s.m_data) { print_move_created(this); s.m_rows = 0; s.m_cols = 0; @@ -39,7 +40,11 @@ TEST_SUBMODULE(buffers, m) { } Matrix &operator=(const Matrix &s) { - print_copy_assigned(this, std::to_string(m_rows) + "x" + std::to_string(m_cols) + " matrix"); + if (this == &s) { + return *this; + } + print_copy_assigned(this, + std::to_string(m_rows) + "x" + std::to_string(m_cols) + " matrix"); delete[] m_data; m_rows = s.m_rows; m_cols = s.m_cols; @@ -48,7 +53,7 @@ TEST_SUBMODULE(buffers, m) { return *this; } - Matrix &operator=(Matrix &&s) { + Matrix &operator=(Matrix &&s) noexcept { print_move_assigned(this, std::to_string(m_rows) + "x" + std::to_string(m_cols) + " matrix"); if (&s != this) { delete[] m_data; @@ -58,27 +63,27 @@ TEST_SUBMODULE(buffers, m) { return *this; } - float operator()(ssize_t i, ssize_t j) const { + float operator()(py::ssize_t i, py::ssize_t j) const { return m_data[(size_t) (i*m_cols + j)]; } - float &operator()(ssize_t i, ssize_t j) { + float &operator()(py::ssize_t i, py::ssize_t j) { return m_data[(size_t) (i*m_cols + j)]; } float *data() { return m_data; } - ssize_t rows() const { return m_rows; } - ssize_t cols() const { return m_cols; } + py::ssize_t rows() const { return m_rows; } + py::ssize_t cols() const { return m_cols; } private: - ssize_t m_rows; - ssize_t m_cols; + py::ssize_t m_rows; + py::ssize_t m_cols; float *m_data; }; py::class_(m, "Matrix", py::buffer_protocol()) - .def(py::init()) + .def(py::init()) /// Construct from a buffer - .def(py::init([](py::buffer const b) { + .def(py::init([](const py::buffer &b) { py::buffer_info info = b.request(); if (info.format != py::format_descriptor::format() || info.ndim != 2) throw std::runtime_error("Incompatible buffer format!"); @@ -88,40 +93,40 @@ TEST_SUBMODULE(buffers, m) { return v; })) - .def("rows", &Matrix::rows) - .def("cols", &Matrix::cols) + .def("rows", &Matrix::rows) + .def("cols", &Matrix::cols) /// Bare bones interface - .def("__getitem__", [](const Matrix &m, std::pair i) { - if (i.first >= m.rows() || i.second >= m.cols()) - throw py::index_error(); - return m(i.first, i.second); - }) - .def("__setitem__", [](Matrix &m, std::pair i, float v) { - if (i.first >= m.rows() || i.second >= m.cols()) - throw py::index_error(); - m(i.first, i.second) = v; - }) - /// Provide buffer access - .def_buffer([](Matrix &m) -> py::buffer_info { + .def("__getitem__", + [](const Matrix &m, std::pair i) { + if (i.first >= m.rows() || i.second >= m.cols()) + throw py::index_error(); + return m(i.first, i.second); + }) + .def("__setitem__", + [](Matrix &m, std::pair i, float v) { + if (i.first >= m.rows() || i.second >= m.cols()) + throw py::index_error(); + m(i.first, i.second) = v; + }) + /// Provide buffer access + .def_buffer([](Matrix &m) -> py::buffer_info { return py::buffer_info( m.data(), /* Pointer to buffer */ { m.rows(), m.cols() }, /* Buffer dimensions */ { sizeof(float) * size_t(m.cols()), /* Strides (in bytes) for each index */ sizeof(float) } ); - }) - ; - + }); // test_inherited_protocol class SquareMatrix : public Matrix { public: - SquareMatrix(ssize_t n) : Matrix(n, n) { } + explicit SquareMatrix(py::ssize_t n) : Matrix(n, n) {} }; // Derived classes inherit the buffer protocol and the buffer access function py::class_(m, "SquareMatrix") - .def(py::init()); + .def(py::init()); // test_pointer_to_member_fn @@ -153,7 +158,7 @@ TEST_SUBMODULE(buffers, m) { py::format_descriptor::format(), 1); } - ConstBuffer() : value(new int32_t{0}) { }; + ConstBuffer() : value(new int32_t{0}) {} }; py::class_(m, "ConstBuffer", py::buffer_protocol()) .def(py::init<>()) @@ -168,7 +173,7 @@ TEST_SUBMODULE(buffers, m) { struct BufferReadOnly { const uint8_t value = 0; - BufferReadOnly(uint8_t value): value(value) {} + explicit BufferReadOnly(uint8_t value) : value(value) {} py::buffer_info get_buffer_info() { return py::buffer_info(&value, 1); @@ -192,4 +197,20 @@ TEST_SUBMODULE(buffers, m) { .def_readwrite("readonly", &BufferReadOnlySelect::readonly) .def_buffer(&BufferReadOnlySelect::get_buffer_info); + // Expose buffer_info for testing. + py::class_(m, "buffer_info") + .def(py::init<>()) + .def_readonly("itemsize", &py::buffer_info::itemsize) + .def_readonly("size", &py::buffer_info::size) + .def_readonly("format", &py::buffer_info::format) + .def_readonly("ndim", &py::buffer_info::ndim) + .def_readonly("shape", &py::buffer_info::shape) + .def_readonly("strides", &py::buffer_info::strides) + .def_readonly("readonly", &py::buffer_info::readonly) + .def("__repr__", [](py::handle self) { + return py::str("itemsize={0.itemsize!r}, size={0.size!r}, format={0.format!r}, ndim={0.ndim!r}, shape={0.shape!r}, strides={0.strides!r}, readonly={0.readonly!r}").format(self); + }) + ; + + m.def("get_buffer_info", [](const py::buffer &buffer) { return buffer.request(); }); } diff --git a/pybind11/tests/test_buffers.py b/pybind11/tests/test_buffers.py index d6adaf1f5..0d5bf16c3 100644 --- a/pybind11/tests/test_buffers.py +++ b/pybind11/tests/test_buffers.py @@ -1,13 +1,13 @@ # -*- coding: utf-8 -*- +import ctypes import io import struct import pytest -import env # noqa: F401 - -from pybind11_tests import buffers as m +import env from pybind11_tests import ConstructorStats +from pybind11_tests import buffers as m np = pytest.importorskip("numpy") @@ -36,6 +36,10 @@ def test_from_python(): # https://foss.heptapod.net/pypy/pypy/-/issues/2444 +# TODO: fix on recent PyPy +@pytest.mark.xfail( + env.PYPY, reason="PyPy 7.3.7 doesn't clear this anymore", strict=False +) def test_to_python(): mat = m.Matrix(5, 4) assert memoryview(mat).shape == (5, 4) @@ -45,8 +49,8 @@ def test_to_python(): mat[3, 2] = 7.0 assert mat[2, 3] == 4 assert mat[3, 2] == 7 - assert struct.unpack_from('f', mat, (3 * 4 + 2) * 4) == (7, ) - assert struct.unpack_from('f', mat, (2 * 4 + 3) * 4) == (4, ) + assert struct.unpack_from("f", mat, (3 * 4 + 2) * 4) == (7,) + assert struct.unpack_from("f", mat, (2 * 4 + 3) * 4) == (4,) mat2 = np.array(mat, copy=False) assert mat2.shape == (5, 4) @@ -82,28 +86,82 @@ def test_pointer_to_member_fn(): for cls in [m.Buffer, m.ConstBuffer, m.DerivedBuffer]: buf = cls() buf.value = 0x12345678 - value = struct.unpack('i', bytearray(buf))[0] + value = struct.unpack("i", bytearray(buf))[0] assert value == 0x12345678 def test_readonly_buffer(): buf = m.BufferReadOnly(0x64) view = memoryview(buf) - assert view[0] == b'd' if env.PY2 else 0x64 + assert view[0] == b"d" if env.PY2 else 0x64 assert view.readonly + with pytest.raises(TypeError): + view[0] = b"\0" if env.PY2 else 0 def test_selective_readonly_buffer(): buf = m.BufferReadOnlySelect() - memoryview(buf)[0] = b'd' if env.PY2 else 0x64 + memoryview(buf)[0] = b"d" if env.PY2 else 0x64 assert buf.value == 0x64 - io.BytesIO(b'A').readinto(buf) - assert buf.value == ord(b'A') + io.BytesIO(b"A").readinto(buf) + assert buf.value == ord(b"A") buf.readonly = True with pytest.raises(TypeError): - memoryview(buf)[0] = b'\0' if env.PY2 else 0 + memoryview(buf)[0] = b"\0" if env.PY2 else 0 with pytest.raises(TypeError): - io.BytesIO(b'1').readinto(buf) + io.BytesIO(b"1").readinto(buf) + + +def test_ctypes_array_1d(): + char1d = (ctypes.c_char * 10)() + int1d = (ctypes.c_int * 15)() + long1d = (ctypes.c_long * 7)() + + for carray in (char1d, int1d, long1d): + info = m.get_buffer_info(carray) + assert info.itemsize == ctypes.sizeof(carray._type_) + assert info.size == len(carray) + assert info.ndim == 1 + assert info.shape == [info.size] + assert info.strides == [info.itemsize] + assert not info.readonly + + +def test_ctypes_array_2d(): + char2d = ((ctypes.c_char * 10) * 4)() + int2d = ((ctypes.c_int * 15) * 3)() + long2d = ((ctypes.c_long * 7) * 2)() + + for carray in (char2d, int2d, long2d): + info = m.get_buffer_info(carray) + assert info.itemsize == ctypes.sizeof(carray[0]._type_) + assert info.size == len(carray) * len(carray[0]) + assert info.ndim == 2 + assert info.shape == [len(carray), len(carray[0])] + assert info.strides == [info.itemsize * len(carray[0]), info.itemsize] + assert not info.readonly + + +@pytest.mark.skipif( + "env.PYPY and env.PY2", reason="PyPy2 bytes buffer not reported as readonly" +) +def test_ctypes_from_buffer(): + test_pystr = b"0123456789" + for pyarray in (test_pystr, bytearray(test_pystr)): + pyinfo = m.get_buffer_info(pyarray) + + if pyinfo.readonly: + cbytes = (ctypes.c_char * len(pyarray)).from_buffer_copy(pyarray) + cinfo = m.get_buffer_info(cbytes) + else: + cbytes = (ctypes.c_char * len(pyarray)).from_buffer(pyarray) + cinfo = m.get_buffer_info(cbytes) + + assert cinfo.size == pyinfo.size + assert cinfo.ndim == pyinfo.ndim + assert cinfo.shape == pyinfo.shape + assert cinfo.strides == pyinfo.strides + assert not cinfo.readonly diff --git a/pybind11/tests/test_builtin_casters.cpp b/pybind11/tests/test_builtin_casters.cpp index acc9f8fb3..4a9f33837 100644 --- a/pybind11/tests/test_builtin_casters.cpp +++ b/pybind11/tests/test_builtin_casters.cpp @@ -10,10 +10,64 @@ #include "pybind11_tests.h" #include -#if defined(_MSC_VER) -# pragma warning(push) -# pragma warning(disable: 4127) // warning C4127: Conditional expression is constant -#endif +struct ConstRefCasted { + int tag; +}; + +PYBIND11_NAMESPACE_BEGIN(pybind11) +PYBIND11_NAMESPACE_BEGIN(detail) +template <> +class type_caster { + public: + static constexpr auto name = const_name(); + + // Input is unimportant, a new value will always be constructed based on the + // cast operator. + bool load(handle, bool) { return true; } + + explicit operator ConstRefCasted &&() { + value = {1}; + // NOLINTNEXTLINE(performance-move-const-arg) + return std::move(value); + } + explicit operator ConstRefCasted &() { + value = {2}; + return value; + } + explicit operator ConstRefCasted *() { + value = {3}; + return &value; + } + + explicit operator const ConstRefCasted &() { + value = {4}; + return value; + } + explicit operator const ConstRefCasted *() { + value = {5}; + return &value; + } + + // custom cast_op to explicitly propagate types to the conversion operators. + template + using cast_op_type = + /// const + conditional_t< + std::is_same, const ConstRefCasted*>::value, const ConstRefCasted*, + conditional_t< + std::is_same::value, const ConstRefCasted&, + /// non-const + conditional_t< + std::is_same, ConstRefCasted*>::value, ConstRefCasted*, + conditional_t< + std::is_same::value, ConstRefCasted&, + /* else */ConstRefCasted&&>>>>; + + private: + ConstRefCasted value = {0}; +}; +PYBIND11_NAMESPACE_END(detail) +PYBIND11_NAMESPACE_END(pybind11) TEST_SUBMODULE(builtin_casters, m) { // test_simple_string @@ -26,7 +80,7 @@ TEST_SUBMODULE(builtin_casters, m) { std::wstring wstr; wstr.push_back(0x61); // a wstr.push_back(0x2e18); // ⸘ - if (sizeof(wchar_t) == 2) { wstr.push_back(mathbfA16_1); wstr.push_back(mathbfA16_2); } // 𝐀, utf16 + if (PYBIND11_SILENCE_MSVC_C4127(sizeof(wchar_t) == 2)) { wstr.push_back(mathbfA16_1); wstr.push_back(mathbfA16_2); } // 𝐀, utf16 else { wstr.push_back((wchar_t) mathbfA32); } // 𝐀, utf32 wstr.push_back(0x7a); // z @@ -36,11 +90,12 @@ TEST_SUBMODULE(builtin_casters, m) { m.def("good_wchar_string", [=]() { return wstr; }); // a‽𝐀z m.def("bad_utf8_string", []() { return std::string("abc\xd0" "def"); }); m.def("bad_utf16_string", [=]() { return std::u16string({ b16, char16_t(0xd800), z16 }); }); +#if PY_MAJOR_VERSION >= 3 // Under Python 2.7, invalid unicode UTF-32 characters don't appear to trigger UnicodeDecodeError - if (PY_MAJOR_VERSION >= 3) - m.def("bad_utf32_string", [=]() { return std::u32string({ a32, char32_t(0xd800), z32 }); }); - if (PY_MAJOR_VERSION >= 3 || sizeof(wchar_t) == 2) + m.def("bad_utf32_string", [=]() { return std::u32string({ a32, char32_t(0xd800), z32 }); }); + if (PYBIND11_SILENCE_MSVC_C4127(sizeof(wchar_t) == 2)) m.def("bad_wchar_string", [=]() { return std::wstring({ wchar_t(0x61), wchar_t(0xd800) }); }); +#endif m.def("u8_Z", []() -> char { return 'Z'; }); m.def("u8_eacute", []() -> char { return '\xe9'; }); m.def("u16_ibang", [=]() -> char16_t { return ib16; }); @@ -58,7 +113,7 @@ TEST_SUBMODULE(builtin_casters, m) { // test_bytes_to_string m.def("strlen", [](char *s) { return strlen(s); }); - m.def("string_length", [](std::string s) { return s.length(); }); + m.def("string_length", [](const std::string &s) { return s.length(); }); #ifdef PYBIND11_HAS_U8STRING m.attr("has_u8string") = true; @@ -85,11 +140,35 @@ TEST_SUBMODULE(builtin_casters, m) { m.def("string_view16_return", []() { return std::u16string_view(u"utf16 secret \U0001f382"); }); m.def("string_view32_return", []() { return std::u32string_view(U"utf32 secret \U0001f382"); }); + // The inner lambdas here are to also test implicit conversion + using namespace std::literals; + m.def("string_view_bytes", []() { return [](py::bytes b) { return b; }("abc \x80\x80 def"sv); }); + m.def("string_view_str", []() { return [](py::str s) { return s; }("abc \342\200\275 def"sv); }); + m.def("string_view_from_bytes", [](const py::bytes &b) { return [](std::string_view s) { return s; }(b); }); +#if PY_MAJOR_VERSION >= 3 + m.def("string_view_memoryview", []() { + static constexpr auto val = "Have some \360\237\216\202"sv; + return py::memoryview::from_memory(val); + }); +#endif + # ifdef PYBIND11_HAS_U8STRING m.def("string_view8_print", [](std::u8string_view s) { py::print(s, s.size()); }); m.def("string_view8_chars", [](std::u8string_view s) { py::list l; for (auto c : s) l.append((std::uint8_t) c); return l; }); m.def("string_view8_return", []() { return std::u8string_view(u8"utf8 secret \U0001f382"); }); + m.def("string_view8_str", []() { return py::str{std::u8string_view{u8"abc ‽ def"}}; }); # endif + + struct TypeWithBothOperatorStringAndStringView { + // NOLINTNEXTLINE(google-explicit-constructor) + operator std::string() const { return "success"; } + // NOLINTNEXTLINE(google-explicit-constructor) + operator std::string_view() const { return "failure"; } + }; + m.def("bytes_from_type_with_both_operator_string_and_string_view", + []() { return py::bytes(TypeWithBothOperatorStringAndStringView()); }); + m.def("str_from_type_with_both_operator_string_and_string_view", + []() { return py::str(TypeWithBothOperatorStringAndStringView()); }); #endif // test_integer_casting @@ -98,10 +177,17 @@ TEST_SUBMODULE(builtin_casters, m) { m.def("i64_str", [](std::int64_t v) { return std::to_string(v); }); m.def("u64_str", [](std::uint64_t v) { return std::to_string(v); }); + // test_int_convert + m.def("int_passthrough", [](int arg) { return arg; }); + m.def("int_passthrough_noconvert", [](int arg) { return arg; }, py::arg{}.noconvert()); + // test_tuple - m.def("pair_passthrough", [](std::pair input) { - return std::make_pair(input.second, input.first); - }, "Return a pair in reversed order"); + m.def( + "pair_passthrough", + [](const std::pair &input) { + return std::make_pair(input.second, input.first); + }, + "Return a pair in reversed order"); m.def("tuple_passthrough", [](std::tuple input) { return std::make_tuple(std::get<2>(input), std::get<1>(input), std::get<0>(input)); }, "Return a triple in reversed order"); @@ -130,23 +216,45 @@ TEST_SUBMODULE(builtin_casters, m) { // test_none_deferred m.def("defer_none_cstring", [](char *) { return false; }); - m.def("defer_none_cstring", [](py::none) { return true; }); + m.def("defer_none_cstring", [](const py::none &) { return true; }); m.def("defer_none_custom", [](UserType *) { return false; }); - m.def("defer_none_custom", [](py::none) { return true; }); + m.def("defer_none_custom", [](const py::none &) { return true; }); m.def("nodefer_none_void", [](void *) { return true; }); - m.def("nodefer_none_void", [](py::none) { return false; }); + m.def("nodefer_none_void", [](const py::none &) { return false; }); // test_void_caster m.def("load_nullptr_t", [](std::nullptr_t) {}); // not useful, but it should still compile m.def("cast_nullptr_t", []() { return std::nullptr_t{}; }); + // [workaround(intel)] ICC 20/21 breaks with py::arg().stuff, using py::arg{}.stuff works. + // test_bool_caster m.def("bool_passthrough", [](bool arg) { return arg; }); - m.def("bool_passthrough_noconvert", [](bool arg) { return arg; }, py::arg().noconvert()); + m.def("bool_passthrough_noconvert", [](bool arg) { return arg; }, py::arg{}.noconvert()); + + // TODO: This should be disabled and fixed in future Intel compilers +#if !defined(__INTEL_COMPILER) + // Test "bool_passthrough_noconvert" again, but using () instead of {} to construct py::arg + // When compiled with the Intel compiler, this results in segmentation faults when importing + // the module. Tested with icc (ICC) 2021.1 Beta 20200827, this should be tested again when + // a newer version of icc is available. + m.def("bool_passthrough_noconvert2", [](bool arg) { return arg; }, py::arg().noconvert()); +#endif // test_reference_wrapper m.def("refwrap_builtin", [](std::reference_wrapper p) { return 10 * p.get(); }); m.def("refwrap_usertype", [](std::reference_wrapper p) { return p.get().value(); }); + m.def("refwrap_usertype_const", [](std::reference_wrapper p) { return p.get().value(); }); + + m.def("refwrap_lvalue", []() -> std::reference_wrapper { + static UserType x(1); + return std::ref(x); + }); + m.def("refwrap_lvalue_const", []() -> std::reference_wrapper { + static UserType x(1); + return std::cref(x); + }); + // Not currently supported (std::pair caster has return-by-value cast operator); // triggers static_assert failure. //m.def("refwrap_pair", [](std::reference_wrapper>) { }); @@ -162,7 +270,7 @@ TEST_SUBMODULE(builtin_casters, m) { }, "copy"_a); m.def("refwrap_iiw", [](const IncType &w) { return w.value(); }); - m.def("refwrap_call_iiw", [](IncType &w, py::function f) { + m.def("refwrap_call_iiw", [](IncType &w, const py::function &f) { py::list l; l.append(f(std::ref(w))); l.append(f(std::cref(w))); @@ -189,4 +297,14 @@ TEST_SUBMODULE(builtin_casters, m) { py::object o = py::cast(v); return py::cast(o) == v; }); + + // Tests const/non-const propagation in cast_op. + m.def("takes", [](ConstRefCasted x) { return x.tag; }); + m.def("takes_move", [](ConstRefCasted&& x) { return x.tag; }); + m.def("takes_ptr", [](ConstRefCasted* x) { return x->tag; }); + m.def("takes_ref", [](ConstRefCasted& x) { return x.tag; }); + m.def("takes_ref_wrap", [](std::reference_wrapper x) { return x.get().tag; }); + m.def("takes_const_ptr", [](const ConstRefCasted* x) { return x->tag; }); + m.def("takes_const_ref", [](const ConstRefCasted& x) { return x.tag; }); + m.def("takes_const_ref_wrap", [](std::reference_wrapper x) { return x.get().tag; }); } diff --git a/pybind11/tests/test_builtin_casters.py b/pybind11/tests/test_builtin_casters.py index 08d38bc15..b1f1e395a 100644 --- a/pybind11/tests/test_builtin_casters.py +++ b/pybind11/tests/test_builtin_casters.py @@ -1,10 +1,9 @@ # -*- coding: utf-8 -*- import pytest -import env # noqa: F401 - +import env +from pybind11_tests import IncType, UserType from pybind11_tests import builtin_casters as m -from pybind11_tests import UserType, IncType def test_simple_string(): @@ -37,79 +36,85 @@ def test_unicode_conversion(): with pytest.raises(UnicodeDecodeError): m.bad_utf8_u8string() - assert m.u8_Z() == 'Z' - assert m.u8_eacute() == u'é' - assert m.u16_ibang() == u'‽' - assert m.u32_mathbfA() == u'𝐀' - assert m.wchar_heart() == u'♥' + assert m.u8_Z() == "Z" + assert m.u8_eacute() == u"é" + assert m.u16_ibang() == u"‽" + assert m.u32_mathbfA() == u"𝐀" + assert m.wchar_heart() == u"♥" if hasattr(m, "has_u8string"): - assert m.u8_char8_Z() == 'Z' + assert m.u8_char8_Z() == "Z" def test_single_char_arguments(): """Tests failures for passing invalid inputs to char-accepting functions""" + def toobig_message(r): - return "Character code point not in range({0:#x})".format(r) + return "Character code point not in range({:#x})".format(r) + toolong_message = "Expected a character, but multi-character string found" - assert m.ord_char(u'a') == 0x61 # simple ASCII - assert m.ord_char_lv(u'b') == 0x62 - assert m.ord_char(u'é') == 0xE9 # requires 2 bytes in utf-8, but can be stuffed in a char + assert m.ord_char(u"a") == 0x61 # simple ASCII + assert m.ord_char_lv(u"b") == 0x62 + assert ( + m.ord_char(u"é") == 0xE9 + ) # requires 2 bytes in utf-8, but can be stuffed in a char with pytest.raises(ValueError) as excinfo: - assert m.ord_char(u'Ā') == 0x100 # requires 2 bytes, doesn't fit in a char + assert m.ord_char(u"Ā") == 0x100 # requires 2 bytes, doesn't fit in a char assert str(excinfo.value) == toobig_message(0x100) with pytest.raises(ValueError) as excinfo: - assert m.ord_char(u'ab') + assert m.ord_char(u"ab") assert str(excinfo.value) == toolong_message - assert m.ord_char16(u'a') == 0x61 - assert m.ord_char16(u'é') == 0xE9 - assert m.ord_char16_lv(u'ê') == 0xEA - assert m.ord_char16(u'Ā') == 0x100 - assert m.ord_char16(u'‽') == 0x203d - assert m.ord_char16(u'♥') == 0x2665 - assert m.ord_char16_lv(u'♡') == 0x2661 + assert m.ord_char16(u"a") == 0x61 + assert m.ord_char16(u"é") == 0xE9 + assert m.ord_char16_lv(u"ê") == 0xEA + assert m.ord_char16(u"Ā") == 0x100 + assert m.ord_char16(u"‽") == 0x203D + assert m.ord_char16(u"♥") == 0x2665 + assert m.ord_char16_lv(u"♡") == 0x2661 with pytest.raises(ValueError) as excinfo: - assert m.ord_char16(u'🎂') == 0x1F382 # requires surrogate pair + assert m.ord_char16(u"🎂") == 0x1F382 # requires surrogate pair assert str(excinfo.value) == toobig_message(0x10000) with pytest.raises(ValueError) as excinfo: - assert m.ord_char16(u'aa') + assert m.ord_char16(u"aa") assert str(excinfo.value) == toolong_message - assert m.ord_char32(u'a') == 0x61 - assert m.ord_char32(u'é') == 0xE9 - assert m.ord_char32(u'Ā') == 0x100 - assert m.ord_char32(u'‽') == 0x203d - assert m.ord_char32(u'♥') == 0x2665 - assert m.ord_char32(u'🎂') == 0x1F382 + assert m.ord_char32(u"a") == 0x61 + assert m.ord_char32(u"é") == 0xE9 + assert m.ord_char32(u"Ā") == 0x100 + assert m.ord_char32(u"‽") == 0x203D + assert m.ord_char32(u"♥") == 0x2665 + assert m.ord_char32(u"🎂") == 0x1F382 with pytest.raises(ValueError) as excinfo: - assert m.ord_char32(u'aa') + assert m.ord_char32(u"aa") assert str(excinfo.value) == toolong_message - assert m.ord_wchar(u'a') == 0x61 - assert m.ord_wchar(u'é') == 0xE9 - assert m.ord_wchar(u'Ā') == 0x100 - assert m.ord_wchar(u'‽') == 0x203d - assert m.ord_wchar(u'♥') == 0x2665 + assert m.ord_wchar(u"a") == 0x61 + assert m.ord_wchar(u"é") == 0xE9 + assert m.ord_wchar(u"Ā") == 0x100 + assert m.ord_wchar(u"‽") == 0x203D + assert m.ord_wchar(u"♥") == 0x2665 if m.wchar_size == 2: with pytest.raises(ValueError) as excinfo: - assert m.ord_wchar(u'🎂') == 0x1F382 # requires surrogate pair + assert m.ord_wchar(u"🎂") == 0x1F382 # requires surrogate pair assert str(excinfo.value) == toobig_message(0x10000) else: - assert m.ord_wchar(u'🎂') == 0x1F382 + assert m.ord_wchar(u"🎂") == 0x1F382 with pytest.raises(ValueError) as excinfo: - assert m.ord_wchar(u'aa') + assert m.ord_wchar(u"aa") assert str(excinfo.value) == toolong_message if hasattr(m, "has_u8string"): - assert m.ord_char8(u'a') == 0x61 # simple ASCII - assert m.ord_char8_lv(u'b') == 0x62 - assert m.ord_char8(u'é') == 0xE9 # requires 2 bytes in utf-8, but can be stuffed in a char + assert m.ord_char8(u"a") == 0x61 # simple ASCII + assert m.ord_char8_lv(u"b") == 0x62 + assert ( + m.ord_char8(u"é") == 0xE9 + ) # requires 2 bytes in utf-8, but can be stuffed in a char with pytest.raises(ValueError) as excinfo: - assert m.ord_char8(u'Ā') == 0x100 # requires 2 bytes, doesn't fit in a char + assert m.ord_char8(u"Ā") == 0x100 # requires 2 bytes, doesn't fit in a char assert str(excinfo.value) == toobig_message(0x100) with pytest.raises(ValueError) as excinfo: - assert m.ord_char8(u'ab') + assert m.ord_char8(u"ab") assert str(excinfo.value) == toolong_message @@ -129,19 +134,19 @@ def test_bytes_to_string(): assert m.strlen(to_bytes("a\x00b")) == 1 # C-string limitation # passing in a utf8 encoded string should work - assert m.string_length(u'💩'.encode("utf8")) == 4 + assert m.string_length(u"💩".encode("utf8")) == 4 @pytest.mark.skipif(not hasattr(m, "has_string_view"), reason="no ") def test_string_view(capture): """Tests support for C++17 string_view arguments and return values""" assert m.string_view_chars("Hi") == [72, 105] - assert m.string_view_chars("Hi 🎂") == [72, 105, 32, 0xf0, 0x9f, 0x8e, 0x82] - assert m.string_view16_chars(u"Hi 🎂") == [72, 105, 32, 0xd83c, 0xdf82] + assert m.string_view_chars("Hi 🎂") == [72, 105, 32, 0xF0, 0x9F, 0x8E, 0x82] + assert m.string_view16_chars(u"Hi 🎂") == [72, 105, 32, 0xD83C, 0xDF82] assert m.string_view32_chars(u"Hi 🎂") == [72, 105, 32, 127874] if hasattr(m, "has_u8string"): assert m.string_view8_chars("Hi") == [72, 105] - assert m.string_view8_chars(u"Hi 🎂") == [72, 105, 32, 0xf0, 0x9f, 0x8e, 0x82] + assert m.string_view8_chars(u"Hi 🎂") == [72, 105, 32, 0xF0, 0x9F, 0x8E, 0x82] assert m.string_view_return() == u"utf8 secret 🎂" assert m.string_view16_return() == u"utf16 secret 🎂" @@ -154,40 +159,63 @@ def test_string_view(capture): m.string_view_print("utf8 🎂") m.string_view16_print(u"utf16 🎂") m.string_view32_print(u"utf32 🎂") - assert capture == u""" + assert ( + capture + == u""" Hi 2 utf8 🎂 9 utf16 🎂 8 utf32 🎂 7 """ + ) if hasattr(m, "has_u8string"): with capture: m.string_view8_print("Hi") m.string_view8_print(u"utf8 🎂") - assert capture == u""" + assert ( + capture + == u""" Hi 2 utf8 🎂 9 """ + ) with capture: m.string_view_print("Hi, ascii") m.string_view_print("Hi, utf8 🎂") m.string_view16_print(u"Hi, utf16 🎂") m.string_view32_print(u"Hi, utf32 🎂") - assert capture == u""" + assert ( + capture + == u""" Hi, ascii 9 Hi, utf8 🎂 13 Hi, utf16 🎂 12 Hi, utf32 🎂 11 """ + ) if hasattr(m, "has_u8string"): with capture: m.string_view8_print("Hi, ascii") m.string_view8_print(u"Hi, utf8 🎂") - assert capture == u""" + assert ( + capture + == u""" Hi, ascii 9 Hi, utf8 🎂 13 """ + ) + + assert m.string_view_bytes() == b"abc \x80\x80 def" + assert m.string_view_str() == u"abc ‽ def" + assert m.string_view_from_bytes(u"abc ‽ def".encode("utf-8")) == u"abc ‽ def" + if hasattr(m, "has_u8string"): + assert m.string_view8_str() == u"abc ‽ def" + if not env.PY2: + assert m.string_view_memoryview() == "Have some 🎂".encode() + + assert m.bytes_from_type_with_both_operator_string_and_string_view() == b"success" + assert m.str_from_type_with_both_operator_string_and_string_view() == "success" def test_integer_casting(): @@ -199,8 +227,14 @@ def test_integer_casting(): if env.PY2: assert m.i32_str(long(-1)) == "-1" # noqa: F821 undefined name 'long' assert m.i64_str(long(-1)) == "-1" # noqa: F821 undefined name 'long' - assert m.i64_str(long(-999999999999)) == "-999999999999" # noqa: F821 undefined name - assert m.u64_str(long(999999999999)) == "999999999999" # noqa: F821 undefined name 'long' + assert ( + m.i64_str(long(-999999999999)) # noqa: F821 undefined name 'long' + == "-999999999999" + ) + assert ( + m.u64_str(long(999999999999)) # noqa: F821 undefined name 'long' + == "999999999999" + ) else: assert m.i64_str(-999999999999) == "-999999999999" assert m.u64_str(999999999999) == "999999999999" @@ -227,6 +261,101 @@ def test_integer_casting(): assert "incompatible function arguments" in str(excinfo.value) +def test_int_convert(): + class Int(object): + def __int__(self): + return 42 + + class NotInt(object): + pass + + class Float(object): + def __float__(self): + return 41.99999 + + class Index(object): + def __index__(self): + return 42 + + class IntAndIndex(object): + def __int__(self): + return 42 + + def __index__(self): + return 0 + + class RaisingTypeErrorOnIndex(object): + def __index__(self): + raise TypeError + + def __int__(self): + return 42 + + class RaisingValueErrorOnIndex(object): + def __index__(self): + raise ValueError + + def __int__(self): + return 42 + + convert, noconvert = m.int_passthrough, m.int_passthrough_noconvert + + def requires_conversion(v): + pytest.raises(TypeError, noconvert, v) + + def cant_convert(v): + pytest.raises(TypeError, convert, v) + + assert convert(7) == 7 + assert noconvert(7) == 7 + cant_convert(3.14159) + # TODO: Avoid DeprecationWarning in `PyLong_AsLong` (and similar) + # TODO: PyPy 3.8 does not behave like CPython 3.8 here yet (7.3.7) + if (3, 8) <= env.PY < (3, 10) and env.CPYTHON: + with env.deprecated_call(): + assert convert(Int()) == 42 + else: + assert convert(Int()) == 42 + requires_conversion(Int()) + cant_convert(NotInt()) + cant_convert(Float()) + + # Before Python 3.8, `PyLong_AsLong` does not pick up on `obj.__index__`, + # but pybind11 "backports" this behavior. + assert convert(Index()) == 42 + assert noconvert(Index()) == 42 + assert convert(IntAndIndex()) == 0 # Fishy; `int(DoubleThought)` == 42 + assert noconvert(IntAndIndex()) == 0 + assert convert(RaisingTypeErrorOnIndex()) == 42 + requires_conversion(RaisingTypeErrorOnIndex()) + assert convert(RaisingValueErrorOnIndex()) == 42 + requires_conversion(RaisingValueErrorOnIndex()) + + +def test_numpy_int_convert(): + np = pytest.importorskip("numpy") + + convert, noconvert = m.int_passthrough, m.int_passthrough_noconvert + + def require_implicit(v): + pytest.raises(TypeError, noconvert, v) + + # `np.intc` is an alias that corresponds to a C++ `int` + assert convert(np.intc(42)) == 42 + assert noconvert(np.intc(42)) == 42 + + # The implicit conversion from np.float32 is undesirable but currently accepted. + # TODO: Avoid DeprecationWarning in `PyLong_AsLong` (and similar) + # TODO: PyPy 3.8 does not behave like CPython 3.8 here yet (7.3.7) + # https://github.com/pybind/pybind11/issues/3408 + if (3, 8) <= env.PY < (3, 10) and env.CPYTHON: + with env.deprecated_call(): + assert convert(np.float32(3.14159)) == 3 + else: + assert convert(np.float32(3.14159)) == 3 + require_implicit(np.float32(3.14159)) + + def test_tuple(doc): """std::pair <-> tuple & std::tuple <-> tuple""" assert m.pair_passthrough((True, "test")) == ("test", True) @@ -236,16 +365,22 @@ def test_tuple(doc): assert m.tuple_passthrough([True, "test", 5]) == (5, "test", True) assert m.empty_tuple() == () - assert doc(m.pair_passthrough) == """ + assert ( + doc(m.pair_passthrough) + == """ pair_passthrough(arg0: Tuple[bool, str]) -> Tuple[str, bool] Return a pair in reversed order """ - assert doc(m.tuple_passthrough) == """ + ) + assert ( + doc(m.tuple_passthrough) + == """ tuple_passthrough(arg0: Tuple[bool, str, int]) -> Tuple[int, str, bool] Return a triple in reversed order """ + ) assert m.rvalue_pair() == ("rvalue", "rvalue") assert m.lvalue_pair() == ("lvalue", "lvalue") @@ -285,6 +420,7 @@ def test_reference_wrapper(): """std::reference_wrapper for builtin and user types""" assert m.refwrap_builtin(42) == 420 assert m.refwrap_usertype(UserType(42)) == 42 + assert m.refwrap_usertype_const(UserType(42)) == 42 with pytest.raises(TypeError) as excinfo: m.refwrap_builtin(None) @@ -294,6 +430,9 @@ def test_reference_wrapper(): m.refwrap_usertype(None) assert "incompatible function arguments" in str(excinfo.value) + assert m.refwrap_lvalue().value == 1 + assert m.refwrap_lvalue_const().value == 1 + a1 = m.refwrap_list(copy=True) a2 = m.refwrap_list(copy=True) assert [x.value for x in a1] == [2, 3] @@ -372,7 +511,7 @@ def test_numpy_bool(): assert convert(np.bool_(False)) is False assert noconvert(np.bool_(True)) is True assert noconvert(np.bool_(False)) is False - cant_convert(np.zeros(2, dtype='int')) + cant_convert(np.zeros(2, dtype="int")) def test_int_long(): @@ -382,7 +521,8 @@ def test_int_long(): long.""" import sys - must_be_long = type(getattr(sys, 'maxint', 1) + 1) + + must_be_long = type(getattr(sys, "maxint", 1) + 1) assert isinstance(m.int_cast(), int) assert isinstance(m.long_cast(), int) assert isinstance(m.longlong_cast(), must_be_long) @@ -390,3 +530,21 @@ def test_int_long(): def test_void_caster_2(): assert m.test_void_caster() + + +def test_const_ref_caster(): + """Verifies that const-ref is propagated through type_caster cast_op. + The returned ConstRefCasted type is a minimal type that is constructed to + reference the casting mode used. + """ + x = False + assert m.takes(x) == 1 + assert m.takes_move(x) == 1 + + assert m.takes_ptr(x) == 3 + assert m.takes_ref(x) == 2 + assert m.takes_ref_wrap(x) == 2 + + assert m.takes_const_ptr(x) == 5 + assert m.takes_const_ref(x) == 4 + assert m.takes_const_ref_wrap(x) == 4 diff --git a/pybind11/tests/test_call_policies.cpp b/pybind11/tests/test_call_policies.cpp index 26c83f81b..7cb98d0d8 100644 --- a/pybind11/tests/test_call_policies.cpp +++ b/pybind11/tests/test_call_policies.cpp @@ -51,6 +51,7 @@ TEST_SUBMODULE(call_policies, m) { void addChild(Child *) { } Child *returnChild() { return new Child(); } Child *returnNullChild() { return nullptr; } + static Child *staticFunction(Parent*) { return new Child(); } }; py::class_(m, "Parent") .def(py::init<>()) @@ -60,7 +61,12 @@ TEST_SUBMODULE(call_policies, m) { .def("returnChild", &Parent::returnChild) .def("returnChildKeepAlive", &Parent::returnChild, py::keep_alive<1, 0>()) .def("returnNullChildKeepAliveChild", &Parent::returnNullChild, py::keep_alive<1, 0>()) - .def("returnNullChildKeepAliveParent", &Parent::returnNullChild, py::keep_alive<0, 1>()); + .def("returnNullChildKeepAliveParent", &Parent::returnNullChild, py::keep_alive<0, 1>()) + .def_static( + "staticFunction", &Parent::staticFunction, py::keep_alive<1, 0>()); + + m.def("free_function", [](Parent*, Child*) {}, py::keep_alive<1, 2>()); + m.def("invalid_arg_index", []{}, py::keep_alive<0, 1>()); #if !defined(PYPY_VERSION) // test_alive_gc diff --git a/pybind11/tests/test_call_policies.py b/pybind11/tests/test_call_policies.py index ec005c132..3599cf81a 100644 --- a/pybind11/tests/test_call_policies.py +++ b/pybind11/tests/test_call_policies.py @@ -2,9 +2,8 @@ import pytest import env # noqa: F401 - -from pybind11_tests import call_policies as m from pybind11_tests import ConstructorStats +from pybind11_tests import call_policies as m @pytest.mark.xfail("env.PYPY", reason="sometimes comes out 1 off on PyPy", strict=False) @@ -16,10 +15,13 @@ def test_keep_alive_argument(capture): with capture: p.addChild(m.Child()) assert ConstructorStats.detail_reg_inst() == n_inst + 1 - assert capture == """ + assert ( + capture + == """ Allocating child. Releasing child. """ + ) with capture: del p assert ConstructorStats.detail_reg_inst() == n_inst @@ -35,10 +37,26 @@ def test_keep_alive_argument(capture): with capture: del p assert ConstructorStats.detail_reg_inst() == n_inst - assert capture == """ + assert ( + capture + == """ Releasing parent. Releasing child. """ + ) + + p = m.Parent() + c = m.Child() + assert ConstructorStats.detail_reg_inst() == n_inst + 2 + m.free_function(p, c) + del c + assert ConstructorStats.detail_reg_inst() == n_inst + 2 + del p + assert ConstructorStats.detail_reg_inst() == n_inst + + with pytest.raises(RuntimeError) as excinfo: + m.invalid_arg_index() + assert str(excinfo.value) == "Could not activate keep_alive!" def test_keep_alive_return_value(capture): @@ -49,10 +67,13 @@ def test_keep_alive_return_value(capture): with capture: p.returnChild() assert ConstructorStats.detail_reg_inst() == n_inst + 1 - assert capture == """ + assert ( + capture + == """ Allocating child. Releasing child. """ + ) with capture: del p assert ConstructorStats.detail_reg_inst() == n_inst @@ -68,10 +89,30 @@ def test_keep_alive_return_value(capture): with capture: del p assert ConstructorStats.detail_reg_inst() == n_inst - assert capture == """ + assert ( + capture + == """ Releasing parent. Releasing child. """ + ) + + p = m.Parent() + assert ConstructorStats.detail_reg_inst() == n_inst + 1 + with capture: + m.Parent.staticFunction(p) + assert ConstructorStats.detail_reg_inst() == n_inst + 2 + assert capture == "Allocating child." + with capture: + del p + assert ConstructorStats.detail_reg_inst() == n_inst + assert ( + capture + == """ + Releasing parent. + Releasing child. + """ + ) # https://foss.heptapod.net/pypy/pypy/-/issues/2447 @@ -82,14 +123,17 @@ def test_alive_gc(capture): p.addChildKeepAlive(m.Child()) assert ConstructorStats.detail_reg_inst() == n_inst + 2 lst = [p] - lst.append(lst) # creates a circular reference + lst.append(lst) # creates a circular reference with capture: del p, lst assert ConstructorStats.detail_reg_inst() == n_inst - assert capture == """ + assert ( + capture + == """ Releasing parent. Releasing child. """ + ) def test_alive_gc_derived(capture): @@ -101,14 +145,17 @@ def test_alive_gc_derived(capture): p.addChildKeepAlive(m.Child()) assert ConstructorStats.detail_reg_inst() == n_inst + 2 lst = [p] - lst.append(lst) # creates a circular reference + lst.append(lst) # creates a circular reference with capture: del p, lst assert ConstructorStats.detail_reg_inst() == n_inst - assert capture == """ + assert ( + capture + == """ Releasing parent. Releasing child. """ + ) def test_alive_gc_multi_derived(capture): @@ -123,15 +170,18 @@ def test_alive_gc_multi_derived(capture): # +3 rather than +2 because Derived corresponds to two registered instances assert ConstructorStats.detail_reg_inst() == n_inst + 3 lst = [p] - lst.append(lst) # creates a circular reference + lst.append(lst) # creates a circular reference with capture: del p, lst assert ConstructorStats.detail_reg_inst() == n_inst - assert capture == """ + assert ( + capture + == """ Releasing parent. Releasing child. Releasing child. """ + ) def test_return_none(capture): @@ -167,17 +217,23 @@ def test_keep_alive_constructor(capture): with capture: p = m.Parent(m.Child()) assert ConstructorStats.detail_reg_inst() == n_inst + 2 - assert capture == """ + assert ( + capture + == """ Allocating child. Allocating parent. """ + ) with capture: del p assert ConstructorStats.detail_reg_inst() == n_inst - assert capture == """ + assert ( + capture + == """ Releasing parent. Releasing child. """ + ) def test_call_guard(): diff --git a/pybind11/tests/test_callbacks.cpp b/pybind11/tests/test_callbacks.cpp index 71b88c44c..58688b6e8 100644 --- a/pybind11/tests/test_callbacks.cpp +++ b/pybind11/tests/test_callbacks.cpp @@ -17,8 +17,8 @@ int dummy_function(int i) { return i + 1; } TEST_SUBMODULE(callbacks, m) { // test_callbacks, test_function_signatures - m.def("test_callback1", [](py::object func) { return func(); }); - m.def("test_callback2", [](py::object func) { return func("Hello", 'x', true, 5); }); + m.def("test_callback1", [](const py::object &func) { return func(); }); + m.def("test_callback2", [](const py::object &func) { return func("Hello", 'x', true, 5); }); m.def("test_callback3", [](const std::function &func) { return "func(43) = " + std::to_string(func(43)); }); m.def("test_callback4", []() -> std::function { return [](int i) { return i+1; }; }); @@ -27,51 +27,48 @@ TEST_SUBMODULE(callbacks, m) { }); // test_keyword_args_and_generalized_unpacking - m.def("test_tuple_unpacking", [](py::function f) { + m.def("test_tuple_unpacking", [](const py::function &f) { auto t1 = py::make_tuple(2, 3); auto t2 = py::make_tuple(5, 6); return f("positional", 1, *t1, 4, *t2); }); - m.def("test_dict_unpacking", [](py::function f) { + m.def("test_dict_unpacking", [](const py::function &f) { auto d1 = py::dict("key"_a="value", "a"_a=1); auto d2 = py::dict(); auto d3 = py::dict("b"_a=2); return f("positional", 1, **d1, **d2, **d3); }); - m.def("test_keyword_args", [](py::function f) { - return f("x"_a=10, "y"_a=20); - }); + m.def("test_keyword_args", [](const py::function &f) { return f("x"_a = 10, "y"_a = 20); }); - m.def("test_unpacking_and_keywords1", [](py::function f) { + m.def("test_unpacking_and_keywords1", [](const py::function &f) { auto args = py::make_tuple(2); auto kwargs = py::dict("d"_a=4); return f(1, *args, "c"_a=3, **kwargs); }); - m.def("test_unpacking_and_keywords2", [](py::function f) { + m.def("test_unpacking_and_keywords2", [](const py::function &f) { auto kwargs1 = py::dict("a"_a=1); auto kwargs2 = py::dict("c"_a=3, "d"_a=4); return f("positional", *py::make_tuple(1), 2, *py::make_tuple(3, 4), 5, "key"_a="value", **kwargs1, "b"_a=2, **kwargs2, "e"_a=5); }); - m.def("test_unpacking_error1", [](py::function f) { + m.def("test_unpacking_error1", [](const py::function &f) { auto kwargs = py::dict("x"_a=3); return f("x"_a=1, "y"_a=2, **kwargs); // duplicate ** after keyword }); - m.def("test_unpacking_error2", [](py::function f) { + m.def("test_unpacking_error2", [](const py::function &f) { auto kwargs = py::dict("x"_a=3); return f(**kwargs, "x"_a=1); // duplicate keyword after ** }); - m.def("test_arg_conversion_error1", [](py::function f) { - f(234, UnregisteredType(), "kw"_a=567); - }); + m.def("test_arg_conversion_error1", + [](const py::function &f) { f(234, UnregisteredType(), "kw"_a = 567); }); - m.def("test_arg_conversion_error2", [](py::function f) { + m.def("test_arg_conversion_error2", [](const py::function &f) { f(234, "expected_name"_a=UnregisteredType(), "kw"_a=567); }); @@ -80,23 +77,64 @@ TEST_SUBMODULE(callbacks, m) { Payload() { print_default_created(this); } ~Payload() { print_destroyed(this); } Payload(const Payload &) { print_copy_created(this); } - Payload(Payload &&) { print_move_created(this); } + Payload(Payload &&) noexcept { print_move_created(this); } }; // Export the payload constructor statistics for testing purposes: m.def("payload_cstats", &ConstructorStats::get); - /* Test cleanup of lambda closure */ - m.def("test_cleanup", []() -> std::function { + m.def("test_lambda_closure_cleanup", []() -> std::function { Payload p; + // In this situation, `Func` in the implementation of + // `cpp_function::initialize` is NOT trivially destructible. return [p]() { /* p should be cleaned up when the returned function is garbage collected */ (void) p; }; }); + class CppCallable { + public: + CppCallable() { track_default_created(this); } + ~CppCallable() { track_destroyed(this); } + CppCallable(const CppCallable &) { track_copy_created(this); } + CppCallable(CppCallable &&) noexcept { track_move_created(this); } + void operator()() {} + }; + + m.def("test_cpp_callable_cleanup", []() { + // Related issue: https://github.com/pybind/pybind11/issues/3228 + // Related PR: https://github.com/pybind/pybind11/pull/3229 + py::list alive_counts; + ConstructorStats &stat = ConstructorStats::get(); + alive_counts.append(stat.alive()); + { + CppCallable cpp_callable; + alive_counts.append(stat.alive()); + { + // In this situation, `Func` in the implementation of + // `cpp_function::initialize` IS trivially destructible, + // only `capture` is not. + py::cpp_function py_func(cpp_callable); + py::detail::silence_unused_warnings(py_func); + alive_counts.append(stat.alive()); + } + alive_counts.append(stat.alive()); + { + py::cpp_function py_func(std::move(cpp_callable)); + py::detail::silence_unused_warnings(py_func); + alive_counts.append(stat.alive()); + } + alive_counts.append(stat.alive()); + } + alive_counts.append(stat.alive()); + return alive_counts; + }); + // test_cpp_function_roundtrip /* Test if passing a function pointer from C++ -> Python -> C++ yields the original pointer */ m.def("dummy_function", &dummy_function); + m.def("dummy_function_overloaded", [](int i, int j) { return i + j; }); + m.def("dummy_function_overloaded", &dummy_function); m.def("dummy_function2", [](int i, int j) { return i + j; }); m.def("roundtrip", [](std::function f, bool expect_none = false) { if (expect_none && f) @@ -109,16 +147,25 @@ TEST_SUBMODULE(callbacks, m) { if (!result) { auto r = f(1); return "can't convert to function pointer: eval(1) = " + std::to_string(r); - } else if (*result == dummy_function) { + } + if (*result == dummy_function) { auto r = (*result)(1); return "matches dummy_function: eval(1) = " + std::to_string(r); - } else { - return "argument does NOT match dummy_function. This should never happen!"; } + return "argument does NOT match dummy_function. This should never happen!"; + }); - class AbstractBase { public: virtual unsigned int func() = 0; }; - m.def("func_accepting_func_accepting_base", [](std::function) { }); + class AbstractBase { + public: + // [workaround(intel)] = default does not work here + // Defaulting this destructor results in linking errors with the Intel compiler + // (in Debug builds only, tested with icpc (ICC) 2021.1 Beta 20200827) + virtual ~AbstractBase() {} // NOLINT(modernize-use-equals-default) + virtual unsigned int func() = 0; + }; + m.def("func_accepting_func_accepting_base", + [](const std::function &) {}); struct MovableObject { bool valid = true; @@ -126,8 +173,8 @@ TEST_SUBMODULE(callbacks, m) { MovableObject() = default; MovableObject(const MovableObject &) = default; MovableObject &operator=(const MovableObject &) = default; - MovableObject(MovableObject &&o) : valid(o.valid) { o.valid = false; } - MovableObject &operator=(MovableObject &&o) { + MovableObject(MovableObject &&o) noexcept : valid(o.valid) { o.valid = false; } + MovableObject &operator=(MovableObject &&o) noexcept { valid = o.valid; o.valid = false; return *this; @@ -136,7 +183,7 @@ TEST_SUBMODULE(callbacks, m) { py::class_(m, "MovableObject"); // test_movable_object - m.def("callback_with_movable", [](std::function f) { + m.def("callback_with_movable", [](const std::function &f) { auto x = MovableObject(); f(x); // lvalue reference shouldn't move out object return x.valid; // must still return `true` @@ -148,9 +195,15 @@ TEST_SUBMODULE(callbacks, m) { .def(py::init<>()) .def("triple", [](CppBoundMethodTest &, int val) { return 3 * val; }); + // This checks that builtin functions can be passed as callbacks + // rather than throwing RuntimeError due to trying to extract as capsule + m.def("test_sum_builtin", [](const std::function &sum_builtin, const py::iterable &i) { + return sum_builtin(i); + }); + // test async Python callbacks using callback_f = std::function; - m.def("test_async_callback", [](callback_f f, py::list work) { + m.def("test_async_callback", [](const callback_f &f, const py::list &work) { // make detached thread that calls `f` with piece of work after a little delay auto start_f = [f](int j) { auto invoke_f = [f, j] { @@ -165,4 +218,10 @@ TEST_SUBMODULE(callbacks, m) { for (auto i : work) start_f(py::cast(i)); }); + + m.def("callback_num_times", [](const py::function &f, std::size_t num) { + for (std::size_t i = 0; i < num; i++) { + f(); + } + }); } diff --git a/pybind11/tests/test_callbacks.py b/pybind11/tests/test_callbacks.py index d5d0e045d..f41ad86e7 100644 --- a/pybind11/tests/test_callbacks.py +++ b/pybind11/tests/test_callbacks.py @@ -1,8 +1,12 @@ # -*- coding: utf-8 -*- -import pytest -from pybind11_tests import callbacks as m +import time from threading import Thread +import pytest + +import env # noqa: F401 +from pybind11_tests import callbacks as m + def test_callbacks(): from functools import partial @@ -42,17 +46,19 @@ def test_bound_method_callback(): def test_keyword_args_and_generalized_unpacking(): - def f(*args, **kwargs): return args, kwargs assert m.test_tuple_unpacking(f) == (("positional", 1, 2, 3, 4, 5, 6), {}) - assert m.test_dict_unpacking(f) == (("positional", 1), {"key": "value", "a": 1, "b": 2}) + assert m.test_dict_unpacking(f) == ( + ("positional", 1), + {"key": "value", "a": 1, "b": 2}, + ) assert m.test_keyword_args(f) == ((), {"x": 10, "y": 20}) assert m.test_unpacking_and_keywords1(f) == ((1, 2), {"c": 3, "d": 4}) assert m.test_unpacking_and_keywords2(f) == ( ("positional", 1, 2, 3, 4, 5), - {"key": "value", "a": 1, "b": 2, "c": 3, "d": 4, "e": 5} + {"key": "value", "a": 1, "b": 2, "c": 3, "d": 4, "e": 5}, ) with pytest.raises(TypeError) as excinfo: @@ -73,22 +79,37 @@ def test_keyword_args_and_generalized_unpacking(): def test_lambda_closure_cleanup(): - m.test_cleanup() + m.test_lambda_closure_cleanup() cstats = m.payload_cstats() assert cstats.alive() == 0 assert cstats.copy_constructions == 1 assert cstats.move_constructions >= 1 +def test_cpp_callable_cleanup(): + alive_counts = m.test_cpp_callable_cleanup() + assert alive_counts == [0, 1, 2, 1, 2, 1, 0] + + def test_cpp_function_roundtrip(): """Test if passing a function pointer from C++ -> Python -> C++ yields the original pointer""" - assert m.test_dummy_function(m.dummy_function) == "matches dummy_function: eval(1) = 2" - assert (m.test_dummy_function(m.roundtrip(m.dummy_function)) == - "matches dummy_function: eval(1) = 2") + assert ( + m.test_dummy_function(m.dummy_function) == "matches dummy_function: eval(1) = 2" + ) + assert ( + m.test_dummy_function(m.roundtrip(m.dummy_function)) + == "matches dummy_function: eval(1) = 2" + ) + assert ( + m.test_dummy_function(m.dummy_function_overloaded) + == "matches dummy_function: eval(1) = 2" + ) assert m.roundtrip(None, expect_none=True) is None - assert (m.test_dummy_function(lambda x: x + 2) == - "can't convert to function pointer: eval(1) = 3") + assert ( + m.test_dummy_function(lambda x: x + 2) + == "can't convert to function pointer: eval(1) = 3" + ) with pytest.raises(TypeError) as excinfo: m.test_dummy_function(m.dummy_function2) @@ -96,8 +117,10 @@ def test_cpp_function_roundtrip(): with pytest.raises(TypeError) as excinfo: m.test_dummy_function(lambda x, y: x + y) - assert any(s in str(excinfo.value) for s in ("missing 1 required positional argument", - "takes exactly 2 arguments")) + assert any( + s in str(excinfo.value) + for s in ("missing 1 required positional argument", "takes exactly 2 arguments") + ) def test_function_signatures(doc): @@ -109,6 +132,16 @@ def test_movable_object(): assert m.callback_with_movable(lambda _: None) is True +@pytest.mark.skipif( + "env.PYPY", + reason="PyPy segfaults on here. See discussion on #1413.", +) +def test_python_builtins(): + """Test if python builtins like sum() can be used as callbacks""" + assert m.test_sum_builtin(sum, [1, 2, 3]) == 6 + assert m.test_sum_builtin(sum, []) == 0 + + def test_async_callbacks(): # serves as state for async callback class Item: @@ -127,11 +160,43 @@ def test_async_callbacks(): m.test_async_callback(gen_f(), work) # wait until work is done from time import sleep + sleep(0.5) - assert sum(res) == sum([x + 3 for x in work]) + assert sum(res) == sum(x + 3 for x in work) def test_async_async_callbacks(): t = Thread(target=test_async_callbacks) t.start() t.join() + + +def test_callback_num_times(): + # Super-simple micro-benchmarking related to PR #2919. + # Example runtimes (Intel Xeon 2.2GHz, fully optimized): + # num_millions 1, repeats 2: 0.1 secs + # num_millions 20, repeats 10: 11.5 secs + one_million = 1000000 + num_millions = 1 # Try 20 for actual micro-benchmarking. + repeats = 2 # Try 10. + rates = [] + for rep in range(repeats): + t0 = time.time() + m.callback_num_times(lambda: None, num_millions * one_million) + td = time.time() - t0 + rate = num_millions / td if td else 0 + rates.append(rate) + if not rep: + print() + print( + "callback_num_times: {:d} million / {:.3f} seconds = {:.3f} million / second".format( + num_millions, td, rate + ) + ) + if len(rates) > 1: + print("Min Mean Max") + print( + "{:6.3f} {:6.3f} {:6.3f}".format( + min(rates), sum(rates) / len(rates), max(rates) + ) + ) diff --git a/pybind11/tests/test_chrono.py b/pybind11/tests/test_chrono.py index ae24b7dda..fdd73d690 100644 --- a/pybind11/tests/test_chrono.py +++ b/pybind11/tests/test_chrono.py @@ -1,9 +1,10 @@ # -*- coding: utf-8 -*- -from pybind11_tests import chrono as m import datetime + import pytest import env # noqa: F401 +from pybind11_tests import chrono as m def test_chrono_system_clock(): @@ -39,9 +40,7 @@ def test_chrono_system_clock_roundtrip(): # They should be identical (no information lost on roundtrip) diff = abs(date1 - date2) - assert diff.days == 0 - assert diff.seconds == 0 - assert diff.microseconds == 0 + assert diff == datetime.timedelta(0) def test_chrono_system_clock_roundtrip_date(): @@ -64,9 +63,7 @@ def test_chrono_system_clock_roundtrip_date(): assert diff.microseconds == 0 # Year, Month & Day should be the same after the round trip - assert date1.year == date2.year - assert date1.month == date2.month - assert date1.day == date2.day + assert date1 == date2 # There should be no time information assert time2.hour == 0 @@ -80,22 +77,28 @@ SKIP_TZ_ENV_ON_WIN = pytest.mark.skipif( ) -@pytest.mark.parametrize("time1", [ - datetime.datetime.today().time(), - datetime.time(0, 0, 0), - datetime.time(0, 0, 0, 1), - datetime.time(0, 28, 45, 109827), - datetime.time(0, 59, 59, 999999), - datetime.time(1, 0, 0), - datetime.time(5, 59, 59, 0), - datetime.time(5, 59, 59, 1), -]) -@pytest.mark.parametrize("tz", [ - None, - pytest.param("Europe/Brussels", marks=SKIP_TZ_ENV_ON_WIN), - pytest.param("Asia/Pyongyang", marks=SKIP_TZ_ENV_ON_WIN), - pytest.param("America/New_York", marks=SKIP_TZ_ENV_ON_WIN), -]) +@pytest.mark.parametrize( + "time1", + [ + datetime.datetime.today().time(), + datetime.time(0, 0, 0), + datetime.time(0, 0, 0, 1), + datetime.time(0, 28, 45, 109827), + datetime.time(0, 59, 59, 999999), + datetime.time(1, 0, 0), + datetime.time(5, 59, 59, 0), + datetime.time(5, 59, 59, 1), + ], +) +@pytest.mark.parametrize( + "tz", + [ + None, + pytest.param("Europe/Brussels", marks=SKIP_TZ_ENV_ON_WIN), + pytest.param("Asia/Pyongyang", marks=SKIP_TZ_ENV_ON_WIN), + pytest.param("America/New_York", marks=SKIP_TZ_ENV_ON_WIN), + ], +) def test_chrono_system_clock_roundtrip_time(time1, tz, monkeypatch): if tz is not None: monkeypatch.setenv("TZ", "/usr/share/zoneinfo/{}".format(tz)) @@ -111,10 +114,7 @@ def test_chrono_system_clock_roundtrip_time(time1, tz, monkeypatch): assert isinstance(time2, datetime.time) # Hour, Minute, Second & Microsecond should be the same after the round trip - assert time1.hour == time2.hour - assert time1.minute == time2.minute - assert time1.second == time2.second - assert time1.microsecond == time2.microsecond + assert time1 == time2 # There should be no date information (i.e. date = python base date) assert date2.year == 1970 @@ -134,9 +134,13 @@ def test_chrono_duration_roundtrip(): cpp_diff = m.test_chrono3(diff) - assert cpp_diff.days == diff.days - assert cpp_diff.seconds == diff.seconds - assert cpp_diff.microseconds == diff.microseconds + assert cpp_diff == diff + + # Negative timedelta roundtrip + diff = datetime.timedelta(microseconds=-1) + cpp_diff = m.test_chrono3(diff) + + assert cpp_diff == diff def test_chrono_duration_subtraction_equivalence(): @@ -147,9 +151,7 @@ def test_chrono_duration_subtraction_equivalence(): diff = date2 - date1 cpp_diff = m.test_chrono4(date2, date1) - assert cpp_diff.days == diff.days - assert cpp_diff.seconds == diff.seconds - assert cpp_diff.microseconds == diff.microseconds + assert cpp_diff == diff def test_chrono_duration_subtraction_equivalence_date(): @@ -160,9 +162,7 @@ def test_chrono_duration_subtraction_equivalence_date(): diff = date2 - date1 cpp_diff = m.test_chrono4(date2, date1) - assert cpp_diff.days == diff.days - assert cpp_diff.seconds == diff.seconds - assert cpp_diff.microseconds == diff.microseconds + assert cpp_diff == diff def test_chrono_steady_clock(): @@ -177,9 +177,7 @@ def test_chrono_steady_clock_roundtrip(): assert isinstance(time2, datetime.timedelta) # They should be identical (no information lost on roundtrip) - assert time1.days == time2.days - assert time1.seconds == time2.seconds - assert time1.microseconds == time2.microseconds + assert time1 == time2 def test_floating_point_duration(): @@ -199,7 +197,7 @@ def test_floating_point_duration(): def test_nano_timepoint(): time = datetime.datetime.now() time1 = m.test_nano_timepoint(time, datetime.timedelta(seconds=60)) - assert(time1 == time + datetime.timedelta(seconds=60)) + assert time1 == time + datetime.timedelta(seconds=60) def test_chrono_different_resolutions(): diff --git a/pybind11/tests/test_class.cpp b/pybind11/tests/test_class.cpp index b0e3d3a4b..52a41a3bc 100644 --- a/pybind11/tests/test_class.cpp +++ b/pybind11/tests/test_class.cpp @@ -7,18 +7,27 @@ BSD-style license that can be found in the LICENSE file. */ +#if defined(__INTEL_COMPILER) && __cplusplus >= 201703L +// Intel compiler requires a separate header file to support aligned new operators +// and does not set the __cpp_aligned_new feature macro. +// This header needs to be included before pybind11. +#include +#endif + #include "pybind11_tests.h" #include "constructor_stats.h" #include "local_bindings.h" #include +#include + #if defined(_MSC_VER) # pragma warning(disable: 4324) // warning C4324: structure was padded due to alignment specifier #endif // test_brace_initialization struct NoBraceInitialization { - NoBraceInitialization(std::vector v) : vec{std::move(v)} {} + explicit NoBraceInitialization(std::vector v) : vec{std::move(v)} {} template NoBraceInitialization(std::initializer_list l) : vec(l) {} @@ -38,10 +47,26 @@ TEST_SUBMODULE(class_, m) { } ~NoConstructor() { print_destroyed(this); } }; + struct NoConstructorNew { + NoConstructorNew() = default; + NoConstructorNew(const NoConstructorNew &) = default; + NoConstructorNew(NoConstructorNew &&) = default; + static NoConstructorNew *new_instance() { + auto *ptr = new NoConstructorNew(); + print_created(ptr, "via new_instance"); + return ptr; + } + ~NoConstructorNew() { print_destroyed(this); } + }; py::class_(m, "NoConstructor") .def_static("new_instance", &NoConstructor::new_instance, "Return an instance"); + py::class_(m, "NoConstructorNew") + .def(py::init([](const NoConstructorNew &self) { return self; })) // Need a NOOP __init__ + .def_static("__new__", + [](const py::object &) { return NoConstructorNew::new_instance(); }); + // test_inheritance class Pet { public: @@ -56,18 +81,18 @@ TEST_SUBMODULE(class_, m) { class Dog : public Pet { public: - Dog(const std::string &name) : Pet(name, "dog") {} + explicit Dog(const std::string &name) : Pet(name, "dog") {} std::string bark() const { return "Woof!"; } }; class Rabbit : public Pet { public: - Rabbit(const std::string &name) : Pet(name, "parrot") {} + explicit Rabbit(const std::string &name) : Pet(name, "parrot") {} }; class Hamster : public Pet { public: - Hamster(const std::string &name) : Pet(name, "rodent") {} + explicit Hamster(const std::string &name) : Pet(name, "rodent") {} }; class Chimera : public Pet { @@ -122,7 +147,7 @@ TEST_SUBMODULE(class_, m) { m.def("return_none", []() -> BaseClass* { return nullptr; }); // test_isinstance - m.def("check_instances", [](py::list l) { + m.def("check_instances", [](const py::list &l) { return py::make_tuple( py::isinstance(l[0]), py::isinstance(l[1]), @@ -144,21 +169,16 @@ TEST_SUBMODULE(class_, m) { // return py::type::of(); if (category == 1) return py::type::of(); - else - return py::type::of(); + return py::type::of(); }); - m.def("get_type_of", [](py::object ob) { - return py::type::of(ob); + m.def("get_type_of", [](py::object ob) { return py::type::of(std::move(ob)); }); + + m.def("get_type_classic", [](py::handle h) { + return h.get_type(); }); - m.def("as_type", [](py::object ob) { - auto tp = py::type(ob); - if (py::isinstance(ob)) - return tp; - else - throw std::runtime_error("Invalid type"); - }); + m.def("as_type", [](const py::object &ob) { return py::type(ob); }); // test_mismatched_holder struct MismatchBase1 { }; @@ -168,12 +188,12 @@ TEST_SUBMODULE(class_, m) { struct MismatchDerived2 : MismatchBase2 { }; m.def("mismatched_holder_1", []() { - auto mod = py::module::import("__main__"); + auto mod = py::module_::import("__main__"); py::class_>(mod, "MismatchBase1"); py::class_(mod, "MismatchDerived1"); }); m.def("mismatched_holder_2", []() { - auto mod = py::module::import("__main__"); + auto mod = py::module_::import("__main__"); py::class_(mod, "MismatchBase2"); py::class_, MismatchBase2>(mod, "MismatchDerived2"); @@ -204,7 +224,7 @@ TEST_SUBMODULE(class_, m) { struct ConvertibleFromUserType { int i; - ConvertibleFromUserType(UserType u) : i(u.value()) { } + explicit ConvertibleFromUserType(UserType u) : i(u.value()) {} }; py::class_(m, "AcceptsUserType") @@ -212,7 +232,7 @@ TEST_SUBMODULE(class_, m) { py::implicitly_convertible(); m.def("implicitly_convert_argument", [](const ConvertibleFromUserType &r) { return r.i; }); - m.def("implicitly_convert_variable", [](py::object o) { + m.def("implicitly_convert_variable", [](const py::object &o) { // `o` is `UserType` and `r` is a reference to a temporary created by implicit // conversion. This is valid when called inside a bound function because the temp // object is attached to the same life support system as the arguments. @@ -231,7 +251,8 @@ TEST_SUBMODULE(class_, m) { }; auto def = new PyMethodDef{"f", f, METH_VARARGS, nullptr}; - return py::reinterpret_steal(PyCFunction_NewEx(def, nullptr, m.ptr())); + py::capsule def_capsule(def, [](void *ptr) { delete reinterpret_cast(ptr); }); + return py::reinterpret_steal(PyCFunction_NewEx(def, def_capsule.ptr(), m.ptr())); }()); // test_operator_new_delete @@ -258,7 +279,7 @@ TEST_SUBMODULE(class_, m) { }; struct PyAliasedHasOpNewDelSize : AliasedHasOpNewDelSize { PyAliasedHasOpNewDelSize() = default; - PyAliasedHasOpNewDelSize(int) { } + explicit PyAliasedHasOpNewDelSize(int) {} std::uint64_t j; }; struct HasOpNewDelBoth { @@ -322,6 +343,10 @@ TEST_SUBMODULE(class_, m) { class PublicistB : public ProtectedB { public: + // [workaround(intel)] = default does not work here + // Removing or defaulting this destructor results in linking errors with the Intel compiler + // (in Debug builds only, tested with icpc (ICC) 2021.1 Beta 20200827) + ~PublicistB() override {}; // NOLINT(modernize-use-equals-default) using ProtectedB::foo; }; @@ -385,7 +410,7 @@ TEST_SUBMODULE(class_, m) { struct StringWrapper { std::string str; }; m.def("test_error_after_conversions", [](int) {}); m.def("test_error_after_conversions", - [](StringWrapper) -> NotRegistered { return {}; }); + [](const StringWrapper &) -> NotRegistered { return {}; }); py::class_(m, "StringWrapper").def(py::init()); py::implicitly_convertible(); @@ -406,6 +431,7 @@ TEST_SUBMODULE(class_, m) { struct IsNonFinalFinal {}; py::class_(m, "IsNonFinalFinal", py::is_final()); + // test_exception_rvalue_abort struct PyPrintDestructor { PyPrintDestructor() = default; ~PyPrintDestructor() { @@ -416,6 +442,55 @@ TEST_SUBMODULE(class_, m) { py::class_(m, "PyPrintDestructor") .def(py::init<>()) .def("throw_something", &PyPrintDestructor::throw_something); + + // test_multiple_instances_with_same_pointer + struct SamePointer {}; + static SamePointer samePointer; + py::class_>(m, "SamePointer") + .def(py::init([]() { return &samePointer; })); + + struct Empty {}; + py::class_(m, "Empty") + .def(py::init<>()); + + // test_base_and_derived_nested_scope + struct BaseWithNested { + struct Nested {}; + }; + + struct DerivedWithNested : BaseWithNested { + struct Nested {}; + }; + + py::class_ baseWithNested_class(m, "BaseWithNested"); + py::class_ derivedWithNested_class(m, "DerivedWithNested"); + py::class_(baseWithNested_class, "Nested") + .def_static("get_name", []() { return "BaseWithNested::Nested"; }); + py::class_(derivedWithNested_class, "Nested") + .def_static("get_name", []() { return "DerivedWithNested::Nested"; }); + + // test_register_duplicate_class + struct Duplicate {}; + struct OtherDuplicate {}; + struct DuplicateNested {}; + struct OtherDuplicateNested {}; + + m.def("register_duplicate_class_name", [](const py::module_ &m) { + py::class_(m, "Duplicate"); + py::class_(m, "Duplicate"); + }); + m.def("register_duplicate_class_type", [](const py::module_ &m) { + py::class_(m, "OtherDuplicate"); + py::class_(m, "YetAnotherDuplicate"); + }); + m.def("register_duplicate_nested_class_name", [](const py::object >) { + py::class_(gt, "DuplicateNested"); + py::class_(gt, "DuplicateNested"); + }); + m.def("register_duplicate_nested_class_type", [](const py::object >) { + py::class_(gt, "OtherDuplicateNested"); + py::class_(gt, "YetAnotherDuplicateNested"); + }); } template class BreaksBase { public: @@ -433,15 +508,15 @@ using DoesntBreak5 = py::class_>; using DoesntBreak6 = py::class_, std::shared_ptr>, BreaksTramp<6>>; using DoesntBreak7 = py::class_, BreaksTramp<7>, std::shared_ptr>>; using DoesntBreak8 = py::class_, std::shared_ptr>>; -#define CHECK_BASE(N) static_assert(std::is_same>::value, \ +#define CHECK_BASE(N) static_assert(std::is_same>::value, \ "DoesntBreak" #N " has wrong type!") CHECK_BASE(1); CHECK_BASE(2); CHECK_BASE(3); CHECK_BASE(4); CHECK_BASE(5); CHECK_BASE(6); CHECK_BASE(7); CHECK_BASE(8); -#define CHECK_ALIAS(N) static_assert(DoesntBreak##N::has_alias && std::is_same>::value, \ +#define CHECK_ALIAS(N) static_assert(DoesntBreak##N::has_alias && std::is_same>::value, \ "DoesntBreak" #N " has wrong type_alias!") #define CHECK_NOALIAS(N) static_assert(!DoesntBreak##N::has_alias && std::is_void::value, \ "DoesntBreak" #N " has type alias, but shouldn't!") CHECK_ALIAS(1); CHECK_ALIAS(2); CHECK_NOALIAS(3); CHECK_ALIAS(4); CHECK_NOALIAS(5); CHECK_ALIAS(6); CHECK_ALIAS(7); CHECK_NOALIAS(8); -#define CHECK_HOLDER(N, TYPE) static_assert(std::is_same>>::value, \ +#define CHECK_HOLDER(N, TYPE) static_assert(std::is_same>>::value, \ "DoesntBreak" #N " has wrong holder_type!") CHECK_HOLDER(1, unique); CHECK_HOLDER(2, unique); CHECK_HOLDER(3, unique); CHECK_HOLDER(4, unique); CHECK_HOLDER(5, unique); CHECK_HOLDER(6, shared); CHECK_HOLDER(7, shared); CHECK_HOLDER(8, shared); @@ -451,7 +526,7 @@ CHECK_HOLDER(6, shared); CHECK_HOLDER(7, shared); CHECK_HOLDER(8, shared); // failures occurs). // We have to actually look into the type: the typedef alone isn't enough to instantiate the type: -#define CHECK_BROKEN(N) static_assert(std::is_same>::value, \ +#define CHECK_BROKEN(N) static_assert(std::is_same>::value, \ "Breaks1 has wrong type!"); //// Two holder classes: diff --git a/pybind11/tests/test_class.py b/pybind11/tests/test_class.py index be21f3709..caafe2068 100644 --- a/pybind11/tests/test_class.py +++ b/pybind11/tests/test_class.py @@ -2,9 +2,8 @@ import pytest import env # noqa: F401 - +from pybind11_tests import ConstructorStats, UserType from pybind11_tests import class_ as m -from pybind11_tests import UserType, ConstructorStats def test_repr(): @@ -26,13 +25,23 @@ def test_instance(msg): assert cstats.alive() == 0 +def test_instance_new(msg): + instance = m.NoConstructorNew() # .__new__(m.NoConstructor.__class__) + cstats = ConstructorStats.get(m.NoConstructorNew) + assert cstats.alive() == 1 + del instance + assert cstats.alive() == 0 + + def test_type(): assert m.check_type(1) == m.DerivedClass1 with pytest.raises(RuntimeError) as execinfo: m.check_type(0) - assert 'pybind11::detail::get_type_info: unable to find type info' in str(execinfo.value) - assert 'Invalid' in str(execinfo.value) + assert "pybind11::detail::get_type_info: unable to find type info" in str( + execinfo.value + ) + assert "Invalid" in str(execinfo.value) # Currently not supported # See https://github.com/pybind/pybind11/issues/2486 @@ -45,6 +54,12 @@ def test_type_of_py(): assert m.get_type_of(int) == type +def test_type_of_classic(): + assert m.get_type_classic(1) == int + assert m.get_type_classic(m.DerivedClass1()) == m.DerivedClass1 + assert m.get_type_classic(int) == type + + def test_type_of_py_nodelete(): # If the above test deleted the class, this will segfault assert m.get_type_of(m.DerivedClass1()) == m.DerivedClass1 @@ -53,10 +68,10 @@ def test_type_of_py_nodelete(): def test_as_type_py(): assert m.as_type(int) == int - with pytest.raises(RuntimeError): + with pytest.raises(TypeError): assert m.as_type(1) == int - with pytest.raises(RuntimeError): + with pytest.raises(TypeError): assert m.as_type(m.DerivedClass1()) == m.DerivedClass1 @@ -67,18 +82,24 @@ def test_docstrings(doc): assert UserType.get_value.__name__ == "get_value" assert UserType.get_value.__module__ == "pybind11_tests" - assert doc(UserType.get_value) == """ + assert ( + doc(UserType.get_value) + == """ get_value(self: m.UserType) -> int Get value using a method """ + ) assert doc(UserType.value) == "Get/set value using a property" - assert doc(m.NoConstructor.new_instance) == """ + assert ( + doc(m.NoConstructor.new_instance) + == """ new_instance() -> m.class_.NoConstructor Return an instance """ + ) def test_qualname(doc): @@ -87,51 +108,69 @@ def test_qualname(doc): assert m.NestBase.__qualname__ == "NestBase" assert m.NestBase.Nested.__qualname__ == "NestBase.Nested" - assert doc(m.NestBase.__init__) == """ + assert ( + doc(m.NestBase.__init__) + == """ __init__(self: m.class_.NestBase) -> None """ - assert doc(m.NestBase.g) == """ + ) + assert ( + doc(m.NestBase.g) + == """ g(self: m.class_.NestBase, arg0: m.class_.NestBase.Nested) -> None """ - assert doc(m.NestBase.Nested.__init__) == """ + ) + assert ( + doc(m.NestBase.Nested.__init__) + == """ __init__(self: m.class_.NestBase.Nested) -> None """ - assert doc(m.NestBase.Nested.fn) == """ + ) + assert ( + doc(m.NestBase.Nested.fn) + == """ fn(self: m.class_.NestBase.Nested, arg0: int, arg1: m.class_.NestBase, arg2: m.class_.NestBase.Nested) -> None """ # noqa: E501 line too long - assert doc(m.NestBase.Nested.fa) == """ + ) + assert ( + doc(m.NestBase.Nested.fa) + == """ fa(self: m.class_.NestBase.Nested, a: int, b: m.class_.NestBase, c: m.class_.NestBase.Nested) -> None """ # noqa: E501 line too long + ) assert m.NestBase.__module__ == "pybind11_tests.class_" assert m.NestBase.Nested.__module__ == "pybind11_tests.class_" def test_inheritance(msg): - roger = m.Rabbit('Rabbit') + roger = m.Rabbit("Rabbit") assert roger.name() + " is a " + roger.species() == "Rabbit is a parrot" assert m.pet_name_species(roger) == "Rabbit is a parrot" - polly = m.Pet('Polly', 'parrot') + polly = m.Pet("Polly", "parrot") assert polly.name() + " is a " + polly.species() == "Polly is a parrot" assert m.pet_name_species(polly) == "Polly is a parrot" - molly = m.Dog('Molly') + molly = m.Dog("Molly") assert molly.name() + " is a " + molly.species() == "Molly is a dog" assert m.pet_name_species(molly) == "Molly is a dog" - fred = m.Hamster('Fred') + fred = m.Hamster("Fred") assert fred.name() + " is a " + fred.species() == "Fred is a rodent" assert m.dog_bark(molly) == "Woof!" with pytest.raises(TypeError) as excinfo: m.dog_bark(polly) - assert msg(excinfo.value) == """ + assert ( + msg(excinfo.value) + == """ dog_bark(): incompatible function arguments. The following argument types are supported: 1. (arg0: m.class_.Dog) -> str Invoked with: """ + ) with pytest.raises(TypeError) as excinfo: m.Chimera("lion", "goat") @@ -144,12 +183,11 @@ def test_inheritance_init(msg): class Python(m.Pet): def __init__(self): pass + with pytest.raises(TypeError) as exc_info: Python() - expected = ["m.class_.Pet.__init__() must be called when overriding __init__", - "Pet.__init__() must be called when overriding __init__"] # PyPy? - # TODO: fix PyPy error message wrt. tp_name/__qualname__? - assert msg(exc_info.value) in expected + expected = "m.class_.Pet.__init__() must be called when overriding __init__" + assert msg(exc_info.value) == expected # Multiple bases class RabbitHamster(m.Rabbit, m.Hamster): @@ -158,9 +196,8 @@ def test_inheritance_init(msg): with pytest.raises(TypeError) as exc_info: RabbitHamster() - expected = ["m.class_.Hamster.__init__() must be called when overriding __init__", - "Hamster.__init__() must be called when overriding __init__"] # PyPy - assert msg(exc_info.value) in expected + expected = "m.class_.Hamster.__init__() must be called when overriding __init__" + assert msg(exc_info.value) == expected def test_automatic_upcasting(): @@ -188,13 +225,19 @@ def test_mismatched_holder(): with pytest.raises(RuntimeError) as excinfo: m.mismatched_holder_1() - assert re.match('generic_type: type ".*MismatchDerived1" does not have a non-default ' - 'holder type while its base ".*MismatchBase1" does', str(excinfo.value)) + assert re.match( + 'generic_type: type ".*MismatchDerived1" does not have a non-default ' + 'holder type while its base ".*MismatchBase1" does', + str(excinfo.value), + ) with pytest.raises(RuntimeError) as excinfo: m.mismatched_holder_2() - assert re.match('generic_type: type ".*MismatchDerived2" has a non-default holder type ' - 'while its base ".*MismatchBase2" does not', str(excinfo.value)) + assert re.match( + 'generic_type: type ".*MismatchDerived2" has a non-default holder type ' + 'while its base ".*MismatchBase2" does not', + str(excinfo.value), + ) def test_override_static(): @@ -226,20 +269,20 @@ def test_operator_new_delete(capture): a = m.HasOpNewDel() b = m.HasOpNewDelSize() d = m.HasOpNewDelBoth() - assert capture == """ + assert ( + capture + == """ A new 8 B new 4 D new 32 """ + ) sz_alias = str(m.AliasedHasOpNewDelSize.size_alias) sz_noalias = str(m.AliasedHasOpNewDelSize.size_noalias) with capture: c = m.AliasedHasOpNewDelSize() c2 = SubAliased() - assert capture == ( - "C new " + sz_noalias + "\n" + - "C new " + sz_alias + "\n" - ) + assert capture == ("C new " + sz_noalias + "\n" + "C new " + sz_alias + "\n") with capture: del a @@ -248,21 +291,21 @@ def test_operator_new_delete(capture): pytest.gc_collect() del d pytest.gc_collect() - assert capture == """ + assert ( + capture + == """ A delete B delete 4 D delete """ + ) with capture: del c pytest.gc_collect() del c2 pytest.gc_collect() - assert capture == ( - "C delete " + sz_noalias + "\n" + - "C delete " + sz_alias + "\n" - ) + assert capture == ("C delete " + sz_noalias + "\n" + "C delete " + sz_alias + "\n") def test_bind_protected_functions(): @@ -285,7 +328,7 @@ def test_bind_protected_functions(): def test_brace_initialization(): - """ Tests that simple POD classes can be constructed using C++11 brace initialization """ + """Tests that simple POD classes can be constructed using C++11 brace initialization""" a = m.BraceInitialization(123, "test") assert a.field1 == 123 assert a.field2 == "test" @@ -322,19 +365,23 @@ def test_reentrant_implicit_conversion_failure(msg): # ensure that there is no runaway reentrant implicit conversion (#1035) with pytest.raises(TypeError) as excinfo: m.BogusImplicitConversion(0) - assert msg(excinfo.value) == ''' + assert ( + msg(excinfo.value) + == """ __init__(): incompatible constructor arguments. The following argument types are supported: 1. m.class_.BogusImplicitConversion(arg0: m.class_.BogusImplicitConversion) Invoked with: 0 - ''' + """ + ) def test_error_after_conversions(): with pytest.raises(TypeError) as exc_info: m.test_error_after_conversions("hello") assert str(exc_info.value).startswith( - "Unable to convert function return value to a Python type!") + "Unable to convert function return value to a Python type!" + ) def test_aligned(): @@ -347,8 +394,10 @@ def test_aligned(): @pytest.mark.xfail("env.PYPY") def test_final(): with pytest.raises(TypeError) as exc_info: + class PyFinalChild(m.IsFinal): pass + assert str(exc_info.value).endswith("is not an acceptable base type") @@ -356,8 +405,10 @@ def test_final(): @pytest.mark.xfail("env.PYPY") def test_non_final_final(): with pytest.raises(TypeError) as exc_info: + class PyNonFinalFinalChild(m.IsNonFinalFinal): pass + assert str(exc_info.value).endswith("is not an acceptable base type") @@ -365,3 +416,58 @@ def test_non_final_final(): def test_exception_rvalue_abort(): with pytest.raises(RuntimeError): m.PyPrintDestructor().throw_something() + + +# https://github.com/pybind/pybind11/issues/1568 +def test_multiple_instances_with_same_pointer(capture): + n = 100 + instances = [m.SamePointer() for _ in range(n)] + for i in range(n): + # We need to reuse the same allocated memory for with a different type, + # to ensure the bug in `deregister_instance_impl` is detected. Otherwise + # `Py_TYPE(self) == Py_TYPE(it->second)` will still succeed, even though + # the `instance` is already deleted. + instances[i] = m.Empty() + # No assert: if this does not trigger the error + # pybind11_fail("pybind11_object_dealloc(): Tried to deallocate unregistered instance!"); + # and just completes without crashing, we're good. + + +# https://github.com/pybind/pybind11/issues/1624 +def test_base_and_derived_nested_scope(): + assert issubclass(m.DerivedWithNested, m.BaseWithNested) + assert m.BaseWithNested.Nested != m.DerivedWithNested.Nested + assert m.BaseWithNested.Nested.get_name() == "BaseWithNested::Nested" + assert m.DerivedWithNested.Nested.get_name() == "DerivedWithNested::Nested" + + +def test_register_duplicate_class(): + import types + + module_scope = types.ModuleType("module_scope") + with pytest.raises(RuntimeError) as exc_info: + m.register_duplicate_class_name(module_scope) + expected = ( + 'generic_type: cannot initialize type "Duplicate": ' + "an object with that name is already defined" + ) + assert str(exc_info.value) == expected + with pytest.raises(RuntimeError) as exc_info: + m.register_duplicate_class_type(module_scope) + expected = 'generic_type: type "YetAnotherDuplicate" is already registered!' + assert str(exc_info.value) == expected + + class ClassScope: + pass + + with pytest.raises(RuntimeError) as exc_info: + m.register_duplicate_nested_class_name(ClassScope) + expected = ( + 'generic_type: cannot initialize type "DuplicateNested": ' + "an object with that name is already defined" + ) + assert str(exc_info.value) == expected + with pytest.raises(RuntimeError) as exc_info: + m.register_duplicate_nested_class_type(ClassScope) + expected = 'generic_type: type "YetAnotherDuplicateNested" is already registered!' + assert str(exc_info.value) == expected diff --git a/pybind11/tests/test_cmake_build/CMakeLists.txt b/pybind11/tests/test_cmake_build/CMakeLists.txt index 0c0578ad3..8bfaa386a 100644 --- a/pybind11/tests/test_cmake_build/CMakeLists.txt +++ b/pybind11/tests/test_cmake_build/CMakeLists.txt @@ -25,7 +25,7 @@ function(pybind11_add_build_test name) endif() if(NOT ARG_INSTALL) - list(APPEND build_options "-DPYBIND11_PROJECT_DIR=${pybind11_SOURCE_DIR}") + list(APPEND build_options "-Dpybind11_SOURCE_DIR=${pybind11_SOURCE_DIR}") else() list(APPEND build_options "-DCMAKE_PREFIX_PATH=${pybind11_BINARY_DIR}/mock_install") endif() @@ -55,6 +55,8 @@ function(pybind11_add_build_test name) add_dependencies(test_cmake_build test_build_${name}) endfunction() +possibly_uninitialized(PYTHON_MODULE_EXTENSION Python_INTERPRETER_ID) + pybind11_add_build_test(subdirectory_function) pybind11_add_build_test(subdirectory_target) if("${PYTHON_MODULE_EXTENSION}" MATCHES "pypy" OR "${Python_INTERPRETER_ID}" STREQUAL "PyPy") @@ -77,3 +79,6 @@ if(PYBIND11_INSTALL) endif() add_dependencies(check test_cmake_build) + +add_subdirectory(subdirectory_target EXCLUDE_FROM_ALL) +add_subdirectory(subdirectory_embed EXCLUDE_FROM_ALL) diff --git a/pybind11/tests/test_cmake_build/embed.cpp b/pybind11/tests/test_cmake_build/embed.cpp index b9581d2fd..a3abc8a84 100644 --- a/pybind11/tests/test_cmake_build/embed.cpp +++ b/pybind11/tests/test_cmake_build/embed.cpp @@ -12,10 +12,10 @@ int main(int argc, char *argv[]) { py::scoped_interpreter guard{}; - auto m = py::module::import("test_cmake_build"); + auto m = py::module_::import("test_cmake_build"); if (m.attr("add")(1, 2).cast() != 3) throw std::runtime_error("embed.cpp failed"); - py::module::import("sys").attr("argv") = py::make_tuple("test.py", "embed.cpp"); + py::module_::import("sys").attr("argv") = py::make_tuple("test.py", "embed.cpp"); py::eval_file(test_py_file, py::globals()); } diff --git a/pybind11/tests/test_cmake_build/installed_embed/CMakeLists.txt b/pybind11/tests/test_cmake_build/installed_embed/CMakeLists.txt index 64ae5c4bf..f7d693998 100644 --- a/pybind11/tests/test_cmake_build/installed_embed/CMakeLists.txt +++ b/pybind11/tests/test_cmake_build/installed_embed/CMakeLists.txt @@ -22,5 +22,7 @@ set_target_properties(test_installed_embed PROPERTIES OUTPUT_NAME test_cmake_bui # This may be needed to resolve header conflicts, e.g. between Python release and debug headers. set_target_properties(test_installed_embed PROPERTIES NO_SYSTEM_FROM_IMPORTED ON) -add_custom_target(check_installed_embed $ - ${PROJECT_SOURCE_DIR}/../test.py) +add_custom_target( + check_installed_embed + $ ${PROJECT_SOURCE_DIR}/../test.py + DEPENDS test_installed_embed) diff --git a/pybind11/tests/test_cmake_build/installed_function/CMakeLists.txt b/pybind11/tests/test_cmake_build/installed_function/CMakeLists.txt index 1a502863c..d7ca4db55 100644 --- a/pybind11/tests/test_cmake_build/installed_function/CMakeLists.txt +++ b/pybind11/tests/test_cmake_build/installed_function/CMakeLists.txt @@ -35,4 +35,5 @@ add_custom_target( PYTHONPATH=$ ${_Python_EXECUTABLE} ${PROJECT_SOURCE_DIR}/../test.py - ${PROJECT_NAME}) + ${PROJECT_NAME} + DEPENDS test_installed_function) diff --git a/pybind11/tests/test_cmake_build/installed_target/CMakeLists.txt b/pybind11/tests/test_cmake_build/installed_target/CMakeLists.txt index b38eb7747..bc5e101f1 100644 --- a/pybind11/tests/test_cmake_build/installed_target/CMakeLists.txt +++ b/pybind11/tests/test_cmake_build/installed_target/CMakeLists.txt @@ -42,4 +42,5 @@ add_custom_target( PYTHONPATH=$ ${_Python_EXECUTABLE} ${PROJECT_SOURCE_DIR}/../test.py - ${PROJECT_NAME}) + ${PROJECT_NAME} + DEPENDS test_installed_target) diff --git a/pybind11/tests/test_cmake_build/subdirectory_embed/CMakeLists.txt b/pybind11/tests/test_cmake_build/subdirectory_embed/CMakeLists.txt index c7df0cf77..58cdd7cfd 100644 --- a/pybind11/tests/test_cmake_build/subdirectory_embed/CMakeLists.txt +++ b/pybind11/tests/test_cmake_build/subdirectory_embed/CMakeLists.txt @@ -16,15 +16,17 @@ set(PYBIND11_INSTALL CACHE BOOL "") set(PYBIND11_EXPORT_NAME test_export) -add_subdirectory(${PYBIND11_PROJECT_DIR} pybind11) +add_subdirectory("${pybind11_SOURCE_DIR}" pybind11) # Test basic target functionality add_executable(test_subdirectory_embed ../embed.cpp) target_link_libraries(test_subdirectory_embed PRIVATE pybind11::embed) set_target_properties(test_subdirectory_embed PROPERTIES OUTPUT_NAME test_cmake_build) -add_custom_target(check_subdirectory_embed $ - ${PROJECT_SOURCE_DIR}/../test.py) +add_custom_target( + check_subdirectory_embed + $ "${PROJECT_SOURCE_DIR}/../test.py" + DEPENDS test_subdirectory_embed) # Test custom export group -- PYBIND11_EXPORT_NAME add_library(test_embed_lib ../embed.cpp) diff --git a/pybind11/tests/test_cmake_build/subdirectory_function/CMakeLists.txt b/pybind11/tests/test_cmake_build/subdirectory_function/CMakeLists.txt index 624c600f8..01557c439 100644 --- a/pybind11/tests/test_cmake_build/subdirectory_function/CMakeLists.txt +++ b/pybind11/tests/test_cmake_build/subdirectory_function/CMakeLists.txt @@ -11,7 +11,7 @@ endif() project(test_subdirectory_function CXX) -add_subdirectory("${PYBIND11_PROJECT_DIR}" pybind11) +add_subdirectory("${pybind11_SOURCE_DIR}" pybind11) pybind11_add_module(test_subdirectory_function ../main.cpp) set_target_properties(test_subdirectory_function PROPERTIES OUTPUT_NAME test_cmake_build) @@ -31,4 +31,5 @@ add_custom_target( PYTHONPATH=$ ${_Python_EXECUTABLE} ${PROJECT_SOURCE_DIR}/../test.py - ${PROJECT_NAME}) + ${PROJECT_NAME} + DEPENDS test_subdirectory_function) diff --git a/pybind11/tests/test_cmake_build/subdirectory_target/CMakeLists.txt b/pybind11/tests/test_cmake_build/subdirectory_target/CMakeLists.txt index 2471941fb..ba82fdee2 100644 --- a/pybind11/tests/test_cmake_build/subdirectory_target/CMakeLists.txt +++ b/pybind11/tests/test_cmake_build/subdirectory_target/CMakeLists.txt @@ -11,7 +11,7 @@ endif() project(test_subdirectory_target CXX) -add_subdirectory(${PYBIND11_PROJECT_DIR} pybind11) +add_subdirectory("${pybind11_SOURCE_DIR}" pybind11) add_library(test_subdirectory_target MODULE ../main.cpp) set_target_properties(test_subdirectory_target PROPERTIES OUTPUT_NAME test_cmake_build) @@ -37,4 +37,5 @@ add_custom_target( PYTHONPATH=$ ${_Python_EXECUTABLE} ${PROJECT_SOURCE_DIR}/../test.py - ${PROJECT_NAME}) + ${PROJECT_NAME} + DEPENDS test_subdirectory_target) diff --git a/pybind11/tests/test_cmake_build/test.py b/pybind11/tests/test_cmake_build/test.py index 87ed5135f..972a27bea 100644 --- a/pybind11/tests/test_cmake_build/test.py +++ b/pybind11/tests/test_cmake_build/test.py @@ -1,6 +1,10 @@ # -*- coding: utf-8 -*- import sys + import test_cmake_build +if str is not bytes: # If not Python2 + assert isinstance(__file__, str) # Test this is properly set + assert test_cmake_build.add(1, 2) == 3 print("{} imports, runs, and adds: 1 + 2 = 3".format(sys.argv[1])) diff --git a/pybind11/tests/test_const_name.cpp b/pybind11/tests/test_const_name.cpp new file mode 100644 index 000000000..5cb3d16c1 --- /dev/null +++ b/pybind11/tests/test_const_name.cpp @@ -0,0 +1,70 @@ +// Copyright (c) 2021 The Pybind Development Team. +// All rights reserved. Use of this source code is governed by a +// BSD-style license that can be found in the LICENSE file. + +#include "pybind11_tests.h" + +#if defined(_MSC_VER) && _MSC_VER < 1910 + +// MSVC 2015 fails in bizarre ways. +# define PYBIND11_SKIP_TEST_CONST_NAME + +#else // Only test with MSVC 2017 or newer. + +// IUT = Implementation Under Test +# define CONST_NAME_TESTS(TEST_FUNC, IUT) \ + std::string TEST_FUNC(int selector) { \ + switch (selector) { \ + case 0: \ + return IUT("").text; \ + case 1: \ + return IUT("A").text; \ + case 2: \ + return IUT("Bd").text; \ + case 3: \ + return IUT("Cef").text; \ + case 4: \ + return IUT().text; /*NOLINT(bugprone-macro-parentheses)*/ \ + case 5: \ + return IUT().text; /*NOLINT(bugprone-macro-parentheses)*/ \ + case 6: \ + return IUT("T1", "T2").text; /*NOLINT(bugprone-macro-parentheses)*/ \ + case 7: \ + return IUT("U1", "U2").text; /*NOLINT(bugprone-macro-parentheses)*/ \ + case 8: \ + /*NOLINTNEXTLINE(bugprone-macro-parentheses)*/ \ + return IUT(IUT("D1"), IUT("D2")).text; \ + case 9: \ + /*NOLINTNEXTLINE(bugprone-macro-parentheses)*/ \ + return IUT(IUT("E1"), IUT("E2")).text; \ + case 10: \ + return IUT("KeepAtEnd").text; \ + default: \ + break; \ + } \ + throw std::runtime_error("Invalid selector value."); \ + } + +CONST_NAME_TESTS(const_name_tests, py::detail::const_name) + +# ifdef PYBIND11_DETAIL_UNDERSCORE_BACKWARD_COMPATIBILITY +CONST_NAME_TESTS(underscore_tests, py::detail::_) +# endif + +#endif // MSVC >= 2017 + +TEST_SUBMODULE(const_name, m) { +#ifdef PYBIND11_SKIP_TEST_CONST_NAME + m.attr("const_name_tests") = "PYBIND11_SKIP_TEST_CONST_NAME"; +#else + m.def("const_name_tests", const_name_tests); +#endif + +#ifdef PYBIND11_SKIP_TEST_CONST_NAME + m.attr("underscore_tests") = "PYBIND11_SKIP_TEST_CONST_NAME"; +#elif defined(PYBIND11_DETAIL_UNDERSCORE_BACKWARD_COMPATIBILITY) + m.def("underscore_tests", underscore_tests); +#else + m.attr("underscore_tests") = "PYBIND11_DETAIL_UNDERSCORE_BACKWARD_COMPATIBILITY not defined."; +#endif +} diff --git a/pybind11/tests/test_const_name.py b/pybind11/tests/test_const_name.py new file mode 100644 index 000000000..d4e45e5e9 --- /dev/null +++ b/pybind11/tests/test_const_name.py @@ -0,0 +1,31 @@ +# -*- coding: utf-8 -*- +import pytest + +import env +from pybind11_tests import const_name as m + + +@pytest.mark.parametrize("func", (m.const_name_tests, m.underscore_tests)) +@pytest.mark.parametrize( + "selector, expected", + enumerate( + ( + "", + "A", + "Bd", + "Cef", + "%", + "%", + "T1", + "U2", + "D1", + "E2", + "KeepAtEnd", + ) + ), +) +def test_const_name(func, selector, expected): + if isinstance(func, type(u"") if env.PY2 else str): + pytest.skip(func) + text = func(selector) + assert text == expected diff --git a/pybind11/tests/test_constants_and_functions.cpp b/pybind11/tests/test_constants_and_functions.cpp index f60779559..c0554503f 100644 --- a/pybind11/tests/test_constants_and_functions.cpp +++ b/pybind11/tests/test_constants_and_functions.cpp @@ -1,5 +1,6 @@ /* - tests/test_constants_and_functions.cpp -- global constants and functions, enumerations, raw byte strings + tests/test_constants_and_functions.cpp -- global constants and functions, enumerations, raw + byte strings Copyright (c) 2016 Wenzel Jakob @@ -33,7 +34,7 @@ py::bytes return_bytes() { return std::string(data, 4); } -std::string print_bytes(py::bytes bytes) { +std::string print_bytes(const py::bytes &bytes) { std::string ret = "bytes["; const auto value = static_cast(bytes); for (size_t i = 0; i < value.length(); ++i) { @@ -46,15 +47,23 @@ std::string print_bytes(py::bytes bytes) { // Test that we properly handle C++17 exception specifiers (which are part of the function signature // in C++17). These should all still work before C++17, but don't affect the function signature. namespace test_exc_sp { +// [workaround(intel)] Unable to use noexcept instead of noexcept(true) +// Make the f1 test basically the same as the f2 test in C++17 mode for the Intel compiler as +// it fails to compile with a plain noexcept (tested with icc (ICC) 2021.1 Beta 20200827). +#if defined(__INTEL_COMPILER) && defined(PYBIND11_CPP17) +int f1(int x) noexcept(true) { return x+1; } +#else int f1(int x) noexcept { return x+1; } +#endif int f2(int x) noexcept(true) { return x+2; } int f3(int x) noexcept(false) { return x+3; } -#if defined(__GNUG__) +#if defined(__GNUG__) && !defined(__INTEL_COMPILER) # pragma GCC diagnostic push # pragma GCC diagnostic ignored "-Wdeprecated" #endif +// NOLINTNEXTLINE(modernize-use-noexcept) int f4(int x) throw() { return x+4; } // Deprecated equivalent to noexcept(true) -#if defined(__GNUG__) +#if defined(__GNUG__) && !defined(__INTEL_COMPILER) # pragma GCC diagnostic pop #endif struct C { @@ -64,13 +73,15 @@ struct C { int m4(int x) const noexcept(true) { return x-4; } int m5(int x) noexcept(false) { return x-5; } int m6(int x) const noexcept(false) { return x-6; } -#if defined(__GNUG__) +#if defined(__GNUG__) && !defined(__INTEL_COMPILER) # pragma GCC diagnostic push # pragma GCC diagnostic ignored "-Wdeprecated" #endif - int m7(int x) throw() { return x-7; } - int m8(int x) const throw() { return x-8; } -#if defined(__GNUG__) + // NOLINTNEXTLINE(modernize-use-noexcept) + int m7(int x) throw() { return x - 7; } + // NOLINTNEXTLINE(modernize-use-noexcept) + int m8(int x) const throw() { return x - 8; } +#if defined(__GNUG__) && !defined(__INTEL_COMPILER) # pragma GCC diagnostic pop #endif }; @@ -122,6 +133,33 @@ TEST_SUBMODULE(constants_and_functions, m) { ; m.def("f1", f1); m.def("f2", f2); +#if defined(__INTEL_COMPILER) +# pragma warning push +# pragma warning disable 878 // incompatible exception specifications +#endif m.def("f3", f3); +#if defined(__INTEL_COMPILER) +# pragma warning pop +#endif m.def("f4", f4); + + // test_function_record_leaks + struct LargeCapture { + // This should always be enough to trigger the alternative branch + // where `sizeof(capture) > sizeof(rec->data)` + uint64_t zeros[10] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9}; + }; + m.def("register_large_capture_with_invalid_arguments", [](py::module_ m) { + LargeCapture capture; // VS 2015's MSVC is acting up if we create the array here + m.def("should_raise", [capture](int) { return capture.zeros[9] + 33; }, py::kw_only(), py::arg()); + }); + m.def("register_with_raising_repr", [](py::module_ m, const py::object &default_value) { + m.def( + "should_raise", + [](int, int, const py::object &) { return 42; }, + "some docstring", + py::arg_v("x", 42), + py::arg_v("y", 42, ""), + py::arg_v("z", default_value)); + }); } diff --git a/pybind11/tests/test_constants_and_functions.py b/pybind11/tests/test_constants_and_functions.py index b980ccf1c..ff13bd0f2 100644 --- a/pybind11/tests/test_constants_and_functions.py +++ b/pybind11/tests/test_constants_and_functions.py @@ -40,3 +40,14 @@ def test_exception_specifiers(): assert m.f2(53) == 55 assert m.f3(86) == 89 assert m.f4(140) == 144 + + +def test_function_record_leaks(): + class RaisingRepr: + def __repr__(self): + raise RuntimeError("Surprise!") + + with pytest.raises(RuntimeError): + m.register_large_capture_with_invalid_arguments(m) + with pytest.raises(RuntimeError): + m.register_with_raising_repr(m, RaisingRepr()) diff --git a/pybind11/tests/test_copy_move.cpp b/pybind11/tests/test_copy_move.cpp index 05d5c4767..4711a9482 100644 --- a/pybind11/tests/test_copy_move.cpp +++ b/pybind11/tests/test_copy_move.cpp @@ -37,9 +37,16 @@ template <> lacking_move_ctor empty::instance_ = {}; class MoveOnlyInt { public: MoveOnlyInt() { print_default_created(this); } - MoveOnlyInt(int v) : value{std::move(v)} { print_created(this, value); } - MoveOnlyInt(MoveOnlyInt &&m) { print_move_created(this, m.value); std::swap(value, m.value); } - MoveOnlyInt &operator=(MoveOnlyInt &&m) { print_move_assigned(this, m.value); std::swap(value, m.value); return *this; } + explicit MoveOnlyInt(int v) : value{v} { print_created(this, value); } + MoveOnlyInt(MoveOnlyInt &&m) noexcept { + print_move_created(this, m.value); + std::swap(value, m.value); + } + MoveOnlyInt &operator=(MoveOnlyInt &&m) noexcept { + print_move_assigned(this, m.value); + std::swap(value, m.value); + return *this; + } MoveOnlyInt(const MoveOnlyInt &) = delete; MoveOnlyInt &operator=(const MoveOnlyInt &) = delete; ~MoveOnlyInt() { print_destroyed(this); } @@ -49,9 +56,16 @@ public: class MoveOrCopyInt { public: MoveOrCopyInt() { print_default_created(this); } - MoveOrCopyInt(int v) : value{std::move(v)} { print_created(this, value); } - MoveOrCopyInt(MoveOrCopyInt &&m) { print_move_created(this, m.value); std::swap(value, m.value); } - MoveOrCopyInt &operator=(MoveOrCopyInt &&m) { print_move_assigned(this, m.value); std::swap(value, m.value); return *this; } + explicit MoveOrCopyInt(int v) : value{v} { print_created(this, value); } + MoveOrCopyInt(MoveOrCopyInt &&m) noexcept { + print_move_created(this, m.value); + std::swap(value, m.value); + } + MoveOrCopyInt &operator=(MoveOrCopyInt &&m) noexcept { + print_move_assigned(this, m.value); + std::swap(value, m.value); + return *this; + } MoveOrCopyInt(const MoveOrCopyInt &c) { print_copy_created(this, c.value); value = c.value; } MoveOrCopyInt &operator=(const MoveOrCopyInt &c) { print_copy_assigned(this, c.value); value = c.value; return *this; } ~MoveOrCopyInt() { print_destroyed(this); } @@ -61,7 +75,7 @@ public: class CopyOnlyInt { public: CopyOnlyInt() { print_default_created(this); } - CopyOnlyInt(int v) : value{std::move(v)} { print_created(this, value); } + explicit CopyOnlyInt(int v) : value{v} { print_created(this, value); } CopyOnlyInt(const CopyOnlyInt &c) { print_copy_created(this, c.value); value = c.value; } CopyOnlyInt &operator=(const CopyOnlyInt &c) { print_copy_assigned(this, c.value); value = c.value; return *this; } ~CopyOnlyInt() { print_destroyed(this); } @@ -71,13 +85,13 @@ public: PYBIND11_NAMESPACE_BEGIN(pybind11) PYBIND11_NAMESPACE_BEGIN(detail) template <> struct type_caster { - PYBIND11_TYPE_CASTER(MoveOnlyInt, _("MoveOnlyInt")); + PYBIND11_TYPE_CASTER(MoveOnlyInt, const_name("MoveOnlyInt")); bool load(handle src, bool) { value = MoveOnlyInt(src.cast()); return true; } static handle cast(const MoveOnlyInt &m, return_value_policy r, handle p) { return pybind11::cast(m.value, r, p); } }; template <> struct type_caster { - PYBIND11_TYPE_CASTER(MoveOrCopyInt, _("MoveOrCopyInt")); + PYBIND11_TYPE_CASTER(MoveOrCopyInt, const_name("MoveOrCopyInt")); bool load(handle src, bool) { value = MoveOrCopyInt(src.cast()); return true; } static handle cast(const MoveOrCopyInt &m, return_value_policy r, handle p) { return pybind11::cast(m.value, r, p); } }; @@ -86,15 +100,15 @@ template <> struct type_caster { protected: CopyOnlyInt value; public: - static constexpr auto name = _("CopyOnlyInt"); + static constexpr auto name = const_name("CopyOnlyInt"); bool load(handle src, bool) { value = CopyOnlyInt(src.cast()); return true; } static handle cast(const CopyOnlyInt &m, return_value_policy r, handle p) { return pybind11::cast(m.value, r, p); } static handle cast(const CopyOnlyInt *src, return_value_policy policy, handle parent) { if (!src) return none().release(); return cast(*src, policy, parent); } - operator CopyOnlyInt*() { return &value; } - operator CopyOnlyInt&() { return value; } + explicit operator CopyOnlyInt *() { return &value; } + explicit operator CopyOnlyInt &() { return value; } template using cast_op_type = pybind11::detail::cast_op_type; }; PYBIND11_NAMESPACE_END(detail) @@ -111,14 +125,15 @@ TEST_SUBMODULE(copy_move_policies, m) { py::return_value_policy::move); // test_move_and_copy_casts - m.def("move_and_copy_casts", [](py::object o) { + // NOLINTNEXTLINE(performance-unnecessary-value-param) + m.def("move_and_copy_casts", [](const py::object &o) { int r = 0; r += py::cast(o).value; /* moves */ r += py::cast(o).value; /* moves */ r += py::cast(o).value; /* copies */ - MoveOrCopyInt m1(py::cast(o)); /* moves */ - MoveOnlyInt m2(py::cast(o)); /* moves */ - CopyOnlyInt m3(py::cast(o)); /* copies */ + auto m1(py::cast(o)); /* moves */ + auto m2(py::cast(o)); /* moves */ + auto m3(py::cast(o)); /* copies */ r += m1.value + m2.value + m3.value; return r; @@ -126,7 +141,11 @@ TEST_SUBMODULE(copy_move_policies, m) { // test_move_and_copy_loads m.def("move_only", [](MoveOnlyInt m) { return m.value; }); + // Changing this breaks the existing test: needs careful review. + // NOLINTNEXTLINE(performance-unnecessary-value-param) m.def("move_or_copy", [](MoveOrCopyInt m) { return m.value; }); + // Changing this breaks the existing test: needs careful review. + // NOLINTNEXTLINE(performance-unnecessary-value-param) m.def("copy_only", [](CopyOnlyInt m) { return m.value; }); m.def("move_pair", [](std::pair p) { return p.first.value + p.second.value; @@ -186,8 +205,7 @@ TEST_SUBMODULE(copy_move_policies, m) { void *ptr = std::malloc(bytes); if (ptr) return ptr; - else - throw std::bad_alloc{}; + throw std::bad_alloc{}; } }; py::class_(m, "PrivateOpNew").def_readonly("value", &PrivateOpNew::value); @@ -201,7 +219,7 @@ TEST_SUBMODULE(copy_move_policies, m) { // #389: rvp::move should fall-through to copy on non-movable objects struct MoveIssue1 { int v; - MoveIssue1(int v) : v{v} {} + explicit MoveIssue1(int v) : v{v} {} MoveIssue1(const MoveIssue1 &c) = default; MoveIssue1(MoveIssue1 &&) = delete; }; @@ -209,11 +227,12 @@ TEST_SUBMODULE(copy_move_policies, m) { struct MoveIssue2 { int v; - MoveIssue2(int v) : v{v} {} + explicit MoveIssue2(int v) : v{v} {} MoveIssue2(MoveIssue2 &&) = default; }; py::class_(m, "MoveIssue2").def(py::init()).def_readwrite("value", &MoveIssue2::v); - m.def("get_moveissue1", [](int i) { return new MoveIssue1(i); }, py::return_value_policy::move); + // #2742: Don't expect ownership of raw pointer to `new`ed object to be transferred with `py::return_value_policy::move` + m.def("get_moveissue1", [](int i) { return std::unique_ptr(new MoveIssue1(i)); }, py::return_value_policy::move); m.def("get_moveissue2", [](int i) { return MoveIssue2(i); }, py::return_value_policy::move); } diff --git a/pybind11/tests/test_copy_move.py b/pybind11/tests/test_copy_move.py index 6b53993a9..eb1efddd5 100644 --- a/pybind11/tests/test_copy_move.py +++ b/pybind11/tests/test_copy_move.py @@ -1,5 +1,6 @@ # -*- coding: utf-8 -*- import pytest + from pybind11_tests import copy_move_policies as m @@ -19,7 +20,11 @@ def test_move_and_copy_casts(): """Cast some values in C++ via custom type casters and count the number of moves/copies.""" cstats = m.move_and_copy_cstats() - c_m, c_mc, c_c = cstats["MoveOnlyInt"], cstats["MoveOrCopyInt"], cstats["CopyOnlyInt"] + c_m, c_mc, c_c = ( + cstats["MoveOnlyInt"], + cstats["MoveOrCopyInt"], + cstats["CopyOnlyInt"], + ) # The type move constructions/assignments below each get incremented: the move assignment comes # from the type_caster load; the move construction happens when extracting that via a cast or @@ -43,7 +48,11 @@ def test_move_and_copy_loads(): moves/copies.""" cstats = m.move_and_copy_cstats() - c_m, c_mc, c_c = cstats["MoveOnlyInt"], cstats["MoveOrCopyInt"], cstats["CopyOnlyInt"] + c_m, c_mc, c_c = ( + cstats["MoveOnlyInt"], + cstats["MoveOrCopyInt"], + cstats["CopyOnlyInt"], + ) assert m.move_only(10) == 10 # 1 move, c_m assert m.move_or_copy(11) == 11 # 1 move, c_mc @@ -66,12 +75,16 @@ def test_move_and_copy_loads(): assert c_m.alive() + c_mc.alive() + c_c.alive() == 0 -@pytest.mark.skipif(not m.has_optional, reason='no ') +@pytest.mark.skipif(not m.has_optional, reason="no ") def test_move_and_copy_load_optional(): """Tests move/copy loads of std::optional arguments""" cstats = m.move_and_copy_cstats() - c_m, c_mc, c_c = cstats["MoveOnlyInt"], cstats["MoveOrCopyInt"], cstats["CopyOnlyInt"] + c_m, c_mc, c_c = ( + cstats["MoveOnlyInt"], + cstats["MoveOrCopyInt"], + cstats["CopyOnlyInt"], + ) # The extra move/copy constructions below come from the std::optional move (which has to move # its arguments): @@ -107,7 +120,7 @@ def test_private_op_new(): def test_move_fallback(): """#389: rvp::move should fall-through to copy on non-movable objects""" - m2 = m.get_moveissue2(2) - assert m2.value == 2 m1 = m.get_moveissue1(1) assert m1.value == 1 + m2 = m.get_moveissue2(2) + assert m2.value == 2 diff --git a/pybind11/tests/test_custom_type_casters.cpp b/pybind11/tests/test_custom_type_casters.cpp index d565add26..48613ee5a 100644 --- a/pybind11/tests/test_custom_type_casters.cpp +++ b/pybind11/tests/test_custom_type_casters.cpp @@ -18,7 +18,12 @@ class ArgAlwaysConverts { }; namespace pybind11 { namespace detail { template <> struct type_caster { public: + // Classic +#ifdef PYBIND11_DETAIL_UNDERSCORE_BACKWARD_COMPATIBILITY PYBIND11_TYPE_CASTER(ArgInspector1, _("ArgInspector1")); +#else + PYBIND11_TYPE_CASTER(ArgInspector1, const_name("ArgInspector1")); +#endif bool load(handle src, bool convert) { value.arg = "loading ArgInspector1 argument " + @@ -33,7 +38,7 @@ public: }; template <> struct type_caster { public: - PYBIND11_TYPE_CASTER(ArgInspector2, _("ArgInspector2")); + PYBIND11_TYPE_CASTER(ArgInspector2, const_name("ArgInspector2")); bool load(handle src, bool convert) { value.arg = "loading ArgInspector2 argument " + @@ -48,7 +53,7 @@ public: }; template <> struct type_caster { public: - PYBIND11_TYPE_CASTER(ArgAlwaysConverts, _("ArgAlwaysConverts")); + PYBIND11_TYPE_CASTER(ArgAlwaysConverts, const_name("ArgAlwaysConverts")); bool load(handle, bool convert) { return convert; @@ -67,13 +72,16 @@ public: DestructionTester() { print_default_created(this); } ~DestructionTester() { print_destroyed(this); } DestructionTester(const DestructionTester &) { print_copy_created(this); } - DestructionTester(DestructionTester &&) { print_move_created(this); } + DestructionTester(DestructionTester &&) noexcept { print_move_created(this); } DestructionTester &operator=(const DestructionTester &) { print_copy_assigned(this); return *this; } - DestructionTester &operator=(DestructionTester &&) { print_move_assigned(this); return *this; } + DestructionTester &operator=(DestructionTester &&) noexcept { + print_move_assigned(this); + return *this; + } }; namespace pybind11 { namespace detail { template <> struct type_caster { - PYBIND11_TYPE_CASTER(DestructionTester, _("DestructionTester")); + PYBIND11_TYPE_CASTER(DestructionTester, const_name("DestructionTester")); bool load(handle, bool) { return true; } static handle cast(const DestructionTester &, return_value_policy, handle) { @@ -94,24 +102,35 @@ TEST_SUBMODULE(custom_type_casters, m) { class ArgInspector { public: ArgInspector1 f(ArgInspector1 a, ArgAlwaysConverts) { return a; } - std::string g(ArgInspector1 a, const ArgInspector1 &b, int c, ArgInspector2 *d, ArgAlwaysConverts) { + std::string g(const ArgInspector1 &a, + const ArgInspector1 &b, + int c, + ArgInspector2 *d, + ArgAlwaysConverts) { return a.arg + "\n" + b.arg + "\n" + std::to_string(c) + "\n" + d->arg; } static ArgInspector2 h(ArgInspector2 a, ArgAlwaysConverts) { return a; } }; + // [workaround(intel)] ICC 20/21 breaks with py::arg().stuff, using py::arg{}.stuff works. py::class_(m, "ArgInspector") .def(py::init<>()) .def("f", &ArgInspector::f, py::arg(), py::arg() = ArgAlwaysConverts()) .def("g", &ArgInspector::g, "a"_a.noconvert(), "b"_a, "c"_a.noconvert()=13, "d"_a=ArgInspector2(), py::arg() = ArgAlwaysConverts()) - .def_static("h", &ArgInspector::h, py::arg().noconvert(), py::arg() = ArgAlwaysConverts()) + .def_static("h", &ArgInspector::h, py::arg{}.noconvert(), py::arg() = ArgAlwaysConverts()) ; - m.def("arg_inspect_func", [](ArgInspector2 a, ArgInspector1 b, ArgAlwaysConverts) { return a.arg + "\n" + b.arg; }, - py::arg().noconvert(false), py::arg_v(nullptr, ArgInspector1()).noconvert(true), py::arg() = ArgAlwaysConverts()); + m.def( + "arg_inspect_func", + [](const ArgInspector2 &a, const ArgInspector1 &b, ArgAlwaysConverts) { + return a.arg + "\n" + b.arg; + }, + py::arg{}.noconvert(false), + py::arg_v(nullptr, ArgInspector1()).noconvert(true), + py::arg() = ArgAlwaysConverts()); - m.def("floats_preferred", [](double f) { return 0.5 * f; }, py::arg("f")); - m.def("floats_only", [](double f) { return 0.5 * f; }, py::arg("f").noconvert()); - m.def("ints_preferred", [](int i) { return i / 2; }, py::arg("i")); - m.def("ints_only", [](int i) { return i / 2; }, py::arg("i").noconvert()); + m.def("floats_preferred", [](double f) { return 0.5 * f; }, "f"_a); + m.def("floats_only", [](double f) { return 0.5 * f; }, "f"_a.noconvert()); + m.def("ints_preferred", [](int i) { return i / 2; }, "i"_a); + m.def("ints_only", [](int i) { return i / 2; }, "i"_a.noconvert()); // test_custom_caster_destruction // Test that `take_ownership` works on types with a custom type caster when given a pointer diff --git a/pybind11/tests/test_custom_type_casters.py b/pybind11/tests/test_custom_type_casters.py index 9475c4516..a10646ff4 100644 --- a/pybind11/tests/test_custom_type_casters.py +++ b/pybind11/tests/test_custom_type_casters.py @@ -1,69 +1,96 @@ # -*- coding: utf-8 -*- import pytest + from pybind11_tests import custom_type_casters as m def test_noconvert_args(msg): a = m.ArgInspector() - assert msg(a.f("hi")) == """ + assert ( + msg(a.f("hi")) + == """ loading ArgInspector1 argument WITH conversion allowed. Argument value = hi """ - assert msg(a.g("this is a", "this is b")) == """ + ) + assert ( + msg(a.g("this is a", "this is b")) + == """ loading ArgInspector1 argument WITHOUT conversion allowed. Argument value = this is a loading ArgInspector1 argument WITH conversion allowed. Argument value = this is b 13 loading ArgInspector2 argument WITH conversion allowed. Argument value = (default arg inspector 2) """ # noqa: E501 line too long - assert msg(a.g("this is a", "this is b", 42)) == """ + ) + assert ( + msg(a.g("this is a", "this is b", 42)) + == """ loading ArgInspector1 argument WITHOUT conversion allowed. Argument value = this is a loading ArgInspector1 argument WITH conversion allowed. Argument value = this is b 42 loading ArgInspector2 argument WITH conversion allowed. Argument value = (default arg inspector 2) """ # noqa: E501 line too long - assert msg(a.g("this is a", "this is b", 42, "this is d")) == """ + ) + assert ( + msg(a.g("this is a", "this is b", 42, "this is d")) + == """ loading ArgInspector1 argument WITHOUT conversion allowed. Argument value = this is a loading ArgInspector1 argument WITH conversion allowed. Argument value = this is b 42 loading ArgInspector2 argument WITH conversion allowed. Argument value = this is d """ - assert (a.h("arg 1") == - "loading ArgInspector2 argument WITHOUT conversion allowed. Argument value = arg 1") - assert msg(m.arg_inspect_func("A1", "A2")) == """ + ) + assert ( + a.h("arg 1") + == "loading ArgInspector2 argument WITHOUT conversion allowed. Argument value = arg 1" + ) + assert ( + msg(m.arg_inspect_func("A1", "A2")) + == """ loading ArgInspector2 argument WITH conversion allowed. Argument value = A1 loading ArgInspector1 argument WITHOUT conversion allowed. Argument value = A2 """ + ) assert m.floats_preferred(4) == 2.0 assert m.floats_only(4.0) == 2.0 with pytest.raises(TypeError) as excinfo: m.floats_only(4) - assert msg(excinfo.value) == """ + assert ( + msg(excinfo.value) + == """ floats_only(): incompatible function arguments. The following argument types are supported: 1. (f: float) -> float Invoked with: 4 """ + ) assert m.ints_preferred(4) == 2 assert m.ints_preferred(True) == 0 with pytest.raises(TypeError) as excinfo: m.ints_preferred(4.0) - assert msg(excinfo.value) == """ + assert ( + msg(excinfo.value) + == """ ints_preferred(): incompatible function arguments. The following argument types are supported: 1. (i: int) -> int Invoked with: 4.0 """ # noqa: E501 line too long + ) assert m.ints_only(4) == 2 with pytest.raises(TypeError) as excinfo: m.ints_only(4.0) - assert msg(excinfo.value) == """ + assert ( + msg(excinfo.value) + == """ ints_only(): incompatible function arguments. The following argument types are supported: 1. (i: int) -> int Invoked with: 4.0 """ + ) def test_custom_caster_destruction(): diff --git a/pybind11/tests/test_custom_type_setup.cpp b/pybind11/tests/test_custom_type_setup.cpp new file mode 100644 index 000000000..42fae05d5 --- /dev/null +++ b/pybind11/tests/test_custom_type_setup.cpp @@ -0,0 +1,41 @@ +/* + tests/test_custom_type_setup.cpp -- Tests `pybind11::custom_type_setup` + + Copyright (c) Google LLC + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#include + +#include "pybind11_tests.h" + +namespace py = pybind11; + +namespace { + +struct OwnsPythonObjects { + py::object value = py::none(); +}; +} // namespace + +TEST_SUBMODULE(custom_type_setup, m) { + py::class_ cls( + m, "OwnsPythonObjects", py::custom_type_setup([](PyHeapTypeObject *heap_type) { + auto *type = &heap_type->ht_type; + type->tp_flags |= Py_TPFLAGS_HAVE_GC; + type->tp_traverse = [](PyObject *self_base, visitproc visit, void *arg) { + auto &self = py::cast(py::handle(self_base)); + Py_VISIT(self.value.ptr()); + return 0; + }; + type->tp_clear = [](PyObject *self_base) { + auto &self = py::cast(py::handle(self_base)); + self.value = py::none(); + return 0; + }; + })); + cls.def(py::init<>()); + cls.def_readwrite("value", &OwnsPythonObjects::value); +} diff --git a/pybind11/tests/test_custom_type_setup.py b/pybind11/tests/test_custom_type_setup.py new file mode 100644 index 000000000..ef96f0814 --- /dev/null +++ b/pybind11/tests/test_custom_type_setup.py @@ -0,0 +1,50 @@ +# -*- coding: utf-8 -*- + +import gc +import weakref + +import pytest + +import env # noqa: F401 +from pybind11_tests import custom_type_setup as m + + +@pytest.fixture +def gc_tester(): + """Tests that an object is garbage collected. + + Assumes that any unreferenced objects are fully collected after calling + `gc.collect()`. That is true on CPython, but does not appear to reliably + hold on PyPy. + """ + + weak_refs = [] + + def add_ref(obj): + # PyPy does not support `gc.is_tracked`. + if hasattr(gc, "is_tracked"): + assert gc.is_tracked(obj) + weak_refs.append(weakref.ref(obj)) + + yield add_ref + + gc.collect() + for ref in weak_refs: + assert ref() is None + + +# PyPy does not seem to reliably garbage collect. +@pytest.mark.skipif("env.PYPY") +def test_self_cycle(gc_tester): + obj = m.OwnsPythonObjects() + obj.value = obj + gc_tester(obj) + + +# PyPy does not seem to reliably garbage collect. +@pytest.mark.skipif("env.PYPY") +def test_indirect_cycle(gc_tester): + obj = m.OwnsPythonObjects() + obj_list = [obj] + obj.value = obj_list + gc_tester(obj) diff --git a/pybind11/tests/test_docstring_options.cpp b/pybind11/tests/test_docstring_options.cpp index 8c8f79fd5..8a97af55f 100644 --- a/pybind11/tests/test_docstring_options.cpp +++ b/pybind11/tests/test_docstring_options.cpp @@ -45,6 +45,14 @@ TEST_SUBMODULE(docstring_options, m) { m.def("test_function7", [](int, int) {}, py::arg("a"), py::arg("b"), "A custom docstring"); + { + py::options options; + options.disable_user_defined_docstrings(); + options.disable_function_signatures(); + + m.def("test_function8", []() {}); + } + { py::options options; options.disable_user_defined_docstrings(); diff --git a/pybind11/tests/test_docstring_options.py b/pybind11/tests/test_docstring_options.py index 80ade0f15..8ee661388 100644 --- a/pybind11/tests/test_docstring_options.py +++ b/pybind11/tests/test_docstring_options.py @@ -18,10 +18,10 @@ def test_docstring_options(): assert m.test_overloaded3.__doc__ == "Overload docstr" # options.enable_function_signatures() - assert m.test_function3.__doc__ .startswith("test_function3(a: int, b: int) -> None") + assert m.test_function3.__doc__.startswith("test_function3(a: int, b: int) -> None") - assert m.test_function4.__doc__ .startswith("test_function4(a: int, b: int) -> None") - assert m.test_function4.__doc__ .endswith("A custom docstring\n") + assert m.test_function4.__doc__.startswith("test_function4(a: int, b: int) -> None") + assert m.test_function4.__doc__.endswith("A custom docstring\n") # options.disable_function_signatures() # options.disable_user_defined_docstrings() @@ -31,8 +31,11 @@ def test_docstring_options(): assert m.test_function6.__doc__ == "A custom docstring" # RAII destructor - assert m.test_function7.__doc__ .startswith("test_function7(a: int, b: int) -> None") - assert m.test_function7.__doc__ .endswith("A custom docstring\n") + assert m.test_function7.__doc__.startswith("test_function7(a: int, b: int) -> None") + assert m.test_function7.__doc__.endswith("A custom docstring\n") + + # when all options are disabled, no docstring (instead of an empty one) should be generated + assert m.test_function8.__doc__ is None # Suppression of user-defined docstrings for non-function objects assert not m.DocstringTestFoo.__doc__ diff --git a/pybind11/tests/test_eigen.cpp b/pybind11/tests/test_eigen.cpp index 56aa1a4a6..d22a94a1a 100644 --- a/pybind11/tests/test_eigen.cpp +++ b/pybind11/tests/test_eigen.cpp @@ -13,6 +13,9 @@ #include #if defined(_MSC_VER) +#if _MSC_VER < 1910 // VS 2015's MSVC +# pragma warning(disable: 4127) // C4127: conditional expression is constant +#endif # pragma warning(disable: 4996) // C4996: std::unary_negation is deprecated #endif @@ -54,15 +57,15 @@ void reset_refs() { } // Returns element 2,1 from a matrix (used to test copy/nocopy) -double get_elem(Eigen::Ref m) { return m(2, 1); }; - +double get_elem(const Eigen::Ref &m) { return m(2, 1); }; // Returns a matrix with 10*r + 100*c added to each matrix element (to help test that the matrix // reference is referencing rows/columns correctly). template Eigen::MatrixXd adjust_matrix(MatrixArgType m) { Eigen::MatrixXd ret(m); - for (int c = 0; c < m.cols(); c++) for (int r = 0; r < m.rows(); r++) - ret(r, c) += 10*r + 100*c; + for (int c = 0; c < m.cols(); c++) + for (int r = 0; r < m.rows(); r++) + ret(r, c) += 10*r + 100*c; // NOLINT(clang-analyzer-core.uninitialized.Assign) return ret; } @@ -93,15 +96,18 @@ TEST_SUBMODULE(eigen, m) { m.def("double_complex", [](const Eigen::VectorXcf &x) -> Eigen::VectorXcf { return 2.0f * x; }); m.def("double_threec", [](py::EigenDRef x) { x *= 2; }); m.def("double_threer", [](py::EigenDRef x) { x *= 2; }); - m.def("double_mat_cm", [](Eigen::MatrixXf x) -> Eigen::MatrixXf { return 2.0f * x; }); - m.def("double_mat_rm", [](DenseMatrixR x) -> DenseMatrixR { return 2.0f * x; }); + m.def("double_mat_cm", [](const Eigen::MatrixXf &x) -> Eigen::MatrixXf { return 2.0f * x; }); + m.def("double_mat_rm", [](const DenseMatrixR &x) -> DenseMatrixR { return 2.0f * x; }); // test_eigen_ref_to_python // Different ways of passing via Eigen::Ref; the first and second are the Eigen-recommended - m.def("cholesky1", [](Eigen::Ref x) -> Eigen::MatrixXd { return x.llt().matrixL(); }); + m.def("cholesky1", + [](const Eigen::Ref &x) -> Eigen::MatrixXd { return x.llt().matrixL(); }); m.def("cholesky2", [](const Eigen::Ref &x) -> Eigen::MatrixXd { return x.llt().matrixL(); }); m.def("cholesky3", [](const Eigen::Ref &x) -> Eigen::MatrixXd { return x.llt().matrixL(); }); - m.def("cholesky4", [](Eigen::Ref x) -> Eigen::MatrixXd { return x.llt().matrixL(); }); + m.def("cholesky4", [](const Eigen::Ref &x) -> Eigen::MatrixXd { + return x.llt().matrixL(); + }); // test_eigen_ref_mutators // Mutators: these add some value to the given element using Eigen, but Eigen should be mapping into @@ -175,6 +181,7 @@ TEST_SUBMODULE(eigen, m) { ReturnTester() { print_created(this); } ~ReturnTester() { print_destroyed(this); } static Eigen::MatrixXd create() { return Eigen::MatrixXd::Ones(10, 10); } + // NOLINTNEXTLINE(readability-const-return-type) static const Eigen::MatrixXd createConst() { return Eigen::MatrixXd::Ones(10, 10); } Eigen::MatrixXd &get() { return mat; } Eigen::MatrixXd *getPtr() { return &mat; } @@ -241,21 +248,27 @@ TEST_SUBMODULE(eigen, m) { // test_fixed, and various other tests m.def("fixed_r", [mat]() -> FixedMatrixR { return FixedMatrixR(mat); }); + // Our Eigen does a hack which respects constness through the numpy writeable flag. + // Therefore, the const return actually affects this type despite being an rvalue. + // NOLINTNEXTLINE(readability-const-return-type) m.def("fixed_r_const", [mat]() -> const FixedMatrixR { return FixedMatrixR(mat); }); m.def("fixed_c", [mat]() -> FixedMatrixC { return FixedMatrixC(mat); }); m.def("fixed_copy_r", [](const FixedMatrixR &m) -> FixedMatrixR { return m; }); m.def("fixed_copy_c", [](const FixedMatrixC &m) -> FixedMatrixC { return m; }); // test_mutator_descriptors - m.def("fixed_mutator_r", [](Eigen::Ref) {}); - m.def("fixed_mutator_c", [](Eigen::Ref) {}); - m.def("fixed_mutator_a", [](py::EigenDRef) {}); + m.def("fixed_mutator_r", [](const Eigen::Ref &) {}); + m.def("fixed_mutator_c", [](const Eigen::Ref &) {}); + m.def("fixed_mutator_a", [](const py::EigenDRef &) {}); // test_dense m.def("dense_r", [mat]() -> DenseMatrixR { return DenseMatrixR(mat); }); m.def("dense_c", [mat]() -> DenseMatrixC { return DenseMatrixC(mat); }); m.def("dense_copy_r", [](const DenseMatrixR &m) -> DenseMatrixR { return m; }); m.def("dense_copy_c", [](const DenseMatrixC &m) -> DenseMatrixC { return m; }); // test_sparse, test_sparse_signature - m.def("sparse_r", [mat]() -> SparseMatrixR { return Eigen::SparseView(mat); }); + m.def("sparse_r", [mat]() -> SparseMatrixR { + // NOLINTNEXTLINE(clang-analyzer-core.uninitialized.UndefReturn) + return Eigen::SparseView(mat); + }); m.def("sparse_c", [mat]() -> SparseMatrixC { return Eigen::SparseView(mat); }); m.def("sparse_copy_r", [](const SparseMatrixR &m) -> SparseMatrixR { return m; }); m.def("sparse_copy_c", [](const SparseMatrixC &m) -> SparseMatrixC { return m; }); @@ -272,39 +285,47 @@ TEST_SUBMODULE(eigen, m) { m.def("cpp_ref_r", [](py::handle m) { return m.cast>()(1, 0); }); m.def("cpp_ref_any", [](py::handle m) { return m.cast>()(1, 0); }); + // [workaround(intel)] ICC 20/21 breaks with py::arg().stuff, using py::arg{}.stuff works. // test_nocopy_wrapper // Test that we can prevent copying into an argument that would normally copy: First a version // that would allow copying (if types or strides don't match) for comparison: m.def("get_elem", &get_elem); // Now this alternative that calls the tells pybind to fail rather than copy: - m.def("get_elem_nocopy", [](Eigen::Ref m) -> double { return get_elem(m); }, - py::arg().noconvert()); + m.def( + "get_elem_nocopy", + [](const Eigen::Ref &m) -> double { return get_elem(m); }, + py::arg{}.noconvert()); // Also test a row-major-only no-copy const ref: m.def("get_elem_rm_nocopy", [](Eigen::Ref> &m) -> long { return m(2, 1); }, - py::arg().noconvert()); + py::arg{}.noconvert()); // test_issue738 // Issue #738: 1xN or Nx1 2D matrices were neither accepted nor properly copied with an // incompatible stride value on the length-1 dimension--but that should be allowed (without // requiring a copy!) because the stride value can be safely ignored on a size-1 dimension. - m.def("iss738_f1", &adjust_matrix &>, py::arg().noconvert()); - m.def("iss738_f2", &adjust_matrix> &>, py::arg().noconvert()); + m.def("iss738_f1", &adjust_matrix &>, py::arg{}.noconvert()); + m.def("iss738_f2", &adjust_matrix> &>, py::arg{}.noconvert()); // test_issue1105 // Issue #1105: when converting from a numpy two-dimensional (Nx1) or (1xN) value into a dense - // eigen Vector or RowVector, the argument would fail to load because the numpy copy would fail: - // numpy won't broadcast a Nx1 into a 1-dimensional vector. - m.def("iss1105_col", [](Eigen::VectorXd) { return true; }); - m.def("iss1105_row", [](Eigen::RowVectorXd) { return true; }); + // eigen Vector or RowVector, the argument would fail to load because the numpy copy would + // fail: numpy won't broadcast a Nx1 into a 1-dimensional vector. + m.def("iss1105_col", [](const Eigen::VectorXd &) { return true; }); + m.def("iss1105_row", [](const Eigen::RowVectorXd &) { return true; }); // test_named_arguments // Make sure named arguments are working properly: - m.def("matrix_multiply", [](const py::EigenDRef A, const py::EigenDRef B) - -> Eigen::MatrixXd { - if (A.cols() != B.rows()) throw std::domain_error("Nonconformable matrices!"); - return A * B; - }, py::arg("A"), py::arg("B")); + m.def( + "matrix_multiply", + [](const py::EigenDRef &A, + const py::EigenDRef &B) -> Eigen::MatrixXd { + if (A.cols() != B.rows()) + throw std::domain_error("Nonconformable matrices!"); + return A * B; + }, + py::arg("A"), + py::arg("B")); // test_custom_operator_new py::class_(m, "CustomOperatorNew") @@ -316,12 +337,12 @@ TEST_SUBMODULE(eigen, m) { // In case of a failure (the caster's temp array does not live long enough), creating // a new array (np.ones(10)) increases the chances that the temp array will be garbage // collected and/or that its memory will be overridden with different values. - m.def("get_elem_direct", [](Eigen::Ref v) { - py::module::import("numpy").attr("ones")(10); + m.def("get_elem_direct", [](const Eigen::Ref &v) { + py::module_::import("numpy").attr("ones")(10); return v(5); }); m.def("get_elem_indirect", [](std::vector> v) { - py::module::import("numpy").attr("ones")(10); + py::module_::import("numpy").attr("ones")(10); return v[0](5); }); } diff --git a/pybind11/tests/test_eigen.py b/pybind11/tests/test_eigen.py index ac6847147..e53826cbb 100644 --- a/pybind11/tests/test_eigen.py +++ b/pybind11/tests/test_eigen.py @@ -1,16 +1,21 @@ # -*- coding: utf-8 -*- import pytest + from pybind11_tests import ConstructorStats np = pytest.importorskip("numpy") m = pytest.importorskip("pybind11_tests.eigen") -ref = np.array([[ 0., 3, 0, 0, 0, 11], - [22, 0, 0, 0, 17, 11], - [ 7, 5, 0, 1, 0, 11], - [ 0, 0, 0, 0, 0, 11], - [ 0, 0, 14, 0, 8, 11]]) +ref = np.array( + [ + [0.0, 3, 0, 0, 0, 11], + [22, 0, 0, 0, 17, 11], + [7, 5, 0, 1, 0, 11], + [0, 0, 0, 0, 0, 11], + [0, 0, 14, 0, 8, 11], + ] +) def assert_equal_ref(mat): @@ -40,28 +45,37 @@ def test_dense(): def test_partially_fixed(): - ref2 = np.array([[0., 1, 2, 3], [4, 5, 6, 7], [8, 9, 10, 11], [12, 13, 14, 15]]) + ref2 = np.array([[0.0, 1, 2, 3], [4, 5, 6, 7], [8, 9, 10, 11], [12, 13, 14, 15]]) np.testing.assert_array_equal(m.partial_copy_four_rm_r(ref2), ref2) np.testing.assert_array_equal(m.partial_copy_four_rm_c(ref2), ref2) np.testing.assert_array_equal(m.partial_copy_four_rm_r(ref2[:, 1]), ref2[:, [1]]) np.testing.assert_array_equal(m.partial_copy_four_rm_c(ref2[0, :]), ref2[[0], :]) - np.testing.assert_array_equal(m.partial_copy_four_rm_r(ref2[:, (0, 2)]), ref2[:, (0, 2)]) np.testing.assert_array_equal( - m.partial_copy_four_rm_c(ref2[(3, 1, 2), :]), ref2[(3, 1, 2), :]) + m.partial_copy_four_rm_r(ref2[:, (0, 2)]), ref2[:, (0, 2)] + ) + np.testing.assert_array_equal( + m.partial_copy_four_rm_c(ref2[(3, 1, 2), :]), ref2[(3, 1, 2), :] + ) np.testing.assert_array_equal(m.partial_copy_four_cm_r(ref2), ref2) np.testing.assert_array_equal(m.partial_copy_four_cm_c(ref2), ref2) np.testing.assert_array_equal(m.partial_copy_four_cm_r(ref2[:, 1]), ref2[:, [1]]) np.testing.assert_array_equal(m.partial_copy_four_cm_c(ref2[0, :]), ref2[[0], :]) - np.testing.assert_array_equal(m.partial_copy_four_cm_r(ref2[:, (0, 2)]), ref2[:, (0, 2)]) np.testing.assert_array_equal( - m.partial_copy_four_cm_c(ref2[(3, 1, 2), :]), ref2[(3, 1, 2), :]) + m.partial_copy_four_cm_r(ref2[:, (0, 2)]), ref2[:, (0, 2)] + ) + np.testing.assert_array_equal( + m.partial_copy_four_cm_c(ref2[(3, 1, 2), :]), ref2[(3, 1, 2), :] + ) # TypeError should be raise for a shape mismatch - functions = [m.partial_copy_four_rm_r, m.partial_copy_four_rm_c, - m.partial_copy_four_cm_r, m.partial_copy_four_cm_c] - matrix_with_wrong_shape = [[1, 2], - [3, 4]] + functions = [ + m.partial_copy_four_rm_r, + m.partial_copy_four_rm_c, + m.partial_copy_four_cm_r, + m.partial_copy_four_cm_c, + ] + matrix_with_wrong_shape = [[1, 2], [3, 4]] for f in functions: with pytest.raises(TypeError) as excinfo: f(matrix_with_wrong_shape) @@ -69,7 +83,7 @@ def test_partially_fixed(): def test_mutator_descriptors(): - zr = np.arange(30, dtype='float32').reshape(5, 6) # row-major + zr = np.arange(30, dtype="float32").reshape(5, 6) # row-major zc = zr.reshape(6, 5).transpose() # column-major m.fixed_mutator_r(zr) @@ -78,18 +92,21 @@ def test_mutator_descriptors(): m.fixed_mutator_a(zc) with pytest.raises(TypeError) as excinfo: m.fixed_mutator_r(zc) - assert ('(arg0: numpy.ndarray[numpy.float32[5, 6],' - ' flags.writeable, flags.c_contiguous]) -> None' - in str(excinfo.value)) + assert ( + "(arg0: numpy.ndarray[numpy.float32[5, 6]," + " flags.writeable, flags.c_contiguous]) -> None" in str(excinfo.value) + ) with pytest.raises(TypeError) as excinfo: m.fixed_mutator_c(zr) - assert ('(arg0: numpy.ndarray[numpy.float32[5, 6],' - ' flags.writeable, flags.f_contiguous]) -> None' - in str(excinfo.value)) + assert ( + "(arg0: numpy.ndarray[numpy.float32[5, 6]," + " flags.writeable, flags.f_contiguous]) -> None" in str(excinfo.value) + ) with pytest.raises(TypeError) as excinfo: - m.fixed_mutator_a(np.array([[1, 2], [3, 4]], dtype='float32')) - assert ('(arg0: numpy.ndarray[numpy.float32[5, 6], flags.writeable]) -> None' - in str(excinfo.value)) + m.fixed_mutator_a(np.array([[1, 2], [3, 4]], dtype="float32")) + assert "(arg0: numpy.ndarray[numpy.float32[5, 6], flags.writeable]) -> None" in str( + excinfo.value + ) zr.flags.writeable = False with pytest.raises(TypeError): m.fixed_mutator_r(zr) @@ -98,26 +115,26 @@ def test_mutator_descriptors(): def test_cpp_casting(): - assert m.cpp_copy(m.fixed_r()) == 22. - assert m.cpp_copy(m.fixed_c()) == 22. - z = np.array([[5., 6], [7, 8]]) - assert m.cpp_copy(z) == 7. - assert m.cpp_copy(m.get_cm_ref()) == 21. - assert m.cpp_copy(m.get_rm_ref()) == 21. - assert m.cpp_ref_c(m.get_cm_ref()) == 21. - assert m.cpp_ref_r(m.get_rm_ref()) == 21. + assert m.cpp_copy(m.fixed_r()) == 22.0 + assert m.cpp_copy(m.fixed_c()) == 22.0 + z = np.array([[5.0, 6], [7, 8]]) + assert m.cpp_copy(z) == 7.0 + assert m.cpp_copy(m.get_cm_ref()) == 21.0 + assert m.cpp_copy(m.get_rm_ref()) == 21.0 + assert m.cpp_ref_c(m.get_cm_ref()) == 21.0 + assert m.cpp_ref_r(m.get_rm_ref()) == 21.0 with pytest.raises(RuntimeError) as excinfo: # Can't reference m.fixed_c: it contains floats, m.cpp_ref_any wants doubles m.cpp_ref_any(m.fixed_c()) - assert 'Unable to cast Python instance' in str(excinfo.value) + assert "Unable to cast Python instance" in str(excinfo.value) with pytest.raises(RuntimeError) as excinfo: # Can't reference m.fixed_r: it contains floats, m.cpp_ref_any wants doubles m.cpp_ref_any(m.fixed_r()) - assert 'Unable to cast Python instance' in str(excinfo.value) - assert m.cpp_ref_any(m.ReturnTester.create()) == 1. + assert "Unable to cast Python instance" in str(excinfo.value) + assert m.cpp_ref_any(m.ReturnTester.create()) == 1.0 - assert m.cpp_ref_any(m.get_cm_ref()) == 21. - assert m.cpp_ref_any(m.get_cm_ref()) == 21. + assert m.cpp_ref_any(m.get_cm_ref()) == 21.0 + assert m.cpp_ref_any(m.get_cm_ref()) == 21.0 def test_pass_readonly_array(): @@ -149,7 +166,7 @@ def test_nonunit_stride_from_python(): # Mutator: m.double_threer(second_row) m.double_threec(second_col) - np.testing.assert_array_equal(counting_mat, [[0., 2, 2], [6, 16, 10], [6, 14, 8]]) + np.testing.assert_array_equal(counting_mat, [[0.0, 2, 2], [6, 16, 10], [6, 14, 8]]) def test_negative_stride_from_python(msg): @@ -178,26 +195,36 @@ def test_negative_stride_from_python(msg): # Mutator: with pytest.raises(TypeError) as excinfo: m.double_threer(second_row) - assert msg(excinfo.value) == """ + assert ( + msg(excinfo.value) + == """ double_threer(): incompatible function arguments. The following argument types are supported: 1. (arg0: numpy.ndarray[numpy.float32[1, 3], flags.writeable]) -> None - Invoked with: """ + repr(np.array([ 5., 4., 3.], dtype='float32')) # noqa: E501 line too long + Invoked with: """ # noqa: E501 line too long + + repr(np.array([5.0, 4.0, 3.0], dtype="float32")) + ) with pytest.raises(TypeError) as excinfo: m.double_threec(second_col) - assert msg(excinfo.value) == """ + assert ( + msg(excinfo.value) + == """ double_threec(): incompatible function arguments. The following argument types are supported: 1. (arg0: numpy.ndarray[numpy.float32[3, 1], flags.writeable]) -> None - Invoked with: """ + repr(np.array([ 7., 4., 1.], dtype='float32')) # noqa: E501 line too long + Invoked with: """ # noqa: E501 line too long + + repr(np.array([7.0, 4.0, 1.0], dtype="float32")) + ) def test_nonunit_stride_to_python(): assert np.all(m.diagonal(ref) == ref.diagonal()) assert np.all(m.diagonal_1(ref) == ref.diagonal(1)) for i in range(-5, 7): - assert np.all(m.diagonal_n(ref, i) == ref.diagonal(i)), "m.diagonal_n({})".format(i) + assert np.all( + m.diagonal_n(ref, i) == ref.diagonal(i) + ), "m.diagonal_n({})".format(i) assert np.all(m.block(ref, 2, 1, 3, 3) == ref[2:5, 1:4]) assert np.all(m.block(ref, 1, 4, 4, 2) == ref[1:, 4:]) @@ -207,8 +234,10 @@ def test_nonunit_stride_to_python(): def test_eigen_ref_to_python(): chols = [m.cholesky1, m.cholesky2, m.cholesky3, m.cholesky4] for i, chol in enumerate(chols, start=1): - mymat = chol(np.array([[1., 2, 4], [2, 13, 23], [4, 23, 77]])) - assert np.all(mymat == np.array([[1, 0, 0], [2, 3, 0], [4, 5, 6]])), "cholesky{}".format(i) + mymat = chol(np.array([[1.0, 2, 4], [2, 13, 23], [4, 23, 77]])) + assert np.all( + mymat == np.array([[1, 0, 0], [2, 3, 0], [4, 5, 6]]) + ), "cholesky{}".format(i) def assign_both(a1, a2, r, c, v): @@ -325,8 +354,12 @@ def test_eigen_return_references(): np.testing.assert_array_equal(a_block1, master[3:5, 3:5]) np.testing.assert_array_equal(a_block2, master[2:5, 2:4]) np.testing.assert_array_equal(a_block3, master[6:10, 7:10]) - np.testing.assert_array_equal(a_corn1, master[0::master.shape[0] - 1, 0::master.shape[1] - 1]) - np.testing.assert_array_equal(a_corn2, master[0::master.shape[0] - 1, 0::master.shape[1] - 1]) + np.testing.assert_array_equal( + a_corn1, master[0 :: master.shape[0] - 1, 0 :: master.shape[1] - 1] + ) + np.testing.assert_array_equal( + a_corn2, master[0 :: master.shape[0] - 1, 0 :: master.shape[1] - 1] + ) np.testing.assert_array_equal(a_copy1, c1want) np.testing.assert_array_equal(a_copy2, c2want) @@ -355,16 +388,28 @@ def test_eigen_keepalive(): cstats = ConstructorStats.get(m.ReturnTester) assert cstats.alive() == 1 unsafe = [a.ref(), a.ref_const(), a.block(1, 2, 3, 4)] - copies = [a.copy_get(), a.copy_view(), a.copy_ref(), a.copy_ref_const(), - a.copy_block(4, 3, 2, 1)] + copies = [ + a.copy_get(), + a.copy_view(), + a.copy_ref(), + a.copy_ref_const(), + a.copy_block(4, 3, 2, 1), + ] del a assert cstats.alive() == 0 del unsafe del copies - for meth in [m.ReturnTester.get, m.ReturnTester.get_ptr, m.ReturnTester.view, - m.ReturnTester.view_ptr, m.ReturnTester.ref_safe, m.ReturnTester.ref_const_safe, - m.ReturnTester.corners, m.ReturnTester.corners_const]: + for meth in [ + m.ReturnTester.get, + m.ReturnTester.get_ptr, + m.ReturnTester.view, + m.ReturnTester.view_ptr, + m.ReturnTester.ref_safe, + m.ReturnTester.ref_const_safe, + m.ReturnTester.corners, + m.ReturnTester.corners_const, + ]: assert_keeps_alive(m.ReturnTester, meth) for meth in [m.ReturnTester.block_safe, m.ReturnTester.block_const]: @@ -374,18 +419,18 @@ def test_eigen_keepalive(): def test_eigen_ref_mutators(): """Tests Eigen's ability to mutate numpy values""" - orig = np.array([[1., 2, 3], [4, 5, 6], [7, 8, 9]]) + orig = np.array([[1.0, 2, 3], [4, 5, 6], [7, 8, 9]]) zr = np.array(orig) - zc = np.array(orig, order='F') + zc = np.array(orig, order="F") m.add_rm(zr, 1, 0, 100) - assert np.all(zr == np.array([[1., 2, 3], [104, 5, 6], [7, 8, 9]])) + assert np.all(zr == np.array([[1.0, 2, 3], [104, 5, 6], [7, 8, 9]])) m.add_cm(zc, 1, 0, 200) - assert np.all(zc == np.array([[1., 2, 3], [204, 5, 6], [7, 8, 9]])) + assert np.all(zc == np.array([[1.0, 2, 3], [204, 5, 6], [7, 8, 9]])) m.add_any(zr, 1, 0, 20) - assert np.all(zr == np.array([[1., 2, 3], [124, 5, 6], [7, 8, 9]])) + assert np.all(zr == np.array([[1.0, 2, 3], [124, 5, 6], [7, 8, 9]])) m.add_any(zc, 1, 0, 10) - assert np.all(zc == np.array([[1., 2, 3], [214, 5, 6], [7, 8, 9]])) + assert np.all(zc == np.array([[1.0, 2, 3], [214, 5, 6], [7, 8, 9]])) # Can't reference a col-major array with a row-major Ref, and vice versa: with pytest.raises(TypeError): @@ -406,8 +451,8 @@ def test_eigen_ref_mutators(): cornersr = zr[0::2, 0::2] cornersc = zc[0::2, 0::2] - assert np.all(cornersr == np.array([[1., 3], [7, 9]])) - assert np.all(cornersc == np.array([[1., 3], [7, 9]])) + assert np.all(cornersr == np.array([[1.0, 3], [7, 9]])) + assert np.all(cornersc == np.array([[1.0, 3], [7, 9]])) with pytest.raises(TypeError): m.add_rm(cornersr, 0, 1, 25) @@ -419,8 +464,8 @@ def test_eigen_ref_mutators(): m.add_cm(cornersc, 0, 1, 25) m.add_any(cornersr, 0, 1, 25) m.add_any(cornersc, 0, 1, 44) - assert np.all(zr == np.array([[1., 2, 28], [4, 5, 6], [7, 8, 9]])) - assert np.all(zc == np.array([[1., 2, 47], [4, 5, 6], [7, 8, 9]])) + assert np.all(zr == np.array([[1.0, 2, 28], [4, 5, 6], [7, 8, 9]])) + assert np.all(zc == np.array([[1.0, 2, 47], [4, 5, 6], [7, 8, 9]])) # You shouldn't be allowed to pass a non-writeable array to a mutating Eigen method: zro = zr[0:4, 0:4] @@ -458,7 +503,7 @@ def test_numpy_ref_mutators(): assert not zrro.flags.owndata and not zrro.flags.writeable zc[1, 2] = 99 - expect = np.array([[11., 12, 13], [21, 22, 99], [31, 32, 33]]) + expect = np.array([[11.0, 12, 13], [21, 22, 99], [31, 32, 33]]) # We should have just changed zc, of course, but also zcro and the original eigen matrix assert np.all(zc == expect) assert np.all(zcro == expect) @@ -506,18 +551,20 @@ def test_both_ref_mutators(): assert np.all(z == z3) assert np.all(z == z4) assert np.all(z == z5) - expect = np.array([[0., 22, 20], [31, 37, 33], [41, 42, 38]]) + expect = np.array([[0.0, 22, 20], [31, 37, 33], [41, 42, 38]]) assert np.all(z == expect) - y = np.array(range(100), dtype='float64').reshape(10, 10) + y = np.array(range(100), dtype="float64").reshape(10, 10) y2 = m.incr_matrix_any(y, 10) # np -> eigen -> np - y3 = m.incr_matrix_any(y2[0::2, 0::2], -33) # np -> eigen -> np slice -> np -> eigen -> np + y3 = m.incr_matrix_any( + y2[0::2, 0::2], -33 + ) # np -> eigen -> np slice -> np -> eigen -> np y4 = m.even_rows(y3) # numpy -> eigen slice -> (... y3) y5 = m.even_cols(y4) # numpy -> eigen slice -> (... y4) y6 = m.incr_matrix_any(y5, 1000) # numpy -> eigen -> (... y5) # Apply same mutations using just numpy: - yexpect = np.array(range(100), dtype='float64').reshape(10, 10) + yexpect = np.array(range(100), dtype="float64").reshape(10, 10) yexpect += 10 yexpect[0::2, 0::2] -= 33 yexpect[0::4, 0::4] += 1000 @@ -532,10 +579,14 @@ def test_both_ref_mutators(): def test_nocopy_wrapper(): # get_elem requires a column-contiguous matrix reference, but should be # callable with other types of matrix (via copying): - int_matrix_colmajor = np.array([[1, 2, 3], [4, 5, 6], [7, 8, 9]], order='F') - dbl_matrix_colmajor = np.array(int_matrix_colmajor, dtype='double', order='F', copy=True) - int_matrix_rowmajor = np.array(int_matrix_colmajor, order='C', copy=True) - dbl_matrix_rowmajor = np.array(int_matrix_rowmajor, dtype='double', order='C', copy=True) + int_matrix_colmajor = np.array([[1, 2, 3], [4, 5, 6], [7, 8, 9]], order="F") + dbl_matrix_colmajor = np.array( + int_matrix_colmajor, dtype="double", order="F", copy=True + ) + int_matrix_rowmajor = np.array(int_matrix_colmajor, order="C", copy=True) + dbl_matrix_rowmajor = np.array( + int_matrix_rowmajor, dtype="double", order="C", copy=True + ) # All should be callable via get_elem: assert m.get_elem(int_matrix_colmajor) == 8 @@ -546,32 +597,38 @@ def test_nocopy_wrapper(): # All but the second should fail with m.get_elem_nocopy: with pytest.raises(TypeError) as excinfo: m.get_elem_nocopy(int_matrix_colmajor) - assert ('get_elem_nocopy(): incompatible function arguments.' in str(excinfo.value) and - ', flags.f_contiguous' in str(excinfo.value)) + assert "get_elem_nocopy(): incompatible function arguments." in str( + excinfo.value + ) and ", flags.f_contiguous" in str(excinfo.value) assert m.get_elem_nocopy(dbl_matrix_colmajor) == 8 with pytest.raises(TypeError) as excinfo: m.get_elem_nocopy(int_matrix_rowmajor) - assert ('get_elem_nocopy(): incompatible function arguments.' in str(excinfo.value) and - ', flags.f_contiguous' in str(excinfo.value)) + assert "get_elem_nocopy(): incompatible function arguments." in str( + excinfo.value + ) and ", flags.f_contiguous" in str(excinfo.value) with pytest.raises(TypeError) as excinfo: m.get_elem_nocopy(dbl_matrix_rowmajor) - assert ('get_elem_nocopy(): incompatible function arguments.' in str(excinfo.value) and - ', flags.f_contiguous' in str(excinfo.value)) + assert "get_elem_nocopy(): incompatible function arguments." in str( + excinfo.value + ) and ", flags.f_contiguous" in str(excinfo.value) # For the row-major test, we take a long matrix in row-major, so only the third is allowed: with pytest.raises(TypeError) as excinfo: m.get_elem_rm_nocopy(int_matrix_colmajor) - assert ('get_elem_rm_nocopy(): incompatible function arguments.' in str(excinfo.value) and - ', flags.c_contiguous' in str(excinfo.value)) + assert "get_elem_rm_nocopy(): incompatible function arguments." in str( + excinfo.value + ) and ", flags.c_contiguous" in str(excinfo.value) with pytest.raises(TypeError) as excinfo: m.get_elem_rm_nocopy(dbl_matrix_colmajor) - assert ('get_elem_rm_nocopy(): incompatible function arguments.' in str(excinfo.value) and - ', flags.c_contiguous' in str(excinfo.value)) + assert "get_elem_rm_nocopy(): incompatible function arguments." in str( + excinfo.value + ) and ", flags.c_contiguous" in str(excinfo.value) assert m.get_elem_rm_nocopy(int_matrix_rowmajor) == 8 with pytest.raises(TypeError) as excinfo: m.get_elem_rm_nocopy(dbl_matrix_rowmajor) - assert ('get_elem_rm_nocopy(): incompatible function arguments.' in str(excinfo.value) and - ', flags.c_contiguous' in str(excinfo.value)) + assert "get_elem_rm_nocopy(): incompatible function arguments." in str( + excinfo.value + ) and ", flags.c_contiguous" in str(excinfo.value) def test_eigen_ref_life_support(): @@ -589,12 +646,9 @@ def test_eigen_ref_life_support(): def test_special_matrix_objects(): - assert np.all(m.incr_diag(7) == np.diag([1., 2, 3, 4, 5, 6, 7])) + assert np.all(m.incr_diag(7) == np.diag([1.0, 2, 3, 4, 5, 6, 7])) - asymm = np.array([[ 1., 2, 3, 4], - [ 5, 6, 7, 8], - [ 9, 10, 11, 12], - [13, 14, 15, 16]]) + asymm = np.array([[1.0, 2, 3, 4], [5, 6, 7, 8], [9, 10, 11, 12], [13, 14, 15, 16]]) symm_lower = np.array(asymm) symm_upper = np.array(asymm) for i in range(4): @@ -607,41 +661,51 @@ def test_special_matrix_objects(): def test_dense_signature(doc): - assert doc(m.double_col) == """ + assert ( + doc(m.double_col) + == """ double_col(arg0: numpy.ndarray[numpy.float32[m, 1]]) -> numpy.ndarray[numpy.float32[m, 1]] """ - assert doc(m.double_row) == """ + ) + assert ( + doc(m.double_row) + == """ double_row(arg0: numpy.ndarray[numpy.float32[1, n]]) -> numpy.ndarray[numpy.float32[1, n]] """ - assert doc(m.double_complex) == (""" + ) + assert doc(m.double_complex) == ( + """ double_complex(arg0: numpy.ndarray[numpy.complex64[m, 1]])""" - """ -> numpy.ndarray[numpy.complex64[m, 1]] - """) - assert doc(m.double_mat_rm) == (""" + """ -> numpy.ndarray[numpy.complex64[m, 1]] + """ + ) + assert doc(m.double_mat_rm) == ( + """ double_mat_rm(arg0: numpy.ndarray[numpy.float32[m, n]])""" - """ -> numpy.ndarray[numpy.float32[m, n]] - """) + """ -> numpy.ndarray[numpy.float32[m, n]] + """ + ) def test_named_arguments(): a = np.array([[1.0, 2], [3, 4], [5, 6]]) b = np.ones((2, 1)) - assert np.all(m.matrix_multiply(a, b) == np.array([[3.], [7], [11]])) - assert np.all(m.matrix_multiply(A=a, B=b) == np.array([[3.], [7], [11]])) - assert np.all(m.matrix_multiply(B=b, A=a) == np.array([[3.], [7], [11]])) + assert np.all(m.matrix_multiply(a, b) == np.array([[3.0], [7], [11]])) + assert np.all(m.matrix_multiply(A=a, B=b) == np.array([[3.0], [7], [11]])) + assert np.all(m.matrix_multiply(B=b, A=a) == np.array([[3.0], [7], [11]])) with pytest.raises(ValueError) as excinfo: m.matrix_multiply(b, a) - assert str(excinfo.value) == 'Nonconformable matrices!' + assert str(excinfo.value) == "Nonconformable matrices!" with pytest.raises(ValueError) as excinfo: m.matrix_multiply(A=b, B=a) - assert str(excinfo.value) == 'Nonconformable matrices!' + assert str(excinfo.value) == "Nonconformable matrices!" with pytest.raises(ValueError) as excinfo: m.matrix_multiply(B=a, A=b) - assert str(excinfo.value) == 'Nonconformable matrices!' + assert str(excinfo.value) == "Nonconformable matrices!" def test_sparse(): @@ -656,21 +720,31 @@ def test_sparse(): def test_sparse_signature(doc): pytest.importorskip("scipy") - assert doc(m.sparse_copy_r) == """ + assert ( + doc(m.sparse_copy_r) + == """ sparse_copy_r(arg0: scipy.sparse.csr_matrix[numpy.float32]) -> scipy.sparse.csr_matrix[numpy.float32] """ # noqa: E501 line too long - assert doc(m.sparse_copy_c) == """ + ) + assert ( + doc(m.sparse_copy_c) + == """ sparse_copy_c(arg0: scipy.sparse.csc_matrix[numpy.float32]) -> scipy.sparse.csc_matrix[numpy.float32] """ # noqa: E501 line too long + ) def test_issue738(): """Ignore strides on a length-1 dimension (even if they would be incompatible length > 1)""" - assert np.all(m.iss738_f1(np.array([[1., 2, 3]])) == np.array([[1., 102, 203]])) - assert np.all(m.iss738_f1(np.array([[1.], [2], [3]])) == np.array([[1.], [12], [23]])) + assert np.all(m.iss738_f1(np.array([[1.0, 2, 3]])) == np.array([[1.0, 102, 203]])) + assert np.all( + m.iss738_f1(np.array([[1.0], [2], [3]])) == np.array([[1.0], [12], [23]]) + ) - assert np.all(m.iss738_f2(np.array([[1., 2, 3]])) == np.array([[1., 102, 203]])) - assert np.all(m.iss738_f2(np.array([[1.], [2], [3]])) == np.array([[1.], [12], [23]])) + assert np.all(m.iss738_f2(np.array([[1.0, 2, 3]])) == np.array([[1.0, 102, 203]])) + assert np.all( + m.iss738_f2(np.array([[1.0], [2], [3]])) == np.array([[1.0], [12], [23]]) + ) def test_issue1105(): diff --git a/pybind11/tests/test_embed/CMakeLists.txt b/pybind11/tests/test_embed/CMakeLists.txt index 2e298fa7e..edb8961a7 100644 --- a/pybind11/tests/test_embed/CMakeLists.txt +++ b/pybind11/tests/test_embed/CMakeLists.txt @@ -1,10 +1,13 @@ +possibly_uninitialized(PYTHON_MODULE_EXTENSION Python_INTERPRETER_ID) + if("${PYTHON_MODULE_EXTENSION}" MATCHES "pypy" OR "${Python_INTERPRETER_ID}" STREQUAL "PyPy") + message(STATUS "Skipping embed test on PyPy") add_custom_target(cpptest) # Dummy target on PyPy. Embedding is not supported. set(_suppress_unused_variable_warning "${DOWNLOAD_CATCH}") return() endif() -find_package(Catch 2.13.0) +find_package(Catch 2.13.2) if(CATCH_FOUND) message(STATUS "Building interpreter tests using Catch v${CATCH_VERSION}") @@ -22,12 +25,13 @@ pybind11_enable_warnings(test_embed) target_link_libraries(test_embed PRIVATE pybind11::embed Catch2::Catch2 Threads::Threads) if(NOT CMAKE_CURRENT_SOURCE_DIR STREQUAL CMAKE_CURRENT_BINARY_DIR) - file(COPY test_interpreter.py DESTINATION "${CMAKE_CURRENT_BINARY_DIR}") + file(COPY test_interpreter.py test_trampoline.py DESTINATION "${CMAKE_CURRENT_BINARY_DIR}") endif() add_custom_target( cpptest COMMAND "$" + DEPENDS test_embed WORKING_DIRECTORY "${CMAKE_CURRENT_BINARY_DIR}") pybind11_add_module(external_module THIN_LTO external_module.cpp) diff --git a/pybind11/tests/test_embed/external_module.cpp b/pybind11/tests/test_embed/external_module.cpp index e9a6058b1..490952299 100644 --- a/pybind11/tests/test_embed/external_module.cpp +++ b/pybind11/tests/test_embed/external_module.cpp @@ -9,7 +9,7 @@ namespace py = pybind11; PYBIND11_MODULE(external_module, m) { class A { public: - A(int value) : v{value} {}; + explicit A(int value) : v{value} {}; int v; }; diff --git a/pybind11/tests/test_embed/test_interpreter.cpp b/pybind11/tests/test_embed/test_interpreter.cpp index 753ce54dc..508975eb3 100644 --- a/pybind11/tests/test_embed/test_interpreter.cpp +++ b/pybind11/tests/test_embed/test_interpreter.cpp @@ -8,20 +8,23 @@ #include -#include +#include #include #include +#include +#include namespace py = pybind11; using namespace py::literals; class Widget { public: - Widget(std::string message) : message(message) { } + explicit Widget(std::string message) : message(std::move(message)) {} virtual ~Widget() = default; std::string the_message() const { return message; } virtual int the_answer() const = 0; + virtual std::string argv0() const = 0; private: std::string message; @@ -31,6 +34,23 @@ class PyWidget final : public Widget { using Widget::Widget; int the_answer() const override { PYBIND11_OVERRIDE_PURE(int, Widget, the_answer); } + std::string argv0() const override { PYBIND11_OVERRIDE_PURE(std::string, Widget, argv0); } +}; + +class test_override_cache_helper { + +public: + virtual int func() { return 0; } + + test_override_cache_helper() = default; + virtual ~test_override_cache_helper() = default; + // Non-copyable + test_override_cache_helper &operator=(test_override_cache_helper const &Right) = delete; + test_override_cache_helper(test_override_cache_helper const &Copy) = delete; +}; + +class test_override_cache_helper_trampoline : public test_override_cache_helper { + int func() override { PYBIND11_OVERRIDE(int, test_override_cache_helper, func); } }; PYBIND11_EMBEDDED_MODULE(widget_module, m) { @@ -41,6 +61,12 @@ PYBIND11_EMBEDDED_MODULE(widget_module, m) { m.def("add", [](int i, int j) { return i + j; }); } +PYBIND11_EMBEDDED_MODULE(trampoline_module, m) { + py::class_>(m, "test_override_cache_helper") + .def(py::init_alias<>()) + .def("func", &test_override_cache_helper::func); +} + PYBIND11_EMBEDDED_MODULE(throw_exception, ) { throw std::runtime_error("C++ Error"); } @@ -51,17 +77,17 @@ PYBIND11_EMBEDDED_MODULE(throw_error_already_set, ) { } TEST_CASE("Pass classes and data between modules defined in C++ and Python") { - auto module = py::module::import("test_interpreter"); - REQUIRE(py::hasattr(module, "DerivedWidget")); + auto module_ = py::module_::import("test_interpreter"); + REQUIRE(py::hasattr(module_, "DerivedWidget")); - auto locals = py::dict("hello"_a="Hello, World!", "x"_a=5, **module.attr("__dict__")); + auto locals = py::dict("hello"_a="Hello, World!", "x"_a=5, **module_.attr("__dict__")); py::exec(R"( widget = DerivedWidget("{} - {}".format(hello, x)) message = widget.the_message )", py::globals(), locals); REQUIRE(locals["message"].cast() == "Hello, World! - 5"); - auto py_widget = module.attr("DerivedWidget")("The question"); + auto py_widget = module_.attr("DerivedWidget")("The question"); auto message = py_widget.attr("the_message"); REQUIRE(message.cast() == "The question"); @@ -69,12 +95,55 @@ TEST_CASE("Pass classes and data between modules defined in C++ and Python") { REQUIRE(cpp_widget.the_answer() == 42); } +TEST_CASE("Override cache") { + auto module_ = py::module_::import("test_trampoline"); + REQUIRE(py::hasattr(module_, "func")); + REQUIRE(py::hasattr(module_, "func2")); + + auto locals = py::dict(**module_.attr("__dict__")); + + int i = 0; + for (; i < 1500; ++i) { + std::shared_ptr p_obj; + std::shared_ptr p_obj2; + + py::object loc_inst = locals["func"](); + p_obj = py::cast>(loc_inst); + + int ret = p_obj->func(); + + REQUIRE(ret == 42); + + loc_inst = locals["func2"](); + + p_obj2 = py::cast>(loc_inst); + + p_obj2->func(); + } +} + TEST_CASE("Import error handling") { - REQUIRE_NOTHROW(py::module::import("widget_module")); - REQUIRE_THROWS_WITH(py::module::import("throw_exception"), + REQUIRE_NOTHROW(py::module_::import("widget_module")); + REQUIRE_THROWS_WITH(py::module_::import("throw_exception"), "ImportError: C++ Error"); - REQUIRE_THROWS_WITH(py::module::import("throw_error_already_set"), +#if PY_VERSION_HEX >= 0x03030000 + REQUIRE_THROWS_WITH(py::module_::import("throw_error_already_set"), + Catch::Contains("ImportError: initialization failed")); + + auto locals = py::dict("is_keyerror"_a=false, "message"_a="not set"); + py::exec(R"( + try: + import throw_error_already_set + except ImportError as e: + is_keyerror = type(e.__cause__) == KeyError + message = str(e.__cause__) + )", py::globals(), locals); + REQUIRE(locals["is_keyerror"].cast() == true); + REQUIRE(locals["message"].cast() == "'missing'"); +#else + REQUIRE_THROWS_WITH(py::module_::import("throw_error_already_set"), Catch::Contains("ImportError: KeyError")); +#endif } TEST_CASE("There can be only one interpreter") { @@ -102,19 +171,19 @@ bool has_pybind11_internals_builtin() { bool has_pybind11_internals_static() { auto **&ipp = py::detail::get_internals_pp(); - return ipp && *ipp; + return (ipp != nullptr) && (*ipp != nullptr); } TEST_CASE("Restart the interpreter") { // Verify pre-restart state. - REQUIRE(py::module::import("widget_module").attr("add")(1, 2).cast() == 3); + REQUIRE(py::module_::import("widget_module").attr("add")(1, 2).cast() == 3); REQUIRE(has_pybind11_internals_builtin()); REQUIRE(has_pybind11_internals_static()); - REQUIRE(py::module::import("external_module").attr("A")(123).attr("value").cast() == 123); + REQUIRE(py::module_::import("external_module").attr("A")(123).attr("value").cast() == 123); // local and foreign module internals should point to the same internals: REQUIRE(reinterpret_cast(*py::detail::get_internals_pp()) == - py::module::import("external_module").attr("internals_at")().cast()); + py::module_::import("external_module").attr("internals_at")().cast()); // Restart the interpreter. py::finalize_interpreter(); @@ -130,14 +199,14 @@ TEST_CASE("Restart the interpreter") { REQUIRE(has_pybind11_internals_builtin()); REQUIRE(has_pybind11_internals_static()); REQUIRE(reinterpret_cast(*py::detail::get_internals_pp()) == - py::module::import("external_module").attr("internals_at")().cast()); + py::module_::import("external_module").attr("internals_at")().cast()); // Make sure that an interpreter with no get_internals() created until finalize still gets the // internals destroyed py::finalize_interpreter(); py::initialize_interpreter(); bool ran = false; - py::module::import("__main__").attr("internals_destroy_test") = + py::module_::import("__main__").attr("internals_destroy_test") = py::capsule(&ran, [](void *ran) { py::detail::get_internals(); *static_cast(ran) = true; }); REQUIRE_FALSE(has_pybind11_internals_builtin()); REQUIRE_FALSE(has_pybind11_internals_static()); @@ -149,20 +218,20 @@ TEST_CASE("Restart the interpreter") { REQUIRE_FALSE(has_pybind11_internals_static()); // C++ modules can be reloaded. - auto cpp_module = py::module::import("widget_module"); + auto cpp_module = py::module_::import("widget_module"); REQUIRE(cpp_module.attr("add")(1, 2).cast() == 3); // C++ type information is reloaded and can be used in python modules. - auto py_module = py::module::import("test_interpreter"); + auto py_module = py::module_::import("test_interpreter"); auto py_widget = py_module.attr("DerivedWidget")("Hello after restart"); REQUIRE(py_widget.attr("the_message").cast() == "Hello after restart"); } TEST_CASE("Subinterpreter") { // Add tags to the modules in the main interpreter and test the basics. - py::module::import("__main__").attr("main_tag") = "main interpreter"; + py::module_::import("__main__").attr("main_tag") = "main interpreter"; { - auto m = py::module::import("widget_module"); + auto m = py::module_::import("widget_module"); m.attr("extension_module_tag") = "added to module in main interpreter"; REQUIRE(m.attr("add")(1, 2).cast() == 3); @@ -181,9 +250,9 @@ TEST_CASE("Subinterpreter") { REQUIRE(has_pybind11_internals_static()); // Modules tags should be gone. - REQUIRE_FALSE(py::hasattr(py::module::import("__main__"), "tag")); + REQUIRE_FALSE(py::hasattr(py::module_::import("__main__"), "tag")); { - auto m = py::module::import("widget_module"); + auto m = py::module_::import("widget_module"); REQUIRE_FALSE(py::hasattr(m, "extension_module_tag")); // Function bindings should still work. @@ -194,8 +263,8 @@ TEST_CASE("Subinterpreter") { Py_EndInterpreter(sub_tstate); PyThreadState_Swap(main_tstate); - REQUIRE(py::hasattr(py::module::import("__main__"), "main_tag")); - REQUIRE(py::hasattr(py::module::import("widget_module"), "extension_module_tag")); + REQUIRE(py::hasattr(py::module_::import("__main__"), "main_tag")); + REQUIRE(py::hasattr(py::module_::import("widget_module"), "extension_module_tag")); } TEST_CASE("Execution frame") { @@ -245,7 +314,7 @@ TEST_CASE("Reload module from file") { // Disable generation of cached bytecode (.pyc files) for this test, otherwise // Python might pick up an old version from the cache instead of the new versions // of the .py files generated below - auto sys = py::module::import("sys"); + auto sys = py::module_::import("sys"); bool dont_write_bytecode = sys.attr("dont_write_bytecode").cast(); sys.attr("dont_write_bytecode") = true; // Reset the value at scope exit @@ -267,8 +336,8 @@ TEST_CASE("Reload module from file") { }); // Import the module from file - auto module = py::module::import(module_name.c_str()); - int result = module.attr("test")().cast(); + auto module_ = py::module_::import(module_name.c_str()); + int result = module_.attr("test")().cast(); REQUIRE(result == 1); // Update the module .py file with a small change @@ -278,7 +347,29 @@ TEST_CASE("Reload module from file") { test_module.close(); // Reload the module - module.reload(); - result = module.attr("test")().cast(); + module_.reload(); + result = module_.attr("test")().cast(); REQUIRE(result == 2); } + +TEST_CASE("sys.argv gets initialized properly") { + py::finalize_interpreter(); + { + py::scoped_interpreter default_scope; + auto module = py::module::import("test_interpreter"); + auto py_widget = module.attr("DerivedWidget")("The question"); + const auto &cpp_widget = py_widget.cast(); + REQUIRE(cpp_widget.argv0().empty()); + } + + { + char *argv[] = {strdup("a.out")}; + py::scoped_interpreter argv_scope(true, 1, argv); + std::free(argv[0]); + auto module = py::module::import("test_interpreter"); + auto py_widget = module.attr("DerivedWidget")("The question"); + const auto &cpp_widget = py_widget.cast(); + REQUIRE(cpp_widget.argv0() == "a.out"); + } + py::initialize_interpreter(); +} diff --git a/pybind11/tests/test_embed/test_interpreter.py b/pybind11/tests/test_embed/test_interpreter.py index 6174ede44..5ab55a4b3 100644 --- a/pybind11/tests/test_embed/test_interpreter.py +++ b/pybind11/tests/test_embed/test_interpreter.py @@ -1,4 +1,6 @@ # -*- coding: utf-8 -*- +import sys + from widget_module import Widget @@ -8,3 +10,6 @@ class DerivedWidget(Widget): def the_answer(self): return 42 + + def argv0(self): + return sys.argv[0] diff --git a/pybind11/tests/test_embed/test_trampoline.py b/pybind11/tests/test_embed/test_trampoline.py new file mode 100644 index 000000000..87c8fa44c --- /dev/null +++ b/pybind11/tests/test_embed/test_trampoline.py @@ -0,0 +1,18 @@ +# -*- coding: utf-8 -*- + +import trampoline_module + + +def func(): + class Test(trampoline_module.test_override_cache_helper): + def func(self): + return 42 + + return Test() + + +def func2(): + class Test(trampoline_module.test_override_cache_helper): + pass + + return Test() diff --git a/pybind11/tests/test_enum.cpp b/pybind11/tests/test_enum.cpp index 315308920..40c48d412 100644 --- a/pybind11/tests/test_enum.cpp +++ b/pybind11/tests/test_enum.cpp @@ -84,4 +84,65 @@ TEST_SUBMODULE(enums, m) { .value("ONE", SimpleEnum::THREE) .export_values(); }); + + // test_enum_scalar + enum UnscopedUCharEnum : unsigned char {}; + enum class ScopedShortEnum : short {}; + enum class ScopedLongEnum : long {}; + enum UnscopedUInt64Enum : std::uint64_t {}; + static_assert(py::detail::all_of< + std::is_same::Scalar, unsigned char>, + std::is_same::Scalar, short>, + std::is_same::Scalar, long>, + std::is_same::Scalar, std::uint64_t> + >::value, "Error during the deduction of enum's scalar type with normal integer underlying"); + + // test_enum_scalar_with_char_underlying + enum class ScopedCharEnum : char { Zero, Positive }; + enum class ScopedWCharEnum : wchar_t { Zero, Positive }; + enum class ScopedChar32Enum : char32_t { Zero, Positive }; + enum class ScopedChar16Enum : char16_t { Zero, Positive }; + + // test the scalar of char type enums according to chapter 'Character types' + // from https://en.cppreference.com/w/cpp/language/types + static_assert(py::detail::any_of< + std::is_same::Scalar, signed char>, // e.g. gcc on x86 + std::is_same::Scalar, unsigned char> // e.g. arm linux + >::value, "char should be cast to either signed char or unsigned char"); + static_assert( + sizeof(py::enum_::Scalar) == 2 || + sizeof(py::enum_::Scalar) == 4 + , "wchar_t should be either 16 bits (Windows) or 32 (everywhere else)"); + static_assert(py::detail::all_of< + std::is_same::Scalar, std::uint_least32_t>, + std::is_same::Scalar, std::uint_least16_t> + >::value, "char32_t, char16_t (and char8_t)'s size, signedness, and alignment is determined"); +#if defined(PYBIND11_HAS_U8STRING) + enum class ScopedChar8Enum : char8_t { Zero, Positive }; + static_assert(std::is_same::Scalar, unsigned char>::value); +#endif + + // test_char_underlying_enum + py::enum_(m, "ScopedCharEnum") + .value("Zero", ScopedCharEnum::Zero) + .value("Positive", ScopedCharEnum::Positive); + py::enum_(m, "ScopedWCharEnum") + .value("Zero", ScopedWCharEnum::Zero) + .value("Positive", ScopedWCharEnum::Positive); + py::enum_(m, "ScopedChar32Enum") + .value("Zero", ScopedChar32Enum::Zero) + .value("Positive", ScopedChar32Enum::Positive); + py::enum_(m, "ScopedChar16Enum") + .value("Zero", ScopedChar16Enum::Zero) + .value("Positive", ScopedChar16Enum::Positive); + + // test_bool_underlying_enum + enum class ScopedBoolEnum : bool { FALSE, TRUE }; + + // bool is unsigned (std::is_signed returns false) and 1-byte long, so represented with u8 + static_assert(std::is_same::Scalar, std::uint8_t>::value, ""); + + py::enum_(m, "ScopedBoolEnum") + .value("FALSE", ScopedBoolEnum::FALSE) + .value("TRUE", ScopedBoolEnum::TRUE); } diff --git a/pybind11/tests/test_enum.py b/pybind11/tests/test_enum.py index bfaa193e9..14c754e72 100644 --- a/pybind11/tests/test_enum.py +++ b/pybind11/tests/test_enum.py @@ -1,5 +1,7 @@ # -*- coding: utf-8 -*- import pytest + +import env from pybind11_tests import enums as m @@ -7,32 +9,50 @@ def test_unscoped_enum(): assert str(m.UnscopedEnum.EOne) == "UnscopedEnum.EOne" assert str(m.UnscopedEnum.ETwo) == "UnscopedEnum.ETwo" assert str(m.EOne) == "UnscopedEnum.EOne" + assert repr(m.UnscopedEnum.EOne) == "" + assert repr(m.UnscopedEnum.ETwo) == "" + assert repr(m.EOne) == "" # name property assert m.UnscopedEnum.EOne.name == "EOne" + assert m.UnscopedEnum.EOne.value == 1 assert m.UnscopedEnum.ETwo.name == "ETwo" - assert m.EOne.name == "EOne" - # name readonly + assert m.UnscopedEnum.ETwo.value == 2 + assert m.EOne is m.UnscopedEnum.EOne + # name, value readonly with pytest.raises(AttributeError): m.UnscopedEnum.EOne.name = "" - # name returns a copy - foo = m.UnscopedEnum.EOne.name - foo = "bar" + with pytest.raises(AttributeError): + m.UnscopedEnum.EOne.value = 10 + # name, value returns a copy + # TODO: Neither the name nor value tests actually check against aliasing. + # Use a mutable type that has reference semantics. + nonaliased_name = m.UnscopedEnum.EOne.name + nonaliased_name = "bar" # noqa: F841 assert m.UnscopedEnum.EOne.name == "EOne" + nonaliased_value = m.UnscopedEnum.EOne.value + nonaliased_value = 10 # noqa: F841 + assert m.UnscopedEnum.EOne.value == 1 # __members__ property - assert m.UnscopedEnum.__members__ == \ - {"EOne": m.UnscopedEnum.EOne, "ETwo": m.UnscopedEnum.ETwo, "EThree": m.UnscopedEnum.EThree} + assert m.UnscopedEnum.__members__ == { + "EOne": m.UnscopedEnum.EOne, + "ETwo": m.UnscopedEnum.ETwo, + "EThree": m.UnscopedEnum.EThree, + } # __members__ readonly with pytest.raises(AttributeError): m.UnscopedEnum.__members__ = {} # __members__ returns a copy - foo = m.UnscopedEnum.__members__ - foo["bar"] = "baz" - assert m.UnscopedEnum.__members__ == \ - {"EOne": m.UnscopedEnum.EOne, "ETwo": m.UnscopedEnum.ETwo, "EThree": m.UnscopedEnum.EThree} + nonaliased_members = m.UnscopedEnum.__members__ + nonaliased_members["bar"] = "baz" + assert m.UnscopedEnum.__members__ == { + "EOne": m.UnscopedEnum.EOne, + "ETwo": m.UnscopedEnum.ETwo, + "EThree": m.UnscopedEnum.EThree, + } - for docstring_line in '''An unscoped enumeration + for docstring_line in """An unscoped enumeration Members: @@ -40,7 +60,9 @@ Members: ETwo : Docstring for ETwo - EThree : Docstring for EThree'''.split('\n'): + EThree : Docstring for EThree""".split( + "\n" + ): assert docstring_line in m.UnscopedEnum.__doc__ # Unscoped enums will accept ==/!= int comparisons @@ -50,10 +72,10 @@ Members: assert y != 3 assert 3 != y # Compare with None - assert (y != None) # noqa: E711 + assert y != None # noqa: E711 assert not (y == None) # noqa: E711 # Compare with an object - assert (y != object()) + assert y != object() assert not (y == object()) # Compare with string assert y != "2" @@ -62,16 +84,16 @@ Members: assert not (y == "2") with pytest.raises(TypeError): - y < object() + y < object() # noqa: B015 with pytest.raises(TypeError): - y <= object() + y <= object() # noqa: B015 with pytest.raises(TypeError): - y > object() + y > object() # noqa: B015 with pytest.raises(TypeError): - y >= object() + y >= object() # noqa: B015 with pytest.raises(TypeError): y | object() @@ -116,20 +138,20 @@ def test_scoped_enum(): assert z != 3 assert 3 != z # Compare with None - assert (z != None) # noqa: E711 + assert z != None # noqa: E711 assert not (z == None) # noqa: E711 # Compare with an object - assert (z != object()) + assert z != object() assert not (z == object()) # Scoped enums will *NOT* accept >, <, >= and <= int comparisons (Will throw exceptions) with pytest.raises(TypeError): - z > 3 + z > 3 # noqa: B015 with pytest.raises(TypeError): - z < 3 + z < 3 # noqa: B015 with pytest.raises(TypeError): - z >= 3 + z >= 3 # noqa: B015 with pytest.raises(TypeError): - z <= 3 + z <= 3 # noqa: B015 # order assert m.ScopedEnum.Two < m.ScopedEnum.Three @@ -143,6 +165,8 @@ def test_scoped_enum(): def test_implicit_conversion(): assert str(m.ClassWithUnscopedEnum.EMode.EFirstMode) == "EMode.EFirstMode" assert str(m.ClassWithUnscopedEnum.EFirstMode) == "EMode.EFirstMode" + assert repr(m.ClassWithUnscopedEnum.EMode.EFirstMode) == "" + assert repr(m.ClassWithUnscopedEnum.EFirstMode) == "" f = m.ClassWithUnscopedEnum.test_function first = m.ClassWithUnscopedEnum.EFirstMode @@ -167,7 +191,7 @@ def test_implicit_conversion(): x[f(first)] = 3 x[f(second)] = 4 # Hashing test - assert str(x) == "{EMode.EFirstMode: 3, EMode.ESecondMode: 4}" + assert repr(x) == "{: 3, : 4}" def test_binary_operators(): @@ -195,13 +219,54 @@ def test_binary_operators(): def test_enum_to_int(): m.test_enum_to_int(m.Flags.Read) m.test_enum_to_int(m.ClassWithUnscopedEnum.EMode.EFirstMode) + m.test_enum_to_int(m.ScopedCharEnum.Positive) + m.test_enum_to_int(m.ScopedBoolEnum.TRUE) m.test_enum_to_uint(m.Flags.Read) m.test_enum_to_uint(m.ClassWithUnscopedEnum.EMode.EFirstMode) + m.test_enum_to_uint(m.ScopedCharEnum.Positive) + m.test_enum_to_uint(m.ScopedBoolEnum.TRUE) m.test_enum_to_long_long(m.Flags.Read) m.test_enum_to_long_long(m.ClassWithUnscopedEnum.EMode.EFirstMode) + m.test_enum_to_long_long(m.ScopedCharEnum.Positive) + m.test_enum_to_long_long(m.ScopedBoolEnum.TRUE) def test_duplicate_enum_name(): with pytest.raises(ValueError) as excinfo: m.register_bad_enum() assert str(excinfo.value) == 'SimpleEnum: element "ONE" already exists!' + + +def test_char_underlying_enum(): # Issue #1331/PR #1334: + assert type(m.ScopedCharEnum.Positive.__int__()) is int + assert int(m.ScopedChar16Enum.Zero) == 0 + assert hash(m.ScopedChar32Enum.Positive) == 1 + if env.PY2: + assert m.ScopedCharEnum.Positive.__getstate__() == 1 # long + else: + assert type(m.ScopedCharEnum.Positive.__getstate__()) is int + assert m.ScopedWCharEnum(1) == m.ScopedWCharEnum.Positive + with pytest.raises(TypeError): + # Even if the underlying type is char, only an int can be used to construct the enum: + m.ScopedCharEnum("0") + + +def test_bool_underlying_enum(): + assert type(m.ScopedBoolEnum.TRUE.__int__()) is int + assert int(m.ScopedBoolEnum.FALSE) == 0 + assert hash(m.ScopedBoolEnum.TRUE) == 1 + if env.PY2: + assert m.ScopedBoolEnum.TRUE.__getstate__() == 1 # long + else: + assert type(m.ScopedBoolEnum.TRUE.__getstate__()) is int + assert m.ScopedBoolEnum(1) == m.ScopedBoolEnum.TRUE + # Enum could construct with a bool + # (bool is a strict subclass of int, and False will be converted to 0) + assert m.ScopedBoolEnum(False) == m.ScopedBoolEnum.FALSE + + +def test_docstring_signatures(): + for enum_type in [m.ScopedEnum, m.UnscopedEnum]: + for attr in enum_type.__dict__.values(): + # Issue #2623/PR #2637: Add argument names to enum_ methods + assert "arg0" not in (attr.__doc__ or "") diff --git a/pybind11/tests/test_eval.cpp b/pybind11/tests/test_eval.cpp index e09482191..29366f679 100644 --- a/pybind11/tests/test_eval.cpp +++ b/pybind11/tests/test_eval.cpp @@ -9,12 +9,14 @@ #include + #include "pybind11_tests.h" +#include TEST_SUBMODULE(eval_, m) { // test_evals - auto global = py::dict(py::module::import("__main__").attr("__dict__")); + auto global = py::dict(py::module_::import("__main__").attr("__dict__")); m.def("test_eval_statements", [global]() { auto local = py::dict(); @@ -64,10 +66,10 @@ TEST_SUBMODULE(eval_, m) { auto local = py::dict(); local["y"] = py::int_(43); - int val_out; + int val_out = 0; local["call_test2"] = py::cpp_function([&](int value) { val_out = value; }); - auto result = py::eval_file(filename, global, local); + auto result = py::eval_file(std::move(filename), global, local); return val_out == 43 && result.is_none(); }); @@ -88,4 +90,30 @@ TEST_SUBMODULE(eval_, m) { } return false; }); + + // test_eval_empty_globals + m.def("eval_empty_globals", [](py::object global) { + if (global.is_none()) + global = py::dict(); + auto int_class = py::eval("isinstance(42, int)", global); + return global; + }); + + // test_eval_closure + m.def("test_eval_closure", []() { + py::dict global; + global["closure_value"] = 42; + py::dict local; + local["closure_value"] = 0; + py::exec(R"( + local_value = closure_value + + def func_global(): + return closure_value + + def func_local(): + return local_value + )", global, local); + return std::make_pair(global, local); + }); } diff --git a/pybind11/tests/test_eval.py b/pybind11/tests/test_eval.py index b6f9d1881..1bbd991bc 100644 --- a/pybind11/tests/test_eval.py +++ b/pybind11/tests/test_eval.py @@ -4,7 +4,6 @@ import os import pytest import env # noqa: F401 - from pybind11_tests import eval_ as m @@ -25,3 +24,28 @@ def test_eval_file(): assert m.test_eval_file(filename) assert m.test_eval_file_failure() + + +def test_eval_empty_globals(): + assert "__builtins__" in m.eval_empty_globals(None) + + g = {} + assert "__builtins__" in m.eval_empty_globals(g) + assert "__builtins__" in g + + +def test_eval_closure(): + global_, local = m.test_eval_closure() + + assert global_["closure_value"] == 42 + assert local["closure_value"] == 0 + + assert "local_value" not in global_ + assert local["local_value"] == 0 + + assert "func_global" not in global_ + assert local["func_global"]() == 42 + + assert "func_local" not in global_ + with pytest.raises(NameError): + local["func_local"]() diff --git a/pybind11/tests/test_eval_call.py b/pybind11/tests/test_eval_call.py index d42a0a6d3..373b67bac 100644 --- a/pybind11/tests/test_eval_call.py +++ b/pybind11/tests/test_eval_call.py @@ -1,5 +1,5 @@ # -*- coding: utf-8 -*- # This file is called from 'test_eval.py' -if 'call_test2' in locals(): +if "call_test2" in locals(): call_test2(y) # noqa: F821 undefined name diff --git a/pybind11/tests/test_exceptions.cpp b/pybind11/tests/test_exceptions.cpp index 6187f2efb..3aa967382 100644 --- a/pybind11/tests/test_exceptions.cpp +++ b/pybind11/tests/test_exceptions.cpp @@ -6,8 +6,14 @@ All rights reserved. Use of this source code is governed by a BSD-style license that can be found in the LICENSE file. */ +#include "test_exceptions.h" + +#include "local_bindings.h" #include "pybind11_tests.h" +#include +#include +#include // A type that should be raised as an exception in Python class MyException : public std::exception { @@ -32,6 +38,13 @@ class MyException3 { public: explicit MyException3(const char * m) : message{m} {} virtual const char * what() const noexcept {return message.c_str();} + // Rule of 5 BEGIN: to preempt compiler warnings. + MyException3(const MyException3&) = default; + MyException3(MyException3&&) = default; + MyException3& operator=(const MyException3&) = default; + MyException3& operator=(MyException3&&) = default; + virtual ~MyException3() = default; + // Rule of 5 END. private: std::string message = ""; }; @@ -58,8 +71,19 @@ class MyException5_1 : public MyException5 { using MyException5::MyException5; }; + +// Exception that will be caught via the module local translator. +class MyException6 : public std::exception { +public: + explicit MyException6(const char * m) : message{m} {} + const char * what() const noexcept override {return message.c_str();} +private: + std::string message = ""; +}; + + struct PythonCallInDestructor { - PythonCallInDestructor(const py::dict &d) : d(d) {} + explicit PythonCallInDestructor(const py::dict &d) : d(d) {} ~PythonCallInDestructor() { d["good"] = true; } py::dict d; @@ -68,7 +92,7 @@ struct PythonCallInDestructor { struct PythonAlreadySetInDestructor { - PythonAlreadySetInDestructor(const py::str &s) : s(s) {} + explicit PythonAlreadySetInDestructor(const py::str &s) : s(s) {} ~PythonAlreadySetInDestructor() { py::dict foo; try { @@ -83,7 +107,6 @@ struct PythonAlreadySetInDestructor { py::str s; }; - TEST_SUBMODULE(exceptions, m) { m.def("throw_std_exception", []() { throw std::runtime_error("This exception was intentionally thrown."); @@ -128,14 +151,29 @@ TEST_SUBMODULE(exceptions, m) { // A slightly more complicated one that declares MyException5_1 as a subclass of MyException5 py::register_exception(m, "MyException5_1", ex5.ptr()); + //py::register_local_exception(m, "LocalSimpleException") + + py::register_local_exception_translator([](std::exception_ptr p) { + try { + if (p) { + std::rethrow_exception(p); + } + } catch (const MyException6 &e) { + PyErr_SetString(PyExc_RuntimeError, e.what()); + } + }); + m.def("throws1", []() { throw MyException("this error should go to a custom type"); }); m.def("throws2", []() { throw MyException2("this error should go to a standard Python exception"); }); m.def("throws3", []() { throw MyException3("this error cannot be translated"); }); m.def("throws4", []() { throw MyException4("this error is rethrown"); }); m.def("throws5", []() { throw MyException5("this is a helper-defined translated exception"); }); m.def("throws5_1", []() { throw MyException5_1("MyException5 subclass"); }); + m.def("throws6", []() { throw MyException6("MyException6 only handled in this module"); }); m.def("throws_logic_error", []() { throw std::logic_error("this error should fall through to the standard handler"); }); - m.def("throws_overflow_error", []() {throw std::overflow_error(""); }); + m.def("throws_overflow_error", []() { throw std::overflow_error(""); }); + m.def("throws_local_error", []() { throw LocalException("never caught"); }); + m.def("throws_local_simple_error", []() { throw LocalSimpleException("this mod"); }); m.def("exception_matches", []() { py::dict foo; try { @@ -163,7 +201,7 @@ TEST_SUBMODULE(exceptions, m) { m.def("modulenotfound_exception_matches_base", []() { try { // On Python >= 3.6, this raises a ModuleNotFoundError, a subclass of ImportError - py::module::import("nonexistent"); + py::module_::import("nonexistent"); } catch (py::error_already_set &ex) { if (!ex.matches(PyExc_ImportError)) throw; @@ -191,34 +229,65 @@ TEST_SUBMODULE(exceptions, m) { throw py::error_already_set(); }); - m.def("python_call_in_destructor", [](py::dict d) { + m.def("python_call_in_destructor", [](const py::dict &d) { + bool retval = false; try { PythonCallInDestructor set_dict_in_destructor(d); PyErr_SetString(PyExc_ValueError, "foo"); throw py::error_already_set(); } catch (const py::error_already_set&) { - return true; + retval = true; } - return false; + return retval; }); - m.def("python_alreadyset_in_destructor", [](py::str s) { + m.def("python_alreadyset_in_destructor", [](const py::str &s) { PythonAlreadySetInDestructor alreadyset_in_destructor(s); return true; }); // test_nested_throws - m.def("try_catch", [m](py::object exc_type, py::function f, py::args args) { - try { f(*args); } - catch (py::error_already_set &ex) { - if (ex.matches(exc_type)) - py::print(ex.what()); - else - throw; - } - }); + m.def("try_catch", + [m](const py::object &exc_type, const py::function &f, const py::args &args) { + try { + f(*args); + } catch (py::error_already_set &ex) { + if (ex.matches(exc_type)) + py::print(ex.what()); + else + throw; + } + }); // Test repr that cannot be displayed m.def("simple_bool_passthrough", [](bool x) {return x;}); + m.def("throw_should_be_translated_to_key_error", []() { throw shared_exception(); }); + +#if PY_VERSION_HEX >= 0x03030000 + + m.def("raise_from", []() { + PyErr_SetString(PyExc_ValueError, "inner"); + py::raise_from(PyExc_ValueError, "outer"); + throw py::error_already_set(); + }); + + m.def("raise_from_already_set", []() { + try { + PyErr_SetString(PyExc_ValueError, "inner"); + throw py::error_already_set(); + } catch (py::error_already_set& e) { + py::raise_from(e, PyExc_ValueError, "outer"); + throw py::error_already_set(); + } + }); + + m.def("throw_nested_exception", []() { + try { + throw std::runtime_error("Inner Exception"); + } catch (const std::runtime_error &) { + std::throw_with_nested(std::runtime_error("Outer Exception")); + } + }); +#endif } diff --git a/pybind11/tests/test_exceptions.h b/pybind11/tests/test_exceptions.h new file mode 100644 index 000000000..9d428312e --- /dev/null +++ b/pybind11/tests/test_exceptions.h @@ -0,0 +1,12 @@ +#pragma once +#include "pybind11_tests.h" +#include + +// shared exceptions for cross_module_tests + +class PYBIND11_EXPORT_EXCEPTION shared_exception : public pybind11::builtin_exception { +public: + using builtin_exception::builtin_exception; + explicit shared_exception() : shared_exception("") {} + void set_error() const override { PyErr_SetString(PyExc_RuntimeError, what()); } +}; diff --git a/pybind11/tests/test_exceptions.py b/pybind11/tests/test_exceptions.py index 7d7088d00..d698b1312 100644 --- a/pybind11/tests/test_exceptions.py +++ b/pybind11/tests/test_exceptions.py @@ -3,8 +3,9 @@ import sys import pytest -from pybind11_tests import exceptions as m +import env import pybind11_cross_module_tests as cm +from pybind11_tests import exceptions as m def test_std_exception(msg): @@ -23,7 +24,23 @@ def test_error_already_set(msg): assert msg(excinfo.value) == "foo" -def test_cross_module_exceptions(): +@pytest.mark.skipif("env.PY2") +def test_raise_from(msg): + with pytest.raises(ValueError) as excinfo: + m.raise_from() + assert msg(excinfo.value) == "outer" + assert msg(excinfo.value.__cause__) == "inner" + + +@pytest.mark.skipif("env.PY2") +def test_raise_from_already_set(msg): + with pytest.raises(ValueError) as excinfo: + m.raise_from_already_set() + assert msg(excinfo.value) == "outer" + assert msg(excinfo.value.__cause__) == "inner" + + +def test_cross_module_exceptions(msg): with pytest.raises(RuntimeError) as excinfo: cm.raise_runtime_error() assert str(excinfo.value) == "My runtime error" @@ -43,6 +60,27 @@ def test_cross_module_exceptions(): with pytest.raises(StopIteration) as excinfo: cm.throw_stop_iteration() + with pytest.raises(cm.LocalSimpleException) as excinfo: + cm.throw_local_simple_error() + assert msg(excinfo.value) == "external mod" + + with pytest.raises(KeyError) as excinfo: + cm.throw_local_error() + # KeyError is a repr of the key, so it has an extra set of quotes + assert str(excinfo.value) == "'just local'" + + +# TODO: FIXME +@pytest.mark.xfail( + "env.PYPY and env.MACOS", + raises=RuntimeError, + reason="Expected failure with PyPy and libc++ (Issue #2847 & PR #2999)", +) +def test_cross_module_exception_translator(): + with pytest.raises(KeyError): + # translator registered in cross_module_tests + m.throw_should_be_translated_to_key_error() + def test_python_call_in_catch(): d = {} @@ -50,31 +88,44 @@ def test_python_call_in_catch(): assert d["good"] is True +def ignore_pytest_unraisable_warning(f): + unraisable = "PytestUnraisableExceptionWarning" + if hasattr(pytest, unraisable): # Python >= 3.8 and pytest >= 6 + dec = pytest.mark.filterwarnings("ignore::pytest.{}".format(unraisable)) + return dec(f) + else: + return f + + +# TODO: find out why this fails on PyPy, https://foss.heptapod.net/pypy/pypy/-/issues/3583 +@pytest.mark.xfail(env.PYPY, reason="Failure on PyPy 3.8 (7.3.7)", strict=False) +@ignore_pytest_unraisable_warning def test_python_alreadyset_in_destructor(monkeypatch, capsys): hooked = False triggered = [False] # mutable, so Python 2.7 closure can modify it - if hasattr(sys, 'unraisablehook'): # Python 3.8+ + if hasattr(sys, "unraisablehook"): # Python 3.8+ hooked = True - default_hook = sys.unraisablehook + # Don't take `sys.unraisablehook`, as that's overwritten by pytest + default_hook = sys.__unraisablehook__ def hook(unraisable_hook_args): exc_type, exc_value, exc_tb, err_msg, obj = unraisable_hook_args - if obj == 'already_set demo': + if obj == "already_set demo": triggered[0] = True default_hook(unraisable_hook_args) return # Use monkeypatch so pytest can apply and remove the patch as appropriate - monkeypatch.setattr(sys, 'unraisablehook', hook) + monkeypatch.setattr(sys, "unraisablehook", hook) - assert m.python_alreadyset_in_destructor('already_set demo') is True + assert m.python_alreadyset_in_destructor("already_set demo") is True if hooked: assert triggered[0] is True _, captured_stderr = capsys.readouterr() # Error message is different in Python 2 and 3, check for words that appear in both - assert 'ignored' in captured_stderr and 'already_set demo' in captured_stderr + assert "ignored" in captured_stderr and "already_set demo" in captured_stderr def test_exception_matches(): @@ -107,7 +158,9 @@ def test_custom(msg): # Can we fall-through to the default handler? with pytest.raises(RuntimeError) as excinfo: m.throws_logic_error() - assert msg(excinfo.value) == "this error should fall through to the standard handler" + assert ( + msg(excinfo.value) == "this error should fall through to the standard handler" + ) # OverFlow error translation. with pytest.raises(OverflowError) as excinfo: @@ -166,7 +219,13 @@ def test_nested_throws(capture): # C++ -> Python -> C++ -> Python with capture: m.try_catch( - m.MyException5, pycatch, m.MyException, m.try_catch, m.MyException, throw_myex5) + m.MyException5, + pycatch, + m.MyException, + m.try_catch, + m.MyException, + throw_myex5, + ) assert str(capture).startswith("MyException5: nested error 5") # C++ -> Python -> C++ @@ -180,12 +239,37 @@ def test_nested_throws(capture): assert str(excinfo.value) == "this is a helper-defined translated exception" +@pytest.mark.skipif("env.PY2") +def test_throw_nested_exception(): + with pytest.raises(RuntimeError) as excinfo: + m.throw_nested_exception() + assert str(excinfo.value) == "Outer Exception" + assert str(excinfo.value.__cause__) == "Inner Exception" + + # This can often happen if you wrap a pybind11 class in a Python wrapper def test_invalid_repr(): - class MyRepr(object): def __repr__(self): raise AttributeError("Example error") with pytest.raises(TypeError): m.simple_bool_passthrough(MyRepr()) + + +def test_local_translator(msg): + """Tests that a local translator works and that the local translator from + the cross module is not applied""" + with pytest.raises(RuntimeError) as excinfo: + m.throws6() + assert msg(excinfo.value) == "MyException6 only handled in this module" + + with pytest.raises(RuntimeError) as excinfo: + m.throws_local_error() + assert not isinstance(excinfo.value, KeyError) + assert msg(excinfo.value) == "never caught" + + with pytest.raises(Exception) as excinfo: + m.throws_local_simple_error() + assert not isinstance(excinfo.value, cm.LocalSimpleException) + assert msg(excinfo.value) == "this mod" diff --git a/pybind11/tests/test_factory_constructors.cpp b/pybind11/tests/test_factory_constructors.cpp index 2368dabb8..660e2896a 100644 --- a/pybind11/tests/test_factory_constructors.cpp +++ b/pybind11/tests/test_factory_constructors.cpp @@ -8,35 +8,45 @@ BSD-style license that can be found in the LICENSE file. */ -#include "pybind11_tests.h" #include "constructor_stats.h" +#include "pybind11_tests.h" #include #include +#include // Classes for testing python construction via C++ factory function: // Not publicly constructible, copyable, or movable: class TestFactory1 { friend class TestFactoryHelper; TestFactory1() : value("(empty)") { print_default_created(this); } - TestFactory1(int v) : value(std::to_string(v)) { print_created(this, value); } - TestFactory1(std::string v) : value(std::move(v)) { print_created(this, value); } + explicit TestFactory1(int v) : value(std::to_string(v)) { print_created(this, value); } + explicit TestFactory1(std::string v) : value(std::move(v)) { print_created(this, value); } + +public: + std::string value; TestFactory1(TestFactory1 &&) = delete; TestFactory1(const TestFactory1 &) = delete; TestFactory1 &operator=(TestFactory1 &&) = delete; TestFactory1 &operator=(const TestFactory1 &) = delete; -public: - std::string value; ~TestFactory1() { print_destroyed(this); } }; // Non-public construction, but moveable: class TestFactory2 { friend class TestFactoryHelper; TestFactory2() : value("(empty2)") { print_default_created(this); } - TestFactory2(int v) : value(std::to_string(v)) { print_created(this, value); } - TestFactory2(std::string v) : value(std::move(v)) { print_created(this, value); } + explicit TestFactory2(int v) : value(std::to_string(v)) { print_created(this, value); } + explicit TestFactory2(std::string v) : value(std::move(v)) { print_created(this, value); } + public: - TestFactory2(TestFactory2 &&m) { value = std::move(m.value); print_move_created(this); } - TestFactory2 &operator=(TestFactory2 &&m) { value = std::move(m.value); print_move_assigned(this); return *this; } + TestFactory2(TestFactory2 &&m) noexcept { + value = std::move(m.value); + print_move_created(this); + } + TestFactory2 &operator=(TestFactory2 &&m) noexcept { + value = std::move(m.value); + print_move_assigned(this); + return *this; + } std::string value; ~TestFactory2() { print_destroyed(this); } }; @@ -45,11 +55,19 @@ class TestFactory3 { protected: friend class TestFactoryHelper; TestFactory3() : value("(empty3)") { print_default_created(this); } - TestFactory3(int v) : value(std::to_string(v)) { print_created(this, value); } + explicit TestFactory3(int v) : value(std::to_string(v)) { print_created(this, value); } + public: - TestFactory3(std::string v) : value(std::move(v)) { print_created(this, value); } - TestFactory3(TestFactory3 &&m) { value = std::move(m.value); print_move_created(this); } - TestFactory3 &operator=(TestFactory3 &&m) { value = std::move(m.value); print_move_assigned(this); return *this; } + explicit TestFactory3(std::string v) : value(std::move(v)) { print_created(this, value); } + TestFactory3(TestFactory3 &&m) noexcept { + value = std::move(m.value); + print_move_created(this); + } + TestFactory3 &operator=(TestFactory3 &&m) noexcept { + value = std::move(m.value); + print_move_assigned(this); + return *this; + } std::string value; virtual ~TestFactory3() { print_destroyed(this); } }; @@ -57,13 +75,13 @@ public: class TestFactory4 : public TestFactory3 { public: TestFactory4() : TestFactory3() { print_default_created(this); } - TestFactory4(int v) : TestFactory3(v) { print_created(this, v); } + explicit TestFactory4(int v) : TestFactory3(v) { print_created(this, v); } ~TestFactory4() override { print_destroyed(this); } }; // Another class for an invalid downcast test class TestFactory5 : public TestFactory3 { public: - TestFactory5(int i) : TestFactory3(i) { print_created(this, i); } + explicit TestFactory5(int i) : TestFactory3(i) { print_created(this, i); } ~TestFactory5() override { print_destroyed(this); } }; @@ -72,22 +90,35 @@ protected: int value; bool alias = false; public: - TestFactory6(int i) : value{i} { print_created(this, i); } - TestFactory6(TestFactory6 &&f) { print_move_created(this); value = f.value; alias = f.alias; } + explicit TestFactory6(int i) : value{i} { print_created(this, i); } + TestFactory6(TestFactory6 &&f) noexcept { + print_move_created(this); + value = f.value; + alias = f.alias; + } TestFactory6(const TestFactory6 &f) { print_copy_created(this); value = f.value; alias = f.alias; } virtual ~TestFactory6() { print_destroyed(this); } virtual int get() { return value; } - bool has_alias() { return alias; } + bool has_alias() const { return alias; } }; class PyTF6 : public TestFactory6 { public: // Special constructor that allows the factory to construct a PyTF6 from a TestFactory6 only // when an alias is needed: - PyTF6(TestFactory6 &&base) : TestFactory6(std::move(base)) { alias = true; print_created(this, "move", value); } - PyTF6(int i) : TestFactory6(i) { alias = true; print_created(this, i); } - PyTF6(PyTF6 &&f) : TestFactory6(std::move(f)) { print_move_created(this); } + explicit PyTF6(TestFactory6 &&base) : TestFactory6(std::move(base)) { + alias = true; + print_created(this, "move", value); + } + explicit PyTF6(int i) : TestFactory6(i) { + alias = true; + print_created(this, i); + } + PyTF6(PyTF6 &&f) noexcept : TestFactory6(std::move(f)) { print_move_created(this); } PyTF6(const PyTF6 &f) : TestFactory6(f) { print_copy_created(this); } - PyTF6(std::string s) : TestFactory6((int) s.size()) { alias = true; print_created(this, s); } + explicit PyTF6(std::string s) : TestFactory6((int) s.size()) { + alias = true; + print_created(this, s); + } ~PyTF6() override { print_destroyed(this); } int get() override { PYBIND11_OVERRIDE(int, TestFactory6, get, /*no args*/); } }; @@ -97,17 +128,24 @@ protected: int value; bool alias = false; public: - TestFactory7(int i) : value{i} { print_created(this, i); } - TestFactory7(TestFactory7 &&f) { print_move_created(this); value = f.value; alias = f.alias; } + explicit TestFactory7(int i) : value{i} { print_created(this, i); } + TestFactory7(TestFactory7 &&f) noexcept { + print_move_created(this); + value = f.value; + alias = f.alias; + } TestFactory7(const TestFactory7 &f) { print_copy_created(this); value = f.value; alias = f.alias; } virtual ~TestFactory7() { print_destroyed(this); } virtual int get() { return value; } - bool has_alias() { return alias; } + bool has_alias() const { return alias; } }; class PyTF7 : public TestFactory7 { public: - PyTF7(int i) : TestFactory7(i) { alias = true; print_created(this, i); } - PyTF7(PyTF7 &&f) : TestFactory7(std::move(f)) { print_move_created(this); } + explicit PyTF7(int i) : TestFactory7(i) { + alias = true; + print_created(this, i); + } + PyTF7(PyTF7 &&f) noexcept : TestFactory7(std::move(f)) { print_move_created(this); } PyTF7(const PyTF7 &f) : TestFactory7(f) { print_copy_created(this); } ~PyTF7() override { print_destroyed(this); } int get() override { PYBIND11_OVERRIDE(int, TestFactory7, get, /*no args*/); } @@ -122,7 +160,9 @@ public: // Holder: static std::unique_ptr construct1(int a) { return std::unique_ptr(new TestFactory1(a)); } // pointer again - static TestFactory1 *construct1_string(std::string a) { return new TestFactory1(a); } + static TestFactory1 *construct1_string(std::string a) { + return new TestFactory1(std::move(a)); + } // Moveable type: // pointer: @@ -130,7 +170,7 @@ public: // holder: static std::unique_ptr construct2(int a) { return std::unique_ptr(new TestFactory2(a)); } // by value moving: - static TestFactory2 construct2(std::string a) { return TestFactory2(a); } + static TestFactory2 construct2(std::string a) { return TestFactory2(std::move(a)); } // shared_ptr holder type: // pointer: @@ -142,7 +182,7 @@ public: TEST_SUBMODULE(factory_constructors, m) { // Define various trivial types to allow simpler overload resolution: - py::module m_tag = m.def_submodule("tag"); + py::module_ m_tag = m.def_submodule("tag"); #define MAKE_TAG_TYPE(Name) \ struct Name##_tag {}; \ py::class_(m_tag, #Name "_tag").def(py::init<>()); \ @@ -173,21 +213,27 @@ TEST_SUBMODULE(factory_constructors, m) { ; py::class_(m, "TestFactory2") .def(py::init([](pointer_tag, int v) { return TestFactoryHelper::construct2(v); })) - .def(py::init([](unique_ptr_tag, std::string v) { return TestFactoryHelper::construct2(v); })) + .def(py::init([](unique_ptr_tag, std::string v) { + return TestFactoryHelper::construct2(std::move(v)); + })) .def(py::init([](move_tag) { return TestFactoryHelper::construct2(); })) - .def_readwrite("value", &TestFactory2::value) - ; + .def_readwrite("value", &TestFactory2::value); // Stateful & reused: int c = 1; auto c4a = [c](pointer_tag, TF4_tag, int a) { (void) c; return new TestFactory4(a);}; // test_init_factory_basic, test_init_factory_casting - py::class_>(m, "TestFactory3") + py::class_> pyTestFactory3(m, "TestFactory3"); + pyTestFactory3 .def(py::init([](pointer_tag, int v) { return TestFactoryHelper::construct3(v); })) - .def(py::init([](shared_ptr_tag) { return TestFactoryHelper::construct3(); })) - .def("__init__", [](TestFactory3 &self, std::string v) { new (&self) TestFactory3(v); }) // placement-new ctor - + .def(py::init([](shared_ptr_tag) { return TestFactoryHelper::construct3(); })); + ignoreOldStyleInitWarnings([&pyTestFactory3]() { + pyTestFactory3.def("__init__", [](TestFactory3 &self, std::string v) { + new (&self) TestFactory3(std::move(v)); + }); // placement-new ctor + }); + pyTestFactory3 // factories returning a derived type: .def(py::init(c4a)) // derived ptr .def(py::init([](pointer_tag, TF5_tag, int a) { return new TestFactory5(a); })) @@ -216,58 +262,60 @@ TEST_SUBMODULE(factory_constructors, m) { py::class_(m, "TestFactory6") .def(py::init([](base_tag, int i) { return TestFactory6(i); })) .def(py::init([](alias_tag, int i) { return PyTF6(i); })) - .def(py::init([](alias_tag, std::string s) { return PyTF6(s); })) + .def(py::init([](alias_tag, std::string s) { return PyTF6(std::move(s)); })) .def(py::init([](alias_tag, pointer_tag, int i) { return new PyTF6(i); })) .def(py::init([](base_tag, pointer_tag, int i) { return new TestFactory6(i); })) - .def(py::init([](base_tag, alias_tag, pointer_tag, int i) { return (TestFactory6 *) new PyTF6(i); })) + .def(py::init( + [](base_tag, alias_tag, pointer_tag, int i) { return (TestFactory6 *) new PyTF6(i); })) .def("get", &TestFactory6::get) .def("has_alias", &TestFactory6::has_alias) - .def_static("get_cstats", &ConstructorStats::get, py::return_value_policy::reference) - .def_static("get_alias_cstats", &ConstructorStats::get, py::return_value_policy::reference) - ; + .def_static( + "get_cstats", &ConstructorStats::get, py::return_value_policy::reference) + .def_static( + "get_alias_cstats", &ConstructorStats::get, py::return_value_policy::reference); // test_init_factory_dual // Separate alias constructor testing py::class_>(m, "TestFactory7") - .def(py::init( - [](int i) { return TestFactory7(i); }, - [](int i) { return PyTF7(i); })) - .def(py::init( - [](pointer_tag, int i) { return new TestFactory7(i); }, - [](pointer_tag, int i) { return new PyTF7(i); })) - .def(py::init( - [](mixed_tag, int i) { return new TestFactory7(i); }, - [](mixed_tag, int i) { return PyTF7(i); })) - .def(py::init( - [](mixed_tag, std::string s) { return TestFactory7((int) s.size()); }, - [](mixed_tag, std::string s) { return new PyTF7((int) s.size()); })) - .def(py::init( - [](base_tag, pointer_tag, int i) { return new TestFactory7(i); }, - [](base_tag, pointer_tag, int i) { return (TestFactory7 *) new PyTF7(i); })) - .def(py::init( - [](alias_tag, pointer_tag, int i) { return new PyTF7(i); }, - [](alias_tag, pointer_tag, int i) { return new PyTF7(10*i); })) + .def(py::init([](int i) { return TestFactory7(i); }, [](int i) { return PyTF7(i); })) + .def(py::init([](pointer_tag, int i) { return new TestFactory7(i); }, + [](pointer_tag, int i) { return new PyTF7(i); })) + .def(py::init([](mixed_tag, int i) { return new TestFactory7(i); }, + [](mixed_tag, int i) { return PyTF7(i); })) + .def(py::init([](mixed_tag, const std::string &s) { return TestFactory7((int) s.size()); }, + [](mixed_tag, const std::string &s) { return new PyTF7((int) s.size()); })) + .def(py::init([](base_tag, pointer_tag, int i) { return new TestFactory7(i); }, + [](base_tag, pointer_tag, int i) { return (TestFactory7 *) new PyTF7(i); })) + .def(py::init([](alias_tag, pointer_tag, int i) { return new PyTF7(i); }, + [](alias_tag, pointer_tag, int i) { return new PyTF7(10 * i); })) .def(py::init( [](shared_ptr_tag, base_tag, int i) { return std::make_shared(i); }, - [](shared_ptr_tag, base_tag, int i) { auto *p = new PyTF7(i); return std::shared_ptr(p); })) - .def(py::init( - [](shared_ptr_tag, invalid_base_tag, int i) { return std::make_shared(i); }, - [](shared_ptr_tag, invalid_base_tag, int i) { return std::make_shared(i); })) // <-- invalid alias factory + [](shared_ptr_tag, base_tag, int i) { + auto *p = new PyTF7(i); + return std::shared_ptr(p); + })) + .def(py::init([](shared_ptr_tag, + invalid_base_tag, + int i) { return std::make_shared(i); }, + [](shared_ptr_tag, invalid_base_tag, int i) { + return std::make_shared(i); + })) // <-- invalid alias factory .def("get", &TestFactory7::get) .def("has_alias", &TestFactory7::has_alias) - .def_static("get_cstats", &ConstructorStats::get, py::return_value_policy::reference) - .def_static("get_alias_cstats", &ConstructorStats::get, py::return_value_policy::reference) - ; + .def_static( + "get_cstats", &ConstructorStats::get, py::return_value_policy::reference) + .def_static( + "get_alias_cstats", &ConstructorStats::get, py::return_value_policy::reference); // test_placement_new_alternative // Class with a custom new operator but *without* a placement new operator (issue #948) class NoPlacementNew { public: - NoPlacementNew(int i) : i(i) { } + explicit NoPlacementNew(int i) : i(i) {} static void *operator new(std::size_t s) { auto *p = ::operator new(s); py::print("operator new called, returning", reinterpret_cast(p)); @@ -291,8 +339,8 @@ TEST_SUBMODULE(factory_constructors, m) { // Class that has verbose operator_new/operator_delete calls struct NoisyAlloc { NoisyAlloc(const NoisyAlloc &) = default; - NoisyAlloc(int i) { py::print(py::str("NoisyAlloc(int {})").format(i)); } - NoisyAlloc(double d) { py::print(py::str("NoisyAlloc(double {})").format(d)); } + explicit NoisyAlloc(int i) { py::print(py::str("NoisyAlloc(int {})").format(i)); } + explicit NoisyAlloc(double d) { py::print(py::str("NoisyAlloc(double {})").format(d)); } ~NoisyAlloc() { py::print("~NoisyAlloc()"); } static void *operator new(size_t s) { py::print("noisy new"); return ::operator new(s); } @@ -304,27 +352,33 @@ TEST_SUBMODULE(factory_constructors, m) { static void operator delete(void *p) { py::print("noisy delete"); ::operator delete(p); } #endif }; - py::class_(m, "NoisyAlloc") + + + py::class_ pyNoisyAlloc(m, "NoisyAlloc"); // Since these overloads have the same number of arguments, the dispatcher will try each of // them until the arguments convert. Thus we can get a pre-allocation here when passing a // single non-integer: - .def("__init__", [](NoisyAlloc *a, int i) { new (a) NoisyAlloc(i); }) // Regular constructor, runs first, requires preallocation - .def(py::init([](double d) { return new NoisyAlloc(d); })) - - // The two-argument version: first the factory pointer overload. - .def(py::init([](int i, int) { return new NoisyAlloc(i); })) - // Return-by-value: - .def(py::init([](double d, int) { return NoisyAlloc(d); })) - // Old-style placement new init; requires preallocation - .def("__init__", [](NoisyAlloc &a, double d, double) { new (&a) NoisyAlloc(d); }) - // Requires deallocation of previous overload preallocated value: - .def(py::init([](int i, double) { return new NoisyAlloc(i); })) - // Regular again: requires yet another preallocation - .def("__init__", [](NoisyAlloc &a, int i, std::string) { new (&a) NoisyAlloc(i); }) - ; - + ignoreOldStyleInitWarnings([&pyNoisyAlloc]() { + pyNoisyAlloc.def("__init__", [](NoisyAlloc *a, int i) { new (a) NoisyAlloc(i); }); // Regular constructor, runs first, requires preallocation + }); + pyNoisyAlloc.def(py::init([](double d) { return new NoisyAlloc(d); })); + // The two-argument version: first the factory pointer overload. + pyNoisyAlloc.def(py::init([](int i, int) { return new NoisyAlloc(i); })); + // Return-by-value: + pyNoisyAlloc.def(py::init([](double d, int) { return NoisyAlloc(d); })); + // Old-style placement new init; requires preallocation + ignoreOldStyleInitWarnings([&pyNoisyAlloc]() { + pyNoisyAlloc.def("__init__", [](NoisyAlloc &a, double d, double) { new (&a) NoisyAlloc(d); }); + }); + // Requires deallocation of previous overload preallocated value: + pyNoisyAlloc.def(py::init([](int i, double) { return new NoisyAlloc(i); })); + // Regular again: requires yet another preallocation + ignoreOldStyleInitWarnings([&pyNoisyAlloc]() { + pyNoisyAlloc.def( + "__init__", [](NoisyAlloc &a, int i, const std::string &) { new (&a) NoisyAlloc(i); }); + }); // static_assert testing (the following def's should all fail with appropriate compilation errors): #if 0 diff --git a/pybind11/tests/test_factory_constructors.py b/pybind11/tests/test_factory_constructors.py index b141c13de..8bc026985 100644 --- a/pybind11/tests/test_factory_constructors.py +++ b/pybind11/tests/test_factory_constructors.py @@ -1,18 +1,21 @@ # -*- coding: utf-8 -*- -import pytest import re -import env # noqa: F401 +import pytest +import env # noqa: F401 +from pybind11_tests import ConstructorStats from pybind11_tests import factory_constructors as m from pybind11_tests.factory_constructors import tag -from pybind11_tests import ConstructorStats def test_init_factory_basic(): """Tests py::init_factory() wrapper around various ways of returning the object""" - cstats = [ConstructorStats.get(c) for c in [m.TestFactory1, m.TestFactory2, m.TestFactory3]] + cstats = [ + ConstructorStats.get(c) + for c in [m.TestFactory1, m.TestFactory2, m.TestFactory3] + ] cstats[0].alive() # force gc n_inst = ConstructorStats.detail_reg_inst() @@ -41,12 +44,12 @@ def test_init_factory_basic(): z3 = m.TestFactory3("bye") assert z3.value == "bye" - for null_ptr_kind in [tag.null_ptr, - tag.null_unique_ptr, - tag.null_shared_ptr]: + for null_ptr_kind in [tag.null_ptr, tag.null_unique_ptr, tag.null_shared_ptr]: with pytest.raises(TypeError) as excinfo: m.TestFactory3(null_ptr_kind) - assert str(excinfo.value) == "pybind11::init(): factory function returned nullptr" + assert ( + str(excinfo.value) == "pybind11::init(): factory function returned nullptr" + ) assert [i.alive() for i in cstats] == [3, 3, 3] assert ConstructorStats.detail_reg_inst() == n_inst + 9 @@ -61,7 +64,7 @@ def test_init_factory_basic(): assert [i.values() for i in cstats] == [ ["3", "hi!"], ["7", "hi again"], - ["42", "bye"] + ["42", "bye"], ] assert [i.default_constructions for i in cstats] == [1, 1, 1] @@ -69,7 +72,9 @@ def test_init_factory_basic(): def test_init_factory_signature(msg): with pytest.raises(TypeError) as excinfo: m.TestFactory1("invalid", "constructor", "arguments") - assert msg(excinfo.value) == """ + assert ( + msg(excinfo.value) + == """ __init__(): incompatible constructor arguments. The following argument types are supported: 1. m.factory_constructors.TestFactory1(arg0: m.factory_constructors.tag.unique_ptr_tag, arg1: int) 2. m.factory_constructors.TestFactory1(arg0: str) @@ -78,8 +83,11 @@ def test_init_factory_signature(msg): Invoked with: 'invalid', 'constructor', 'arguments' """ # noqa: E501 line too long + ) - assert msg(m.TestFactory1.__init__.__doc__) == """ + assert ( + msg(m.TestFactory1.__init__.__doc__) + == """ __init__(*args, **kwargs) Overloaded function. @@ -91,12 +99,16 @@ def test_init_factory_signature(msg): 4. __init__(self: m.factory_constructors.TestFactory1, arg0: handle, arg1: int, arg2: handle) -> None """ # noqa: E501 line too long + ) def test_init_factory_casting(): """Tests py::init_factory() wrapper with various upcasting and downcasting returns""" - cstats = [ConstructorStats.get(c) for c in [m.TestFactory3, m.TestFactory4, m.TestFactory5]] + cstats = [ + ConstructorStats.get(c) + for c in [m.TestFactory3, m.TestFactory4, m.TestFactory5] + ] cstats[0].alive() # force gc n_inst = ConstructorStats.detail_reg_inst() @@ -134,7 +146,7 @@ def test_init_factory_casting(): assert [i.values() for i in cstats] == [ ["4", "5", "6", "7", "8"], ["4", "5", "8"], - ["6", "7"] + ["6", "7"], ] @@ -204,7 +216,7 @@ def test_init_factory_alias(): assert [i.values() for i in cstats] == [ ["1", "8", "3", "4", "5", "6", "123", "10", "47"], - ["hi there", "3", "4", "6", "move", "123", "why hello!", "move", "47"] + ["hi there", "3", "4", "6", "move", "123", "why hello!", "move", "47"], ] @@ -268,9 +280,11 @@ def test_init_factory_dual(): assert not g1.has_alias() with pytest.raises(TypeError) as excinfo: PythFactory7(tag.shared_ptr, tag.invalid_base, 14) - assert (str(excinfo.value) == - "pybind11::init(): construction failed: returned holder-wrapped instance is not an " - "alias instance") + assert ( + str(excinfo.value) + == "pybind11::init(): construction failed: returned holder-wrapped instance is not an " + "alias instance" + ) assert [i.alive() for i in cstats] == [13, 7] assert ConstructorStats.detail_reg_inst() == n_inst + 13 @@ -284,7 +298,7 @@ def test_init_factory_dual(): assert [i.values() for i in cstats] == [ ["1", "2", "3", "4", "5", "6", "7", "8", "9", "100", "11", "12", "13", "14"], - ["2", "4", "6", "8", "9", "100", "12"] + ["2", "4", "6", "8", "9", "100", "12"], ] @@ -294,7 +308,7 @@ def test_no_placement_new(capture): with capture: a = m.NoPlacementNew(123) - found = re.search(r'^operator new called, returning (\d+)\n$', str(capture)) + found = re.search(r"^operator new called, returning (\d+)\n$", str(capture)) assert found assert a.i == 123 with capture: @@ -305,7 +319,7 @@ def test_no_placement_new(capture): with capture: b = m.NoPlacementNew() - found = re.search(r'^operator new called, returning (\d+)\n$', str(capture)) + found = re.search(r"^operator new called, returning (\d+)\n$", str(capture)) assert found assert b.i == 100 with capture: @@ -333,7 +347,7 @@ def create_and_destroy(*args): def strip_comments(s): - return re.sub(r'\s+#.*', '', s) + return re.sub(r"\s+#.*", "", s) def test_reallocation_a(capture, msg): @@ -345,7 +359,9 @@ def test_reallocation_a(capture, msg): with capture: create_and_destroy(1) - assert msg(capture) == """ + assert ( + msg(capture) + == """ noisy new noisy placement new NoisyAlloc(int 1) @@ -353,12 +369,14 @@ def test_reallocation_a(capture, msg): ~NoisyAlloc() noisy delete """ + ) def test_reallocation_b(capture, msg): with capture: create_and_destroy(1.5) - assert msg(capture) == strip_comments(""" + assert msg(capture) == strip_comments( + """ noisy new # allocation required to attempt first overload noisy delete # have to dealloc before considering factory init overload noisy new # pointer factory calling "new", part 1: allocation @@ -366,51 +384,59 @@ def test_reallocation_b(capture, msg): --- ~NoisyAlloc() # Destructor noisy delete # operator delete - """) + """ + ) def test_reallocation_c(capture, msg): with capture: create_and_destroy(2, 3) - assert msg(capture) == strip_comments(""" + assert msg(capture) == strip_comments( + """ noisy new # pointer factory calling "new", allocation NoisyAlloc(int 2) # constructor --- ~NoisyAlloc() # Destructor noisy delete # operator delete - """) + """ + ) def test_reallocation_d(capture, msg): with capture: create_and_destroy(2.5, 3) - assert msg(capture) == strip_comments(""" + assert msg(capture) == strip_comments( + """ NoisyAlloc(double 2.5) # construction (local func variable: operator_new not called) noisy new # return-by-value "new" part 1: allocation ~NoisyAlloc() # moved-away local func variable destruction --- ~NoisyAlloc() # Destructor noisy delete # operator delete - """) + """ + ) def test_reallocation_e(capture, msg): with capture: create_and_destroy(3.5, 4.5) - assert msg(capture) == strip_comments(""" + assert msg(capture) == strip_comments( + """ noisy new # preallocation needed before invoking placement-new overload noisy placement new # Placement new NoisyAlloc(double 3.5) # construction --- ~NoisyAlloc() # Destructor noisy delete # operator delete - """) + """ + ) def test_reallocation_f(capture, msg): with capture: create_and_destroy(4, 0.5) - assert msg(capture) == strip_comments(""" + assert msg(capture) == strip_comments( + """ noisy new # preallocation needed before invoking placement-new overload noisy delete # deallocation of preallocated storage noisy new # Factory pointer allocation @@ -418,13 +444,15 @@ def test_reallocation_f(capture, msg): --- ~NoisyAlloc() # Destructor noisy delete # operator delete - """) + """ + ) def test_reallocation_g(capture, msg): with capture: create_and_destroy(5, "hi") - assert msg(capture) == strip_comments(""" + assert msg(capture) == strip_comments( + """ noisy new # preallocation needed before invoking first placement new noisy delete # delete before considering new-style constructor noisy new # preallocation for second placement new @@ -433,13 +461,15 @@ def test_reallocation_g(capture, msg): --- ~NoisyAlloc() # Destructor noisy delete # operator delete - """) + """ + ) @pytest.mark.skipif("env.PY2") def test_invalid_self(): """Tests invocation of the pybind-registered base class with an invalid `self` argument. You can only actually do this on Python 3: Python 2 raises an exception itself if you try.""" + class NotPybindDerived(object): pass @@ -456,23 +486,35 @@ def test_invalid_self(): # Same as above, but for a class with an alias: class BrokenTF6(m.TestFactory6): def __init__(self, bad): - if bad == 1: + if bad == 0: + m.TestFactory6.__init__() + elif bad == 1: a = m.TestFactory2(tag.pointer, 1) m.TestFactory6.__init__(a, tag.base, 1) elif bad == 2: a = m.TestFactory2(tag.pointer, 1) m.TestFactory6.__init__(a, tag.alias, 1) elif bad == 3: - m.TestFactory6.__init__(NotPybindDerived.__new__(NotPybindDerived), tag.base, 1) + m.TestFactory6.__init__( + NotPybindDerived.__new__(NotPybindDerived), tag.base, 1 + ) elif bad == 4: - m.TestFactory6.__init__(NotPybindDerived.__new__(NotPybindDerived), tag.alias, 1) + m.TestFactory6.__init__( + NotPybindDerived.__new__(NotPybindDerived), tag.alias, 1 + ) for arg in (1, 2): with pytest.raises(TypeError) as excinfo: BrokenTF1(arg) - assert str(excinfo.value) == "__init__(self, ...) called with invalid `self` argument" + assert ( + str(excinfo.value) + == "__init__(self, ...) called with invalid or missing `self` argument" + ) - for arg in (1, 2, 3, 4): + for arg in (0, 1, 2, 3, 4): with pytest.raises(TypeError) as excinfo: BrokenTF6(arg) - assert str(excinfo.value) == "__init__(self, ...) called with invalid `self` argument" + assert ( + str(excinfo.value) + == "__init__(self, ...) called with invalid or missing `self` argument" + ) diff --git a/pybind11/tests/test_gil_scoped.cpp b/pybind11/tests/test_gil_scoped.cpp index eb6308956..b261085c8 100644 --- a/pybind11/tests/test_gil_scoped.cpp +++ b/pybind11/tests/test_gil_scoped.cpp @@ -35,20 +35,15 @@ TEST_SUBMODULE(gil_scoped, m) { .def("virtual_func", &VirtClass::virtual_func) .def("pure_virtual_func", &VirtClass::pure_virtual_func); - m.def("test_callback_py_obj", - [](py::object func) { func(); }); - m.def("test_callback_std_func", - [](const std::function &func) { func(); }); - m.def("test_callback_virtual_func", - [](VirtClass &virt) { virt.virtual_func(); }); - m.def("test_callback_pure_virtual_func", - [](VirtClass &virt) { virt.pure_virtual_func(); }); - m.def("test_cross_module_gil", - []() { - auto cm = py::module::import("cross_module_gil_utils"); - auto gil_acquire = reinterpret_cast( - PyLong_AsVoidPtr(cm.attr("gil_acquire_funcaddr").ptr())); - py::gil_scoped_release gil_release; - gil_acquire(); - }); + m.def("test_callback_py_obj", [](py::object &func) { func(); }); + m.def("test_callback_std_func", [](const std::function &func) { func(); }); + m.def("test_callback_virtual_func", [](VirtClass &virt) { virt.virtual_func(); }); + m.def("test_callback_pure_virtual_func", [](VirtClass &virt) { virt.pure_virtual_func(); }); + m.def("test_cross_module_gil", []() { + auto cm = py::module_::import("cross_module_gil_utils"); + auto gil_acquire + = reinterpret_cast(PyLong_AsVoidPtr(cm.attr("gil_acquire_funcaddr").ptr())); + py::gil_scoped_release gil_release; + gil_acquire(); + }); } diff --git a/pybind11/tests/test_gil_scoped.py b/pybind11/tests/test_gil_scoped.py index 27122cca2..0a1d62747 100644 --- a/pybind11/tests/test_gil_scoped.py +++ b/pybind11/tests/test_gil_scoped.py @@ -2,10 +2,6 @@ import multiprocessing import threading -import pytest - -import env # noqa: F401 - from pybind11_tests import gil_scoped as m @@ -25,6 +21,7 @@ def _run_in_process(target, *args, **kwargs): def _python_to_cpp_to_python(): """Calls different C++ functions that come back to Python.""" + class ExtendedVirtClass(m.VirtClass): def virtual_func(self): pass @@ -54,8 +51,7 @@ def _python_to_cpp_to_python_from_threads(num_threads, parallel=False): thread.join() -# TODO: FIXME, sometimes returns -11 instead of 0 -@pytest.mark.xfail("env.PY > (3,8) and env.MACOS", strict=False) +# TODO: FIXME, sometimes returns -11 (segfault) instead of 0 on macOS Python 3.9 def test_python_to_cpp_to_python_from_thread(): """Makes sure there is no GIL deadlock when running in a thread. @@ -64,8 +60,7 @@ def test_python_to_cpp_to_python_from_thread(): assert _run_in_process(_python_to_cpp_to_python_from_threads, 1) == 0 -# TODO: FIXME -@pytest.mark.xfail("env.PY > (3,8) and env.MACOS", strict=False) +# TODO: FIXME on macOS Python 3.9 def test_python_to_cpp_to_python_from_thread_multiple_parallel(): """Makes sure there is no GIL deadlock when running in a thread multiple times in parallel. @@ -74,18 +69,18 @@ def test_python_to_cpp_to_python_from_thread_multiple_parallel(): assert _run_in_process(_python_to_cpp_to_python_from_threads, 8, parallel=True) == 0 -# TODO: FIXME -@pytest.mark.xfail("env.PY > (3,8) and env.MACOS", strict=False) +# TODO: FIXME on macOS Python 3.9 def test_python_to_cpp_to_python_from_thread_multiple_sequential(): """Makes sure there is no GIL deadlock when running in a thread multiple times sequentially. It runs in a separate process to be able to stop and assert if it deadlocks. """ - assert _run_in_process(_python_to_cpp_to_python_from_threads, 8, parallel=False) == 0 + assert ( + _run_in_process(_python_to_cpp_to_python_from_threads, 8, parallel=False) == 0 + ) -# TODO: FIXME -@pytest.mark.xfail("env.PY > (3,8) and env.MACOS", strict=False) +# TODO: FIXME on macOS Python 3.9 def test_python_to_cpp_to_python_from_process(): """Makes sure there is no GIL deadlock when using processes. diff --git a/pybind11/tests/test_iostream.cpp b/pybind11/tests/test_iostream.cpp index e67f88af5..c620b5949 100644 --- a/pybind11/tests/test_iostream.cpp +++ b/pybind11/tests/test_iostream.cpp @@ -7,37 +7,87 @@ BSD-style license that can be found in the LICENSE file. */ +#if defined(_MSC_VER) && _MSC_VER < 1910 // VS 2015's MSVC +# pragma warning(disable: 4702) // unreachable code in system header (xatomic.h(382)) +#endif #include #include "pybind11_tests.h" +#include #include +#include +#include +#include - -void noisy_function(std::string msg, bool flush) { +void noisy_function(const std::string &msg, bool flush) { std::cout << msg; if (flush) std::cout << std::flush; } -void noisy_funct_dual(std::string msg, std::string emsg) { +void noisy_funct_dual(const std::string &msg, const std::string &emsg) { std::cout << msg; std::cerr << emsg; } +// object to manage C++ thread +// simply repeatedly write to std::cerr until stopped +// redirect is called at some point to test the safety of scoped_estream_redirect +struct TestThread { + TestThread() : stop_{false} { + auto thread_f = [this] { + static std::mutex cout_mutex; + while (!stop_) { + { + // #HelpAppreciated: Work on iostream.h thread safety. + // Without this lock, the clang ThreadSanitizer (tsan) reliably reports a + // data race, and this test is predictably flakey on Windows. + // For more background see the discussion under + // https://github.com/pybind/pybind11/pull/2982 and + // https://github.com/pybind/pybind11/pull/2995. + const std::lock_guard lock(cout_mutex); + std::cout << "x" << std::flush; + } + std::this_thread::sleep_for(std::chrono::microseconds(50)); + } }; + t_ = new std::thread(std::move(thread_f)); + } + + ~TestThread() { + delete t_; + } + + void stop() { stop_ = true; } + + void join() const { + py::gil_scoped_release gil_lock; + t_->join(); + } + + void sleep() { + py::gil_scoped_release gil_lock; + std::this_thread::sleep_for(std::chrono::milliseconds(50)); + } + + std::thread *t_{nullptr}; + std::atomic stop_; +}; + + TEST_SUBMODULE(iostream, m) { add_ostream_redirect(m); // test_evals - m.def("captured_output_default", [](std::string msg) { + m.def("captured_output_default", [](const std::string &msg) { py::scoped_ostream_redirect redir; std::cout << msg << std::flush; }); - m.def("captured_output", [](std::string msg) { - py::scoped_ostream_redirect redir(std::cout, py::module::import("sys").attr("stdout")); + m.def("captured_output", [](const std::string &msg) { + py::scoped_ostream_redirect redir(std::cout, py::module_::import("sys").attr("stdout")); std::cout << msg << std::flush; }); @@ -45,8 +95,8 @@ TEST_SUBMODULE(iostream, m) { py::call_guard(), py::arg("msg"), py::arg("flush")=true); - m.def("captured_err", [](std::string msg) { - py::scoped_ostream_redirect redir(std::cerr, py::module::import("sys").attr("stderr")); + m.def("captured_err", [](const std::string &msg) { + py::scoped_ostream_redirect redir(std::cerr, py::module_::import("sys").attr("stderr")); std::cerr << msg << std::flush; }); @@ -56,18 +106,20 @@ TEST_SUBMODULE(iostream, m) { py::call_guard(), py::arg("msg"), py::arg("emsg")); - m.def("raw_output", [](std::string msg) { - std::cout << msg << std::flush; - }); + m.def("raw_output", [](const std::string &msg) { std::cout << msg << std::flush; }); - m.def("raw_err", [](std::string msg) { - std::cerr << msg << std::flush; - }); + m.def("raw_err", [](const std::string &msg) { std::cerr << msg << std::flush; }); - m.def("captured_dual", [](std::string msg, std::string emsg) { - py::scoped_ostream_redirect redirout(std::cout, py::module::import("sys").attr("stdout")); - py::scoped_ostream_redirect redirerr(std::cerr, py::module::import("sys").attr("stderr")); + m.def("captured_dual", [](const std::string &msg, const std::string &emsg) { + py::scoped_ostream_redirect redirout(std::cout, py::module_::import("sys").attr("stdout")); + py::scoped_ostream_redirect redirerr(std::cerr, py::module_::import("sys").attr("stderr")); std::cout << msg << std::flush; std::cerr << emsg << std::flush; }); + + py::class_(m, "TestThread") + .def(py::init<>()) + .def("stop", &TestThread::stop) + .def("join", &TestThread::join) + .def("sleep", &TestThread::sleep); } diff --git a/pybind11/tests/test_iostream.py b/pybind11/tests/test_iostream.py index 7ac4fcece..7f18ca65c 100644 --- a/pybind11/tests/test_iostream.py +++ b/pybind11/tests/test_iostream.py @@ -1,9 +1,9 @@ # -*- coding: utf-8 -*- -from pybind11_tests import iostream as m import sys - from contextlib import contextmanager +from pybind11_tests import iostream as m + try: # Python 3 from io import StringIO @@ -18,6 +18,7 @@ try: # Python 3.4 from contextlib import redirect_stdout except ImportError: + @contextmanager def redirect_stdout(target): original = sys.stdout @@ -25,10 +26,12 @@ except ImportError: yield sys.stdout = original + try: # Python 3.5 from contextlib import redirect_stderr except ImportError: + @contextmanager def redirect_stderr(target): original = sys.stderr @@ -42,16 +45,16 @@ def test_captured(capsys): m.captured_output(msg) stdout, stderr = capsys.readouterr() assert stdout == msg - assert stderr == '' + assert stderr == "" m.captured_output_default(msg) stdout, stderr = capsys.readouterr() assert stdout == msg - assert stderr == '' + assert stderr == "" m.captured_err(msg) stdout, stderr = capsys.readouterr() - assert stdout == '' + assert stdout == "" assert stderr == msg @@ -63,7 +66,97 @@ def test_captured_large_string(capsys): m.captured_output_default(msg) stdout, stderr = capsys.readouterr() assert stdout == msg - assert stderr == '' + assert stderr == "" + + +def test_captured_utf8_2byte_offset0(capsys): + msg = "\u07FF" + msg = "" + msg * (1024 // len(msg) + 1) + + m.captured_output_default(msg) + stdout, stderr = capsys.readouterr() + assert stdout == msg + assert stderr == "" + + +def test_captured_utf8_2byte_offset1(capsys): + msg = "\u07FF" + msg = "1" + msg * (1024 // len(msg) + 1) + + m.captured_output_default(msg) + stdout, stderr = capsys.readouterr() + assert stdout == msg + assert stderr == "" + + +def test_captured_utf8_3byte_offset0(capsys): + msg = "\uFFFF" + msg = "" + msg * (1024 // len(msg) + 1) + + m.captured_output_default(msg) + stdout, stderr = capsys.readouterr() + assert stdout == msg + assert stderr == "" + + +def test_captured_utf8_3byte_offset1(capsys): + msg = "\uFFFF" + msg = "1" + msg * (1024 // len(msg) + 1) + + m.captured_output_default(msg) + stdout, stderr = capsys.readouterr() + assert stdout == msg + assert stderr == "" + + +def test_captured_utf8_3byte_offset2(capsys): + msg = "\uFFFF" + msg = "12" + msg * (1024 // len(msg) + 1) + + m.captured_output_default(msg) + stdout, stderr = capsys.readouterr() + assert stdout == msg + assert stderr == "" + + +def test_captured_utf8_4byte_offset0(capsys): + msg = "\U0010FFFF" + msg = "" + msg * (1024 // len(msg) + 1) + + m.captured_output_default(msg) + stdout, stderr = capsys.readouterr() + assert stdout == msg + assert stderr == "" + + +def test_captured_utf8_4byte_offset1(capsys): + msg = "\U0010FFFF" + msg = "1" + msg * (1024 // len(msg) + 1) + + m.captured_output_default(msg) + stdout, stderr = capsys.readouterr() + assert stdout == msg + assert stderr == "" + + +def test_captured_utf8_4byte_offset2(capsys): + msg = "\U0010FFFF" + msg = "12" + msg * (1024 // len(msg) + 1) + + m.captured_output_default(msg) + stdout, stderr = capsys.readouterr() + assert stdout == msg + assert stderr == "" + + +def test_captured_utf8_4byte_offset3(capsys): + msg = "\U0010FFFF" + msg = "123" + msg * (1024 // len(msg) + 1) + + m.captured_output_default(msg) + stdout, stderr = capsys.readouterr() + assert stdout == msg + assert stderr == "" def test_guard_capture(capsys): @@ -71,7 +164,7 @@ def test_guard_capture(capsys): m.guard_output(msg) stdout, stderr = capsys.readouterr() assert stdout == msg - assert stderr == '' + assert stderr == "" def test_series_captured(capture): @@ -88,7 +181,7 @@ def test_flush(capfd): with m.ostream_redirect(): m.noisy_function(msg, flush=False) stdout, stderr = capfd.readouterr() - assert stdout == '' + assert stdout == "" m.noisy_function(msg2, flush=True) stdout, stderr = capfd.readouterr() @@ -107,15 +200,15 @@ def test_not_captured(capfd): m.raw_output(msg) stdout, stderr = capfd.readouterr() assert stdout == msg - assert stderr == '' - assert stream.getvalue() == '' + assert stderr == "" + assert stream.getvalue() == "" stream = StringIO() with redirect_stdout(stream): m.captured_output(msg) stdout, stderr = capfd.readouterr() - assert stdout == '' - assert stderr == '' + assert stdout == "" + assert stderr == "" assert stream.getvalue() == msg @@ -125,16 +218,16 @@ def test_err(capfd): with redirect_stderr(stream): m.raw_err(msg) stdout, stderr = capfd.readouterr() - assert stdout == '' + assert stdout == "" assert stderr == msg - assert stream.getvalue() == '' + assert stream.getvalue() == "" stream = StringIO() with redirect_stderr(stream): m.captured_err(msg) stdout, stderr = capfd.readouterr() - assert stdout == '' - assert stderr == '' + assert stdout == "" + assert stderr == "" assert stream.getvalue() == msg @@ -146,8 +239,8 @@ def test_multi_captured(capfd): m.captured_output("c") m.raw_output("d") stdout, stderr = capfd.readouterr() - assert stdout == 'bd' - assert stream.getvalue() == 'ac' + assert stdout == "bd" + assert stream.getvalue() == "ac" def test_dual(capsys): @@ -164,14 +257,14 @@ def test_redirect(capfd): m.raw_output(msg) stdout, stderr = capfd.readouterr() assert stdout == msg - assert stream.getvalue() == '' + assert stream.getvalue() == "" stream = StringIO() with redirect_stdout(stream): with m.ostream_redirect(): m.raw_output(msg) stdout, stderr = capfd.readouterr() - assert stdout == '' + assert stdout == "" assert stream.getvalue() == msg stream = StringIO() @@ -179,7 +272,7 @@ def test_redirect(capfd): m.raw_output(msg) stdout, stderr = capfd.readouterr() assert stdout == msg - assert stream.getvalue() == '' + assert stream.getvalue() == "" def test_redirect_err(capfd): @@ -193,7 +286,7 @@ def test_redirect_err(capfd): m.raw_err(msg2) stdout, stderr = capfd.readouterr() assert stdout == msg - assert stderr == '' + assert stderr == "" assert stream.getvalue() == msg2 @@ -209,7 +302,30 @@ def test_redirect_both(capfd): m.raw_output(msg) m.raw_err(msg2) stdout, stderr = capfd.readouterr() - assert stdout == '' - assert stderr == '' + assert stdout == "" + assert stderr == "" assert stream.getvalue() == msg assert stream2.getvalue() == msg2 + + +def test_threading(): + with m.ostream_redirect(stdout=True, stderr=False): + # start some threads + threads = [] + + # start some threads + for _j in range(20): + threads.append(m.TestThread()) + + # give the threads some time to fail + threads[0].sleep() + + # stop all the threads + for t in threads: + t.stop() + + for t in threads: + t.join() + + # if a thread segfaults, we don't get here + assert True diff --git a/pybind11/tests/test_kwargs_and_defaults.cpp b/pybind11/tests/test_kwargs_and_defaults.cpp index 641ec88c4..34ad2a864 100644 --- a/pybind11/tests/test_kwargs_and_defaults.cpp +++ b/pybind11/tests/test_kwargs_and_defaults.cpp @@ -11,6 +11,8 @@ #include "constructor_stats.h" #include +#include + TEST_SUBMODULE(kwargs_and_defaults, m) { auto kw_func = [](int x, int y) { return "x=" + std::to_string(x) + ", y=" + std::to_string(y); }; @@ -37,18 +39,16 @@ TEST_SUBMODULE(kwargs_and_defaults, m) { m.def("args_function", [](py::args args) -> py::tuple { return std::move(args); }); - m.def("args_kwargs_function", [](py::args args, py::kwargs kwargs) { + m.def("args_kwargs_function", [](const py::args &args, const py::kwargs &kwargs) { return py::make_tuple(args, kwargs); }); // test_mixed_args_and_kwargs - m.def("mixed_plus_args", [](int i, double j, py::args args) { - return py::make_tuple(i, j, args); - }); - m.def("mixed_plus_kwargs", [](int i, double j, py::kwargs kwargs) { - return py::make_tuple(i, j, kwargs); - }); - auto mixed_plus_both = [](int i, double j, py::args args, py::kwargs kwargs) { + m.def("mixed_plus_args", + [](int i, double j, const py::args &args) { return py::make_tuple(i, j, args); }); + m.def("mixed_plus_kwargs", + [](int i, double j, const py::kwargs &kwargs) { return py::make_tuple(i, j, kwargs); }); + auto mixed_plus_both = [](int i, double j, const py::args &args, const py::kwargs &kwargs) { return py::make_tuple(i, j, args, kwargs); }; m.def("mixed_plus_args_kwargs", mixed_plus_both); @@ -56,6 +56,23 @@ TEST_SUBMODULE(kwargs_and_defaults, m) { m.def("mixed_plus_args_kwargs_defaults", mixed_plus_both, py::arg("i") = 1, py::arg("j") = 3.14159); + m.def("args_kwonly", + [](int i, double j, const py::args &args, int z) { return py::make_tuple(i, j, args, z); }, + "i"_a, "j"_a, "z"_a); + m.def("args_kwonly_kwargs", + [](int i, double j, const py::args &args, int z, const py::kwargs &kwargs) { + return py::make_tuple(i, j, args, z, kwargs); }, + "i"_a, "j"_a, py::kw_only{}, "z"_a); + m.def("args_kwonly_kwargs_defaults", + [](int i, double j, const py::args &args, int z, const py::kwargs &kwargs) { + return py::make_tuple(i, j, args, z, kwargs); }, + "i"_a = 1, "j"_a = 3.14159, "z"_a = 42); + m.def("args_kwonly_full_monty", + [](int h, int i, double j, const py::args &args, int z, const py::kwargs &kwargs) { + return py::make_tuple(h, i, j, args, z, kwargs); }, + py::arg() = 1, py::arg() = 2, py::pos_only{}, "j"_a = 3.14159, "z"_a = 42); + + // test_args_refcount // PyPy needs a garbage collection to get the reference count values to match CPython's behaviour #ifdef PYPY_VERSION @@ -65,22 +82,25 @@ TEST_SUBMODULE(kwargs_and_defaults, m) { #endif m.def("arg_refcount_h", [](py::handle h) { GC_IF_NEEDED; return h.ref_count(); }); m.def("arg_refcount_h", [](py::handle h, py::handle, py::handle) { GC_IF_NEEDED; return h.ref_count(); }); - m.def("arg_refcount_o", [](py::object o) { GC_IF_NEEDED; return o.ref_count(); }); + m.def("arg_refcount_o", [](const py::object &o) { + GC_IF_NEEDED; + return o.ref_count(); + }); m.def("args_refcount", [](py::args a) { GC_IF_NEEDED; py::tuple t(a.size()); for (size_t i = 0; i < a.size(); i++) // Use raw Python API here to avoid an extra, intermediate incref on the tuple item: - t[i] = (int) Py_REFCNT(PyTuple_GET_ITEM(a.ptr(), static_cast(i))); + t[i] = (int) Py_REFCNT(PyTuple_GET_ITEM(a.ptr(), static_cast(i))); return t; }); - m.def("mixed_args_refcount", [](py::object o, py::args a) { + m.def("mixed_args_refcount", [](const py::object &o, py::args a) { GC_IF_NEEDED; py::tuple t(a.size() + 1); t[0] = o.ref_count(); for (size_t i = 0; i < a.size(); i++) // Use raw Python API here to avoid an extra, intermediate incref on the tuple item: - t[i + 1] = (int) Py_REFCNT(PyTuple_GET_ITEM(a.ptr(), static_cast(i))); + t[i + 1] = (int) Py_REFCNT(PyTuple_GET_ITEM(a.ptr(), static_cast(i))); return t; }); @@ -103,11 +123,17 @@ TEST_SUBMODULE(kwargs_and_defaults, m) { py::arg() = 3, "j"_a = 4, py::kw_only(), "k"_a = 5, "z"_a); m.def("kw_only_mixed", [](int i, int j) { return py::make_tuple(i, j); }, "i"_a, py::kw_only(), "j"_a); - m.def("kw_only_plus_more", [](int i, int j, int k, py::kwargs kwargs) { - return py::make_tuple(i, j, k, kwargs); }, - py::arg() /* positional */, py::arg("j") = -1 /* both */, py::kw_only(), py::arg("k") /* kw-only */); + m.def( + "kw_only_plus_more", + [](int i, int j, int k, const py::kwargs &kwargs) { + return py::make_tuple(i, j, k, kwargs); + }, + py::arg() /* positional */, + py::arg("j") = -1 /* both */, + py::kw_only(), + py::arg("k") /* kw-only */); - m.def("register_invalid_kw_only", [](py::module m) { + m.def("register_invalid_kw_only", [](py::module_ m) { m.def("bad_kw_only", [](int i, int j) { return py::make_tuple(i, j); }, py::kw_only(), py::arg() /* invalid unnamed argument */, "j"_a); }); @@ -137,6 +163,25 @@ TEST_SUBMODULE(kwargs_and_defaults, m) { // Make sure a class (not an instance) can be used as a default argument. // The return value doesn't matter, only that the module is importable. - m.def("class_default_argument", [](py::object a) { return py::repr(a); }, - "a"_a = py::module::import("decimal").attr("Decimal")); + m.def( + "class_default_argument", + [](py::object a) { return py::repr(std::move(a)); }, + "a"_a = py::module_::import("decimal").attr("Decimal")); + + // Initial implementation of kw_only was broken when used on a method/constructor before any + // other arguments + // https://github.com/pybind/pybind11/pull/3402#issuecomment-963341987 + + struct first_arg_kw_only {}; + py::class_(m, "first_arg_kw_only") + .def(py::init([](int) { return first_arg_kw_only(); }), + py::kw_only(), // This being before any args was broken + py::arg("i") = 0) + .def("method", [](first_arg_kw_only&, int, int) {}, + py::kw_only(), // and likewise here + py::arg("i") = 1, py::arg("j") = 2) + // Closely related: pos_only marker didn't show up properly when it was before any other + // arguments (although that is fairly useless in practice). + .def("pos_only", [](first_arg_kw_only&, int, int) {}, + py::pos_only{}, py::arg("i"), py::arg("j")); } diff --git a/pybind11/tests/test_kwargs_and_defaults.py b/pybind11/tests/test_kwargs_and_defaults.py index 2a81dbdc5..d61cf2aa5 100644 --- a/pybind11/tests/test_kwargs_and_defaults.py +++ b/pybind11/tests/test_kwargs_and_defaults.py @@ -2,7 +2,6 @@ import pytest import env # noqa: F401 - from pybind11_tests import kwargs_and_defaults as m @@ -15,11 +14,17 @@ def test_function_signatures(doc): assert doc(m.kw_func_udl) == "kw_func_udl(x: int, y: int = 300) -> str" assert doc(m.kw_func_udl_z) == "kw_func_udl_z(x: int, y: int = 0) -> str" assert doc(m.args_function) == "args_function(*args) -> tuple" - assert doc(m.args_kwargs_function) == "args_kwargs_function(*args, **kwargs) -> tuple" - assert doc(m.KWClass.foo0) == \ - "foo0(self: m.kwargs_and_defaults.KWClass, arg0: int, arg1: float) -> None" - assert doc(m.KWClass.foo1) == \ - "foo1(self: m.kwargs_and_defaults.KWClass, x: int, y: float) -> None" + assert ( + doc(m.args_kwargs_function) == "args_kwargs_function(*args, **kwargs) -> tuple" + ) + assert ( + doc(m.KWClass.foo0) + == "foo0(self: m.kwargs_and_defaults.KWClass, arg0: int, arg1: float) -> None" + ) + assert ( + doc(m.KWClass.foo1) + == "foo1(self: m.kwargs_and_defaults.KWClass, x: int, y: float) -> None" + ) def test_named_arguments(msg): @@ -40,7 +45,9 @@ def test_named_arguments(msg): # noinspection PyArgumentList m.kw_func2(x=5, y=10, z=12) assert excinfo.match( - r'(?s)^kw_func2\(\): incompatible.*Invoked with: kwargs: ((x=5|y=10|z=12)(, |$))' + '{3}$') + r"(?s)^kw_func2\(\): incompatible.*Invoked with: kwargs: ((x=5|y=10|z=12)(, |$))" + + "{3}$" + ) assert m.kw_func4() == "{13 17}" assert m.kw_func4(myList=[1, 2, 3]) == "{1 2 3}" @@ -50,11 +57,11 @@ def test_named_arguments(msg): def test_arg_and_kwargs(): - args = 'arg1_value', 'arg2_value', 3 + args = "arg1_value", "arg2_value", 3 assert m.args_function(*args) == args - args = 'a1', 'a2' - kwargs = dict(arg3='a3', arg4=4) + args = "a1", "a2" + kwargs = dict(arg3="a3", arg4=4) assert m.args_kwargs_function(*args, **kwargs) == (args, kwargs) @@ -68,47 +75,118 @@ def test_mixed_args_and_kwargs(msg): assert mpa(1, 2.5) == (1, 2.5, ()) with pytest.raises(TypeError) as excinfo: assert mpa(1) - assert msg(excinfo.value) == """ + assert ( + msg(excinfo.value) + == """ mixed_plus_args(): incompatible function arguments. The following argument types are supported: 1. (arg0: int, arg1: float, *args) -> tuple Invoked with: 1 """ # noqa: E501 line too long + ) with pytest.raises(TypeError) as excinfo: assert mpa() - assert msg(excinfo.value) == """ + assert ( + msg(excinfo.value) + == """ mixed_plus_args(): incompatible function arguments. The following argument types are supported: 1. (arg0: int, arg1: float, *args) -> tuple Invoked with: """ # noqa: E501 line too long + ) - assert mpk(-2, 3.5, pi=3.14159, e=2.71828) == (-2, 3.5, {'e': 2.71828, 'pi': 3.14159}) + assert mpk(-2, 3.5, pi=3.14159, e=2.71828) == ( + -2, + 3.5, + {"e": 2.71828, "pi": 3.14159}, + ) assert mpak(7, 7.7, 7.77, 7.777, 7.7777, minusseven=-7) == ( - 7, 7.7, (7.77, 7.777, 7.7777), {'minusseven': -7}) + 7, + 7.7, + (7.77, 7.777, 7.7777), + {"minusseven": -7}, + ) assert mpakd() == (1, 3.14159, (), {}) assert mpakd(3) == (3, 3.14159, (), {}) assert mpakd(j=2.71828) == (1, 2.71828, (), {}) - assert mpakd(k=42) == (1, 3.14159, (), {'k': 42}) + assert mpakd(k=42) == (1, 3.14159, (), {"k": 42}) assert mpakd(1, 1, 2, 3, 5, 8, then=13, followedby=21) == ( - 1, 1, (2, 3, 5, 8), {'then': 13, 'followedby': 21}) + 1, + 1, + (2, 3, 5, 8), + {"then": 13, "followedby": 21}, + ) # Arguments specified both positionally and via kwargs should fail: with pytest.raises(TypeError) as excinfo: assert mpakd(1, i=1) - assert msg(excinfo.value) == """ + assert ( + msg(excinfo.value) + == """ mixed_plus_args_kwargs_defaults(): incompatible function arguments. The following argument types are supported: 1. (i: int = 1, j: float = 3.14159, *args, **kwargs) -> tuple Invoked with: 1; kwargs: i=1 """ # noqa: E501 line too long + ) with pytest.raises(TypeError) as excinfo: assert mpakd(1, 2, j=1) - assert msg(excinfo.value) == """ + assert ( + msg(excinfo.value) + == """ mixed_plus_args_kwargs_defaults(): incompatible function arguments. The following argument types are supported: 1. (i: int = 1, j: float = 3.14159, *args, **kwargs) -> tuple Invoked with: 1, 2; kwargs: j=1 """ # noqa: E501 line too long + ) + + # Arguments after a py::args are automatically keyword-only (pybind 2.9+) + assert m.args_kwonly(2, 2.5, z=22) == (2, 2.5, (), 22) + assert m.args_kwonly(2, 2.5, "a", "b", "c", z=22) == (2, 2.5, ("a", "b", "c"), 22) + assert m.args_kwonly(z=22, i=4, j=16) == (4, 16, (), 22) + + with pytest.raises(TypeError) as excinfo: + assert m.args_kwonly(2, 2.5, 22) # missing z= keyword + assert ( + msg(excinfo.value) + == """ + args_kwonly(): incompatible function arguments. The following argument types are supported: + 1. (i: int, j: float, *args, z: int) -> tuple + + Invoked with: 2, 2.5, 22 + """ + ) + + assert m.args_kwonly_kwargs(i=1, k=4, j=10, z=-1, y=9) == ( + 1, + 10, + (), + -1, + {"k": 4, "y": 9}, + ) + assert m.args_kwonly_kwargs(1, 2, 3, 4, 5, 6, 7, 8, 9, 10, z=11, y=12) == ( + 1, + 2, + (3, 4, 5, 6, 7, 8, 9, 10), + 11, + {"y": 12}, + ) + assert ( + m.args_kwonly_kwargs.__doc__ + == "args_kwonly_kwargs(i: int, j: float, *args, z: int, **kwargs) -> tuple\n" + ) + + assert ( + m.args_kwonly_kwargs_defaults.__doc__ + == "args_kwonly_kwargs_defaults(i: int = 1, j: float = 3.14159, *args, z: int = 42, **kwargs) -> tuple\n" # noqa: E501 line too long + ) + assert m.args_kwonly_kwargs_defaults() == (1, 3.14159, (), 42, {}) + assert m.args_kwonly_kwargs_defaults(2) == (2, 3.14159, (), 42, {}) + assert m.args_kwonly_kwargs_defaults(z=-99) == (1, 3.14159, (), -99, {}) + assert m.args_kwonly_kwargs_defaults(5, 6, 7, 8) == (5, 6, (7, 8), 42, {}) + assert m.args_kwonly_kwargs_defaults(5, 6, 7, m=8) == (5, 6, (7,), 42, {"m": 8}) + assert m.args_kwonly_kwargs_defaults(5, 6, 7, m=8, z=9) == (5, 6, (7,), 9, {"m": 8}) def test_keyword_only_args(msg): @@ -134,9 +212,9 @@ def test_keyword_only_args(msg): assert m.kw_only_mixed(j=2, i=3) == (3, 2) assert m.kw_only_mixed(i=2, j=3) == (2, 3) - assert m.kw_only_plus_more(4, 5, k=6, extra=7) == (4, 5, 6, {'extra': 7}) - assert m.kw_only_plus_more(3, k=5, j=4, extra=6) == (3, 4, 5, {'extra': 6}) - assert m.kw_only_plus_more(2, k=3, extra=4) == (2, -1, 3, {'extra': 4}) + assert m.kw_only_plus_more(4, 5, k=6, extra=7) == (4, 5, 6, {"extra": 7}) + assert m.kw_only_plus_more(3, k=5, j=4, extra=6) == (3, 4, 5, {"extra": 6}) + assert m.kw_only_plus_more(2, k=3, extra=4) == (2, -1, 3, {"extra": 4}) with pytest.raises(TypeError) as excinfo: assert m.kw_only_mixed(i=1) == (1,) @@ -144,9 +222,25 @@ def test_keyword_only_args(msg): with pytest.raises(RuntimeError) as excinfo: m.register_invalid_kw_only(m) - assert msg(excinfo.value) == """ - arg(): cannot specify an unnamed argument after an kw_only() annotation + assert ( + msg(excinfo.value) + == """ + arg(): cannot specify an unnamed argument after a kw_only() annotation or args() argument """ + ) + + # https://github.com/pybind/pybind11/pull/3402#issuecomment-963341987 + x = m.first_arg_kw_only(i=1) + x.method() + x.method(i=1, j=2) + assert ( + m.first_arg_kw_only.__init__.__doc__ + == "__init__(self: pybind11_tests.kwargs_and_defaults.first_arg_kw_only, *, i: int = 0) -> None\n" # noqa: E501 line too long + ) + assert ( + m.first_arg_kw_only.method.__doc__ + == "method(self: pybind11_tests.kwargs_and_defaults.first_arg_kw_only, *, i: int = 1, j: int = 2) -> None\n" # noqa: E501 line too long + ) def test_positional_only_args(msg): @@ -188,13 +282,65 @@ def test_positional_only_args(msg): m.pos_only_def_mix(1, j=4) assert "incompatible function arguments" in str(excinfo.value) + # Mix it with args and kwargs: + assert ( + m.args_kwonly_full_monty.__doc__ + == "args_kwonly_full_monty(arg0: int = 1, arg1: int = 2, /, j: float = 3.14159, *args, z: int = 42, **kwargs) -> tuple\n" # noqa: E501 line too long + ) + assert m.args_kwonly_full_monty() == (1, 2, 3.14159, (), 42, {}) + assert m.args_kwonly_full_monty(8) == (8, 2, 3.14159, (), 42, {}) + assert m.args_kwonly_full_monty(8, 9) == (8, 9, 3.14159, (), 42, {}) + assert m.args_kwonly_full_monty(8, 9, 10) == (8, 9, 10.0, (), 42, {}) + assert m.args_kwonly_full_monty(3, 4, 5, 6, 7, m=8, z=9) == ( + 3, + 4, + 5.0, + ( + 6, + 7, + ), + 9, + {"m": 8}, + ) + assert m.args_kwonly_full_monty(3, 4, 5, 6, 7, m=8, z=9) == ( + 3, + 4, + 5.0, + ( + 6, + 7, + ), + 9, + {"m": 8}, + ) + assert m.args_kwonly_full_monty(5, j=7, m=8, z=9) == (5, 2, 7.0, (), 9, {"m": 8}) + assert m.args_kwonly_full_monty(i=5, j=7, m=8, z=9) == ( + 1, + 2, + 7.0, + (), + 9, + {"i": 5, "m": 8}, + ) + + # pos_only at the beginning of the argument list was "broken" in how it was displayed (though + # this is fairly useless in practice). Related to: + # https://github.com/pybind/pybind11/pull/3402#issuecomment-963341987 + assert ( + m.first_arg_kw_only.pos_only.__doc__ + == "pos_only(self: pybind11_tests.kwargs_and_defaults.first_arg_kw_only, /, i: int, j: int) -> None\n" # noqa: E501 line too long + ) + def test_signatures(): assert "kw_only_all(*, i: int, j: int) -> tuple\n" == m.kw_only_all.__doc__ assert "kw_only_mixed(i: int, *, j: int) -> tuple\n" == m.kw_only_mixed.__doc__ assert "pos_only_all(i: int, j: int, /) -> tuple\n" == m.pos_only_all.__doc__ assert "pos_only_mix(i: int, /, j: int) -> tuple\n" == m.pos_only_mix.__doc__ - assert "pos_kw_only_mix(i: int, /, j: int, *, k: int) -> tuple\n" == m.pos_kw_only_mix.__doc__ + assert ( + "pos_kw_only_mix(i: int, /, j: int, *, k: int) -> tuple\n" + == m.pos_kw_only_mix.__doc__ + ) @pytest.mark.xfail("env.PYPY and env.PY2", reason="PyPy2 doesn't double count") @@ -219,11 +365,18 @@ def test_args_refcount(): assert m.args_function(-1, myval) == (-1, myval) assert refcount(myval) == expected - assert m.mixed_plus_args_kwargs(5, 6.0, myval, a=myval) == (5, 6.0, (myval,), {"a": myval}) + assert m.mixed_plus_args_kwargs(5, 6.0, myval, a=myval) == ( + 5, + 6.0, + (myval,), + {"a": myval}, + ) assert refcount(myval) == expected - assert m.args_kwargs_function(7, 8, myval, a=1, b=myval) == \ - ((7, 8, myval), {"a": 1, "b": myval}) + assert m.args_kwargs_function(7, 8, myval, a=1, b=myval) == ( + (7, 8, myval), + {"a": 1, "b": myval}, + ) assert refcount(myval) == expected exp3 = refcount(myval, myval, myval) diff --git a/pybind11/tests/test_local_bindings.cpp b/pybind11/tests/test_local_bindings.cpp index 97c02dbeb..a5808e2f2 100644 --- a/pybind11/tests/test_local_bindings.cpp +++ b/pybind11/tests/test_local_bindings.cpp @@ -10,9 +10,12 @@ #include "pybind11_tests.h" #include "local_bindings.h" + #include #include + #include +#include TEST_SUBMODULE(local_bindings, m) { // test_load_external @@ -41,7 +44,7 @@ TEST_SUBMODULE(local_bindings, m) { // should raise a runtime error from the duplicate definition attempt. If test_class isn't // available it *also* throws a runtime error (with "test_class not enabled" as value). m.def("register_local_external", [m]() { - auto main = py::module::import("pybind11_tests"); + auto main = py::module_::import("pybind11_tests"); if (py::hasattr(main, "class_")) { bind_local(m, "LocalExternal", py::module_local()); } @@ -75,7 +78,7 @@ TEST_SUBMODULE(local_bindings, m) { m.def("get_mixed_lg", [](int i) { return MixedLocalGlobal(i); }); // test_internal_locals_differ - m.def("local_cpp_types_addr", []() { return (uintptr_t) &py::detail::registered_local_types_cpp(); }); + m.def("local_cpp_types_addr", []() { return (uintptr_t) &py::detail::get_local_internals().registered_types_cpp; }); // test_stl_caster_vs_stl_bind m.def("load_vector_via_caster", [](std::vector v) { @@ -86,7 +89,10 @@ TEST_SUBMODULE(local_bindings, m) { m.def("return_self", [](LocalVec *v) { return v; }); m.def("return_copy", [](const LocalVec &v) { return LocalVec(v); }); - class Cat : public pets::Pet { public: Cat(std::string name) : Pet(name) {}; }; + class Cat : public pets::Pet { + public: + explicit Cat(std::string name) : Pet(std::move(name)) {} + }; py::class_(m, "Pet", py::module_local()) .def("get_name", &pets::Pet::name); // Binding for local extending class: diff --git a/pybind11/tests/test_local_bindings.py b/pybind11/tests/test_local_bindings.py index 5460727e1..52b1b6335 100644 --- a/pybind11/tests/test_local_bindings.py +++ b/pybind11/tests/test_local_bindings.py @@ -2,7 +2,6 @@ import pytest import env # noqa: F401 - from pybind11_tests import local_bindings as m @@ -36,8 +35,8 @@ def test_local_bindings(): assert i2.get() == 11 assert i2.get2() == 12 - assert not hasattr(i1, 'get2') - assert not hasattr(i2, 'get3') + assert not hasattr(i1, "get2") + assert not hasattr(i2, "get3") # Loading within the local module assert m.local_value(i1) == 5 @@ -55,7 +54,9 @@ def test_nonlocal_failure(): with pytest.raises(RuntimeError) as excinfo: cm.register_nonlocal() - assert str(excinfo.value) == 'generic_type: type "NonLocalType" is already registered!' + assert ( + str(excinfo.value) == 'generic_type: type "NonLocalType" is already registered!' + ) def test_duplicate_local(): @@ -63,9 +64,12 @@ def test_duplicate_local(): with pytest.raises(RuntimeError) as excinfo: m.register_local_external() import pybind11_tests + assert str(excinfo.value) == ( 'generic_type: type "LocalExternal" is already registered!' - if hasattr(pybind11_tests, 'class_') else 'test_class not enabled') + if hasattr(pybind11_tests, "class_") + else "test_class not enabled" + ) def test_stl_bind_local(): @@ -98,8 +102,8 @@ def test_stl_bind_local(): d1["b"] = v1[1] d2["c"] = v2[0] d2["d"] = v2[1] - assert {i: d1[i].get() for i in d1} == {'a': 0, 'b': 1} - assert {i: d2[i].get() for i in d2} == {'c': 2, 'd': 3} + assert {i: d1[i].get() for i in d1} == {"a": 0, "b": 1} + assert {i: d2[i].get() for i in d2} == {"c": 2, "d": 3} def test_stl_bind_global(): @@ -107,15 +111,21 @@ def test_stl_bind_global(): with pytest.raises(RuntimeError) as excinfo: cm.register_nonlocal_map() - assert str(excinfo.value) == 'generic_type: type "NonLocalMap" is already registered!' + assert ( + str(excinfo.value) == 'generic_type: type "NonLocalMap" is already registered!' + ) with pytest.raises(RuntimeError) as excinfo: cm.register_nonlocal_vec() - assert str(excinfo.value) == 'generic_type: type "NonLocalVec" is already registered!' + assert ( + str(excinfo.value) == 'generic_type: type "NonLocalVec" is already registered!' + ) with pytest.raises(RuntimeError) as excinfo: cm.register_nonlocal_map2() - assert str(excinfo.value) == 'generic_type: type "NonLocalMap2" is already registered!' + assert ( + str(excinfo.value) == 'generic_type: type "NonLocalMap2" is already registered!' + ) def test_mixed_local_global(): @@ -123,6 +133,7 @@ def test_mixed_local_global(): type can be registered even if the type is already registered globally. With the module, casting will go to the local type; outside the module casting goes to the global type.""" import pybind11_cross_module_tests as cm + m.register_mixed_global() m.register_mixed_local() @@ -145,17 +156,30 @@ def test_mixed_local_global(): a.append(cm.get_mixed_gl(11)) a.append(cm.get_mixed_lg(12)) - assert [x.get() for x in a] == \ - [101, 1002, 103, 1004, 105, 1006, 207, 2008, 109, 1010, 211, 2012] + assert [x.get() for x in a] == [ + 101, + 1002, + 103, + 1004, + 105, + 1006, + 207, + 2008, + 109, + 1010, + 211, + 2012, + ] def test_internal_locals_differ(): """Makes sure the internal local type map differs across the two modules""" import pybind11_cross_module_tests as cm + assert m.local_cpp_types_addr() != cm.local_cpp_types_addr() -@pytest.mark.xfail("env.PYPY") +@pytest.mark.xfail("env.PYPY and sys.pypy_version_info < (7, 3, 2)") def test_stl_caster_vs_stl_bind(msg): """One module uses a generic vector caster from `` while the other exports `std::vector` via `py:bind_vector` and `py::module_local`""" @@ -168,13 +192,16 @@ def test_stl_caster_vs_stl_bind(msg): v2 = [1, 2, 3] assert m.load_vector_via_caster(v2) == 6 with pytest.raises(TypeError) as excinfo: - cm.load_vector_via_binding(v2) == 6 - assert msg(excinfo.value) == """ + cm.load_vector_via_binding(v2) + assert ( + msg(excinfo.value) + == """ load_vector_via_binding(): incompatible function arguments. The following argument types are supported: 1. (arg0: pybind11_cross_module_tests.VectorInt) -> int Invoked with: [1, 2, 3] """ # noqa: E501 line too long + ) def test_cross_module_calls(): diff --git a/pybind11/tests/test_methods_and_attributes.cpp b/pybind11/tests/test_methods_and_attributes.cpp index 11d4e7b35..9e55452de 100644 --- a/pybind11/tests/test_methods_and_attributes.cpp +++ b/pybind11/tests/test_methods_and_attributes.cpp @@ -19,19 +19,21 @@ using overload_cast_ = pybind11::detail::overload_cast_impl; class ExampleMandA { public: ExampleMandA() { print_default_created(this); } - ExampleMandA(int value) : value(value) { print_created(this, value); } + explicit ExampleMandA(int value) : value(value) { print_created(this, value); } ExampleMandA(const ExampleMandA &e) : value(e.value) { print_copy_created(this); } - ExampleMandA(std::string&&) {} - ExampleMandA(ExampleMandA &&e) : value(e.value) { print_move_created(this); } + explicit ExampleMandA(std::string &&) {} + ExampleMandA(ExampleMandA &&e) noexcept : value(e.value) { print_move_created(this); } ~ExampleMandA() { print_destroyed(this); } - std::string toString() { - return "ExampleMandA[value=" + std::to_string(value) + "]"; - } + std::string toString() const { return "ExampleMandA[value=" + std::to_string(value) + "]"; } void operator=(const ExampleMandA &e) { print_copy_assigned(this); value = e.value; } - void operator=(ExampleMandA &&e) { print_move_assigned(this); value = e.value; } + void operator=(ExampleMandA &&e) noexcept { + print_move_assigned(this); + value = e.value; + } + // NOLINTNEXTLINE(performance-unnecessary-value-param) void add1(ExampleMandA other) { value += other.value; } // passing by value void add2(ExampleMandA &other) { value += other.value; } // passing by reference void add3(const ExampleMandA &other) { value += other.value; } // passing by const reference @@ -41,6 +43,7 @@ public: void add6(int other) { value += other; } // passing by value void add7(int &other) { value += other; } // passing by reference void add8(const int &other) { value += other; } // passing by const reference + // NOLINTNEXTLINE(readability-non-const-parameter) Deliberately non-const for testing void add9(int *other) { value += *other; } // passing by pointer void add10(const int *other) { value += *other; } // passing by const pointer @@ -48,13 +51,13 @@ public: ExampleMandA self1() { return *this; } // return by value ExampleMandA &self2() { return *this; } // return by reference - const ExampleMandA &self3() { return *this; } // return by const reference + const ExampleMandA &self3() const { return *this; } // return by const reference ExampleMandA *self4() { return this; } // return by pointer - const ExampleMandA *self5() { return this; } // return by const pointer + const ExampleMandA *self5() const { return this; } // return by const pointer - int internal1() { return value; } // return by value + int internal1() const { return value; } // return by value int &internal2() { return value; } // return by reference - const int &internal3() { return value; } // return by const reference + const int &internal3() const { return value; } // return by const reference int *internal4() { return &value; } // return by pointer const int *internal5() { return &value; } // return by const pointer @@ -114,13 +117,21 @@ int none1(const NoneTester &obj) { return obj.answer; } int none2(NoneTester *obj) { return obj ? obj->answer : -1; } int none3(std::shared_ptr &obj) { return obj ? obj->answer : -1; } int none4(std::shared_ptr *obj) { return obj && *obj ? (*obj)->answer : -1; } -int none5(std::shared_ptr obj) { return obj ? obj->answer : -1; } +int none5(const std::shared_ptr &obj) { return obj ? obj->answer : -1; } + +// Issue #2778: implicit casting from None to object (not pointer) +class NoneCastTester { +public: + int answer = -1; + NoneCastTester() = default; + explicit NoneCastTester(int v) : answer(v) {} +}; struct StrIssue { int val = -1; StrIssue() = default; - StrIssue(int i) : val{i} {} + explicit StrIssue(int i) : val{i} {} }; // Issues #854, #910: incompatible function args when member function/pointer is in unregistered base class @@ -148,6 +159,14 @@ struct RefQualified { int constRefQualified(int other) const & { return value + other; } }; +// Test rvalue ref param +struct RValueRefParam { + std::size_t func1(std::string&& s) { return s.size(); } + std::size_t func2(std::string&& s) const { return s.size(); } + std::size_t func3(std::string&& s) & { return s.size(); } + std::size_t func4(std::string&& s) const & { return s.size(); } +}; + TEST_SUBMODULE(methods_and_attributes, m) { // test_methods_and_attributes py::class_ emna(m, "ExampleMandA"); @@ -207,12 +226,12 @@ TEST_SUBMODULE(methods_and_attributes, m) { // test_no_mixed_overloads // Raise error if trying to mix static/non-static overloads on the same name: .def_static("add_mixed_overloads1", []() { - auto emna = py::reinterpret_borrow>(py::module::import("pybind11_tests.methods_and_attributes").attr("ExampleMandA")); + auto emna = py::reinterpret_borrow>(py::module_::import("pybind11_tests.methods_and_attributes").attr("ExampleMandA")); emna.def ("overload_mixed1", static_cast(&ExampleMandA::overloaded)) .def_static("overload_mixed1", static_cast(&ExampleMandA::overloaded)); }) .def_static("add_mixed_overloads2", []() { - auto emna = py::reinterpret_borrow>(py::module::import("pybind11_tests.methods_and_attributes").attr("ExampleMandA")); + auto emna = py::reinterpret_borrow>(py::module_::import("pybind11_tests.methods_and_attributes").attr("ExampleMandA")); emna.def_static("overload_mixed2", static_cast(&ExampleMandA::overloaded)) .def ("overload_mixed2", static_cast(&ExampleMandA::overloaded)); }) @@ -228,36 +247,41 @@ TEST_SUBMODULE(methods_and_attributes, m) { .def(py::init<>()) .def_readonly("def_readonly", &TestProperties::value) .def_readwrite("def_readwrite", &TestProperties::value) - .def_property("def_writeonly", nullptr, - [](TestProperties& s,int v) { s.value = v; } ) + .def_property("def_writeonly", nullptr, [](TestProperties &s, int v) { s.value = v; }) .def_property("def_property_writeonly", nullptr, &TestProperties::set) .def_property_readonly("def_property_readonly", &TestProperties::get) .def_property("def_property", &TestProperties::get, &TestProperties::set) .def_property("def_property_impossible", nullptr, nullptr) .def_readonly_static("def_readonly_static", &TestProperties::static_value) .def_readwrite_static("def_readwrite_static", &TestProperties::static_value) - .def_property_static("def_writeonly_static", nullptr, - [](py::object, int v) { TestProperties::static_value = v; }) - .def_property_readonly_static("def_property_readonly_static", - [](py::object) { return TestProperties::static_get(); }) - .def_property_static("def_property_writeonly_static", nullptr, - [](py::object, int v) { return TestProperties::static_set(v); }) - .def_property_static("def_property_static", - [](py::object) { return TestProperties::static_get(); }, - [](py::object, int v) { TestProperties::static_set(v); }) - .def_property_static("static_cls", - [](py::object cls) { return cls; }, - [](py::object cls, py::function f) { f(cls); }); + .def_property_static("def_writeonly_static", + nullptr, + [](const py::object &, int v) { TestProperties::static_value = v; }) + .def_property_readonly_static( + "def_property_readonly_static", + [](const py::object &) { return TestProperties::static_get(); }) + .def_property_static( + "def_property_writeonly_static", + nullptr, + [](const py::object &, int v) { return TestProperties::static_set(v); }) + .def_property_static( + "def_property_static", + [](const py::object &) { return TestProperties::static_get(); }, + [](const py::object &, int v) { TestProperties::static_set(v); }) + .def_property_static( + "static_cls", + [](py::object cls) { return cls; }, + [](const py::object &cls, const py::function &f) { f(cls); }); py::class_(m, "TestPropertiesOverride") .def(py::init<>()) .def_readonly("def_readonly", &TestPropertiesOverride::value) .def_readonly_static("def_readonly_static", &TestPropertiesOverride::static_value); - auto static_get1 = [](py::object) -> const UserType & { return TestPropRVP::sv1; }; - auto static_get2 = [](py::object) -> const UserType & { return TestPropRVP::sv2; }; - auto static_set1 = [](py::object, int v) { TestPropRVP::sv1.set(v); }; - auto static_set2 = [](py::object, int v) { TestPropRVP::sv2.set(v); }; + auto static_get1 = [](const py::object &) -> const UserType & { return TestPropRVP::sv1; }; + auto static_get2 = [](const py::object &) -> const UserType & { return TestPropRVP::sv2; }; + auto static_set1 = [](const py::object &, int v) { TestPropRVP::sv1.set(v); }; + auto static_set2 = [](const py::object &, int v) { TestPropRVP::sv2.set(v); }; auto rvp_copy = py::return_value_policy::copy; // test_property_return_value_policies @@ -268,21 +292,30 @@ TEST_SUBMODULE(methods_and_attributes, m) { .def_property_readonly("ro_func", py::cpp_function(&TestPropRVP::get2, rvp_copy)) .def_property("rw_ref", &TestPropRVP::get1, &TestPropRVP::set1) .def_property("rw_copy", &TestPropRVP::get2, &TestPropRVP::set2, rvp_copy) - .def_property("rw_func", py::cpp_function(&TestPropRVP::get2, rvp_copy), &TestPropRVP::set2) + .def_property( + "rw_func", py::cpp_function(&TestPropRVP::get2, rvp_copy), &TestPropRVP::set2) .def_property_readonly_static("static_ro_ref", static_get1) .def_property_readonly_static("static_ro_copy", static_get2, rvp_copy) .def_property_readonly_static("static_ro_func", py::cpp_function(static_get2, rvp_copy)) .def_property_static("static_rw_ref", static_get1, static_set1) .def_property_static("static_rw_copy", static_get2, static_set2, rvp_copy) - .def_property_static("static_rw_func", py::cpp_function(static_get2, rvp_copy), static_set2) + .def_property_static( + "static_rw_func", py::cpp_function(static_get2, rvp_copy), static_set2) // test_property_rvalue_policy .def_property_readonly("rvalue", &TestPropRVP::get_rvalue) - .def_property_readonly_static("static_rvalue", [](py::object) { return UserType(1); }); + .def_property_readonly_static("static_rvalue", + [](const py::object &) { return UserType(1); }); // test_metaclass_override struct MetaclassOverride { }; py::class_(m, "MetaclassOverride", py::metaclass((PyObject *) &PyType_Type)) - .def_property_readonly_static("readonly", [](py::object) { return 1; }); + .def_property_readonly_static("readonly", [](const py::object &) { return 1; }); + + // test_overload_ordering + m.def("overload_order", [](const std::string &) { return 1; }); + m.def("overload_order", [](const std::string &) { return 2; }); + m.def("overload_order", [](int) { return 3; }); + m.def("overload_order", [](int) { return 4; }, py::prepend{}); #if !defined(PYPY_VERSION) // test_dynamic_attributes @@ -308,28 +341,43 @@ TEST_SUBMODULE(methods_and_attributes, m) { m.attr("debug_enabled") = false; #endif m.def("bad_arg_def_named", []{ - auto m = py::module::import("pybind11_tests"); + auto m = py::module_::import("pybind11_tests"); m.def("should_fail", [](int, UnregisteredType) {}, py::arg(), py::arg("a") = UnregisteredType()); }); m.def("bad_arg_def_unnamed", []{ - auto m = py::module::import("pybind11_tests"); + auto m = py::module_::import("pybind11_tests"); m.def("should_fail", [](int, UnregisteredType) {}, py::arg(), py::arg() = UnregisteredType()); }); + // [workaround(intel)] ICC 20/21 breaks with py::arg().stuff, using py::arg{}.stuff works. + // test_accepts_none py::class_>(m, "NoneTester") .def(py::init<>()); - m.def("no_none1", &none1, py::arg().none(false)); - m.def("no_none2", &none2, py::arg().none(false)); - m.def("no_none3", &none3, py::arg().none(false)); - m.def("no_none4", &none4, py::arg().none(false)); - m.def("no_none5", &none5, py::arg().none(false)); + m.def("no_none1", &none1, py::arg{}.none(false)); + m.def("no_none2", &none2, py::arg{}.none(false)); + m.def("no_none3", &none3, py::arg{}.none(false)); + m.def("no_none4", &none4, py::arg{}.none(false)); + m.def("no_none5", &none5, py::arg{}.none(false)); m.def("ok_none1", &none1); - m.def("ok_none2", &none2, py::arg().none(true)); + m.def("ok_none2", &none2, py::arg{}.none(true)); m.def("ok_none3", &none3); - m.def("ok_none4", &none4, py::arg().none(true)); + m.def("ok_none4", &none4, py::arg{}.none(true)); m.def("ok_none5", &none5); + m.def("no_none_kwarg", &none2, "a"_a.none(false)); + m.def("no_none_kwarg_kw_only", &none2, py::kw_only(), "a"_a.none(false)); + + // test_casts_none + // Issue #2778: implicit casting from None to object (not pointer) + py::class_(m, "NoneCastTester") + .def(py::init<>()) + .def(py::init()) + .def(py::init([](py::none const&) { return NoneCastTester{}; })); + py::implicitly_convertible(); + m.def("ok_obj_or_none", [](NoneCastTester const& foo) { return foo.answer; }); + + // test_str_issue // Issue #283: __str__ called on uninitialized instance when constructor arguments invalid py::class_(m, "StrIssue") @@ -351,14 +399,14 @@ TEST_SUBMODULE(methods_and_attributes, m) { .def("increase_value", &RegisteredDerived::increase_value) .def_readwrite("rw_value", &RegisteredDerived::rw_value) .def_readonly("ro_value", &RegisteredDerived::ro_value) - // These should trigger a static_assert if uncommented - //.def_readwrite("fails", &UserType::value) // should trigger a static_assert if uncommented - //.def_readonly("fails", &UserType::value) // should trigger a static_assert if uncommented + // Uncommenting the next line should trigger a static_assert: + // .def_readwrite("fails", &UserType::value) + // Uncommenting the next line should trigger a static_assert: + // .def_readonly("fails", &UserType::value) .def_property("rw_value_prop", &RegisteredDerived::get_int, &RegisteredDerived::set_int) .def_property_readonly("ro_value_prop", &RegisteredDerived::get_double) // This one is in the registered class: - .def("sum", &RegisteredDerived::sum) - ; + .def("sum", &RegisteredDerived::sum); using Adapted = decltype(py::method_adaptor(&RegisteredDerived::do_nothing)); static_assert(std::is_same::value, ""); @@ -369,4 +417,11 @@ TEST_SUBMODULE(methods_and_attributes, m) { .def_readonly("value", &RefQualified::value) .def("refQualified", &RefQualified::refQualified) .def("constRefQualified", &RefQualified::constRefQualified); + + py::class_(m, "RValueRefParam") + .def(py::init<>()) + .def("func1", &RValueRefParam::func1) + .def("func2", &RValueRefParam::func2) + .def("func3", &RValueRefParam::func3) + .def("func4", &RValueRefParam::func4); } diff --git a/pybind11/tests/test_methods_and_attributes.py b/pybind11/tests/test_methods_and_attributes.py index c296b6868..fa026f9ed 100644 --- a/pybind11/tests/test_methods_and_attributes.py +++ b/pybind11/tests/test_methods_and_attributes.py @@ -2,9 +2,8 @@ import pytest import env # noqa: F401 - -from pybind11_tests import methods_and_attributes as m from pybind11_tests import ConstructorStats +from pybind11_tests import methods_and_attributes as m def test_methods_and_attributes(): @@ -40,17 +39,17 @@ def test_methods_and_attributes(): assert instance1.overloaded(0) == "(int)" assert instance1.overloaded(1, 1.0) == "(int, float)" assert instance1.overloaded(2.0, 2) == "(float, int)" - assert instance1.overloaded(3, 3) == "(int, int)" - assert instance1.overloaded(4., 4.) == "(float, float)" + assert instance1.overloaded(3, 3) == "(int, int)" + assert instance1.overloaded(4.0, 4.0) == "(float, float)" assert instance1.overloaded_const(-3) == "(int) const" assert instance1.overloaded_const(5, 5.0) == "(int, float) const" assert instance1.overloaded_const(6.0, 6) == "(float, int) const" - assert instance1.overloaded_const(7, 7) == "(int, int) const" - assert instance1.overloaded_const(8., 8.) == "(float, float) const" + assert instance1.overloaded_const(7, 7) == "(int, int) const" + assert instance1.overloaded_const(8.0, 8.0) == "(float, float) const" assert instance1.overloaded_float(1, 1) == "(float, float)" - assert instance1.overloaded_float(1, 1.) == "(float, float)" - assert instance1.overloaded_float(1., 1) == "(float, float)" - assert instance1.overloaded_float(1., 1.) == "(float, float)" + assert instance1.overloaded_float(1, 1.0) == "(float, float)" + assert instance1.overloaded_float(1.0, 1) == "(float, float)" + assert instance1.overloaded_float(1.0, 1.0) == "(float, float)" assert instance1.value == 320 instance1.value = 100 @@ -103,7 +102,7 @@ def test_properties(): assert instance.def_property == 3 with pytest.raises(AttributeError) as excinfo: - dummy = instance.def_property_writeonly # noqa: F841 unused var + dummy = instance.def_property_writeonly # unused var assert "unreadable attribute" in str(excinfo.value) instance.def_property_writeonly = 4 @@ -128,7 +127,7 @@ def test_static_properties(): assert m.TestProperties.def_readwrite_static == 2 with pytest.raises(AttributeError) as excinfo: - dummy = m.TestProperties.def_writeonly_static # noqa: F841 unused var + dummy = m.TestProperties.def_writeonly_static # unused var assert "unreadable attribute" in str(excinfo.value) m.TestProperties.def_writeonly_static = 3 @@ -171,6 +170,19 @@ def test_static_properties(): assert m.TestPropertiesOverride().def_readonly == 99 assert m.TestPropertiesOverride.def_readonly_static == 99 + # Only static attributes can be deleted + del m.TestPropertiesOverride.def_readonly_static + assert ( + hasattr(m.TestPropertiesOverride, "def_readonly_static") + and m.TestPropertiesOverride.def_readonly_static + is m.TestProperties.def_readonly_static + ) + assert "def_readonly_static" not in m.TestPropertiesOverride.__dict__ + properties_override = m.TestPropertiesOverride() + with pytest.raises(AttributeError) as excinfo: + del properties_override.def_readonly + assert "can't delete attribute" in str(excinfo.value) + def test_static_cls(): """Static property getter and setters expect the type object as the their only argument""" @@ -193,7 +205,10 @@ def test_metaclass_override(): assert type(m.MetaclassOverride).__name__ == "type" assert m.MetaclassOverride.readonly == 1 - assert type(m.MetaclassOverride.__dict__["readonly"]).__name__ == "pybind11_static_property" + assert ( + type(m.MetaclassOverride.__dict__["readonly"]).__name__ + == "pybind11_static_property" + ) # Regular `type` replaces the property instead of calling `__set__()` m.MetaclassOverride.readonly = 2 @@ -206,22 +221,26 @@ def test_no_mixed_overloads(): with pytest.raises(RuntimeError) as excinfo: m.ExampleMandA.add_mixed_overloads1() - assert (str(excinfo.value) == - "overloading a method with both static and instance methods is not supported; " + - ("compile in debug mode for more details" if not debug_enabled else - "error while attempting to bind static method ExampleMandA.overload_mixed1" - "(arg0: float) -> str") - ) + assert str( + excinfo.value + ) == "overloading a method with both static and instance methods is not supported; " + ( + "compile in debug mode for more details" + if not debug_enabled + else "error while attempting to bind static method ExampleMandA.overload_mixed1" + "(arg0: float) -> str" + ) with pytest.raises(RuntimeError) as excinfo: m.ExampleMandA.add_mixed_overloads2() - assert (str(excinfo.value) == - "overloading a method with both static and instance methods is not supported; " + - ("compile in debug mode for more details" if not debug_enabled else - "error while attempting to bind instance method ExampleMandA.overload_mixed2" - "(self: pybind11_tests.methods_and_attributes.ExampleMandA, arg0: int, arg1: int)" - " -> str") - ) + assert str( + excinfo.value + ) == "overloading a method with both static and instance methods is not supported; " + ( + "compile in debug mode for more details" + if not debug_enabled + else "error while attempting to bind instance method ExampleMandA.overload_mixed2" + "(self: pybind11_tests.methods_and_attributes.ExampleMandA, arg0: int, arg1: int)" + " -> str" + ) @pytest.mark.parametrize("access", ["ro", "rw", "static_ro", "static_rw"]) @@ -333,8 +352,8 @@ def test_bad_arg_default(msg): assert msg(excinfo.value) == ( "arg(): could not convert default argument 'a: UnregisteredType' in function " "'should_fail' into a Python object (type not registered yet?)" - if debug_enabled else - "arg(): could not convert default argument into a Python object (type not registered " + if debug_enabled + else "arg(): could not convert default argument into a Python object (type not registered " "yet?). Compile in debug mode for more information." ) @@ -343,8 +362,8 @@ def test_bad_arg_default(msg): assert msg(excinfo.value) == ( "arg(): could not convert default argument 'UnregisteredType' in function " "'should_fail' into a Python object (type not registered yet?)" - if debug_enabled else - "arg(): could not convert default argument into a Python object (type not registered " + if debug_enabled + else "arg(): could not convert default argument into a Python object (type not registered " "yet?). Compile in debug mode for more information." ) @@ -381,12 +400,15 @@ def test_accepts_none(msg): # The first one still raises because you can't pass None as a lvalue reference arg: with pytest.raises(TypeError) as excinfo: assert m.ok_none1(None) == -1 - assert msg(excinfo.value) == """ + assert ( + msg(excinfo.value) + == """ ok_none1(): incompatible function arguments. The following argument types are supported: 1. (arg0: m.methods_and_attributes.NoneTester) -> int Invoked with: None """ + ) # The rest take the argument as pointer or holder, and accept None: assert m.ok_none2(None) == -1 @@ -394,6 +416,30 @@ def test_accepts_none(msg): assert m.ok_none4(None) == -1 assert m.ok_none5(None) == -1 + with pytest.raises(TypeError) as excinfo: + m.no_none_kwarg(None) + assert "incompatible function arguments" in str(excinfo.value) + with pytest.raises(TypeError) as excinfo: + m.no_none_kwarg(a=None) + assert "incompatible function arguments" in str(excinfo.value) + with pytest.raises(TypeError) as excinfo: + m.no_none_kwarg_kw_only(None) + assert "incompatible function arguments" in str(excinfo.value) + with pytest.raises(TypeError) as excinfo: + m.no_none_kwarg_kw_only(a=None) + assert "incompatible function arguments" in str(excinfo.value) + + +def test_casts_none(): + """#2778: implicit casting from None to object (not pointer)""" + a = m.NoneCastTester() + assert m.ok_obj_or_none(a) == -1 + a = m.NoneCastTester(4) + assert m.ok_obj_or_none(a) == 4 + a = m.NoneCastTester(None) + assert m.ok_obj_or_none(a) == -1 + assert m.ok_obj_or_none(None) == -1 + def test_str_issue(msg): """#283: __str__ called on uninitialized instance when constructor arguments invalid""" @@ -402,13 +448,16 @@ def test_str_issue(msg): with pytest.raises(TypeError) as excinfo: str(m.StrIssue("no", "such", "constructor")) - assert msg(excinfo.value) == """ + assert ( + msg(excinfo.value) + == """ __init__(): incompatible constructor arguments. The following argument types are supported: 1. m.methods_and_attributes.StrIssue(arg0: int) 2. m.methods_and_attributes.StrIssue() Invoked with: 'no', 'such', 'constructor' """ + ) def test_unregistered_base_implementations(): @@ -438,3 +487,39 @@ def test_ref_qualified(): r.refQualified(17) assert r.value == 17 assert r.constRefQualified(23) == 40 + + +def test_overload_ordering(): + "Check to see if the normal overload order (first defined) and prepend overload order works" + assert m.overload_order("string") == 1 + assert m.overload_order(0) == 4 + + # Different for Python 2 vs. 3 + uni_name = type(u"").__name__ + + assert "1. overload_order(arg0: int) -> int" in m.overload_order.__doc__ + assert ( + "2. overload_order(arg0: {}) -> int".format(uni_name) + in m.overload_order.__doc__ + ) + assert ( + "3. overload_order(arg0: {}) -> int".format(uni_name) + in m.overload_order.__doc__ + ) + assert "4. overload_order(arg0: int) -> int" in m.overload_order.__doc__ + + with pytest.raises(TypeError) as err: + m.overload_order(1.1) + + assert "1. (arg0: int) -> int" in str(err.value) + assert "2. (arg0: {}) -> int".format(uni_name) in str(err.value) + assert "3. (arg0: {}) -> int".format(uni_name) in str(err.value) + assert "4. (arg0: int) -> int" in str(err.value) + + +def test_rvalue_ref_param(): + r = m.RValueRefParam() + assert r.func1("123") == 3 + assert r.func2("1234") == 4 + assert r.func3("12345") == 5 + assert r.func4("123456") == 6 diff --git a/pybind11/tests/test_modules.cpp b/pybind11/tests/test_modules.cpp index c1475fa62..ce61c1a25 100644 --- a/pybind11/tests/test_modules.cpp +++ b/pybind11/tests/test_modules.cpp @@ -13,17 +13,19 @@ TEST_SUBMODULE(modules, m) { // test_nested_modules + // This is intentionally "py::module" to verify it still can be used in place of "py::module_" py::module m_sub = m.def_submodule("subsubmodule"); m_sub.def("submodule_func", []() { return "submodule_func()"; }); // test_reference_internal class A { public: - A(int v) : v(v) { print_created(this, v); } + explicit A(int v) : v(v) { print_created(this, v); } ~A() { print_destroyed(this); } A(const A&) { print_copy_created(this); } A& operator=(const A ©) { print_copy_assigned(this); v = copy.v; return *this; } - std::string toString() { return "A[" + std::to_string(v) + "]"; } + std::string toString() const { return "A[" + std::to_string(v) + "]"; } + private: int v; }; @@ -50,6 +52,7 @@ TEST_SUBMODULE(modules, m) { .def_readwrite("a1", &B::a1) // def_readonly uses an internal reference return policy by default .def_readwrite("a2", &B::a2); + // This is intentionally "py::module" to verify it still can be used in place of "py::module_" m.attr("OD") = py::module::import("collections").attr("OrderedDict"); // test_duplicate_registration @@ -60,7 +63,8 @@ TEST_SUBMODULE(modules, m) { class Dupe3 { }; class DupeException { }; - auto dm = py::module("dummy"); + // Go ahead and leak, until we have a non-leaking py::module_ constructor + auto dm = py::module_::create_extension_module("dummy", nullptr, new py::module_::module_def); auto failures = py::list(); py::class_(dm, "Dupe1"); diff --git a/pybind11/tests/test_modules.py b/pybind11/tests/test_modules.py index 7e2100524..49e1ea5e3 100644 --- a/pybind11/tests/test_modules.py +++ b/pybind11/tests/test_modules.py @@ -1,14 +1,18 @@ # -*- coding: utf-8 -*- +from pybind11_tests import ConstructorStats from pybind11_tests import modules as m from pybind11_tests.modules import subsubmodule as ms -from pybind11_tests import ConstructorStats def test_nested_modules(): import pybind11_tests + assert pybind11_tests.__name__ == "pybind11_tests" assert pybind11_tests.modules.__name__ == "pybind11_tests.modules" - assert pybind11_tests.modules.subsubmodule.__name__ == "pybind11_tests.modules.subsubmodule" + assert ( + pybind11_tests.modules.subsubmodule.__name__ + == "pybind11_tests.modules.subsubmodule" + ) assert m.__name__ == "pybind11_tests.modules" assert ms.__name__ == "pybind11_tests.modules.subsubmodule" @@ -35,7 +39,7 @@ def test_reference_internal(): del b assert astats.alive() == 0 assert bstats.alive() == 0 - assert astats.values() == ['1', '2', '42', '43'] + assert astats.values() == ["1", "2", "42", "43"] assert bstats.values() == [] assert astats.default_constructions == 0 assert bstats.default_constructions == 1 @@ -50,18 +54,20 @@ def test_reference_internal(): def test_importing(): - from pybind11_tests.modules import OD from collections import OrderedDict + from pybind11_tests.modules import OD + assert OD is OrderedDict - assert str(OD([(1, 'a'), (2, 'b')])) == "OrderedDict([(1, 'a'), (2, 'b')])" + assert str(OD([(1, "a"), (2, "b")])) == "OrderedDict([(1, 'a'), (2, 'b')])" def test_pydoc(): """Pydoc needs to be able to provide help() for everything inside a pybind11 module""" - import pybind11_tests import pydoc + import pybind11_tests + assert pybind11_tests.__name__ == "pybind11_tests" assert pybind11_tests.__doc__ == "pybind11 test module" assert pydoc.text.docmodule(pybind11_tests) @@ -71,3 +77,16 @@ def test_duplicate_registration(): """Registering two things with the same name""" assert m.duplicate_registration() == [] + + +def test_builtin_key_type(): + """Test that all the keys in the builtin modules have type str. + + Previous versions of pybind11 would add a unicode key in python 2. + """ + if hasattr(__builtins__, "keys"): + keys = __builtins__.keys() + else: # this is to make pypy happy since builtins is different there. + keys = __builtins__.__dict__.keys() + + assert {type(k) for k in keys} == {str} diff --git a/pybind11/tests/test_multiple_inheritance.cpp b/pybind11/tests/test_multiple_inheritance.cpp index 70e341785..4689df4e4 100644 --- a/pybind11/tests/test_multiple_inheritance.cpp +++ b/pybind11/tests/test_multiple_inheritance.cpp @@ -11,10 +11,12 @@ #include "pybind11_tests.h" #include "constructor_stats.h" +namespace { + // Many bases for testing that multiple inheritance from many classes (i.e. requiring extra // space for holder constructed flags) works. template struct BaseN { - BaseN(int i) : i(i) { } + explicit BaseN(int i) : i(i) {} int i; }; @@ -43,13 +45,40 @@ int WithStatic2::static_value2 = 2; int VanillaStaticMix1::static_value = 12; int VanillaStaticMix2::static_value = 12; +// test_multiple_inheritance_virtbase +struct Base1a { + explicit Base1a(int i) : i(i) {} + int foo() const { return i; } + int i; +}; +struct Base2a { + explicit Base2a(int i) : i(i) {} + int bar() const { return i; } + int i; +}; +struct Base12a : Base1a, Base2a { + Base12a(int i, int j) : Base1a(i), Base2a(j) { } +}; + +// test_mi_unaligned_base +// test_mi_base_return +struct I801B1 { int a = 1; I801B1() = default; I801B1(const I801B1 &) = default; virtual ~I801B1() = default; }; +struct I801B2 { int b = 2; I801B2() = default; I801B2(const I801B2 &) = default; virtual ~I801B2() = default; }; +struct I801C : I801B1, I801B2 {}; +struct I801D : I801C {}; // Indirect MI + +} // namespace + TEST_SUBMODULE(multiple_inheritance, m) { + // Please do not interleave `struct` and `class` definitions with bindings code, + // but implement `struct`s and `class`es in the anonymous namespace above. + // This helps keeping the smart_holder branch in sync with master. // test_multiple_inheritance_mix1 // test_multiple_inheritance_mix2 struct Base1 { - Base1(int i) : i(i) { } - int foo() { return i; } + explicit Base1(int i) : i(i) {} + int foo() const { return i; } int i; }; py::class_ b1(m, "Base1"); @@ -57,8 +86,8 @@ TEST_SUBMODULE(multiple_inheritance, m) { .def("foo", &Base1::foo); struct Base2 { - Base2(int i) : i(i) { } - int bar() { return i; } + explicit Base2(int i) : i(i) {} + int bar() const { return i; } int i; }; py::class_ b2(m, "Base2"); @@ -79,7 +108,10 @@ TEST_SUBMODULE(multiple_inheritance, m) { // test_multiple_inheritance_python_many_bases - #define PYBIND11_BASEN(N) py::class_>(m, "BaseN" #N).def(py::init()).def("f" #N, [](BaseN &b) { return b.i + N; }) +#define PYBIND11_BASEN(N) \ + py::class_>(m, "BaseN" #N).def(py::init()).def("f" #N, [](BaseN &b) { \ + return b.i + (N); \ + }) PYBIND11_BASEN( 1); PYBIND11_BASEN( 2); PYBIND11_BASEN( 3); PYBIND11_BASEN( 4); PYBIND11_BASEN( 5); PYBIND11_BASEN( 6); PYBIND11_BASEN( 7); PYBIND11_BASEN( 8); PYBIND11_BASEN( 9); PYBIND11_BASEN(10); PYBIND11_BASEN(11); PYBIND11_BASEN(12); @@ -99,41 +131,24 @@ TEST_SUBMODULE(multiple_inheritance, m) { // test_multiple_inheritance_virtbase // Test the case where not all base classes are specified, and where pybind11 requires the // py::multiple_inheritance flag to perform proper casting between types. - struct Base1a { - Base1a(int i) : i(i) { } - int foo() { return i; } - int i; - }; py::class_>(m, "Base1a") .def(py::init()) .def("foo", &Base1a::foo); - struct Base2a { - Base2a(int i) : i(i) { } - int bar() { return i; } - int i; - }; py::class_>(m, "Base2a") .def(py::init()) .def("bar", &Base2a::bar); - struct Base12a : Base1a, Base2a { - Base12a(int i, int j) : Base1a(i), Base2a(j) { } - }; py::class_>(m, "Base12a", py::multiple_inheritance()) .def(py::init()); m.def("bar_base2a", [](Base2a *b) { return b->bar(); }); - m.def("bar_base2a_sharedptr", [](std::shared_ptr b) { return b->bar(); }); + m.def("bar_base2a_sharedptr", [](const std::shared_ptr &b) { return b->bar(); }); // test_mi_unaligned_base // test_mi_base_return // Issue #801: invalid casting to derived type with MI bases - struct I801B1 { int a = 1; I801B1() = default; I801B1(const I801B1 &) = default; virtual ~I801B1() = default; }; - struct I801B2 { int b = 2; I801B2() = default; I801B2(const I801B2 &) = default; virtual ~I801B2() = default; }; - struct I801C : I801B1, I801B2 {}; - struct I801D : I801C {}; // Indirect MI // Unregistered classes: struct I801B3 { int c = 3; virtual ~I801B3() = default; }; struct I801E : I801B3, I801D {}; @@ -193,14 +208,12 @@ TEST_SUBMODULE(multiple_inheritance, m) { .def_readwrite_static("static_value", &VanillaStaticMix2::static_value); -#if !(defined(PYPY_VERSION) && (PYPY_VERSION_NUM < 0x06000000)) struct WithDict { }; struct VanillaDictMix1 : Vanilla, WithDict { }; struct VanillaDictMix2 : WithDict, Vanilla { }; py::class_(m, "WithDict", py::dynamic_attr()).def(py::init<>()); py::class_(m, "VanillaDictMix1").def(py::init<>()); py::class_(m, "VanillaDictMix2").def(py::init<>()); -#endif // test_diamond_inheritance // Issue #959: segfault when constructing diamond inheritance instance @@ -217,4 +230,87 @@ TEST_SUBMODULE(multiple_inheritance, m) { .def("c1", [](C1 *self) { return self; }); py::class_(m, "D") .def(py::init<>()); + + // test_pr3635_diamond_* + // - functions are get_{base}_{var}, return {var} + struct MVB { + MVB() = default; + MVB(const MVB &) = default; + virtual ~MVB() = default; + + int b = 1; + int get_b_b() const { return b; } + }; + struct MVC : virtual MVB { + int c = 2; + int get_c_b() const { return b; } + int get_c_c() const { return c; } + }; + struct MVD0 : virtual MVC { + int d0 = 3; + int get_d0_b() const { return b; } + int get_d0_c() const { return c; } + int get_d0_d0() const { return d0; } + }; + struct MVD1 : virtual MVC { + int d1 = 4; + int get_d1_b() const { return b; } + int get_d1_c() const { return c; } + int get_d1_d1() const { return d1; } + }; + struct MVE : virtual MVD0, virtual MVD1 { + int e = 5; + int get_e_b() const { return b; } + int get_e_c() const { return c; } + int get_e_d0() const { return d0; } + int get_e_d1() const { return d1; } + int get_e_e() const { return e; } + }; + struct MVF : virtual MVE { + int f = 6; + int get_f_b() const { return b; } + int get_f_c() const { return c; } + int get_f_d0() const { return d0; } + int get_f_d1() const { return d1; } + int get_f_e() const { return e; } + int get_f_f() const { return f; } + }; + py::class_(m, "MVB") + .def(py::init<>()) + .def("get_b_b", &MVB::get_b_b) + .def_readwrite("b", &MVB::b); + py::class_(m, "MVC") + .def(py::init<>()) + .def("get_c_b", &MVC::get_c_b) + .def("get_c_c", &MVC::get_c_c) + .def_readwrite("c", &MVC::c); + py::class_(m, "MVD0") + .def(py::init<>()) + .def("get_d0_b", &MVD0::get_d0_b) + .def("get_d0_c", &MVD0::get_d0_c) + .def("get_d0_d0", &MVD0::get_d0_d0) + .def_readwrite("d0", &MVD0::d0); + py::class_(m, "MVD1") + .def(py::init<>()) + .def("get_d1_b", &MVD1::get_d1_b) + .def("get_d1_c", &MVD1::get_d1_c) + .def("get_d1_d1", &MVD1::get_d1_d1) + .def_readwrite("d1", &MVD1::d1); + py::class_(m, "MVE") + .def(py::init<>()) + .def("get_e_b", &MVE::get_e_b) + .def("get_e_c", &MVE::get_e_c) + .def("get_e_d0", &MVE::get_e_d0) + .def("get_e_d1", &MVE::get_e_d1) + .def("get_e_e", &MVE::get_e_e) + .def_readwrite("e", &MVE::e); + py::class_(m, "MVF") + .def(py::init<>()) + .def("get_f_b", &MVF::get_f_b) + .def("get_f_c", &MVF::get_f_c) + .def("get_f_d0", &MVF::get_f_d0) + .def("get_f_d1", &MVF::get_f_d1) + .def("get_f_e", &MVF::get_f_e) + .def("get_f_f", &MVF::get_f_f) + .def_readwrite("f", &MVF::f); } diff --git a/pybind11/tests/test_multiple_inheritance.py b/pybind11/tests/test_multiple_inheritance.py index 7a0259d21..abdf25d60 100644 --- a/pybind11/tests/test_multiple_inheritance.py +++ b/pybind11/tests/test_multiple_inheritance.py @@ -2,7 +2,6 @@ import pytest import env # noqa: F401 - from pybind11_tests import ConstructorStats from pybind11_tests import multiple_inheritance as m @@ -57,7 +56,6 @@ def test_multiple_inheritance_mix2(): @pytest.mark.skipif("env.PYPY and env.PY2") @pytest.mark.xfail("env.PYPY and not env.PY2") def test_multiple_inheritance_python(): - class MI1(m.Base1, m.Base2): def __init__(self, i, j): m.Base1.__init__(self, i) @@ -163,7 +161,6 @@ def test_multiple_inheritance_python(): def test_multiple_inheritance_python_many_bases(): - class MIMany14(m.BaseN1, m.BaseN2, m.BaseN3, m.BaseN4): def __init__(self): m.BaseN1.__init__(self, 1) @@ -178,8 +175,16 @@ def test_multiple_inheritance_python_many_bases(): m.BaseN7.__init__(self, 7) m.BaseN8.__init__(self, 8) - class MIMany916(m.BaseN9, m.BaseN10, m.BaseN11, m.BaseN12, m.BaseN13, m.BaseN14, m.BaseN15, - m.BaseN16): + class MIMany916( + m.BaseN9, + m.BaseN10, + m.BaseN11, + m.BaseN12, + m.BaseN13, + m.BaseN14, + m.BaseN15, + m.BaseN16, + ): def __init__(self): m.BaseN9.__init__(self, 9) m.BaseN10.__init__(self, 10) @@ -225,7 +230,6 @@ def test_multiple_inheritance_python_many_bases(): def test_multiple_inheritance_virtbase(): - class MITypePy(m.Base12a): def __init__(self, i, j): m.Base12a.__init__(self, i, j) @@ -238,7 +242,7 @@ def test_multiple_inheritance_virtbase(): def test_mi_static_properties(): """Mixing bases with and without static properties should be possible - and the result should be independent of base definition order""" + and the result should be independent of base definition order""" for d in (m.VanillaStaticMix1(), m.VanillaStaticMix2()): assert d.vanilla() == "Vanilla" @@ -354,3 +358,139 @@ def test_diamond_inheritance(): assert d is d.c0().b() assert d is d.c1().b() assert d is d.c0().c1().b().c0().b() + + +def test_pr3635_diamond_b(): + o = m.MVB() + assert o.b == 1 + + assert o.get_b_b() == 1 + + +def test_pr3635_diamond_c(): + o = m.MVC() + assert o.b == 1 + assert o.c == 2 + + assert o.get_b_b() == 1 + assert o.get_c_b() == 1 + + assert o.get_c_c() == 2 + + +def test_pr3635_diamond_d0(): + o = m.MVD0() + assert o.b == 1 + assert o.c == 2 + assert o.d0 == 3 + + assert o.get_b_b() == 1 + assert o.get_c_b() == 1 + assert o.get_d0_b() == 1 + + assert o.get_c_c() == 2 + assert o.get_d0_c() == 2 + + assert o.get_d0_d0() == 3 + + +def test_pr3635_diamond_d1(): + o = m.MVD1() + assert o.b == 1 + assert o.c == 2 + assert o.d1 == 4 + + assert o.get_b_b() == 1 + assert o.get_c_b() == 1 + assert o.get_d1_b() == 1 + + assert o.get_c_c() == 2 + assert o.get_d1_c() == 2 + + assert o.get_d1_d1() == 4 + + +def test_pr3635_diamond_e(): + o = m.MVE() + assert o.b == 1 + assert o.c == 2 + assert o.d0 == 3 + assert o.d1 == 4 + assert o.e == 5 + + assert o.get_b_b() == 1 + assert o.get_c_b() == 1 + assert o.get_d0_b() == 1 + assert o.get_d1_b() == 1 + assert o.get_e_b() == 1 + + assert o.get_c_c() == 2 + assert o.get_d0_c() == 2 + assert o.get_d1_c() == 2 + assert o.get_e_c() == 2 + + assert o.get_d0_d0() == 3 + assert o.get_e_d0() == 3 + + assert o.get_d1_d1() == 4 + assert o.get_e_d1() == 4 + + assert o.get_e_e() == 5 + + +def test_pr3635_diamond_f(): + o = m.MVF() + assert o.b == 1 + assert o.c == 2 + assert o.d0 == 3 + assert o.d1 == 4 + assert o.e == 5 + assert o.f == 6 + + assert o.get_b_b() == 1 + assert o.get_c_b() == 1 + assert o.get_d0_b() == 1 + assert o.get_d1_b() == 1 + assert o.get_e_b() == 1 + assert o.get_f_b() == 1 + + assert o.get_c_c() == 2 + assert o.get_d0_c() == 2 + assert o.get_d1_c() == 2 + assert o.get_e_c() == 2 + assert o.get_f_c() == 2 + + assert o.get_d0_d0() == 3 + assert o.get_e_d0() == 3 + assert o.get_f_d0() == 3 + + assert o.get_d1_d1() == 4 + assert o.get_e_d1() == 4 + assert o.get_f_d1() == 4 + + assert o.get_e_e() == 5 + assert o.get_f_e() == 5 + + assert o.get_f_f() == 6 + + +def test_python_inherit_from_mi(): + """Tests extending a Python class from a single inheritor of a MI class""" + + class PyMVF(m.MVF): + g = 7 + + def get_g_g(self): + return self.g + + o = PyMVF() + + assert o.b == 1 + assert o.c == 2 + assert o.d0 == 3 + assert o.d1 == 4 + assert o.e == 5 + assert o.f == 6 + assert o.g == 7 + + assert o.get_g_g() == 7 diff --git a/pybind11/tests/test_numpy_array.cpp b/pybind11/tests/test_numpy_array.cpp index 33f1d7857..30a71acc9 100644 --- a/pybind11/tests/test_numpy_array.cpp +++ b/pybind11/tests/test_numpy_array.cpp @@ -13,6 +13,7 @@ #include #include +#include // Size / dtype checks. struct DtypeCheck { @@ -22,7 +23,7 @@ struct DtypeCheck { template DtypeCheck get_dtype_check(const char* name) { - py::module np = py::module::import("numpy"); + py::module_ np = py::module_::import("numpy"); DtypeCheck check{}; check.numpy = np.attr("dtype")(np.attr(name)); check.pybind11 = py::dtype::of(); @@ -89,23 +90,23 @@ template arr data_t(const arr_t& a, Ix... index) { template arr& mutate_data(arr& a, Ix... index) { auto ptr = (uint8_t *) a.mutable_data(index...); - for (ssize_t i = 0; i < a.nbytes() - a.offset_at(index...); i++) + for (py::ssize_t i = 0; i < a.nbytes() - a.offset_at(index...); i++) ptr[i] = (uint8_t) (ptr[i] * 2); return a; } template arr_t& mutate_data_t(arr_t& a, Ix... index) { auto ptr = a.mutable_data(index...); - for (ssize_t i = 0; i < a.size() - a.index_at(index...); i++) + for (py::ssize_t i = 0; i < a.size() - a.index_at(index...); i++) ptr[i]++; return a; } -template ssize_t index_at(const arr& a, Ix... idx) { return a.index_at(idx...); } -template ssize_t index_at_t(const arr_t& a, Ix... idx) { return a.index_at(idx...); } -template ssize_t offset_at(const arr& a, Ix... idx) { return a.offset_at(idx...); } -template ssize_t offset_at_t(const arr_t& a, Ix... idx) { return a.offset_at(idx...); } -template ssize_t at_t(const arr_t& a, Ix... idx) { return a.at(idx...); } +template py::ssize_t index_at(const arr& a, Ix... idx) { return a.index_at(idx...); } +template py::ssize_t index_at_t(const arr_t& a, Ix... idx) { return a.index_at(idx...); } +template py::ssize_t offset_at(const arr& a, Ix... idx) { return a.offset_at(idx...); } +template py::ssize_t offset_at_t(const arr_t& a, Ix... idx) { return a.offset_at(idx...); } +template py::ssize_t at_t(const arr_t& a, Ix... idx) { return a.at(idx...); } template arr_t& mutate_at_t(arr_t& a, Ix... idx) { a.mutable_at(idx...)++; return a; } #define def_index_fn(name, type) \ @@ -133,7 +134,7 @@ template py::handle auxiliaries(T &&r, T2 &&r2) { static int data_i = 42; TEST_SUBMODULE(numpy_array, sm) { - try { py::module::import("numpy"); } + try { py::module_::import("numpy"); } catch (...) { return; } // test_dtypes @@ -159,9 +160,9 @@ TEST_SUBMODULE(numpy_array, sm) { // test_array_attributes sm.def("ndim", [](const arr& a) { return a.ndim(); }); sm.def("shape", [](const arr& a) { return arr(a.ndim(), a.shape()); }); - sm.def("shape", [](const arr& a, ssize_t dim) { return a.shape(dim); }); + sm.def("shape", [](const arr& a, py::ssize_t dim) { return a.shape(dim); }); sm.def("strides", [](const arr& a) { return arr(a.ndim(), a.strides()); }); - sm.def("strides", [](const arr& a, ssize_t dim) { return a.strides(dim); }); + sm.def("strides", [](const arr& a, py::ssize_t dim) { return a.strides(dim); }); sm.def("writeable", [](const arr& a) { return a.writeable(); }); sm.def("size", [](const arr& a) { return a.size(); }); sm.def("itemsize", [](const arr& a) { return a.itemsize(); }); @@ -192,7 +193,7 @@ TEST_SUBMODULE(numpy_array, sm) { sm.def("scalar_int", []() { return py::array(py::dtype("i"), {}, {}, &data_i); }); // test_wrap - sm.def("wrap", [](py::array a) { + sm.def("wrap", [](const py::array &a) { return py::array( a.dtype(), {a.shape(), a.shape() + a.ndim()}, @@ -222,9 +223,10 @@ TEST_SUBMODULE(numpy_array, sm) { // test_isinstance sm.def("isinstance_untyped", [](py::object yes, py::object no) { - return py::isinstance(yes) && !py::isinstance(no); + return py::isinstance(std::move(yes)) + && !py::isinstance(std::move(no)); }); - sm.def("isinstance_typed", [](py::object o) { + sm.def("isinstance_typed", [](const py::object &o) { return py::isinstance>(o) && !py::isinstance>(o); }); @@ -236,7 +238,7 @@ TEST_SUBMODULE(numpy_array, sm) { "array_t"_a=py::array_t() ); }); - sm.def("converting_constructors", [](py::object o) { + sm.def("converting_constructors", [](const py::object &o) { return py::dict( "array"_a=py::array(o), "array_t"_a=py::array_t(o), @@ -245,69 +247,78 @@ TEST_SUBMODULE(numpy_array, sm) { }); // test_overload_resolution - sm.def("overloaded", [](py::array_t) { return "double"; }); - sm.def("overloaded", [](py::array_t) { return "float"; }); - sm.def("overloaded", [](py::array_t) { return "int"; }); - sm.def("overloaded", [](py::array_t) { return "unsigned short"; }); - sm.def("overloaded", [](py::array_t) { return "long long"; }); - sm.def("overloaded", [](py::array_t>) { return "double complex"; }); - sm.def("overloaded", [](py::array_t>) { return "float complex"; }); + sm.def("overloaded", [](const py::array_t &) { return "double"; }); + sm.def("overloaded", [](const py::array_t &) { return "float"; }); + sm.def("overloaded", [](const py::array_t &) { return "int"; }); + sm.def("overloaded", [](const py::array_t &) { return "unsigned short"; }); + sm.def("overloaded", [](const py::array_t &) { return "long long"; }); + sm.def("overloaded", + [](const py::array_t> &) { return "double complex"; }); + sm.def("overloaded", [](const py::array_t> &) { return "float complex"; }); - sm.def("overloaded2", [](py::array_t>) { return "double complex"; }); - sm.def("overloaded2", [](py::array_t) { return "double"; }); - sm.def("overloaded2", [](py::array_t>) { return "float complex"; }); - sm.def("overloaded2", [](py::array_t) { return "float"; }); + sm.def("overloaded2", + [](const py::array_t> &) { return "double complex"; }); + sm.def("overloaded2", [](const py::array_t &) { return "double"; }); + sm.def("overloaded2", + [](const py::array_t> &) { return "float complex"; }); + sm.def("overloaded2", [](const py::array_t &) { return "float"; }); + + // [workaround(intel)] ICC 20/21 breaks with py::arg().stuff, using py::arg{}.stuff works. // Only accept the exact types: - sm.def("overloaded3", [](py::array_t) { return "int"; }, py::arg().noconvert()); - sm.def("overloaded3", [](py::array_t) { return "double"; }, py::arg().noconvert()); + sm.def( + "overloaded3", [](const py::array_t &) { return "int"; }, py::arg{}.noconvert()); + sm.def( + "overloaded3", + [](const py::array_t &) { return "double"; }, + py::arg{}.noconvert()); // Make sure we don't do unsafe coercion (e.g. float to int) when not using forcecast, but // rather that float gets converted via the safe (conversion to double) overload: - sm.def("overloaded4", [](py::array_t) { return "long long"; }); - sm.def("overloaded4", [](py::array_t) { return "double"; }); + sm.def("overloaded4", [](const py::array_t &) { return "long long"; }); + sm.def("overloaded4", [](const py::array_t &) { return "double"; }); // But we do allow conversion to int if forcecast is enabled (but only if no overload matches // without conversion) - sm.def("overloaded5", [](py::array_t) { return "unsigned int"; }); - sm.def("overloaded5", [](py::array_t) { return "double"; }); + sm.def("overloaded5", [](const py::array_t &) { return "unsigned int"; }); + sm.def("overloaded5", [](const py::array_t &) { return "double"; }); // test_greedy_string_overload // Issue 685: ndarray shouldn't go to std::string overload - sm.def("issue685", [](std::string) { return "string"; }); - sm.def("issue685", [](py::array) { return "array"; }); - sm.def("issue685", [](py::object) { return "other"; }); + sm.def("issue685", [](const std::string &) { return "string"; }); + sm.def("issue685", [](const py::array &) { return "array"; }); + sm.def("issue685", [](const py::object &) { return "other"; }); // test_array_unchecked_fixed_dims sm.def("proxy_add2", [](py::array_t a, double v) { auto r = a.mutable_unchecked<2>(); - for (ssize_t i = 0; i < r.shape(0); i++) - for (ssize_t j = 0; j < r.shape(1); j++) + for (py::ssize_t i = 0; i < r.shape(0); i++) + for (py::ssize_t j = 0; j < r.shape(1); j++) r(i, j) += v; - }, py::arg().noconvert(), py::arg()); + }, py::arg{}.noconvert(), py::arg()); sm.def("proxy_init3", [](double start) { py::array_t a({ 3, 3, 3 }); auto r = a.mutable_unchecked<3>(); - for (ssize_t i = 0; i < r.shape(0); i++) - for (ssize_t j = 0; j < r.shape(1); j++) - for (ssize_t k = 0; k < r.shape(2); k++) + for (py::ssize_t i = 0; i < r.shape(0); i++) + for (py::ssize_t j = 0; j < r.shape(1); j++) + for (py::ssize_t k = 0; k < r.shape(2); k++) r(i, j, k) = start++; return a; }); sm.def("proxy_init3F", [](double start) { py::array_t a({ 3, 3, 3 }); auto r = a.mutable_unchecked<3>(); - for (ssize_t k = 0; k < r.shape(2); k++) - for (ssize_t j = 0; j < r.shape(1); j++) - for (ssize_t i = 0; i < r.shape(0); i++) + for (py::ssize_t k = 0; k < r.shape(2); k++) + for (py::ssize_t j = 0; j < r.shape(1); j++) + for (py::ssize_t i = 0; i < r.shape(0); i++) r(i, j, k) = start++; return a; }); - sm.def("proxy_squared_L2_norm", [](py::array_t a) { + sm.def("proxy_squared_L2_norm", [](const py::array_t &a) { auto r = a.unchecked<1>(); double sumsq = 0; - for (ssize_t i = 0; i < r.shape(0); i++) + for (py::ssize_t i = 0; i < r.shape(0); i++) sumsq += r[i] * r(i); // Either notation works for a 1D array return sumsq; }); @@ -318,22 +329,34 @@ TEST_SUBMODULE(numpy_array, sm) { return auxiliaries(r, r2); }); + sm.def("proxy_auxiliaries1_const_ref", [](py::array_t a) { + const auto &r = a.unchecked<1>(); + const auto &r2 = a.mutable_unchecked<1>(); + return r(0) == r2(0) && r[0] == r2[0]; + }); + + sm.def("proxy_auxiliaries2_const_ref", [](py::array_t a) { + const auto &r = a.unchecked<2>(); + const auto &r2 = a.mutable_unchecked<2>(); + return r(0, 0) == r2(0, 0); + }); + // test_array_unchecked_dyn_dims // Same as the above, but without a compile-time dimensions specification: sm.def("proxy_add2_dyn", [](py::array_t a, double v) { auto r = a.mutable_unchecked(); if (r.ndim() != 2) throw std::domain_error("error: ndim != 2"); - for (ssize_t i = 0; i < r.shape(0); i++) - for (ssize_t j = 0; j < r.shape(1); j++) + for (py::ssize_t i = 0; i < r.shape(0); i++) + for (py::ssize_t j = 0; j < r.shape(1); j++) r(i, j) += v; - }, py::arg().noconvert(), py::arg()); + }, py::arg{}.noconvert(), py::arg()); sm.def("proxy_init3_dyn", [](double start) { py::array_t a({ 3, 3, 3 }); auto r = a.mutable_unchecked(); if (r.ndim() != 3) throw std::domain_error("error: ndim != 3"); - for (ssize_t i = 0; i < r.shape(0); i++) - for (ssize_t j = 0; j < r.shape(1); j++) - for (ssize_t k = 0; k < r.shape(2); k++) + for (py::ssize_t i = 0; i < r.shape(0); i++) + for (py::ssize_t j = 0; j < r.shape(1); j++) + for (py::ssize_t k = 0; k < r.shape(2); k++) r(i, j, k) = start++; return a; }); @@ -362,7 +385,7 @@ TEST_SUBMODULE(numpy_array, sm) { // test_array_resize // reshape array to 2D without changing size sm.def("array_reshape2", [](py::array_t a) { - const auto dim_sz = (ssize_t)std::sqrt(a.size()); + const auto dim_sz = (py::ssize_t)std::sqrt(a.size()); if (dim_sz * dim_sz != a.size()) throw std::domain_error("array_reshape2: input array total size is not a squared integer"); a.resize({dim_sz, dim_sz}); @@ -382,45 +405,68 @@ TEST_SUBMODULE(numpy_array, sm) { return a; }); - sm.def("index_using_ellipsis", [](py::array a) { - return a[py::make_tuple(0, py::ellipsis(), 0)]; + sm.def("array_view", + [](py::array_t a, const std::string &dtype) { return a.view(dtype); }); + + sm.def("reshape_initializer_list", [](py::array_t a, size_t N, size_t M, size_t O) { + return a.reshape({N, M, O}); + }); + sm.def("reshape_tuple", [](py::array_t a, const std::vector &new_shape) { + return a.reshape(new_shape); }); + sm.def("index_using_ellipsis", + [](const py::array &a) { return a[py::make_tuple(0, py::ellipsis(), 0)]; }); + // test_argument_conversions - sm.def("accept_double", - [](py::array_t) {}, - py::arg("a")); - sm.def("accept_double_forcecast", - [](py::array_t) {}, - py::arg("a")); - sm.def("accept_double_c_style", - [](py::array_t) {}, - py::arg("a")); - sm.def("accept_double_c_style_forcecast", - [](py::array_t) {}, - py::arg("a")); - sm.def("accept_double_f_style", - [](py::array_t) {}, - py::arg("a")); - sm.def("accept_double_f_style_forcecast", - [](py::array_t) {}, - py::arg("a")); - sm.def("accept_double_noconvert", - [](py::array_t) {}, - py::arg("a").noconvert()); - sm.def("accept_double_forcecast_noconvert", - [](py::array_t) {}, - py::arg("a").noconvert()); - sm.def("accept_double_c_style_noconvert", - [](py::array_t) {}, - py::arg("a").noconvert()); - sm.def("accept_double_c_style_forcecast_noconvert", - [](py::array_t) {}, - py::arg("a").noconvert()); - sm.def("accept_double_f_style_noconvert", - [](py::array_t) {}, - py::arg("a").noconvert()); - sm.def("accept_double_f_style_forcecast_noconvert", - [](py::array_t) {}, - py::arg("a").noconvert()); + sm.def( + "accept_double", [](const py::array_t &) {}, py::arg("a")); + sm.def( + "accept_double_forcecast", + [](const py::array_t &) {}, + py::arg("a")); + sm.def( + "accept_double_c_style", + [](const py::array_t &) {}, + py::arg("a")); + sm.def( + "accept_double_c_style_forcecast", + [](const py::array_t &) {}, + py::arg("a")); + sm.def( + "accept_double_f_style", + [](const py::array_t &) {}, + py::arg("a")); + sm.def( + "accept_double_f_style_forcecast", + [](const py::array_t &) {}, + py::arg("a")); + sm.def( + "accept_double_noconvert", [](const py::array_t &) {}, "a"_a.noconvert()); + sm.def( + "accept_double_forcecast_noconvert", + [](const py::array_t &) {}, + "a"_a.noconvert()); + sm.def( + "accept_double_c_style_noconvert", + [](const py::array_t &) {}, + "a"_a.noconvert()); + sm.def( + "accept_double_c_style_forcecast_noconvert", + [](const py::array_t &) {}, + "a"_a.noconvert()); + sm.def( + "accept_double_f_style_noconvert", + [](const py::array_t &) {}, + "a"_a.noconvert()); + sm.def( + "accept_double_f_style_forcecast_noconvert", + [](const py::array_t &) {}, + "a"_a.noconvert()); + + // Check that types returns correct npy format descriptor + sm.def("test_fmt_desc_float", [](const py::array_t &) {}); + sm.def("test_fmt_desc_double", [](const py::array_t &) {}); + sm.def("test_fmt_desc_const_float", [](const py::array_t &) {}); + sm.def("test_fmt_desc_const_double", [](const py::array_t &) {}); } diff --git a/pybind11/tests/test_numpy_array.py b/pybind11/tests/test_numpy_array.py index a36e707c1..e4138f023 100644 --- a/pybind11/tests/test_numpy_array.py +++ b/pybind11/tests/test_numpy_array.py @@ -2,7 +2,6 @@ import pytest import env # noqa: F401 - from pybind11_tests import numpy_array as m np = pytest.importorskip("numpy") @@ -19,33 +18,36 @@ def test_dtypes(): print(check) assert check.numpy == check.pybind11, check if check.numpy.num != check.pybind11.num: - print("NOTE: typenum mismatch for {}: {} != {}".format( - check, check.numpy.num, check.pybind11.num)) + print( + "NOTE: typenum mismatch for {}: {} != {}".format( + check, check.numpy.num, check.pybind11.num + ) + ) -@pytest.fixture(scope='function') +@pytest.fixture(scope="function") def arr(): - return np.array([[1, 2, 3], [4, 5, 6]], '=u2') + return np.array([[1, 2, 3], [4, 5, 6]], "=u2") def test_array_attributes(): - a = np.array(0, 'f8') + a = np.array(0, "f8") assert m.ndim(a) == 0 assert all(m.shape(a) == []) assert all(m.strides(a) == []) with pytest.raises(IndexError) as excinfo: m.shape(a, 0) - assert str(excinfo.value) == 'invalid axis: 0 (ndim = 0)' + assert str(excinfo.value) == "invalid axis: 0 (ndim = 0)" with pytest.raises(IndexError) as excinfo: m.strides(a, 0) - assert str(excinfo.value) == 'invalid axis: 0 (ndim = 0)' + assert str(excinfo.value) == "invalid axis: 0 (ndim = 0)" assert m.writeable(a) assert m.size(a) == 1 assert m.itemsize(a) == 8 assert m.nbytes(a) == 8 assert m.owndata(a) - a = np.array([[1, 2, 3], [4, 5, 6]], 'u2').view() + a = np.array([[1, 2, 3], [4, 5, 6]], "u2").view() a.flags.writeable = False assert m.ndim(a) == 2 assert all(m.shape(a) == [2, 3]) @@ -56,10 +58,10 @@ def test_array_attributes(): assert m.strides(a, 1) == 2 with pytest.raises(IndexError) as excinfo: m.shape(a, 2) - assert str(excinfo.value) == 'invalid axis: 2 (ndim = 2)' + assert str(excinfo.value) == "invalid axis: 2 (ndim = 2)" with pytest.raises(IndexError) as excinfo: m.strides(a, 2) - assert str(excinfo.value) == 'invalid axis: 2 (ndim = 2)' + assert str(excinfo.value) == "invalid axis: 2 (ndim = 2)" assert not m.writeable(a) assert m.size(a) == 6 assert m.itemsize(a) == 2 @@ -67,7 +69,9 @@ def test_array_attributes(): assert not m.owndata(a) -@pytest.mark.parametrize('args, ret', [([], 0), ([0], 0), ([1], 3), ([0, 1], 1), ([1, 2], 5)]) +@pytest.mark.parametrize( + "args, ret", [([], 0), ([0], 0), ([1], 3), ([0, 1], 1), ([1, 2], 5)] +) def test_index_offset(arr, args, ret): assert m.index_at(arr, *args) == ret assert m.index_at_t(arr, *args) == ret @@ -76,31 +80,46 @@ def test_index_offset(arr, args, ret): def test_dim_check_fail(arr): - for func in (m.index_at, m.index_at_t, m.offset_at, m.offset_at_t, m.data, m.data_t, - m.mutate_data, m.mutate_data_t): + for func in ( + m.index_at, + m.index_at_t, + m.offset_at, + m.offset_at_t, + m.data, + m.data_t, + m.mutate_data, + m.mutate_data_t, + ): with pytest.raises(IndexError) as excinfo: func(arr, 1, 2, 3) - assert str(excinfo.value) == 'too many indices for an array: 3 (ndim = 2)' + assert str(excinfo.value) == "too many indices for an array: 3 (ndim = 2)" -@pytest.mark.parametrize('args, ret', - [([], [1, 2, 3, 4, 5, 6]), - ([1], [4, 5, 6]), - ([0, 1], [2, 3, 4, 5, 6]), - ([1, 2], [6])]) +@pytest.mark.parametrize( + "args, ret", + [ + ([], [1, 2, 3, 4, 5, 6]), + ([1], [4, 5, 6]), + ([0, 1], [2, 3, 4, 5, 6]), + ([1, 2], [6]), + ], +) def test_data(arr, args, ret): from sys import byteorder + assert all(m.data_t(arr, *args) == ret) - assert all(m.data(arr, *args)[(0 if byteorder == 'little' else 1)::2] == ret) - assert all(m.data(arr, *args)[(1 if byteorder == 'little' else 0)::2] == 0) + assert all(m.data(arr, *args)[(0 if byteorder == "little" else 1) :: 2] == ret) + assert all(m.data(arr, *args)[(1 if byteorder == "little" else 0) :: 2] == 0) -@pytest.mark.parametrize('dim', [0, 1, 3]) +@pytest.mark.parametrize("dim", [0, 1, 3]) def test_at_fail(arr, dim): for func in m.at_t, m.mutate_at_t: with pytest.raises(IndexError) as excinfo: func(arr, *([0] * dim)) - assert str(excinfo.value) == 'index dimension mismatch: {} (ndim = 2)'.format(dim) + assert str(excinfo.value) == "index dimension mismatch: {} (ndim = 2)".format( + dim + ) def test_at(arr): @@ -113,10 +132,14 @@ def test_at(arr): def test_mutate_readonly(arr): arr.flags.writeable = False - for func, args in (m.mutate_data, ()), (m.mutate_data_t, ()), (m.mutate_at_t, (0, 0)): + for func, args in ( + (m.mutate_data, ()), + (m.mutate_data_t, ()), + (m.mutate_at_t, (0, 0)), + ): with pytest.raises(ValueError) as excinfo: func(arr, *args) - assert str(excinfo.value) == 'array is not writeable' + assert str(excinfo.value) == "array is not writeable" def test_mutate_data(arr): @@ -134,14 +157,22 @@ def test_mutate_data(arr): def test_bounds_check(arr): - for func in (m.index_at, m.index_at_t, m.data, m.data_t, - m.mutate_data, m.mutate_data_t, m.at_t, m.mutate_at_t): + for func in ( + m.index_at, + m.index_at_t, + m.data, + m.data_t, + m.mutate_data, + m.mutate_data_t, + m.at_t, + m.mutate_at_t, + ): with pytest.raises(IndexError) as excinfo: func(arr, 2, 0) - assert str(excinfo.value) == 'index 2 is out of bounds for axis 0 with size 2' + assert str(excinfo.value) == "index 2 is out of bounds for axis 0 with size 2" with pytest.raises(IndexError) as excinfo: func(arr, 0, 4) - assert str(excinfo.value) == 'index 4 is out of bounds for axis 1 with size 3' + assert str(excinfo.value) == "index 4 is out of bounds for axis 1 with size 3" def test_make_c_f_array(): @@ -163,10 +194,11 @@ def test_make_empty_shaped_array(): def test_wrap(): def assert_references(a, b, base=None): from distutils.version import LooseVersion + if base is None: base = a assert a is not b - assert a.__array_interface__['data'][0] == b.__array_interface__['data'][0] + assert a.__array_interface__["data"][0] == b.__array_interface__["data"][0] assert a.shape == b.shape assert a.strides == b.strides assert a.flags.c_contiguous == b.flags.c_contiguous @@ -189,12 +221,12 @@ def test_wrap(): a2 = m.wrap(a1) assert_references(a1, a2) - a1 = np.array([[1, 2], [3, 4]], dtype=np.float32, order='F') + a1 = np.array([[1, 2], [3, 4]], dtype=np.float32, order="F") assert a1.flags.owndata and a1.base is None a2 = m.wrap(a1) assert_references(a1, a2) - a1 = np.array([[1, 2], [3, 4]], dtype=np.float32, order='C') + a1 = np.array([[1, 2], [3, 4]], dtype=np.float32, order="C") a1.flags.writeable = False a2 = m.wrap(a1) assert_references(a1, a2) @@ -224,11 +256,14 @@ def test_numpy_view(capture): assert np.all(ac_view_1 == np.array([1, 2], dtype=np.int32)) del ac pytest.gc_collect() - assert capture == """ + assert ( + capture + == """ ArrayClass() ArrayClass::numpy_view() ArrayClass::numpy_view() """ + ) ac_view_1[0] = 4 ac_view_1[1] = 3 assert ac_view_2[0] == 4 @@ -238,9 +273,12 @@ def test_numpy_view(capture): del ac_view_2 pytest.gc_collect() pytest.gc_collect() - assert capture == """ + assert ( + capture + == """ ~ArrayClass() """ + ) def test_cast_numpy_int64_to_uint64(): @@ -271,20 +309,22 @@ def test_constructors(): def test_overload_resolution(msg): # Exact overload matches: - assert m.overloaded(np.array([1], dtype='float64')) == 'double' - assert m.overloaded(np.array([1], dtype='float32')) == 'float' - assert m.overloaded(np.array([1], dtype='ushort')) == 'unsigned short' - assert m.overloaded(np.array([1], dtype='intc')) == 'int' - assert m.overloaded(np.array([1], dtype='longlong')) == 'long long' - assert m.overloaded(np.array([1], dtype='complex')) == 'double complex' - assert m.overloaded(np.array([1], dtype='csingle')) == 'float complex' + assert m.overloaded(np.array([1], dtype="float64")) == "double" + assert m.overloaded(np.array([1], dtype="float32")) == "float" + assert m.overloaded(np.array([1], dtype="ushort")) == "unsigned short" + assert m.overloaded(np.array([1], dtype="intc")) == "int" + assert m.overloaded(np.array([1], dtype="longlong")) == "long long" + assert m.overloaded(np.array([1], dtype="complex")) == "double complex" + assert m.overloaded(np.array([1], dtype="csingle")) == "float complex" # No exact match, should call first convertible version: - assert m.overloaded(np.array([1], dtype='uint8')) == 'double' + assert m.overloaded(np.array([1], dtype="uint8")) == "double" with pytest.raises(TypeError) as excinfo: m.overloaded("not an array") - assert msg(excinfo.value) == """ + assert ( + msg(excinfo.value) + == """ overloaded(): incompatible function arguments. The following argument types are supported: 1. (arg0: numpy.ndarray[numpy.float64]) -> str 2. (arg0: numpy.ndarray[numpy.float32]) -> str @@ -296,15 +336,16 @@ def test_overload_resolution(msg): Invoked with: 'not an array' """ + ) - assert m.overloaded2(np.array([1], dtype='float64')) == 'double' - assert m.overloaded2(np.array([1], dtype='float32')) == 'float' - assert m.overloaded2(np.array([1], dtype='complex64')) == 'float complex' - assert m.overloaded2(np.array([1], dtype='complex128')) == 'double complex' - assert m.overloaded2(np.array([1], dtype='float32')) == 'float' + assert m.overloaded2(np.array([1], dtype="float64")) == "double" + assert m.overloaded2(np.array([1], dtype="float32")) == "float" + assert m.overloaded2(np.array([1], dtype="complex64")) == "float complex" + assert m.overloaded2(np.array([1], dtype="complex128")) == "double complex" + assert m.overloaded2(np.array([1], dtype="float32")) == "float" - assert m.overloaded3(np.array([1], dtype='float64')) == 'double' - assert m.overloaded3(np.array([1], dtype='intc')) == 'int' + assert m.overloaded3(np.array([1], dtype="float64")) == "double" + assert m.overloaded3(np.array([1], dtype="intc")) == "int" expected_exc = """ overloaded3(): incompatible function arguments. The following argument types are supported: 1. (arg0: numpy.ndarray[numpy.int32]) -> str @@ -313,47 +354,49 @@ def test_overload_resolution(msg): Invoked with: """ with pytest.raises(TypeError) as excinfo: - m.overloaded3(np.array([1], dtype='uintc')) - assert msg(excinfo.value) == expected_exc + repr(np.array([1], dtype='uint32')) + m.overloaded3(np.array([1], dtype="uintc")) + assert msg(excinfo.value) == expected_exc + repr(np.array([1], dtype="uint32")) with pytest.raises(TypeError) as excinfo: - m.overloaded3(np.array([1], dtype='float32')) - assert msg(excinfo.value) == expected_exc + repr(np.array([1.], dtype='float32')) + m.overloaded3(np.array([1], dtype="float32")) + assert msg(excinfo.value) == expected_exc + repr(np.array([1.0], dtype="float32")) with pytest.raises(TypeError) as excinfo: - m.overloaded3(np.array([1], dtype='complex')) - assert msg(excinfo.value) == expected_exc + repr(np.array([1. + 0.j])) + m.overloaded3(np.array([1], dtype="complex")) + assert msg(excinfo.value) == expected_exc + repr(np.array([1.0 + 0.0j])) # Exact matches: - assert m.overloaded4(np.array([1], dtype='double')) == 'double' - assert m.overloaded4(np.array([1], dtype='longlong')) == 'long long' + assert m.overloaded4(np.array([1], dtype="double")) == "double" + assert m.overloaded4(np.array([1], dtype="longlong")) == "long long" # Non-exact matches requiring conversion. Since float to integer isn't a # save conversion, it should go to the double overload, but short can go to # either (and so should end up on the first-registered, the long long). - assert m.overloaded4(np.array([1], dtype='float32')) == 'double' - assert m.overloaded4(np.array([1], dtype='short')) == 'long long' + assert m.overloaded4(np.array([1], dtype="float32")) == "double" + assert m.overloaded4(np.array([1], dtype="short")) == "long long" - assert m.overloaded5(np.array([1], dtype='double')) == 'double' - assert m.overloaded5(np.array([1], dtype='uintc')) == 'unsigned int' - assert m.overloaded5(np.array([1], dtype='float32')) == 'unsigned int' + assert m.overloaded5(np.array([1], dtype="double")) == "double" + assert m.overloaded5(np.array([1], dtype="uintc")) == "unsigned int" + assert m.overloaded5(np.array([1], dtype="float32")) == "unsigned int" def test_greedy_string_overload(): """Tests fix for #685 - ndarray shouldn't go to std::string overload""" assert m.issue685("abc") == "string" - assert m.issue685(np.array([97, 98, 99], dtype='b')) == "array" + assert m.issue685(np.array([97, 98, 99], dtype="b")) == "array" assert m.issue685(123) == "other" def test_array_unchecked_fixed_dims(msg): - z1 = np.array([[1, 2], [3, 4]], dtype='float64') + z1 = np.array([[1, 2], [3, 4]], dtype="float64") m.proxy_add2(z1, 10) assert np.all(z1 == [[11, 12], [13, 14]]) with pytest.raises(ValueError) as excinfo: - m.proxy_add2(np.array([1., 2, 3]), 5.0) - assert msg(excinfo.value) == "array has incorrect number of dimensions: 1; expected 2" + m.proxy_add2(np.array([1.0, 2, 3]), 5.0) + assert ( + msg(excinfo.value) == "array has incorrect number of dimensions: 1; expected 2" + ) - expect_c = np.ndarray(shape=(3, 3, 3), buffer=np.array(range(3, 30)), dtype='int') + expect_c = np.ndarray(shape=(3, 3, 3), buffer=np.array(range(3, 30)), dtype="int") assert np.all(m.proxy_init3(3.0) == expect_c) expect_f = np.transpose(expect_c) assert np.all(m.proxy_init3F(3.0) == expect_f) @@ -364,13 +407,16 @@ def test_array_unchecked_fixed_dims(msg): assert m.proxy_auxiliaries2(z1) == [11, 11, True, 2, 8, 2, 2, 4, 32] assert m.proxy_auxiliaries2(z1) == m.array_auxiliaries2(z1) + assert m.proxy_auxiliaries1_const_ref(z1[0, :]) + assert m.proxy_auxiliaries2_const_ref(z1) -def test_array_unchecked_dyn_dims(msg): - z1 = np.array([[1, 2], [3, 4]], dtype='float64') + +def test_array_unchecked_dyn_dims(): + z1 = np.array([[1, 2], [3, 4]], dtype="float64") m.proxy_add2_dyn(z1, 10) assert np.all(z1 == [[11, 12], [13, 14]]) - expect_c = np.ndarray(shape=(3, 3, 3), buffer=np.array(range(3, 30)), dtype='int') + expect_c = np.ndarray(shape=(3, 3, 3), buffer=np.array(range(3, 30)), dtype="int") assert np.all(m.proxy_init3_dyn(3.0) == expect_c) assert m.proxy_auxiliaries2_dyn(z1) == [11, 11, True, 2, 8, 2, 2, 4, 32] @@ -380,15 +426,15 @@ def test_array_unchecked_dyn_dims(msg): def test_array_failure(): with pytest.raises(ValueError) as excinfo: m.array_fail_test() - assert str(excinfo.value) == 'cannot create a pybind11::array from a nullptr' + assert str(excinfo.value) == "cannot create a pybind11::array from a nullptr" with pytest.raises(ValueError) as excinfo: m.array_t_fail_test() - assert str(excinfo.value) == 'cannot create a pybind11::array_t from a nullptr' + assert str(excinfo.value) == "cannot create a pybind11::array_t from a nullptr" with pytest.raises(ValueError) as excinfo: m.array_fail_test_negative_size() - assert str(excinfo.value) == 'negative dimensions are not allowed' + assert str(excinfo.value) == "negative dimensions are not allowed" def test_initializer_list(): @@ -398,36 +444,76 @@ def test_initializer_list(): assert m.array_initializer_list4().shape == (1, 2, 3, 4) -def test_array_resize(msg): - a = np.array([1, 2, 3, 4, 5, 6, 7, 8, 9], dtype='float64') +def test_array_resize(): + a = np.array([1, 2, 3, 4, 5, 6, 7, 8, 9], dtype="float64") m.array_reshape2(a) - assert(a.size == 9) - assert(np.all(a == [[1, 2, 3], [4, 5, 6], [7, 8, 9]])) + assert a.size == 9 + assert np.all(a == [[1, 2, 3], [4, 5, 6], [7, 8, 9]]) # total size change should succced with refcheck off m.array_resize3(a, 4, False) - assert(a.size == 64) + assert a.size == 64 # ... and fail with refcheck on try: m.array_resize3(a, 3, True) except ValueError as e: - assert(str(e).startswith("cannot resize an array")) + assert str(e).startswith("cannot resize an array") # transposed array doesn't own data b = a.transpose() try: m.array_resize3(b, 3, False) except ValueError as e: - assert(str(e).startswith("cannot resize this array: it does not own its data")) + assert str(e).startswith("cannot resize this array: it does not own its data") # ... but reshape should be fine m.array_reshape2(b) - assert(b.shape == (8, 8)) + assert b.shape == (8, 8) @pytest.mark.xfail("env.PYPY") -def test_array_create_and_resize(msg): +def test_array_create_and_resize(): a = m.create_and_resize(2) - assert(a.size == 4) - assert(np.all(a == 42.)) + assert a.size == 4 + assert np.all(a == 42.0) + + +def test_array_view(): + a = np.ones(100 * 4).astype("uint8") + a_float_view = m.array_view(a, "float32") + assert a_float_view.shape == (100 * 1,) # 1 / 4 bytes = 8 / 32 + + a_int16_view = m.array_view(a, "int16") # 1 / 2 bytes = 16 / 32 + assert a_int16_view.shape == (100 * 2,) + + +def test_array_view_invalid(): + a = np.ones(100 * 4).astype("uint8") + with pytest.raises(TypeError): + m.array_view(a, "deadly_dtype") + + +def test_reshape_initializer_list(): + a = np.arange(2 * 7 * 3) + 1 + x = m.reshape_initializer_list(a, 2, 7, 3) + assert x.shape == (2, 7, 3) + assert list(x[1][4]) == [34, 35, 36] + with pytest.raises(ValueError) as excinfo: + m.reshape_initializer_list(a, 1, 7, 3) + assert str(excinfo.value) == "cannot reshape array of size 42 into shape (1,7,3)" + + +def test_reshape_tuple(): + a = np.arange(3 * 7 * 2) + 1 + x = m.reshape_tuple(a, (3, 7, 2)) + assert x.shape == (3, 7, 2) + assert list(x[1][4]) == [23, 24] + y = m.reshape_tuple(x, (x.size,)) + assert y.shape == (42,) + with pytest.raises(ValueError) as excinfo: + m.reshape_tuple(a, (3, 7, 1)) + assert str(excinfo.value) == "cannot reshape array of size 42 into shape (3,7,1)" + with pytest.raises(ValueError) as excinfo: + m.reshape_tuple(a, ()) + assert str(excinfo.value) == "cannot reshape array of size 42 into shape ()" def test_index_using_ellipsis(): @@ -435,17 +521,30 @@ def test_index_using_ellipsis(): assert a.shape == (6,) +@pytest.mark.parametrize( + "test_func", + [ + m.test_fmt_desc_float, + m.test_fmt_desc_double, + m.test_fmt_desc_const_float, + m.test_fmt_desc_const_double, + ], +) +def test_format_descriptors_for_floating_point_types(test_func): + assert "numpy.ndarray[numpy.float" in test_func.__doc__ + + @pytest.mark.parametrize("forcecast", [False, True]) -@pytest.mark.parametrize("contiguity", [None, 'C', 'F']) +@pytest.mark.parametrize("contiguity", [None, "C", "F"]) @pytest.mark.parametrize("noconvert", [False, True]) @pytest.mark.filterwarnings( "ignore:Casting complex values to real discards the imaginary part:numpy.ComplexWarning" ) def test_argument_conversions(forcecast, contiguity, noconvert): function_name = "accept_double" - if contiguity == 'C': + if contiguity == "C": function_name += "_c_style" - elif contiguity == 'F': + elif contiguity == "F": function_name += "_f_style" if forcecast: function_name += "_forcecast" @@ -453,37 +552,39 @@ def test_argument_conversions(forcecast, contiguity, noconvert): function_name += "_noconvert" function = getattr(m, function_name) - for dtype in [np.dtype('float32'), np.dtype('float64'), np.dtype('complex128')]: - for order in ['C', 'F']: + for dtype in [np.dtype("float32"), np.dtype("float64"), np.dtype("complex128")]: + for order in ["C", "F"]: for shape in [(2, 2), (1, 3, 1, 1), (1, 1, 1), (0,)]: if not noconvert: # If noconvert is not passed, only complex128 needs to be truncated and # "cannot be safely obtained". So without `forcecast`, the argument shouldn't # be accepted. - should_raise = dtype.name == 'complex128' and not forcecast + should_raise = dtype.name == "complex128" and not forcecast else: # If noconvert is passed, only float64 and the matching order is accepted. # If at most one dimension has a size greater than 1, the array is also # trivially contiguous. trivially_contiguous = sum(1 for d in shape if d > 1) <= 1 - should_raise = ( - dtype.name != 'float64' or - (contiguity is not None and - contiguity != order and - not trivially_contiguous) + should_raise = dtype.name != "float64" or ( + contiguity is not None + and contiguity != order + and not trivially_contiguous ) array = np.zeros(shape, dtype=dtype, order=order) if not should_raise: function(array) else: - with pytest.raises(TypeError, match="incompatible function arguments"): + with pytest.raises( + TypeError, match="incompatible function arguments" + ): function(array) @pytest.mark.xfail("env.PYPY") def test_dtype_refcount_leak(): from sys import getrefcount + dtype = np.dtype(np.float_) a = np.array([1], dtype=dtype) before = getrefcount(dtype) diff --git a/pybind11/tests/test_numpy_dtypes.cpp b/pybind11/tests/test_numpy_dtypes.cpp index 467e0253f..bf4f4cee7 100644 --- a/pybind11/tests/test_numpy_dtypes.cpp +++ b/pybind11/tests/test_numpy_dtypes.cpp @@ -108,9 +108,11 @@ PYBIND11_PACKED(struct EnumStruct { std::ostream& operator<<(std::ostream& os, const StringStruct& v) { os << "a='"; - for (size_t i = 0; i < 3 && v.a[i]; i++) os << v.a[i]; + for (size_t i = 0; i < 3 && (v.a[i] != 0); i++) + os << v.a[i]; os << "',b='"; - for (size_t i = 0; i < 3 && v.b[i]; i++) os << v.b[i]; + for (size_t i = 0; i < 3 && (v.b[i] != 0); i++) + os << v.b[i]; return os << "'"; } @@ -146,11 +148,13 @@ py::array mkarray_via_buffer(size_t n) { 1, { n }, { sizeof(T) })); } -#define SET_TEST_VALS(s, i) do { \ - s.bool_ = (i) % 2 != 0; \ - s.uint_ = (uint32_t) (i); \ - s.float_ = (float) (i) * 1.5f; \ - s.ldbl_ = (long double) (i) * -2.5L; } while (0) +#define SET_TEST_VALS(s, i) \ + do { \ + (s).bool_ = (i) % 2 != 0; \ + (s).uint_ = (uint32_t) (i); \ + (s).float_ = (float) (i) *1.5f; \ + (s).ldbl_ = (long double) (i) * -2.5L; \ + } while (0) template py::array_t create_recarray(size_t n) { @@ -168,7 +172,7 @@ py::list print_recarray(py::array_t arr) { const auto req = arr.request(); const auto ptr = static_cast(req.ptr); auto l = py::list(); - for (ssize_t i = 0; i < req.size; i++) { + for (py::ssize_t i = 0; i < req.size; i++) { std::stringstream ss; ss << ptr[i]; l.append(py::str(ss.str())); @@ -180,8 +184,8 @@ py::array_t test_array_ctors(int i) { using arr_t = py::array_t; std::vector data { 1, 2, 3, 4, 5, 6 }; - std::vector shape { 3, 2 }; - std::vector strides { 8, 4 }; + std::vector shape { 3, 2 }; + std::vector strides { 8, 4 }; auto ptr = data.data(); auto vptr = (void *) ptr; @@ -255,11 +259,31 @@ struct A {}; struct B {}; TEST_SUBMODULE(numpy_dtypes, m) { - try { py::module::import("numpy"); } + try { py::module_::import("numpy"); } catch (...) { return; } // typeinfo may be registered before the dtype descriptor for scalar casts to work... - py::class_(m, "SimpleStruct"); + py::class_(m, "SimpleStruct") + // Explicit construct to ensure zero-valued initialization. + .def(py::init([]() { return SimpleStruct(); })) + .def_readwrite("bool_", &SimpleStruct::bool_) + .def_readwrite("uint_", &SimpleStruct::uint_) + .def_readwrite("float_", &SimpleStruct::float_) + .def_readwrite("ldbl_", &SimpleStruct::ldbl_) + .def("astuple", + [](const SimpleStruct &self) { + return py::make_tuple(self.bool_, self.uint_, self.float_, self.ldbl_); + }) + .def_static("fromtuple", [](const py::tuple &tup) { + if (py::len(tup) != 4) { + throw py::cast_error("Invalid size"); + } + return SimpleStruct{ + tup[0].cast(), + tup[1].cast(), + tup[2].cast(), + tup[3].cast()}; + }); PYBIND11_NUMPY_DTYPE(SimpleStruct, bool_, uint_, float_, ldbl_); PYBIND11_NUMPY_DTYPE(SimpleStructReordered, bool_, uint_, float_, ldbl_); @@ -339,6 +363,14 @@ TEST_SUBMODULE(numpy_dtypes, m) { }); // test_dtype + std::vector dtype_names{ + "byte", "short", "intc", "int_", "longlong", + "ubyte", "ushort", "uintc", "uint", "ulonglong", + "half", "single", "double", "longdouble", + "csingle", "cdouble", "clongdouble", + "bool_", "datetime64", "timedelta64", "object_" + }; + m.def("print_dtypes", []() { py::list l; for (const py::handle &d : { @@ -357,6 +389,18 @@ TEST_SUBMODULE(numpy_dtypes, m) { return l; }); m.def("test_dtype_ctors", &test_dtype_ctors); + m.def("test_dtype_kind", [dtype_names]() { + py::list list; + for (auto& dt_name : dtype_names) + list.append(py::dtype(dt_name).kind()); + return list; + }); + m.def("test_dtype_char_", [dtype_names]() { + py::list list; + for (auto& dt_name : dtype_names) + list.append(py::dtype(dt_name).char_()); + return list; + }); m.def("test_dtype_methods", []() { py::list list; auto dt1 = py::dtype::of(); @@ -379,7 +423,7 @@ TEST_SUBMODULE(numpy_dtypes, m) { if (non_empty) { auto req = arr.request(); auto ptr = static_cast(req.ptr); - for (ssize_t i = 0; i < req.size * req.itemsize; i++) + for (py::ssize_t i = 0; i < req.size * req.itemsize; i++) static_cast(req.ptr)[i] = 0; ptr[1].a[0] = 'a'; ptr[1].b[0] = 'a'; ptr[2].a[0] = 'a'; ptr[2].b[0] = 'a'; @@ -462,10 +506,16 @@ TEST_SUBMODULE(numpy_dtypes, m) { m.def("buffer_to_dtype", [](py::buffer& buf) { return py::dtype(buf.request()); }); // test_scalar_conversion - m.def("f_simple", [](SimpleStruct s) { return s.uint_ * 10; }); + auto f_simple = [](SimpleStruct s) { return s.uint_ * 10; }; + m.def("f_simple", f_simple); m.def("f_packed", [](PackedStruct s) { return s.uint_ * 10; }); m.def("f_nested", [](NestedStruct s) { return s.a.uint_ * 10; }); + // test_vectorize + m.def("f_simple_vectorized", py::vectorize(f_simple)); + auto f_simple_pass_thru = [](SimpleStruct s) { return s; }; + m.def("f_simple_pass_thru_vectorized", py::vectorize(f_simple_pass_thru)); + // test_register_dtype m.def("register_dtype", []() { PYBIND11_NUMPY_DTYPE(SimpleStruct, bool_, uint_, float_, ldbl_); }); diff --git a/pybind11/tests/test_numpy_dtypes.py b/pybind11/tests/test_numpy_dtypes.py index 417d6f1cf..06e578329 100644 --- a/pybind11/tests/test_numpy_dtypes.py +++ b/pybind11/tests/test_numpy_dtypes.py @@ -4,63 +4,82 @@ import re import pytest import env # noqa: F401 - from pybind11_tests import numpy_dtypes as m np = pytest.importorskip("numpy") -@pytest.fixture(scope='module') +@pytest.fixture(scope="module") def simple_dtype(): - ld = np.dtype('longdouble') - return np.dtype({'names': ['bool_', 'uint_', 'float_', 'ldbl_'], - 'formats': ['?', 'u4', 'f4', 'f{}'.format(ld.itemsize)], - 'offsets': [0, 4, 8, (16 if ld.alignment > 4 else 12)]}) + ld = np.dtype("longdouble") + return np.dtype( + { + "names": ["bool_", "uint_", "float_", "ldbl_"], + "formats": ["?", "u4", "f4", "f{}".format(ld.itemsize)], + "offsets": [0, 4, 8, (16 if ld.alignment > 4 else 12)], + } + ) -@pytest.fixture(scope='module') +@pytest.fixture(scope="module") def packed_dtype(): - return np.dtype([('bool_', '?'), ('uint_', 'u4'), ('float_', 'f4'), ('ldbl_', 'g')]) + return np.dtype([("bool_", "?"), ("uint_", "u4"), ("float_", "f4"), ("ldbl_", "g")]) def dt_fmt(): from sys import byteorder - e = '<' if byteorder == 'little' else '>' - return ("{{'names':['bool_','uint_','float_','ldbl_']," - " 'formats':['?','" + e + "u4','" + e + "f4','" + e + "f{}']," - " 'offsets':[0,4,8,{}], 'itemsize':{}}}") + + e = "<" if byteorder == "little" else ">" + return ( + "{{'names':['bool_','uint_','float_','ldbl_']," + " 'formats':['?','" + e + "u4','" + e + "f4','" + e + "f{}']," + " 'offsets':[0,4,8,{}], 'itemsize':{}}}" + ) def simple_dtype_fmt(): - ld = np.dtype('longdouble') + ld = np.dtype("longdouble") simple_ld_off = 12 + 4 * (ld.alignment > 4) return dt_fmt().format(ld.itemsize, simple_ld_off, simple_ld_off + ld.itemsize) def packed_dtype_fmt(): from sys import byteorder + return "[('bool_', '?'), ('uint_', '{e}u4'), ('float_', '{e}f4'), ('ldbl_', '{e}f{}')]".format( - np.dtype('longdouble').itemsize, e='<' if byteorder == 'little' else '>') + np.dtype("longdouble").itemsize, e="<" if byteorder == "little" else ">" + ) def partial_ld_offset(): - return 12 + 4 * (np.dtype('uint64').alignment > 4) + 8 + 8 * ( - np.dtype('longdouble').alignment > 8) + return ( + 12 + + 4 * (np.dtype("uint64").alignment > 4) + + 8 + + 8 * (np.dtype("longdouble").alignment > 8) + ) def partial_dtype_fmt(): - ld = np.dtype('longdouble') + ld = np.dtype("longdouble") partial_ld_off = partial_ld_offset() - return dt_fmt().format(ld.itemsize, partial_ld_off, partial_ld_off + ld.itemsize) + partial_size = partial_ld_off + ld.itemsize + partial_end_padding = partial_size % np.dtype("uint64").alignment + return dt_fmt().format( + ld.itemsize, partial_ld_off, partial_size + partial_end_padding + ) def partial_nested_fmt(): - ld = np.dtype('longdouble') + ld = np.dtype("longdouble") partial_nested_off = 8 + 8 * (ld.alignment > 8) partial_ld_off = partial_ld_offset() - partial_nested_size = partial_nested_off * 2 + partial_ld_off + ld.itemsize + partial_size = partial_ld_off + ld.itemsize + partial_end_padding = partial_size % np.dtype("uint64").alignment + partial_nested_size = partial_nested_off * 2 + partial_size + partial_end_padding return "{{'names':['a'], 'formats':[{}], 'offsets':[{}], 'itemsize':{}}}".format( - partial_dtype_fmt(), partial_nested_off, partial_nested_size) + partial_dtype_fmt(), partial_nested_off, partial_nested_size + ) def assert_equal(actual, expected_data, expected_dtype): @@ -70,15 +89,21 @@ def assert_equal(actual, expected_data, expected_dtype): def test_format_descriptors(): with pytest.raises(RuntimeError) as excinfo: m.get_format_unbound() - assert re.match('^NumPy type info missing for .*UnboundStruct.*$', str(excinfo.value)) + assert re.match( + "^NumPy type info missing for .*UnboundStruct.*$", str(excinfo.value) + ) - ld = np.dtype('longdouble') - ldbl_fmt = ('4x' if ld.alignment > 4 else '') + ld.char + ld = np.dtype("longdouble") + ldbl_fmt = ("4x" if ld.alignment > 4 else "") + ld.char ss_fmt = "^T{?:bool_:3xI:uint_:f:float_:" + ldbl_fmt + ":ldbl_:}" - dbl = np.dtype('double') - partial_fmt = ("^T{?:bool_:3xI:uint_:f:float_:" + - str(4 * (dbl.alignment > 4) + dbl.itemsize + 8 * (ld.alignment > 8)) + - "xg:ldbl_:}") + dbl = np.dtype("double") + end_padding = ld.itemsize % np.dtype("uint64").alignment + partial_fmt = ( + "^T{?:bool_:3xI:uint_:f:float_:" + + str(4 * (dbl.alignment > 4) + dbl.itemsize + 8 * (ld.alignment > 8)) + + "xg:ldbl_:" + + (str(end_padding) + "x}" if end_padding > 0 else "}") + ) nested_extra = str(max(8, ld.alignment)) assert m.print_format_descriptors() == [ ss_fmt, @@ -88,14 +113,15 @@ def test_format_descriptors(): "^T{" + nested_extra + "x" + partial_fmt + ":a:" + nested_extra + "x}", "^T{3s:a:3s:b:}", "^T{(3)4s:a:(2)i:b:(3)B:c:1x(4, 2)f:d:}", - '^T{q:e1:B:e2:}', - '^T{Zf:cflt:Zd:cdbl:}' + "^T{q:e1:B:e2:}", + "^T{Zf:cflt:Zd:cdbl:}", ] def test_dtype(simple_dtype): from sys import byteorder - e = '<' if byteorder == 'little' else '>' + + e = "<" if byteorder == "little" else ">" assert m.print_dtypes() == [ simple_dtype_fmt(), @@ -104,30 +130,63 @@ def test_dtype(simple_dtype): partial_dtype_fmt(), partial_nested_fmt(), "[('a', 'S3'), ('b', 'S3')]", - ("{{'names':['a','b','c','d'], " + - "'formats':[('S4', (3,)),('" + e + "i4', (2,)),('u1', (3,)),('" + e + "f4', (4, 2))], " + - "'offsets':[0,12,20,24], 'itemsize':56}}").format(e=e), + ( + "{{'names':['a','b','c','d'], " + + "'formats':[('S4', (3,)),('" + + e + + "i4', (2,)),('u1', (3,)),('" + + e + + "f4', (4, 2))], " + + "'offsets':[0,12,20,24], 'itemsize':56}}" + ).format(e=e), "[('e1', '" + e + "i8'), ('e2', 'u1')]", "[('x', 'i1'), ('y', '" + e + "u8')]", - "[('cflt', '" + e + "c8'), ('cdbl', '" + e + "c16')]" + "[('cflt', '" + e + "c8'), ('cdbl', '" + e + "c16')]", ] - d1 = np.dtype({'names': ['a', 'b'], 'formats': ['int32', 'float64'], - 'offsets': [1, 10], 'itemsize': 20}) - d2 = np.dtype([('a', 'i4'), ('b', 'f4')]) - assert m.test_dtype_ctors() == [np.dtype('int32'), np.dtype('float64'), - np.dtype('bool'), d1, d1, np.dtype('uint32'), d2] + d1 = np.dtype( + { + "names": ["a", "b"], + "formats": ["int32", "float64"], + "offsets": [1, 10], + "itemsize": 20, + } + ) + d2 = np.dtype([("a", "i4"), ("b", "f4")]) + assert m.test_dtype_ctors() == [ + np.dtype("int32"), + np.dtype("float64"), + np.dtype("bool"), + d1, + d1, + np.dtype("uint32"), + d2, + ] - assert m.test_dtype_methods() == [np.dtype('int32'), simple_dtype, False, True, - np.dtype('int32').itemsize, simple_dtype.itemsize] + assert m.test_dtype_methods() == [ + np.dtype("int32"), + simple_dtype, + False, + True, + np.dtype("int32").itemsize, + simple_dtype.itemsize, + ] - assert m.trailing_padding_dtype() == m.buffer_to_dtype(np.zeros(1, m.trailing_padding_dtype())) + assert m.trailing_padding_dtype() == m.buffer_to_dtype( + np.zeros(1, m.trailing_padding_dtype()) + ) + + assert m.test_dtype_kind() == list("iiiiiuuuuuffffcccbMmO") + assert m.test_dtype_char_() == list("bhilqBHILQefdgFDG?MmO") def test_recarray(simple_dtype, packed_dtype): elements = [(False, 0, 0.0, -0.0), (True, 1, 1.5, -2.5), (False, 2, 3.0, -5.0)] - for func, dtype in [(m.create_rec_simple, simple_dtype), (m.create_rec_packed, packed_dtype)]: + for func, dtype in [ + (m.create_rec_simple, simple_dtype), + (m.create_rec_packed, packed_dtype), + ]: arr = func(0) assert arr.dtype == dtype assert_equal(arr, [], simple_dtype) @@ -138,20 +197,24 @@ def test_recarray(simple_dtype, packed_dtype): assert_equal(arr, elements, simple_dtype) assert_equal(arr, elements, packed_dtype) + # Show what recarray's look like in NumPy. + assert type(arr[0]) == np.void + assert type(arr[0].item()) == tuple + if dtype == simple_dtype: assert m.print_rec_simple(arr) == [ "s:0,0,0,-0", "s:1,1,1.5,-2.5", - "s:0,2,3,-5" + "s:0,2,3,-5", ] else: assert m.print_rec_packed(arr) == [ "p:0,0,0,-0", "p:1,1,1.5,-2.5", - "p:0,2,3,-5" + "p:0,2,3,-5", ] - nested_dtype = np.dtype([('a', simple_dtype), ('b', packed_dtype)]) + nested_dtype = np.dtype([("a", simple_dtype), ("b", packed_dtype)]) arr = m.create_rec_nested(0) assert arr.dtype == nested_dtype @@ -159,33 +222,39 @@ def test_recarray(simple_dtype, packed_dtype): arr = m.create_rec_nested(3) assert arr.dtype == nested_dtype - assert_equal(arr, [((False, 0, 0.0, -0.0), (True, 1, 1.5, -2.5)), - ((True, 1, 1.5, -2.5), (False, 2, 3.0, -5.0)), - ((False, 2, 3.0, -5.0), (True, 3, 4.5, -7.5))], nested_dtype) + assert_equal( + arr, + [ + ((False, 0, 0.0, -0.0), (True, 1, 1.5, -2.5)), + ((True, 1, 1.5, -2.5), (False, 2, 3.0, -5.0)), + ((False, 2, 3.0, -5.0), (True, 3, 4.5, -7.5)), + ], + nested_dtype, + ) assert m.print_rec_nested(arr) == [ "n:a=s:0,0,0,-0;b=p:1,1,1.5,-2.5", "n:a=s:1,1,1.5,-2.5;b=p:0,2,3,-5", - "n:a=s:0,2,3,-5;b=p:1,3,4.5,-7.5" + "n:a=s:0,2,3,-5;b=p:1,3,4.5,-7.5", ] arr = m.create_rec_partial(3) assert str(arr.dtype) == partial_dtype_fmt() partial_dtype = arr.dtype - assert '' not in arr.dtype.fields + assert "" not in arr.dtype.fields assert partial_dtype.itemsize > simple_dtype.itemsize assert_equal(arr, elements, simple_dtype) assert_equal(arr, elements, packed_dtype) arr = m.create_rec_partial_nested(3) assert str(arr.dtype) == partial_nested_fmt() - assert '' not in arr.dtype.fields - assert '' not in arr.dtype.fields['a'][0].fields + assert "" not in arr.dtype.fields + assert "" not in arr.dtype.fields["a"][0].fields assert arr.dtype.itemsize > partial_dtype.itemsize - np.testing.assert_equal(arr['a'], m.create_rec_partial(3)) + np.testing.assert_equal(arr["a"], m.create_rec_partial(3)) def test_array_constructors(): - data = np.arange(1, 7, dtype='int32') + data = np.arange(1, 7, dtype="int32") for i in range(8): np.testing.assert_array_equal(m.test_array_ctors(10 + i), data.reshape((3, 2))) np.testing.assert_array_equal(m.test_array_ctors(20 + i), data.reshape((3, 2))) @@ -201,82 +270,92 @@ def test_string_array(): "a='',b=''", "a='a',b='a'", "a='ab',b='ab'", - "a='abc',b='abc'" + "a='abc',b='abc'", ] dtype = arr.dtype - assert arr['a'].tolist() == [b'', b'a', b'ab', b'abc'] - assert arr['b'].tolist() == [b'', b'a', b'ab', b'abc'] + assert arr["a"].tolist() == [b"", b"a", b"ab", b"abc"] + assert arr["b"].tolist() == [b"", b"a", b"ab", b"abc"] arr = m.create_string_array(False) assert dtype == arr.dtype def test_array_array(): from sys import byteorder - e = '<' if byteorder == 'little' else '>' + + e = "<" if byteorder == "little" else ">" arr = m.create_array_array(3) assert str(arr.dtype) == ( - "{{'names':['a','b','c','d'], " + - "'formats':[('S4', (3,)),('" + e + "i4', (2,)),('u1', (3,)),('{e}f4', (4, 2))], " + - "'offsets':[0,12,20,24], 'itemsize':56}}").format(e=e) + "{{'names':['a','b','c','d'], " + + "'formats':[('S4', (3,)),('" + + e + + "i4', (2,)),('u1', (3,)),('{e}f4', (4, 2))], " + + "'offsets':[0,12,20,24], 'itemsize':56}}" + ).format(e=e) assert m.print_array_array(arr) == [ - "a={{A,B,C,D},{K,L,M,N},{U,V,W,X}},b={0,1}," + - "c={0,1,2},d={{0,1},{10,11},{20,21},{30,31}}", - "a={{W,X,Y,Z},{G,H,I,J},{Q,R,S,T}},b={1000,1001}," + - "c={10,11,12},d={{100,101},{110,111},{120,121},{130,131}}", - "a={{S,T,U,V},{C,D,E,F},{M,N,O,P}},b={2000,2001}," + - "c={20,21,22},d={{200,201},{210,211},{220,221},{230,231}}", + "a={{A,B,C,D},{K,L,M,N},{U,V,W,X}},b={0,1}," + + "c={0,1,2},d={{0,1},{10,11},{20,21},{30,31}}", + "a={{W,X,Y,Z},{G,H,I,J},{Q,R,S,T}},b={1000,1001}," + + "c={10,11,12},d={{100,101},{110,111},{120,121},{130,131}}", + "a={{S,T,U,V},{C,D,E,F},{M,N,O,P}},b={2000,2001}," + + "c={20,21,22},d={{200,201},{210,211},{220,221},{230,231}}", ] - assert arr['a'].tolist() == [[b'ABCD', b'KLMN', b'UVWX'], - [b'WXYZ', b'GHIJ', b'QRST'], - [b'STUV', b'CDEF', b'MNOP']] - assert arr['b'].tolist() == [[0, 1], [1000, 1001], [2000, 2001]] + assert arr["a"].tolist() == [ + [b"ABCD", b"KLMN", b"UVWX"], + [b"WXYZ", b"GHIJ", b"QRST"], + [b"STUV", b"CDEF", b"MNOP"], + ] + assert arr["b"].tolist() == [[0, 1], [1000, 1001], [2000, 2001]] assert m.create_array_array(0).dtype == arr.dtype def test_enum_array(): from sys import byteorder - e = '<' if byteorder == 'little' else '>' + + e = "<" if byteorder == "little" else ">" arr = m.create_enum_array(3) dtype = arr.dtype - assert dtype == np.dtype([('e1', e + 'i8'), ('e2', 'u1')]) - assert m.print_enum_array(arr) == [ - "e1=A,e2=X", - "e1=B,e2=Y", - "e1=A,e2=X" - ] - assert arr['e1'].tolist() == [-1, 1, -1] - assert arr['e2'].tolist() == [1, 2, 1] + assert dtype == np.dtype([("e1", e + "i8"), ("e2", "u1")]) + assert m.print_enum_array(arr) == ["e1=A,e2=X", "e1=B,e2=Y", "e1=A,e2=X"] + assert arr["e1"].tolist() == [-1, 1, -1] + assert arr["e2"].tolist() == [1, 2, 1] assert m.create_enum_array(0).dtype == dtype def test_complex_array(): from sys import byteorder - e = '<' if byteorder == 'little' else '>' + + e = "<" if byteorder == "little" else ">" arr = m.create_complex_array(3) dtype = arr.dtype - assert dtype == np.dtype([('cflt', e + 'c8'), ('cdbl', e + 'c16')]) + assert dtype == np.dtype([("cflt", e + "c8"), ("cdbl", e + "c16")]) assert m.print_complex_array(arr) == [ "c:(0,0.25),(0.5,0.75)", "c:(1,1.25),(1.5,1.75)", - "c:(2,2.25),(2.5,2.75)" + "c:(2,2.25),(2.5,2.75)", ] - assert arr['cflt'].tolist() == [0.0 + 0.25j, 1.0 + 1.25j, 2.0 + 2.25j] - assert arr['cdbl'].tolist() == [0.5 + 0.75j, 1.5 + 1.75j, 2.5 + 2.75j] + assert arr["cflt"].tolist() == [0.0 + 0.25j, 1.0 + 1.25j, 2.0 + 2.25j] + assert arr["cdbl"].tolist() == [0.5 + 0.75j, 1.5 + 1.75j, 2.5 + 2.75j] assert m.create_complex_array(0).dtype == dtype def test_signature(doc): - assert doc(m.create_rec_nested) == \ - "create_rec_nested(arg0: int) -> numpy.ndarray[NestedStruct]" + assert ( + doc(m.create_rec_nested) + == "create_rec_nested(arg0: int) -> numpy.ndarray[NestedStruct]" + ) def test_scalar_conversion(): n = 3 - arrays = [m.create_rec_simple(n), m.create_rec_packed(n), - m.create_rec_nested(n), m.create_enum_array(n)] + arrays = [ + m.create_rec_simple(n), + m.create_rec_packed(n), + m.create_rec_nested(n), + m.create_enum_array(n), + ] funcs = [m.f_simple, m.f_packed, m.f_nested] for i, func in enumerate(funcs): @@ -286,18 +365,68 @@ def test_scalar_conversion(): else: with pytest.raises(TypeError) as excinfo: func(arr[0]) - assert 'incompatible function arguments' in str(excinfo.value) + assert "incompatible function arguments" in str(excinfo.value) + + +def test_vectorize(): + n = 3 + array = m.create_rec_simple(n) + values = m.f_simple_vectorized(array) + np.testing.assert_array_equal(values, [0, 10, 20]) + array_2 = m.f_simple_pass_thru_vectorized(array) + np.testing.assert_array_equal(array, array_2) + + +def test_cls_and_dtype_conversion(simple_dtype): + s = m.SimpleStruct() + assert s.astuple() == (False, 0, 0.0, 0.0) + assert m.SimpleStruct.fromtuple(s.astuple()).astuple() == s.astuple() + + s.uint_ = 2 + assert m.f_simple(s) == 20 + + # Try as recarray of shape==(1,). + s_recarray = np.array([(False, 2, 0.0, 0.0)], dtype=simple_dtype) + # Show that this will work for vectorized case. + np.testing.assert_array_equal(m.f_simple_vectorized(s_recarray), [20]) + + # Show as a scalar that inherits from np.generic. + s_scalar = s_recarray[0] + assert isinstance(s_scalar, np.void) + assert m.f_simple(s_scalar) == 20 + + # Show that an *array* scalar (np.ndarray.shape == ()) does not convert. + # More specifically, conversion to SimpleStruct is not implicit. + s_recarray_scalar = s_recarray.reshape(()) + assert isinstance(s_recarray_scalar, np.ndarray) + assert s_recarray_scalar.dtype == simple_dtype + with pytest.raises(TypeError) as excinfo: + m.f_simple(s_recarray_scalar) + assert "incompatible function arguments" in str(excinfo.value) + # Explicitly convert to m.SimpleStruct. + assert m.f_simple(m.SimpleStruct.fromtuple(s_recarray_scalar.item())) == 20 + + # Show that an array of dtype=object does *not* convert. + s_array_object = np.array([s]) + assert s_array_object.dtype == object + with pytest.raises(TypeError) as excinfo: + m.f_simple_vectorized(s_array_object) + assert "incompatible function arguments" in str(excinfo.value) + # Explicitly convert to `np.array(..., dtype=simple_dtype)` + s_array = np.array([s.astuple()], dtype=simple_dtype) + np.testing.assert_array_equal(m.f_simple_vectorized(s_array), [20]) def test_register_dtype(): with pytest.raises(RuntimeError) as excinfo: m.register_dtype() - assert 'dtype is already registered' in str(excinfo.value) + assert "dtype is already registered" in str(excinfo.value) @pytest.mark.xfail("env.PYPY") def test_str_leak(): from sys import getrefcount + fmt = "f4" pytest.gc_collect() start = getrefcount(fmt) diff --git a/pybind11/tests/test_numpy_vectorize.cpp b/pybind11/tests/test_numpy_vectorize.cpp index e76e462cb..eb5281fb1 100644 --- a/pybind11/tests/test_numpy_vectorize.cpp +++ b/pybind11/tests/test_numpy_vectorize.cpp @@ -11,13 +11,15 @@ #include "pybind11_tests.h" #include +#include + double my_func(int x, float y, double z) { py::print("my_func(x:int={}, y:float={:.0f}, z:float={:.0f})"_s.format(x, y, z)); return (float) x*y*z; } TEST_SUBMODULE(numpy_vectorize, m) { - try { py::module::import("numpy"); } + try { py::module_::import("numpy"); } catch (...) { return; } // test_vectorize, test_docs, test_array_collapse @@ -25,11 +27,10 @@ TEST_SUBMODULE(numpy_vectorize, m) { m.def("vectorized_func", py::vectorize(my_func)); // Vectorize a lambda function with a capture object (e.g. to exclude some arguments from the vectorization) - m.def("vectorized_func2", - [](py::array_t x, py::array_t y, float z) { - return py::vectorize([z](int x, float y) { return my_func(x, y, z); })(x, y); - } - ); + m.def("vectorized_func2", [](py::array_t x, py::array_t y, float z) { + return py::vectorize([z](int x, float y) { return my_func(x, y, z); })(std::move(x), + std::move(y)); + }); // Vectorize a complex-valued function m.def("vectorized_func3", py::vectorize( @@ -38,29 +39,40 @@ TEST_SUBMODULE(numpy_vectorize, m) { // test_type_selection // NumPy function which only accepts specific data types - m.def("selective_func", [](py::array_t) { return "Int branch taken."; }); - m.def("selective_func", [](py::array_t) { return "Float branch taken."; }); - m.def("selective_func", [](py::array_t, py::array::c_style>) { return "Complex float branch taken."; }); - + // A lot of these no lints could be replaced with const refs, and probably should at some point. + m.def("selective_func", + [](const py::array_t &) { return "Int branch taken."; }); + m.def("selective_func", + [](const py::array_t &) { return "Float branch taken."; }); + m.def("selective_func", [](const py::array_t, py::array::c_style> &) { + return "Complex float branch taken."; + }); // test_passthrough_arguments // Passthrough test: references and non-pod types should be automatically passed through (in the // function definition below, only `b`, `d`, and `g` are vectorized): struct NonPODClass { - NonPODClass(int v) : value{v} {} + explicit NonPODClass(int v) : value{v} {} int value; }; - py::class_(m, "NonPODClass").def(py::init()); - m.def("vec_passthrough", py::vectorize( - [](double *a, double b, py::array_t c, const int &d, int &e, NonPODClass f, const double g) { - return *a + b + c.at(0) + d + e + f.value + g; - } - )); + py::class_(m, "NonPODClass") + .def(py::init()) + .def_readwrite("value", &NonPODClass::value); + m.def("vec_passthrough", + py::vectorize([](const double *a, + double b, + // Changing this broke things + // NOLINTNEXTLINE(performance-unnecessary-value-param) + py::array_t c, + const int &d, + int &e, + NonPODClass f, + const double g) { return *a + b + c.at(0) + d + e + f.value + g; })); // test_method_vectorization struct VectorizeTestClass { - VectorizeTestClass(int v) : value{v} {}; - float method(int x, float y) { return y + (float) (x + value); } + explicit VectorizeTestClass(int v) : value{v} {}; + float method(int x, float y) const { return y + (float) (x + value); } int value = 0; }; py::class_ vtc(m, "VectorizeTestClass"); @@ -76,14 +88,16 @@ TEST_SUBMODULE(numpy_vectorize, m) { .value("f_trivial", py::detail::broadcast_trivial::f_trivial) .value("c_trivial", py::detail::broadcast_trivial::c_trivial) .value("non_trivial", py::detail::broadcast_trivial::non_trivial); - m.def("vectorized_is_trivial", []( - py::array_t arg1, - py::array_t arg2, - py::array_t arg3 - ) { - ssize_t ndim; - std::vector shape; - std::array buffers {{ arg1.request(), arg2.request(), arg3.request() }}; - return py::detail::broadcast(buffers, ndim, shape); - }); + m.def("vectorized_is_trivial", + [](const py::array_t &arg1, + const py::array_t &arg2, + const py::array_t &arg3) { + py::ssize_t ndim = 0; + std::vector shape; + std::array buffers{ + {arg1.request(), arg2.request(), arg3.request()}}; + return py::detail::broadcast(buffers, ndim, shape); + }); + + m.def("add_to", py::vectorize([](NonPODClass& x, int a) { x.value += a; })); } diff --git a/pybind11/tests/test_numpy_vectorize.py b/pybind11/tests/test_numpy_vectorize.py index 54e44cd8d..de5c9a607 100644 --- a/pybind11/tests/test_numpy_vectorize.py +++ b/pybind11/tests/test_numpy_vectorize.py @@ -1,5 +1,6 @@ # -*- coding: utf-8 -*- import pytest + from pybind11_tests import numpy_vectorize as m np = pytest.importorskip("numpy") @@ -17,28 +18,40 @@ def test_vectorize(capture): assert capture == "my_func(x:int=1, y:float=2, z:float=3)" with capture: assert np.allclose(f(np.array([1, 3]), np.array([2, 4]), 3), [6, 36]) - assert capture == """ + assert ( + capture + == """ my_func(x:int=1, y:float=2, z:float=3) my_func(x:int=3, y:float=4, z:float=3) """ + ) with capture: - a = np.array([[1, 2], [3, 4]], order='F') - b = np.array([[10, 20], [30, 40]], order='F') + a = np.array([[1, 2], [3, 4]], order="F") + b = np.array([[10, 20], [30, 40]], order="F") c = 3 result = f(a, b, c) assert np.allclose(result, a * b * c) assert result.flags.f_contiguous # All inputs are F order and full or singletons, so we the result is in col-major order: - assert capture == """ + assert ( + capture + == """ my_func(x:int=1, y:float=10, z:float=3) my_func(x:int=3, y:float=30, z:float=3) my_func(x:int=2, y:float=20, z:float=3) my_func(x:int=4, y:float=40, z:float=3) """ + ) with capture: - a, b, c = np.array([[1, 3, 5], [7, 9, 11]]), np.array([[2, 4, 6], [8, 10, 12]]), 3 + a, b, c = ( + np.array([[1, 3, 5], [7, 9, 11]]), + np.array([[2, 4, 6], [8, 10, 12]]), + 3, + ) assert np.allclose(f(a, b, c), a * b * c) - assert capture == """ + assert ( + capture + == """ my_func(x:int=1, y:float=2, z:float=3) my_func(x:int=3, y:float=4, z:float=3) my_func(x:int=5, y:float=6, z:float=3) @@ -46,10 +59,13 @@ def test_vectorize(capture): my_func(x:int=9, y:float=10, z:float=3) my_func(x:int=11, y:float=12, z:float=3) """ + ) with capture: a, b, c = np.array([[1, 2, 3], [4, 5, 6]]), np.array([2, 3, 4]), 2 assert np.allclose(f(a, b, c), a * b * c) - assert capture == """ + assert ( + capture + == """ my_func(x:int=1, y:float=2, z:float=2) my_func(x:int=2, y:float=3, z:float=2) my_func(x:int=3, y:float=4, z:float=2) @@ -57,10 +73,13 @@ def test_vectorize(capture): my_func(x:int=5, y:float=3, z:float=2) my_func(x:int=6, y:float=4, z:float=2) """ + ) with capture: a, b, c = np.array([[1, 2, 3], [4, 5, 6]]), np.array([[2], [3]]), 2 assert np.allclose(f(a, b, c), a * b * c) - assert capture == """ + assert ( + capture + == """ my_func(x:int=1, y:float=2, z:float=2) my_func(x:int=2, y:float=2, z:float=2) my_func(x:int=3, y:float=2, z:float=2) @@ -68,10 +87,17 @@ def test_vectorize(capture): my_func(x:int=5, y:float=3, z:float=2) my_func(x:int=6, y:float=3, z:float=2) """ + ) with capture: - a, b, c = np.array([[1, 2, 3], [4, 5, 6]], order='F'), np.array([[2], [3]]), 2 + a, b, c = ( + np.array([[1, 2, 3], [4, 5, 6]], order="F"), + np.array([[2], [3]]), + 2, + ) assert np.allclose(f(a, b, c), a * b * c) - assert capture == """ + assert ( + capture + == """ my_func(x:int=1, y:float=2, z:float=2) my_func(x:int=2, y:float=2, z:float=2) my_func(x:int=3, y:float=2, z:float=2) @@ -79,36 +105,53 @@ def test_vectorize(capture): my_func(x:int=5, y:float=3, z:float=2) my_func(x:int=6, y:float=3, z:float=2) """ + ) with capture: a, b, c = np.array([[1, 2, 3], [4, 5, 6]])[::, ::2], np.array([[2], [3]]), 2 assert np.allclose(f(a, b, c), a * b * c) - assert capture == """ + assert ( + capture + == """ my_func(x:int=1, y:float=2, z:float=2) my_func(x:int=3, y:float=2, z:float=2) my_func(x:int=4, y:float=3, z:float=2) my_func(x:int=6, y:float=3, z:float=2) """ + ) with capture: - a, b, c = np.array([[1, 2, 3], [4, 5, 6]], order='F')[::, ::2], np.array([[2], [3]]), 2 + a, b, c = ( + np.array([[1, 2, 3], [4, 5, 6]], order="F")[::, ::2], + np.array([[2], [3]]), + 2, + ) assert np.allclose(f(a, b, c), a * b * c) - assert capture == """ + assert ( + capture + == """ my_func(x:int=1, y:float=2, z:float=2) my_func(x:int=3, y:float=2, z:float=2) my_func(x:int=4, y:float=3, z:float=2) my_func(x:int=6, y:float=3, z:float=2) """ + ) def test_type_selection(): assert m.selective_func(np.array([1], dtype=np.int32)) == "Int branch taken." assert m.selective_func(np.array([1.0], dtype=np.float32)) == "Float branch taken." - assert m.selective_func(np.array([1.0j], dtype=np.complex64)) == "Complex float branch taken." + assert ( + m.selective_func(np.array([1.0j], dtype=np.complex64)) + == "Complex float branch taken." + ) def test_docs(doc): - assert doc(m.vectorized_func) == """ + assert ( + doc(m.vectorized_func) + == """ vectorized_func(arg0: numpy.ndarray[numpy.int32], arg1: numpy.ndarray[numpy.float32], arg2: numpy.ndarray[numpy.float64]) -> object """ # noqa: E501 line too long + ) def test_trivial_broadcasting(): @@ -116,16 +159,24 @@ def test_trivial_broadcasting(): assert vectorized_is_trivial(1, 2, 3) == trivial.c_trivial assert vectorized_is_trivial(np.array(1), np.array(2), 3) == trivial.c_trivial - assert vectorized_is_trivial(np.array([1, 3]), np.array([2, 4]), 3) == trivial.c_trivial + assert ( + vectorized_is_trivial(np.array([1, 3]), np.array([2, 4]), 3) + == trivial.c_trivial + ) assert trivial.c_trivial == vectorized_is_trivial( - np.array([[1, 3, 5], [7, 9, 11]]), np.array([[2, 4, 6], [8, 10, 12]]), 3) - assert vectorized_is_trivial( - np.array([[1, 2, 3], [4, 5, 6]]), np.array([2, 3, 4]), 2) == trivial.non_trivial - assert vectorized_is_trivial( - np.array([[1, 2, 3], [4, 5, 6]]), np.array([[2], [3]]), 2) == trivial.non_trivial - z1 = np.array([[1, 2, 3, 4], [5, 6, 7, 8]], dtype='int32') - z2 = np.array(z1, dtype='float32') - z3 = np.array(z1, dtype='float64') + np.array([[1, 3, 5], [7, 9, 11]]), np.array([[2, 4, 6], [8, 10, 12]]), 3 + ) + assert ( + vectorized_is_trivial(np.array([[1, 2, 3], [4, 5, 6]]), np.array([2, 3, 4]), 2) + == trivial.non_trivial + ) + assert ( + vectorized_is_trivial(np.array([[1, 2, 3], [4, 5, 6]]), np.array([[2], [3]]), 2) + == trivial.non_trivial + ) + z1 = np.array([[1, 2, 3, 4], [5, 6, 7, 8]], dtype="int32") + z2 = np.array(z1, dtype="float32") + z3 = np.array(z1, dtype="float64") assert vectorized_is_trivial(z1, z2, z3) == trivial.c_trivial assert vectorized_is_trivial(1, z2, z3) == trivial.c_trivial assert vectorized_is_trivial(z1, 1, z3) == trivial.c_trivial @@ -135,7 +186,7 @@ def test_trivial_broadcasting(): assert vectorized_is_trivial(1, 1, z3[::2, ::2]) == trivial.non_trivial assert vectorized_is_trivial(z1, 1, z3[1::4, 1::4]) == trivial.c_trivial - y1 = np.array(z1, order='F') + y1 = np.array(z1, order="F") y2 = np.array(y1) y3 = np.array(y1) assert vectorized_is_trivial(y1, y2, y3) == trivial.f_trivial @@ -156,30 +207,41 @@ def test_trivial_broadcasting(): def test_passthrough_arguments(doc): assert doc(m.vec_passthrough) == ( - "vec_passthrough(" + ", ".join([ - "arg0: float", - "arg1: numpy.ndarray[numpy.float64]", - "arg2: numpy.ndarray[numpy.float64]", - "arg3: numpy.ndarray[numpy.int32]", - "arg4: int", - "arg5: m.numpy_vectorize.NonPODClass", - "arg6: numpy.ndarray[numpy.float64]"]) + ") -> object") + "vec_passthrough(" + + ", ".join( + [ + "arg0: float", + "arg1: numpy.ndarray[numpy.float64]", + "arg2: numpy.ndarray[numpy.float64]", + "arg3: numpy.ndarray[numpy.int32]", + "arg4: int", + "arg5: m.numpy_vectorize.NonPODClass", + "arg6: numpy.ndarray[numpy.float64]", + ] + ) + + ") -> object" + ) - b = np.array([[10, 20, 30]], dtype='float64') + b = np.array([[10, 20, 30]], dtype="float64") c = np.array([100, 200]) # NOT a vectorized argument - d = np.array([[1000], [2000], [3000]], dtype='int') - g = np.array([[1000000, 2000000, 3000000]], dtype='int') # requires casting + d = np.array([[1000], [2000], [3000]], dtype="int") + g = np.array([[1000000, 2000000, 3000000]], dtype="int") # requires casting assert np.all( - m.vec_passthrough(1, b, c, d, 10000, m.NonPODClass(100000), g) == - np.array([[1111111, 2111121, 3111131], - [1112111, 2112121, 3112131], - [1113111, 2113121, 3113131]])) + m.vec_passthrough(1, b, c, d, 10000, m.NonPODClass(100000), g) + == np.array( + [ + [1111111, 2111121, 3111131], + [1112111, 2112121, 3112131], + [1113111, 2113121, 3113131], + ] + ) + ) def test_method_vectorization(): o = m.VectorizeTestClass(3) - x = np.array([1, 2], dtype='int') - y = np.array([[10], [20]], dtype='float32') + x = np.array([1, 2], dtype="int") + y = np.array([[10], [20]], dtype="float32") assert np.all(o.method(x, y) == [[14, 15], [24, 25]]) @@ -188,7 +250,18 @@ def test_array_collapse(): assert not isinstance(m.vectorized_func(np.array(1), 2, 3), np.ndarray) z = m.vectorized_func([1], 2, 3) assert isinstance(z, np.ndarray) - assert z.shape == (1, ) + assert z.shape == (1,) z = m.vectorized_func(1, [[[2]]], 3) assert isinstance(z, np.ndarray) assert z.shape == (1, 1, 1) + + +def test_vectorized_noreturn(): + x = m.NonPODClass(0) + assert x.value == 0 + m.add_to(x, [1, 2, 3, 4]) + assert x.value == 10 + m.add_to(x, 1) + assert x.value == 11 + m.add_to(x, [[1, 1], [2, 3]]) + assert x.value == 18 diff --git a/pybind11/tests/test_opaque_types.cpp b/pybind11/tests/test_opaque_types.cpp index 594c45a08..804de6d4f 100644 --- a/pybind11/tests/test_opaque_types.cpp +++ b/pybind11/tests/test_opaque_types.cpp @@ -44,7 +44,7 @@ TEST_SUBMODULE(opaque_types, m) { m.def("print_opaque_list", [](const StringList &l) { std::string ret = "Opaque list: ["; bool first = true; - for (auto entry : l) { + for (const auto &entry : l) { if (!first) ret += ", "; ret += entry; @@ -64,4 +64,10 @@ TEST_SUBMODULE(opaque_types, m) { result->push_back("some value"); return std::unique_ptr(result); }); + + // test unions + py::class_(m, "IntFloat") + .def(py::init<>()) + .def_readwrite("i", &IntFloat::i) + .def_readwrite("f", &IntFloat::f); } diff --git a/pybind11/tests/test_opaque_types.py b/pybind11/tests/test_opaque_types.py index 3f2392775..5495cb6b4 100644 --- a/pybind11/tests/test_opaque_types.py +++ b/pybind11/tests/test_opaque_types.py @@ -1,7 +1,8 @@ # -*- coding: utf-8 -*- import pytest -from pybind11_tests import opaque_types as m + from pybind11_tests import ConstructorStats, UserType +from pybind11_tests import opaque_types as m def test_string_list(): @@ -32,12 +33,15 @@ def test_pointers(msg): with pytest.raises(TypeError) as excinfo: m.get_void_ptr_value([1, 2, 3]) # This should not work - assert msg(excinfo.value) == """ + assert ( + msg(excinfo.value) + == """ get_void_ptr_value(): incompatible function arguments. The following argument types are supported: 1. (arg0: capsule) -> int Invoked with: [1, 2, 3] """ # noqa: E501 line too long + ) assert m.return_null_str() is None assert m.get_null_str_value(m.return_null_str()) is not None @@ -45,3 +49,11 @@ def test_pointers(msg): ptr = m.return_unique_ptr() assert "StringList" in repr(ptr) assert m.print_opaque_list(ptr) == "Opaque list: [some value]" + + +def test_unions(): + int_float_union = m.IntFloat() + int_float_union.i = 42 + assert int_float_union.i == 42 + int_float_union.f = 3.0 + assert int_float_union.f == 3.0 diff --git a/pybind11/tests/test_operator_overloading.cpp b/pybind11/tests/test_operator_overloading.cpp index d55495471..ffa059d5b 100644 --- a/pybind11/tests/test_operator_overloading.cpp +++ b/pybind11/tests/test_operator_overloading.cpp @@ -7,18 +7,28 @@ BSD-style license that can be found in the LICENSE file. */ -#include "pybind11_tests.h" #include "constructor_stats.h" -#include +#include "pybind11_tests.h" #include +#include +#include class Vector2 { public: Vector2(float x, float y) : x(x), y(y) { print_created(this, toString()); } Vector2(const Vector2 &v) : x(v.x), y(v.y) { print_copy_created(this); } - Vector2(Vector2 &&v) : x(v.x), y(v.y) { print_move_created(this); v.x = v.y = 0; } + Vector2(Vector2 &&v) noexcept : x(v.x), y(v.y) { + print_move_created(this); + v.x = v.y = 0; + } Vector2 &operator=(const Vector2 &v) { x = v.x; y = v.y; print_copy_assigned(this); return *this; } - Vector2 &operator=(Vector2 &&v) { x = v.x; y = v.y; v.x = v.y = 0; print_move_assigned(this); return *this; } + Vector2 &operator=(Vector2 &&v) noexcept { + x = v.x; + y = v.y; + v.x = v.y = 0; + print_move_assigned(this); + return *this; + } ~Vector2() { print_destroyed(this); } std::string toString() const { return "[" + std::to_string(x) + ", " + std::to_string(y) + "]"; } @@ -62,6 +72,12 @@ int operator+(const C2 &, const C2 &) { return 22; } int operator+(const C2 &, const C1 &) { return 21; } int operator+(const C1 &, const C2 &) { return 12; } +struct HashMe { + std::string member; +}; + +bool operator==(const HashMe &lhs, const HashMe &rhs) { return lhs.member == rhs.member; } + // Note: Specializing explicit within `namespace std { ... }` is done due to a // bug in GCC<7. If you are supporting compilers later than this, consider // specializing `using template<> struct std::hash<...>` in the global @@ -73,6 +89,14 @@ namespace std { // Not a good hash function, but easy to test size_t operator()(const Vector2 &) { return 4; } }; + + // HashMe has a hash function in C++ but no `__hash__` for Python. + template <> + struct hash { + std::size_t operator()(const HashMe &selector) const { + return std::hash()(selector.member); + } + }; } // namespace std // Not a good abs function, but easy to test. @@ -80,8 +104,8 @@ std::string abs(const Vector2&) { return "abs(Vector2)"; } -// MSVC warns about unknown pragmas, and warnings are errors. -#ifndef _MSC_VER +// MSVC & Intel warns about unknown pragmas, and warnings are errors. +#if !defined(_MSC_VER) && !defined(__INTEL_COMPILER) #pragma GCC diagnostic push // clang 7.0.0 and Apple LLVM 10.0.1 introduce `-Wself-assign-overloaded` to // `-Wall`, which is used here for overloading (e.g. `py::self += py::self `). @@ -89,7 +113,7 @@ std::string abs(const Vector2&) { // Taken from: https://github.com/RobotLocomotion/drake/commit/aaf84b46 // TODO(eric): This could be resolved using a function / functor (e.g. `py::self()`). #if defined(__APPLE__) && defined(__clang__) - #if (__clang_major__ >= 10) && (__clang_minor__ >= 0) && (__clang_patchlevel__ >= 1) + #if (__clang_major__ >= 10) #pragma GCC diagnostic ignored "-Wself-assign-overloaded" #endif #elif defined(__clang__) @@ -219,8 +243,12 @@ TEST_SUBMODULE(operators, m) { .def("__hash__", &Hashable::hash) .def(py::init()) .def(py::self == py::self); -} -#ifndef _MSC_VER + // define __eq__ but not __hash__ + py::class_(m, "HashMe").def(py::self == py::self); + + m.def("get_unhashable_HashMe_set", []() { return std::unordered_set{{"one"}}; }); +} +#if !defined(_MSC_VER) && !defined(__INTEL_COMPILER) #pragma GCC diagnostic pop #endif diff --git a/pybind11/tests/test_operator_overloading.py b/pybind11/tests/test_operator_overloading.py index 39e3aee27..8cf375b6d 100644 --- a/pybind11/tests/test_operator_overloading.py +++ b/pybind11/tests/test_operator_overloading.py @@ -1,7 +1,9 @@ # -*- coding: utf-8 -*- import pytest -from pybind11_tests import operators as m + +import env from pybind11_tests import ConstructorStats +from pybind11_tests import operators as m def test_operator_overloading(): @@ -56,23 +58,23 @@ def test_operator_overloading(): del v3 assert cstats.alive() == 0 assert cstats.values() == [ - '[1.000000, 2.000000]', - '[3.000000, -1.000000]', - '[1.000000, 2.000000]', - '[-3.000000, 1.000000]', - '[4.000000, 1.000000]', - '[-2.000000, 3.000000]', - '[-7.000000, -6.000000]', - '[9.000000, 10.000000]', - '[8.000000, 16.000000]', - '[0.125000, 0.250000]', - '[7.000000, 6.000000]', - '[9.000000, 10.000000]', - '[8.000000, 16.000000]', - '[8.000000, 4.000000]', - '[3.000000, -2.000000]', - '[3.000000, -0.500000]', - '[6.000000, -2.000000]', + "[1.000000, 2.000000]", + "[3.000000, -1.000000]", + "[1.000000, 2.000000]", + "[-3.000000, 1.000000]", + "[4.000000, 1.000000]", + "[-2.000000, 3.000000]", + "[-7.000000, -6.000000]", + "[9.000000, 10.000000]", + "[8.000000, 16.000000]", + "[0.125000, 0.250000]", + "[7.000000, 6.000000]", + "[9.000000, 10.000000]", + "[8.000000, 16.000000]", + "[8.000000, 4.000000]", + "[3.000000, -2.000000]", + "[3.000000, -0.500000]", + "[6.000000, -2.000000]", ] assert cstats.default_constructions == 0 assert cstats.copy_constructions == 0 @@ -134,8 +136,9 @@ def test_overriding_eq_reset_hash(): assert m.Comparable(15) is not m.Comparable(15) assert m.Comparable(15) == m.Comparable(15) - with pytest.raises(TypeError): - hash(m.Comparable(15)) # TypeError: unhashable type: 'm.Comparable' + with pytest.raises(TypeError) as excinfo: + hash(m.Comparable(15)) + assert str(excinfo.value).startswith("unhashable type:") for hashable in (m.Hashable, m.Hashable2): assert hashable(15) is not hashable(15) @@ -143,3 +146,10 @@ def test_overriding_eq_reset_hash(): assert hash(hashable(15)) == 15 assert hash(hashable(15)) == hash(hashable(15)) + + +def test_return_set_of_unhashable(): + with pytest.raises(TypeError) as excinfo: + m.get_unhashable_HashMe_set() + if not env.PY2: + assert str(excinfo.value.__cause__).startswith("unhashable type:") diff --git a/pybind11/tests/test_pickling.cpp b/pybind11/tests/test_pickling.cpp index 9dc63bda3..b77636dd1 100644 --- a/pybind11/tests/test_pickling.cpp +++ b/pybind11/tests/test_pickling.cpp @@ -1,7 +1,9 @@ +// clang-format off /* tests/test_pickling.cpp -- pickle support Copyright (c) 2016 Wenzel Jakob + Copyright (c) 2021 The Pybind Development Team. All rights reserved. Use of this source code is governed by a BSD-style license that can be found in the LICENSE file. @@ -9,11 +11,63 @@ #include "pybind11_tests.h" +// clang-format on + +#include +#include +#include + +namespace exercise_trampoline { + +struct SimpleBase { + int num = 0; + virtual ~SimpleBase() = default; + + // For compatibility with old clang versions: + SimpleBase() = default; + SimpleBase(const SimpleBase &) = default; +}; + +struct SimpleBaseTrampoline : SimpleBase {}; + +struct SimpleCppDerived : SimpleBase {}; + +void wrap(py::module m) { + py::class_(m, "SimpleBase") + .def(py::init<>()) + .def_readwrite("num", &SimpleBase::num) + .def(py::pickle( + [](const py::object &self) { + py::dict d; + if (py::hasattr(self, "__dict__")) + d = self.attr("__dict__"); + return py::make_tuple(self.attr("num"), d); + }, + [](const py::tuple &t) { + if (t.size() != 2) + throw std::runtime_error("Invalid state!"); + auto cpp_state = std::unique_ptr(new SimpleBaseTrampoline); + cpp_state->num = t[0].cast(); + auto py_state = t[1].cast(); + return std::make_pair(std::move(cpp_state), py_state); + })); + + m.def("make_SimpleCppDerivedAsBase", + []() { return std::unique_ptr(new SimpleCppDerived); }); + m.def("check_dynamic_cast_SimpleCppDerived", [](const SimpleBase *base_ptr) { + return dynamic_cast(base_ptr) != nullptr; + }); +} + +} // namespace exercise_trampoline + +// clang-format off + TEST_SUBMODULE(pickling, m) { // test_roundtrip class Pickleable { public: - Pickleable(const std::string &value) : m_value(value) { } + explicit Pickleable(const std::string &value) : m_value(value) { } const std::string &value() const { return m_value; } void setExtra1(int extra1) { m_extra1 = extra1; } @@ -31,7 +85,8 @@ TEST_SUBMODULE(pickling, m) { using Pickleable::Pickleable; }; - py::class_(m, "Pickleable") + py::class_ pyPickleable(m, "Pickleable"); + pyPickleable .def(py::init()) .def("value", &Pickleable::value) .def("extra1", &Pickleable::extra1) @@ -43,8 +98,9 @@ TEST_SUBMODULE(pickling, m) { .def("__getstate__", [](const Pickleable &p) { /* Return a tuple that fully encodes the state of the object */ return py::make_tuple(p.value(), p.extra1(), p.extra2()); - }) - .def("__setstate__", [](Pickleable &p, py::tuple t) { + }); + ignoreOldStyleInitWarnings([&pyPickleable]() { + pyPickleable.def("__setstate__", [](Pickleable &p, const py::tuple &t) { if (t.size() != 3) throw std::runtime_error("Invalid state!"); /* Invoke the constructor (need to use in-place version) */ @@ -54,6 +110,7 @@ TEST_SUBMODULE(pickling, m) { p.setExtra1(t[1].cast()); p.setExtra2(t[2].cast()); }); + }); py::class_(m, "PickleableNew") .def(py::init()) @@ -61,7 +118,7 @@ TEST_SUBMODULE(pickling, m) { [](const PickleableNew &p) { return py::make_tuple(p.value(), p.extra1(), p.extra2()); }, - [](py::tuple t) { + [](const py::tuple &t) { if (t.size() != 3) throw std::runtime_error("Invalid state!"); auto p = PickleableNew(t[0].cast()); @@ -69,14 +126,13 @@ TEST_SUBMODULE(pickling, m) { p.setExtra1(t[1].cast()); p.setExtra2(t[2].cast()); return p; - } - )); + })); #if !defined(PYPY_VERSION) // test_roundtrip_with_dict class PickleableWithDict { public: - PickleableWithDict(const std::string &value) : value(value) { } + explicit PickleableWithDict(const std::string &value) : value(value) { } std::string value; int extra; @@ -87,19 +143,20 @@ TEST_SUBMODULE(pickling, m) { using PickleableWithDict::PickleableWithDict; }; - py::class_(m, "PickleableWithDict", py::dynamic_attr()) - .def(py::init()) + py::class_ pyPickleableWithDict(m, "PickleableWithDict", py::dynamic_attr()); + pyPickleableWithDict.def(py::init()) .def_readwrite("value", &PickleableWithDict::value) .def_readwrite("extra", &PickleableWithDict::extra) - .def("__getstate__", [](py::object self) { + .def("__getstate__", [](const py::object &self) { /* Also include __dict__ in state */ return py::make_tuple(self.attr("value"), self.attr("extra"), self.attr("__dict__")); - }) - .def("__setstate__", [](py::object self, py::tuple t) { + }); + ignoreOldStyleInitWarnings([&pyPickleableWithDict]() { + pyPickleableWithDict.def("__setstate__", [](const py::object &self, const py::tuple &t) { if (t.size() != 3) throw std::runtime_error("Invalid state!"); /* Cast and construct */ - auto& p = self.cast(); + auto &p = self.cast(); new (&p) PickleableWithDict(t[0].cast()); /* Assign C++ state */ @@ -108,11 +165,12 @@ TEST_SUBMODULE(pickling, m) { /* Assign Python state */ self.attr("__dict__") = t[2]; }); + }); py::class_(m, "PickleableWithDictNew") .def(py::init()) .def(py::pickle( - [](py::object self) { + [](const py::object &self) { return py::make_tuple(self.attr("value"), self.attr("extra"), self.attr("__dict__")); }, [](const py::tuple &t) { @@ -124,7 +182,8 @@ TEST_SUBMODULE(pickling, m) { auto py_state = t[2].cast(); return std::make_pair(cpp_state, py_state); - } - )); + })); #endif + + exercise_trampoline::wrap(m); } diff --git a/pybind11/tests/test_pickling.py b/pybind11/tests/test_pickling.py index 9aee70505..9f68f37dc 100644 --- a/pybind11/tests/test_pickling.py +++ b/pybind11/tests/test_pickling.py @@ -1,8 +1,7 @@ # -*- coding: utf-8 -*- import pytest -import env # noqa: F401 - +import env from pybind11_tests import pickling as m try: @@ -42,5 +41,42 @@ def test_roundtrip_with_dict(cls_name): def test_enum_pickle(): from pybind11_tests import enums as e + data = pickle.dumps(e.EOne, 2) assert e.EOne == pickle.loads(data) + + +# +# exercise_trampoline +# +class SimplePyDerived(m.SimpleBase): + pass + + +def test_roundtrip_simple_py_derived(): + p = SimplePyDerived() + p.num = 202 + p.stored_in_dict = 303 + data = pickle.dumps(p, pickle.HIGHEST_PROTOCOL) + p2 = pickle.loads(data) + assert isinstance(p2, SimplePyDerived) + assert p2.num == 202 + assert p2.stored_in_dict == 303 + + +def test_roundtrip_simple_cpp_derived(): + p = m.make_SimpleCppDerivedAsBase() + assert m.check_dynamic_cast_SimpleCppDerived(p) + p.num = 404 + if not env.PYPY: + # To ensure that this unit test is not accidentally invalidated. + with pytest.raises(AttributeError): + # Mimics the `setstate` C++ implementation. + setattr(p, "__dict__", {}) # noqa: B010 + data = pickle.dumps(p, pickle.HIGHEST_PROTOCOL) + p2 = pickle.loads(data) + assert isinstance(p2, m.SimpleBase) + assert p2.num == 404 + # Issue #3062: pickleable base C++ classes can incur object slicing + # if derived typeid is not registered with pybind11 + assert not m.check_dynamic_cast_SimpleCppDerived(p2) diff --git a/pybind11/tests/test_pytypes.cpp b/pybind11/tests/test_pytypes.cpp index 4ef1b9ff0..85cb98fcb 100644 --- a/pybind11/tests/test_pytypes.cpp +++ b/pybind11/tests/test_pytypes.cpp @@ -7,17 +7,28 @@ BSD-style license that can be found in the LICENSE file. */ +#include + #include "pybind11_tests.h" TEST_SUBMODULE(pytypes, m) { + // test_bool + m.def("get_bool", []{return py::bool_(false);}); // test_int m.def("get_int", []{return py::int_(0);}); // test_iterator m.def("get_iterator", []{return py::iterator();}); // test_iterable m.def("get_iterable", []{return py::iterable();}); + // test_float + m.def("get_float", []{return py::float_(0.0f);}); // test_list + m.def("list_no_args", []() { return py::list{}; }); + m.def("list_ssize_t", []() { return py::list{(py::ssize_t) 0}; }); + m.def("list_size_t", []() { return py::list{(py::size_t) 0}; }); + m.def("list_insert_ssize_t", [](py::list *l) { return l->insert((py::ssize_t) 1, 83); }); + m.def("list_insert_size_t", [](py::list *l) { return l->insert((py::size_t) 3, 57); }); m.def("get_list", []() { py::list list; list.append("value"); @@ -27,16 +38,14 @@ TEST_SUBMODULE(pytypes, m) { list.insert(2, "inserted-2"); return list; }); - m.def("print_list", [](py::list list) { + m.def("print_list", [](const py::list &list) { int index = 0; for (auto item : list) py::print("list item {}: {}"_s.format(index++, item)); }); // test_none m.def("get_none", []{return py::none();}); - m.def("print_none", [](py::none none) { - py::print("none: {}"_s.format(none)); - }); + m.def("print_none", [](const py::none &none) { py::print("none: {}"_s.format(none)); }); // test_set m.def("get_set", []() { @@ -46,20 +55,17 @@ TEST_SUBMODULE(pytypes, m) { set.add(std::string("key3")); return set; }); - m.def("print_set", [](py::set set) { + m.def("print_set", [](const py::set &set) { for (auto item : set) py::print("key:", item); }); - m.def("set_contains", [](py::set set, py::object key) { - return set.contains(key); - }); - m.def("set_contains", [](py::set set, const char* key) { - return set.contains(key); - }); + m.def("set_contains", + [](const py::set &set, const py::object &key) { return set.contains(key); }); + m.def("set_contains", [](const py::set &set, const char *key) { return set.contains(key); }); // test_dict m.def("get_dict", []() { return py::dict("key"_a="value"); }); - m.def("print_dict", [](py::dict dict) { + m.def("print_dict", [](const py::dict &dict) { for (auto item : dict) py::print("key: {}, value={}"_s.format(item.first, item.second)); }); @@ -68,19 +74,38 @@ TEST_SUBMODULE(pytypes, m) { auto d2 = py::dict("z"_a=3, **d1); return d2; }); - m.def("dict_contains", [](py::dict dict, py::object val) { - return dict.contains(val); - }); - m.def("dict_contains", [](py::dict dict, const char* val) { - return dict.contains(val); + m.def("dict_contains", + [](const py::dict &dict, py::object val) { return dict.contains(val); }); + m.def("dict_contains", + [](const py::dict &dict, const char *val) { return dict.contains(val); }); + + // test_tuple + m.def("tuple_no_args", []() { return py::tuple{}; }); + m.def("tuple_ssize_t", []() { return py::tuple{(py::ssize_t) 0}; }); + m.def("tuple_size_t", []() { return py::tuple{(py::size_t) 0}; }); + m.def("get_tuple", []() { return py::make_tuple(42, py::none(), "spam"); }); + +#if PY_VERSION_HEX >= 0x03030000 + // test_simple_namespace + m.def("get_simple_namespace", []() { + auto ns = py::module_::import("types").attr("SimpleNamespace")("attr"_a=42, "x"_a="foo", "wrong"_a=1); + py::delattr(ns, "wrong"); + py::setattr(ns, "right", py::int_(2)); + return ns; }); +#endif // test_str + m.def("str_from_char_ssize_t", []() { return py::str{"red", (py::ssize_t) 3}; }); + m.def("str_from_char_size_t", []() { return py::str{"blue", (py::size_t) 4}; }); m.def("str_from_string", []() { return py::str(std::string("baz")); }); m.def("str_from_bytes", []() { return py::str(py::bytes("boo", 3)); }); m.def("str_from_object", [](const py::object& obj) { return py::str(obj); }); m.def("repr_from_object", [](const py::object& obj) { return py::repr(obj); }); m.def("str_from_handle", [](py::handle h) { return py::str(h); }); + m.def("str_from_string_from_str", [](const py::str& obj) { + return py::str(static_cast(obj)); + }); m.def("str_format", []() { auto s1 = "{} + {} = {}"_s.format(1, 2, 3); @@ -89,9 +114,17 @@ TEST_SUBMODULE(pytypes, m) { }); // test_bytes + m.def("bytes_from_char_ssize_t", []() { return py::bytes{"green", (py::ssize_t) 5}; }); + m.def("bytes_from_char_size_t", []() { return py::bytes{"purple", (py::size_t) 6}; }); m.def("bytes_from_string", []() { return py::bytes(std::string("foo")); }); m.def("bytes_from_str", []() { return py::bytes(py::str("bar", 3)); }); + // test bytearray + m.def("bytearray_from_char_ssize_t", []() { return py::bytearray{"$%", (py::ssize_t) 2}; }); + m.def("bytearray_from_char_size_t", []() { return py::bytearray{"@$!", (py::size_t) 3}; }); + m.def("bytearray_from_string", []() { return py::bytearray(std::string("foo")); }); + m.def("bytearray_size", []() { return py::bytearray("foo").size(); }); + // test_capsule m.def("return_capsule_with_destructor", []() { py::print("creating capsule"); @@ -108,7 +141,7 @@ TEST_SUBMODULE(pytypes, m) { }); m.def("return_capsule_with_name_and_destructor", []() { - auto capsule = py::capsule((void *) 1234, "pointer type description", [](PyObject *ptr) { + auto capsule = py::capsule((void *) 12345, "pointer type description", [](PyObject *ptr) { if (ptr) { auto name = PyCapsule_GetName(ptr); py::print("destructing capsule ({}, '{}')"_s.format( @@ -116,19 +149,30 @@ TEST_SUBMODULE(pytypes, m) { )); } }); - void *contents = capsule; - py::print("created capsule ({}, '{}')"_s.format((size_t) contents, capsule.name())); + + capsule.set_pointer((void *) 1234); + + // Using get_pointer() + void* contents1 = static_cast(capsule); + void* contents2 = capsule.get_pointer(); + void* contents3 = capsule.get_pointer(); + + auto result1 = reinterpret_cast(contents1); + auto result2 = reinterpret_cast(contents2); + auto result3 = reinterpret_cast(contents3); + + py::print("created capsule ({}, '{}')"_s.format(result1 & result2 & result3, capsule.name())); return capsule; }); // test_accessors - m.def("accessor_api", [](py::object o) { + m.def("accessor_api", [](const py::object &o) { auto d = py::dict(); d["basic_attr"] = o.attr("basic_attr"); auto l = py::list(); - for (const auto &item : o.attr("begin_end")) { + for (auto item : o.attr("begin_end")) { l.append(item); } d["begin_end"] = l; @@ -163,7 +207,7 @@ TEST_SUBMODULE(pytypes, m) { return d; }); - m.def("tuple_accessor", [](py::tuple existing_t) { + m.def("tuple_accessor", [](const py::tuple &existing_t) { try { existing_t[0] = 1; } catch (const py::error_already_set &) { @@ -199,6 +243,7 @@ TEST_SUBMODULE(pytypes, m) { m.def("default_constructors", []() { return py::dict( "bytes"_a=py::bytes(), + "bytearray"_a=py::bytearray(), "str"_a=py::str(), "bool"_a=py::bool_(), "int"_a=py::int_(), @@ -210,9 +255,10 @@ TEST_SUBMODULE(pytypes, m) { ); }); - m.def("converting_constructors", [](py::dict d) { + m.def("converting_constructors", [](const py::dict &d) { return py::dict( "bytes"_a=py::bytes(d["bytes"]), + "bytearray"_a=py::bytearray(d["bytearray"]), "str"_a=py::str(d["str"]), "bool"_a=py::bool_(d["bool"]), "int"_a=py::int_(d["int"]), @@ -225,10 +271,11 @@ TEST_SUBMODULE(pytypes, m) { ); }); - m.def("cast_functions", [](py::dict d) { + m.def("cast_functions", [](const py::dict &d) { // When converting between Python types, obj.cast() should be the same as T(obj) return py::dict( "bytes"_a=d["bytes"].cast(), + "bytearray"_a=d["bytearray"].cast(), "str"_a=d["str"].cast(), "bool"_a=d["bool"].cast(), "int"_a=d["int"].cast(), @@ -241,7 +288,24 @@ TEST_SUBMODULE(pytypes, m) { ); }); - m.def("convert_to_pybind11_str", [](py::object o) { return py::str(o); }); + m.def("convert_to_pybind11_str", [](const py::object &o) { return py::str(o); }); + + m.def("nonconverting_constructor", + [](const std::string &type, py::object value, bool move) -> py::object { + if (type == "bytes") { + return move ? py::bytes(std::move(value)) : py::bytes(value); + } + if (type == "none") { + return move ? py::none(std::move(value)) : py::none(value); + } + if (type == "ellipsis") { + return move ? py::ellipsis(std::move(value)) : py::ellipsis(value); + } + if (type == "type") { + return move ? py::type(std::move(value)) : py::type(value); + } + throw std::runtime_error("Invalid type"); + }); m.def("get_implicit_casting", []() { py::dict d; @@ -289,7 +353,7 @@ TEST_SUBMODULE(pytypes, m) { py::print("no new line here", "end"_a=" -- "); py::print("next print"); - auto py_stderr = py::module::import("sys").attr("stderr"); + auto py_stderr = py::module_::import("sys").attr("stderr"); py::print("this goes to stderr", "file"_a=py_stderr); py::print("flush", "flush"_a=true); @@ -299,9 +363,9 @@ TEST_SUBMODULE(pytypes, m) { m.def("print_failure", []() { py::print(42, UnregisteredType()); }); - m.def("hash_function", [](py::object obj) { return py::hash(obj); }); + m.def("hash_function", [](py::object obj) { return py::hash(std::move(obj)); }); - m.def("test_number_protocol", [](py::object a, py::object b) { + m.def("test_number_protocol", [](const py::object &a, const py::object &b) { py::list l; l.append(a.equal(b)); l.append(a.not_equal(b)); @@ -321,9 +385,7 @@ TEST_SUBMODULE(pytypes, m) { return l; }); - m.def("test_list_slicing", [](py::list a) { - return a[py::slice(0, -1, 2)]; - }); + m.def("test_list_slicing", [](const py::list &a) { return a[py::slice(0, -1, 2)]; }); // See #2361 m.def("issue2361_str_implicit_copy_none", []() { @@ -335,13 +397,10 @@ TEST_SUBMODULE(pytypes, m) { return is_this_none; }); - m.def("test_memoryview_object", [](py::buffer b) { - return py::memoryview(b); - }); + m.def("test_memoryview_object", [](const py::buffer &b) { return py::memoryview(b); }); - m.def("test_memoryview_buffer_info", [](py::buffer b) { - return py::memoryview(b.request()); - }); + m.def("test_memoryview_buffer_info", + [](const py::buffer &b) { return py::memoryview(b.request()); }); m.def("test_memoryview_from_buffer", [](bool is_unsigned) { static const int16_t si16[] = { 3, 1, 4, 1, 5 }; @@ -349,9 +408,7 @@ TEST_SUBMODULE(pytypes, m) { if (is_unsigned) return py::memoryview::from_buffer( ui16, { 4 }, { sizeof(uint16_t) }); - else - return py::memoryview::from_buffer( - si16, { 5 }, { sizeof(int16_t) }); + return py::memoryview::from_buffer(si16, {5}, {sizeof(int16_t)}); }); m.def("test_memoryview_from_buffer_nativeformat", []() { @@ -380,7 +437,128 @@ TEST_SUBMODULE(pytypes, m) { m.def("test_memoryview_from_memory", []() { const char* buf = "\xff\xe1\xab\x37"; return py::memoryview::from_memory( - buf, static_cast(strlen(buf))); + buf, static_cast(strlen(buf))); }); #endif + + // test_builtin_functions + m.def("get_len", [](py::handle h) { return py::len(h); }); + +#ifdef PYBIND11_STR_LEGACY_PERMISSIVE + m.attr("PYBIND11_STR_LEGACY_PERMISSIVE") = true; +#endif + + m.def("isinstance_pybind11_bytes", + [](py::object o) { return py::isinstance(std::move(o)); }); + m.def("isinstance_pybind11_str", + [](py::object o) { return py::isinstance(std::move(o)); }); + + m.def("pass_to_pybind11_bytes", [](py::bytes b) { return py::len(std::move(b)); }); + m.def("pass_to_pybind11_str", [](py::str s) { return py::len(std::move(s)); }); + m.def("pass_to_std_string", [](const std::string &s) { return s.size(); }); + + // test_weakref + m.def("weakref_from_handle", + [](py::handle h) { return py::weakref(h); }); + m.def("weakref_from_handle_and_function", + [](py::handle h, py::function f) { return py::weakref(h, std::move(f)); }); + m.def("weakref_from_object", [](const py::object &o) { return py::weakref(o); }); + m.def("weakref_from_object_and_function", + [](py::object o, py::function f) { return py::weakref(std::move(o), std::move(f)); }); + +// See PR #3263 for background (https://github.com/pybind/pybind11/pull/3263): +// pytypes.h could be changed to enforce the "most correct" user code below, by removing +// `const` from iterator `reference` using type aliases, but that will break existing +// user code. +#if (defined(__APPLE__) && defined(__clang__)) || defined(PYPY_VERSION) +// This is "most correct" and enforced on these platforms. +# define PYBIND11_AUTO_IT auto it +#else +// This works on many platforms and is (unfortunately) reflective of existing user code. +// NOLINTNEXTLINE(bugprone-macro-parentheses) +# define PYBIND11_AUTO_IT auto &it +#endif + + m.def("tuple_iterator", []() { + auto tup = py::make_tuple(5, 7); + int tup_sum = 0; + for (PYBIND11_AUTO_IT : tup) { + tup_sum += it.cast(); + } + return tup_sum; + }); + + m.def("dict_iterator", []() { + py::dict dct; + dct[py::int_(3)] = 5; + dct[py::int_(7)] = 11; + int kv_sum = 0; + for (PYBIND11_AUTO_IT : dct) { + kv_sum += it.first.cast() * 100 + it.second.cast(); + } + return kv_sum; + }); + + m.def("passed_iterator", [](const py::iterator &py_it) { + int elem_sum = 0; + for (PYBIND11_AUTO_IT : py_it) { + elem_sum += it.cast(); + } + return elem_sum; + }); + +#undef PYBIND11_AUTO_IT + + // Tests below this line are for pybind11 IMPLEMENTATION DETAILS: + + m.def("sequence_item_get_ssize_t", [](const py::object &o) { + return py::detail::accessor_policies::sequence_item::get(o, (py::ssize_t) 1); + }); + m.def("sequence_item_set_ssize_t", [](const py::object &o) { + auto s = py::str{"peppa", 5}; + py::detail::accessor_policies::sequence_item::set(o, (py::ssize_t) 1, s); + }); + m.def("sequence_item_get_size_t", [](const py::object &o) { + return py::detail::accessor_policies::sequence_item::get(o, (py::size_t) 2); + }); + m.def("sequence_item_set_size_t", [](const py::object &o) { + auto s = py::str{"george", 6}; + py::detail::accessor_policies::sequence_item::set(o, (py::size_t) 2, s); + }); + m.def("list_item_get_ssize_t", [](const py::object &o) { + return py::detail::accessor_policies::list_item::get(o, (py::ssize_t) 3); + }); + m.def("list_item_set_ssize_t", [](const py::object &o) { + auto s = py::str{"rebecca", 7}; + py::detail::accessor_policies::list_item::set(o, (py::ssize_t) 3, s); + }); + m.def("list_item_get_size_t", [](const py::object &o) { + return py::detail::accessor_policies::list_item::get(o, (py::size_t) 4); + }); + m.def("list_item_set_size_t", [](const py::object &o) { + auto s = py::str{"richard", 7}; + py::detail::accessor_policies::list_item::set(o, (py::size_t) 4, s); + }); + m.def("tuple_item_get_ssize_t", [](const py::object &o) { + return py::detail::accessor_policies::tuple_item::get(o, (py::ssize_t) 5); + }); + m.def("tuple_item_set_ssize_t", []() { + auto s0 = py::str{"emely", 5}; + auto s1 = py::str{"edmond", 6}; + auto o = py::tuple{2}; + py::detail::accessor_policies::tuple_item::set(o, (py::ssize_t) 0, s0); + py::detail::accessor_policies::tuple_item::set(o, (py::ssize_t) 1, s1); + return o; + }); + m.def("tuple_item_get_size_t", [](const py::object &o) { + return py::detail::accessor_policies::tuple_item::get(o, (py::size_t) 6); + }); + m.def("tuple_item_set_size_t", []() { + auto s0 = py::str{"candy", 5}; + auto s1 = py::str{"cat", 3}; + auto o = py::tuple{2}; + py::detail::accessor_policies::tuple_item::set(o, (py::size_t) 1, s1); + py::detail::accessor_policies::tuple_item::set(o, (py::size_t) 0, s0); + return o; + }); } diff --git a/pybind11/tests/test_pytypes.py b/pybind11/tests/test_pytypes.py index 0618cd54c..2cd6c3f03 100644 --- a/pybind11/tests/test_pytypes.py +++ b/pybind11/tests/test_pytypes.py @@ -1,12 +1,17 @@ # -*- coding: utf-8 -*- from __future__ import division -import pytest + import sys -import env # noqa: F401 +import pytest -from pybind11_tests import pytypes as m +import env from pybind11_tests import debug_enabled +from pybind11_tests import pytypes as m + + +def test_bool(doc): + assert doc(m.get_bool) == "get_bool() -> bool" def test_int(doc): @@ -21,20 +26,36 @@ def test_iterable(doc): assert doc(m.get_iterable) == "get_iterable() -> Iterable" +def test_float(doc): + assert doc(m.get_float) == "get_float() -> float" + + def test_list(capture, doc): + assert m.list_no_args() == [] + assert m.list_ssize_t() == [] + assert m.list_size_t() == [] + lins = [1, 2] + m.list_insert_ssize_t(lins) + assert lins == [1, 83, 2] + m.list_insert_size_t(lins) + assert lins == [1, 83, 2, 57] + with capture: lst = m.get_list() assert lst == ["inserted-0", "overwritten", "inserted-2"] lst.append("value2") m.print_list(lst) - assert capture.unordered == """ + assert ( + capture.unordered + == """ Entry at position 0: value list item 0: inserted-0 list item 1: overwritten list item 2: inserted-2 list item 3: value2 """ + ) assert doc(m.get_list) == "get_list() -> list" assert doc(m.print_list) == "print_list(arg0: list) -> None" @@ -52,14 +73,17 @@ def test_set(capture, doc): with capture: s.add("key4") m.print_set(s) - assert capture.unordered == """ + assert ( + capture.unordered + == """ key: key1 key: key2 key: key3 key: key4 """ + ) - assert not m.set_contains(set([]), 42) + assert not m.set_contains(set(), 42) assert m.set_contains({42}, 42) assert m.set_contains({"foo"}, "foo") @@ -74,10 +98,13 @@ def test_dict(capture, doc): with capture: d["key2"] = "value2" m.print_dict(d) - assert capture.unordered == """ + assert ( + capture.unordered + == """ key: key, value=value key: key2, value=value2 """ + ) assert not m.dict_contains({}, 42) assert m.dict_contains({42: None}, 42) @@ -89,7 +116,25 @@ def test_dict(capture, doc): assert m.dict_keyword_constructor() == {"x": 1, "y": 2, "z": 3} +def test_tuple(): + assert m.tuple_no_args() == () + assert m.tuple_ssize_t() == () + assert m.tuple_size_t() == () + assert m.get_tuple() == (42, None, "spam") + + +@pytest.mark.skipif("env.PY2") +def test_simple_namespace(): + ns = m.get_simple_namespace() + assert ns.attr == 42 + assert ns.x == "foo" + assert ns.right == 2 + assert not hasattr(ns, "wrong") + + def test_str(doc): + assert m.str_from_char_ssize_t().encode().decode() == "red" + assert m.str_from_char_size_t().encode().decode() == "blue" assert m.str_from_string().encode().decode() == "baz" assert m.str_from_bytes().encode().decode() == "boo" @@ -111,18 +156,31 @@ def test_str(doc): assert s1 == s2 malformed_utf8 = b"\x80" - assert m.str_from_object(malformed_utf8) is malformed_utf8 # To be fixed; see #2380 + if hasattr(m, "PYBIND11_STR_LEGACY_PERMISSIVE"): + assert m.str_from_object(malformed_utf8) is malformed_utf8 + elif env.PY2: + with pytest.raises(UnicodeDecodeError): + m.str_from_object(malformed_utf8) + else: + assert m.str_from_object(malformed_utf8) == "b'\\x80'" if env.PY2: - # with pytest.raises(UnicodeDecodeError): - # m.str_from_object(malformed_utf8) with pytest.raises(UnicodeDecodeError): m.str_from_handle(malformed_utf8) else: - # assert m.str_from_object(malformed_utf8) == "b'\\x80'" assert m.str_from_handle(malformed_utf8) == "b'\\x80'" + assert m.str_from_string_from_str("this is a str") == "this is a str" + ucs_surrogates_str = u"\udcc3" + if env.PY2: + assert u"\udcc3" == m.str_from_string_from_str(ucs_surrogates_str) + else: + with pytest.raises(UnicodeEncodeError): + m.str_from_string_from_str(ucs_surrogates_str) + def test_bytes(doc): + assert m.bytes_from_char_ssize_t().decode() == "green" + assert m.bytes_from_char_size_t().decode() == "purple" assert m.bytes_from_string().decode() == "foo" assert m.bytes_from_str().decode() == "bar" @@ -131,34 +189,50 @@ def test_bytes(doc): ) +def test_bytearray(doc): + assert m.bytearray_from_char_ssize_t().decode() == "$%" + assert m.bytearray_from_char_size_t().decode() == "@$!" + assert m.bytearray_from_string().decode() == "foo" + assert m.bytearray_size() == len("foo") + + def test_capsule(capture): pytest.gc_collect() with capture: a = m.return_capsule_with_destructor() del a pytest.gc_collect() - assert capture.unordered == """ + assert ( + capture.unordered + == """ creating capsule destructing capsule """ + ) with capture: a = m.return_capsule_with_destructor_2() del a pytest.gc_collect() - assert capture.unordered == """ + assert ( + capture.unordered + == """ creating capsule destructing capsule: 1234 """ + ) with capture: a = m.return_capsule_with_name_and_destructor() del a pytest.gc_collect() - assert capture.unordered == """ + assert ( + capture.unordered + == """ created capsule (1234, 'pointer type description') destructing capsule (1234, 'pointer type description') """ + ) def test_accessors(): @@ -202,7 +276,7 @@ def test_accessors(): def test_constructors(): """C++ default and converting constructors are equivalent to type calls in Python""" - types = [bytes, str, bool, int, float, tuple, list, dict, set] + types = [bytes, bytearray, str, bool, int, float, tuple, list, dict, set] expected = {t.__name__: t() for t in types} if env.PY2: # Note that bytes.__name__ == 'str' in Python 2. @@ -212,7 +286,8 @@ def test_constructors(): assert m.default_constructors() == expected data = { - bytes: b'41', # Currently no supported or working conversions. + bytes: b"41", # Currently no supported or working conversions. + bytearray: bytearray(b"41"), str: 42, bool: "Not empty", int: "42", @@ -221,14 +296,14 @@ def test_constructors(): list: range(3), dict: [("two", 2), ("one", 1), ("three", 3)], set: [4, 4, 5, 6, 6, 6], - memoryview: b'abc' + memoryview: b"abc", } inputs = {k.__name__: v for k, v in data.items()} expected = {k.__name__: k(v) for k, v in data.items()} if env.PY2: # Similar to the above. See comments above. - inputs["bytes"] = b'41' + inputs["bytes"] = b"41" inputs["str"] = 42 - expected["bytes"] = b'41' + expected["bytes"] = b"41" expected["str"] = u"42" assert m.converting_constructors(inputs) == expected @@ -245,16 +320,33 @@ def test_constructors(): assert noconv2[k] is expected[k] +def test_non_converting_constructors(): + non_converting_test_cases = [ + ("bytes", range(10)), + ("none", 42), + ("ellipsis", 42), + ("type", 42), + ] + for t, v in non_converting_test_cases: + for move in [True, False]: + with pytest.raises(TypeError) as excinfo: + m.nonconverting_constructor(t, v, move) + expected_error = "Object of type '{}' is not an instance of '{}'".format( + type(v).__name__, t + ) + assert str(excinfo.value) == expected_error + + def test_pybind11_str_raw_str(): # specifically to exercise pybind11::str::raw_str cvt = m.convert_to_pybind11_str assert cvt(u"Str") == u"Str" - assert cvt(b'Bytes') == u"Bytes" if env.PY2 else "b'Bytes'" + assert cvt(b"Bytes") == u"Bytes" if env.PY2 else "b'Bytes'" assert cvt(None) == u"None" assert cvt(False) == u"False" assert cvt(True) == u"True" assert cvt(42) == u"42" - assert cvt(2**65) == u"36893488147419103232" + assert cvt(2 ** 65) == u"36893488147419103232" assert cvt(-1.50) == u"-1.5" assert cvt(()) == u"()" assert cvt((18,)) == u"(18,)" @@ -268,30 +360,54 @@ def test_pybind11_str_raw_str(): valid_orig = u"DZ" valid_utf8 = valid_orig.encode("utf-8") valid_cvt = cvt(valid_utf8) - assert type(valid_cvt) == bytes # Probably surprising. - assert valid_cvt == b'\xc7\xb1' + if hasattr(m, "PYBIND11_STR_LEGACY_PERMISSIVE"): + assert valid_cvt is valid_utf8 + else: + assert type(valid_cvt) is unicode if env.PY2 else str # noqa: F821 + if env.PY2: + assert valid_cvt == valid_orig + else: + assert valid_cvt == "b'\\xc7\\xb1'" - malformed_utf8 = b'\x80' - malformed_cvt = cvt(malformed_utf8) - assert type(malformed_cvt) == bytes # Probably surprising. - assert malformed_cvt == b'\x80' + malformed_utf8 = b"\x80" + if hasattr(m, "PYBIND11_STR_LEGACY_PERMISSIVE"): + assert cvt(malformed_utf8) is malformed_utf8 + else: + if env.PY2: + with pytest.raises(UnicodeDecodeError): + cvt(malformed_utf8) + else: + malformed_cvt = cvt(malformed_utf8) + assert type(malformed_cvt) is str + assert malformed_cvt == "b'\\x80'" def test_implicit_casting(): """Tests implicit casting when assigning or appending to dicts and lists.""" z = m.get_implicit_casting() - assert z['d'] == { - 'char*_i1': 'abc', 'char*_i2': 'abc', 'char*_e': 'abc', 'char*_p': 'abc', - 'str_i1': 'str', 'str_i2': 'str1', 'str_e': 'str2', 'str_p': 'str3', - 'int_i1': 42, 'int_i2': 42, 'int_e': 43, 'int_p': 44 + assert z["d"] == { + "char*_i1": "abc", + "char*_i2": "abc", + "char*_e": "abc", + "char*_p": "abc", + "str_i1": "str", + "str_i2": "str1", + "str_e": "str2", + "str_p": "str3", + "int_i1": 42, + "int_i2": 42, + "int_e": 43, + "int_p": 44, } - assert z['l'] == [3, 6, 9, 12, 15] + assert z["l"] == [3, 6, 9, 12, 15] def test_print(capture): with capture: m.print_function() - assert capture == """ + assert ( + capture + == """ Hello, World! 1 2.0 three True -- multiple args *args-and-a-custom-separator @@ -299,14 +415,15 @@ def test_print(capture): flush py::print + str.format = this """ + ) assert capture.stderr == "this goes to stderr" with pytest.raises(RuntimeError) as excinfo: m.print_failure() - assert str(excinfo.value) == "make_tuple(): unable to convert " + ( - "argument of type 'UnregisteredType' to Python object" - if debug_enabled else - "arguments to Python object (compile in debug mode for details)" + assert str(excinfo.value) == "Unable to convert call argument " + ( + "'1' of type 'UnregisteredType' to Python object" + if debug_enabled + else "to Python object (compile in debug mode for details)" ) @@ -328,8 +445,23 @@ def test_hash(): def test_number_protocol(): for a, b in [(1, 1), (3, 5)]: - li = [a == b, a != b, a < b, a <= b, a > b, a >= b, a + b, - a - b, a * b, a / b, a | b, a & b, a ^ b, a >> b, a << b] + li = [ + a == b, + a != b, + a < b, + a <= b, + a > b, + a >= b, + a + b, + a - b, + a * b, + a / b, + a | b, + a & b, + a ^ b, + a >> b, + a << b, + ] assert m.test_number_protocol(a, b) == li @@ -343,16 +475,20 @@ def test_issue2361(): assert m.issue2361_str_implicit_copy_none() == "None" with pytest.raises(TypeError) as excinfo: assert m.issue2361_dict_implicit_copy_none() - assert "'NoneType' object is not iterable" in str(excinfo.value) + assert "NoneType" in str(excinfo.value) + assert "iterable" in str(excinfo.value) -@pytest.mark.parametrize('method, args, fmt, expected_view', [ - (m.test_memoryview_object, (b'red',), 'B', b'red'), - (m.test_memoryview_buffer_info, (b'green',), 'B', b'green'), - (m.test_memoryview_from_buffer, (False,), 'h', [3, 1, 4, 1, 5]), - (m.test_memoryview_from_buffer, (True,), 'H', [2, 7, 1, 8]), - (m.test_memoryview_from_buffer_nativeformat, (), '@i', [4, 7, 5]), -]) +@pytest.mark.parametrize( + "method, args, fmt, expected_view", + [ + (m.test_memoryview_object, (b"red",), "B", b"red"), + (m.test_memoryview_buffer_info, (b"green",), "B", b"green"), + (m.test_memoryview_from_buffer, (False,), "h", [3, 1, 4, 1, 5]), + (m.test_memoryview_from_buffer, (True,), "H", [2, 7, 1, 8]), + (m.test_memoryview_from_buffer_nativeformat, (), "@i", [4, 7, 5]), + ], +) def test_memoryview(method, args, fmt, expected_view): view = method(*args) assert isinstance(view, memoryview) @@ -361,17 +497,20 @@ def test_memoryview(method, args, fmt, expected_view): view_as_list = list(view) else: # Using max to pick non-zero byte (big-endian vs little-endian). - view_as_list = [max([ord(c) for c in s]) for s in view] + view_as_list = [max(ord(c) for c in s) for s in view] assert view_as_list == list(expected_view) @pytest.mark.xfail("env.PYPY", reason="getrefcount is not available") -@pytest.mark.parametrize('method', [ - m.test_memoryview_object, - m.test_memoryview_buffer_info, -]) +@pytest.mark.parametrize( + "method", + [ + m.test_memoryview_object, + m.test_memoryview_buffer_info, + ], +) def test_memoryview_refcount(method): - buf = b'\x0a\x0b\x0c\x0d' + buf = b"\x0a\x0b\x0c\x0d" ref_before = sys.getrefcount(buf) view = method(buf) ref_after = sys.getrefcount(buf) @@ -382,13 +521,13 @@ def test_memoryview_refcount(method): def test_memoryview_from_buffer_empty_shape(): view = m.test_memoryview_from_buffer_empty_shape() assert isinstance(view, memoryview) - assert view.format == 'B' + assert view.format == "B" if env.PY2: # Python 2 behavior is weird, but Python 3 (the future) is fine. # PyPy3 has #include +#include +#include + +#ifdef PYBIND11_HAS_OPTIONAL +#include +#endif // PYBIND11_HAS_OPTIONAL + template class NonZeroIterator { const T* ptr_; public: - NonZeroIterator(const T* ptr) : ptr_(ptr) {} + explicit NonZeroIterator(const T *ptr) : ptr_(ptr) {} const T& operator*() const { return *ptr_; } NonZeroIterator& operator++() { ++ptr_; return *this; } }; @@ -31,6 +38,40 @@ bool operator==(const NonZeroIterator>& it, const NonZeroSentine return !(*it).first || !(*it).second; } +/* Iterator where dereferencing returns prvalues instead of references. */ +template +class NonRefIterator { + const T* ptr_; +public: + explicit NonRefIterator(const T *ptr) : ptr_(ptr) {} + T operator*() const { return T(*ptr_); } + NonRefIterator& operator++() { ++ptr_; return *this; } + bool operator==(const NonRefIterator &other) const { return ptr_ == other.ptr_; } +}; + +class NonCopyableInt { +public: + explicit NonCopyableInt(int value) : value_(value) {} + NonCopyableInt(const NonCopyableInt &) = delete; + NonCopyableInt(NonCopyableInt &&other) noexcept : value_(other.value_) { + other.value_ = -1; // detect when an unwanted move occurs + } + NonCopyableInt &operator=(const NonCopyableInt &) = delete; + NonCopyableInt &operator=(NonCopyableInt &&other) noexcept { + value_ = other.value_; + other.value_ = -1; // detect when an unwanted move occurs + return *this; + } + int get() const { return value_; } + void set(int value) { value_ = value; } + ~NonCopyableInt() = default; +private: + int value_; +}; +using NonCopyableIntPair = std::pair; +PYBIND11_MAKE_OPAQUE(std::vector); +PYBIND11_MAKE_OPAQUE(std::vector); + template py::list test_random_access_iterator(PythonType x) { if (x.size() < 5) @@ -76,32 +117,43 @@ TEST_SUBMODULE(sequences_and_iterators, m) { // test_sliceable class Sliceable{ public: - Sliceable(int n): size(n) {} - int start,stop,step; - int size; + explicit Sliceable(int n) : size(n) {} + int start, stop, step; + int size; }; - py::class_(m,"Sliceable") + py::class_(m, "Sliceable") .def(py::init()) - .def("__getitem__",[](const Sliceable &s, py::slice slice) { - ssize_t start, stop, step, slicelength; - if (!slice.compute(s.size, &start, &stop, &step, &slicelength)) - throw py::error_already_set(); - int istart = static_cast(start); - int istop = static_cast(stop); - int istep = static_cast(step); - return std::make_tuple(istart,istop,istep); - }) - ; + .def("__getitem__", [](const Sliceable &s, const py::slice &slice) { + py::ssize_t start = 0, stop = 0, step = 0, slicelength = 0; + if (!slice.compute(s.size, &start, &stop, &step, &slicelength)) + throw py::error_already_set(); + int istart = static_cast(start); + int istop = static_cast(stop); + int istep = static_cast(step); + return std::make_tuple(istart, istop, istep); + }); + + m.def("make_forward_slice_size_t", []() { return py::slice(0, -1, 1); }); + m.def("make_reversed_slice_object", []() { return py::slice(py::none(), py::none(), py::int_(-1)); }); +#ifdef PYBIND11_HAS_OPTIONAL + m.attr("has_optional") = true; + m.def("make_reversed_slice_size_t_optional_verbose", []() { return py::slice(std::nullopt, std::nullopt, -1); }); + // Warning: The following spelling may still compile if optional<> is not present and give wrong answers. + // Please use with caution. + m.def("make_reversed_slice_size_t_optional", []() { return py::slice({}, {}, -1); }); +#else + m.attr("has_optional") = false; +#endif // test_sequence class Sequence { public: - Sequence(size_t size) : m_size(size) { + explicit Sequence(size_t size) : m_size(size) { print_created(this, "of size", m_size); m_data = new float[size]; memset(m_data, 0, sizeof(float) * size); } - Sequence(const std::vector &value) : m_size(value.size()) { + explicit Sequence(const std::vector &value) : m_size(value.size()) { print_created(this, "of size", m_size, "from std::vector"); m_data = new float[m_size]; memcpy(m_data, &value[0], sizeof(float) * m_size); @@ -111,7 +163,7 @@ TEST_SUBMODULE(sequences_and_iterators, m) { m_data = new float[m_size]; memcpy(m_data, s.m_data, sizeof(float)*m_size); } - Sequence(Sequence &&s) : m_size(s.m_size), m_data(s.m_data) { + Sequence(Sequence &&s) noexcept : m_size(s.m_size), m_data(s.m_data) { print_move_created(this); s.m_size = 0; s.m_data = nullptr; @@ -130,7 +182,7 @@ TEST_SUBMODULE(sequences_and_iterators, m) { return *this; } - Sequence &operator=(Sequence &&s) { + Sequence &operator=(Sequence &&s) noexcept { if (&s != this) { delete[] m_data; m_size = s.m_size; @@ -179,43 +231,54 @@ TEST_SUBMODULE(sequences_and_iterators, m) { }; py::class_(m, "Sequence") .def(py::init()) - .def(py::init&>()) + .def(py::init &>()) /// Bare bones interface - .def("__getitem__", [](const Sequence &s, size_t i) { - if (i >= s.size()) throw py::index_error(); - return s[i]; - }) - .def("__setitem__", [](Sequence &s, size_t i, float v) { - if (i >= s.size()) throw py::index_error(); - s[i] = v; - }) + .def("__getitem__", + [](const Sequence &s, size_t i) { + if (i >= s.size()) + throw py::index_error(); + return s[i]; + }) + .def("__setitem__", + [](Sequence &s, size_t i, float v) { + if (i >= s.size()) + throw py::index_error(); + s[i] = v; + }) .def("__len__", &Sequence::size) /// Optional sequence protocol operations - .def("__iter__", [](const Sequence &s) { return py::make_iterator(s.begin(), s.end()); }, - py::keep_alive<0, 1>() /* Essential: keep object alive while iterator exists */) + .def( + "__iter__", + [](const Sequence &s) { return py::make_iterator(s.begin(), s.end()); }, + py::keep_alive<0, 1>() /* Essential: keep object alive while iterator exists */) .def("__contains__", [](const Sequence &s, float v) { return s.contains(v); }) .def("__reversed__", [](const Sequence &s) -> Sequence { return s.reversed(); }) /// Slicing protocol (optional) - .def("__getitem__", [](const Sequence &s, py::slice slice) -> Sequence* { - size_t start, stop, step, slicelength; - if (!slice.compute(s.size(), &start, &stop, &step, &slicelength)) - throw py::error_already_set(); - auto *seq = new Sequence(slicelength); - for (size_t i = 0; i < slicelength; ++i) { - (*seq)[i] = s[start]; start += step; - } - return seq; - }) - .def("__setitem__", [](Sequence &s, py::slice slice, const Sequence &value) { - size_t start, stop, step, slicelength; - if (!slice.compute(s.size(), &start, &stop, &step, &slicelength)) - throw py::error_already_set(); - if (slicelength != value.size()) - throw std::runtime_error("Left and right hand size of slice assignment have different sizes!"); - for (size_t i = 0; i < slicelength; ++i) { - s[start] = value[i]; start += step; - } - }) + .def("__getitem__", + [](const Sequence &s, const py::slice &slice) -> Sequence * { + size_t start = 0, stop = 0, step = 0, slicelength = 0; + if (!slice.compute(s.size(), &start, &stop, &step, &slicelength)) + throw py::error_already_set(); + auto *seq = new Sequence(slicelength); + for (size_t i = 0; i < slicelength; ++i) { + (*seq)[i] = s[start]; + start += step; + } + return seq; + }) + .def("__setitem__", + [](Sequence &s, const py::slice &slice, const Sequence &value) { + size_t start = 0, stop = 0, step = 0, slicelength = 0; + if (!slice.compute(s.size(), &start, &stop, &step, &slicelength)) + throw py::error_already_set(); + if (slicelength != value.size()) + throw std::runtime_error( + "Left and right hand size of slice assignment have different sizes!"); + for (size_t i = 0; i < slicelength; ++i) { + s[start] = value[i]; + start += step; + } + }) /// Comparisons .def(py::self == py::self) .def(py::self != py::self) @@ -228,11 +291,11 @@ TEST_SUBMODULE(sequences_and_iterators, m) { class StringMap { public: StringMap() = default; - StringMap(std::unordered_map init) + explicit StringMap(std::unordered_map init) : map(std::move(init)) {} - void set(std::string key, std::string val) { map[key] = val; } - std::string get(std::string key) const { return map.at(key); } + void set(const std::string &key, std::string val) { map[key] = std::move(val); } + std::string get(const std::string &key) const { return map.at(key); } size_t size() const { return map.size(); } private: std::unordered_map map; @@ -243,38 +306,117 @@ TEST_SUBMODULE(sequences_and_iterators, m) { py::class_(m, "StringMap") .def(py::init<>()) .def(py::init>()) - .def("__getitem__", [](const StringMap &map, std::string key) { - try { return map.get(key); } - catch (const std::out_of_range&) { - throw py::key_error("key '" + key + "' does not exist"); - } - }) + .def("__getitem__", + [](const StringMap &map, const std::string &key) { + try { + return map.get(key); + } catch (const std::out_of_range &) { + throw py::key_error("key '" + key + "' does not exist"); + } + }) .def("__setitem__", &StringMap::set) .def("__len__", &StringMap::size) - .def("__iter__", [](const StringMap &map) { return py::make_key_iterator(map.begin(), map.end()); }, - py::keep_alive<0, 1>()) - .def("items", [](const StringMap &map) { return py::make_iterator(map.begin(), map.end()); }, - py::keep_alive<0, 1>()) - ; + .def( + "__iter__", + [](const StringMap &map) { return py::make_key_iterator(map.begin(), map.end()); }, + py::keep_alive<0, 1>()) + .def( + "items", + [](const StringMap &map) { return py::make_iterator(map.begin(), map.end()); }, + py::keep_alive<0, 1>()) + .def( + "values", + [](const StringMap &map) { return py::make_value_iterator(map.begin(), map.end()); }, + py::keep_alive<0, 1>()); // test_generalized_iterators class IntPairs { public: - IntPairs(std::vector> data) : data_(std::move(data)) {} + explicit IntPairs(std::vector> data) : data_(std::move(data)) {} const std::pair* begin() const { return data_.data(); } + // .end() only required for py::make_iterator(self) overload + const std::pair* end() const { return data_.data() + data_.size(); } private: std::vector> data_; }; py::class_(m, "IntPairs") .def(py::init>>()) .def("nonzero", [](const IntPairs& s) { - return py::make_iterator(NonZeroIterator>(s.begin()), NonZeroSentinel()); + return py::make_iterator(NonZeroIterator>(s.begin()), NonZeroSentinel()); }, py::keep_alive<0, 1>()) .def("nonzero_keys", [](const IntPairs& s) { return py::make_key_iterator(NonZeroIterator>(s.begin()), NonZeroSentinel()); }, py::keep_alive<0, 1>()) + .def("nonzero_values", [](const IntPairs& s) { + return py::make_value_iterator(NonZeroIterator>(s.begin()), NonZeroSentinel()); + }, py::keep_alive<0, 1>()) + + // test iterator that returns values instead of references + .def("nonref", [](const IntPairs& s) { + return py::make_iterator(NonRefIterator>(s.begin()), + NonRefIterator>(s.end())); + }, py::keep_alive<0, 1>()) + .def("nonref_keys", [](const IntPairs& s) { + return py::make_key_iterator(NonRefIterator>(s.begin()), + NonRefIterator>(s.end())); + }, py::keep_alive<0, 1>()) + .def("nonref_values", [](const IntPairs& s) { + return py::make_value_iterator(NonRefIterator>(s.begin()), + NonRefIterator>(s.end())); + }, py::keep_alive<0, 1>()) + + // test single-argument make_iterator + .def("simple_iterator", [](IntPairs& self) { + return py::make_iterator(self); + }, py::keep_alive<0, 1>()) + .def("simple_keys", [](IntPairs& self) { + return py::make_key_iterator(self); + }, py::keep_alive<0, 1>()) + .def("simple_values", [](IntPairs& self) { + return py::make_value_iterator(self); + }, py::keep_alive<0, 1>()) + + // Test iterator with an Extra (doesn't do anything useful, so not used + // at runtime, but tests need to be able to compile with the correct + // overload. See PR #3293. + .def("_make_iterator_extras", [](IntPairs& self) { + return py::make_iterator(self, py::call_guard()); + }, py::keep_alive<0, 1>()) + .def("_make_key_extras", [](IntPairs& self) { + return py::make_key_iterator(self, py::call_guard()); + }, py::keep_alive<0, 1>()) + .def("_make_value_extras", [](IntPairs& self) { + return py::make_value_iterator(self, py::call_guard()); + }, py::keep_alive<0, 1>()) ; + // test_iterater_referencing + py::class_(m, "NonCopyableInt") + .def(py::init()) + .def("set", &NonCopyableInt::set) + .def("__int__", &NonCopyableInt::get) + ; + py::class_>(m, "VectorNonCopyableInt") + .def(py::init<>()) + .def("append", [](std::vector &vec, int value) { + vec.emplace_back(value); + }) + .def("__iter__", [](std::vector &vec) { + return py::make_iterator(vec.begin(), vec.end()); + }) + ; + py::class_>(m, "VectorNonCopyableIntPair") + .def(py::init<>()) + .def("append", [](std::vector &vec, const std::pair &value) { + vec.emplace_back(NonCopyableInt(value.first), NonCopyableInt(value.second)); + }) + .def("keys", [](std::vector &vec) { + return py::make_key_iterator(vec.begin(), vec.end()); + }) + .def("values", [](std::vector &vec) { + return py::make_value_iterator(vec.begin(), vec.end()); + }) + ; #if 0 // Obsolete: special data structure for exposing custom iterator types to python @@ -304,7 +446,7 @@ TEST_SUBMODULE(sequences_and_iterators, m) { #endif // test_python_iterator_in_cpp - m.def("object_to_list", [](py::object o) { + m.def("object_to_list", [](const py::object &o) { auto l = py::list(); for (auto item : o) { l.append(item); @@ -322,22 +464,22 @@ TEST_SUBMODULE(sequences_and_iterators, m) { }); // test_sequence_length: check that Python sequences can be converted to py::sequence. - m.def("sequence_length", [](py::sequence seq) { return seq.size(); }); + m.def("sequence_length", [](const py::sequence &seq) { return seq.size(); }); // Make sure that py::iterator works with std algorithms - m.def("count_none", [](py::object o) { + m.def("count_none", [](const py::object &o) { return std::count_if(o.begin(), o.end(), [](py::handle h) { return h.is_none(); }); }); - m.def("find_none", [](py::object o) { + m.def("find_none", [](const py::object &o) { auto it = std::find_if(o.begin(), o.end(), [](py::handle h) { return h.is_none(); }); return it->is_none(); }); - m.def("count_nonzeros", [](py::dict d) { - return std::count_if(d.begin(), d.end(), [](std::pair p) { - return p.second.cast() != 0; - }); + m.def("count_nonzeros", [](const py::dict &d) { + return std::count_if(d.begin(), d.end(), [](std::pair p) { + return p.second.cast() != 0; + }); }); m.def("tuple_iterator", &test_random_access_iterator); diff --git a/pybind11/tests/test_sequences_and_iterators.py b/pybind11/tests/test_sequences_and_iterators.py index 8f6c0c4bb..6985918a1 100644 --- a/pybind11/tests/test_sequences_and_iterators.py +++ b/pybind11/tests/test_sequences_and_iterators.py @@ -1,7 +1,8 @@ # -*- coding: utf-8 -*- import pytest -from pybind11_tests import sequences_and_iterators as m + from pybind11_tests import ConstructorStats +from pybind11_tests import sequences_and_iterators as m def isclose(a, b, rel_tol=1e-05, abs_tol=0.0): @@ -10,7 +11,20 @@ def isclose(a, b, rel_tol=1e-05, abs_tol=0.0): def allclose(a_list, b_list, rel_tol=1e-05, abs_tol=0.0): - return all(isclose(a, b, rel_tol=rel_tol, abs_tol=abs_tol) for a, b in zip(a_list, b_list)) + return all( + isclose(a, b, rel_tol=rel_tol, abs_tol=abs_tol) for a, b in zip(a_list, b_list) + ) + + +def test_slice_constructors(): + assert m.make_forward_slice_size_t() == slice(0, -1, 1) + assert m.make_reversed_slice_object() == slice(None, None, -1) + + +@pytest.mark.skipif(not m.has_optional, reason="no ") +def test_slice_constructors_explicit_optional(): + assert m.make_reversed_slice_size_t_optional() == slice(None, None, -1) + assert m.make_reversed_slice_size_t_optional_verbose() == slice(None, None, -1) def test_generalized_iterators(): @@ -22,6 +36,10 @@ def test_generalized_iterators(): assert list(m.IntPairs([(1, 2), (2, 0), (0, 3), (4, 5)]).nonzero_keys()) == [1] assert list(m.IntPairs([(0, 3), (1, 2), (3, 4)]).nonzero_keys()) == [] + assert list(m.IntPairs([(1, 2), (3, 4), (0, 5)]).nonzero_values()) == [2, 4] + assert list(m.IntPairs([(1, 2), (2, 0), (0, 3), (4, 5)]).nonzero_values()) == [2] + assert list(m.IntPairs([(0, 3), (1, 2), (3, 4)]).nonzero_values()) == [] + # __next__ must continue to raise StopIteration it = m.IntPairs([(0, 0)]).nonzero() for _ in range(3): @@ -34,6 +52,47 @@ def test_generalized_iterators(): next(it) +def test_nonref_iterators(): + pairs = m.IntPairs([(1, 2), (3, 4), (0, 5)]) + assert list(pairs.nonref()) == [(1, 2), (3, 4), (0, 5)] + assert list(pairs.nonref_keys()) == [1, 3, 0] + assert list(pairs.nonref_values()) == [2, 4, 5] + + +def test_generalized_iterators_simple(): + assert list(m.IntPairs([(1, 2), (3, 4), (0, 5)]).simple_iterator()) == [ + (1, 2), + (3, 4), + (0, 5), + ] + assert list(m.IntPairs([(1, 2), (3, 4), (0, 5)]).simple_keys()) == [1, 3, 0] + assert list(m.IntPairs([(1, 2), (3, 4), (0, 5)]).simple_values()) == [2, 4, 5] + + +def test_iterator_referencing(): + """Test that iterators reference rather than copy their referents.""" + vec = m.VectorNonCopyableInt() + vec.append(3) + vec.append(5) + assert [int(x) for x in vec] == [3, 5] + # Increment everything to make sure the referents can be mutated + for x in vec: + x.set(int(x) + 1) + assert [int(x) for x in vec] == [4, 6] + + vec = m.VectorNonCopyableIntPair() + vec.append([3, 4]) + vec.append([5, 7]) + assert [int(x) for x in vec.keys()] == [3, 5] + assert [int(x) for x in vec.values()] == [4, 7] + for x in vec.keys(): + x.set(int(x) + 1) + for x in vec.values(): + x.set(int(x) + 10) + assert [int(x) for x in vec.keys()] == [4, 6] + assert [int(x) for x in vec.values()] == [14, 17] + + def test_sliceable(): sliceable = m.Sliceable(100) assert sliceable[::] == (0, 100, 1) @@ -51,7 +110,7 @@ def test_sequence(): cstats = ConstructorStats.get(m.Sequence) s = m.Sequence(5) - assert cstats.values() == ['of size', '5'] + assert cstats.values() == ["of size", "5"] assert "Sequence" in repr(s) assert len(s) == 5 @@ -62,16 +121,16 @@ def test_sequence(): assert isclose(s[0], 12.34) and isclose(s[3], 56.78) rev = reversed(s) - assert cstats.values() == ['of size', '5'] + assert cstats.values() == ["of size", "5"] rev2 = s[::-1] - assert cstats.values() == ['of size', '5'] + assert cstats.values() == ["of size", "5"] it = iter(m.Sequence(0)) for _ in range(3): # __next__ must continue to raise StopIteration with pytest.raises(StopIteration): next(it) - assert cstats.values() == ['of size', '0'] + assert cstats.values() == ["of size", "0"] expected = [0, 56.78, 0, 0, 12.34] assert allclose(rev, expected) @@ -79,7 +138,7 @@ def test_sequence(): assert rev == rev2 rev[0::2] = m.Sequence([2.0, 2.0, 2.0]) - assert cstats.values() == ['of size', '3', 'from std::vector'] + assert cstats.values() == ["of size", "3", "from std::vector"] assert allclose(rev, [2, 56.78, 2, 0, 2]) @@ -102,11 +161,12 @@ def test_sequence(): def test_sequence_length(): - """#2076: Exception raised by len(arg) should be propagated """ + """#2076: Exception raised by len(arg) should be propagated""" + class BadLen(RuntimeError): pass - class SequenceLike(): + class SequenceLike: def __getitem__(self, i): return None @@ -121,21 +181,22 @@ def test_sequence_length(): def test_map_iterator(): - sm = m.StringMap({'hi': 'bye', 'black': 'white'}) - assert sm['hi'] == 'bye' + sm = m.StringMap({"hi": "bye", "black": "white"}) + assert sm["hi"] == "bye" assert len(sm) == 2 - assert sm['black'] == 'white' + assert sm["black"] == "white" with pytest.raises(KeyError): - assert sm['orange'] - sm['orange'] = 'banana' - assert sm['orange'] == 'banana' + assert sm["orange"] + sm["orange"] = "banana" + assert sm["orange"] == "banana" - expected = {'hi': 'bye', 'black': 'white', 'orange': 'banana'} + expected = {"hi": "bye", "black": "white", "orange": "banana"} for k in sm: assert sm[k] == expected[k] for k, v in sm.items(): assert v == expected[k] + assert list(sm.values()) == [expected[k] for k in sm] it = iter(m.StringMap({})) for _ in range(3): # __next__ must continue to raise StopIteration @@ -179,11 +240,12 @@ def test_iterator_passthrough(): """#181: iterator passthrough did not compile""" from pybind11_tests.sequences_and_iterators import iterator_passthrough - assert list(iterator_passthrough(iter([3, 5, 7, 9, 11, 13, 15]))) == [3, 5, 7, 9, 11, 13, 15] + values = [3, 5, 7, 9, 11, 13, 15] + assert list(iterator_passthrough(iter(values))) == values def test_iterator_rvp(): - """#388: Can't make iterators via make_iterator() with different r/v policies """ + """#388: Can't make iterators via make_iterator() with different r/v policies""" import pybind11_tests.sequences_and_iterators as m assert list(m.make_iterator_1()) == [1, 2, 3] diff --git a/pybind11/tests/test_smart_ptr.cpp b/pybind11/tests/test_smart_ptr.cpp index 60c2e692e..94f04330a 100644 --- a/pybind11/tests/test_smart_ptr.cpp +++ b/pybind11/tests/test_smart_ptr.cpp @@ -8,30 +8,14 @@ BSD-style license that can be found in the LICENSE file. */ -#if defined(_MSC_VER) && _MSC_VER < 1910 -# pragma warning(disable: 4702) // unreachable code in system header +#if defined(_MSC_VER) && _MSC_VER < 1910 // VS 2015's MSVC +# pragma warning(disable: 4702) // unreachable code in system header (xatomic.h(382)) #endif #include "pybind11_tests.h" #include "object.h" -// Make pybind aware of the ref-counted wrapper type (s): - -// ref is a wrapper for 'Object' which uses intrusive reference counting -// It is always possible to construct a ref from an Object* pointer without -// possible inconsistencies, hence the 'true' argument at the end. -PYBIND11_DECLARE_HOLDER_TYPE(T, ref, true); -// Make pybind11 aware of the non-standard getter member function -namespace pybind11 { namespace detail { - template - struct holder_helper> { - static const T *get(const ref &p) { return p.get_ptr(); } - }; -} // namespace detail -} // namespace pybind11 - -// The following is not required anymore for std::shared_ptr, but it should compile without error: -PYBIND11_DECLARE_HOLDER_TYPE(T, std::shared_ptr); +namespace { // This is just a wrapper around unique_ptr, but with extra fields to deliberately bloat up the // holder size to trigger the non-simple-layout internal instance layout for single inheritance with @@ -40,21 +24,19 @@ template class huge_unique_ptr { std::unique_ptr ptr; uint64_t padding[10]; public: - huge_unique_ptr(T *p) : ptr(p) {}; + explicit huge_unique_ptr(T *p) : ptr(p) {} T *get() { return ptr.get(); } }; -PYBIND11_DECLARE_HOLDER_TYPE(T, huge_unique_ptr); // Simple custom holder that works like unique_ptr template class custom_unique_ptr { std::unique_ptr impl; public: - custom_unique_ptr(T* p) : impl(p) { } + explicit custom_unique_ptr(T *p) : impl(p) {} T* get() const { return impl.get(); } T* release_ptr() { return impl.release(); } }; -PYBIND11_DECLARE_HOLDER_TYPE(T, custom_unique_ptr); // Simple custom holder that works like shared_ptr and has operator& overload // To obtain address of an instance of this holder pybind should use std::addressof @@ -64,11 +46,10 @@ class shared_ptr_with_addressof_operator { std::shared_ptr impl; public: shared_ptr_with_addressof_operator( ) = default; - shared_ptr_with_addressof_operator(T* p) : impl(p) { } + explicit shared_ptr_with_addressof_operator(T *p) : impl(p) {} T* get() const { return impl.get(); } T** operator&() { throw std::logic_error("Call of overloaded operator& is not expected"); } }; -PYBIND11_DECLARE_HOLDER_TYPE(T, shared_ptr_with_addressof_operator); // Simple custom holder that works like unique_ptr and has operator& overload // To obtain address of an instance of this holder pybind should use std::addressof @@ -78,15 +59,226 @@ class unique_ptr_with_addressof_operator { std::unique_ptr impl; public: unique_ptr_with_addressof_operator() = default; - unique_ptr_with_addressof_operator(T* p) : impl(p) { } + explicit unique_ptr_with_addressof_operator(T *p) : impl(p) {} T* get() const { return impl.get(); } T* release_ptr() { return impl.release(); } T** operator&() { throw std::logic_error("Call of overloaded operator& is not expected"); } }; + +// Custom object with builtin reference counting (see 'object.h' for the implementation) +class MyObject1 : public Object { +public: + explicit MyObject1(int value) : value(value) { print_created(this, toString()); } + std::string toString() const override { return "MyObject1[" + std::to_string(value) + "]"; } +protected: + ~MyObject1() override { print_destroyed(this); } +private: + int value; +}; + +// Object managed by a std::shared_ptr<> +class MyObject2 { +public: + MyObject2(const MyObject2 &) = default; + explicit MyObject2(int value) : value(value) { print_created(this, toString()); } + std::string toString() const { return "MyObject2[" + std::to_string(value) + "]"; } + virtual ~MyObject2() { print_destroyed(this); } +private: + int value; +}; + +// Object managed by a std::shared_ptr<>, additionally derives from std::enable_shared_from_this<> +class MyObject3 : public std::enable_shared_from_this { +public: + MyObject3(const MyObject3 &) = default; + explicit MyObject3(int value) : value(value) { print_created(this, toString()); } + std::string toString() const { return "MyObject3[" + std::to_string(value) + "]"; } + virtual ~MyObject3() { print_destroyed(this); } +private: + int value; +}; + +// test_unique_nodelete +// Object with a private destructor +class MyObject4; +std::unordered_set myobject4_instances; +class MyObject4 { +public: + explicit MyObject4(int value) : value{value} { + print_created(this); + myobject4_instances.insert(this); + } + int value; + + static void cleanupAllInstances() { + auto tmp = std::move(myobject4_instances); + myobject4_instances.clear(); + for (auto o : tmp) + delete o; + } +private: + ~MyObject4() { + myobject4_instances.erase(this); + print_destroyed(this); + } +}; + +// test_unique_deleter +// Object with std::unique_ptr where D is not matching the base class +// Object with a protected destructor +class MyObject4a; +std::unordered_set myobject4a_instances; +class MyObject4a { +public: + explicit MyObject4a(int i) { + value = i; + print_created(this); + myobject4a_instances.insert(this); + }; + int value; + + static void cleanupAllInstances() { + auto tmp = std::move(myobject4a_instances); + myobject4a_instances.clear(); + for (auto o : tmp) + delete o; + } +protected: + virtual ~MyObject4a() { + myobject4a_instances.erase(this); + print_destroyed(this); + } +}; + +// Object derived but with public destructor and no Deleter in default holder +class MyObject4b : public MyObject4a { +public: + explicit MyObject4b(int i) : MyObject4a(i) { print_created(this); } + ~MyObject4b() override { print_destroyed(this); } +}; + +// test_large_holder +class MyObject5 { // managed by huge_unique_ptr +public: + explicit MyObject5(int value) : value{value} { print_created(this); } + ~MyObject5() { print_destroyed(this); } + int value; +}; + +// test_shared_ptr_and_references +struct SharedPtrRef { + struct A { + A() { print_created(this); } + A(const A &) { print_copy_created(this); } + A(A &&) noexcept { print_move_created(this); } + ~A() { print_destroyed(this); } + }; + + A value = {}; + std::shared_ptr shared = std::make_shared(); +}; + +// test_shared_ptr_from_this_and_references +struct SharedFromThisRef { + struct B : std::enable_shared_from_this { + B() { print_created(this); } + // NOLINTNEXTLINE(bugprone-copy-constructor-init) + B(const B &) : std::enable_shared_from_this() { print_copy_created(this); } + B(B &&) noexcept : std::enable_shared_from_this() { print_move_created(this); } + ~B() { print_destroyed(this); } + }; + + B value = {}; + std::shared_ptr shared = std::make_shared(); +}; + +// Issue #865: shared_from_this doesn't work with virtual inheritance +struct SharedFromThisVBase : std::enable_shared_from_this { + SharedFromThisVBase() = default; + SharedFromThisVBase(const SharedFromThisVBase &) = default; + virtual ~SharedFromThisVBase() = default; +}; +struct SharedFromThisVirt : virtual SharedFromThisVBase {}; + +// test_move_only_holder +struct C { + C() { print_created(this); } + ~C() { print_destroyed(this); } +}; + +// test_holder_with_addressof_operator +struct TypeForHolderWithAddressOf { + TypeForHolderWithAddressOf() { print_created(this); } + TypeForHolderWithAddressOf(const TypeForHolderWithAddressOf &) { print_copy_created(this); } + TypeForHolderWithAddressOf(TypeForHolderWithAddressOf &&) noexcept { + print_move_created(this); + } + ~TypeForHolderWithAddressOf() { print_destroyed(this); } + std::string toString() const { + return "TypeForHolderWithAddressOf[" + std::to_string(value) + "]"; + } + int value = 42; +}; + +// test_move_only_holder_with_addressof_operator +struct TypeForMoveOnlyHolderWithAddressOf { + explicit TypeForMoveOnlyHolderWithAddressOf(int value) : value{value} { print_created(this); } + ~TypeForMoveOnlyHolderWithAddressOf() { print_destroyed(this); } + std::string toString() const { + return "MoveOnlyHolderWithAddressOf[" + std::to_string(value) + "]"; + } + int value; +}; + +// test_smart_ptr_from_default +struct HeldByDefaultHolder { }; + +// test_shared_ptr_gc +// #187: issue involving std::shared_ptr<> return value policy & garbage collection +struct ElementBase { + virtual ~ElementBase() = default; /* Force creation of virtual table */ + ElementBase() = default; + ElementBase(const ElementBase&) = delete; +}; + +struct ElementA : ElementBase { + explicit ElementA(int v) : v(v) {} + int value() const { return v; } + int v; +}; + +struct ElementList { + void add(const std::shared_ptr &e) { l.push_back(e); } + std::vector> l; +}; + +} // namespace + +// ref is a wrapper for 'Object' which uses intrusive reference counting +// It is always possible to construct a ref from an Object* pointer without +// possible inconsistencies, hence the 'true' argument at the end. +// Make pybind11 aware of the non-standard getter member function +namespace pybind11 { namespace detail { + template + struct holder_helper> { + static const T *get(const ref &p) { return p.get_ptr(); } + }; +} // namespace detail +} // namespace pybind11 + +// Make pybind aware of the ref-counted wrapper type (s): +PYBIND11_DECLARE_HOLDER_TYPE(T, ref, true); +// The following is not required anymore for std::shared_ptr, but it should compile without error: +PYBIND11_DECLARE_HOLDER_TYPE(T, std::shared_ptr); +PYBIND11_DECLARE_HOLDER_TYPE(T, huge_unique_ptr); +PYBIND11_DECLARE_HOLDER_TYPE(T, custom_unique_ptr); +PYBIND11_DECLARE_HOLDER_TYPE(T, shared_ptr_with_addressof_operator); PYBIND11_DECLARE_HOLDER_TYPE(T, unique_ptr_with_addressof_operator); - TEST_SUBMODULE(smart_ptr, m) { + // Please do not interleave `struct` and `class` definitions with bindings code, + // but implement `struct`s and `class`es in the anonymous namespace above. + // This helps keeping the smart_holder branch in sync with master. // test_smart_ptr @@ -94,24 +286,14 @@ TEST_SUBMODULE(smart_ptr, m) { py::class_> obj(m, "Object"); obj.def("getRefCount", &Object::getRefCount); - // Custom object with builtin reference counting (see 'object.h' for the implementation) - class MyObject1 : public Object { - public: - MyObject1(int value) : value(value) { print_created(this, toString()); } - std::string toString() const override { return "MyObject1[" + std::to_string(value) + "]"; } - protected: - ~MyObject1() override { print_destroyed(this); } - private: - int value; - }; py::class_>(m, "MyObject1", obj) .def(py::init()); py::implicitly_convertible(); m.def("make_object_1", []() -> Object * { return new MyObject1(1); }); - m.def("make_object_2", []() -> ref { return new MyObject1(2); }); + m.def("make_object_2", []() -> ref { return ref(new MyObject1(2)); }); m.def("make_myobject1_1", []() -> MyObject1 * { return new MyObject1(4); }); - m.def("make_myobject1_2", []() -> ref { return new MyObject1(5); }); + m.def("make_myobject1_2", []() -> ref { return ref(new MyObject1(5)); }); m.def("print_object_1", [](const Object *obj) { py::print(obj->toString()); }); m.def("print_object_2", [](ref obj) { py::print(obj->toString()); }); m.def("print_object_3", [](const ref &obj) { py::print(obj->toString()); }); @@ -124,48 +306,29 @@ TEST_SUBMODULE(smart_ptr, m) { // Expose constructor stats for the ref type m.def("cstats_ref", &ConstructorStats::get); - - // Object managed by a std::shared_ptr<> - class MyObject2 { - public: - MyObject2(const MyObject2 &) = default; - MyObject2(int value) : value(value) { print_created(this, toString()); } - std::string toString() const { return "MyObject2[" + std::to_string(value) + "]"; } - virtual ~MyObject2() { print_destroyed(this); } - private: - int value; - }; py::class_>(m, "MyObject2") .def(py::init()); m.def("make_myobject2_1", []() { return new MyObject2(6); }); m.def("make_myobject2_2", []() { return std::make_shared(7); }); m.def("print_myobject2_1", [](const MyObject2 *obj) { py::print(obj->toString()); }); + // NOLINTNEXTLINE(performance-unnecessary-value-param) m.def("print_myobject2_2", [](std::shared_ptr obj) { py::print(obj->toString()); }); m.def("print_myobject2_3", [](const std::shared_ptr &obj) { py::print(obj->toString()); }); m.def("print_myobject2_4", [](const std::shared_ptr *obj) { py::print((*obj)->toString()); }); - // Object managed by a std::shared_ptr<>, additionally derives from std::enable_shared_from_this<> - class MyObject3 : public std::enable_shared_from_this { - public: - MyObject3(const MyObject3 &) = default; - MyObject3(int value) : value(value) { print_created(this, toString()); } - std::string toString() const { return "MyObject3[" + std::to_string(value) + "]"; } - virtual ~MyObject3() { print_destroyed(this); } - private: - int value; - }; py::class_>(m, "MyObject3") .def(py::init()); m.def("make_myobject3_1", []() { return new MyObject3(8); }); m.def("make_myobject3_2", []() { return std::make_shared(9); }); m.def("print_myobject3_1", [](const MyObject3 *obj) { py::print(obj->toString()); }); + // NOLINTNEXTLINE(performance-unnecessary-value-param) m.def("print_myobject3_2", [](std::shared_ptr obj) { py::print(obj->toString()); }); m.def("print_myobject3_3", [](const std::shared_ptr &obj) { py::print(obj->toString()); }); m.def("print_myobject3_4", [](const std::shared_ptr *obj) { py::print((*obj)->toString()); }); // test_smart_ptr_refcounting m.def("test_object1_refcounting", []() { - ref o = new MyObject1(0); + auto o = ref(new MyObject1(0)); bool good = o->getRefCount() == 1; py::object o2 = py::cast(o, py::return_value_policy::reference); // always request (partial) ownership for objects with intrusive @@ -175,155 +338,88 @@ TEST_SUBMODULE(smart_ptr, m) { }); // test_unique_nodelete - // Object with a private destructor - class MyObject4 { - public: - MyObject4(int value) : value{value} { print_created(this); } - int value; - private: - ~MyObject4() { print_destroyed(this); } - }; py::class_>(m, "MyObject4") .def(py::init()) - .def_readwrite("value", &MyObject4::value); + .def_readwrite("value", &MyObject4::value) + .def_static("cleanup_all_instances", &MyObject4::cleanupAllInstances); // test_unique_deleter - // Object with std::unique_ptr where D is not matching the base class - // Object with a protected destructor - class MyObject4a { - public: - MyObject4a(int i) { - value = i; - print_created(this); - }; - int value; - protected: - virtual ~MyObject4a() { print_destroyed(this); } - }; py::class_>(m, "MyObject4a") .def(py::init()) - .def_readwrite("value", &MyObject4a::value); + .def_readwrite("value", &MyObject4a::value) + .def_static("cleanup_all_instances", &MyObject4a::cleanupAllInstances); - // Object derived but with public destructor and no Deleter in default holder - class MyObject4b : public MyObject4a { - public: - MyObject4b(int i) : MyObject4a(i) { print_created(this); } - ~MyObject4b() override { print_destroyed(this); } - }; - py::class_(m, "MyObject4b") + py::class_>(m, "MyObject4b") .def(py::init()); // test_large_holder - class MyObject5 { // managed by huge_unique_ptr - public: - MyObject5(int value) : value{value} { print_created(this); } - ~MyObject5() { print_destroyed(this); } - int value; - }; py::class_>(m, "MyObject5") .def(py::init()) .def_readwrite("value", &MyObject5::value); // test_shared_ptr_and_references - struct SharedPtrRef { - struct A { - A() { print_created(this); } - A(const A &) { print_copy_created(this); } - A(A &&) { print_move_created(this); } - ~A() { print_destroyed(this); } - }; - - A value = {}; - std::shared_ptr shared = std::make_shared(); - }; using A = SharedPtrRef::A; py::class_>(m, "A"); - py::class_(m, "SharedPtrRef") + py::class_>(m, "SharedPtrRef") .def(py::init<>()) .def_readonly("ref", &SharedPtrRef::value) - .def_property_readonly("copy", [](const SharedPtrRef &s) { return s.value; }, - py::return_value_policy::copy) + .def_property_readonly( + "copy", [](const SharedPtrRef &s) { return s.value; }, py::return_value_policy::copy) .def_readonly("holder_ref", &SharedPtrRef::shared) - .def_property_readonly("holder_copy", [](const SharedPtrRef &s) { return s.shared; }, - py::return_value_policy::copy) + .def_property_readonly( + "holder_copy", + [](const SharedPtrRef &s) { return s.shared; }, + py::return_value_policy::copy) .def("set_ref", [](SharedPtrRef &, const A &) { return true; }) + // NOLINTNEXTLINE(performance-unnecessary-value-param) .def("set_holder", [](SharedPtrRef &, std::shared_ptr) { return true; }); // test_shared_ptr_from_this_and_references - struct SharedFromThisRef { - struct B : std::enable_shared_from_this { - B() { print_created(this); } - B(const B &) : std::enable_shared_from_this() { print_copy_created(this); } - B(B &&) : std::enable_shared_from_this() { print_move_created(this); } - ~B() { print_destroyed(this); } - }; - - B value = {}; - std::shared_ptr shared = std::make_shared(); - }; using B = SharedFromThisRef::B; py::class_>(m, "B"); - py::class_(m, "SharedFromThisRef") + py::class_>(m, "SharedFromThisRef") .def(py::init<>()) .def_readonly("bad_wp", &SharedFromThisRef::value) - .def_property_readonly("ref", [](const SharedFromThisRef &s) -> const B & { return *s.shared; }) - .def_property_readonly("copy", [](const SharedFromThisRef &s) { return s.value; }, - py::return_value_policy::copy) + .def_property_readonly("ref", + [](const SharedFromThisRef &s) -> const B & { return *s.shared; }) + .def_property_readonly( + "copy", + [](const SharedFromThisRef &s) { return s.value; }, + py::return_value_policy::copy) .def_readonly("holder_ref", &SharedFromThisRef::shared) - .def_property_readonly("holder_copy", [](const SharedFromThisRef &s) { return s.shared; }, - py::return_value_policy::copy) + .def_property_readonly( + "holder_copy", + [](const SharedFromThisRef &s) { return s.shared; }, + py::return_value_policy::copy) .def("set_ref", [](SharedFromThisRef &, const B &) { return true; }) + // NOLINTNEXTLINE(performance-unnecessary-value-param) .def("set_holder", [](SharedFromThisRef &, std::shared_ptr) { return true; }); // Issue #865: shared_from_this doesn't work with virtual inheritance - struct SharedFromThisVBase : std::enable_shared_from_this { - SharedFromThisVBase() = default; - SharedFromThisVBase(const SharedFromThisVBase &) = default; - virtual ~SharedFromThisVBase() = default; - }; - struct SharedFromThisVirt : virtual SharedFromThisVBase {}; static std::shared_ptr sft(new SharedFromThisVirt()); py::class_>(m, "SharedFromThisVirt") .def_static("get", []() { return sft.get(); }); // test_move_only_holder - struct C { - C() { print_created(this); } - ~C() { print_destroyed(this); } - }; py::class_>(m, "TypeWithMoveOnlyHolder") .def_static("make", []() { return custom_unique_ptr(new C); }) .def_static("make_as_object", []() { return py::cast(custom_unique_ptr(new C)); }); // test_holder_with_addressof_operator - struct TypeForHolderWithAddressOf { - TypeForHolderWithAddressOf() { print_created(this); } - TypeForHolderWithAddressOf(const TypeForHolderWithAddressOf &) { print_copy_created(this); } - TypeForHolderWithAddressOf(TypeForHolderWithAddressOf &&) { print_move_created(this); } - ~TypeForHolderWithAddressOf() { print_destroyed(this); } - std::string toString() const { - return "TypeForHolderWithAddressOf[" + std::to_string(value) + "]"; - } - int value = 42; - }; using HolderWithAddressOf = shared_ptr_with_addressof_operator; py::class_(m, "TypeForHolderWithAddressOf") .def_static("make", []() { return HolderWithAddressOf(new TypeForHolderWithAddressOf); }) .def("get", [](const HolderWithAddressOf &self) { return self.get(); }) - .def("print_object_1", [](const TypeForHolderWithAddressOf *obj) { py::print(obj->toString()); }) + .def("print_object_1", + [](const TypeForHolderWithAddressOf *obj) { py::print(obj->toString()); }) + // NOLINTNEXTLINE(performance-unnecessary-value-param) .def("print_object_2", [](HolderWithAddressOf obj) { py::print(obj.get()->toString()); }) - .def("print_object_3", [](const HolderWithAddressOf &obj) { py::print(obj.get()->toString()); }) - .def("print_object_4", [](const HolderWithAddressOf *obj) { py::print((*obj).get()->toString()); }); + .def("print_object_3", + [](const HolderWithAddressOf &obj) { py::print(obj.get()->toString()); }) + .def("print_object_4", + [](const HolderWithAddressOf *obj) { py::print((*obj).get()->toString()); }); // test_move_only_holder_with_addressof_operator - struct TypeForMoveOnlyHolderWithAddressOf { - TypeForMoveOnlyHolderWithAddressOf(int value) : value{value} { print_created(this); } - ~TypeForMoveOnlyHolderWithAddressOf() { print_destroyed(this); } - std::string toString() const { - return "MoveOnlyHolderWithAddressOf[" + std::to_string(value) + "]"; - } - int value; - }; using MoveOnlyHolderWithAddressOf = unique_ptr_with_addressof_operator; py::class_(m, "TypeForMoveOnlyHolderWithAddressOf") .def_static("make", []() { return MoveOnlyHolderWithAddressOf(new TypeForMoveOnlyHolderWithAddressOf(0)); }) @@ -331,33 +427,19 @@ TEST_SUBMODULE(smart_ptr, m) { .def("print_object", [](const TypeForMoveOnlyHolderWithAddressOf *obj) { py::print(obj->toString()); }); // test_smart_ptr_from_default - struct HeldByDefaultHolder { }; - py::class_(m, "HeldByDefaultHolder") + py::class_>(m, "HeldByDefaultHolder") .def(py::init<>()) + // NOLINTNEXTLINE(performance-unnecessary-value-param) .def_static("load_shared_ptr", [](std::shared_ptr) {}); // test_shared_ptr_gc // #187: issue involving std::shared_ptr<> return value policy & garbage collection - struct ElementBase { - virtual ~ElementBase() = default; /* Force creation of virtual table */ - ElementBase() = default; - ElementBase(const ElementBase&) = delete; - }; py::class_>(m, "ElementBase"); - struct ElementA : ElementBase { - ElementA(int v) : v(v) { } - int value() { return v; } - int v; - }; py::class_>(m, "ElementA") .def(py::init()) .def("value", &ElementA::value); - struct ElementList { - void add(std::shared_ptr e) { l.push_back(e); } - std::vector> l; - }; py::class_>(m, "ElementList") .def(py::init<>()) .def("add", &ElementList::add) diff --git a/pybind11/tests/test_smart_ptr.py b/pybind11/tests/test_smart_ptr.py index 0b1ca45b5..85f61a322 100644 --- a/pybind11/tests/test_smart_ptr.py +++ b/pybind11/tests/test_smart_ptr.py @@ -7,7 +7,9 @@ from pybind11_tests import ConstructorStats # noqa: E402 def test_smart_ptr(capture): # Object1 - for i, o in enumerate([m.make_object_1(), m.make_object_2(), m.MyObject1(3)], start=1): + for i, o in enumerate( + [m.make_object_1(), m.make_object_2(), m.MyObject1(3)], start=1 + ): assert o.getRefCount() == 1 with capture: m.print_object_1(o) @@ -16,8 +18,9 @@ def test_smart_ptr(capture): m.print_object_4(o) assert capture == "MyObject1[{i}]\n".format(i=i) * 4 - for i, o in enumerate([m.make_myobject1_1(), m.make_myobject1_2(), m.MyObject1(6), 7], - start=4): + for i, o in enumerate( + [m.make_myobject1_1(), m.make_myobject1_2(), m.MyObject1(6), 7], start=4 + ): print(o) with capture: if not isinstance(o, int): @@ -29,11 +32,15 @@ def test_smart_ptr(capture): m.print_myobject1_2(o) m.print_myobject1_3(o) m.print_myobject1_4(o) - assert capture == "MyObject1[{i}]\n".format(i=i) * (4 if isinstance(o, int) else 8) + + times = 4 if isinstance(o, int) else 8 + assert capture == "MyObject1[{i}]\n".format(i=i) * times cstats = ConstructorStats.get(m.MyObject1) assert cstats.alive() == 0 - expected_values = ['MyObject1[{}]'.format(i) for i in range(1, 7)] + ['MyObject1[7]'] * 4 + expected_values = ["MyObject1[{}]".format(i) for i in range(1, 7)] + [ + "MyObject1[7]" + ] * 4 assert cstats.values() == expected_values assert cstats.default_constructions == 0 assert cstats.copy_constructions == 0 @@ -42,7 +49,9 @@ def test_smart_ptr(capture): assert cstats.move_assignments == 0 # Object2 - for i, o in zip([8, 6, 7], [m.MyObject2(8), m.make_myobject2_1(), m.make_myobject2_2()]): + for i, o in zip( + [8, 6, 7], [m.MyObject2(8), m.make_myobject2_1(), m.make_myobject2_2()] + ): print(o) with capture: m.print_myobject2_1(o) @@ -55,7 +64,7 @@ def test_smart_ptr(capture): assert cstats.alive() == 1 o = None assert cstats.alive() == 0 - assert cstats.values() == ['MyObject2[8]', 'MyObject2[6]', 'MyObject2[7]'] + assert cstats.values() == ["MyObject2[8]", "MyObject2[6]", "MyObject2[7]"] assert cstats.default_constructions == 0 assert cstats.copy_constructions == 0 # assert cstats.move_constructions >= 0 # Doesn't invoke any @@ -63,7 +72,9 @@ def test_smart_ptr(capture): assert cstats.move_assignments == 0 # Object3 - for i, o in zip([9, 8, 9], [m.MyObject3(9), m.make_myobject3_1(), m.make_myobject3_2()]): + for i, o in zip( + [9, 8, 9], [m.MyObject3(9), m.make_myobject3_1(), m.make_myobject3_2()] + ): print(o) with capture: m.print_myobject3_1(o) @@ -76,7 +87,7 @@ def test_smart_ptr(capture): assert cstats.alive() == 1 o = None assert cstats.alive() == 0 - assert cstats.values() == ['MyObject3[9]', 'MyObject3[8]', 'MyObject3[9]'] + assert cstats.values() == ["MyObject3[9]", "MyObject3[8]", "MyObject3[9]"] assert cstats.default_constructions == 0 assert cstats.copy_constructions == 0 # assert cstats.move_constructions >= 0 # Doesn't invoke any @@ -96,7 +107,7 @@ def test_smart_ptr(capture): # ref<> cstats = m.cstats_ref() assert cstats.alive() == 0 - assert cstats.values() == ['from pointer'] * 10 + assert cstats.values() == ["from pointer"] * 10 assert cstats.default_constructions == 30 assert cstats.copy_constructions == 12 # assert cstats.move_constructions >= 0 # Doesn't invoke any @@ -114,7 +125,9 @@ def test_unique_nodelete(): cstats = ConstructorStats.get(m.MyObject4) assert cstats.alive() == 1 del o - assert cstats.alive() == 1 # Leak, but that's intentional + assert cstats.alive() == 1 + m.MyObject4.cleanup_all_instances() + assert cstats.alive() == 0 def test_unique_nodelete4a(): @@ -123,19 +136,25 @@ def test_unique_nodelete4a(): cstats = ConstructorStats.get(m.MyObject4a) assert cstats.alive() == 1 del o - assert cstats.alive() == 1 # Leak, but that's intentional + assert cstats.alive() == 1 + m.MyObject4a.cleanup_all_instances() + assert cstats.alive() == 0 def test_unique_deleter(): + m.MyObject4a(0) o = m.MyObject4b(23) assert o.value == 23 cstats4a = ConstructorStats.get(m.MyObject4a) - assert cstats4a.alive() == 2 # Two because of previous test + assert cstats4a.alive() == 2 cstats4b = ConstructorStats.get(m.MyObject4b) assert cstats4b.alive() == 1 del o - assert cstats4a.alive() == 1 # Should now only be one leftover from previous test + assert cstats4a.alive() == 1 # Should now only be one leftover assert cstats4b.alive() == 0 # Should be deleted + m.MyObject4a.cleanup_all_instances() + assert cstats4a.alive() == 0 + assert cstats4b.alive() == 0 def test_large_holder(): @@ -186,7 +205,9 @@ def test_shared_ptr_from_this_and_references(): ref = s.ref # init_holder_helper(holder_ptr=false, owned=false, bad_wp=false) assert stats.alive() == 2 assert s.set_ref(ref) - assert s.set_holder(ref) # std::enable_shared_from_this can create a holder from a reference + assert s.set_holder( + ref + ) # std::enable_shared_from_this can create a holder from a reference bad_wp = s.bad_wp # init_holder_helper(holder_ptr=false, owned=false, bad_wp=true) assert stats.alive() == 2 @@ -200,12 +221,16 @@ def test_shared_ptr_from_this_and_references(): assert s.set_ref(copy) assert s.set_holder(copy) - holder_ref = s.holder_ref # init_holder_helper(holder_ptr=true, owned=false, bad_wp=false) + holder_ref = ( + s.holder_ref + ) # init_holder_helper(holder_ptr=true, owned=false, bad_wp=false) assert stats.alive() == 3 assert s.set_ref(holder_ref) assert s.set_holder(holder_ref) - holder_copy = s.holder_copy # init_holder_helper(holder_ptr=true, owned=true, bad_wp=false) + holder_copy = ( + s.holder_copy + ) # init_holder_helper(holder_ptr=true, owned=true, bad_wp=false) assert stats.alive() == 3 assert s.set_ref(holder_copy) assert s.set_holder(holder_copy) @@ -277,8 +302,10 @@ def test_smart_ptr_from_default(): instance = m.HeldByDefaultHolder() with pytest.raises(RuntimeError) as excinfo: m.HeldByDefaultHolder.load_shared_ptr(instance) - assert "Unable to load a custom holder type from a " \ - "default-holder instance" in str(excinfo.value) + assert ( + "Unable to load a custom holder type from a " + "default-holder instance" in str(excinfo.value) + ) def test_shared_ptr_gc(): diff --git a/pybind11/tests/test_stl.cpp b/pybind11/tests/test_stl.cpp index 059016277..bc5c6553a 100644 --- a/pybind11/tests/test_stl.cpp +++ b/pybind11/tests/test_stl.cpp @@ -11,9 +11,26 @@ #include "constructor_stats.h" #include +#ifndef PYBIND11_HAS_FILESYSTEM_IS_OPTIONAL +#define PYBIND11_HAS_FILESYSTEM_IS_OPTIONAL +#endif +#include + #include #include +#if defined(PYBIND11_TEST_BOOST) +#include + +namespace pybind11 { namespace detail { +template +struct type_caster> : optional_caster> {}; + +template <> +struct type_caster : void_caster {}; +}} // namespace pybind11::detail +#endif + // Test with `std::variant` in C++17 mode, or with `boost::variant` in C++11/14 #if defined(PYBIND11_HAS_VARIANT) using std::variant; @@ -40,7 +57,8 @@ PYBIND11_MAKE_OPAQUE(std::vector>); /// Issue #528: templated constructor struct TplCtorClass { - template TplCtorClass(const T &) { } + template + explicit TplCtorClass(const T &) {} bool operator==(const TplCtorClass &) const { return true; } }; @@ -53,7 +71,8 @@ namespace std { template