From 257f576ebfd87143ab3c6545813d746301470e0d Mon Sep 17 00:00:00 2001 From: Your Name Date: Sat, 27 Apr 2024 03:19:52 -0500 Subject: [PATCH] wip --- rednose/SConscript | 17 + rednose/helpers/ekf.h | 42 + rednose/helpers/ekf_load.cc | 39 + rednose/helpers/ekf_load.h | 9 + rednose/helpers/ekf_sym.cc | 223 + rednose/helpers/ekf_sym.h | 113 + rednose/helpers/ekf_sym.py | 2 +- rednose/helpers/ekf_sym_pyx.cpp | 35816 ------------------------------ rednose/helpers/ekf_sym_pyx.so | Bin 4898664 -> 0 bytes rednose/helpers/kalmanfilter.py | 6 +- rednose/logger/logger.h | 20 + 11 files changed, 467 insertions(+), 35820 deletions(-) create mode 100644 rednose/SConscript create mode 100644 rednose/helpers/ekf.h create mode 100644 rednose/helpers/ekf_load.cc create mode 100644 rednose/helpers/ekf_load.h create mode 100644 rednose/helpers/ekf_sym.cc create mode 100644 rednose/helpers/ekf_sym.h delete mode 100644 rednose/helpers/ekf_sym_pyx.cpp delete mode 100755 rednose/helpers/ekf_sym_pyx.so create mode 100644 rednose/logger/logger.h diff --git a/rednose/SConscript b/rednose/SConscript new file mode 100644 index 0000000..52e36e0 --- /dev/null +++ b/rednose/SConscript @@ -0,0 +1,17 @@ +Import('env', 'envCython', 'common') + +cc_sources = [ + "helpers/ekf_load.cc", + "helpers/ekf_sym.cc", +] +libs = ["dl"] +if common != "": + # for SWAGLOG support + libs += [common, 'zmq'] + +ekf_objects = env.SharedObject(cc_sources) +rednose = env.Library("helpers/ekf_sym", ekf_objects, LIBS=libs) +rednose_python = envCython.Program("helpers/ekf_sym_pyx.so", ["helpers/ekf_sym_pyx.pyx", ekf_objects], + LIBS=libs + envCython["LIBS"]) + +Export('rednose', 'rednose_python') diff --git a/rednose/helpers/ekf.h b/rednose/helpers/ekf.h new file mode 100644 index 0000000..2afe6dd --- /dev/null +++ b/rednose/helpers/ekf.h @@ -0,0 +1,42 @@ +#pragma once + +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +typedef void (*extra_routine_t)(double *, double *); + +struct EKF { + std::string name; + std::vector kinds; + std::vector feature_kinds; + + void (*f_fun)(double *, double, double *); + void (*F_fun)(double *, double, double *); + void (*err_fun)(double *, double *, double *); + void (*inv_err_fun)(double *, double *, double *); + void (*H_mod_fun)(double *, double *); + void (*predict)(double *, double *, double *, double); + std::unordered_map hs = {}; + std::unordered_map Hs = {}; + std::unordered_map updates = {}; + std::unordered_map Hes = {}; + std::unordered_map sets = {}; + std::unordered_map extra_routines = {}; +}; + +#define ekf_lib_init(ekf) \ +extern "C" void* ekf_get() { \ + return (void*) &ekf; \ +} \ +extern void __attribute__((weak)) ekf_register(const EKF* ptr); \ +static void __attribute__((constructor)) do_ekf_init_ ## ekf(void) { \ + if (ekf_register) ekf_register(&ekf); \ +} diff --git a/rednose/helpers/ekf_load.cc b/rednose/helpers/ekf_load.cc new file mode 100644 index 0000000..882b0b4 --- /dev/null +++ b/rednose/helpers/ekf_load.cc @@ -0,0 +1,39 @@ +#include "ekf_load.h" +#include + +std::vector& ekf_get_all() { + static std::vector vec; + return vec; +} + +void ekf_register(const EKF* ekf) { + ekf_get_all().push_back(ekf); +} + +const EKF* ekf_lookup(const std::string& ekf_name) { + for (const auto& ekfi : ekf_get_all()) { + if (ekf_name == ekfi->name) { + return ekfi; + } + } + return NULL; +} + +void ekf_load_and_register(const std::string& ekf_directory, const std::string& ekf_name) { + if (ekf_lookup(ekf_name)) { + return; + } + +#ifdef __APPLE__ + std::string dylib_ext = ".dylib"; +#else + std::string dylib_ext = ".so"; +#endif + std::string ekf_path = ekf_directory + "/lib" + ekf_name + dylib_ext; + void* handle = dlopen(ekf_path.c_str(), RTLD_NOW); + assert(handle); + void* (*ekf_get)() = (void*(*)())dlsym(handle, "ekf_get"); + assert(ekf_get != NULL); + const EKF* ekf = (const EKF*)ekf_get(); + ekf_register(ekf); +} diff --git a/rednose/helpers/ekf_load.h b/rednose/helpers/ekf_load.h new file mode 100644 index 0000000..89180b8 --- /dev/null +++ b/rednose/helpers/ekf_load.h @@ -0,0 +1,9 @@ +#include +#include + +#include "ekf.h" + +std::vector& ekf_get_all(); +const EKF* ekf_lookup(const std::string& ekf_name); +void ekf_register(const EKF* ekf); +void ekf_load_and_register(const std::string& ekf_directory, const std::string& ekf_name); diff --git a/rednose/helpers/ekf_sym.cc b/rednose/helpers/ekf_sym.cc new file mode 100644 index 0000000..38d419d --- /dev/null +++ b/rednose/helpers/ekf_sym.cc @@ -0,0 +1,223 @@ +#include "ekf_sym.h" +#include "logger/logger.h" + +using namespace EKFS; +using namespace Eigen; + +EKFSym::EKFSym(std::string name, Map Q, Map x_initial, Map P_initial, int dim_main, + int dim_main_err, int N, int dim_augment, int dim_augment_err, std::vector maha_test_kinds, + std::vector quaternion_idxs, std::vector global_vars, double max_rewind_age) +{ + // TODO: add logger + this->ekf = ekf_lookup(name); + assert(this->ekf); + + this->msckf = N > 0; + this->N = N; + this->dim_augment = dim_augment; + this->dim_augment_err = dim_augment_err; + this->dim_main = dim_main; + this->dim_main_err = dim_main_err; + + this->dim_x = x_initial.rows(); + this->dim_err = P_initial.rows(); + + assert(dim_main + dim_augment * N == dim_x); + assert(dim_main_err + dim_augment_err * N == this->dim_err); + assert(Q.rows() == P_initial.rows() && Q.cols() == P_initial.cols()); + + // kinds that should get mahalanobis distance + // tested for outlier rejection + this->maha_test_kinds = maha_test_kinds; + + // quaternions need normalization + this->quaternion_idxs = quaternion_idxs; + + this->global_vars = global_vars; + + // Process noise + this->Q = Q; + + this->max_rewind_age = max_rewind_age; + this->init_state(x_initial, P_initial, NAN); +} + +void EKFSym::init_state(Map state, Map covs, double init_filter_time) { + this->x = state; + this->P = covs; + this->filter_time = init_filter_time; + this->augment_times = VectorXd::Zero(this->N); + this->reset_rewind(); +} + +VectorXd EKFSym::state() { + return this->x; +} + +MatrixXdr EKFSym::covs() { + return this->P; +} + +void EKFSym::set_filter_time(double t) { + this->filter_time = t; +} + +double EKFSym::get_filter_time() { + return this->filter_time; +} + +void EKFSym::normalize_quaternions() { + for(std::size_t i = 0; i < this->quaternion_idxs.size(); ++i) { + this->normalize_slice(this->quaternion_idxs[i], this->quaternion_idxs[i] + 4); + } +} + +void EKFSym::normalize_slice(int slice_start, int slice_end_ex) { + this->x.block(slice_start, 0, slice_end_ex - slice_start, this->x.cols()).normalize(); +} + +void EKFSym::set_global(std::string global_var, double val) { + this->ekf->sets.at(global_var)(val); +} + +std::optional EKFSym::predict_and_update_batch(double t, int kind, std::vector> z_map, + std::vector> R_map, std::vector> extra_args, bool augment) +{ + // TODO handle rewinding at this level + + std::deque rewound; + if (!std::isnan(this->filter_time) && t < this->filter_time) { + if (this->rewind_t.empty() || t < this->rewind_t.front() || t < this->rewind_t.back() - this->max_rewind_age) { + LOGD("observation too old at %f with filter at %f, ignoring!", t, this->filter_time); + return std::nullopt; + } + rewound = this->rewind(t); + } + + Observation obs; + obs.t = t; + obs.kind = kind; + obs.extra_args = extra_args; + for (Map zi : z_map) { + obs.z.push_back(zi); + } + for (Map Ri : R_map) { + obs.R.push_back(Ri); + } + + std::optional res = std::make_optional(this->predict_and_update_batch(obs, augment)); + + // optional fast forward + while (!rewound.empty()) { + this->predict_and_update_batch(rewound.front(), false); + rewound.pop_front(); + } + + return res; +} + +void EKFSym::reset_rewind() { + this->rewind_obscache.clear(); + this->rewind_t.clear(); + this->rewind_states.clear(); +} + +std::deque EKFSym::rewind(double t) { + std::deque rewound; + + // rewind observations until t is after previous observation + while (this->rewind_t.back() > t) { + rewound.push_front(this->rewind_obscache.back()); + this->rewind_t.pop_back(); + this->rewind_states.pop_back(); + this->rewind_obscache.pop_back(); + } + + // set the state to the time right before that + this->filter_time = this->rewind_t.back(); + this->x = this->rewind_states.back().first; + this->P = this->rewind_states.back().second; + + return rewound; +} + +void EKFSym::checkpoint(Observation& obs) { + // push to rewinder + this->rewind_t.push_back(this->filter_time); + this->rewind_states.push_back(std::make_pair(this->x, this->P)); + this->rewind_obscache.push_back(obs); + + // only keep a certain number around + if (this->rewind_t.size() > REWIND_TO_KEEP) { + this->rewind_t.pop_front(); + this->rewind_states.pop_front(); + this->rewind_obscache.pop_front(); + } +} + +Estimate EKFSym::predict_and_update_batch(Observation& obs, bool augment) { + assert(obs.z.size() == obs.R.size()); + assert(obs.z.size() == obs.extra_args.size()); + + this->predict(obs.t); + + Estimate res; + res.t = obs.t; + res.kind = obs.kind; + res.z = obs.z; + res.extra_args = obs.extra_args; + res.xk1 = this->x; + res.Pk1 = this->P; + + // update batch + std::vector y; + for (int i = 0; i < obs.z.size(); i++) { + assert(obs.z[i].rows() == obs.R[i].rows()); + assert(obs.z[i].rows() == obs.R[i].cols()); + + // update state + y.push_back(this->update(obs.kind, obs.z[i], obs.R[i], obs.extra_args[i])); + } + + res.xk = this->x; + res.Pk = this->P; + res.y = y; + + assert(!augment); // TODO + // if (augment) { + // this->augment(); + // } + + this->checkpoint(obs); + + return res; +} + +void EKFSym::predict(double t) { + // initialize time + if (std::isnan(this->filter_time)) { + this->filter_time = t; + } + + // predict + double dt = t - this->filter_time; + assert(dt >= 0.0); + + this->ekf->predict(this->x.data(), this->P.data(), this->Q.data(), dt); + this->normalize_quaternions(); + this->filter_time = t; +} + +VectorXd EKFSym::update(int kind, VectorXd z, MatrixXdr R, std::vector extra_args) { + this->ekf->updates.at(kind)(this->x.data(), this->P.data(), z.data(), R.data(), extra_args.data()); + this->normalize_quaternions(); + + if (this->msckf && std::find(this->feature_track_kinds.begin(), this->feature_track_kinds.end(), kind) != this->feature_track_kinds.end()) { + return z.head(z.rows() - extra_args.size()); + } + return z; +} + +extra_routine_t EKFSym::get_extra_routine(const std::string& routine) { + return this->ekf->extra_routines.at(routine); +} diff --git a/rednose/helpers/ekf_sym.h b/rednose/helpers/ekf_sym.h new file mode 100644 index 0000000..b83d7f3 --- /dev/null +++ b/rednose/helpers/ekf_sym.h @@ -0,0 +1,113 @@ +#pragma once + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +#include "ekf.h" +#include "ekf_load.h" + +#define REWIND_TO_KEEP 512 + +namespace EKFS { + +typedef Eigen::Matrix MatrixXdr; + +typedef struct Observation { + double t; + int kind; + std::vector z; + std::vector R; + std::vector> extra_args; +} Observation; + +typedef struct Estimate { + Eigen::VectorXd xk1; + Eigen::VectorXd xk; + MatrixXdr Pk1; + MatrixXdr Pk; + double t; + int kind; + std::vector y; + std::vector z; + std::vector> extra_args; +} Estimate; + +class EKFSym { +public: + EKFSym(std::string name, Eigen::Map Q, Eigen::Map x_initial, + Eigen::Map P_initial, int dim_main, int dim_main_err, int N = 0, int dim_augment = 0, + int dim_augment_err = 0, std::vector maha_test_kinds = std::vector(), + std::vector quaternion_idxs = std::vector(), + std::vector global_vars = std::vector(), double max_rewind_age = 1.0); + void init_state(Eigen::Map state, Eigen::Map covs, double filter_time); + + Eigen::VectorXd state(); + MatrixXdr covs(); + void set_filter_time(double t); + double get_filter_time(); + void normalize_quaternions(); + void normalize_slice(int slice_start, int slice_end_ex); + void set_global(std::string global_var, double val); + void reset_rewind(); + + void predict(double t); + std::optional predict_and_update_batch(double t, int kind, std::vector> z, + std::vector> R, std::vector> extra_args = {{}}, bool augment = false); + + extra_routine_t get_extra_routine(const std::string& routine); + +private: + std::deque rewind(double t); + void checkpoint(Observation& obs); + + Estimate predict_and_update_batch(Observation& obs, bool augment); + Eigen::VectorXd update(int kind, Eigen::VectorXd z, MatrixXdr R, std::vector extra_args); + + // stuct with linked sympy generated functions + const EKF *ekf = NULL; + + Eigen::VectorXd x; // state + MatrixXdr P; // covs + + bool msckf; + int N; + int dim_augment; + int dim_augment_err; + int dim_main; + int dim_main_err; + + // state + int dim_x; + int dim_err; + + double filter_time; + + std::vector maha_test_kinds; + std::vector quaternion_idxs; + + std::vector global_vars; + + // process noise + MatrixXdr Q; + + // rewind stuff + double max_rewind_age; + std::deque rewind_t; + std::deque> rewind_states; + std::deque rewind_obscache; + + Eigen::VectorXd augment_times; + + std::vector feature_track_kinds; +}; + +} diff --git a/rednose/helpers/ekf_sym.py b/rednose/helpers/ekf_sym.py index 8f0425c..e8bd642 100644 --- a/rednose/helpers/ekf_sym.py +++ b/rednose/helpers/ekf_sym.py @@ -464,7 +464,7 @@ class EKF_sym(): # rewind if self.filter_time is not None and t < self.filter_time: if len(self.rewind_t) == 0 or t < self.rewind_t[0] or t < self.rewind_t[-1] - self.max_rewind_age: - self.logger.error("observation too old at %.3f with filter at %.3f, ignoring" % (t, self.filter_time)) + self.logger.error(f"observation too old at {t:.3f} with filter at {self.filter_time:.3f}, ignoring") return None rewound = self.rewind(t) else: diff --git a/rednose/helpers/ekf_sym_pyx.cpp b/rednose/helpers/ekf_sym_pyx.cpp deleted file mode 100644 index de77e6b..0000000 --- a/rednose/helpers/ekf_sym_pyx.cpp +++ /dev/null @@ -1,35816 +0,0 @@ -/* Generated by Cython 3.0.8 */ - -/* BEGIN: Cython Metadata -{ - "distutils": { - "depends": [ - "rednose/helpers/ekf_load.h", - "rednose/helpers/ekf_sym.h" - ], - "language": "c++", - "name": "rednose.helpers.ekf_sym_pyx", - "sources": [ - "/data/openpilot/rednose/helpers/ekf_sym_pyx.pyx" - ] - }, - "module_name": "rednose.helpers.ekf_sym_pyx" -} -END: Cython Metadata */ - -#ifndef PY_SSIZE_T_CLEAN -#define PY_SSIZE_T_CLEAN -#endif /* PY_SSIZE_T_CLEAN */ -#if defined(CYTHON_LIMITED_API) && 0 - #ifndef Py_LIMITED_API - #if CYTHON_LIMITED_API+0 > 0x03030000 - #define Py_LIMITED_API CYTHON_LIMITED_API - #else - #define Py_LIMITED_API 0x03030000 - #endif - #endif -#endif - -#include "Python.h" -#ifndef Py_PYTHON_H - #error Python headers needed to compile C extensions, please install development version of Python. -#elif PY_VERSION_HEX < 0x02070000 || (0x03000000 <= PY_VERSION_HEX && PY_VERSION_HEX < 0x03030000) - #error Cython requires Python 2.7+ or Python 3.3+. -#else -#if defined(CYTHON_LIMITED_API) && CYTHON_LIMITED_API -#define __PYX_EXTRA_ABI_MODULE_NAME "limited" -#else -#define __PYX_EXTRA_ABI_MODULE_NAME "" -#endif -#define CYTHON_ABI "3_0_8" __PYX_EXTRA_ABI_MODULE_NAME -#define __PYX_ABI_MODULE_NAME "_cython_" CYTHON_ABI -#define __PYX_TYPE_MODULE_PREFIX __PYX_ABI_MODULE_NAME "." -#define CYTHON_HEX_VERSION 0x030008F0 -#define CYTHON_FUTURE_DIVISION 1 -#include -#ifndef offsetof - #define offsetof(type, member) ( (size_t) & ((type*)0) -> member ) -#endif -#if !defined(_WIN32) && !defined(WIN32) && !defined(MS_WINDOWS) - #ifndef __stdcall - #define __stdcall - #endif - #ifndef __cdecl - #define __cdecl - #endif - #ifndef __fastcall - #define __fastcall - #endif -#endif -#ifndef DL_IMPORT - #define DL_IMPORT(t) t -#endif -#ifndef DL_EXPORT - #define DL_EXPORT(t) t -#endif -#define __PYX_COMMA , -#ifndef HAVE_LONG_LONG - #define HAVE_LONG_LONG -#endif -#ifndef PY_LONG_LONG - #define PY_LONG_LONG LONG_LONG -#endif -#ifndef Py_HUGE_VAL - #define Py_HUGE_VAL HUGE_VAL -#endif -#define __PYX_LIMITED_VERSION_HEX PY_VERSION_HEX -#if defined(GRAALVM_PYTHON) - /* For very preliminary testing purposes. Most variables are set the same as PyPy. - The existence of this section does not imply that anything works or is even tested */ - #define CYTHON_COMPILING_IN_PYPY 0 - #define CYTHON_COMPILING_IN_CPYTHON 0 - #define CYTHON_COMPILING_IN_LIMITED_API 0 - #define CYTHON_COMPILING_IN_GRAAL 1 - #define CYTHON_COMPILING_IN_NOGIL 0 - #undef CYTHON_USE_TYPE_SLOTS - #define CYTHON_USE_TYPE_SLOTS 0 - #undef CYTHON_USE_TYPE_SPECS - #define CYTHON_USE_TYPE_SPECS 0 - #undef CYTHON_USE_PYTYPE_LOOKUP - #define CYTHON_USE_PYTYPE_LOOKUP 0 - #if PY_VERSION_HEX < 0x03050000 - #undef CYTHON_USE_ASYNC_SLOTS - #define CYTHON_USE_ASYNC_SLOTS 0 - #elif !defined(CYTHON_USE_ASYNC_SLOTS) - #define CYTHON_USE_ASYNC_SLOTS 1 - #endif - #undef CYTHON_USE_PYLIST_INTERNALS - #define CYTHON_USE_PYLIST_INTERNALS 0 - #undef CYTHON_USE_UNICODE_INTERNALS - #define CYTHON_USE_UNICODE_INTERNALS 0 - #undef CYTHON_USE_UNICODE_WRITER - #define CYTHON_USE_UNICODE_WRITER 0 - #undef CYTHON_USE_PYLONG_INTERNALS - #define CYTHON_USE_PYLONG_INTERNALS 0 - #undef CYTHON_AVOID_BORROWED_REFS - #define CYTHON_AVOID_BORROWED_REFS 1 - #undef CYTHON_ASSUME_SAFE_MACROS - #define CYTHON_ASSUME_SAFE_MACROS 0 - #undef CYTHON_UNPACK_METHODS - #define CYTHON_UNPACK_METHODS 0 - #undef CYTHON_FAST_THREAD_STATE - #define CYTHON_FAST_THREAD_STATE 0 - #undef CYTHON_FAST_GIL - #define CYTHON_FAST_GIL 0 - #undef CYTHON_METH_FASTCALL - #define CYTHON_METH_FASTCALL 0 - #undef CYTHON_FAST_PYCALL - #define CYTHON_FAST_PYCALL 0 - #ifndef CYTHON_PEP487_INIT_SUBCLASS - #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) - #endif - #undef CYTHON_PEP489_MULTI_PHASE_INIT - #define CYTHON_PEP489_MULTI_PHASE_INIT 1 - #undef CYTHON_USE_MODULE_STATE - #define CYTHON_USE_MODULE_STATE 0 - #undef CYTHON_USE_TP_FINALIZE - #define CYTHON_USE_TP_FINALIZE 0 - #undef CYTHON_USE_DICT_VERSIONS - #define CYTHON_USE_DICT_VERSIONS 0 - #undef CYTHON_USE_EXC_INFO_STACK - #define CYTHON_USE_EXC_INFO_STACK 0 - #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC - #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 - #endif -#elif defined(PYPY_VERSION) - #define CYTHON_COMPILING_IN_PYPY 1 - #define CYTHON_COMPILING_IN_CPYTHON 0 - #define CYTHON_COMPILING_IN_LIMITED_API 0 - #define CYTHON_COMPILING_IN_GRAAL 0 - #define CYTHON_COMPILING_IN_NOGIL 0 - #undef CYTHON_USE_TYPE_SLOTS - #define CYTHON_USE_TYPE_SLOTS 0 - #ifndef CYTHON_USE_TYPE_SPECS - #define CYTHON_USE_TYPE_SPECS 0 - #endif - #undef CYTHON_USE_PYTYPE_LOOKUP - #define CYTHON_USE_PYTYPE_LOOKUP 0 - #if PY_VERSION_HEX < 0x03050000 - #undef CYTHON_USE_ASYNC_SLOTS - #define CYTHON_USE_ASYNC_SLOTS 0 - #elif !defined(CYTHON_USE_ASYNC_SLOTS) - #define CYTHON_USE_ASYNC_SLOTS 1 - #endif - #undef CYTHON_USE_PYLIST_INTERNALS - #define CYTHON_USE_PYLIST_INTERNALS 0 - #undef CYTHON_USE_UNICODE_INTERNALS - #define CYTHON_USE_UNICODE_INTERNALS 0 - #undef CYTHON_USE_UNICODE_WRITER - #define CYTHON_USE_UNICODE_WRITER 0 - #undef CYTHON_USE_PYLONG_INTERNALS - #define CYTHON_USE_PYLONG_INTERNALS 0 - #undef CYTHON_AVOID_BORROWED_REFS - #define CYTHON_AVOID_BORROWED_REFS 1 - #undef CYTHON_ASSUME_SAFE_MACROS - #define CYTHON_ASSUME_SAFE_MACROS 0 - #undef CYTHON_UNPACK_METHODS - #define CYTHON_UNPACK_METHODS 0 - #undef CYTHON_FAST_THREAD_STATE - #define CYTHON_FAST_THREAD_STATE 0 - #undef CYTHON_FAST_GIL - #define CYTHON_FAST_GIL 0 - #undef CYTHON_METH_FASTCALL - #define CYTHON_METH_FASTCALL 0 - #undef CYTHON_FAST_PYCALL - #define CYTHON_FAST_PYCALL 0 - #ifndef CYTHON_PEP487_INIT_SUBCLASS - #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) - #endif - #if PY_VERSION_HEX < 0x03090000 - #undef CYTHON_PEP489_MULTI_PHASE_INIT - #define CYTHON_PEP489_MULTI_PHASE_INIT 0 - #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) - #define CYTHON_PEP489_MULTI_PHASE_INIT 1 - #endif - #undef CYTHON_USE_MODULE_STATE - #define CYTHON_USE_MODULE_STATE 0 - #undef CYTHON_USE_TP_FINALIZE - #define CYTHON_USE_TP_FINALIZE (PY_VERSION_HEX >= 0x030400a1 && PYPY_VERSION_NUM >= 0x07030C00) - #undef CYTHON_USE_DICT_VERSIONS - #define CYTHON_USE_DICT_VERSIONS 0 - #undef CYTHON_USE_EXC_INFO_STACK - #define CYTHON_USE_EXC_INFO_STACK 0 - #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC - #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 - #endif -#elif defined(CYTHON_LIMITED_API) - #ifdef Py_LIMITED_API - #undef __PYX_LIMITED_VERSION_HEX - #define __PYX_LIMITED_VERSION_HEX Py_LIMITED_API - #endif - #define CYTHON_COMPILING_IN_PYPY 0 - #define CYTHON_COMPILING_IN_CPYTHON 0 - #define CYTHON_COMPILING_IN_LIMITED_API 1 - #define CYTHON_COMPILING_IN_GRAAL 0 - #define CYTHON_COMPILING_IN_NOGIL 0 - #undef CYTHON_CLINE_IN_TRACEBACK - #define CYTHON_CLINE_IN_TRACEBACK 0 - #undef CYTHON_USE_TYPE_SLOTS - #define CYTHON_USE_TYPE_SLOTS 0 - #undef CYTHON_USE_TYPE_SPECS - #define CYTHON_USE_TYPE_SPECS 1 - #undef CYTHON_USE_PYTYPE_LOOKUP - #define CYTHON_USE_PYTYPE_LOOKUP 0 - #undef CYTHON_USE_ASYNC_SLOTS - #define CYTHON_USE_ASYNC_SLOTS 0 - #undef CYTHON_USE_PYLIST_INTERNALS - #define CYTHON_USE_PYLIST_INTERNALS 0 - #undef CYTHON_USE_UNICODE_INTERNALS - #define CYTHON_USE_UNICODE_INTERNALS 0 - #ifndef CYTHON_USE_UNICODE_WRITER - #define CYTHON_USE_UNICODE_WRITER 0 - #endif - #undef CYTHON_USE_PYLONG_INTERNALS - #define CYTHON_USE_PYLONG_INTERNALS 0 - #ifndef CYTHON_AVOID_BORROWED_REFS - #define CYTHON_AVOID_BORROWED_REFS 0 - #endif - #undef CYTHON_ASSUME_SAFE_MACROS - #define CYTHON_ASSUME_SAFE_MACROS 0 - #undef CYTHON_UNPACK_METHODS - #define CYTHON_UNPACK_METHODS 0 - #undef CYTHON_FAST_THREAD_STATE - #define CYTHON_FAST_THREAD_STATE 0 - #undef CYTHON_FAST_GIL - #define CYTHON_FAST_GIL 0 - #undef CYTHON_METH_FASTCALL - #define CYTHON_METH_FASTCALL 0 - #undef CYTHON_FAST_PYCALL - #define CYTHON_FAST_PYCALL 0 - #ifndef CYTHON_PEP487_INIT_SUBCLASS - #define CYTHON_PEP487_INIT_SUBCLASS 1 - #endif - #undef CYTHON_PEP489_MULTI_PHASE_INIT - #define CYTHON_PEP489_MULTI_PHASE_INIT 0 - #undef CYTHON_USE_MODULE_STATE - #define CYTHON_USE_MODULE_STATE 1 - #ifndef CYTHON_USE_TP_FINALIZE - #define CYTHON_USE_TP_FINALIZE 0 - #endif - #undef CYTHON_USE_DICT_VERSIONS - #define CYTHON_USE_DICT_VERSIONS 0 - #undef CYTHON_USE_EXC_INFO_STACK - #define CYTHON_USE_EXC_INFO_STACK 0 - #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC - #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 - #endif -#elif defined(Py_GIL_DISABLED) || defined(Py_NOGIL) - #define CYTHON_COMPILING_IN_PYPY 0 - #define CYTHON_COMPILING_IN_CPYTHON 0 - #define CYTHON_COMPILING_IN_LIMITED_API 0 - #define CYTHON_COMPILING_IN_GRAAL 0 - #define CYTHON_COMPILING_IN_NOGIL 1 - #ifndef CYTHON_USE_TYPE_SLOTS - #define CYTHON_USE_TYPE_SLOTS 1 - #endif - #undef CYTHON_USE_PYTYPE_LOOKUP - #define CYTHON_USE_PYTYPE_LOOKUP 0 - #ifndef CYTHON_USE_ASYNC_SLOTS - #define CYTHON_USE_ASYNC_SLOTS 1 - #endif - #undef CYTHON_USE_PYLIST_INTERNALS - #define CYTHON_USE_PYLIST_INTERNALS 0 - #ifndef CYTHON_USE_UNICODE_INTERNALS - #define CYTHON_USE_UNICODE_INTERNALS 1 - #endif - #undef CYTHON_USE_UNICODE_WRITER - #define CYTHON_USE_UNICODE_WRITER 0 - #undef CYTHON_USE_PYLONG_INTERNALS - #define CYTHON_USE_PYLONG_INTERNALS 0 - #ifndef CYTHON_AVOID_BORROWED_REFS - #define CYTHON_AVOID_BORROWED_REFS 0 - #endif - #ifndef CYTHON_ASSUME_SAFE_MACROS - #define CYTHON_ASSUME_SAFE_MACROS 1 - #endif - #ifndef CYTHON_UNPACK_METHODS - #define CYTHON_UNPACK_METHODS 1 - #endif - #undef CYTHON_FAST_THREAD_STATE - #define CYTHON_FAST_THREAD_STATE 0 - #undef CYTHON_FAST_PYCALL - #define CYTHON_FAST_PYCALL 0 - #ifndef CYTHON_PEP489_MULTI_PHASE_INIT - #define CYTHON_PEP489_MULTI_PHASE_INIT 1 - #endif - #ifndef CYTHON_USE_TP_FINALIZE - #define CYTHON_USE_TP_FINALIZE 1 - #endif - #undef CYTHON_USE_DICT_VERSIONS - #define CYTHON_USE_DICT_VERSIONS 0 - #undef CYTHON_USE_EXC_INFO_STACK - #define CYTHON_USE_EXC_INFO_STACK 0 -#else - #define CYTHON_COMPILING_IN_PYPY 0 - #define CYTHON_COMPILING_IN_CPYTHON 1 - #define CYTHON_COMPILING_IN_LIMITED_API 0 - #define CYTHON_COMPILING_IN_GRAAL 0 - #define CYTHON_COMPILING_IN_NOGIL 0 - #ifndef CYTHON_USE_TYPE_SLOTS - #define CYTHON_USE_TYPE_SLOTS 1 - #endif - #ifndef CYTHON_USE_TYPE_SPECS - #define CYTHON_USE_TYPE_SPECS 0 - #endif - #ifndef CYTHON_USE_PYTYPE_LOOKUP - #define CYTHON_USE_PYTYPE_LOOKUP 1 - #endif - #if PY_MAJOR_VERSION < 3 - #undef CYTHON_USE_ASYNC_SLOTS - #define CYTHON_USE_ASYNC_SLOTS 0 - #elif !defined(CYTHON_USE_ASYNC_SLOTS) - #define CYTHON_USE_ASYNC_SLOTS 1 - #endif - #ifndef CYTHON_USE_PYLONG_INTERNALS - #define CYTHON_USE_PYLONG_INTERNALS 1 - #endif - #ifndef CYTHON_USE_PYLIST_INTERNALS - #define CYTHON_USE_PYLIST_INTERNALS 1 - #endif - #ifndef CYTHON_USE_UNICODE_INTERNALS - #define CYTHON_USE_UNICODE_INTERNALS 1 - #endif - #if PY_VERSION_HEX < 0x030300F0 || PY_VERSION_HEX >= 0x030B00A2 - #undef CYTHON_USE_UNICODE_WRITER - #define CYTHON_USE_UNICODE_WRITER 0 - #elif !defined(CYTHON_USE_UNICODE_WRITER) - #define CYTHON_USE_UNICODE_WRITER 1 - #endif - #ifndef CYTHON_AVOID_BORROWED_REFS - #define CYTHON_AVOID_BORROWED_REFS 0 - #endif - #ifndef CYTHON_ASSUME_SAFE_MACROS - #define CYTHON_ASSUME_SAFE_MACROS 1 - #endif - #ifndef CYTHON_UNPACK_METHODS - #define CYTHON_UNPACK_METHODS 1 - #endif - #ifndef CYTHON_FAST_THREAD_STATE - #define CYTHON_FAST_THREAD_STATE 1 - #endif - #ifndef CYTHON_FAST_GIL - #define CYTHON_FAST_GIL (PY_MAJOR_VERSION < 3 || PY_VERSION_HEX >= 0x03060000 && PY_VERSION_HEX < 0x030C00A6) - #endif - #ifndef CYTHON_METH_FASTCALL - #define CYTHON_METH_FASTCALL (PY_VERSION_HEX >= 0x030700A1) - #endif - #ifndef CYTHON_FAST_PYCALL - #define CYTHON_FAST_PYCALL 1 - #endif - #ifndef CYTHON_PEP487_INIT_SUBCLASS - #define CYTHON_PEP487_INIT_SUBCLASS 1 - #endif - #if PY_VERSION_HEX < 0x03050000 - #undef CYTHON_PEP489_MULTI_PHASE_INIT - #define CYTHON_PEP489_MULTI_PHASE_INIT 0 - #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) - #define CYTHON_PEP489_MULTI_PHASE_INIT 1 - #endif - #ifndef CYTHON_USE_MODULE_STATE - #define CYTHON_USE_MODULE_STATE 0 - #endif - #if PY_VERSION_HEX < 0x030400a1 - #undef CYTHON_USE_TP_FINALIZE - #define CYTHON_USE_TP_FINALIZE 0 - #elif !defined(CYTHON_USE_TP_FINALIZE) - #define CYTHON_USE_TP_FINALIZE 1 - #endif - #if PY_VERSION_HEX < 0x030600B1 - #undef CYTHON_USE_DICT_VERSIONS - #define CYTHON_USE_DICT_VERSIONS 0 - #elif !defined(CYTHON_USE_DICT_VERSIONS) - #define CYTHON_USE_DICT_VERSIONS (PY_VERSION_HEX < 0x030C00A5) - #endif - #if PY_VERSION_HEX < 0x030700A3 - #undef CYTHON_USE_EXC_INFO_STACK - #define CYTHON_USE_EXC_INFO_STACK 0 - #elif !defined(CYTHON_USE_EXC_INFO_STACK) - #define CYTHON_USE_EXC_INFO_STACK 1 - #endif - #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC - #define CYTHON_UPDATE_DESCRIPTOR_DOC 1 - #endif -#endif -#if !defined(CYTHON_FAST_PYCCALL) -#define CYTHON_FAST_PYCCALL (CYTHON_FAST_PYCALL && PY_VERSION_HEX >= 0x030600B1) -#endif -#if !defined(CYTHON_VECTORCALL) -#define CYTHON_VECTORCALL (CYTHON_FAST_PYCCALL && PY_VERSION_HEX >= 0x030800B1) -#endif -#define CYTHON_BACKPORT_VECTORCALL (CYTHON_METH_FASTCALL && PY_VERSION_HEX < 0x030800B1) -#if CYTHON_USE_PYLONG_INTERNALS - #if PY_MAJOR_VERSION < 3 - #include "longintrepr.h" - #endif - #undef SHIFT - #undef BASE - #undef MASK - #ifdef SIZEOF_VOID_P - enum { __pyx_check_sizeof_voidp = 1 / (int)(SIZEOF_VOID_P == sizeof(void*)) }; - #endif -#endif -#ifndef __has_attribute - #define __has_attribute(x) 0 -#endif -#ifndef __has_cpp_attribute - #define __has_cpp_attribute(x) 0 -#endif -#ifndef CYTHON_RESTRICT - #if defined(__GNUC__) - #define CYTHON_RESTRICT __restrict__ - #elif defined(_MSC_VER) && _MSC_VER >= 1400 - #define CYTHON_RESTRICT __restrict - #elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L - #define CYTHON_RESTRICT restrict - #else - #define CYTHON_RESTRICT - #endif -#endif -#ifndef CYTHON_UNUSED - #if defined(__cplusplus) - /* for clang __has_cpp_attribute(maybe_unused) is true even before C++17 - * but leads to warnings with -pedantic, since it is a C++17 feature */ - #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) - #if __has_cpp_attribute(maybe_unused) - #define CYTHON_UNUSED [[maybe_unused]] - #endif - #endif - #endif -#endif -#ifndef CYTHON_UNUSED -# if defined(__GNUC__) -# if !(defined(__cplusplus)) || (__GNUC__ > 3 || (__GNUC__ == 3 && __GNUC_MINOR__ >= 4)) -# define CYTHON_UNUSED __attribute__ ((__unused__)) -# else -# define CYTHON_UNUSED -# endif -# elif defined(__ICC) || (defined(__INTEL_COMPILER) && !defined(_MSC_VER)) -# define CYTHON_UNUSED __attribute__ ((__unused__)) -# else -# define CYTHON_UNUSED -# endif -#endif -#ifndef CYTHON_UNUSED_VAR -# if defined(__cplusplus) - template void CYTHON_UNUSED_VAR( const T& ) { } -# else -# define CYTHON_UNUSED_VAR(x) (void)(x) -# endif -#endif -#ifndef CYTHON_MAYBE_UNUSED_VAR - #define CYTHON_MAYBE_UNUSED_VAR(x) CYTHON_UNUSED_VAR(x) -#endif -#ifndef CYTHON_NCP_UNUSED -# if CYTHON_COMPILING_IN_CPYTHON -# define CYTHON_NCP_UNUSED -# else -# define CYTHON_NCP_UNUSED CYTHON_UNUSED -# endif -#endif -#ifndef CYTHON_USE_CPP_STD_MOVE - #if defined(__cplusplus) && (\ - __cplusplus >= 201103L || (defined(_MSC_VER) && _MSC_VER >= 1600)) - #define CYTHON_USE_CPP_STD_MOVE 1 - #else - #define CYTHON_USE_CPP_STD_MOVE 0 - #endif -#endif -#define __Pyx_void_to_None(void_result) ((void)(void_result), Py_INCREF(Py_None), Py_None) -#ifdef _MSC_VER - #ifndef _MSC_STDINT_H_ - #if _MSC_VER < 1300 - typedef unsigned char uint8_t; - typedef unsigned short uint16_t; - typedef unsigned int uint32_t; - #else - typedef unsigned __int8 uint8_t; - typedef unsigned __int16 uint16_t; - typedef unsigned __int32 uint32_t; - #endif - #endif - #if _MSC_VER < 1300 - #ifdef _WIN64 - typedef unsigned long long __pyx_uintptr_t; - #else - typedef unsigned int __pyx_uintptr_t; - #endif - #else - #ifdef _WIN64 - typedef unsigned __int64 __pyx_uintptr_t; - #else - typedef unsigned __int32 __pyx_uintptr_t; - #endif - #endif -#else - #include - typedef uintptr_t __pyx_uintptr_t; -#endif -#ifndef CYTHON_FALLTHROUGH - #if defined(__cplusplus) - /* for clang __has_cpp_attribute(fallthrough) is true even before C++17 - * but leads to warnings with -pedantic, since it is a C++17 feature */ - #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) - #if __has_cpp_attribute(fallthrough) - #define CYTHON_FALLTHROUGH [[fallthrough]] - #endif - #endif - #ifndef CYTHON_FALLTHROUGH - #if __has_cpp_attribute(clang::fallthrough) - #define CYTHON_FALLTHROUGH [[clang::fallthrough]] - #elif __has_cpp_attribute(gnu::fallthrough) - #define CYTHON_FALLTHROUGH [[gnu::fallthrough]] - #endif - #endif - #endif - #ifndef CYTHON_FALLTHROUGH - #if __has_attribute(fallthrough) - #define CYTHON_FALLTHROUGH __attribute__((fallthrough)) - #else - #define CYTHON_FALLTHROUGH - #endif - #endif - #if defined(__clang__) && defined(__apple_build_version__) - #if __apple_build_version__ < 7000000 - #undef CYTHON_FALLTHROUGH - #define CYTHON_FALLTHROUGH - #endif - #endif -#endif -#ifdef __cplusplus - template - struct __PYX_IS_UNSIGNED_IMPL {static const bool value = T(0) < T(-1);}; - #define __PYX_IS_UNSIGNED(type) (__PYX_IS_UNSIGNED_IMPL::value) -#else - #define __PYX_IS_UNSIGNED(type) (((type)-1) > 0) -#endif -#if CYTHON_COMPILING_IN_PYPY == 1 - #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x030A0000) -#else - #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x03090000) -#endif -#define __PYX_REINTERPRET_FUNCION(func_pointer, other_pointer) ((func_pointer)(void(*)(void))(other_pointer)) - -#ifndef __cplusplus - #error "Cython files generated with the C++ option must be compiled with a C++ compiler." -#endif -#ifndef CYTHON_INLINE - #if defined(__clang__) - #define CYTHON_INLINE __inline__ __attribute__ ((__unused__)) - #else - #define CYTHON_INLINE inline - #endif -#endif -template -void __Pyx_call_destructor(T& x) { - x.~T(); -} -template -class __Pyx_FakeReference { - public: - __Pyx_FakeReference() : ptr(NULL) { } - __Pyx_FakeReference(const T& ref) : ptr(const_cast(&ref)) { } - T *operator->() { return ptr; } - T *operator&() { return ptr; } - operator T&() { return *ptr; } - template bool operator ==(const U& other) const { return *ptr == other; } - template bool operator !=(const U& other) const { return *ptr != other; } - template bool operator==(const __Pyx_FakeReference& other) const { return *ptr == *other.ptr; } - template bool operator!=(const __Pyx_FakeReference& other) const { return *ptr != *other.ptr; } - private: - T *ptr; -}; - -#define __PYX_BUILD_PY_SSIZE_T "n" -#define CYTHON_FORMAT_SSIZE_T "z" -#if PY_MAJOR_VERSION < 3 - #define __Pyx_BUILTIN_MODULE_NAME "__builtin__" - #define __Pyx_DefaultClassType PyClass_Type - #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ - PyCode_New(a+k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) -#else - #define __Pyx_BUILTIN_MODULE_NAME "builtins" - #define __Pyx_DefaultClassType PyType_Type -#if CYTHON_COMPILING_IN_LIMITED_API - static CYTHON_INLINE PyObject* __Pyx_PyCode_New(int a, int p, int k, int l, int s, int f, - PyObject *code, PyObject *c, PyObject* n, PyObject *v, - PyObject *fv, PyObject *cell, PyObject* fn, - PyObject *name, int fline, PyObject *lnos) { - PyObject *exception_table = NULL; - PyObject *types_module=NULL, *code_type=NULL, *result=NULL; - #if __PYX_LIMITED_VERSION_HEX < 0x030B0000 - PyObject *version_info; - PyObject *py_minor_version = NULL; - #endif - long minor_version = 0; - PyObject *type, *value, *traceback; - PyErr_Fetch(&type, &value, &traceback); - #if __PYX_LIMITED_VERSION_HEX >= 0x030B0000 - minor_version = 11; - #else - if (!(version_info = PySys_GetObject("version_info"))) goto end; - if (!(py_minor_version = PySequence_GetItem(version_info, 1))) goto end; - minor_version = PyLong_AsLong(py_minor_version); - Py_DECREF(py_minor_version); - if (minor_version == -1 && PyErr_Occurred()) goto end; - #endif - if (!(types_module = PyImport_ImportModule("types"))) goto end; - if (!(code_type = PyObject_GetAttrString(types_module, "CodeType"))) goto end; - if (minor_version <= 7) { - (void)p; - result = PyObject_CallFunction(code_type, "iiiiiOOOOOOiOO", a, k, l, s, f, code, - c, n, v, fn, name, fline, lnos, fv, cell); - } else if (minor_version <= 10) { - result = PyObject_CallFunction(code_type, "iiiiiiOOOOOOiOO", a,p, k, l, s, f, code, - c, n, v, fn, name, fline, lnos, fv, cell); - } else { - if (!(exception_table = PyBytes_FromStringAndSize(NULL, 0))) goto end; - result = PyObject_CallFunction(code_type, "iiiiiiOOOOOOOiOO", a,p, k, l, s, f, code, - c, n, v, fn, name, name, fline, lnos, exception_table, fv, cell); - } - end: - Py_XDECREF(code_type); - Py_XDECREF(exception_table); - Py_XDECREF(types_module); - if (type) { - PyErr_Restore(type, value, traceback); - } - return result; - } - #ifndef CO_OPTIMIZED - #define CO_OPTIMIZED 0x0001 - #endif - #ifndef CO_NEWLOCALS - #define CO_NEWLOCALS 0x0002 - #endif - #ifndef CO_VARARGS - #define CO_VARARGS 0x0004 - #endif - #ifndef CO_VARKEYWORDS - #define CO_VARKEYWORDS 0x0008 - #endif - #ifndef CO_ASYNC_GENERATOR - #define CO_ASYNC_GENERATOR 0x0200 - #endif - #ifndef CO_GENERATOR - #define CO_GENERATOR 0x0020 - #endif - #ifndef CO_COROUTINE - #define CO_COROUTINE 0x0080 - #endif -#elif PY_VERSION_HEX >= 0x030B0000 - static CYTHON_INLINE PyCodeObject* __Pyx_PyCode_New(int a, int p, int k, int l, int s, int f, - PyObject *code, PyObject *c, PyObject* n, PyObject *v, - PyObject *fv, PyObject *cell, PyObject* fn, - PyObject *name, int fline, PyObject *lnos) { - PyCodeObject *result; - PyObject *empty_bytes = PyBytes_FromStringAndSize("", 0); - if (!empty_bytes) return NULL; - result = - #if PY_VERSION_HEX >= 0x030C0000 - PyUnstable_Code_NewWithPosOnlyArgs - #else - PyCode_NewWithPosOnlyArgs - #endif - (a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, name, fline, lnos, empty_bytes); - Py_DECREF(empty_bytes); - return result; - } -#elif PY_VERSION_HEX >= 0x030800B2 && !CYTHON_COMPILING_IN_PYPY - #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ - PyCode_NewWithPosOnlyArgs(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) -#else - #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ - PyCode_New(a, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) -#endif -#endif -#if PY_VERSION_HEX >= 0x030900A4 || defined(Py_IS_TYPE) - #define __Pyx_IS_TYPE(ob, type) Py_IS_TYPE(ob, type) -#else - #define __Pyx_IS_TYPE(ob, type) (((const PyObject*)ob)->ob_type == (type)) -#endif -#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_Is) - #define __Pyx_Py_Is(x, y) Py_Is(x, y) -#else - #define __Pyx_Py_Is(x, y) ((x) == (y)) -#endif -#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsNone) - #define __Pyx_Py_IsNone(ob) Py_IsNone(ob) -#else - #define __Pyx_Py_IsNone(ob) __Pyx_Py_Is((ob), Py_None) -#endif -#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsTrue) - #define __Pyx_Py_IsTrue(ob) Py_IsTrue(ob) -#else - #define __Pyx_Py_IsTrue(ob) __Pyx_Py_Is((ob), Py_True) -#endif -#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsFalse) - #define __Pyx_Py_IsFalse(ob) Py_IsFalse(ob) -#else - #define __Pyx_Py_IsFalse(ob) __Pyx_Py_Is((ob), Py_False) -#endif -#define __Pyx_NoneAsNull(obj) (__Pyx_Py_IsNone(obj) ? NULL : (obj)) -#if PY_VERSION_HEX >= 0x030900F0 && !CYTHON_COMPILING_IN_PYPY - #define __Pyx_PyObject_GC_IsFinalized(o) PyObject_GC_IsFinalized(o) -#else - #define __Pyx_PyObject_GC_IsFinalized(o) _PyGC_FINALIZED(o) -#endif -#ifndef CO_COROUTINE - #define CO_COROUTINE 0x80 -#endif -#ifndef CO_ASYNC_GENERATOR - #define CO_ASYNC_GENERATOR 0x200 -#endif -#ifndef Py_TPFLAGS_CHECKTYPES - #define Py_TPFLAGS_CHECKTYPES 0 -#endif -#ifndef Py_TPFLAGS_HAVE_INDEX - #define Py_TPFLAGS_HAVE_INDEX 0 -#endif -#ifndef Py_TPFLAGS_HAVE_NEWBUFFER - #define Py_TPFLAGS_HAVE_NEWBUFFER 0 -#endif -#ifndef Py_TPFLAGS_HAVE_FINALIZE - #define Py_TPFLAGS_HAVE_FINALIZE 0 -#endif -#ifndef Py_TPFLAGS_SEQUENCE - #define Py_TPFLAGS_SEQUENCE 0 -#endif -#ifndef Py_TPFLAGS_MAPPING - #define Py_TPFLAGS_MAPPING 0 -#endif -#ifndef METH_STACKLESS - #define METH_STACKLESS 0 -#endif -#if PY_VERSION_HEX <= 0x030700A3 || !defined(METH_FASTCALL) - #ifndef METH_FASTCALL - #define METH_FASTCALL 0x80 - #endif - typedef PyObject *(*__Pyx_PyCFunctionFast) (PyObject *self, PyObject *const *args, Py_ssize_t nargs); - typedef PyObject *(*__Pyx_PyCFunctionFastWithKeywords) (PyObject *self, PyObject *const *args, - Py_ssize_t nargs, PyObject *kwnames); -#else - #define __Pyx_PyCFunctionFast _PyCFunctionFast - #define __Pyx_PyCFunctionFastWithKeywords _PyCFunctionFastWithKeywords -#endif -#if CYTHON_METH_FASTCALL - #define __Pyx_METH_FASTCALL METH_FASTCALL - #define __Pyx_PyCFunction_FastCall __Pyx_PyCFunctionFast - #define __Pyx_PyCFunction_FastCallWithKeywords __Pyx_PyCFunctionFastWithKeywords -#else - #define __Pyx_METH_FASTCALL METH_VARARGS - #define __Pyx_PyCFunction_FastCall PyCFunction - #define __Pyx_PyCFunction_FastCallWithKeywords PyCFunctionWithKeywords -#endif -#if CYTHON_VECTORCALL - #define __pyx_vectorcallfunc vectorcallfunc - #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET PY_VECTORCALL_ARGUMENTS_OFFSET - #define __Pyx_PyVectorcall_NARGS(n) PyVectorcall_NARGS((size_t)(n)) -#elif CYTHON_BACKPORT_VECTORCALL - typedef PyObject *(*__pyx_vectorcallfunc)(PyObject *callable, PyObject *const *args, - size_t nargsf, PyObject *kwnames); - #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET ((size_t)1 << (8 * sizeof(size_t) - 1)) - #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(((size_t)(n)) & ~__Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET)) -#else - #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET 0 - #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(n)) -#endif -#if PY_MAJOR_VERSION >= 0x030900B1 -#define __Pyx_PyCFunction_CheckExact(func) PyCFunction_CheckExact(func) -#else -#define __Pyx_PyCFunction_CheckExact(func) PyCFunction_Check(func) -#endif -#define __Pyx_CyOrPyCFunction_Check(func) PyCFunction_Check(func) -#if CYTHON_COMPILING_IN_CPYTHON -#define __Pyx_CyOrPyCFunction_GET_FUNCTION(func) (((PyCFunctionObject*)(func))->m_ml->ml_meth) -#elif !CYTHON_COMPILING_IN_LIMITED_API -#define __Pyx_CyOrPyCFunction_GET_FUNCTION(func) PyCFunction_GET_FUNCTION(func) -#endif -#if CYTHON_COMPILING_IN_CPYTHON -#define __Pyx_CyOrPyCFunction_GET_FLAGS(func) (((PyCFunctionObject*)(func))->m_ml->ml_flags) -static CYTHON_INLINE PyObject* __Pyx_CyOrPyCFunction_GET_SELF(PyObject *func) { - return (__Pyx_CyOrPyCFunction_GET_FLAGS(func) & METH_STATIC) ? NULL : ((PyCFunctionObject*)func)->m_self; -} -#endif -static CYTHON_INLINE int __Pyx__IsSameCFunction(PyObject *func, void *cfunc) { -#if CYTHON_COMPILING_IN_LIMITED_API - return PyCFunction_Check(func) && PyCFunction_GetFunction(func) == (PyCFunction) cfunc; -#else - return PyCFunction_Check(func) && PyCFunction_GET_FUNCTION(func) == (PyCFunction) cfunc; -#endif -} -#define __Pyx_IsSameCFunction(func, cfunc) __Pyx__IsSameCFunction(func, cfunc) -#if __PYX_LIMITED_VERSION_HEX < 0x030900B1 - #define __Pyx_PyType_FromModuleAndSpec(m, s, b) ((void)m, PyType_FromSpecWithBases(s, b)) - typedef PyObject *(*__Pyx_PyCMethod)(PyObject *, PyTypeObject *, PyObject *const *, size_t, PyObject *); -#else - #define __Pyx_PyType_FromModuleAndSpec(m, s, b) PyType_FromModuleAndSpec(m, s, b) - #define __Pyx_PyCMethod PyCMethod -#endif -#ifndef METH_METHOD - #define METH_METHOD 0x200 -#endif -#if CYTHON_COMPILING_IN_PYPY && !defined(PyObject_Malloc) - #define PyObject_Malloc(s) PyMem_Malloc(s) - #define PyObject_Free(p) PyMem_Free(p) - #define PyObject_Realloc(p) PyMem_Realloc(p) -#endif -#if CYTHON_COMPILING_IN_LIMITED_API - #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) - #define __Pyx_PyFrame_SetLineNumber(frame, lineno) -#else - #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) - #define __Pyx_PyFrame_SetLineNumber(frame, lineno) (frame)->f_lineno = (lineno) -#endif -#if CYTHON_COMPILING_IN_LIMITED_API - #define __Pyx_PyThreadState_Current PyThreadState_Get() -#elif !CYTHON_FAST_THREAD_STATE - #define __Pyx_PyThreadState_Current PyThreadState_GET() -#elif PY_VERSION_HEX >= 0x030d00A1 - #define __Pyx_PyThreadState_Current PyThreadState_GetUnchecked() -#elif PY_VERSION_HEX >= 0x03060000 - #define __Pyx_PyThreadState_Current _PyThreadState_UncheckedGet() -#elif PY_VERSION_HEX >= 0x03000000 - #define __Pyx_PyThreadState_Current PyThreadState_GET() -#else - #define __Pyx_PyThreadState_Current _PyThreadState_Current -#endif -#if CYTHON_COMPILING_IN_LIMITED_API -static CYTHON_INLINE void *__Pyx_PyModule_GetState(PyObject *op) -{ - void *result; - result = PyModule_GetState(op); - if (!result) - Py_FatalError("Couldn't find the module state"); - return result; -} -#endif -#define __Pyx_PyObject_GetSlot(obj, name, func_ctype) __Pyx_PyType_GetSlot(Py_TYPE(obj), name, func_ctype) -#if CYTHON_COMPILING_IN_LIMITED_API - #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((func_ctype) PyType_GetSlot((type), Py_##name)) -#else - #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((type)->name) -#endif -#if PY_VERSION_HEX < 0x030700A2 && !defined(PyThread_tss_create) && !defined(Py_tss_NEEDS_INIT) -#include "pythread.h" -#define Py_tss_NEEDS_INIT 0 -typedef int Py_tss_t; -static CYTHON_INLINE int PyThread_tss_create(Py_tss_t *key) { - *key = PyThread_create_key(); - return 0; -} -static CYTHON_INLINE Py_tss_t * PyThread_tss_alloc(void) { - Py_tss_t *key = (Py_tss_t *)PyObject_Malloc(sizeof(Py_tss_t)); - *key = Py_tss_NEEDS_INIT; - return key; -} -static CYTHON_INLINE void PyThread_tss_free(Py_tss_t *key) { - PyObject_Free(key); -} -static CYTHON_INLINE int PyThread_tss_is_created(Py_tss_t *key) { - return *key != Py_tss_NEEDS_INIT; -} -static CYTHON_INLINE void PyThread_tss_delete(Py_tss_t *key) { - PyThread_delete_key(*key); - *key = Py_tss_NEEDS_INIT; -} -static CYTHON_INLINE int PyThread_tss_set(Py_tss_t *key, void *value) { - return PyThread_set_key_value(*key, value); -} -static CYTHON_INLINE void * PyThread_tss_get(Py_tss_t *key) { - return PyThread_get_key_value(*key); -} -#endif -#if PY_MAJOR_VERSION < 3 - #if CYTHON_COMPILING_IN_PYPY - #if PYPY_VERSION_NUM < 0x07030600 - #if defined(__cplusplus) && __cplusplus >= 201402L - [[deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")]] - #elif defined(__GNUC__) || defined(__clang__) - __attribute__ ((__deprecated__("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6"))) - #elif defined(_MSC_VER) - __declspec(deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")) - #endif - static CYTHON_INLINE int PyGILState_Check(void) { - return 0; - } - #else // PYPY_VERSION_NUM < 0x07030600 - #endif // PYPY_VERSION_NUM < 0x07030600 - #else - static CYTHON_INLINE int PyGILState_Check(void) { - PyThreadState * tstate = _PyThreadState_Current; - return tstate && (tstate == PyGILState_GetThisThreadState()); - } - #endif -#endif -#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030d0000 || defined(_PyDict_NewPresized) -#define __Pyx_PyDict_NewPresized(n) ((n <= 8) ? PyDict_New() : _PyDict_NewPresized(n)) -#else -#define __Pyx_PyDict_NewPresized(n) PyDict_New() -#endif -#if PY_MAJOR_VERSION >= 3 || CYTHON_FUTURE_DIVISION - #define __Pyx_PyNumber_Divide(x,y) PyNumber_TrueDivide(x,y) - #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceTrueDivide(x,y) -#else - #define __Pyx_PyNumber_Divide(x,y) PyNumber_Divide(x,y) - #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceDivide(x,y) -#endif -#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX > 0x030600B4 && PY_VERSION_HEX < 0x030d0000 && CYTHON_USE_UNICODE_INTERNALS -#define __Pyx_PyDict_GetItemStrWithError(dict, name) _PyDict_GetItem_KnownHash(dict, name, ((PyASCIIObject *) name)->hash) -static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStr(PyObject *dict, PyObject *name) { - PyObject *res = __Pyx_PyDict_GetItemStrWithError(dict, name); - if (res == NULL) PyErr_Clear(); - return res; -} -#elif PY_MAJOR_VERSION >= 3 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07020000) -#define __Pyx_PyDict_GetItemStrWithError PyDict_GetItemWithError -#define __Pyx_PyDict_GetItemStr PyDict_GetItem -#else -static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStrWithError(PyObject *dict, PyObject *name) { -#if CYTHON_COMPILING_IN_PYPY - return PyDict_GetItem(dict, name); -#else - PyDictEntry *ep; - PyDictObject *mp = (PyDictObject*) dict; - long hash = ((PyStringObject *) name)->ob_shash; - assert(hash != -1); - ep = (mp->ma_lookup)(mp, name, hash); - if (ep == NULL) { - return NULL; - } - return ep->me_value; -#endif -} -#define __Pyx_PyDict_GetItemStr PyDict_GetItem -#endif -#if CYTHON_USE_TYPE_SLOTS - #define __Pyx_PyType_GetFlags(tp) (((PyTypeObject *)tp)->tp_flags) - #define __Pyx_PyType_HasFeature(type, feature) ((__Pyx_PyType_GetFlags(type) & (feature)) != 0) - #define __Pyx_PyObject_GetIterNextFunc(obj) (Py_TYPE(obj)->tp_iternext) -#else - #define __Pyx_PyType_GetFlags(tp) (PyType_GetFlags((PyTypeObject *)tp)) - #define __Pyx_PyType_HasFeature(type, feature) PyType_HasFeature(type, feature) - #define __Pyx_PyObject_GetIterNextFunc(obj) PyIter_Next -#endif -#if CYTHON_COMPILING_IN_LIMITED_API - #define __Pyx_SetItemOnTypeDict(tp, k, v) PyObject_GenericSetAttr((PyObject*)tp, k, v) -#else - #define __Pyx_SetItemOnTypeDict(tp, k, v) PyDict_SetItem(tp->tp_dict, k, v) -#endif -#if CYTHON_USE_TYPE_SPECS && PY_VERSION_HEX >= 0x03080000 -#define __Pyx_PyHeapTypeObject_GC_Del(obj) {\ - PyTypeObject *type = Py_TYPE((PyObject*)obj);\ - assert(__Pyx_PyType_HasFeature(type, Py_TPFLAGS_HEAPTYPE));\ - PyObject_GC_Del(obj);\ - Py_DECREF(type);\ -} -#else -#define __Pyx_PyHeapTypeObject_GC_Del(obj) PyObject_GC_Del(obj) -#endif -#if CYTHON_COMPILING_IN_LIMITED_API - #define CYTHON_PEP393_ENABLED 1 - #define __Pyx_PyUnicode_READY(op) (0) - #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GetLength(u) - #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_ReadChar(u, i) - #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((void)u, 1114111U) - #define __Pyx_PyUnicode_KIND(u) ((void)u, (0)) - #define __Pyx_PyUnicode_DATA(u) ((void*)u) - #define __Pyx_PyUnicode_READ(k, d, i) ((void)k, PyUnicode_ReadChar((PyObject*)(d), i)) - #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GetLength(u)) -#elif PY_VERSION_HEX > 0x03030000 && defined(PyUnicode_KIND) - #define CYTHON_PEP393_ENABLED 1 - #if PY_VERSION_HEX >= 0x030C0000 - #define __Pyx_PyUnicode_READY(op) (0) - #else - #define __Pyx_PyUnicode_READY(op) (likely(PyUnicode_IS_READY(op)) ?\ - 0 : _PyUnicode_Ready((PyObject *)(op))) - #endif - #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_LENGTH(u) - #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_READ_CHAR(u, i) - #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) PyUnicode_MAX_CHAR_VALUE(u) - #define __Pyx_PyUnicode_KIND(u) ((int)PyUnicode_KIND(u)) - #define __Pyx_PyUnicode_DATA(u) PyUnicode_DATA(u) - #define __Pyx_PyUnicode_READ(k, d, i) PyUnicode_READ(k, d, i) - #define __Pyx_PyUnicode_WRITE(k, d, i, ch) PyUnicode_WRITE(k, d, i, (Py_UCS4) ch) - #if PY_VERSION_HEX >= 0x030C0000 - #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_LENGTH(u)) - #else - #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x03090000 - #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : ((PyCompactUnicodeObject *)(u))->wstr_length)) - #else - #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : PyUnicode_GET_SIZE(u))) - #endif - #endif -#else - #define CYTHON_PEP393_ENABLED 0 - #define PyUnicode_1BYTE_KIND 1 - #define PyUnicode_2BYTE_KIND 2 - #define PyUnicode_4BYTE_KIND 4 - #define __Pyx_PyUnicode_READY(op) (0) - #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_SIZE(u) - #define __Pyx_PyUnicode_READ_CHAR(u, i) ((Py_UCS4)(PyUnicode_AS_UNICODE(u)[i])) - #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((sizeof(Py_UNICODE) == 2) ? 65535U : 1114111U) - #define __Pyx_PyUnicode_KIND(u) ((int)sizeof(Py_UNICODE)) - #define __Pyx_PyUnicode_DATA(u) ((void*)PyUnicode_AS_UNICODE(u)) - #define __Pyx_PyUnicode_READ(k, d, i) ((void)(k), (Py_UCS4)(((Py_UNICODE*)d)[i])) - #define __Pyx_PyUnicode_WRITE(k, d, i, ch) (((void)(k)), ((Py_UNICODE*)d)[i] = (Py_UNICODE) ch) - #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_SIZE(u)) -#endif -#if CYTHON_COMPILING_IN_PYPY - #define __Pyx_PyUnicode_Concat(a, b) PyNumber_Add(a, b) - #define __Pyx_PyUnicode_ConcatSafe(a, b) PyNumber_Add(a, b) -#else - #define __Pyx_PyUnicode_Concat(a, b) PyUnicode_Concat(a, b) - #define __Pyx_PyUnicode_ConcatSafe(a, b) ((unlikely((a) == Py_None) || unlikely((b) == Py_None)) ?\ - PyNumber_Add(a, b) : __Pyx_PyUnicode_Concat(a, b)) -#endif -#if CYTHON_COMPILING_IN_PYPY - #if !defined(PyUnicode_DecodeUnicodeEscape) - #define PyUnicode_DecodeUnicodeEscape(s, size, errors) PyUnicode_Decode(s, size, "unicode_escape", errors) - #endif - #if !defined(PyUnicode_Contains) || (PY_MAJOR_VERSION == 2 && PYPY_VERSION_NUM < 0x07030500) - #undef PyUnicode_Contains - #define PyUnicode_Contains(u, s) PySequence_Contains(u, s) - #endif - #if !defined(PyByteArray_Check) - #define PyByteArray_Check(obj) PyObject_TypeCheck(obj, &PyByteArray_Type) - #endif - #if !defined(PyObject_Format) - #define PyObject_Format(obj, fmt) PyObject_CallMethod(obj, "__format__", "O", fmt) - #endif -#endif -#define __Pyx_PyString_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyString_Check(b) && !PyString_CheckExact(b)))) ? PyNumber_Remainder(a, b) : __Pyx_PyString_Format(a, b)) -#define __Pyx_PyUnicode_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyUnicode_Check(b) && !PyUnicode_CheckExact(b)))) ? PyNumber_Remainder(a, b) : PyUnicode_Format(a, b)) -#if PY_MAJOR_VERSION >= 3 - #define __Pyx_PyString_Format(a, b) PyUnicode_Format(a, b) -#else - #define __Pyx_PyString_Format(a, b) PyString_Format(a, b) -#endif -#if PY_MAJOR_VERSION < 3 && !defined(PyObject_ASCII) - #define PyObject_ASCII(o) PyObject_Repr(o) -#endif -#if PY_MAJOR_VERSION >= 3 - #define PyBaseString_Type PyUnicode_Type - #define PyStringObject PyUnicodeObject - #define PyString_Type PyUnicode_Type - #define PyString_Check PyUnicode_Check - #define PyString_CheckExact PyUnicode_CheckExact -#ifndef PyObject_Unicode - #define PyObject_Unicode PyObject_Str -#endif -#endif -#if PY_MAJOR_VERSION >= 3 - #define __Pyx_PyBaseString_Check(obj) PyUnicode_Check(obj) - #define __Pyx_PyBaseString_CheckExact(obj) PyUnicode_CheckExact(obj) -#else - #define __Pyx_PyBaseString_Check(obj) (PyString_Check(obj) || PyUnicode_Check(obj)) - #define __Pyx_PyBaseString_CheckExact(obj) (PyString_CheckExact(obj) || PyUnicode_CheckExact(obj)) -#endif -#if CYTHON_COMPILING_IN_CPYTHON - #define __Pyx_PySequence_ListKeepNew(obj)\ - (likely(PyList_CheckExact(obj) && Py_REFCNT(obj) == 1) ? __Pyx_NewRef(obj) : PySequence_List(obj)) -#else - #define __Pyx_PySequence_ListKeepNew(obj) PySequence_List(obj) -#endif -#ifndef PySet_CheckExact - #define PySet_CheckExact(obj) __Pyx_IS_TYPE(obj, &PySet_Type) -#endif -#if PY_VERSION_HEX >= 0x030900A4 - #define __Pyx_SET_REFCNT(obj, refcnt) Py_SET_REFCNT(obj, refcnt) - #define __Pyx_SET_SIZE(obj, size) Py_SET_SIZE(obj, size) -#else - #define __Pyx_SET_REFCNT(obj, refcnt) Py_REFCNT(obj) = (refcnt) - #define __Pyx_SET_SIZE(obj, size) Py_SIZE(obj) = (size) -#endif -#if CYTHON_ASSUME_SAFE_MACROS - #define __Pyx_PySequence_ITEM(o, i) PySequence_ITEM(o, i) - #define __Pyx_PySequence_SIZE(seq) Py_SIZE(seq) - #define __Pyx_PyTuple_SET_ITEM(o, i, v) (PyTuple_SET_ITEM(o, i, v), (0)) - #define __Pyx_PyList_SET_ITEM(o, i, v) (PyList_SET_ITEM(o, i, v), (0)) - #define __Pyx_PyTuple_GET_SIZE(o) PyTuple_GET_SIZE(o) - #define __Pyx_PyList_GET_SIZE(o) PyList_GET_SIZE(o) - #define __Pyx_PySet_GET_SIZE(o) PySet_GET_SIZE(o) - #define __Pyx_PyBytes_GET_SIZE(o) PyBytes_GET_SIZE(o) - #define __Pyx_PyByteArray_GET_SIZE(o) PyByteArray_GET_SIZE(o) -#else - #define __Pyx_PySequence_ITEM(o, i) PySequence_GetItem(o, i) - #define __Pyx_PySequence_SIZE(seq) PySequence_Size(seq) - #define __Pyx_PyTuple_SET_ITEM(o, i, v) PyTuple_SetItem(o, i, v) - #define __Pyx_PyList_SET_ITEM(o, i, v) PyList_SetItem(o, i, v) - #define __Pyx_PyTuple_GET_SIZE(o) PyTuple_Size(o) - #define __Pyx_PyList_GET_SIZE(o) PyList_Size(o) - #define __Pyx_PySet_GET_SIZE(o) PySet_Size(o) - #define __Pyx_PyBytes_GET_SIZE(o) PyBytes_Size(o) - #define __Pyx_PyByteArray_GET_SIZE(o) PyByteArray_Size(o) -#endif -#if PY_VERSION_HEX >= 0x030d00A1 - #define __Pyx_PyImport_AddModuleRef(name) PyImport_AddModuleRef(name) -#else - static CYTHON_INLINE PyObject *__Pyx_PyImport_AddModuleRef(const char *name) { - PyObject *module = PyImport_AddModule(name); - Py_XINCREF(module); - return module; - } -#endif -#if PY_MAJOR_VERSION >= 3 - #define PyIntObject PyLongObject - #define PyInt_Type PyLong_Type - #define PyInt_Check(op) PyLong_Check(op) - #define PyInt_CheckExact(op) PyLong_CheckExact(op) - #define __Pyx_Py3Int_Check(op) PyLong_Check(op) - #define __Pyx_Py3Int_CheckExact(op) PyLong_CheckExact(op) - #define PyInt_FromString PyLong_FromString - #define PyInt_FromUnicode PyLong_FromUnicode - #define PyInt_FromLong PyLong_FromLong - #define PyInt_FromSize_t PyLong_FromSize_t - #define PyInt_FromSsize_t PyLong_FromSsize_t - #define PyInt_AsLong PyLong_AsLong - #define PyInt_AS_LONG PyLong_AS_LONG - #define PyInt_AsSsize_t PyLong_AsSsize_t - #define PyInt_AsUnsignedLongMask PyLong_AsUnsignedLongMask - #define PyInt_AsUnsignedLongLongMask PyLong_AsUnsignedLongLongMask - #define PyNumber_Int PyNumber_Long -#else - #define __Pyx_Py3Int_Check(op) (PyLong_Check(op) || PyInt_Check(op)) - #define __Pyx_Py3Int_CheckExact(op) (PyLong_CheckExact(op) || PyInt_CheckExact(op)) -#endif -#if PY_MAJOR_VERSION >= 3 - #define PyBoolObject PyLongObject -#endif -#if PY_MAJOR_VERSION >= 3 && CYTHON_COMPILING_IN_PYPY - #ifndef PyUnicode_InternFromString - #define PyUnicode_InternFromString(s) PyUnicode_FromString(s) - #endif -#endif -#if PY_VERSION_HEX < 0x030200A4 - typedef long Py_hash_t; - #define __Pyx_PyInt_FromHash_t PyInt_FromLong - #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsHash_t -#else - #define __Pyx_PyInt_FromHash_t PyInt_FromSsize_t - #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsSsize_t -#endif -#if CYTHON_USE_ASYNC_SLOTS - #if PY_VERSION_HEX >= 0x030500B1 - #define __Pyx_PyAsyncMethodsStruct PyAsyncMethods - #define __Pyx_PyType_AsAsync(obj) (Py_TYPE(obj)->tp_as_async) - #else - #define __Pyx_PyType_AsAsync(obj) ((__Pyx_PyAsyncMethodsStruct*) (Py_TYPE(obj)->tp_reserved)) - #endif -#else - #define __Pyx_PyType_AsAsync(obj) NULL -#endif -#ifndef __Pyx_PyAsyncMethodsStruct - typedef struct { - unaryfunc am_await; - unaryfunc am_aiter; - unaryfunc am_anext; - } __Pyx_PyAsyncMethodsStruct; -#endif - -#if defined(_WIN32) || defined(WIN32) || defined(MS_WINDOWS) - #if !defined(_USE_MATH_DEFINES) - #define _USE_MATH_DEFINES - #endif -#endif -#include -#ifdef NAN -#define __PYX_NAN() ((float) NAN) -#else -static CYTHON_INLINE float __PYX_NAN() { - float value; - memset(&value, 0xFF, sizeof(value)); - return value; -} -#endif -#if defined(__CYGWIN__) && defined(_LDBL_EQ_DBL) -#define __Pyx_truncl trunc -#else -#define __Pyx_truncl truncl -#endif - -#define __PYX_MARK_ERR_POS(f_index, lineno) \ - { __pyx_filename = __pyx_f[f_index]; (void)__pyx_filename; __pyx_lineno = lineno; (void)__pyx_lineno; __pyx_clineno = __LINE__; (void)__pyx_clineno; } -#define __PYX_ERR(f_index, lineno, Ln_error) \ - { __PYX_MARK_ERR_POS(f_index, lineno) goto Ln_error; } - -#ifdef CYTHON_EXTERN_C - #undef __PYX_EXTERN_C - #define __PYX_EXTERN_C CYTHON_EXTERN_C -#elif defined(__PYX_EXTERN_C) - #ifdef _MSC_VER - #pragma message ("Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead.") - #else - #warning Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead. - #endif -#else - #define __PYX_EXTERN_C extern "C++" -#endif - -#define __PYX_HAVE__rednose__helpers__ekf_sym_pyx -#define __PYX_HAVE_API__rednose__helpers__ekf_sym_pyx -/* Early includes */ -#include -#include -#include "ios" -#include "new" -#include "stdexcept" -#include "typeinfo" -#include -#include - - /* Using NumPy API declarations from "numpy/__init__.cython-30.pxd" */ - -#include "numpy/arrayobject.h" -#include "numpy/ndarrayobject.h" -#include "numpy/ndarraytypes.h" -#include "numpy/arrayscalars.h" -#include "numpy/ufuncobject.h" -#include -#include "rednose/helpers/ekf_load.h" -#include "rednose/helpers/ekf_sym.h" -#include "pythread.h" -#include -#ifdef _OPENMP -#include -#endif /* _OPENMP */ - -#if defined(PYREX_WITHOUT_ASSERTIONS) && !defined(CYTHON_WITHOUT_ASSERTIONS) -#define CYTHON_WITHOUT_ASSERTIONS -#endif - -typedef struct {PyObject **p; const char *s; const Py_ssize_t n; const char* encoding; - const char is_unicode; const char is_str; const char intern; } __Pyx_StringTabEntry; - -#define __PYX_DEFAULT_STRING_ENCODING_IS_ASCII 0 -#define __PYX_DEFAULT_STRING_ENCODING_IS_UTF8 0 -#define __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT (PY_MAJOR_VERSION >= 3 && __PYX_DEFAULT_STRING_ENCODING_IS_UTF8) -#define __PYX_DEFAULT_STRING_ENCODING "" -#define __Pyx_PyObject_FromString __Pyx_PyBytes_FromString -#define __Pyx_PyObject_FromStringAndSize __Pyx_PyBytes_FromStringAndSize -#define __Pyx_uchar_cast(c) ((unsigned char)c) -#define __Pyx_long_cast(x) ((long)x) -#define __Pyx_fits_Py_ssize_t(v, type, is_signed) (\ - (sizeof(type) < sizeof(Py_ssize_t)) ||\ - (sizeof(type) > sizeof(Py_ssize_t) &&\ - likely(v < (type)PY_SSIZE_T_MAX ||\ - v == (type)PY_SSIZE_T_MAX) &&\ - (!is_signed || likely(v > (type)PY_SSIZE_T_MIN ||\ - v == (type)PY_SSIZE_T_MIN))) ||\ - (sizeof(type) == sizeof(Py_ssize_t) &&\ - (is_signed || likely(v < (type)PY_SSIZE_T_MAX ||\ - v == (type)PY_SSIZE_T_MAX))) ) -static CYTHON_INLINE int __Pyx_is_valid_index(Py_ssize_t i, Py_ssize_t limit) { - return (size_t) i < (size_t) limit; -} -#if defined (__cplusplus) && __cplusplus >= 201103L - #include - #define __Pyx_sst_abs(value) std::abs(value) -#elif SIZEOF_INT >= SIZEOF_SIZE_T - #define __Pyx_sst_abs(value) abs(value) -#elif SIZEOF_LONG >= SIZEOF_SIZE_T - #define __Pyx_sst_abs(value) labs(value) -#elif defined (_MSC_VER) - #define __Pyx_sst_abs(value) ((Py_ssize_t)_abs64(value)) -#elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L - #define __Pyx_sst_abs(value) llabs(value) -#elif defined (__GNUC__) - #define __Pyx_sst_abs(value) __builtin_llabs(value) -#else - #define __Pyx_sst_abs(value) ((value<0) ? -value : value) -#endif -static CYTHON_INLINE Py_ssize_t __Pyx_ssize_strlen(const char *s); -static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject*); -static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject*, Py_ssize_t* length); -static CYTHON_INLINE PyObject* __Pyx_PyByteArray_FromString(const char*); -#define __Pyx_PyByteArray_FromStringAndSize(s, l) PyByteArray_FromStringAndSize((const char*)s, l) -#define __Pyx_PyBytes_FromString PyBytes_FromString -#define __Pyx_PyBytes_FromStringAndSize PyBytes_FromStringAndSize -static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char*); -#if PY_MAJOR_VERSION < 3 - #define __Pyx_PyStr_FromString __Pyx_PyBytes_FromString - #define __Pyx_PyStr_FromStringAndSize __Pyx_PyBytes_FromStringAndSize -#else - #define __Pyx_PyStr_FromString __Pyx_PyUnicode_FromString - #define __Pyx_PyStr_FromStringAndSize __Pyx_PyUnicode_FromStringAndSize -#endif -#define __Pyx_PyBytes_AsWritableString(s) ((char*) PyBytes_AS_STRING(s)) -#define __Pyx_PyBytes_AsWritableSString(s) ((signed char*) PyBytes_AS_STRING(s)) -#define __Pyx_PyBytes_AsWritableUString(s) ((unsigned char*) PyBytes_AS_STRING(s)) -#define __Pyx_PyBytes_AsString(s) ((const char*) PyBytes_AS_STRING(s)) -#define __Pyx_PyBytes_AsSString(s) ((const signed char*) PyBytes_AS_STRING(s)) -#define __Pyx_PyBytes_AsUString(s) ((const unsigned char*) PyBytes_AS_STRING(s)) -#define __Pyx_PyObject_AsWritableString(s) ((char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) -#define __Pyx_PyObject_AsWritableSString(s) ((signed char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) -#define __Pyx_PyObject_AsWritableUString(s) ((unsigned char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) -#define __Pyx_PyObject_AsSString(s) ((const signed char*) __Pyx_PyObject_AsString(s)) -#define __Pyx_PyObject_AsUString(s) ((const unsigned char*) __Pyx_PyObject_AsString(s)) -#define __Pyx_PyObject_FromCString(s) __Pyx_PyObject_FromString((const char*)s) -#define __Pyx_PyBytes_FromCString(s) __Pyx_PyBytes_FromString((const char*)s) -#define __Pyx_PyByteArray_FromCString(s) __Pyx_PyByteArray_FromString((const char*)s) -#define __Pyx_PyStr_FromCString(s) __Pyx_PyStr_FromString((const char*)s) -#define __Pyx_PyUnicode_FromCString(s) __Pyx_PyUnicode_FromString((const char*)s) -#if CYTHON_COMPILING_IN_LIMITED_API -static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const wchar_t *u) -{ - const wchar_t *u_end = u; - while (*u_end++) ; - return (size_t)(u_end - u - 1); -} -#else -static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const Py_UNICODE *u) -{ - const Py_UNICODE *u_end = u; - while (*u_end++) ; - return (size_t)(u_end - u - 1); -} -#endif -#define __Pyx_PyUnicode_FromOrdinal(o) PyUnicode_FromOrdinal((int)o) -#define __Pyx_PyUnicode_FromUnicode(u) PyUnicode_FromUnicode(u, __Pyx_Py_UNICODE_strlen(u)) -#define __Pyx_PyUnicode_FromUnicodeAndLength PyUnicode_FromUnicode -#define __Pyx_PyUnicode_AsUnicode PyUnicode_AsUnicode -#define __Pyx_NewRef(obj) (Py_INCREF(obj), obj) -#define __Pyx_Owned_Py_None(b) __Pyx_NewRef(Py_None) -static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b); -static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject*); -static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject*); -static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x); -#define __Pyx_PySequence_Tuple(obj)\ - (likely(PyTuple_CheckExact(obj)) ? __Pyx_NewRef(obj) : PySequence_Tuple(obj)) -static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject*); -static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t); -static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject*); -#if CYTHON_ASSUME_SAFE_MACROS -#define __pyx_PyFloat_AsDouble(x) (PyFloat_CheckExact(x) ? PyFloat_AS_DOUBLE(x) : PyFloat_AsDouble(x)) -#else -#define __pyx_PyFloat_AsDouble(x) PyFloat_AsDouble(x) -#endif -#define __pyx_PyFloat_AsFloat(x) ((float) __pyx_PyFloat_AsDouble(x)) -#if PY_MAJOR_VERSION >= 3 -#define __Pyx_PyNumber_Int(x) (PyLong_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Long(x)) -#else -#define __Pyx_PyNumber_Int(x) (PyInt_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Int(x)) -#endif -#if CYTHON_USE_PYLONG_INTERNALS - #if PY_VERSION_HEX >= 0x030C00A7 - #ifndef _PyLong_SIGN_MASK - #define _PyLong_SIGN_MASK 3 - #endif - #ifndef _PyLong_NON_SIZE_BITS - #define _PyLong_NON_SIZE_BITS 3 - #endif - #define __Pyx_PyLong_Sign(x) (((PyLongObject*)x)->long_value.lv_tag & _PyLong_SIGN_MASK) - #define __Pyx_PyLong_IsNeg(x) ((__Pyx_PyLong_Sign(x) & 2) != 0) - #define __Pyx_PyLong_IsNonNeg(x) (!__Pyx_PyLong_IsNeg(x)) - #define __Pyx_PyLong_IsZero(x) (__Pyx_PyLong_Sign(x) & 1) - #define __Pyx_PyLong_IsPos(x) (__Pyx_PyLong_Sign(x) == 0) - #define __Pyx_PyLong_CompactValueUnsigned(x) (__Pyx_PyLong_Digits(x)[0]) - #define __Pyx_PyLong_DigitCount(x) ((Py_ssize_t) (((PyLongObject*)x)->long_value.lv_tag >> _PyLong_NON_SIZE_BITS)) - #define __Pyx_PyLong_SignedDigitCount(x)\ - ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * __Pyx_PyLong_DigitCount(x)) - #if defined(PyUnstable_Long_IsCompact) && defined(PyUnstable_Long_CompactValue) - #define __Pyx_PyLong_IsCompact(x) PyUnstable_Long_IsCompact((PyLongObject*) x) - #define __Pyx_PyLong_CompactValue(x) PyUnstable_Long_CompactValue((PyLongObject*) x) - #else - #define __Pyx_PyLong_IsCompact(x) (((PyLongObject*)x)->long_value.lv_tag < (2 << _PyLong_NON_SIZE_BITS)) - #define __Pyx_PyLong_CompactValue(x) ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * (Py_ssize_t) __Pyx_PyLong_Digits(x)[0]) - #endif - typedef Py_ssize_t __Pyx_compact_pylong; - typedef size_t __Pyx_compact_upylong; - #else - #define __Pyx_PyLong_IsNeg(x) (Py_SIZE(x) < 0) - #define __Pyx_PyLong_IsNonNeg(x) (Py_SIZE(x) >= 0) - #define __Pyx_PyLong_IsZero(x) (Py_SIZE(x) == 0) - #define __Pyx_PyLong_IsPos(x) (Py_SIZE(x) > 0) - #define __Pyx_PyLong_CompactValueUnsigned(x) ((Py_SIZE(x) == 0) ? 0 : __Pyx_PyLong_Digits(x)[0]) - #define __Pyx_PyLong_DigitCount(x) __Pyx_sst_abs(Py_SIZE(x)) - #define __Pyx_PyLong_SignedDigitCount(x) Py_SIZE(x) - #define __Pyx_PyLong_IsCompact(x) (Py_SIZE(x) == 0 || Py_SIZE(x) == 1 || Py_SIZE(x) == -1) - #define __Pyx_PyLong_CompactValue(x)\ - ((Py_SIZE(x) == 0) ? (sdigit) 0 : ((Py_SIZE(x) < 0) ? -(sdigit)__Pyx_PyLong_Digits(x)[0] : (sdigit)__Pyx_PyLong_Digits(x)[0])) - typedef sdigit __Pyx_compact_pylong; - typedef digit __Pyx_compact_upylong; - #endif - #if PY_VERSION_HEX >= 0x030C00A5 - #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->long_value.ob_digit) - #else - #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->ob_digit) - #endif -#endif -#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII -#include -static int __Pyx_sys_getdefaultencoding_not_ascii; -static int __Pyx_init_sys_getdefaultencoding_params(void) { - PyObject* sys; - PyObject* default_encoding = NULL; - PyObject* ascii_chars_u = NULL; - PyObject* ascii_chars_b = NULL; - const char* default_encoding_c; - sys = PyImport_ImportModule("sys"); - if (!sys) goto bad; - default_encoding = PyObject_CallMethod(sys, (char*) "getdefaultencoding", NULL); - Py_DECREF(sys); - if (!default_encoding) goto bad; - default_encoding_c = PyBytes_AsString(default_encoding); - if (!default_encoding_c) goto bad; - if (strcmp(default_encoding_c, "ascii") == 0) { - __Pyx_sys_getdefaultencoding_not_ascii = 0; - } else { - char ascii_chars[128]; - int c; - for (c = 0; c < 128; c++) { - ascii_chars[c] = (char) c; - } - __Pyx_sys_getdefaultencoding_not_ascii = 1; - ascii_chars_u = PyUnicode_DecodeASCII(ascii_chars, 128, NULL); - if (!ascii_chars_u) goto bad; - ascii_chars_b = PyUnicode_AsEncodedString(ascii_chars_u, default_encoding_c, NULL); - if (!ascii_chars_b || !PyBytes_Check(ascii_chars_b) || memcmp(ascii_chars, PyBytes_AS_STRING(ascii_chars_b), 128) != 0) { - PyErr_Format( - PyExc_ValueError, - "This module compiled with c_string_encoding=ascii, but default encoding '%.200s' is not a superset of ascii.", - default_encoding_c); - goto bad; - } - Py_DECREF(ascii_chars_u); - Py_DECREF(ascii_chars_b); - } - Py_DECREF(default_encoding); - return 0; -bad: - Py_XDECREF(default_encoding); - Py_XDECREF(ascii_chars_u); - Py_XDECREF(ascii_chars_b); - return -1; -} -#endif -#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT && PY_MAJOR_VERSION >= 3 -#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_DecodeUTF8(c_str, size, NULL) -#else -#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_Decode(c_str, size, __PYX_DEFAULT_STRING_ENCODING, NULL) -#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT -#include -static char* __PYX_DEFAULT_STRING_ENCODING; -static int __Pyx_init_sys_getdefaultencoding_params(void) { - PyObject* sys; - PyObject* default_encoding = NULL; - char* default_encoding_c; - sys = PyImport_ImportModule("sys"); - if (!sys) goto bad; - default_encoding = PyObject_CallMethod(sys, (char*) (const char*) "getdefaultencoding", NULL); - Py_DECREF(sys); - if (!default_encoding) goto bad; - default_encoding_c = PyBytes_AsString(default_encoding); - if (!default_encoding_c) goto bad; - __PYX_DEFAULT_STRING_ENCODING = (char*) malloc(strlen(default_encoding_c) + 1); - if (!__PYX_DEFAULT_STRING_ENCODING) goto bad; - strcpy(__PYX_DEFAULT_STRING_ENCODING, default_encoding_c); - Py_DECREF(default_encoding); - return 0; -bad: - Py_XDECREF(default_encoding); - return -1; -} -#endif -#endif - - -/* Test for GCC > 2.95 */ -#if defined(__GNUC__) && (__GNUC__ > 2 || (__GNUC__ == 2 && (__GNUC_MINOR__ > 95))) - #define likely(x) __builtin_expect(!!(x), 1) - #define unlikely(x) __builtin_expect(!!(x), 0) -#else /* !__GNUC__ or GCC < 2.95 */ - #define likely(x) (x) - #define unlikely(x) (x) -#endif /* __GNUC__ */ -static CYTHON_INLINE void __Pyx_pretend_to_initialize(void* ptr) { (void)ptr; } - -#if !CYTHON_USE_MODULE_STATE -static PyObject *__pyx_m = NULL; -#endif -static int __pyx_lineno; -static int __pyx_clineno = 0; -static const char * __pyx_cfilenm = __FILE__; -static const char *__pyx_filename; - -/* Header.proto */ -#if !defined(CYTHON_CCOMPLEX) - #if defined(__cplusplus) - #define CYTHON_CCOMPLEX 1 - #elif (defined(_Complex_I) && !defined(_MSC_VER)) || ((defined (__STDC_VERSION__) && __STDC_VERSION__ >= 201112L) && !defined(__STDC_NO_COMPLEX__) && !defined(_MSC_VER)) - #define CYTHON_CCOMPLEX 1 - #else - #define CYTHON_CCOMPLEX 0 - #endif -#endif -#if CYTHON_CCOMPLEX - #ifdef __cplusplus - #include - #else - #include - #endif -#endif -#if CYTHON_CCOMPLEX && !defined(__cplusplus) && defined(__sun__) && defined(__GNUC__) - #undef _Complex_I - #define _Complex_I 1.0fj -#endif - -/* #### Code section: filename_table ### */ - -static const char *__pyx_f[] = { - "rednose/helpers/ekf_sym_pyx.pyx", - "", - "__init__.cython-30.pxd", - "type.pxd", -}; -/* #### Code section: utility_code_proto_before_types ### */ -/* ForceInitThreads.proto */ -#ifndef __PYX_FORCE_INIT_THREADS - #define __PYX_FORCE_INIT_THREADS 0 -#endif - -/* NoFastGil.proto */ -#define __Pyx_PyGILState_Ensure PyGILState_Ensure -#define __Pyx_PyGILState_Release PyGILState_Release -#define __Pyx_FastGIL_Remember() -#define __Pyx_FastGIL_Forget() -#define __Pyx_FastGilFuncInit() - -/* BufferFormatStructs.proto */ -struct __Pyx_StructField_; -#define __PYX_BUF_FLAGS_PACKED_STRUCT (1 << 0) -typedef struct { - const char* name; - struct __Pyx_StructField_* fields; - size_t size; - size_t arraysize[8]; - int ndim; - char typegroup; - char is_unsigned; - int flags; -} __Pyx_TypeInfo; -typedef struct __Pyx_StructField_ { - __Pyx_TypeInfo* type; - const char* name; - size_t offset; -} __Pyx_StructField; -typedef struct { - __Pyx_StructField* field; - size_t parent_offset; -} __Pyx_BufFmt_StackElem; -typedef struct { - __Pyx_StructField root; - __Pyx_BufFmt_StackElem* head; - size_t fmt_offset; - size_t new_count, enc_count; - size_t struct_alignment; - int is_complex; - char enc_type; - char new_packmode; - char enc_packmode; - char is_valid_array; -} __Pyx_BufFmt_Context; - -/* Atomics.proto */ -#include -#ifndef CYTHON_ATOMICS - #define CYTHON_ATOMICS 1 -#endif -#define __PYX_CYTHON_ATOMICS_ENABLED() CYTHON_ATOMICS -#define __pyx_atomic_int_type int -#define __pyx_nonatomic_int_type int -#if CYTHON_ATOMICS && (defined(__STDC_VERSION__) &&\ - (__STDC_VERSION__ >= 201112L) &&\ - !defined(__STDC_NO_ATOMICS__)) - #include -#elif CYTHON_ATOMICS && (defined(__cplusplus) && (\ - (__cplusplus >= 201103L) ||\ - (defined(_MSC_VER) && _MSC_VER >= 1700))) - #include -#endif -#if CYTHON_ATOMICS && (defined(__STDC_VERSION__) &&\ - (__STDC_VERSION__ >= 201112L) &&\ - !defined(__STDC_NO_ATOMICS__) &&\ - ATOMIC_INT_LOCK_FREE == 2) - #undef __pyx_atomic_int_type - #define __pyx_atomic_int_type atomic_int - #define __pyx_atomic_incr_aligned(value) atomic_fetch_add_explicit(value, 1, memory_order_relaxed) - #define __pyx_atomic_decr_aligned(value) atomic_fetch_sub_explicit(value, 1, memory_order_acq_rel) - #if defined(__PYX_DEBUG_ATOMICS) && defined(_MSC_VER) - #pragma message ("Using standard C atomics") - #elif defined(__PYX_DEBUG_ATOMICS) - #warning "Using standard C atomics" - #endif -#elif CYTHON_ATOMICS && (defined(__cplusplus) && (\ - (__cplusplus >= 201103L) ||\ -\ - (defined(_MSC_VER) && _MSC_VER >= 1700)) &&\ - ATOMIC_INT_LOCK_FREE == 2) - #undef __pyx_atomic_int_type - #define __pyx_atomic_int_type std::atomic_int - #define __pyx_atomic_incr_aligned(value) std::atomic_fetch_add_explicit(value, 1, std::memory_order_relaxed) - #define __pyx_atomic_decr_aligned(value) std::atomic_fetch_sub_explicit(value, 1, std::memory_order_acq_rel) - #if defined(__PYX_DEBUG_ATOMICS) && defined(_MSC_VER) - #pragma message ("Using standard C++ atomics") - #elif defined(__PYX_DEBUG_ATOMICS) - #warning "Using standard C++ atomics" - #endif -#elif CYTHON_ATOMICS && (__GNUC__ >= 5 || (__GNUC__ == 4 &&\ - (__GNUC_MINOR__ > 1 ||\ - (__GNUC_MINOR__ == 1 && __GNUC_PATCHLEVEL__ >= 2)))) - #define __pyx_atomic_incr_aligned(value) __sync_fetch_and_add(value, 1) - #define __pyx_atomic_decr_aligned(value) __sync_fetch_and_sub(value, 1) - #ifdef __PYX_DEBUG_ATOMICS - #warning "Using GNU atomics" - #endif -#elif CYTHON_ATOMICS && defined(_MSC_VER) - #include - #undef __pyx_atomic_int_type - #define __pyx_atomic_int_type long - #undef __pyx_nonatomic_int_type - #define __pyx_nonatomic_int_type long - #pragma intrinsic (_InterlockedExchangeAdd) - #define __pyx_atomic_incr_aligned(value) _InterlockedExchangeAdd(value, 1) - #define __pyx_atomic_decr_aligned(value) _InterlockedExchangeAdd(value, -1) - #ifdef __PYX_DEBUG_ATOMICS - #pragma message ("Using MSVC atomics") - #endif -#else - #undef CYTHON_ATOMICS - #define CYTHON_ATOMICS 0 - #ifdef __PYX_DEBUG_ATOMICS - #warning "Not using atomics" - #endif -#endif -#if CYTHON_ATOMICS - #define __pyx_add_acquisition_count(memview)\ - __pyx_atomic_incr_aligned(__pyx_get_slice_count_pointer(memview)) - #define __pyx_sub_acquisition_count(memview)\ - __pyx_atomic_decr_aligned(__pyx_get_slice_count_pointer(memview)) -#else - #define __pyx_add_acquisition_count(memview)\ - __pyx_add_acquisition_count_locked(__pyx_get_slice_count_pointer(memview), memview->lock) - #define __pyx_sub_acquisition_count(memview)\ - __pyx_sub_acquisition_count_locked(__pyx_get_slice_count_pointer(memview), memview->lock) -#endif - -/* MemviewSliceStruct.proto */ -struct __pyx_memoryview_obj; -typedef struct { - struct __pyx_memoryview_obj *memview; - char *data; - Py_ssize_t shape[8]; - Py_ssize_t strides[8]; - Py_ssize_t suboffsets[8]; -} __Pyx_memviewslice; -#define __Pyx_MemoryView_Len(m) (m.shape[0]) - -/* #### Code section: numeric_typedefs ### */ - -/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":730 - * # in Cython to enable them only on the right systems. - * - * ctypedef npy_int8 int8_t # <<<<<<<<<<<<<< - * ctypedef npy_int16 int16_t - * ctypedef npy_int32 int32_t - */ -typedef npy_int8 __pyx_t_5numpy_int8_t; - -/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":731 - * - * ctypedef npy_int8 int8_t - * ctypedef npy_int16 int16_t # <<<<<<<<<<<<<< - * ctypedef npy_int32 int32_t - * ctypedef npy_int64 int64_t - */ -typedef npy_int16 __pyx_t_5numpy_int16_t; - -/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":732 - * ctypedef npy_int8 int8_t - * ctypedef npy_int16 int16_t - * ctypedef npy_int32 int32_t # <<<<<<<<<<<<<< - * ctypedef npy_int64 int64_t - * #ctypedef npy_int96 int96_t - */ -typedef npy_int32 __pyx_t_5numpy_int32_t; - -/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":733 - * ctypedef npy_int16 int16_t - * ctypedef npy_int32 int32_t - * ctypedef npy_int64 int64_t # <<<<<<<<<<<<<< - * #ctypedef npy_int96 int96_t - * #ctypedef npy_int128 int128_t - */ -typedef npy_int64 __pyx_t_5numpy_int64_t; - -/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":737 - * #ctypedef npy_int128 int128_t - * - * ctypedef npy_uint8 uint8_t # <<<<<<<<<<<<<< - * ctypedef npy_uint16 uint16_t - * ctypedef npy_uint32 uint32_t - */ -typedef npy_uint8 __pyx_t_5numpy_uint8_t; - -/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":738 - * - * ctypedef npy_uint8 uint8_t - * ctypedef npy_uint16 uint16_t # <<<<<<<<<<<<<< - * ctypedef npy_uint32 uint32_t - * ctypedef npy_uint64 uint64_t - */ -typedef npy_uint16 __pyx_t_5numpy_uint16_t; - -/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":739 - * ctypedef npy_uint8 uint8_t - * ctypedef npy_uint16 uint16_t - * ctypedef npy_uint32 uint32_t # <<<<<<<<<<<<<< - * ctypedef npy_uint64 uint64_t - * #ctypedef npy_uint96 uint96_t - */ -typedef npy_uint32 __pyx_t_5numpy_uint32_t; - -/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":740 - * ctypedef npy_uint16 uint16_t - * ctypedef npy_uint32 uint32_t - * ctypedef npy_uint64 uint64_t # <<<<<<<<<<<<<< - * #ctypedef npy_uint96 uint96_t - * #ctypedef npy_uint128 uint128_t - */ -typedef npy_uint64 __pyx_t_5numpy_uint64_t; - -/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":744 - * #ctypedef npy_uint128 uint128_t - * - * ctypedef npy_float32 float32_t # <<<<<<<<<<<<<< - * ctypedef npy_float64 float64_t - * #ctypedef npy_float80 float80_t - */ -typedef npy_float32 __pyx_t_5numpy_float32_t; - -/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":745 - * - * ctypedef npy_float32 float32_t - * ctypedef npy_float64 float64_t # <<<<<<<<<<<<<< - * #ctypedef npy_float80 float80_t - * #ctypedef npy_float128 float128_t - */ -typedef npy_float64 __pyx_t_5numpy_float64_t; - -/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":754 - * # The int types are mapped a bit surprising -- - * # numpy.int corresponds to 'l' and numpy.long to 'q' - * ctypedef npy_long int_t # <<<<<<<<<<<<<< - * ctypedef npy_longlong longlong_t - * - */ -typedef npy_long __pyx_t_5numpy_int_t; - -/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":755 - * # numpy.int corresponds to 'l' and numpy.long to 'q' - * ctypedef npy_long int_t - * ctypedef npy_longlong longlong_t # <<<<<<<<<<<<<< - * - * ctypedef npy_ulong uint_t - */ -typedef npy_longlong __pyx_t_5numpy_longlong_t; - -/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":757 - * ctypedef npy_longlong longlong_t - * - * ctypedef npy_ulong uint_t # <<<<<<<<<<<<<< - * ctypedef npy_ulonglong ulonglong_t - * - */ -typedef npy_ulong __pyx_t_5numpy_uint_t; - -/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":758 - * - * ctypedef npy_ulong uint_t - * ctypedef npy_ulonglong ulonglong_t # <<<<<<<<<<<<<< - * - * ctypedef npy_intp intp_t - */ -typedef npy_ulonglong __pyx_t_5numpy_ulonglong_t; - -/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":760 - * ctypedef npy_ulonglong ulonglong_t - * - * ctypedef npy_intp intp_t # <<<<<<<<<<<<<< - * ctypedef npy_uintp uintp_t - * - */ -typedef npy_intp __pyx_t_5numpy_intp_t; - -/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":761 - * - * ctypedef npy_intp intp_t - * ctypedef npy_uintp uintp_t # <<<<<<<<<<<<<< - * - * ctypedef npy_double float_t - */ -typedef npy_uintp __pyx_t_5numpy_uintp_t; - -/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":763 - * ctypedef npy_uintp uintp_t - * - * ctypedef npy_double float_t # <<<<<<<<<<<<<< - * ctypedef npy_double double_t - * ctypedef npy_longdouble longdouble_t - */ -typedef npy_double __pyx_t_5numpy_float_t; - -/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":764 - * - * ctypedef npy_double float_t - * ctypedef npy_double double_t # <<<<<<<<<<<<<< - * ctypedef npy_longdouble longdouble_t - * - */ -typedef npy_double __pyx_t_5numpy_double_t; - -/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":765 - * ctypedef npy_double float_t - * ctypedef npy_double double_t - * ctypedef npy_longdouble longdouble_t # <<<<<<<<<<<<<< - * - * ctypedef npy_cfloat cfloat_t - */ -typedef npy_longdouble __pyx_t_5numpy_longdouble_t; -/* #### Code section: complex_type_declarations ### */ -/* Declarations.proto */ -#if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) - #ifdef __cplusplus - typedef ::std::complex< float > __pyx_t_float_complex; - #else - typedef float _Complex __pyx_t_float_complex; - #endif -#else - typedef struct { float real, imag; } __pyx_t_float_complex; -#endif -static CYTHON_INLINE __pyx_t_float_complex __pyx_t_float_complex_from_parts(float, float); - -/* Declarations.proto */ -#if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) - #ifdef __cplusplus - typedef ::std::complex< double > __pyx_t_double_complex; - #else - typedef double _Complex __pyx_t_double_complex; - #endif -#else - typedef struct { double real, imag; } __pyx_t_double_complex; -#endif -static CYTHON_INLINE __pyx_t_double_complex __pyx_t_double_complex_from_parts(double, double); - -/* #### Code section: type_declarations ### */ - -/*--- Type declarations ---*/ -struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx; -struct __pyx_array_obj; -struct __pyx_MemviewEnum_obj; -struct __pyx_memoryview_obj; -struct __pyx_memoryviewslice_obj; - -/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":767 - * ctypedef npy_longdouble longdouble_t - * - * ctypedef npy_cfloat cfloat_t # <<<<<<<<<<<<<< - * ctypedef npy_cdouble cdouble_t - * ctypedef npy_clongdouble clongdouble_t - */ -typedef npy_cfloat __pyx_t_5numpy_cfloat_t; - -/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":768 - * - * ctypedef npy_cfloat cfloat_t - * ctypedef npy_cdouble cdouble_t # <<<<<<<<<<<<<< - * ctypedef npy_clongdouble clongdouble_t - * - */ -typedef npy_cdouble __pyx_t_5numpy_cdouble_t; - -/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":769 - * ctypedef npy_cfloat cfloat_t - * ctypedef npy_cdouble cdouble_t - * ctypedef npy_clongdouble clongdouble_t # <<<<<<<<<<<<<< - * - * ctypedef npy_cdouble complex_t - */ -typedef npy_clongdouble __pyx_t_5numpy_clongdouble_t; - -/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":771 - * ctypedef npy_clongdouble clongdouble_t - * - * ctypedef npy_cdouble complex_t # <<<<<<<<<<<<<< - * - * cdef inline object PyArray_MultiIterNew1(a): - */ -typedef npy_cdouble __pyx_t_5numpy_complex_t; - -/* "rednose/helpers/ekf_sym_pyx.pyx":85 - * return np.copy(np.asarray(mem_view, dtype=np.double, order="C")) - * - * cdef class EKF_sym_pyx: # <<<<<<<<<<<<<< - * cdef EKFSym* ekf - * def __cinit__(self, str gen_dir, str name, np.ndarray[np.float64_t, ndim=2] Q, - */ -struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx { - PyObject_HEAD - EKFS::EKFSym *ekf; -}; - - -/* "View.MemoryView":114 - * @cython.collection_type("sequence") - * @cname("__pyx_array") - * cdef class array: # <<<<<<<<<<<<<< - * - * cdef: - */ -struct __pyx_array_obj { - PyObject_HEAD - struct __pyx_vtabstruct_array *__pyx_vtab; - char *data; - Py_ssize_t len; - char *format; - int ndim; - Py_ssize_t *_shape; - Py_ssize_t *_strides; - Py_ssize_t itemsize; - PyObject *mode; - PyObject *_format; - void (*callback_free_data)(void *); - int free_data; - int dtype_is_object; -}; - - -/* "View.MemoryView":302 - * - * @cname('__pyx_MemviewEnum') - * cdef class Enum(object): # <<<<<<<<<<<<<< - * cdef object name - * def __init__(self, name): - */ -struct __pyx_MemviewEnum_obj { - PyObject_HEAD - PyObject *name; -}; - - -/* "View.MemoryView":337 - * - * @cname('__pyx_memoryview') - * cdef class memoryview: # <<<<<<<<<<<<<< - * - * cdef object obj - */ -struct __pyx_memoryview_obj { - PyObject_HEAD - struct __pyx_vtabstruct_memoryview *__pyx_vtab; - PyObject *obj; - PyObject *_size; - PyObject *_array_interface; - PyThread_type_lock lock; - __pyx_atomic_int_type acquisition_count; - Py_buffer view; - int flags; - int dtype_is_object; - __Pyx_TypeInfo *typeinfo; -}; - - -/* "View.MemoryView":952 - * @cython.collection_type("sequence") - * @cname('__pyx_memoryviewslice') - * cdef class _memoryviewslice(memoryview): # <<<<<<<<<<<<<< - * "Internal class for passing memoryview slices to Python" - * - */ -struct __pyx_memoryviewslice_obj { - struct __pyx_memoryview_obj __pyx_base; - __Pyx_memviewslice from_slice; - PyObject *from_object; - PyObject *(*to_object_func)(char *); - int (*to_dtype_func)(char *, PyObject *); -}; - - - -/* "View.MemoryView":114 - * @cython.collection_type("sequence") - * @cname("__pyx_array") - * cdef class array: # <<<<<<<<<<<<<< - * - * cdef: - */ - -struct __pyx_vtabstruct_array { - PyObject *(*get_memview)(struct __pyx_array_obj *); -}; -static struct __pyx_vtabstruct_array *__pyx_vtabptr_array; - - -/* "View.MemoryView":337 - * - * @cname('__pyx_memoryview') - * cdef class memoryview: # <<<<<<<<<<<<<< - * - * cdef object obj - */ - -struct __pyx_vtabstruct_memoryview { - char *(*get_item_pointer)(struct __pyx_memoryview_obj *, PyObject *); - PyObject *(*is_slice)(struct __pyx_memoryview_obj *, PyObject *); - PyObject *(*setitem_slice_assignment)(struct __pyx_memoryview_obj *, PyObject *, PyObject *); - PyObject *(*setitem_slice_assign_scalar)(struct __pyx_memoryview_obj *, struct __pyx_memoryview_obj *, PyObject *); - PyObject *(*setitem_indexed)(struct __pyx_memoryview_obj *, PyObject *, PyObject *); - PyObject *(*convert_item_to_object)(struct __pyx_memoryview_obj *, char *); - PyObject *(*assign_item_from_object)(struct __pyx_memoryview_obj *, char *, PyObject *); - PyObject *(*_get_base)(struct __pyx_memoryview_obj *); -}; -static struct __pyx_vtabstruct_memoryview *__pyx_vtabptr_memoryview; - - -/* "View.MemoryView":952 - * @cython.collection_type("sequence") - * @cname('__pyx_memoryviewslice') - * cdef class _memoryviewslice(memoryview): # <<<<<<<<<<<<<< - * "Internal class for passing memoryview slices to Python" - * - */ - -struct __pyx_vtabstruct__memoryviewslice { - struct __pyx_vtabstruct_memoryview __pyx_base; -}; -static struct __pyx_vtabstruct__memoryviewslice *__pyx_vtabptr__memoryviewslice; -/* #### Code section: utility_code_proto ### */ - -/* --- Runtime support code (head) --- */ -/* Refnanny.proto */ -#ifndef CYTHON_REFNANNY - #define CYTHON_REFNANNY 0 -#endif -#if CYTHON_REFNANNY - typedef struct { - void (*INCREF)(void*, PyObject*, Py_ssize_t); - void (*DECREF)(void*, PyObject*, Py_ssize_t); - void (*GOTREF)(void*, PyObject*, Py_ssize_t); - void (*GIVEREF)(void*, PyObject*, Py_ssize_t); - void* (*SetupContext)(const char*, Py_ssize_t, const char*); - void (*FinishContext)(void**); - } __Pyx_RefNannyAPIStruct; - static __Pyx_RefNannyAPIStruct *__Pyx_RefNanny = NULL; - static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname); - #define __Pyx_RefNannyDeclarations void *__pyx_refnanny = NULL; -#ifdef WITH_THREAD - #define __Pyx_RefNannySetupContext(name, acquire_gil)\ - if (acquire_gil) {\ - PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ - __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ - PyGILState_Release(__pyx_gilstate_save);\ - } else {\ - __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ - } - #define __Pyx_RefNannyFinishContextNogil() {\ - PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ - __Pyx_RefNannyFinishContext();\ - PyGILState_Release(__pyx_gilstate_save);\ - } -#else - #define __Pyx_RefNannySetupContext(name, acquire_gil)\ - __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__)) - #define __Pyx_RefNannyFinishContextNogil() __Pyx_RefNannyFinishContext() -#endif - #define __Pyx_RefNannyFinishContextNogil() {\ - PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ - __Pyx_RefNannyFinishContext();\ - PyGILState_Release(__pyx_gilstate_save);\ - } - #define __Pyx_RefNannyFinishContext()\ - __Pyx_RefNanny->FinishContext(&__pyx_refnanny) - #define __Pyx_INCREF(r) __Pyx_RefNanny->INCREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) - #define __Pyx_DECREF(r) __Pyx_RefNanny->DECREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) - #define __Pyx_GOTREF(r) __Pyx_RefNanny->GOTREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) - #define __Pyx_GIVEREF(r) __Pyx_RefNanny->GIVEREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) - #define __Pyx_XINCREF(r) do { if((r) == NULL); else {__Pyx_INCREF(r); }} while(0) - #define __Pyx_XDECREF(r) do { if((r) == NULL); else {__Pyx_DECREF(r); }} while(0) - #define __Pyx_XGOTREF(r) do { if((r) == NULL); else {__Pyx_GOTREF(r); }} while(0) - #define __Pyx_XGIVEREF(r) do { if((r) == NULL); else {__Pyx_GIVEREF(r);}} while(0) -#else - #define __Pyx_RefNannyDeclarations - #define __Pyx_RefNannySetupContext(name, acquire_gil) - #define __Pyx_RefNannyFinishContextNogil() - #define __Pyx_RefNannyFinishContext() - #define __Pyx_INCREF(r) Py_INCREF(r) - #define __Pyx_DECREF(r) Py_DECREF(r) - #define __Pyx_GOTREF(r) - #define __Pyx_GIVEREF(r) - #define __Pyx_XINCREF(r) Py_XINCREF(r) - #define __Pyx_XDECREF(r) Py_XDECREF(r) - #define __Pyx_XGOTREF(r) - #define __Pyx_XGIVEREF(r) -#endif -#define __Pyx_Py_XDECREF_SET(r, v) do {\ - PyObject *tmp = (PyObject *) r;\ - r = v; Py_XDECREF(tmp);\ - } while (0) -#define __Pyx_XDECREF_SET(r, v) do {\ - PyObject *tmp = (PyObject *) r;\ - r = v; __Pyx_XDECREF(tmp);\ - } while (0) -#define __Pyx_DECREF_SET(r, v) do {\ - PyObject *tmp = (PyObject *) r;\ - r = v; __Pyx_DECREF(tmp);\ - } while (0) -#define __Pyx_CLEAR(r) do { PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);} while(0) -#define __Pyx_XCLEAR(r) do { if((r) != NULL) {PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);}} while(0) - -/* PyErrExceptionMatches.proto */ -#if CYTHON_FAST_THREAD_STATE -#define __Pyx_PyErr_ExceptionMatches(err) __Pyx_PyErr_ExceptionMatchesInState(__pyx_tstate, err) -static CYTHON_INLINE int __Pyx_PyErr_ExceptionMatchesInState(PyThreadState* tstate, PyObject* err); -#else -#define __Pyx_PyErr_ExceptionMatches(err) PyErr_ExceptionMatches(err) -#endif - -/* PyThreadStateGet.proto */ -#if CYTHON_FAST_THREAD_STATE -#define __Pyx_PyThreadState_declare PyThreadState *__pyx_tstate; -#define __Pyx_PyThreadState_assign __pyx_tstate = __Pyx_PyThreadState_Current; -#if PY_VERSION_HEX >= 0x030C00A6 -#define __Pyx_PyErr_Occurred() (__pyx_tstate->current_exception != NULL) -#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->current_exception ? (PyObject*) Py_TYPE(__pyx_tstate->current_exception) : (PyObject*) NULL) -#else -#define __Pyx_PyErr_Occurred() (__pyx_tstate->curexc_type != NULL) -#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->curexc_type) -#endif -#else -#define __Pyx_PyThreadState_declare -#define __Pyx_PyThreadState_assign -#define __Pyx_PyErr_Occurred() (PyErr_Occurred() != NULL) -#define __Pyx_PyErr_CurrentExceptionType() PyErr_Occurred() -#endif - -/* PyErrFetchRestore.proto */ -#if CYTHON_FAST_THREAD_STATE -#define __Pyx_PyErr_Clear() __Pyx_ErrRestore(NULL, NULL, NULL) -#define __Pyx_ErrRestoreWithState(type, value, tb) __Pyx_ErrRestoreInState(PyThreadState_GET(), type, value, tb) -#define __Pyx_ErrFetchWithState(type, value, tb) __Pyx_ErrFetchInState(PyThreadState_GET(), type, value, tb) -#define __Pyx_ErrRestore(type, value, tb) __Pyx_ErrRestoreInState(__pyx_tstate, type, value, tb) -#define __Pyx_ErrFetch(type, value, tb) __Pyx_ErrFetchInState(__pyx_tstate, type, value, tb) -static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb); -static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); -#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A6 -#define __Pyx_PyErr_SetNone(exc) (Py_INCREF(exc), __Pyx_ErrRestore((exc), NULL, NULL)) -#else -#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) -#endif -#else -#define __Pyx_PyErr_Clear() PyErr_Clear() -#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) -#define __Pyx_ErrRestoreWithState(type, value, tb) PyErr_Restore(type, value, tb) -#define __Pyx_ErrFetchWithState(type, value, tb) PyErr_Fetch(type, value, tb) -#define __Pyx_ErrRestoreInState(tstate, type, value, tb) PyErr_Restore(type, value, tb) -#define __Pyx_ErrFetchInState(tstate, type, value, tb) PyErr_Fetch(type, value, tb) -#define __Pyx_ErrRestore(type, value, tb) PyErr_Restore(type, value, tb) -#define __Pyx_ErrFetch(type, value, tb) PyErr_Fetch(type, value, tb) -#endif - -/* PyObjectGetAttrStr.proto */ -#if CYTHON_USE_TYPE_SLOTS -static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name); -#else -#define __Pyx_PyObject_GetAttrStr(o,n) PyObject_GetAttr(o,n) -#endif - -/* PyObjectGetAttrStrNoError.proto */ -static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name); - -/* GetBuiltinName.proto */ -static PyObject *__Pyx_GetBuiltinName(PyObject *name); - -/* TupleAndListFromArray.proto */ -#if CYTHON_COMPILING_IN_CPYTHON -static CYTHON_INLINE PyObject* __Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n); -static CYTHON_INLINE PyObject* __Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n); -#endif - -/* IncludeStringH.proto */ -#include - -/* BytesEquals.proto */ -static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals); - -/* UnicodeEquals.proto */ -static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals); - -/* fastcall.proto */ -#if CYTHON_AVOID_BORROWED_REFS - #define __Pyx_Arg_VARARGS(args, i) PySequence_GetItem(args, i) -#elif CYTHON_ASSUME_SAFE_MACROS - #define __Pyx_Arg_VARARGS(args, i) PyTuple_GET_ITEM(args, i) -#else - #define __Pyx_Arg_VARARGS(args, i) PyTuple_GetItem(args, i) -#endif -#if CYTHON_AVOID_BORROWED_REFS - #define __Pyx_Arg_NewRef_VARARGS(arg) __Pyx_NewRef(arg) - #define __Pyx_Arg_XDECREF_VARARGS(arg) Py_XDECREF(arg) -#else - #define __Pyx_Arg_NewRef_VARARGS(arg) arg - #define __Pyx_Arg_XDECREF_VARARGS(arg) -#endif -#define __Pyx_NumKwargs_VARARGS(kwds) PyDict_Size(kwds) -#define __Pyx_KwValues_VARARGS(args, nargs) NULL -#define __Pyx_GetKwValue_VARARGS(kw, kwvalues, s) __Pyx_PyDict_GetItemStrWithError(kw, s) -#define __Pyx_KwargsAsDict_VARARGS(kw, kwvalues) PyDict_Copy(kw) -#if CYTHON_METH_FASTCALL - #define __Pyx_Arg_FASTCALL(args, i) args[i] - #define __Pyx_NumKwargs_FASTCALL(kwds) PyTuple_GET_SIZE(kwds) - #define __Pyx_KwValues_FASTCALL(args, nargs) ((args) + (nargs)) - static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s); -#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030d0000 - CYTHON_UNUSED static PyObject *__Pyx_KwargsAsDict_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues); - #else - #define __Pyx_KwargsAsDict_FASTCALL(kw, kwvalues) _PyStack_AsDict(kwvalues, kw) - #endif - #define __Pyx_Arg_NewRef_FASTCALL(arg) arg /* no-op, __Pyx_Arg_FASTCALL is direct and this needs - to have the same reference counting */ - #define __Pyx_Arg_XDECREF_FASTCALL(arg) -#else - #define __Pyx_Arg_FASTCALL __Pyx_Arg_VARARGS - #define __Pyx_NumKwargs_FASTCALL __Pyx_NumKwargs_VARARGS - #define __Pyx_KwValues_FASTCALL __Pyx_KwValues_VARARGS - #define __Pyx_GetKwValue_FASTCALL __Pyx_GetKwValue_VARARGS - #define __Pyx_KwargsAsDict_FASTCALL __Pyx_KwargsAsDict_VARARGS - #define __Pyx_Arg_NewRef_FASTCALL(arg) __Pyx_Arg_NewRef_VARARGS(arg) - #define __Pyx_Arg_XDECREF_FASTCALL(arg) __Pyx_Arg_XDECREF_VARARGS(arg) -#endif -#if CYTHON_COMPILING_IN_CPYTHON && CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS -#define __Pyx_ArgsSlice_VARARGS(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_VARARGS(args, start), stop - start) -#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_FASTCALL(args, start), stop - start) -#else -#define __Pyx_ArgsSlice_VARARGS(args, start, stop) PyTuple_GetSlice(args, start, stop) -#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) PyTuple_GetSlice(args, start, stop) -#endif - -/* RaiseArgTupleInvalid.proto */ -static void __Pyx_RaiseArgtupleInvalid(const char* func_name, int exact, - Py_ssize_t num_min, Py_ssize_t num_max, Py_ssize_t num_found); - -/* RaiseDoubleKeywords.proto */ -static void __Pyx_RaiseDoubleKeywordsError(const char* func_name, PyObject* kw_name); - -/* ParseKeywords.proto */ -static int __Pyx_ParseOptionalKeywords(PyObject *kwds, PyObject *const *kwvalues, - PyObject **argnames[], - PyObject *kwds2, PyObject *values[], Py_ssize_t num_pos_args, - const char* function_name); - -/* ArgTypeTest.proto */ -#define __Pyx_ArgTypeTest(obj, type, none_allowed, name, exact)\ - ((likely(__Pyx_IS_TYPE(obj, type) | (none_allowed && (obj == Py_None)))) ? 1 :\ - __Pyx__ArgTypeTest(obj, type, name, exact)) -static int __Pyx__ArgTypeTest(PyObject *obj, PyTypeObject *type, const char *name, int exact); - -/* RaiseException.proto */ -static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause); - -/* PyFunctionFastCall.proto */ -#if CYTHON_FAST_PYCALL -#if !CYTHON_VECTORCALL -#define __Pyx_PyFunction_FastCall(func, args, nargs)\ - __Pyx_PyFunction_FastCallDict((func), (args), (nargs), NULL) -static PyObject *__Pyx_PyFunction_FastCallDict(PyObject *func, PyObject **args, Py_ssize_t nargs, PyObject *kwargs); -#endif -#define __Pyx_BUILD_ASSERT_EXPR(cond)\ - (sizeof(char [1 - 2*!(cond)]) - 1) -#ifndef Py_MEMBER_SIZE -#define Py_MEMBER_SIZE(type, member) sizeof(((type *)0)->member) -#endif -#if !CYTHON_VECTORCALL -#if PY_VERSION_HEX >= 0x03080000 - #include "frameobject.h" -#if PY_VERSION_HEX >= 0x030b00a6 && !CYTHON_COMPILING_IN_LIMITED_API - #ifndef Py_BUILD_CORE - #define Py_BUILD_CORE 1 - #endif - #include "internal/pycore_frame.h" -#endif - #define __Pxy_PyFrame_Initialize_Offsets() - #define __Pyx_PyFrame_GetLocalsplus(frame) ((frame)->f_localsplus) -#else - static size_t __pyx_pyframe_localsplus_offset = 0; - #include "frameobject.h" - #define __Pxy_PyFrame_Initialize_Offsets()\ - ((void)__Pyx_BUILD_ASSERT_EXPR(sizeof(PyFrameObject) == offsetof(PyFrameObject, f_localsplus) + Py_MEMBER_SIZE(PyFrameObject, f_localsplus)),\ - (void)(__pyx_pyframe_localsplus_offset = ((size_t)PyFrame_Type.tp_basicsize) - Py_MEMBER_SIZE(PyFrameObject, f_localsplus))) - #define __Pyx_PyFrame_GetLocalsplus(frame)\ - (assert(__pyx_pyframe_localsplus_offset), (PyObject **)(((char *)(frame)) + __pyx_pyframe_localsplus_offset)) -#endif -#endif -#endif - -/* PyObjectCall.proto */ -#if CYTHON_COMPILING_IN_CPYTHON -static CYTHON_INLINE PyObject* __Pyx_PyObject_Call(PyObject *func, PyObject *arg, PyObject *kw); -#else -#define __Pyx_PyObject_Call(func, arg, kw) PyObject_Call(func, arg, kw) -#endif - -/* PyObjectCallMethO.proto */ -#if CYTHON_COMPILING_IN_CPYTHON -static CYTHON_INLINE PyObject* __Pyx_PyObject_CallMethO(PyObject *func, PyObject *arg); -#endif - -/* PyObjectFastCall.proto */ -#define __Pyx_PyObject_FastCall(func, args, nargs) __Pyx_PyObject_FastCallDict(func, args, (size_t)(nargs), NULL) -static CYTHON_INLINE PyObject* __Pyx_PyObject_FastCallDict(PyObject *func, PyObject **args, size_t nargs, PyObject *kwargs); - -/* RaiseUnexpectedTypeError.proto */ -static int __Pyx_RaiseUnexpectedTypeError(const char *expected, PyObject *obj); - -/* GCCDiagnostics.proto */ -#if !defined(__INTEL_COMPILER) && defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 6)) -#define __Pyx_HAS_GCC_DIAGNOSTIC -#endif - -/* BuildPyUnicode.proto */ -static PyObject* __Pyx_PyUnicode_BuildFromAscii(Py_ssize_t ulength, char* chars, int clength, - int prepend_sign, char padding_char); - -/* CIntToPyUnicode.proto */ -static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_int(int value, Py_ssize_t width, char padding_char, char format_char); - -/* CIntToPyUnicode.proto */ -static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_Py_ssize_t(Py_ssize_t value, Py_ssize_t width, char padding_char, char format_char); - -/* JoinPyUnicode.proto */ -static PyObject* __Pyx_PyUnicode_Join(PyObject* value_tuple, Py_ssize_t value_count, Py_ssize_t result_ulength, - Py_UCS4 max_char); - -/* StrEquals.proto */ -#if PY_MAJOR_VERSION >= 3 -#define __Pyx_PyString_Equals __Pyx_PyUnicode_Equals -#else -#define __Pyx_PyString_Equals __Pyx_PyBytes_Equals -#endif - -/* PyObjectFormatSimple.proto */ -#if CYTHON_COMPILING_IN_PYPY - #define __Pyx_PyObject_FormatSimple(s, f) (\ - likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ - PyObject_Format(s, f)) -#elif PY_MAJOR_VERSION < 3 - #define __Pyx_PyObject_FormatSimple(s, f) (\ - likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ - likely(PyString_CheckExact(s)) ? PyUnicode_FromEncodedObject(s, NULL, "strict") :\ - PyObject_Format(s, f)) -#elif CYTHON_USE_TYPE_SLOTS - #define __Pyx_PyObject_FormatSimple(s, f) (\ - likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ - likely(PyLong_CheckExact(s)) ? PyLong_Type.tp_repr(s) :\ - likely(PyFloat_CheckExact(s)) ? PyFloat_Type.tp_repr(s) :\ - PyObject_Format(s, f)) -#else - #define __Pyx_PyObject_FormatSimple(s, f) (\ - likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ - PyObject_Format(s, f)) -#endif - -CYTHON_UNUSED static int __pyx_array_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ -static PyObject *__pyx_array_get_memview(struct __pyx_array_obj *); /*proto*/ -/* GetAttr.proto */ -static CYTHON_INLINE PyObject *__Pyx_GetAttr(PyObject *, PyObject *); - -/* GetItemInt.proto */ -#define __Pyx_GetItemInt(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ - (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ - __Pyx_GetItemInt_Fast(o, (Py_ssize_t)i, is_list, wraparound, boundscheck) :\ - (is_list ? (PyErr_SetString(PyExc_IndexError, "list index out of range"), (PyObject*)NULL) :\ - __Pyx_GetItemInt_Generic(o, to_py_func(i)))) -#define __Pyx_GetItemInt_List(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ - (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ - __Pyx_GetItemInt_List_Fast(o, (Py_ssize_t)i, wraparound, boundscheck) :\ - (PyErr_SetString(PyExc_IndexError, "list index out of range"), (PyObject*)NULL)) -static CYTHON_INLINE PyObject *__Pyx_GetItemInt_List_Fast(PyObject *o, Py_ssize_t i, - int wraparound, int boundscheck); -#define __Pyx_GetItemInt_Tuple(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ - (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ - __Pyx_GetItemInt_Tuple_Fast(o, (Py_ssize_t)i, wraparound, boundscheck) :\ - (PyErr_SetString(PyExc_IndexError, "tuple index out of range"), (PyObject*)NULL)) -static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Tuple_Fast(PyObject *o, Py_ssize_t i, - int wraparound, int boundscheck); -static PyObject *__Pyx_GetItemInt_Generic(PyObject *o, PyObject* j); -static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Fast(PyObject *o, Py_ssize_t i, - int is_list, int wraparound, int boundscheck); - -/* PyObjectCallOneArg.proto */ -static CYTHON_INLINE PyObject* __Pyx_PyObject_CallOneArg(PyObject *func, PyObject *arg); - -/* ObjectGetItem.proto */ -#if CYTHON_USE_TYPE_SLOTS -static CYTHON_INLINE PyObject *__Pyx_PyObject_GetItem(PyObject *obj, PyObject *key); -#else -#define __Pyx_PyObject_GetItem(obj, key) PyObject_GetItem(obj, key) -#endif - -/* KeywordStringCheck.proto */ -static int __Pyx_CheckKeywordStrings(PyObject *kw, const char* function_name, int kw_allowed); - -/* DivInt[Py_ssize_t].proto */ -static CYTHON_INLINE Py_ssize_t __Pyx_div_Py_ssize_t(Py_ssize_t, Py_ssize_t); - -/* UnaryNegOverflows.proto */ -#define __Pyx_UNARY_NEG_WOULD_OVERFLOW(x)\ - (((x) < 0) & ((unsigned long)(x) == 0-(unsigned long)(x))) - -/* GetAttr3.proto */ -static CYTHON_INLINE PyObject *__Pyx_GetAttr3(PyObject *, PyObject *, PyObject *); - -/* PyDictVersioning.proto */ -#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS -#define __PYX_DICT_VERSION_INIT ((PY_UINT64_T) -1) -#define __PYX_GET_DICT_VERSION(dict) (((PyDictObject*)(dict))->ma_version_tag) -#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var)\ - (version_var) = __PYX_GET_DICT_VERSION(dict);\ - (cache_var) = (value); -#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) {\ - static PY_UINT64_T __pyx_dict_version = 0;\ - static PyObject *__pyx_dict_cached_value = NULL;\ - if (likely(__PYX_GET_DICT_VERSION(DICT) == __pyx_dict_version)) {\ - (VAR) = __pyx_dict_cached_value;\ - } else {\ - (VAR) = __pyx_dict_cached_value = (LOOKUP);\ - __pyx_dict_version = __PYX_GET_DICT_VERSION(DICT);\ - }\ -} -static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj); -static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj); -static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version); -#else -#define __PYX_GET_DICT_VERSION(dict) (0) -#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var) -#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) (VAR) = (LOOKUP); -#endif - -/* GetModuleGlobalName.proto */ -#if CYTHON_USE_DICT_VERSIONS -#define __Pyx_GetModuleGlobalName(var, name) do {\ - static PY_UINT64_T __pyx_dict_version = 0;\ - static PyObject *__pyx_dict_cached_value = NULL;\ - (var) = (likely(__pyx_dict_version == __PYX_GET_DICT_VERSION(__pyx_d))) ?\ - (likely(__pyx_dict_cached_value) ? __Pyx_NewRef(__pyx_dict_cached_value) : __Pyx_GetBuiltinName(name)) :\ - __Pyx__GetModuleGlobalName(name, &__pyx_dict_version, &__pyx_dict_cached_value);\ -} while(0) -#define __Pyx_GetModuleGlobalNameUncached(var, name) do {\ - PY_UINT64_T __pyx_dict_version;\ - PyObject *__pyx_dict_cached_value;\ - (var) = __Pyx__GetModuleGlobalName(name, &__pyx_dict_version, &__pyx_dict_cached_value);\ -} while(0) -static PyObject *__Pyx__GetModuleGlobalName(PyObject *name, PY_UINT64_T *dict_version, PyObject **dict_cached_value); -#else -#define __Pyx_GetModuleGlobalName(var, name) (var) = __Pyx__GetModuleGlobalName(name) -#define __Pyx_GetModuleGlobalNameUncached(var, name) (var) = __Pyx__GetModuleGlobalName(name) -static CYTHON_INLINE PyObject *__Pyx__GetModuleGlobalName(PyObject *name); -#endif - -/* AssertionsEnabled.proto */ -#if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX < 0x02070600 && !defined(Py_OptimizeFlag) - #define __Pyx_init_assertions_enabled() (0) - #define __pyx_assertions_enabled() (1) -#elif CYTHON_COMPILING_IN_LIMITED_API || (CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030C0000) - static int __pyx_assertions_enabled_flag; - #define __pyx_assertions_enabled() (__pyx_assertions_enabled_flag) - static int __Pyx_init_assertions_enabled(void) { - PyObject *builtins, *debug, *debug_str; - int flag; - builtins = PyEval_GetBuiltins(); - if (!builtins) goto bad; - debug_str = PyUnicode_FromStringAndSize("__debug__", 9); - if (!debug_str) goto bad; - debug = PyObject_GetItem(builtins, debug_str); - Py_DECREF(debug_str); - if (!debug) goto bad; - flag = PyObject_IsTrue(debug); - Py_DECREF(debug); - if (flag == -1) goto bad; - __pyx_assertions_enabled_flag = flag; - return 0; - bad: - __pyx_assertions_enabled_flag = 1; - return -1; - } -#else - #define __Pyx_init_assertions_enabled() (0) - #define __pyx_assertions_enabled() (!Py_OptimizeFlag) -#endif - -/* RaiseTooManyValuesToUnpack.proto */ -static CYTHON_INLINE void __Pyx_RaiseTooManyValuesError(Py_ssize_t expected); - -/* RaiseNeedMoreValuesToUnpack.proto */ -static CYTHON_INLINE void __Pyx_RaiseNeedMoreValuesError(Py_ssize_t index); - -/* RaiseNoneIterError.proto */ -static CYTHON_INLINE void __Pyx_RaiseNoneNotIterableError(void); - -/* ExtTypeTest.proto */ -static CYTHON_INLINE int __Pyx_TypeTest(PyObject *obj, PyTypeObject *type); - -/* GetTopmostException.proto */ -#if CYTHON_USE_EXC_INFO_STACK && CYTHON_FAST_THREAD_STATE -static _PyErr_StackItem * __Pyx_PyErr_GetTopmostException(PyThreadState *tstate); -#endif - -/* SaveResetException.proto */ -#if CYTHON_FAST_THREAD_STATE -#define __Pyx_ExceptionSave(type, value, tb) __Pyx__ExceptionSave(__pyx_tstate, type, value, tb) -static CYTHON_INLINE void __Pyx__ExceptionSave(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); -#define __Pyx_ExceptionReset(type, value, tb) __Pyx__ExceptionReset(__pyx_tstate, type, value, tb) -static CYTHON_INLINE void __Pyx__ExceptionReset(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb); -#else -#define __Pyx_ExceptionSave(type, value, tb) PyErr_GetExcInfo(type, value, tb) -#define __Pyx_ExceptionReset(type, value, tb) PyErr_SetExcInfo(type, value, tb) -#endif - -/* GetException.proto */ -#if CYTHON_FAST_THREAD_STATE -#define __Pyx_GetException(type, value, tb) __Pyx__GetException(__pyx_tstate, type, value, tb) -static int __Pyx__GetException(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); -#else -static int __Pyx_GetException(PyObject **type, PyObject **value, PyObject **tb); -#endif - -/* SwapException.proto */ -#if CYTHON_FAST_THREAD_STATE -#define __Pyx_ExceptionSwap(type, value, tb) __Pyx__ExceptionSwap(__pyx_tstate, type, value, tb) -static CYTHON_INLINE void __Pyx__ExceptionSwap(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); -#else -static CYTHON_INLINE void __Pyx_ExceptionSwap(PyObject **type, PyObject **value, PyObject **tb); -#endif - -/* Import.proto */ -static PyObject *__Pyx_Import(PyObject *name, PyObject *from_list, int level); - -/* ImportDottedModule.proto */ -static PyObject *__Pyx_ImportDottedModule(PyObject *name, PyObject *parts_tuple); -#if PY_MAJOR_VERSION >= 3 -static PyObject *__Pyx_ImportDottedModule_WalkParts(PyObject *module, PyObject *name, PyObject *parts_tuple); -#endif - -/* FastTypeChecks.proto */ -#if CYTHON_COMPILING_IN_CPYTHON -#define __Pyx_TypeCheck(obj, type) __Pyx_IsSubtype(Py_TYPE(obj), (PyTypeObject *)type) -#define __Pyx_TypeCheck2(obj, type1, type2) __Pyx_IsAnySubtype2(Py_TYPE(obj), (PyTypeObject *)type1, (PyTypeObject *)type2) -static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b); -static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b); -static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches(PyObject *err, PyObject *type); -static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches2(PyObject *err, PyObject *type1, PyObject *type2); -#else -#define __Pyx_TypeCheck(obj, type) PyObject_TypeCheck(obj, (PyTypeObject *)type) -#define __Pyx_TypeCheck2(obj, type1, type2) (PyObject_TypeCheck(obj, (PyTypeObject *)type1) || PyObject_TypeCheck(obj, (PyTypeObject *)type2)) -#define __Pyx_PyErr_GivenExceptionMatches(err, type) PyErr_GivenExceptionMatches(err, type) -#define __Pyx_PyErr_GivenExceptionMatches2(err, type1, type2) (PyErr_GivenExceptionMatches(err, type1) || PyErr_GivenExceptionMatches(err, type2)) -#endif -#define __Pyx_PyErr_ExceptionMatches2(err1, err2) __Pyx_PyErr_GivenExceptionMatches2(__Pyx_PyErr_CurrentExceptionType(), err1, err2) -#define __Pyx_PyException_Check(obj) __Pyx_TypeCheck(obj, PyExc_Exception) - -CYTHON_UNUSED static int __pyx_memoryview_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ -/* ListCompAppend.proto */ -#if CYTHON_USE_PYLIST_INTERNALS && CYTHON_ASSUME_SAFE_MACROS -static CYTHON_INLINE int __Pyx_ListComp_Append(PyObject* list, PyObject* x) { - PyListObject* L = (PyListObject*) list; - Py_ssize_t len = Py_SIZE(list); - if (likely(L->allocated > len)) { - Py_INCREF(x); - #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030d0000 - L->ob_item[len] = x; - #else - PyList_SET_ITEM(list, len, x); - #endif - __Pyx_SET_SIZE(list, len + 1); - return 0; - } - return PyList_Append(list, x); -} -#else -#define __Pyx_ListComp_Append(L,x) PyList_Append(L,x) -#endif - -/* PySequenceMultiply.proto */ -#define __Pyx_PySequence_Multiply_Left(mul, seq) __Pyx_PySequence_Multiply(seq, mul) -static CYTHON_INLINE PyObject* __Pyx_PySequence_Multiply(PyObject *seq, Py_ssize_t mul); - -/* SetItemInt.proto */ -#define __Pyx_SetItemInt(o, i, v, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ - (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ - __Pyx_SetItemInt_Fast(o, (Py_ssize_t)i, v, is_list, wraparound, boundscheck) :\ - (is_list ? (PyErr_SetString(PyExc_IndexError, "list assignment index out of range"), -1) :\ - __Pyx_SetItemInt_Generic(o, to_py_func(i), v))) -static int __Pyx_SetItemInt_Generic(PyObject *o, PyObject *j, PyObject *v); -static CYTHON_INLINE int __Pyx_SetItemInt_Fast(PyObject *o, Py_ssize_t i, PyObject *v, - int is_list, int wraparound, int boundscheck); - -/* RaiseUnboundLocalError.proto */ -static CYTHON_INLINE void __Pyx_RaiseUnboundLocalError(const char *varname); - -/* DivInt[long].proto */ -static CYTHON_INLINE long __Pyx_div_long(long, long); - -/* PySequenceContains.proto */ -static CYTHON_INLINE int __Pyx_PySequence_ContainsTF(PyObject* item, PyObject* seq, int eq) { - int result = PySequence_Contains(seq, item); - return unlikely(result < 0) ? result : (result == (eq == Py_EQ)); -} - -/* ImportFrom.proto */ -static PyObject* __Pyx_ImportFrom(PyObject* module, PyObject* name); - -/* HasAttr.proto */ -#if __PYX_LIMITED_VERSION_HEX >= 0x030d00A1 -#define __Pyx_HasAttr(o, n) PyObject_HasAttrWithError(o, n) -#else -static CYTHON_INLINE int __Pyx_HasAttr(PyObject *, PyObject *); -#endif - -/* ListAppend.proto */ -#if CYTHON_USE_PYLIST_INTERNALS && CYTHON_ASSUME_SAFE_MACROS -static CYTHON_INLINE int __Pyx_PyList_Append(PyObject* list, PyObject* x) { - PyListObject* L = (PyListObject*) list; - Py_ssize_t len = Py_SIZE(list); - if (likely(L->allocated > len) & likely(len > (L->allocated >> 1))) { - Py_INCREF(x); - #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030d0000 - L->ob_item[len] = x; - #else - PyList_SET_ITEM(list, len, x); - #endif - __Pyx_SET_SIZE(list, len + 1); - return 0; - } - return PyList_Append(list, x); -} -#else -#define __Pyx_PyList_Append(L,x) PyList_Append(L,x) -#endif - -/* PyObjectCall2Args.proto */ -static CYTHON_INLINE PyObject* __Pyx_PyObject_Call2Args(PyObject* function, PyObject* arg1, PyObject* arg2); - -/* PyObjectGetMethod.proto */ -static int __Pyx_PyObject_GetMethod(PyObject *obj, PyObject *name, PyObject **method); - -/* PyObjectCallMethod1.proto */ -static PyObject* __Pyx_PyObject_CallMethod1(PyObject* obj, PyObject* method_name, PyObject* arg); - -/* StringJoin.proto */ -#if PY_MAJOR_VERSION < 3 -#define __Pyx_PyString_Join __Pyx_PyBytes_Join -#define __Pyx_PyBaseString_Join(s, v) (PyUnicode_CheckExact(s) ? PyUnicode_Join(s, v) : __Pyx_PyBytes_Join(s, v)) -#else -#define __Pyx_PyString_Join PyUnicode_Join -#define __Pyx_PyBaseString_Join PyUnicode_Join -#endif -static CYTHON_INLINE PyObject* __Pyx_PyBytes_Join(PyObject* sep, PyObject* values); - -/* CIntToPyUnicode.proto */ -static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_size_t(size_t value, Py_ssize_t width, char padding_char, char format_char); - -/* Profile.proto */ -#ifndef CYTHON_PROFILE -#if CYTHON_COMPILING_IN_LIMITED_API || CYTHON_COMPILING_IN_PYPY - #define CYTHON_PROFILE 0 -#else - #define CYTHON_PROFILE 1 -#endif -#endif -#ifndef CYTHON_TRACE_NOGIL - #define CYTHON_TRACE_NOGIL 0 -#else - #if CYTHON_TRACE_NOGIL && !defined(CYTHON_TRACE) - #define CYTHON_TRACE 1 - #endif -#endif -#ifndef CYTHON_TRACE - #define CYTHON_TRACE 0 -#endif -#if CYTHON_TRACE - #undef CYTHON_PROFILE_REUSE_FRAME -#endif -#ifndef CYTHON_PROFILE_REUSE_FRAME - #define CYTHON_PROFILE_REUSE_FRAME 0 -#endif -#if CYTHON_PROFILE || CYTHON_TRACE - #include "compile.h" - #include "frameobject.h" - #include "traceback.h" -#if PY_VERSION_HEX >= 0x030b00a6 - #ifndef Py_BUILD_CORE - #define Py_BUILD_CORE 1 - #endif - #include "internal/pycore_frame.h" -#endif - #if CYTHON_PROFILE_REUSE_FRAME - #define CYTHON_FRAME_MODIFIER static - #define CYTHON_FRAME_DEL(frame) - #else - #define CYTHON_FRAME_MODIFIER - #define CYTHON_FRAME_DEL(frame) Py_CLEAR(frame) - #endif - #define __Pyx_TraceDeclarations\ - static PyCodeObject *__pyx_frame_code = NULL;\ - CYTHON_FRAME_MODIFIER PyFrameObject *__pyx_frame = NULL;\ - int __Pyx_use_tracing = 0; - #define __Pyx_TraceFrameInit(codeobj)\ - if (codeobj) __pyx_frame_code = (PyCodeObject*) codeobj; -#if PY_VERSION_HEX >= 0x030b00a2 - #if PY_VERSION_HEX >= 0x030C00b1 - #define __Pyx_IsTracing(tstate, check_tracing, check_funcs)\ - ((!(check_tracing) || !(tstate)->tracing) &&\ - (!(check_funcs) || (tstate)->c_profilefunc || (CYTHON_TRACE && (tstate)->c_tracefunc))) - #else - #define __Pyx_IsTracing(tstate, check_tracing, check_funcs)\ - (unlikely((tstate)->cframe->use_tracing) &&\ - (!(check_tracing) || !(tstate)->tracing) &&\ - (!(check_funcs) || (tstate)->c_profilefunc || (CYTHON_TRACE && (tstate)->c_tracefunc))) - #endif - #define __Pyx_EnterTracing(tstate) PyThreadState_EnterTracing(tstate) - #define __Pyx_LeaveTracing(tstate) PyThreadState_LeaveTracing(tstate) -#elif PY_VERSION_HEX >= 0x030a00b1 - #define __Pyx_IsTracing(tstate, check_tracing, check_funcs)\ - (unlikely((tstate)->cframe->use_tracing) &&\ - (!(check_tracing) || !(tstate)->tracing) &&\ - (!(check_funcs) || (tstate)->c_profilefunc || (CYTHON_TRACE && (tstate)->c_tracefunc))) - #define __Pyx_EnterTracing(tstate)\ - do { tstate->tracing++; tstate->cframe->use_tracing = 0; } while (0) - #define __Pyx_LeaveTracing(tstate)\ - do {\ - tstate->tracing--;\ - tstate->cframe->use_tracing = ((CYTHON_TRACE && tstate->c_tracefunc != NULL)\ - || tstate->c_profilefunc != NULL);\ - } while (0) -#else - #define __Pyx_IsTracing(tstate, check_tracing, check_funcs)\ - (unlikely((tstate)->use_tracing) &&\ - (!(check_tracing) || !(tstate)->tracing) &&\ - (!(check_funcs) || (tstate)->c_profilefunc || (CYTHON_TRACE && (tstate)->c_tracefunc))) - #define __Pyx_EnterTracing(tstate)\ - do { tstate->tracing++; tstate->use_tracing = 0; } while (0) - #define __Pyx_LeaveTracing(tstate)\ - do {\ - tstate->tracing--;\ - tstate->use_tracing = ((CYTHON_TRACE && tstate->c_tracefunc != NULL)\ - || tstate->c_profilefunc != NULL);\ - } while (0) -#endif - #ifdef WITH_THREAD - #define __Pyx_TraceCall(funcname, srcfile, firstlineno, nogil, goto_error)\ - if (nogil) {\ - if (CYTHON_TRACE_NOGIL) {\ - PyThreadState *tstate;\ - PyGILState_STATE state = PyGILState_Ensure();\ - tstate = __Pyx_PyThreadState_Current;\ - if (__Pyx_IsTracing(tstate, 1, 1)) {\ - __Pyx_use_tracing = __Pyx_TraceSetupAndCall(&__pyx_frame_code, &__pyx_frame, tstate, funcname, srcfile, firstlineno);\ - }\ - PyGILState_Release(state);\ - if (unlikely(__Pyx_use_tracing < 0)) goto_error;\ - }\ - } else {\ - PyThreadState* tstate = PyThreadState_GET();\ - if (__Pyx_IsTracing(tstate, 1, 1)) {\ - __Pyx_use_tracing = __Pyx_TraceSetupAndCall(&__pyx_frame_code, &__pyx_frame, tstate, funcname, srcfile, firstlineno);\ - if (unlikely(__Pyx_use_tracing < 0)) goto_error;\ - }\ - } - #else - #define __Pyx_TraceCall(funcname, srcfile, firstlineno, nogil, goto_error)\ - { PyThreadState* tstate = PyThreadState_GET();\ - if (__Pyx_IsTracing(tstate, 1, 1)) {\ - __Pyx_use_tracing = __Pyx_TraceSetupAndCall(&__pyx_frame_code, &__pyx_frame, tstate, funcname, srcfile, firstlineno);\ - if (unlikely(__Pyx_use_tracing < 0)) goto_error;\ - }\ - } - #endif - #define __Pyx_TraceException()\ - if (likely(!__Pyx_use_tracing)); else {\ - PyThreadState* tstate = __Pyx_PyThreadState_Current;\ - if (__Pyx_IsTracing(tstate, 0, 1)) {\ - __Pyx_EnterTracing(tstate);\ - PyObject *exc_info = __Pyx_GetExceptionTuple(tstate);\ - if (exc_info) {\ - if (CYTHON_TRACE && tstate->c_tracefunc)\ - tstate->c_tracefunc(\ - tstate->c_traceobj, __pyx_frame, PyTrace_EXCEPTION, exc_info);\ - tstate->c_profilefunc(\ - tstate->c_profileobj, __pyx_frame, PyTrace_EXCEPTION, exc_info);\ - Py_DECREF(exc_info);\ - }\ - __Pyx_LeaveTracing(tstate);\ - }\ - } - static void __Pyx_call_return_trace_func(PyThreadState *tstate, PyFrameObject *frame, PyObject *result) { - PyObject *type, *value, *traceback; - __Pyx_ErrFetchInState(tstate, &type, &value, &traceback); - __Pyx_EnterTracing(tstate); - if (CYTHON_TRACE && tstate->c_tracefunc) - tstate->c_tracefunc(tstate->c_traceobj, frame, PyTrace_RETURN, result); - if (tstate->c_profilefunc) - tstate->c_profilefunc(tstate->c_profileobj, frame, PyTrace_RETURN, result); - CYTHON_FRAME_DEL(frame); - __Pyx_LeaveTracing(tstate); - __Pyx_ErrRestoreInState(tstate, type, value, traceback); - } - #ifdef WITH_THREAD - #define __Pyx_TraceReturn(result, nogil)\ - if (likely(!__Pyx_use_tracing)); else {\ - if (nogil) {\ - if (CYTHON_TRACE_NOGIL) {\ - PyThreadState *tstate;\ - PyGILState_STATE state = PyGILState_Ensure();\ - tstate = __Pyx_PyThreadState_Current;\ - if (__Pyx_IsTracing(tstate, 0, 0)) {\ - __Pyx_call_return_trace_func(tstate, __pyx_frame, (PyObject*)result);\ - }\ - PyGILState_Release(state);\ - }\ - } else {\ - PyThreadState* tstate = __Pyx_PyThreadState_Current;\ - if (__Pyx_IsTracing(tstate, 0, 0)) {\ - __Pyx_call_return_trace_func(tstate, __pyx_frame, (PyObject*)result);\ - }\ - }\ - } - #else - #define __Pyx_TraceReturn(result, nogil)\ - if (likely(!__Pyx_use_tracing)); else {\ - PyThreadState* tstate = __Pyx_PyThreadState_Current;\ - if (__Pyx_IsTracing(tstate, 0, 0)) {\ - __Pyx_call_return_trace_func(tstate, __pyx_frame, (PyObject*)result);\ - }\ - } - #endif - static PyCodeObject *__Pyx_createFrameCodeObject(const char *funcname, const char *srcfile, int firstlineno); - static int __Pyx_TraceSetupAndCall(PyCodeObject** code, PyFrameObject** frame, PyThreadState* tstate, const char *funcname, const char *srcfile, int firstlineno); -#else - #define __Pyx_TraceDeclarations - #define __Pyx_TraceFrameInit(codeobj) - #define __Pyx_TraceCall(funcname, srcfile, firstlineno, nogil, goto_error) if ((1)); else goto_error; - #define __Pyx_TraceException() - #define __Pyx_TraceReturn(result, nogil) -#endif -#if CYTHON_TRACE - static int __Pyx_call_line_trace_func(PyThreadState *tstate, PyFrameObject *frame, int lineno) { - int ret; - PyObject *type, *value, *traceback; - __Pyx_ErrFetchInState(tstate, &type, &value, &traceback); - __Pyx_PyFrame_SetLineNumber(frame, lineno); - __Pyx_EnterTracing(tstate); - ret = tstate->c_tracefunc(tstate->c_traceobj, frame, PyTrace_LINE, NULL); - __Pyx_LeaveTracing(tstate); - if (likely(!ret)) { - __Pyx_ErrRestoreInState(tstate, type, value, traceback); - } else { - Py_XDECREF(type); - Py_XDECREF(value); - Py_XDECREF(traceback); - } - return ret; - } - #ifdef WITH_THREAD - #define __Pyx_TraceLine(lineno, nogil, goto_error)\ - if (likely(!__Pyx_use_tracing)); else {\ - if (nogil) {\ - if (CYTHON_TRACE_NOGIL) {\ - int ret = 0;\ - PyThreadState *tstate;\ - PyGILState_STATE state = __Pyx_PyGILState_Ensure();\ - tstate = __Pyx_PyThreadState_Current;\ - if (__Pyx_IsTracing(tstate, 0, 0) && tstate->c_tracefunc && __pyx_frame->f_trace) {\ - ret = __Pyx_call_line_trace_func(tstate, __pyx_frame, lineno);\ - }\ - __Pyx_PyGILState_Release(state);\ - if (unlikely(ret)) goto_error;\ - }\ - } else {\ - PyThreadState* tstate = __Pyx_PyThreadState_Current;\ - if (__Pyx_IsTracing(tstate, 0, 0) && tstate->c_tracefunc && __pyx_frame->f_trace) {\ - int ret = __Pyx_call_line_trace_func(tstate, __pyx_frame, lineno);\ - if (unlikely(ret)) goto_error;\ - }\ - }\ - } - #else - #define __Pyx_TraceLine(lineno, nogil, goto_error)\ - if (likely(!__Pyx_use_tracing)); else {\ - PyThreadState* tstate = __Pyx_PyThreadState_Current;\ - if (__Pyx_IsTracing(tstate, 0, 0) && tstate->c_tracefunc && __pyx_frame->f_trace) {\ - int ret = __Pyx_call_line_trace_func(tstate, __pyx_frame, lineno);\ - if (unlikely(ret)) goto_error;\ - }\ - } - #endif -#else - #define __Pyx_TraceLine(lineno, nogil, goto_error) if ((1)); else goto_error; -#endif - -/* IsLittleEndian.proto */ -static CYTHON_INLINE int __Pyx_Is_Little_Endian(void); - -/* BufferFormatCheck.proto */ -static const char* __Pyx_BufFmt_CheckString(__Pyx_BufFmt_Context* ctx, const char* ts); -static void __Pyx_BufFmt_Init(__Pyx_BufFmt_Context* ctx, - __Pyx_BufFmt_StackElem* stack, - __Pyx_TypeInfo* type); - -/* BufferGetAndValidate.proto */ -#define __Pyx_GetBufferAndValidate(buf, obj, dtype, flags, nd, cast, stack)\ - ((obj == Py_None || obj == NULL) ?\ - (__Pyx_ZeroBuffer(buf), 0) :\ - __Pyx__GetBufferAndValidate(buf, obj, dtype, flags, nd, cast, stack)) -static int __Pyx__GetBufferAndValidate(Py_buffer* buf, PyObject* obj, - __Pyx_TypeInfo* dtype, int flags, int nd, int cast, __Pyx_BufFmt_StackElem* stack); -static void __Pyx_ZeroBuffer(Py_buffer* buf); -static CYTHON_INLINE void __Pyx_SafeReleaseBuffer(Py_buffer* info); -static Py_ssize_t __Pyx_minusones[] = { -1, -1, -1, -1, -1, -1, -1, -1 }; -static Py_ssize_t __Pyx_zeros[] = { 0, 0, 0, 0, 0, 0, 0, 0 }; - -/* MoveIfSupported.proto */ -#if CYTHON_USE_CPP_STD_MOVE - #include - #define __PYX_STD_MOVE_IF_SUPPORTED(x) std::move(x) -#else - #define __PYX_STD_MOVE_IF_SUPPORTED(x) x -#endif - -/* BufferFallbackError.proto */ -static void __Pyx_RaiseBufferFallbackError(void); - -/* PyObjectCallNoArg.proto */ -static CYTHON_INLINE PyObject* __Pyx_PyObject_CallNoArg(PyObject *func); - -/* WriteUnraisableException.proto */ -static void __Pyx_WriteUnraisable(const char *name, int clineno, - int lineno, const char *filename, - int full_traceback, int nogil); - -/* PyObject_GenericGetAttrNoDict.proto */ -#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 -static CYTHON_INLINE PyObject* __Pyx_PyObject_GenericGetAttrNoDict(PyObject* obj, PyObject* attr_name); -#else -#define __Pyx_PyObject_GenericGetAttrNoDict PyObject_GenericGetAttr -#endif - -/* PyObject_GenericGetAttr.proto */ -#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 -static PyObject* __Pyx_PyObject_GenericGetAttr(PyObject* obj, PyObject* attr_name); -#else -#define __Pyx_PyObject_GenericGetAttr PyObject_GenericGetAttr -#endif - -/* IncludeStructmemberH.proto */ -#include - -/* FixUpExtensionType.proto */ -#if CYTHON_USE_TYPE_SPECS -static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type); -#endif - -/* PyObjectCallMethod0.proto */ -static PyObject* __Pyx_PyObject_CallMethod0(PyObject* obj, PyObject* method_name); - -/* ValidateBasesTuple.proto */ -#if CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API || CYTHON_USE_TYPE_SPECS -static int __Pyx_validate_bases_tuple(const char *type_name, Py_ssize_t dictoffset, PyObject *bases); -#endif - -/* PyType_Ready.proto */ -CYTHON_UNUSED static int __Pyx_PyType_Ready(PyTypeObject *t); - -/* SetupReduce.proto */ -#if !CYTHON_COMPILING_IN_LIMITED_API -static int __Pyx_setup_reduce(PyObject* type_obj); -#endif - -/* SetVTable.proto */ -static int __Pyx_SetVtable(PyTypeObject* typeptr , void* vtable); - -/* GetVTable.proto */ -static void* __Pyx_GetVtable(PyTypeObject *type); - -/* MergeVTables.proto */ -#if !CYTHON_COMPILING_IN_LIMITED_API -static int __Pyx_MergeVtables(PyTypeObject *type); -#endif - -/* TypeImport.proto */ -#ifndef __PYX_HAVE_RT_ImportType_proto_3_0_8 -#define __PYX_HAVE_RT_ImportType_proto_3_0_8 -#if defined (__STDC_VERSION__) && __STDC_VERSION__ >= 201112L -#include -#endif -#if (defined (__STDC_VERSION__) && __STDC_VERSION__ >= 201112L) || __cplusplus >= 201103L -#define __PYX_GET_STRUCT_ALIGNMENT_3_0_8(s) alignof(s) -#else -#define __PYX_GET_STRUCT_ALIGNMENT_3_0_8(s) sizeof(void*) -#endif -enum __Pyx_ImportType_CheckSize_3_0_8 { - __Pyx_ImportType_CheckSize_Error_3_0_8 = 0, - __Pyx_ImportType_CheckSize_Warn_3_0_8 = 1, - __Pyx_ImportType_CheckSize_Ignore_3_0_8 = 2 -}; -static PyTypeObject *__Pyx_ImportType_3_0_8(PyObject* module, const char *module_name, const char *class_name, size_t size, size_t alignment, enum __Pyx_ImportType_CheckSize_3_0_8 check_size); -#endif - -/* FetchSharedCythonModule.proto */ -static PyObject *__Pyx_FetchSharedCythonABIModule(void); - -/* FetchCommonType.proto */ -#if !CYTHON_USE_TYPE_SPECS -static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type); -#else -static PyTypeObject* __Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases); -#endif - -/* PyMethodNew.proto */ -#if CYTHON_COMPILING_IN_LIMITED_API -static PyObject *__Pyx_PyMethod_New(PyObject *func, PyObject *self, PyObject *typ) { - PyObject *typesModule=NULL, *methodType=NULL, *result=NULL; - CYTHON_UNUSED_VAR(typ); - if (!self) - return __Pyx_NewRef(func); - typesModule = PyImport_ImportModule("types"); - if (!typesModule) return NULL; - methodType = PyObject_GetAttrString(typesModule, "MethodType"); - Py_DECREF(typesModule); - if (!methodType) return NULL; - result = PyObject_CallFunctionObjArgs(methodType, func, self, NULL); - Py_DECREF(methodType); - return result; -} -#elif PY_MAJOR_VERSION >= 3 -static PyObject *__Pyx_PyMethod_New(PyObject *func, PyObject *self, PyObject *typ) { - CYTHON_UNUSED_VAR(typ); - if (!self) - return __Pyx_NewRef(func); - return PyMethod_New(func, self); -} -#else - #define __Pyx_PyMethod_New PyMethod_New -#endif - -/* PyVectorcallFastCallDict.proto */ -#if CYTHON_METH_FASTCALL -static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw); -#endif - -/* CythonFunctionShared.proto */ -#define __Pyx_CyFunction_USED -#define __Pyx_CYFUNCTION_STATICMETHOD 0x01 -#define __Pyx_CYFUNCTION_CLASSMETHOD 0x02 -#define __Pyx_CYFUNCTION_CCLASS 0x04 -#define __Pyx_CYFUNCTION_COROUTINE 0x08 -#define __Pyx_CyFunction_GetClosure(f)\ - (((__pyx_CyFunctionObject *) (f))->func_closure) -#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API - #define __Pyx_CyFunction_GetClassObj(f)\ - (((__pyx_CyFunctionObject *) (f))->func_classobj) -#else - #define __Pyx_CyFunction_GetClassObj(f)\ - ((PyObject*) ((PyCMethodObject *) (f))->mm_class) -#endif -#define __Pyx_CyFunction_SetClassObj(f, classobj)\ - __Pyx__CyFunction_SetClassObj((__pyx_CyFunctionObject *) (f), (classobj)) -#define __Pyx_CyFunction_Defaults(type, f)\ - ((type *)(((__pyx_CyFunctionObject *) (f))->defaults)) -#define __Pyx_CyFunction_SetDefaultsGetter(f, g)\ - ((__pyx_CyFunctionObject *) (f))->defaults_getter = (g) -typedef struct { -#if CYTHON_COMPILING_IN_LIMITED_API - PyObject_HEAD - PyObject *func; -#elif PY_VERSION_HEX < 0x030900B1 - PyCFunctionObject func; -#else - PyCMethodObject func; -#endif -#if CYTHON_BACKPORT_VECTORCALL - __pyx_vectorcallfunc func_vectorcall; -#endif -#if PY_VERSION_HEX < 0x030500A0 || CYTHON_COMPILING_IN_LIMITED_API - PyObject *func_weakreflist; -#endif - PyObject *func_dict; - PyObject *func_name; - PyObject *func_qualname; - PyObject *func_doc; - PyObject *func_globals; - PyObject *func_code; - PyObject *func_closure; -#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API - PyObject *func_classobj; -#endif - void *defaults; - int defaults_pyobjects; - size_t defaults_size; - int flags; - PyObject *defaults_tuple; - PyObject *defaults_kwdict; - PyObject *(*defaults_getter)(PyObject *); - PyObject *func_annotations; - PyObject *func_is_coroutine; -} __pyx_CyFunctionObject; -#undef __Pyx_CyOrPyCFunction_Check -#define __Pyx_CyFunction_Check(obj) __Pyx_TypeCheck(obj, __pyx_CyFunctionType) -#define __Pyx_CyOrPyCFunction_Check(obj) __Pyx_TypeCheck2(obj, __pyx_CyFunctionType, &PyCFunction_Type) -#define __Pyx_CyFunction_CheckExact(obj) __Pyx_IS_TYPE(obj, __pyx_CyFunctionType) -static CYTHON_INLINE int __Pyx__IsSameCyOrCFunction(PyObject *func, void *cfunc); -#undef __Pyx_IsSameCFunction -#define __Pyx_IsSameCFunction(func, cfunc) __Pyx__IsSameCyOrCFunction(func, cfunc) -static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject* op, PyMethodDef *ml, - int flags, PyObject* qualname, - PyObject *closure, - PyObject *module, PyObject *globals, - PyObject* code); -static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj); -static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *m, - size_t size, - int pyobjects); -static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *m, - PyObject *tuple); -static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *m, - PyObject *dict); -static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *m, - PyObject *dict); -static int __pyx_CyFunction_init(PyObject *module); -#if CYTHON_METH_FASTCALL -static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); -static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); -static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); -static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); -#if CYTHON_BACKPORT_VECTORCALL -#define __Pyx_CyFunction_func_vectorcall(f) (((__pyx_CyFunctionObject*)f)->func_vectorcall) -#else -#define __Pyx_CyFunction_func_vectorcall(f) (((PyCFunctionObject*)f)->vectorcall) -#endif -#endif - -/* CythonFunction.proto */ -static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, - int flags, PyObject* qualname, - PyObject *closure, - PyObject *module, PyObject *globals, - PyObject* code); - -/* CLineInTraceback.proto */ -#ifdef CYTHON_CLINE_IN_TRACEBACK -#define __Pyx_CLineForTraceback(tstate, c_line) (((CYTHON_CLINE_IN_TRACEBACK)) ? c_line : 0) -#else -static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line); -#endif - -/* CodeObjectCache.proto */ -#if !CYTHON_COMPILING_IN_LIMITED_API -typedef struct { - PyCodeObject* code_object; - int code_line; -} __Pyx_CodeObjectCacheEntry; -struct __Pyx_CodeObjectCache { - int count; - int max_count; - __Pyx_CodeObjectCacheEntry* entries; -}; -static struct __Pyx_CodeObjectCache __pyx_code_cache = {0,0,NULL}; -static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line); -static PyCodeObject *__pyx_find_code_object(int code_line); -static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object); -#endif - -/* AddTraceback.proto */ -static void __Pyx_AddTraceback(const char *funcname, int c_line, - int py_line, const char *filename); - -#if PY_MAJOR_VERSION < 3 - static int __Pyx_GetBuffer(PyObject *obj, Py_buffer *view, int flags); - static void __Pyx_ReleaseBuffer(Py_buffer *view); -#else - #define __Pyx_GetBuffer PyObject_GetBuffer - #define __Pyx_ReleaseBuffer PyBuffer_Release -#endif - - -/* BufferStructDeclare.proto */ -typedef struct { - Py_ssize_t shape, strides, suboffsets; -} __Pyx_Buf_DimInfo; -typedef struct { - size_t refcount; - Py_buffer pybuffer; -} __Pyx_Buffer; -typedef struct { - __Pyx_Buffer *rcbuffer; - char *data; - __Pyx_Buf_DimInfo diminfo[8]; -} __Pyx_LocalBuf_ND; - -/* MemviewSliceIsContig.proto */ -static int __pyx_memviewslice_is_contig(const __Pyx_memviewslice mvs, char order, int ndim); - -/* OverlappingSlices.proto */ -static int __pyx_slices_overlap(__Pyx_memviewslice *slice1, - __Pyx_memviewslice *slice2, - int ndim, size_t itemsize); - -/* TypeInfoCompare.proto */ -static int __pyx_typeinfo_cmp(__Pyx_TypeInfo *a, __Pyx_TypeInfo *b); - -/* MemviewSliceValidateAndInit.proto */ -static int __Pyx_ValidateAndInit_memviewslice( - int *axes_specs, - int c_or_f_flag, - int buf_flags, - int ndim, - __Pyx_TypeInfo *dtype, - __Pyx_BufFmt_StackElem stack[], - __Pyx_memviewslice *memviewslice, - PyObject *original_obj); - -/* ObjectToMemviewSlice.proto */ -static CYTHON_INLINE __Pyx_memviewslice __Pyx_PyObject_to_MemoryviewSlice_dsds_double(PyObject *, int writable_flag); - -/* MemviewDtypeToObject.proto */ -static CYTHON_INLINE PyObject *__pyx_memview_get_double(const char *itemp); -static CYTHON_INLINE int __pyx_memview_set_double(const char *itemp, PyObject *obj); - -/* ObjectToMemviewSlice.proto */ -static CYTHON_INLINE __Pyx_memviewslice __Pyx_PyObject_to_MemoryviewSlice_ds_double(PyObject *, int writable_flag); - -/* CppExceptionConversion.proto */ -#ifndef __Pyx_CppExn2PyErr -#include -#include -#include -#include -static void __Pyx_CppExn2PyErr() { - try { - if (PyErr_Occurred()) - ; // let the latest Python exn pass through and ignore the current one - else - throw; - } catch (const std::bad_alloc& exn) { - PyErr_SetString(PyExc_MemoryError, exn.what()); - } catch (const std::bad_cast& exn) { - PyErr_SetString(PyExc_TypeError, exn.what()); - } catch (const std::bad_typeid& exn) { - PyErr_SetString(PyExc_TypeError, exn.what()); - } catch (const std::domain_error& exn) { - PyErr_SetString(PyExc_ValueError, exn.what()); - } catch (const std::invalid_argument& exn) { - PyErr_SetString(PyExc_ValueError, exn.what()); - } catch (const std::ios_base::failure& exn) { - PyErr_SetString(PyExc_IOError, exn.what()); - } catch (const std::out_of_range& exn) { - PyErr_SetString(PyExc_IndexError, exn.what()); - } catch (const std::overflow_error& exn) { - PyErr_SetString(PyExc_OverflowError, exn.what()); - } catch (const std::range_error& exn) { - PyErr_SetString(PyExc_ArithmeticError, exn.what()); - } catch (const std::underflow_error& exn) { - PyErr_SetString(PyExc_ArithmeticError, exn.what()); - } catch (const std::exception& exn) { - PyErr_SetString(PyExc_RuntimeError, exn.what()); - } - catch (...) - { - PyErr_SetString(PyExc_RuntimeError, "Unknown exception"); - } -} -#endif - -/* RealImag.proto */ -#if CYTHON_CCOMPLEX - #ifdef __cplusplus - #define __Pyx_CREAL(z) ((z).real()) - #define __Pyx_CIMAG(z) ((z).imag()) - #else - #define __Pyx_CREAL(z) (__real__(z)) - #define __Pyx_CIMAG(z) (__imag__(z)) - #endif -#else - #define __Pyx_CREAL(z) ((z).real) - #define __Pyx_CIMAG(z) ((z).imag) -#endif -#if defined(__cplusplus) && CYTHON_CCOMPLEX\ - && (defined(_WIN32) || defined(__clang__) || (defined(__GNUC__) && (__GNUC__ >= 5 || __GNUC__ == 4 && __GNUC_MINOR__ >= 4 )) || __cplusplus >= 201103) - #define __Pyx_SET_CREAL(z,x) ((z).real(x)) - #define __Pyx_SET_CIMAG(z,y) ((z).imag(y)) -#else - #define __Pyx_SET_CREAL(z,x) __Pyx_CREAL(z) = (x) - #define __Pyx_SET_CIMAG(z,y) __Pyx_CIMAG(z) = (y) -#endif - -/* Arithmetic.proto */ -#if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) - #define __Pyx_c_eq_float(a, b) ((a)==(b)) - #define __Pyx_c_sum_float(a, b) ((a)+(b)) - #define __Pyx_c_diff_float(a, b) ((a)-(b)) - #define __Pyx_c_prod_float(a, b) ((a)*(b)) - #define __Pyx_c_quot_float(a, b) ((a)/(b)) - #define __Pyx_c_neg_float(a) (-(a)) - #ifdef __cplusplus - #define __Pyx_c_is_zero_float(z) ((z)==(float)0) - #define __Pyx_c_conj_float(z) (::std::conj(z)) - #if 1 - #define __Pyx_c_abs_float(z) (::std::abs(z)) - #define __Pyx_c_pow_float(a, b) (::std::pow(a, b)) - #endif - #else - #define __Pyx_c_is_zero_float(z) ((z)==0) - #define __Pyx_c_conj_float(z) (conjf(z)) - #if 1 - #define __Pyx_c_abs_float(z) (cabsf(z)) - #define __Pyx_c_pow_float(a, b) (cpowf(a, b)) - #endif - #endif -#else - static CYTHON_INLINE int __Pyx_c_eq_float(__pyx_t_float_complex, __pyx_t_float_complex); - static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_sum_float(__pyx_t_float_complex, __pyx_t_float_complex); - static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_diff_float(__pyx_t_float_complex, __pyx_t_float_complex); - static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_prod_float(__pyx_t_float_complex, __pyx_t_float_complex); - static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_quot_float(__pyx_t_float_complex, __pyx_t_float_complex); - static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_neg_float(__pyx_t_float_complex); - static CYTHON_INLINE int __Pyx_c_is_zero_float(__pyx_t_float_complex); - static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_conj_float(__pyx_t_float_complex); - #if 1 - static CYTHON_INLINE float __Pyx_c_abs_float(__pyx_t_float_complex); - static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_pow_float(__pyx_t_float_complex, __pyx_t_float_complex); - #endif -#endif - -/* Arithmetic.proto */ -#if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) - #define __Pyx_c_eq_double(a, b) ((a)==(b)) - #define __Pyx_c_sum_double(a, b) ((a)+(b)) - #define __Pyx_c_diff_double(a, b) ((a)-(b)) - #define __Pyx_c_prod_double(a, b) ((a)*(b)) - #define __Pyx_c_quot_double(a, b) ((a)/(b)) - #define __Pyx_c_neg_double(a) (-(a)) - #ifdef __cplusplus - #define __Pyx_c_is_zero_double(z) ((z)==(double)0) - #define __Pyx_c_conj_double(z) (::std::conj(z)) - #if 1 - #define __Pyx_c_abs_double(z) (::std::abs(z)) - #define __Pyx_c_pow_double(a, b) (::std::pow(a, b)) - #endif - #else - #define __Pyx_c_is_zero_double(z) ((z)==0) - #define __Pyx_c_conj_double(z) (conj(z)) - #if 1 - #define __Pyx_c_abs_double(z) (cabs(z)) - #define __Pyx_c_pow_double(a, b) (cpow(a, b)) - #endif - #endif -#else - static CYTHON_INLINE int __Pyx_c_eq_double(__pyx_t_double_complex, __pyx_t_double_complex); - static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_sum_double(__pyx_t_double_complex, __pyx_t_double_complex); - static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_diff_double(__pyx_t_double_complex, __pyx_t_double_complex); - static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_prod_double(__pyx_t_double_complex, __pyx_t_double_complex); - static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_quot_double(__pyx_t_double_complex, __pyx_t_double_complex); - static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_neg_double(__pyx_t_double_complex); - static CYTHON_INLINE int __Pyx_c_is_zero_double(__pyx_t_double_complex); - static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_conj_double(__pyx_t_double_complex); - #if 1 - static CYTHON_INLINE double __Pyx_c_abs_double(__pyx_t_double_complex); - static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_pow_double(__pyx_t_double_complex, __pyx_t_double_complex); - #endif -#endif - -/* MemviewSliceCopyTemplate.proto */ -static __Pyx_memviewslice -__pyx_memoryview_copy_new_contig(const __Pyx_memviewslice *from_mvs, - const char *mode, int ndim, - size_t sizeof_dtype, int contig_flag, - int dtype_is_object); - -/* MemviewSliceInit.proto */ -#define __Pyx_BUF_MAX_NDIMS %(BUF_MAX_NDIMS)d -#define __Pyx_MEMVIEW_DIRECT 1 -#define __Pyx_MEMVIEW_PTR 2 -#define __Pyx_MEMVIEW_FULL 4 -#define __Pyx_MEMVIEW_CONTIG 8 -#define __Pyx_MEMVIEW_STRIDED 16 -#define __Pyx_MEMVIEW_FOLLOW 32 -#define __Pyx_IS_C_CONTIG 1 -#define __Pyx_IS_F_CONTIG 2 -static int __Pyx_init_memviewslice( - struct __pyx_memoryview_obj *memview, - int ndim, - __Pyx_memviewslice *memviewslice, - int memview_is_new_reference); -static CYTHON_INLINE int __pyx_add_acquisition_count_locked( - __pyx_atomic_int_type *acquisition_count, PyThread_type_lock lock); -static CYTHON_INLINE int __pyx_sub_acquisition_count_locked( - __pyx_atomic_int_type *acquisition_count, PyThread_type_lock lock); -#define __pyx_get_slice_count_pointer(memview) (&memview->acquisition_count) -#define __PYX_INC_MEMVIEW(slice, have_gil) __Pyx_INC_MEMVIEW(slice, have_gil, __LINE__) -#define __PYX_XCLEAR_MEMVIEW(slice, have_gil) __Pyx_XCLEAR_MEMVIEW(slice, have_gil, __LINE__) -static CYTHON_INLINE void __Pyx_INC_MEMVIEW(__Pyx_memviewslice *, int, int); -static CYTHON_INLINE void __Pyx_XCLEAR_MEMVIEW(__Pyx_memviewslice *, int, int); - -/* TypeInfoToFormat.proto */ -struct __pyx_typeinfo_string { - char string[3]; -}; -static struct __pyx_typeinfo_string __Pyx_TypeInfoToFormat(__Pyx_TypeInfo *type); - -/* CIntFromPy.proto */ -static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *); - -/* CIntToPy.proto */ -static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value); - -/* CIntToPy.proto */ -static CYTHON_INLINE PyObject* __Pyx_PyInt_From_int(int value); - -/* None.proto */ -#include - -/* CIntFromPy.proto */ -static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *); - -/* CIntFromPy.proto */ -static CYTHON_INLINE char __Pyx_PyInt_As_char(PyObject *); - -/* FormatTypeName.proto */ -#if CYTHON_COMPILING_IN_LIMITED_API -typedef PyObject *__Pyx_TypeName; -#define __Pyx_FMT_TYPENAME "%U" -static __Pyx_TypeName __Pyx_PyType_GetName(PyTypeObject* tp); -#define __Pyx_DECREF_TypeName(obj) Py_XDECREF(obj) -#else -typedef const char *__Pyx_TypeName; -#define __Pyx_FMT_TYPENAME "%.200s" -#define __Pyx_PyType_GetName(tp) ((tp)->tp_name) -#define __Pyx_DECREF_TypeName(obj) -#endif - -/* CheckBinaryVersion.proto */ -static unsigned long __Pyx_get_runtime_version(void); -static int __Pyx_check_binary_version(unsigned long ct_version, unsigned long rt_version, int allow_newer); - -/* InitStrings.proto */ -static int __Pyx_InitStrings(__Pyx_StringTabEntry *t); - -/* #### Code section: module_declarations ### */ -static PyObject *__pyx_array_get_memview(struct __pyx_array_obj *__pyx_v_self); /* proto*/ -static char *__pyx_memoryview_get_item_pointer(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index); /* proto*/ -static PyObject *__pyx_memoryview_is_slice(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj); /* proto*/ -static PyObject *__pyx_memoryview_setitem_slice_assignment(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_dst, PyObject *__pyx_v_src); /* proto*/ -static PyObject *__pyx_memoryview_setitem_slice_assign_scalar(struct __pyx_memoryview_obj *__pyx_v_self, struct __pyx_memoryview_obj *__pyx_v_dst, PyObject *__pyx_v_value); /* proto*/ -static PyObject *__pyx_memoryview_setitem_indexed(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value); /* proto*/ -static PyObject *__pyx_memoryview_convert_item_to_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp); /* proto*/ -static PyObject *__pyx_memoryview_assign_item_from_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value); /* proto*/ -static PyObject *__pyx_memoryview__get_base(struct __pyx_memoryview_obj *__pyx_v_self); /* proto*/ -static PyObject *__pyx_memoryviewslice_convert_item_to_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp); /* proto*/ -static PyObject *__pyx_memoryviewslice_assign_item_from_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value); /* proto*/ -static PyObject *__pyx_memoryviewslice__get_base(struct __pyx_memoryviewslice_obj *__pyx_v_self); /* proto*/ -static CYTHON_INLINE PyObject *__pyx_f_5numpy_7ndarray_4base_base(PyArrayObject *__pyx_v_self); /* proto*/ -static CYTHON_INLINE PyArray_Descr *__pyx_f_5numpy_7ndarray_5descr_descr(PyArrayObject *__pyx_v_self); /* proto*/ -static CYTHON_INLINE int __pyx_f_5numpy_7ndarray_4ndim_ndim(PyArrayObject *__pyx_v_self); /* proto*/ -static CYTHON_INLINE npy_intp *__pyx_f_5numpy_7ndarray_5shape_shape(PyArrayObject *__pyx_v_self); /* proto*/ -static CYTHON_INLINE npy_intp *__pyx_f_5numpy_7ndarray_7strides_strides(PyArrayObject *__pyx_v_self); /* proto*/ -static CYTHON_INLINE npy_intp __pyx_f_5numpy_7ndarray_4size_size(PyArrayObject *__pyx_v_self); /* proto*/ -static CYTHON_INLINE char *__pyx_f_5numpy_7ndarray_4data_data(PyArrayObject *__pyx_v_self); /* proto*/ - -/* Module declarations from "cython.view" */ -static struct __pyx_array_obj *__pyx_array_new(PyObject *, Py_ssize_t, char *, char *, char *); /*proto*/ - -/* Module declarations from "cython.dataclasses" */ - -/* Module declarations from "cython" */ - -/* Module declarations from "libc.string" */ - -/* Module declarations from "libcpp.string" */ - -/* Module declarations from "libcpp.vector" */ - -/* Module declarations from "libcpp" */ - -/* Module declarations from "libc.stdio" */ - -/* Module declarations from "__builtin__" */ - -/* Module declarations from "cpython.type" */ - -/* Module declarations from "cpython" */ - -/* Module declarations from "cpython.object" */ - -/* Module declarations from "cpython.ref" */ - -/* Module declarations from "numpy" */ - -/* Module declarations from "numpy" */ - -/* Module declarations from "rednose.helpers.ekf_sym_pyx" */ -static PyObject *__pyx_collections_abc_Sequence = 0; -static PyObject *generic = 0; -static PyObject *strided = 0; -static PyObject *indirect = 0; -static PyObject *contiguous = 0; -static PyObject *indirect_contiguous = 0; -static int __pyx_memoryview_thread_locks_used; -static PyThread_type_lock __pyx_memoryview_thread_locks[8]; -static PyArrayObject *__pyx_f_7rednose_7helpers_11ekf_sym_pyx_matrix_to_numpy(Eigen::Matrix); /*proto*/ -static PyArrayObject *__pyx_f_7rednose_7helpers_11ekf_sym_pyx_vector_to_numpy(Eigen::VectorXd); /*proto*/ -static std::string __pyx_convert_string_from_py_std__in_string(PyObject *); /*proto*/ -static std::vector __pyx_convert_vector_from_py_int(PyObject *); /*proto*/ -static std::vector __pyx_convert_vector_from_py_std_3a__3a_string(PyObject *); /*proto*/ -static int __pyx_array_allocate_buffer(struct __pyx_array_obj *); /*proto*/ -static struct __pyx_array_obj *__pyx_array_new(PyObject *, Py_ssize_t, char *, char *, char *); /*proto*/ -static PyObject *__pyx_memoryview_new(PyObject *, int, int, __Pyx_TypeInfo *); /*proto*/ -static CYTHON_INLINE int __pyx_memoryview_check(PyObject *); /*proto*/ -static PyObject *_unellipsify(PyObject *, int); /*proto*/ -static int assert_direct_dimensions(Py_ssize_t *, int); /*proto*/ -static struct __pyx_memoryview_obj *__pyx_memview_slice(struct __pyx_memoryview_obj *, PyObject *); /*proto*/ -static int __pyx_memoryview_slice_memviewslice(__Pyx_memviewslice *, Py_ssize_t, Py_ssize_t, Py_ssize_t, int, int, int *, Py_ssize_t, Py_ssize_t, Py_ssize_t, int, int, int, int); /*proto*/ -static char *__pyx_pybuffer_index(Py_buffer *, char *, Py_ssize_t, Py_ssize_t); /*proto*/ -static int __pyx_memslice_transpose(__Pyx_memviewslice *); /*proto*/ -static PyObject *__pyx_memoryview_fromslice(__Pyx_memviewslice, int, PyObject *(*)(char *), int (*)(char *, PyObject *), int); /*proto*/ -static __Pyx_memviewslice *__pyx_memoryview_get_slice_from_memoryview(struct __pyx_memoryview_obj *, __Pyx_memviewslice *); /*proto*/ -static void __pyx_memoryview_slice_copy(struct __pyx_memoryview_obj *, __Pyx_memviewslice *); /*proto*/ -static PyObject *__pyx_memoryview_copy_object(struct __pyx_memoryview_obj *); /*proto*/ -static PyObject *__pyx_memoryview_copy_object_from_slice(struct __pyx_memoryview_obj *, __Pyx_memviewslice *); /*proto*/ -static Py_ssize_t abs_py_ssize_t(Py_ssize_t); /*proto*/ -static char __pyx_get_best_slice_order(__Pyx_memviewslice *, int); /*proto*/ -static void _copy_strided_to_strided(char *, Py_ssize_t *, char *, Py_ssize_t *, Py_ssize_t *, Py_ssize_t *, int, size_t); /*proto*/ -static void copy_strided_to_strided(__Pyx_memviewslice *, __Pyx_memviewslice *, int, size_t); /*proto*/ -static Py_ssize_t __pyx_memoryview_slice_get_size(__Pyx_memviewslice *, int); /*proto*/ -static Py_ssize_t __pyx_fill_contig_strides_array(Py_ssize_t *, Py_ssize_t *, Py_ssize_t, int, char); /*proto*/ -static void *__pyx_memoryview_copy_data_to_temp(__Pyx_memviewslice *, __Pyx_memviewslice *, char, int); /*proto*/ -static int __pyx_memoryview_err_extents(int, Py_ssize_t, Py_ssize_t); /*proto*/ -static int __pyx_memoryview_err_dim(PyObject *, PyObject *, int); /*proto*/ -static int __pyx_memoryview_err(PyObject *, PyObject *); /*proto*/ -static int __pyx_memoryview_err_no_memory(void); /*proto*/ -static int __pyx_memoryview_copy_contents(__Pyx_memviewslice, __Pyx_memviewslice, int, int, int); /*proto*/ -static void __pyx_memoryview_broadcast_leading(__Pyx_memviewslice *, int, int); /*proto*/ -static void __pyx_memoryview_refcount_copying(__Pyx_memviewslice *, int, int, int); /*proto*/ -static void __pyx_memoryview_refcount_objects_in_slice_with_gil(char *, Py_ssize_t *, Py_ssize_t *, int, int); /*proto*/ -static void __pyx_memoryview_refcount_objects_in_slice(char *, Py_ssize_t *, Py_ssize_t *, int, int); /*proto*/ -static void __pyx_memoryview_slice_assign_scalar(__Pyx_memviewslice *, int, size_t, void *, int); /*proto*/ -static void __pyx_memoryview__slice_assign_scalar(char *, Py_ssize_t *, Py_ssize_t *, int, size_t, void *); /*proto*/ -static PyObject *__pyx_unpickle_Enum__set_state(struct __pyx_MemviewEnum_obj *, PyObject *); /*proto*/ -static PyObject *__pyx_format_from_typeinfo(__Pyx_TypeInfo *); /*proto*/ -/* #### Code section: typeinfo ### */ -static __Pyx_TypeInfo __Pyx_TypeInfo_double = { "double", NULL, sizeof(double), { 0 }, 0, 'R', 0, 0 }; -static __Pyx_TypeInfo __Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t = { "float64_t", NULL, sizeof(__pyx_t_5numpy_float64_t), { 0 }, 0, 'R', 0, 0 }; -/* #### Code section: before_global_var ### */ -#define __Pyx_MODULE_NAME "rednose.helpers.ekf_sym_pyx" -extern int __pyx_module_is_main_rednose__helpers__ekf_sym_pyx; -int __pyx_module_is_main_rednose__helpers__ekf_sym_pyx = 0; - -/* Implementation of "rednose.helpers.ekf_sym_pyx" */ -/* #### Code section: global_var ### */ -static PyObject *__pyx_builtin_NotImplementedError; -static PyObject *__pyx_builtin_TypeError; -static PyObject *__pyx_builtin___import__; -static PyObject *__pyx_builtin_ValueError; -static PyObject *__pyx_builtin_MemoryError; -static PyObject *__pyx_builtin_enumerate; -static PyObject *__pyx_builtin_range; -static PyObject *__pyx_builtin_AssertionError; -static PyObject *__pyx_builtin_Ellipsis; -static PyObject *__pyx_builtin_id; -static PyObject *__pyx_builtin_IndexError; -static PyObject *__pyx_builtin_ImportError; -/* #### Code section: string_decls ### */ -static const char __pyx_k_[] = ": "; -static const char __pyx_k_C[] = "C"; -static const char __pyx_k_N[] = "N"; -static const char __pyx_k_O[] = "O"; -static const char __pyx_k_P[] = "P"; -static const char __pyx_k_Q[] = "Q"; -static const char __pyx_k_R[] = "R"; -static const char __pyx_k_T[] = "T{"; - static const char __pyx_k_a[] = "a"; - static const char __pyx_k_c[] = "c"; - static const char __pyx_k_t[] = "t"; - static const char __pyx_k_x[] = "x"; - static const char __pyx_k_z[] = "z"; - static const char __pyx_k_Ri[] = "Ri"; - static const char __pyx_k__2[] = "."; - static const char __pyx_k__3[] = "*"; - static const char __pyx_k__6[] = "'"; - static const char __pyx_k__7[] = ")"; - static const char __pyx_k__9[] = "^"; - static const char __pyx_k_gc[] = "gc"; - static const char __pyx_k_id[] = "id"; - static const char __pyx_k_np[] = "np"; - static const char __pyx_k_zi[] = "zi"; - static const char __pyx_k__10[] = ""; - static const char __pyx_k__11[] = ":"; -static const char __pyx_k__12[] = "}"; -static const char __pyx_k__13[] = "("; -static const char __pyx_k__14[] = ","; -static const char __pyx_k__58[] = "?"; -static const char __pyx_k_abc[] = "abc"; -static const char __pyx_k_and[] = " and "; -static const char __pyx_k_got[] = " (got "; -static const char __pyx_k_nan[] = "nan"; -static const char __pyx_k_new[] = "__new__"; -static const char __pyx_k_obj[] = "obj"; -static const char __pyx_k_res[] = "res"; -static const char __pyx_k_sys[] = "sys"; -static const char __pyx_k_val[] = "val"; -static const char __pyx_k_Ri_b[] = "Ri_b"; -static const char __pyx_k_args[] = "args"; -static const char __pyx_k_base[] = "base"; -static const char __pyx_k_copy[] = "copy"; -static const char __pyx_k_covs[] = "covs"; -static const char __pyx_k_dict[] = "__dict__"; -static const char __pyx_k_join[] = "join"; -static const char __pyx_k_kind[] = "kind"; -static const char __pyx_k_main[] = "__main__"; -static const char __pyx_k_mode[] = "mode"; -static const char __pyx_k_name[] = "name"; -static const char __pyx_k_ndim[] = "ndim"; -static const char __pyx_k_pack[] = "pack"; -static const char __pyx_k_self[] = "self"; -static const char __pyx_k_size[] = "size"; -static const char __pyx_k_spec[] = "__spec__"; -static const char __pyx_k_step[] = "step"; -static const char __pyx_k_stop[] = "stop"; -static const char __pyx_k_test[] = "__test__"; -static const char __pyx_k_utf8[] = "utf8"; -static const char __pyx_k_zi_b[] = "zi_b"; -static const char __pyx_k_ASCII[] = "ASCII"; -static const char __pyx_k_R_map[] = "R_map"; -static const char __pyx_k_class[] = "__class__"; -static const char __pyx_k_count[] = "count"; -static const char __pyx_k_dtype[] = "dtype"; -static const char __pyx_k_error[] = "error"; -static const char __pyx_k_flags[] = "flags"; -static const char __pyx_k_index[] = "index"; -static const char __pyx_k_numpy[] = "numpy"; -static const char __pyx_k_order[] = "order"; -static const char __pyx_k_range[] = "range"; -static const char __pyx_k_shape[] = "shape"; -static const char __pyx_k_start[] = "start"; -static const char __pyx_k_state[] = "state"; -static const char __pyx_k_z_map[] = "z_map"; -static const char __pyx_k_covs_b[] = "covs_b"; -static const char __pyx_k_double[] = "double"; -static const char __pyx_k_enable[] = "enable"; -static const char __pyx_k_encode[] = "encode"; -static const char __pyx_k_format[] = "format"; -static const char __pyx_k_import[] = "__import__"; -static const char __pyx_k_logger[] = "logger"; -static const char __pyx_k_name_2[] = "__name__"; -static const char __pyx_k_pickle[] = "pickle"; -static const char __pyx_k_reduce[] = "__reduce__"; -static const char __pyx_k_struct[] = "struct"; -static const char __pyx_k_tmpvec[] = "tmpvec"; -static const char __pyx_k_unpack[] = "unpack"; -static const char __pyx_k_update[] = "update"; -static const char __pyx_k_asarray[] = "asarray"; -static const char __pyx_k_augment[] = "augment"; -static const char __pyx_k_disable[] = "disable"; -static const char __pyx_k_fortran[] = "fortran"; -static const char __pyx_k_gen_dir[] = "gen_dir"; -static const char __pyx_k_memview[] = "memview"; -static const char __pyx_k_predict[] = "predict"; -static const char __pyx_k_state_b[] = "state_b"; -static const char __pyx_k_Ellipsis[] = "Ellipsis"; -static const char __pyx_k_Sequence[] = "Sequence"; -static const char __pyx_k_args_map[] = "args_map"; -static const char __pyx_k_dim_main[] = "dim_main"; -static const char __pyx_k_getstate[] = "__getstate__"; -static const char __pyx_k_itemsize[] = "itemsize"; -static const char __pyx_k_pyx_type[] = "__pyx_type"; -static const char __pyx_k_register[] = "register"; -static const char __pyx_k_setstate[] = "__setstate__"; -static const char __pyx_k_P_initial[] = "P_initial"; -static const char __pyx_k_TypeError[] = "TypeError"; -static const char __pyx_k_enumerate[] = "enumerate"; -static const char __pyx_k_estimates[] = "estimates"; -static const char __pyx_k_isenabled[] = "isenabled"; -static const char __pyx_k_maha_test[] = "maha_test"; -static const char __pyx_k_pyx_state[] = "__pyx_state"; -static const char __pyx_k_reduce_ex[] = "__reduce_ex__"; -static const char __pyx_k_x_initial[] = "x_initial"; -static const char __pyx_k_IndexError[] = "IndexError"; -static const char __pyx_k_ValueError[] = "ValueError"; -static const char __pyx_k_extra_args[] = "extra_args"; -static const char __pyx_k_global_var[] = "global_var"; -static const char __pyx_k_init_state[] = "init_state"; -static const char __pyx_k_norm_quats[] = "norm_quats"; -static const char __pyx_k_pyx_result[] = "__pyx_result"; -static const char __pyx_k_pyx_vtable[] = "__pyx_vtable__"; -static const char __pyx_k_rts_smooth[] = "rts_smooth"; -static const char __pyx_k_set_global[] = "set_global"; -static const char __pyx_k_EKF_sym_pyx[] = "EKF_sym_pyx"; -static const char __pyx_k_ImportError[] = "ImportError"; -static const char __pyx_k_MemoryError[] = "MemoryError"; -static const char __pyx_k_PickleError[] = "PickleError"; -static const char __pyx_k_collections[] = "collections"; -static const char __pyx_k_dim_augment[] = "dim_augment"; -static const char __pyx_k_filter_time[] = "filter_time"; -static const char __pyx_k_global_vars[] = "global_vars"; -static const char __pyx_k_maha_thresh[] = "maha_thresh"; -static const char __pyx_k_dim_main_err[] = "dim_main_err"; -static const char __pyx_k_initializing[] = "_initializing"; -static const char __pyx_k_is_coroutine[] = "_is_coroutine"; -static const char __pyx_k_pyx_checksum[] = "__pyx_checksum"; -static const char __pyx_k_reset_rewind[] = "reset_rewind"; -static const char __pyx_k_stringsource[] = ""; -static const char __pyx_k_version_info[] = "version_info"; -static const char __pyx_k_class_getitem[] = "__class_getitem__"; -static const char __pyx_k_reduce_cython[] = "__reduce_cython__"; -static const char __pyx_k_AssertionError[] = "AssertionError"; -static const char __pyx_k_extra_args_map[] = "extra_args_map"; -static const char __pyx_k_max_rewind_age[] = "max_rewind_age"; -static const char __pyx_k_View_MemoryView[] = "View.MemoryView"; -static const char __pyx_k_allocate_buffer[] = "allocate_buffer"; -static const char __pyx_k_collections_abc[] = "collections.abc"; -static const char __pyx_k_dim_augment_err[] = "dim_augment_err"; -static const char __pyx_k_dtype_is_object[] = "dtype_is_object"; -static const char __pyx_k_get_filter_time[] = "get_filter_time"; -static const char __pyx_k_maha_test_kinds[] = "maha_test_kinds"; -static const char __pyx_k_pyx_PickleError[] = "__pyx_PickleError"; -static const char __pyx_k_quaternion_idxs[] = "quaternion_idxs"; -static const char __pyx_k_set_filter_time[] = "set_filter_time"; -static const char __pyx_k_setstate_cython[] = "__setstate_cython__"; -static const char __pyx_k_EKF_sym_pyx_covs[] = "EKF_sym_pyx.covs"; -static const char __pyx_k_EKF_sym_pyx_state[] = "EKF_sym_pyx.state"; -static const char __pyx_k_ascontiguousarray[] = "ascontiguousarray"; -static const char __pyx_k_get_augment_times[] = "get_augment_times"; -static const char __pyx_k_pyx_unpickle_Enum[] = "__pyx_unpickle_Enum"; -static const char __pyx_k_asyncio_coroutines[] = "asyncio.coroutines"; -static const char __pyx_k_cline_in_traceback[] = "cline_in_traceback"; -static const char __pyx_k_strided_and_direct[] = ""; -static const char __pyx_k_EKF_sym_pyx_augment[] = "EKF_sym_pyx.augment"; -static const char __pyx_k_EKF_sym_pyx_predict[] = "EKF_sym_pyx.predict"; -static const char __pyx_k_NotImplementedError[] = "NotImplementedError"; -static const char __pyx_k_strided_and_indirect[] = ""; -static const char __pyx_k_EKF_sym_pyx_maha_test[] = "EKF_sym_pyx.maha_test"; -static const char __pyx_k_Invalid_shape_in_axis[] = "Invalid shape in axis "; -static const char __pyx_k_contiguous_and_direct[] = ""; -static const char __pyx_k_Cannot_index_with_type[] = "Cannot index with type '"; -static const char __pyx_k_EKF_sym_pyx_init_state[] = "EKF_sym_pyx.init_state"; -static const char __pyx_k_EKF_sym_pyx_rts_smooth[] = "EKF_sym_pyx.rts_smooth"; -static const char __pyx_k_EKF_sym_pyx_set_global[] = "EKF_sym_pyx.set_global"; -static const char __pyx_k_MemoryView_of_r_object[] = ""; -static const char __pyx_k_MemoryView_of_r_at_0x_x[] = ""; -static const char __pyx_k_contiguous_and_indirect[] = ""; -static const char __pyx_k_EKF_sym_pyx_reset_rewind[] = "EKF_sym_pyx.reset_rewind"; -static const char __pyx_k_predict_and_update_batch[] = "predict_and_update_batch"; -static const char __pyx_k_Dimension_d_is_not_direct[] = "Dimension %d is not direct"; -static const char __pyx_k_Index_out_of_bounds_axis_d[] = "Index out of bounds (axis %d)"; -static const char __pyx_k_EKF_sym_pyx___reduce_cython[] = "EKF_sym_pyx.__reduce_cython__"; -static const char __pyx_k_EKF_sym_pyx_get_filter_time[] = "EKF_sym_pyx.get_filter_time"; -static const char __pyx_k_EKF_sym_pyx_set_filter_time[] = "EKF_sym_pyx.set_filter_time"; -static const char __pyx_k_Step_may_not_be_zero_axis_d[] = "Step may not be zero (axis %d)"; -static const char __pyx_k_itemsize_0_for_cython_array[] = "itemsize <= 0 for cython.array"; -static const char __pyx_k_rednose_helpers_ekf_sym_pyx[] = "rednose.helpers.ekf_sym_pyx"; -static const char __pyx_k_EKF_sym_pyx___setstate_cython[] = "EKF_sym_pyx.__setstate_cython__"; -static const char __pyx_k_EKF_sym_pyx_get_augment_times[] = "EKF_sym_pyx.get_augment_times"; -static const char __pyx_k_unable_to_allocate_array_data[] = "unable to allocate array data."; -static const char __pyx_k_strided_and_direct_or_indirect[] = ""; -static const char __pyx_k_numpy_core_multiarray_failed_to[] = "numpy.core.multiarray failed to import"; -static const char __pyx_k_rednose_helpers_ekf_sym_pyx_pyx[] = "rednose/helpers/ekf_sym_pyx.pyx"; -static const char __pyx_k_All_dimensions_preceding_dimensi[] = "All dimensions preceding dimension %d must be indexed and not sliced"; -static const char __pyx_k_Buffer_view_does_not_expose_stri[] = "Buffer view does not expose strides"; -static const char __pyx_k_Can_only_create_a_buffer_that_is[] = "Can only create a buffer that is contiguous in memory."; -static const char __pyx_k_Cannot_assign_to_read_only_memor[] = "Cannot assign to read-only memoryview"; -static const char __pyx_k_Cannot_create_writable_memory_vi[] = "Cannot create writable memory view from read-only memoryview"; -static const char __pyx_k_Cannot_transpose_memoryview_with[] = "Cannot transpose memoryview with indirect dimensions"; -static const char __pyx_k_EKF_sym_pyx_predict_and_update_b[] = "EKF_sym_pyx.predict_and_update_batch"; -static const char __pyx_k_Empty_shape_tuple_for_cython_arr[] = "Empty shape tuple for cython.array"; -static const char __pyx_k_Incompatible_checksums_0x_x_vs_0[] = "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))"; -static const char __pyx_k_Indirect_dimensions_not_supporte[] = "Indirect dimensions not supported"; -static const char __pyx_k_Invalid_mode_expected_c_or_fortr[] = "Invalid mode, expected 'c' or 'fortran', got "; -static const char __pyx_k_Out_of_bounds_on_buffer_access_a[] = "Out of bounds on buffer access (axis "; -static const char __pyx_k_Unable_to_convert_item_to_object[] = "Unable to convert item to object"; -static const char __pyx_k_got_differing_extents_in_dimensi[] = "got differing extents in dimension "; -static const char __pyx_k_no_default___reduce___due_to_non[] = "no default __reduce__ due to non-trivial __cinit__"; -static const char __pyx_k_numpy_core_umath_failed_to_impor[] = "numpy.core.umath failed to import"; -static const char __pyx_k_unable_to_allocate_shape_and_str[] = "unable to allocate shape and strides."; -/* #### Code section: decls ### */ -static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array___cinit__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_shape, Py_ssize_t __pyx_v_itemsize, PyObject *__pyx_v_format, PyObject *__pyx_v_mode, int __pyx_v_allocate_buffer); /* proto */ -static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_2__getbuffer__(struct __pyx_array_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /* proto */ -static void __pyx_array___pyx_pf_15View_dot_MemoryView_5array_4__dealloc__(struct __pyx_array_obj *__pyx_v_self); /* proto */ -static PyObject *__pyx_pf_15View_dot_MemoryView_5array_7memview___get__(struct __pyx_array_obj *__pyx_v_self); /* proto */ -static Py_ssize_t __pyx_array___pyx_pf_15View_dot_MemoryView_5array_6__len__(struct __pyx_array_obj *__pyx_v_self); /* proto */ -static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_8__getattr__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_attr); /* proto */ -static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_10__getitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item); /* proto */ -static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_12__setitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value); /* proto */ -static PyObject *__pyx_pf___pyx_array___reduce_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self); /* proto */ -static PyObject *__pyx_pf___pyx_array_2__setstate_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ -static int __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum___init__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v_name); /* proto */ -static PyObject *__pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum_2__repr__(struct __pyx_MemviewEnum_obj *__pyx_v_self); /* proto */ -static PyObject *__pyx_pf___pyx_MemviewEnum___reduce_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self); /* proto */ -static PyObject *__pyx_pf___pyx_MemviewEnum_2__setstate_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v___pyx_state); /* proto */ -static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview___cinit__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj, int __pyx_v_flags, int __pyx_v_dtype_is_object); /* proto */ -static void __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_2__dealloc__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ -static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_4__getitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index); /* proto */ -static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_6__setitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value); /* proto */ -static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_8__getbuffer__(struct __pyx_memoryview_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /* proto */ -static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_1T___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ -static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4base___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ -static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_5shape___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ -static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_7strides___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ -static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_10suboffsets___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ -static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4ndim___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ -static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_8itemsize___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ -static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_6nbytes___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ -static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4size___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ -static Py_ssize_t __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_10__len__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ -static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_12__repr__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ -static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_14__str__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ -static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_16is_c_contig(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ -static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_18is_f_contig(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ -static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_20copy(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ -static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_22copy_fortran(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ -static PyObject *__pyx_pf___pyx_memoryview___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ -static PyObject *__pyx_pf___pyx_memoryview_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ -static void __pyx_memoryviewslice___pyx_pf_15View_dot_MemoryView_16_memoryviewslice___dealloc__(struct __pyx_memoryviewslice_obj *__pyx_v_self); /* proto */ -static PyObject *__pyx_pf___pyx_memoryviewslice___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self); /* proto */ -static PyObject *__pyx_pf___pyx_memoryviewslice_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ -static PyObject *__pyx_pf_15View_dot_MemoryView___pyx_unpickle_Enum(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v___pyx_type, long __pyx_v___pyx_checksum, PyObject *__pyx_v___pyx_state); /* proto */ -static int __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx___cinit__(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, PyObject *__pyx_v_gen_dir, PyObject *__pyx_v_name, PyArrayObject *__pyx_v_Q, PyArrayObject *__pyx_v_x_initial, PyArrayObject *__pyx_v_P_initial, int __pyx_v_dim_main, int __pyx_v_dim_main_err, int __pyx_v_N, int __pyx_v_dim_augment, int __pyx_v_dim_augment_err, PyObject *__pyx_v_maha_test_kinds, PyObject *__pyx_v_quaternion_idxs, PyObject *__pyx_v_global_vars, double __pyx_v_max_rewind_age, CYTHON_UNUSED PyObject *__pyx_v_logger); /* proto */ -static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_2init_state(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, PyArrayObject *__pyx_v_state, PyArrayObject *__pyx_v_covs, PyObject *__pyx_v_filter_time); /* proto */ -static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_4state(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self); /* proto */ -static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_6covs(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self); /* proto */ -static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_8set_filter_time(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, double __pyx_v_t); /* proto */ -static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_10get_filter_time(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self); /* proto */ -static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_12set_global(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, PyObject *__pyx_v_global_var, double __pyx_v_val); /* proto */ -static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_14reset_rewind(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self); /* proto */ -static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_16predict(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, double __pyx_v_t); /* proto */ -static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_18predict_and_update_batch(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, double __pyx_v_t, int __pyx_v_kind, PyObject *__pyx_v_z, PyObject *__pyx_v_R, PyObject *__pyx_v_extra_args, bool __pyx_v_augment); /* proto */ -static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_20augment(CYTHON_UNUSED struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self); /* proto */ -static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_22get_augment_times(CYTHON_UNUSED struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self); /* proto */ -static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_24rts_smooth(CYTHON_UNUSED struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v_estimates, CYTHON_UNUSED PyObject *__pyx_v_norm_quats); /* proto */ -static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_26maha_test(CYTHON_UNUSED struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v_x, CYTHON_UNUSED PyObject *__pyx_v_P, CYTHON_UNUSED PyObject *__pyx_v_kind, CYTHON_UNUSED PyObject *__pyx_v_z, CYTHON_UNUSED PyObject *__pyx_v_R, CYTHON_UNUSED PyObject *__pyx_v_extra_args, CYTHON_UNUSED PyObject *__pyx_v_maha_thresh); /* proto */ -static void __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_28__dealloc__(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self); /* proto */ -static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_30__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self); /* proto */ -static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_32__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ -static PyObject *__pyx_tp_new_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ -static PyObject *__pyx_tp_new_array(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ -static PyObject *__pyx_tp_new_Enum(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ -static PyObject *__pyx_tp_new_memoryview(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ -static PyObject *__pyx_tp_new__memoryviewslice(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ -/* #### Code section: late_includes ### */ -/* #### Code section: module_state ### */ -typedef struct { - PyObject *__pyx_d; - PyObject *__pyx_b; - PyObject *__pyx_cython_runtime; - PyObject *__pyx_empty_tuple; - PyObject *__pyx_empty_bytes; - PyObject *__pyx_empty_unicode; - #ifdef __Pyx_CyFunction_USED - PyTypeObject *__pyx_CyFunctionType; - #endif - #ifdef __Pyx_FusedFunction_USED - PyTypeObject *__pyx_FusedFunctionType; - #endif - #ifdef __Pyx_Generator_USED - PyTypeObject *__pyx_GeneratorType; - #endif - #ifdef __Pyx_IterableCoroutine_USED - PyTypeObject *__pyx_IterableCoroutineType; - #endif - #ifdef __Pyx_Coroutine_USED - PyTypeObject *__pyx_CoroutineAwaitType; - #endif - #ifdef __Pyx_Coroutine_USED - PyTypeObject *__pyx_CoroutineType; - #endif - #if CYTHON_USE_MODULE_STATE - #endif - #if CYTHON_USE_MODULE_STATE - #endif - #if CYTHON_USE_MODULE_STATE - #endif - #if CYTHON_USE_MODULE_STATE - #endif - #if CYTHON_USE_MODULE_STATE - #endif - #if CYTHON_USE_MODULE_STATE - #endif - #if CYTHON_USE_MODULE_STATE - #endif - #if CYTHON_USE_MODULE_STATE - #endif - #if CYTHON_USE_MODULE_STATE - #endif - #if CYTHON_USE_MODULE_STATE - #endif - PyTypeObject *__pyx_ptype_7cpython_4type_type; - #if CYTHON_USE_MODULE_STATE - #endif - #if CYTHON_USE_MODULE_STATE - #endif - #if CYTHON_USE_MODULE_STATE - #endif - #if CYTHON_USE_MODULE_STATE - #endif - #if CYTHON_USE_MODULE_STATE - #endif - PyTypeObject *__pyx_ptype_5numpy_dtype; - PyTypeObject *__pyx_ptype_5numpy_flatiter; - PyTypeObject *__pyx_ptype_5numpy_broadcast; - PyTypeObject *__pyx_ptype_5numpy_ndarray; - PyTypeObject *__pyx_ptype_5numpy_generic; - PyTypeObject *__pyx_ptype_5numpy_number; - PyTypeObject *__pyx_ptype_5numpy_integer; - PyTypeObject *__pyx_ptype_5numpy_signedinteger; - PyTypeObject *__pyx_ptype_5numpy_unsignedinteger; - PyTypeObject *__pyx_ptype_5numpy_inexact; - PyTypeObject *__pyx_ptype_5numpy_floating; - PyTypeObject *__pyx_ptype_5numpy_complexfloating; - PyTypeObject *__pyx_ptype_5numpy_flexible; - PyTypeObject *__pyx_ptype_5numpy_character; - PyTypeObject *__pyx_ptype_5numpy_ufunc; - #if CYTHON_USE_MODULE_STATE - PyObject *__pyx_type_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx; - PyObject *__pyx_type___pyx_array; - PyObject *__pyx_type___pyx_MemviewEnum; - PyObject *__pyx_type___pyx_memoryview; - PyObject *__pyx_type___pyx_memoryviewslice; - #endif - PyTypeObject *__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx; - PyTypeObject *__pyx_array_type; - PyTypeObject *__pyx_MemviewEnum_type; - PyTypeObject *__pyx_memoryview_type; - PyTypeObject *__pyx_memoryviewslice_type; - PyObject *__pyx_kp_u_; - PyObject *__pyx_n_s_ASCII; - PyObject *__pyx_kp_s_All_dimensions_preceding_dimensi; - PyObject *__pyx_n_s_AssertionError; - PyObject *__pyx_kp_s_Buffer_view_does_not_expose_stri; - PyObject *__pyx_n_u_C; - PyObject *__pyx_kp_s_Can_only_create_a_buffer_that_is; - PyObject *__pyx_kp_s_Cannot_assign_to_read_only_memor; - PyObject *__pyx_kp_s_Cannot_create_writable_memory_vi; - PyObject *__pyx_kp_u_Cannot_index_with_type; - PyObject *__pyx_kp_s_Cannot_transpose_memoryview_with; - PyObject *__pyx_kp_s_Dimension_d_is_not_direct; - PyObject *__pyx_n_s_EKF_sym_pyx; - PyObject *__pyx_n_s_EKF_sym_pyx___reduce_cython; - PyObject *__pyx_n_s_EKF_sym_pyx___setstate_cython; - PyObject *__pyx_n_s_EKF_sym_pyx_augment; - PyObject *__pyx_n_s_EKF_sym_pyx_covs; - PyObject *__pyx_n_s_EKF_sym_pyx_get_augment_times; - PyObject *__pyx_n_s_EKF_sym_pyx_get_filter_time; - PyObject *__pyx_n_s_EKF_sym_pyx_init_state; - PyObject *__pyx_n_s_EKF_sym_pyx_maha_test; - PyObject *__pyx_n_s_EKF_sym_pyx_predict; - PyObject *__pyx_n_s_EKF_sym_pyx_predict_and_update_b; - PyObject *__pyx_n_s_EKF_sym_pyx_reset_rewind; - PyObject *__pyx_n_s_EKF_sym_pyx_rts_smooth; - PyObject *__pyx_n_s_EKF_sym_pyx_set_filter_time; - PyObject *__pyx_n_s_EKF_sym_pyx_set_global; - PyObject *__pyx_n_s_EKF_sym_pyx_state; - PyObject *__pyx_n_s_Ellipsis; - PyObject *__pyx_kp_s_Empty_shape_tuple_for_cython_arr; - PyObject *__pyx_n_s_ImportError; - PyObject *__pyx_kp_s_Incompatible_checksums_0x_x_vs_0; - PyObject *__pyx_n_s_IndexError; - PyObject *__pyx_kp_s_Index_out_of_bounds_axis_d; - PyObject *__pyx_kp_s_Indirect_dimensions_not_supporte; - PyObject *__pyx_kp_u_Invalid_mode_expected_c_or_fortr; - PyObject *__pyx_kp_u_Invalid_shape_in_axis; - PyObject *__pyx_n_s_MemoryError; - PyObject *__pyx_kp_s_MemoryView_of_r_at_0x_x; - PyObject *__pyx_kp_s_MemoryView_of_r_object; - PyObject *__pyx_n_s_N; - PyObject *__pyx_n_s_NotImplementedError; - PyObject *__pyx_n_b_O; - PyObject *__pyx_kp_u_Out_of_bounds_on_buffer_access_a; - PyObject *__pyx_n_s_P; - PyObject *__pyx_n_s_P_initial; - PyObject *__pyx_n_s_PickleError; - PyObject *__pyx_n_s_Q; - PyObject *__pyx_n_s_R; - PyObject *__pyx_n_s_R_map; - PyObject *__pyx_n_s_Ri; - PyObject *__pyx_n_s_Ri_b; - PyObject *__pyx_n_s_Sequence; - PyObject *__pyx_kp_s_Step_may_not_be_zero_axis_d; - PyObject *__pyx_kp_b_T; - PyObject *__pyx_n_s_TypeError; - PyObject *__pyx_kp_s_Unable_to_convert_item_to_object; - PyObject *__pyx_n_s_ValueError; - PyObject *__pyx_n_s_View_MemoryView; - PyObject *__pyx_kp_b__10; - PyObject *__pyx_kp_b__11; - PyObject *__pyx_kp_b__12; - PyObject *__pyx_kp_u__13; - PyObject *__pyx_kp_u__14; - PyObject *__pyx_kp_u__2; - PyObject *__pyx_n_s__3; - PyObject *__pyx_n_s__58; - PyObject *__pyx_kp_u__6; - PyObject *__pyx_kp_u__7; - PyObject *__pyx_kp_b__9; - PyObject *__pyx_n_s_a; - PyObject *__pyx_n_s_abc; - PyObject *__pyx_n_s_allocate_buffer; - PyObject *__pyx_kp_u_and; - PyObject *__pyx_n_s_args; - PyObject *__pyx_n_s_args_map; - PyObject *__pyx_n_s_asarray; - PyObject *__pyx_n_s_ascontiguousarray; - PyObject *__pyx_n_s_asyncio_coroutines; - PyObject *__pyx_n_s_augment; - PyObject *__pyx_n_s_base; - PyObject *__pyx_n_s_c; - PyObject *__pyx_n_u_c; - PyObject *__pyx_n_s_class; - PyObject *__pyx_n_s_class_getitem; - PyObject *__pyx_n_s_cline_in_traceback; - PyObject *__pyx_n_s_collections; - PyObject *__pyx_kp_s_collections_abc; - PyObject *__pyx_kp_s_contiguous_and_direct; - PyObject *__pyx_kp_s_contiguous_and_indirect; - PyObject *__pyx_n_s_copy; - PyObject *__pyx_n_s_count; - PyObject *__pyx_n_s_covs; - PyObject *__pyx_n_s_covs_b; - PyObject *__pyx_n_s_dict; - PyObject *__pyx_n_s_dim_augment; - PyObject *__pyx_n_s_dim_augment_err; - PyObject *__pyx_n_s_dim_main; - PyObject *__pyx_n_s_dim_main_err; - PyObject *__pyx_kp_u_disable; - PyObject *__pyx_n_s_double; - PyObject *__pyx_n_s_dtype; - PyObject *__pyx_n_s_dtype_is_object; - PyObject *__pyx_kp_u_enable; - PyObject *__pyx_n_s_encode; - PyObject *__pyx_n_s_enumerate; - PyObject *__pyx_n_s_error; - PyObject *__pyx_n_s_estimates; - PyObject *__pyx_n_s_extra_args; - PyObject *__pyx_n_s_extra_args_map; - PyObject *__pyx_n_s_filter_time; - PyObject *__pyx_n_s_flags; - PyObject *__pyx_n_s_format; - PyObject *__pyx_n_s_fortran; - PyObject *__pyx_n_u_fortran; - PyObject *__pyx_kp_u_gc; - PyObject *__pyx_n_s_gen_dir; - PyObject *__pyx_n_s_get_augment_times; - PyObject *__pyx_n_s_get_filter_time; - PyObject *__pyx_n_s_getstate; - PyObject *__pyx_n_s_global_var; - PyObject *__pyx_n_s_global_vars; - PyObject *__pyx_kp_u_got; - PyObject *__pyx_kp_u_got_differing_extents_in_dimensi; - PyObject *__pyx_n_s_id; - PyObject *__pyx_n_s_import; - PyObject *__pyx_n_s_index; - PyObject *__pyx_n_s_init_state; - PyObject *__pyx_n_s_initializing; - PyObject *__pyx_n_s_is_coroutine; - PyObject *__pyx_kp_u_isenabled; - PyObject *__pyx_n_s_itemsize; - PyObject *__pyx_kp_s_itemsize_0_for_cython_array; - PyObject *__pyx_n_s_join; - PyObject *__pyx_n_s_kind; - PyObject *__pyx_n_s_logger; - PyObject *__pyx_n_s_maha_test; - PyObject *__pyx_n_s_maha_test_kinds; - PyObject *__pyx_n_s_maha_thresh; - PyObject *__pyx_n_s_main; - PyObject *__pyx_n_s_max_rewind_age; - PyObject *__pyx_n_s_memview; - PyObject *__pyx_n_s_mode; - PyObject *__pyx_n_s_name; - PyObject *__pyx_n_s_name_2; - PyObject *__pyx_n_s_nan; - PyObject *__pyx_n_s_ndim; - PyObject *__pyx_n_s_new; - PyObject *__pyx_kp_s_no_default___reduce___due_to_non; - PyObject *__pyx_n_s_norm_quats; - PyObject *__pyx_n_s_np; - PyObject *__pyx_n_s_numpy; - PyObject *__pyx_kp_u_numpy_core_multiarray_failed_to; - PyObject *__pyx_kp_u_numpy_core_umath_failed_to_impor; - PyObject *__pyx_n_s_obj; - PyObject *__pyx_n_s_order; - PyObject *__pyx_n_s_pack; - PyObject *__pyx_n_s_pickle; - PyObject *__pyx_n_s_predict; - PyObject *__pyx_n_s_predict_and_update_batch; - PyObject *__pyx_n_s_pyx_PickleError; - PyObject *__pyx_n_s_pyx_checksum; - PyObject *__pyx_n_s_pyx_result; - PyObject *__pyx_n_s_pyx_state; - PyObject *__pyx_n_s_pyx_type; - PyObject *__pyx_n_s_pyx_unpickle_Enum; - PyObject *__pyx_n_s_pyx_vtable; - PyObject *__pyx_n_s_quaternion_idxs; - PyObject *__pyx_n_s_range; - PyObject *__pyx_n_s_rednose_helpers_ekf_sym_pyx; - PyObject *__pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx; - PyObject *__pyx_n_s_reduce; - PyObject *__pyx_n_s_reduce_cython; - PyObject *__pyx_n_s_reduce_ex; - PyObject *__pyx_n_s_register; - PyObject *__pyx_n_s_res; - PyObject *__pyx_n_s_reset_rewind; - PyObject *__pyx_n_s_rts_smooth; - PyObject *__pyx_n_s_self; - PyObject *__pyx_n_s_set_filter_time; - PyObject *__pyx_n_s_set_global; - PyObject *__pyx_n_s_setstate; - PyObject *__pyx_n_s_setstate_cython; - PyObject *__pyx_n_s_shape; - PyObject *__pyx_n_s_size; - PyObject *__pyx_n_s_spec; - PyObject *__pyx_n_s_start; - PyObject *__pyx_n_s_state; - PyObject *__pyx_n_s_state_b; - PyObject *__pyx_n_s_step; - PyObject *__pyx_n_s_stop; - PyObject *__pyx_kp_s_strided_and_direct; - PyObject *__pyx_kp_s_strided_and_direct_or_indirect; - PyObject *__pyx_kp_s_strided_and_indirect; - PyObject *__pyx_kp_s_stringsource; - PyObject *__pyx_n_s_struct; - PyObject *__pyx_n_s_sys; - PyObject *__pyx_n_s_t; - PyObject *__pyx_n_s_test; - PyObject *__pyx_n_s_tmpvec; - PyObject *__pyx_kp_s_unable_to_allocate_array_data; - PyObject *__pyx_kp_s_unable_to_allocate_shape_and_str; - PyObject *__pyx_n_s_unpack; - PyObject *__pyx_n_s_update; - PyObject *__pyx_n_u_utf8; - PyObject *__pyx_n_s_val; - PyObject *__pyx_n_s_version_info; - PyObject *__pyx_n_s_x; - PyObject *__pyx_n_s_x_initial; - PyObject *__pyx_n_s_z; - PyObject *__pyx_n_s_z_map; - PyObject *__pyx_n_s_zi; - PyObject *__pyx_n_s_zi_b; - PyObject *__pyx_float_0_95; - PyObject *__pyx_int_0; - PyObject *__pyx_int_1; - PyObject *__pyx_int_3; - PyObject *__pyx_int_112105877; - PyObject *__pyx_int_136983863; - PyObject *__pyx_int_184977713; - PyObject *__pyx_int_neg_1; - PyObject *__pyx_k__17; - PyObject *__pyx_k__18; - PyObject *__pyx_k__19; - PyObject *__pyx_k__28; - PyObject *__pyx_k__33; - PyObject *__pyx_slice__5; - PyObject *__pyx_tuple__4; - PyObject *__pyx_tuple__8; - PyObject *__pyx_tuple__15; - PyObject *__pyx_tuple__16; - PyObject *__pyx_tuple__37; - PyObject *__pyx_tuple__38; - PyObject *__pyx_tuple__39; - PyObject *__pyx_tuple__40; - PyObject *__pyx_tuple__41; - PyObject *__pyx_tuple__42; - PyObject *__pyx_tuple__43; - PyObject *__pyx_tuple__44; - PyObject *__pyx_tuple__45; - PyObject *__pyx_tuple__46; - PyObject *__pyx_tuple__48; - PyObject *__pyx_tuple__49; - PyObject *__pyx_tuple__50; - PyObject *__pyx_tuple__51; - PyObject *__pyx_tuple__52; - PyObject *__pyx_tuple__53; - PyObject *__pyx_tuple__54; - PyObject *__pyx_tuple__55; - PyObject *__pyx_tuple__56; - PyObject *__pyx_tuple__57; - PyObject *__pyx_codeobj__20; - PyObject *__pyx_codeobj__21; - PyObject *__pyx_codeobj__22; - PyObject *__pyx_codeobj__23; - PyObject *__pyx_codeobj__24; - PyObject *__pyx_codeobj__25; - PyObject *__pyx_codeobj__26; - PyObject *__pyx_codeobj__27; - PyObject *__pyx_codeobj__29; - PyObject *__pyx_codeobj__30; - PyObject *__pyx_codeobj__31; - PyObject *__pyx_codeobj__32; - PyObject *__pyx_codeobj__34; - PyObject *__pyx_codeobj__35; - PyObject *__pyx_codeobj__36; - PyObject *__pyx_codeobj__47; -} __pyx_mstate; - -#if CYTHON_USE_MODULE_STATE -#ifdef __cplusplus -namespace { - extern struct PyModuleDef __pyx_moduledef; -} /* anonymous namespace */ -#else -static struct PyModuleDef __pyx_moduledef; -#endif - -#define __pyx_mstate(o) ((__pyx_mstate *)__Pyx_PyModule_GetState(o)) - -#define __pyx_mstate_global (__pyx_mstate(PyState_FindModule(&__pyx_moduledef))) - -#define __pyx_m (PyState_FindModule(&__pyx_moduledef)) -#else -static __pyx_mstate __pyx_mstate_global_static = -#ifdef __cplusplus - {}; -#else - {0}; -#endif -static __pyx_mstate *__pyx_mstate_global = &__pyx_mstate_global_static; -#endif -/* #### Code section: module_state_clear ### */ -#if CYTHON_USE_MODULE_STATE -static int __pyx_m_clear(PyObject *m) { - __pyx_mstate *clear_module_state = __pyx_mstate(m); - if (!clear_module_state) return 0; - Py_CLEAR(clear_module_state->__pyx_d); - Py_CLEAR(clear_module_state->__pyx_b); - Py_CLEAR(clear_module_state->__pyx_cython_runtime); - Py_CLEAR(clear_module_state->__pyx_empty_tuple); - Py_CLEAR(clear_module_state->__pyx_empty_bytes); - Py_CLEAR(clear_module_state->__pyx_empty_unicode); - #ifdef __Pyx_CyFunction_USED - Py_CLEAR(clear_module_state->__pyx_CyFunctionType); - #endif - #ifdef __Pyx_FusedFunction_USED - Py_CLEAR(clear_module_state->__pyx_FusedFunctionType); - #endif - Py_CLEAR(clear_module_state->__pyx_ptype_7cpython_4type_type); - Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_dtype); - Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_flatiter); - Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_broadcast); - Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_ndarray); - Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_generic); - Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_number); - Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_integer); - Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_signedinteger); - Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_unsignedinteger); - Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_inexact); - Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_floating); - Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_complexfloating); - Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_flexible); - Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_character); - Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_ufunc); - Py_CLEAR(clear_module_state->__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx); - Py_CLEAR(clear_module_state->__pyx_type_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx); - Py_CLEAR(clear_module_state->__pyx_array_type); - Py_CLEAR(clear_module_state->__pyx_type___pyx_array); - Py_CLEAR(clear_module_state->__pyx_MemviewEnum_type); - Py_CLEAR(clear_module_state->__pyx_type___pyx_MemviewEnum); - Py_CLEAR(clear_module_state->__pyx_memoryview_type); - Py_CLEAR(clear_module_state->__pyx_type___pyx_memoryview); - Py_CLEAR(clear_module_state->__pyx_memoryviewslice_type); - Py_CLEAR(clear_module_state->__pyx_type___pyx_memoryviewslice); - Py_CLEAR(clear_module_state->__pyx_kp_u_); - Py_CLEAR(clear_module_state->__pyx_n_s_ASCII); - Py_CLEAR(clear_module_state->__pyx_kp_s_All_dimensions_preceding_dimensi); - Py_CLEAR(clear_module_state->__pyx_n_s_AssertionError); - Py_CLEAR(clear_module_state->__pyx_kp_s_Buffer_view_does_not_expose_stri); - Py_CLEAR(clear_module_state->__pyx_n_u_C); - Py_CLEAR(clear_module_state->__pyx_kp_s_Can_only_create_a_buffer_that_is); - Py_CLEAR(clear_module_state->__pyx_kp_s_Cannot_assign_to_read_only_memor); - Py_CLEAR(clear_module_state->__pyx_kp_s_Cannot_create_writable_memory_vi); - Py_CLEAR(clear_module_state->__pyx_kp_u_Cannot_index_with_type); - Py_CLEAR(clear_module_state->__pyx_kp_s_Cannot_transpose_memoryview_with); - Py_CLEAR(clear_module_state->__pyx_kp_s_Dimension_d_is_not_direct); - Py_CLEAR(clear_module_state->__pyx_n_s_EKF_sym_pyx); - Py_CLEAR(clear_module_state->__pyx_n_s_EKF_sym_pyx___reduce_cython); - Py_CLEAR(clear_module_state->__pyx_n_s_EKF_sym_pyx___setstate_cython); - Py_CLEAR(clear_module_state->__pyx_n_s_EKF_sym_pyx_augment); - Py_CLEAR(clear_module_state->__pyx_n_s_EKF_sym_pyx_covs); - Py_CLEAR(clear_module_state->__pyx_n_s_EKF_sym_pyx_get_augment_times); - Py_CLEAR(clear_module_state->__pyx_n_s_EKF_sym_pyx_get_filter_time); - Py_CLEAR(clear_module_state->__pyx_n_s_EKF_sym_pyx_init_state); - Py_CLEAR(clear_module_state->__pyx_n_s_EKF_sym_pyx_maha_test); - Py_CLEAR(clear_module_state->__pyx_n_s_EKF_sym_pyx_predict); - Py_CLEAR(clear_module_state->__pyx_n_s_EKF_sym_pyx_predict_and_update_b); - Py_CLEAR(clear_module_state->__pyx_n_s_EKF_sym_pyx_reset_rewind); - Py_CLEAR(clear_module_state->__pyx_n_s_EKF_sym_pyx_rts_smooth); - Py_CLEAR(clear_module_state->__pyx_n_s_EKF_sym_pyx_set_filter_time); - Py_CLEAR(clear_module_state->__pyx_n_s_EKF_sym_pyx_set_global); - Py_CLEAR(clear_module_state->__pyx_n_s_EKF_sym_pyx_state); - Py_CLEAR(clear_module_state->__pyx_n_s_Ellipsis); - Py_CLEAR(clear_module_state->__pyx_kp_s_Empty_shape_tuple_for_cython_arr); - Py_CLEAR(clear_module_state->__pyx_n_s_ImportError); - Py_CLEAR(clear_module_state->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0); - Py_CLEAR(clear_module_state->__pyx_n_s_IndexError); - Py_CLEAR(clear_module_state->__pyx_kp_s_Index_out_of_bounds_axis_d); - Py_CLEAR(clear_module_state->__pyx_kp_s_Indirect_dimensions_not_supporte); - Py_CLEAR(clear_module_state->__pyx_kp_u_Invalid_mode_expected_c_or_fortr); - Py_CLEAR(clear_module_state->__pyx_kp_u_Invalid_shape_in_axis); - Py_CLEAR(clear_module_state->__pyx_n_s_MemoryError); - Py_CLEAR(clear_module_state->__pyx_kp_s_MemoryView_of_r_at_0x_x); - Py_CLEAR(clear_module_state->__pyx_kp_s_MemoryView_of_r_object); - Py_CLEAR(clear_module_state->__pyx_n_s_N); - Py_CLEAR(clear_module_state->__pyx_n_s_NotImplementedError); - Py_CLEAR(clear_module_state->__pyx_n_b_O); - Py_CLEAR(clear_module_state->__pyx_kp_u_Out_of_bounds_on_buffer_access_a); - Py_CLEAR(clear_module_state->__pyx_n_s_P); - Py_CLEAR(clear_module_state->__pyx_n_s_P_initial); - Py_CLEAR(clear_module_state->__pyx_n_s_PickleError); - Py_CLEAR(clear_module_state->__pyx_n_s_Q); - Py_CLEAR(clear_module_state->__pyx_n_s_R); - Py_CLEAR(clear_module_state->__pyx_n_s_R_map); - Py_CLEAR(clear_module_state->__pyx_n_s_Ri); - Py_CLEAR(clear_module_state->__pyx_n_s_Ri_b); - Py_CLEAR(clear_module_state->__pyx_n_s_Sequence); - Py_CLEAR(clear_module_state->__pyx_kp_s_Step_may_not_be_zero_axis_d); - Py_CLEAR(clear_module_state->__pyx_kp_b_T); - Py_CLEAR(clear_module_state->__pyx_n_s_TypeError); - Py_CLEAR(clear_module_state->__pyx_kp_s_Unable_to_convert_item_to_object); - Py_CLEAR(clear_module_state->__pyx_n_s_ValueError); - Py_CLEAR(clear_module_state->__pyx_n_s_View_MemoryView); - Py_CLEAR(clear_module_state->__pyx_kp_b__10); - Py_CLEAR(clear_module_state->__pyx_kp_b__11); - Py_CLEAR(clear_module_state->__pyx_kp_b__12); - Py_CLEAR(clear_module_state->__pyx_kp_u__13); - Py_CLEAR(clear_module_state->__pyx_kp_u__14); - Py_CLEAR(clear_module_state->__pyx_kp_u__2); - Py_CLEAR(clear_module_state->__pyx_n_s__3); - Py_CLEAR(clear_module_state->__pyx_n_s__58); - Py_CLEAR(clear_module_state->__pyx_kp_u__6); - Py_CLEAR(clear_module_state->__pyx_kp_u__7); - Py_CLEAR(clear_module_state->__pyx_kp_b__9); - Py_CLEAR(clear_module_state->__pyx_n_s_a); - Py_CLEAR(clear_module_state->__pyx_n_s_abc); - Py_CLEAR(clear_module_state->__pyx_n_s_allocate_buffer); - Py_CLEAR(clear_module_state->__pyx_kp_u_and); - Py_CLEAR(clear_module_state->__pyx_n_s_args); - Py_CLEAR(clear_module_state->__pyx_n_s_args_map); - Py_CLEAR(clear_module_state->__pyx_n_s_asarray); - Py_CLEAR(clear_module_state->__pyx_n_s_ascontiguousarray); - Py_CLEAR(clear_module_state->__pyx_n_s_asyncio_coroutines); - Py_CLEAR(clear_module_state->__pyx_n_s_augment); - Py_CLEAR(clear_module_state->__pyx_n_s_base); - Py_CLEAR(clear_module_state->__pyx_n_s_c); - Py_CLEAR(clear_module_state->__pyx_n_u_c); - Py_CLEAR(clear_module_state->__pyx_n_s_class); - Py_CLEAR(clear_module_state->__pyx_n_s_class_getitem); - Py_CLEAR(clear_module_state->__pyx_n_s_cline_in_traceback); - Py_CLEAR(clear_module_state->__pyx_n_s_collections); - Py_CLEAR(clear_module_state->__pyx_kp_s_collections_abc); - Py_CLEAR(clear_module_state->__pyx_kp_s_contiguous_and_direct); - Py_CLEAR(clear_module_state->__pyx_kp_s_contiguous_and_indirect); - Py_CLEAR(clear_module_state->__pyx_n_s_copy); - Py_CLEAR(clear_module_state->__pyx_n_s_count); - Py_CLEAR(clear_module_state->__pyx_n_s_covs); - Py_CLEAR(clear_module_state->__pyx_n_s_covs_b); - Py_CLEAR(clear_module_state->__pyx_n_s_dict); - Py_CLEAR(clear_module_state->__pyx_n_s_dim_augment); - Py_CLEAR(clear_module_state->__pyx_n_s_dim_augment_err); - Py_CLEAR(clear_module_state->__pyx_n_s_dim_main); - Py_CLEAR(clear_module_state->__pyx_n_s_dim_main_err); - Py_CLEAR(clear_module_state->__pyx_kp_u_disable); - Py_CLEAR(clear_module_state->__pyx_n_s_double); - Py_CLEAR(clear_module_state->__pyx_n_s_dtype); - Py_CLEAR(clear_module_state->__pyx_n_s_dtype_is_object); - Py_CLEAR(clear_module_state->__pyx_kp_u_enable); - Py_CLEAR(clear_module_state->__pyx_n_s_encode); - Py_CLEAR(clear_module_state->__pyx_n_s_enumerate); - Py_CLEAR(clear_module_state->__pyx_n_s_error); - Py_CLEAR(clear_module_state->__pyx_n_s_estimates); - Py_CLEAR(clear_module_state->__pyx_n_s_extra_args); - Py_CLEAR(clear_module_state->__pyx_n_s_extra_args_map); - Py_CLEAR(clear_module_state->__pyx_n_s_filter_time); - Py_CLEAR(clear_module_state->__pyx_n_s_flags); - Py_CLEAR(clear_module_state->__pyx_n_s_format); - Py_CLEAR(clear_module_state->__pyx_n_s_fortran); - Py_CLEAR(clear_module_state->__pyx_n_u_fortran); - Py_CLEAR(clear_module_state->__pyx_kp_u_gc); - Py_CLEAR(clear_module_state->__pyx_n_s_gen_dir); - Py_CLEAR(clear_module_state->__pyx_n_s_get_augment_times); - Py_CLEAR(clear_module_state->__pyx_n_s_get_filter_time); - Py_CLEAR(clear_module_state->__pyx_n_s_getstate); - Py_CLEAR(clear_module_state->__pyx_n_s_global_var); - Py_CLEAR(clear_module_state->__pyx_n_s_global_vars); - Py_CLEAR(clear_module_state->__pyx_kp_u_got); - Py_CLEAR(clear_module_state->__pyx_kp_u_got_differing_extents_in_dimensi); - Py_CLEAR(clear_module_state->__pyx_n_s_id); - Py_CLEAR(clear_module_state->__pyx_n_s_import); - Py_CLEAR(clear_module_state->__pyx_n_s_index); - Py_CLEAR(clear_module_state->__pyx_n_s_init_state); - Py_CLEAR(clear_module_state->__pyx_n_s_initializing); - Py_CLEAR(clear_module_state->__pyx_n_s_is_coroutine); - Py_CLEAR(clear_module_state->__pyx_kp_u_isenabled); - Py_CLEAR(clear_module_state->__pyx_n_s_itemsize); - Py_CLEAR(clear_module_state->__pyx_kp_s_itemsize_0_for_cython_array); - Py_CLEAR(clear_module_state->__pyx_n_s_join); - Py_CLEAR(clear_module_state->__pyx_n_s_kind); - Py_CLEAR(clear_module_state->__pyx_n_s_logger); - Py_CLEAR(clear_module_state->__pyx_n_s_maha_test); - Py_CLEAR(clear_module_state->__pyx_n_s_maha_test_kinds); - Py_CLEAR(clear_module_state->__pyx_n_s_maha_thresh); - Py_CLEAR(clear_module_state->__pyx_n_s_main); - Py_CLEAR(clear_module_state->__pyx_n_s_max_rewind_age); - Py_CLEAR(clear_module_state->__pyx_n_s_memview); - Py_CLEAR(clear_module_state->__pyx_n_s_mode); - Py_CLEAR(clear_module_state->__pyx_n_s_name); - Py_CLEAR(clear_module_state->__pyx_n_s_name_2); - Py_CLEAR(clear_module_state->__pyx_n_s_nan); - Py_CLEAR(clear_module_state->__pyx_n_s_ndim); - Py_CLEAR(clear_module_state->__pyx_n_s_new); - Py_CLEAR(clear_module_state->__pyx_kp_s_no_default___reduce___due_to_non); - Py_CLEAR(clear_module_state->__pyx_n_s_norm_quats); - Py_CLEAR(clear_module_state->__pyx_n_s_np); - Py_CLEAR(clear_module_state->__pyx_n_s_numpy); - Py_CLEAR(clear_module_state->__pyx_kp_u_numpy_core_multiarray_failed_to); - Py_CLEAR(clear_module_state->__pyx_kp_u_numpy_core_umath_failed_to_impor); - Py_CLEAR(clear_module_state->__pyx_n_s_obj); - Py_CLEAR(clear_module_state->__pyx_n_s_order); - Py_CLEAR(clear_module_state->__pyx_n_s_pack); - Py_CLEAR(clear_module_state->__pyx_n_s_pickle); - Py_CLEAR(clear_module_state->__pyx_n_s_predict); - Py_CLEAR(clear_module_state->__pyx_n_s_predict_and_update_batch); - Py_CLEAR(clear_module_state->__pyx_n_s_pyx_PickleError); - Py_CLEAR(clear_module_state->__pyx_n_s_pyx_checksum); - Py_CLEAR(clear_module_state->__pyx_n_s_pyx_result); - Py_CLEAR(clear_module_state->__pyx_n_s_pyx_state); - Py_CLEAR(clear_module_state->__pyx_n_s_pyx_type); - Py_CLEAR(clear_module_state->__pyx_n_s_pyx_unpickle_Enum); - Py_CLEAR(clear_module_state->__pyx_n_s_pyx_vtable); - Py_CLEAR(clear_module_state->__pyx_n_s_quaternion_idxs); - Py_CLEAR(clear_module_state->__pyx_n_s_range); - Py_CLEAR(clear_module_state->__pyx_n_s_rednose_helpers_ekf_sym_pyx); - Py_CLEAR(clear_module_state->__pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx); - Py_CLEAR(clear_module_state->__pyx_n_s_reduce); - Py_CLEAR(clear_module_state->__pyx_n_s_reduce_cython); - Py_CLEAR(clear_module_state->__pyx_n_s_reduce_ex); - Py_CLEAR(clear_module_state->__pyx_n_s_register); - Py_CLEAR(clear_module_state->__pyx_n_s_res); - Py_CLEAR(clear_module_state->__pyx_n_s_reset_rewind); - Py_CLEAR(clear_module_state->__pyx_n_s_rts_smooth); - Py_CLEAR(clear_module_state->__pyx_n_s_self); - Py_CLEAR(clear_module_state->__pyx_n_s_set_filter_time); - Py_CLEAR(clear_module_state->__pyx_n_s_set_global); - Py_CLEAR(clear_module_state->__pyx_n_s_setstate); - Py_CLEAR(clear_module_state->__pyx_n_s_setstate_cython); - Py_CLEAR(clear_module_state->__pyx_n_s_shape); - Py_CLEAR(clear_module_state->__pyx_n_s_size); - Py_CLEAR(clear_module_state->__pyx_n_s_spec); - Py_CLEAR(clear_module_state->__pyx_n_s_start); - Py_CLEAR(clear_module_state->__pyx_n_s_state); - Py_CLEAR(clear_module_state->__pyx_n_s_state_b); - Py_CLEAR(clear_module_state->__pyx_n_s_step); - Py_CLEAR(clear_module_state->__pyx_n_s_stop); - Py_CLEAR(clear_module_state->__pyx_kp_s_strided_and_direct); - Py_CLEAR(clear_module_state->__pyx_kp_s_strided_and_direct_or_indirect); - Py_CLEAR(clear_module_state->__pyx_kp_s_strided_and_indirect); - Py_CLEAR(clear_module_state->__pyx_kp_s_stringsource); - Py_CLEAR(clear_module_state->__pyx_n_s_struct); - Py_CLEAR(clear_module_state->__pyx_n_s_sys); - Py_CLEAR(clear_module_state->__pyx_n_s_t); - Py_CLEAR(clear_module_state->__pyx_n_s_test); - Py_CLEAR(clear_module_state->__pyx_n_s_tmpvec); - Py_CLEAR(clear_module_state->__pyx_kp_s_unable_to_allocate_array_data); - Py_CLEAR(clear_module_state->__pyx_kp_s_unable_to_allocate_shape_and_str); - Py_CLEAR(clear_module_state->__pyx_n_s_unpack); - Py_CLEAR(clear_module_state->__pyx_n_s_update); - Py_CLEAR(clear_module_state->__pyx_n_u_utf8); - Py_CLEAR(clear_module_state->__pyx_n_s_val); - Py_CLEAR(clear_module_state->__pyx_n_s_version_info); - Py_CLEAR(clear_module_state->__pyx_n_s_x); - Py_CLEAR(clear_module_state->__pyx_n_s_x_initial); - Py_CLEAR(clear_module_state->__pyx_n_s_z); - Py_CLEAR(clear_module_state->__pyx_n_s_z_map); - Py_CLEAR(clear_module_state->__pyx_n_s_zi); - Py_CLEAR(clear_module_state->__pyx_n_s_zi_b); - Py_CLEAR(clear_module_state->__pyx_float_0_95); - Py_CLEAR(clear_module_state->__pyx_int_0); - Py_CLEAR(clear_module_state->__pyx_int_1); - Py_CLEAR(clear_module_state->__pyx_int_3); - Py_CLEAR(clear_module_state->__pyx_int_112105877); - Py_CLEAR(clear_module_state->__pyx_int_136983863); - Py_CLEAR(clear_module_state->__pyx_int_184977713); - Py_CLEAR(clear_module_state->__pyx_int_neg_1); - Py_CLEAR(clear_module_state->__pyx_k__17); - Py_CLEAR(clear_module_state->__pyx_k__18); - Py_CLEAR(clear_module_state->__pyx_k__19); - Py_CLEAR(clear_module_state->__pyx_k__28); - Py_CLEAR(clear_module_state->__pyx_k__33); - Py_CLEAR(clear_module_state->__pyx_slice__5); - Py_CLEAR(clear_module_state->__pyx_tuple__4); - Py_CLEAR(clear_module_state->__pyx_tuple__8); - Py_CLEAR(clear_module_state->__pyx_tuple__15); - Py_CLEAR(clear_module_state->__pyx_tuple__16); - Py_CLEAR(clear_module_state->__pyx_tuple__37); - Py_CLEAR(clear_module_state->__pyx_tuple__38); - Py_CLEAR(clear_module_state->__pyx_tuple__39); - Py_CLEAR(clear_module_state->__pyx_tuple__40); - Py_CLEAR(clear_module_state->__pyx_tuple__41); - Py_CLEAR(clear_module_state->__pyx_tuple__42); - Py_CLEAR(clear_module_state->__pyx_tuple__43); - Py_CLEAR(clear_module_state->__pyx_tuple__44); - Py_CLEAR(clear_module_state->__pyx_tuple__45); - Py_CLEAR(clear_module_state->__pyx_tuple__46); - Py_CLEAR(clear_module_state->__pyx_tuple__48); - Py_CLEAR(clear_module_state->__pyx_tuple__49); - Py_CLEAR(clear_module_state->__pyx_tuple__50); - Py_CLEAR(clear_module_state->__pyx_tuple__51); - Py_CLEAR(clear_module_state->__pyx_tuple__52); - Py_CLEAR(clear_module_state->__pyx_tuple__53); - Py_CLEAR(clear_module_state->__pyx_tuple__54); - Py_CLEAR(clear_module_state->__pyx_tuple__55); - Py_CLEAR(clear_module_state->__pyx_tuple__56); - Py_CLEAR(clear_module_state->__pyx_tuple__57); - Py_CLEAR(clear_module_state->__pyx_codeobj__20); - Py_CLEAR(clear_module_state->__pyx_codeobj__21); - Py_CLEAR(clear_module_state->__pyx_codeobj__22); - Py_CLEAR(clear_module_state->__pyx_codeobj__23); - Py_CLEAR(clear_module_state->__pyx_codeobj__24); - Py_CLEAR(clear_module_state->__pyx_codeobj__25); - Py_CLEAR(clear_module_state->__pyx_codeobj__26); - Py_CLEAR(clear_module_state->__pyx_codeobj__27); - Py_CLEAR(clear_module_state->__pyx_codeobj__29); - Py_CLEAR(clear_module_state->__pyx_codeobj__30); - Py_CLEAR(clear_module_state->__pyx_codeobj__31); - Py_CLEAR(clear_module_state->__pyx_codeobj__32); - Py_CLEAR(clear_module_state->__pyx_codeobj__34); - Py_CLEAR(clear_module_state->__pyx_codeobj__35); - Py_CLEAR(clear_module_state->__pyx_codeobj__36); - Py_CLEAR(clear_module_state->__pyx_codeobj__47); - return 0; -} -#endif -/* #### Code section: module_state_traverse ### */ -#if CYTHON_USE_MODULE_STATE -static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { - __pyx_mstate *traverse_module_state = __pyx_mstate(m); - if (!traverse_module_state) return 0; - Py_VISIT(traverse_module_state->__pyx_d); - Py_VISIT(traverse_module_state->__pyx_b); - Py_VISIT(traverse_module_state->__pyx_cython_runtime); - Py_VISIT(traverse_module_state->__pyx_empty_tuple); - Py_VISIT(traverse_module_state->__pyx_empty_bytes); - Py_VISIT(traverse_module_state->__pyx_empty_unicode); - #ifdef __Pyx_CyFunction_USED - Py_VISIT(traverse_module_state->__pyx_CyFunctionType); - #endif - #ifdef __Pyx_FusedFunction_USED - Py_VISIT(traverse_module_state->__pyx_FusedFunctionType); - #endif - Py_VISIT(traverse_module_state->__pyx_ptype_7cpython_4type_type); - Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_dtype); - Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_flatiter); - Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_broadcast); - Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_ndarray); - Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_generic); - Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_number); - Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_integer); - Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_signedinteger); - Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_unsignedinteger); - Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_inexact); - Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_floating); - Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_complexfloating); - Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_flexible); - Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_character); - Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_ufunc); - Py_VISIT(traverse_module_state->__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx); - Py_VISIT(traverse_module_state->__pyx_type_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx); - Py_VISIT(traverse_module_state->__pyx_array_type); - Py_VISIT(traverse_module_state->__pyx_type___pyx_array); - Py_VISIT(traverse_module_state->__pyx_MemviewEnum_type); - Py_VISIT(traverse_module_state->__pyx_type___pyx_MemviewEnum); - Py_VISIT(traverse_module_state->__pyx_memoryview_type); - Py_VISIT(traverse_module_state->__pyx_type___pyx_memoryview); - Py_VISIT(traverse_module_state->__pyx_memoryviewslice_type); - Py_VISIT(traverse_module_state->__pyx_type___pyx_memoryviewslice); - Py_VISIT(traverse_module_state->__pyx_kp_u_); - Py_VISIT(traverse_module_state->__pyx_n_s_ASCII); - Py_VISIT(traverse_module_state->__pyx_kp_s_All_dimensions_preceding_dimensi); - Py_VISIT(traverse_module_state->__pyx_n_s_AssertionError); - Py_VISIT(traverse_module_state->__pyx_kp_s_Buffer_view_does_not_expose_stri); - Py_VISIT(traverse_module_state->__pyx_n_u_C); - Py_VISIT(traverse_module_state->__pyx_kp_s_Can_only_create_a_buffer_that_is); - Py_VISIT(traverse_module_state->__pyx_kp_s_Cannot_assign_to_read_only_memor); - Py_VISIT(traverse_module_state->__pyx_kp_s_Cannot_create_writable_memory_vi); - Py_VISIT(traverse_module_state->__pyx_kp_u_Cannot_index_with_type); - Py_VISIT(traverse_module_state->__pyx_kp_s_Cannot_transpose_memoryview_with); - Py_VISIT(traverse_module_state->__pyx_kp_s_Dimension_d_is_not_direct); - Py_VISIT(traverse_module_state->__pyx_n_s_EKF_sym_pyx); - Py_VISIT(traverse_module_state->__pyx_n_s_EKF_sym_pyx___reduce_cython); - Py_VISIT(traverse_module_state->__pyx_n_s_EKF_sym_pyx___setstate_cython); - Py_VISIT(traverse_module_state->__pyx_n_s_EKF_sym_pyx_augment); - Py_VISIT(traverse_module_state->__pyx_n_s_EKF_sym_pyx_covs); - Py_VISIT(traverse_module_state->__pyx_n_s_EKF_sym_pyx_get_augment_times); - Py_VISIT(traverse_module_state->__pyx_n_s_EKF_sym_pyx_get_filter_time); - Py_VISIT(traverse_module_state->__pyx_n_s_EKF_sym_pyx_init_state); - Py_VISIT(traverse_module_state->__pyx_n_s_EKF_sym_pyx_maha_test); - Py_VISIT(traverse_module_state->__pyx_n_s_EKF_sym_pyx_predict); - Py_VISIT(traverse_module_state->__pyx_n_s_EKF_sym_pyx_predict_and_update_b); - Py_VISIT(traverse_module_state->__pyx_n_s_EKF_sym_pyx_reset_rewind); - Py_VISIT(traverse_module_state->__pyx_n_s_EKF_sym_pyx_rts_smooth); - Py_VISIT(traverse_module_state->__pyx_n_s_EKF_sym_pyx_set_filter_time); - Py_VISIT(traverse_module_state->__pyx_n_s_EKF_sym_pyx_set_global); - Py_VISIT(traverse_module_state->__pyx_n_s_EKF_sym_pyx_state); - Py_VISIT(traverse_module_state->__pyx_n_s_Ellipsis); - Py_VISIT(traverse_module_state->__pyx_kp_s_Empty_shape_tuple_for_cython_arr); - Py_VISIT(traverse_module_state->__pyx_n_s_ImportError); - Py_VISIT(traverse_module_state->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0); - Py_VISIT(traverse_module_state->__pyx_n_s_IndexError); - Py_VISIT(traverse_module_state->__pyx_kp_s_Index_out_of_bounds_axis_d); - Py_VISIT(traverse_module_state->__pyx_kp_s_Indirect_dimensions_not_supporte); - Py_VISIT(traverse_module_state->__pyx_kp_u_Invalid_mode_expected_c_or_fortr); - Py_VISIT(traverse_module_state->__pyx_kp_u_Invalid_shape_in_axis); - Py_VISIT(traverse_module_state->__pyx_n_s_MemoryError); - Py_VISIT(traverse_module_state->__pyx_kp_s_MemoryView_of_r_at_0x_x); - Py_VISIT(traverse_module_state->__pyx_kp_s_MemoryView_of_r_object); - Py_VISIT(traverse_module_state->__pyx_n_s_N); - Py_VISIT(traverse_module_state->__pyx_n_s_NotImplementedError); - Py_VISIT(traverse_module_state->__pyx_n_b_O); - Py_VISIT(traverse_module_state->__pyx_kp_u_Out_of_bounds_on_buffer_access_a); - Py_VISIT(traverse_module_state->__pyx_n_s_P); - Py_VISIT(traverse_module_state->__pyx_n_s_P_initial); - Py_VISIT(traverse_module_state->__pyx_n_s_PickleError); - Py_VISIT(traverse_module_state->__pyx_n_s_Q); - Py_VISIT(traverse_module_state->__pyx_n_s_R); - Py_VISIT(traverse_module_state->__pyx_n_s_R_map); - Py_VISIT(traverse_module_state->__pyx_n_s_Ri); - Py_VISIT(traverse_module_state->__pyx_n_s_Ri_b); - Py_VISIT(traverse_module_state->__pyx_n_s_Sequence); - Py_VISIT(traverse_module_state->__pyx_kp_s_Step_may_not_be_zero_axis_d); - Py_VISIT(traverse_module_state->__pyx_kp_b_T); - Py_VISIT(traverse_module_state->__pyx_n_s_TypeError); - Py_VISIT(traverse_module_state->__pyx_kp_s_Unable_to_convert_item_to_object); - Py_VISIT(traverse_module_state->__pyx_n_s_ValueError); - Py_VISIT(traverse_module_state->__pyx_n_s_View_MemoryView); - Py_VISIT(traverse_module_state->__pyx_kp_b__10); - Py_VISIT(traverse_module_state->__pyx_kp_b__11); - Py_VISIT(traverse_module_state->__pyx_kp_b__12); - Py_VISIT(traverse_module_state->__pyx_kp_u__13); - Py_VISIT(traverse_module_state->__pyx_kp_u__14); - Py_VISIT(traverse_module_state->__pyx_kp_u__2); - Py_VISIT(traverse_module_state->__pyx_n_s__3); - Py_VISIT(traverse_module_state->__pyx_n_s__58); - Py_VISIT(traverse_module_state->__pyx_kp_u__6); - Py_VISIT(traverse_module_state->__pyx_kp_u__7); - Py_VISIT(traverse_module_state->__pyx_kp_b__9); - Py_VISIT(traverse_module_state->__pyx_n_s_a); - Py_VISIT(traverse_module_state->__pyx_n_s_abc); - Py_VISIT(traverse_module_state->__pyx_n_s_allocate_buffer); - Py_VISIT(traverse_module_state->__pyx_kp_u_and); - Py_VISIT(traverse_module_state->__pyx_n_s_args); - Py_VISIT(traverse_module_state->__pyx_n_s_args_map); - Py_VISIT(traverse_module_state->__pyx_n_s_asarray); - Py_VISIT(traverse_module_state->__pyx_n_s_ascontiguousarray); - Py_VISIT(traverse_module_state->__pyx_n_s_asyncio_coroutines); - Py_VISIT(traverse_module_state->__pyx_n_s_augment); - Py_VISIT(traverse_module_state->__pyx_n_s_base); - Py_VISIT(traverse_module_state->__pyx_n_s_c); - Py_VISIT(traverse_module_state->__pyx_n_u_c); - Py_VISIT(traverse_module_state->__pyx_n_s_class); - Py_VISIT(traverse_module_state->__pyx_n_s_class_getitem); - Py_VISIT(traverse_module_state->__pyx_n_s_cline_in_traceback); - Py_VISIT(traverse_module_state->__pyx_n_s_collections); - Py_VISIT(traverse_module_state->__pyx_kp_s_collections_abc); - Py_VISIT(traverse_module_state->__pyx_kp_s_contiguous_and_direct); - Py_VISIT(traverse_module_state->__pyx_kp_s_contiguous_and_indirect); - Py_VISIT(traverse_module_state->__pyx_n_s_copy); - Py_VISIT(traverse_module_state->__pyx_n_s_count); - Py_VISIT(traverse_module_state->__pyx_n_s_covs); - Py_VISIT(traverse_module_state->__pyx_n_s_covs_b); - Py_VISIT(traverse_module_state->__pyx_n_s_dict); - Py_VISIT(traverse_module_state->__pyx_n_s_dim_augment); - Py_VISIT(traverse_module_state->__pyx_n_s_dim_augment_err); - Py_VISIT(traverse_module_state->__pyx_n_s_dim_main); - Py_VISIT(traverse_module_state->__pyx_n_s_dim_main_err); - Py_VISIT(traverse_module_state->__pyx_kp_u_disable); - Py_VISIT(traverse_module_state->__pyx_n_s_double); - Py_VISIT(traverse_module_state->__pyx_n_s_dtype); - Py_VISIT(traverse_module_state->__pyx_n_s_dtype_is_object); - Py_VISIT(traverse_module_state->__pyx_kp_u_enable); - Py_VISIT(traverse_module_state->__pyx_n_s_encode); - Py_VISIT(traverse_module_state->__pyx_n_s_enumerate); - Py_VISIT(traverse_module_state->__pyx_n_s_error); - Py_VISIT(traverse_module_state->__pyx_n_s_estimates); - Py_VISIT(traverse_module_state->__pyx_n_s_extra_args); - Py_VISIT(traverse_module_state->__pyx_n_s_extra_args_map); - Py_VISIT(traverse_module_state->__pyx_n_s_filter_time); - Py_VISIT(traverse_module_state->__pyx_n_s_flags); - Py_VISIT(traverse_module_state->__pyx_n_s_format); - Py_VISIT(traverse_module_state->__pyx_n_s_fortran); - Py_VISIT(traverse_module_state->__pyx_n_u_fortran); - Py_VISIT(traverse_module_state->__pyx_kp_u_gc); - Py_VISIT(traverse_module_state->__pyx_n_s_gen_dir); - Py_VISIT(traverse_module_state->__pyx_n_s_get_augment_times); - Py_VISIT(traverse_module_state->__pyx_n_s_get_filter_time); - Py_VISIT(traverse_module_state->__pyx_n_s_getstate); - Py_VISIT(traverse_module_state->__pyx_n_s_global_var); - Py_VISIT(traverse_module_state->__pyx_n_s_global_vars); - Py_VISIT(traverse_module_state->__pyx_kp_u_got); - Py_VISIT(traverse_module_state->__pyx_kp_u_got_differing_extents_in_dimensi); - Py_VISIT(traverse_module_state->__pyx_n_s_id); - Py_VISIT(traverse_module_state->__pyx_n_s_import); - Py_VISIT(traverse_module_state->__pyx_n_s_index); - Py_VISIT(traverse_module_state->__pyx_n_s_init_state); - Py_VISIT(traverse_module_state->__pyx_n_s_initializing); - Py_VISIT(traverse_module_state->__pyx_n_s_is_coroutine); - Py_VISIT(traverse_module_state->__pyx_kp_u_isenabled); - Py_VISIT(traverse_module_state->__pyx_n_s_itemsize); - Py_VISIT(traverse_module_state->__pyx_kp_s_itemsize_0_for_cython_array); - Py_VISIT(traverse_module_state->__pyx_n_s_join); - Py_VISIT(traverse_module_state->__pyx_n_s_kind); - Py_VISIT(traverse_module_state->__pyx_n_s_logger); - Py_VISIT(traverse_module_state->__pyx_n_s_maha_test); - Py_VISIT(traverse_module_state->__pyx_n_s_maha_test_kinds); - Py_VISIT(traverse_module_state->__pyx_n_s_maha_thresh); - Py_VISIT(traverse_module_state->__pyx_n_s_main); - Py_VISIT(traverse_module_state->__pyx_n_s_max_rewind_age); - Py_VISIT(traverse_module_state->__pyx_n_s_memview); - Py_VISIT(traverse_module_state->__pyx_n_s_mode); - Py_VISIT(traverse_module_state->__pyx_n_s_name); - Py_VISIT(traverse_module_state->__pyx_n_s_name_2); - Py_VISIT(traverse_module_state->__pyx_n_s_nan); - Py_VISIT(traverse_module_state->__pyx_n_s_ndim); - Py_VISIT(traverse_module_state->__pyx_n_s_new); - Py_VISIT(traverse_module_state->__pyx_kp_s_no_default___reduce___due_to_non); - Py_VISIT(traverse_module_state->__pyx_n_s_norm_quats); - Py_VISIT(traverse_module_state->__pyx_n_s_np); - Py_VISIT(traverse_module_state->__pyx_n_s_numpy); - Py_VISIT(traverse_module_state->__pyx_kp_u_numpy_core_multiarray_failed_to); - Py_VISIT(traverse_module_state->__pyx_kp_u_numpy_core_umath_failed_to_impor); - Py_VISIT(traverse_module_state->__pyx_n_s_obj); - Py_VISIT(traverse_module_state->__pyx_n_s_order); - Py_VISIT(traverse_module_state->__pyx_n_s_pack); - Py_VISIT(traverse_module_state->__pyx_n_s_pickle); - Py_VISIT(traverse_module_state->__pyx_n_s_predict); - Py_VISIT(traverse_module_state->__pyx_n_s_predict_and_update_batch); - Py_VISIT(traverse_module_state->__pyx_n_s_pyx_PickleError); - Py_VISIT(traverse_module_state->__pyx_n_s_pyx_checksum); - Py_VISIT(traverse_module_state->__pyx_n_s_pyx_result); - Py_VISIT(traverse_module_state->__pyx_n_s_pyx_state); - Py_VISIT(traverse_module_state->__pyx_n_s_pyx_type); - Py_VISIT(traverse_module_state->__pyx_n_s_pyx_unpickle_Enum); - Py_VISIT(traverse_module_state->__pyx_n_s_pyx_vtable); - Py_VISIT(traverse_module_state->__pyx_n_s_quaternion_idxs); - Py_VISIT(traverse_module_state->__pyx_n_s_range); - Py_VISIT(traverse_module_state->__pyx_n_s_rednose_helpers_ekf_sym_pyx); - Py_VISIT(traverse_module_state->__pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx); - Py_VISIT(traverse_module_state->__pyx_n_s_reduce); - Py_VISIT(traverse_module_state->__pyx_n_s_reduce_cython); - Py_VISIT(traverse_module_state->__pyx_n_s_reduce_ex); - Py_VISIT(traverse_module_state->__pyx_n_s_register); - Py_VISIT(traverse_module_state->__pyx_n_s_res); - Py_VISIT(traverse_module_state->__pyx_n_s_reset_rewind); - Py_VISIT(traverse_module_state->__pyx_n_s_rts_smooth); - Py_VISIT(traverse_module_state->__pyx_n_s_self); - Py_VISIT(traverse_module_state->__pyx_n_s_set_filter_time); - Py_VISIT(traverse_module_state->__pyx_n_s_set_global); - Py_VISIT(traverse_module_state->__pyx_n_s_setstate); - Py_VISIT(traverse_module_state->__pyx_n_s_setstate_cython); - Py_VISIT(traverse_module_state->__pyx_n_s_shape); - Py_VISIT(traverse_module_state->__pyx_n_s_size); - Py_VISIT(traverse_module_state->__pyx_n_s_spec); - Py_VISIT(traverse_module_state->__pyx_n_s_start); - Py_VISIT(traverse_module_state->__pyx_n_s_state); - Py_VISIT(traverse_module_state->__pyx_n_s_state_b); - Py_VISIT(traverse_module_state->__pyx_n_s_step); - Py_VISIT(traverse_module_state->__pyx_n_s_stop); - Py_VISIT(traverse_module_state->__pyx_kp_s_strided_and_direct); - Py_VISIT(traverse_module_state->__pyx_kp_s_strided_and_direct_or_indirect); - Py_VISIT(traverse_module_state->__pyx_kp_s_strided_and_indirect); - Py_VISIT(traverse_module_state->__pyx_kp_s_stringsource); - Py_VISIT(traverse_module_state->__pyx_n_s_struct); - Py_VISIT(traverse_module_state->__pyx_n_s_sys); - Py_VISIT(traverse_module_state->__pyx_n_s_t); - Py_VISIT(traverse_module_state->__pyx_n_s_test); - Py_VISIT(traverse_module_state->__pyx_n_s_tmpvec); - Py_VISIT(traverse_module_state->__pyx_kp_s_unable_to_allocate_array_data); - Py_VISIT(traverse_module_state->__pyx_kp_s_unable_to_allocate_shape_and_str); - Py_VISIT(traverse_module_state->__pyx_n_s_unpack); - Py_VISIT(traverse_module_state->__pyx_n_s_update); - Py_VISIT(traverse_module_state->__pyx_n_u_utf8); - Py_VISIT(traverse_module_state->__pyx_n_s_val); - Py_VISIT(traverse_module_state->__pyx_n_s_version_info); - Py_VISIT(traverse_module_state->__pyx_n_s_x); - Py_VISIT(traverse_module_state->__pyx_n_s_x_initial); - Py_VISIT(traverse_module_state->__pyx_n_s_z); - Py_VISIT(traverse_module_state->__pyx_n_s_z_map); - Py_VISIT(traverse_module_state->__pyx_n_s_zi); - Py_VISIT(traverse_module_state->__pyx_n_s_zi_b); - Py_VISIT(traverse_module_state->__pyx_float_0_95); - Py_VISIT(traverse_module_state->__pyx_int_0); - Py_VISIT(traverse_module_state->__pyx_int_1); - Py_VISIT(traverse_module_state->__pyx_int_3); - Py_VISIT(traverse_module_state->__pyx_int_112105877); - Py_VISIT(traverse_module_state->__pyx_int_136983863); - Py_VISIT(traverse_module_state->__pyx_int_184977713); - Py_VISIT(traverse_module_state->__pyx_int_neg_1); - Py_VISIT(traverse_module_state->__pyx_k__17); - Py_VISIT(traverse_module_state->__pyx_k__18); - Py_VISIT(traverse_module_state->__pyx_k__19); - Py_VISIT(traverse_module_state->__pyx_k__28); - Py_VISIT(traverse_module_state->__pyx_k__33); - Py_VISIT(traverse_module_state->__pyx_slice__5); - Py_VISIT(traverse_module_state->__pyx_tuple__4); - Py_VISIT(traverse_module_state->__pyx_tuple__8); - Py_VISIT(traverse_module_state->__pyx_tuple__15); - Py_VISIT(traverse_module_state->__pyx_tuple__16); - Py_VISIT(traverse_module_state->__pyx_tuple__37); - Py_VISIT(traverse_module_state->__pyx_tuple__38); - Py_VISIT(traverse_module_state->__pyx_tuple__39); - Py_VISIT(traverse_module_state->__pyx_tuple__40); - Py_VISIT(traverse_module_state->__pyx_tuple__41); - Py_VISIT(traverse_module_state->__pyx_tuple__42); - Py_VISIT(traverse_module_state->__pyx_tuple__43); - Py_VISIT(traverse_module_state->__pyx_tuple__44); - Py_VISIT(traverse_module_state->__pyx_tuple__45); - Py_VISIT(traverse_module_state->__pyx_tuple__46); - Py_VISIT(traverse_module_state->__pyx_tuple__48); - Py_VISIT(traverse_module_state->__pyx_tuple__49); - Py_VISIT(traverse_module_state->__pyx_tuple__50); - Py_VISIT(traverse_module_state->__pyx_tuple__51); - Py_VISIT(traverse_module_state->__pyx_tuple__52); - Py_VISIT(traverse_module_state->__pyx_tuple__53); - Py_VISIT(traverse_module_state->__pyx_tuple__54); - Py_VISIT(traverse_module_state->__pyx_tuple__55); - Py_VISIT(traverse_module_state->__pyx_tuple__56); - Py_VISIT(traverse_module_state->__pyx_tuple__57); - Py_VISIT(traverse_module_state->__pyx_codeobj__20); - Py_VISIT(traverse_module_state->__pyx_codeobj__21); - Py_VISIT(traverse_module_state->__pyx_codeobj__22); - Py_VISIT(traverse_module_state->__pyx_codeobj__23); - Py_VISIT(traverse_module_state->__pyx_codeobj__24); - Py_VISIT(traverse_module_state->__pyx_codeobj__25); - Py_VISIT(traverse_module_state->__pyx_codeobj__26); - Py_VISIT(traverse_module_state->__pyx_codeobj__27); - Py_VISIT(traverse_module_state->__pyx_codeobj__29); - Py_VISIT(traverse_module_state->__pyx_codeobj__30); - Py_VISIT(traverse_module_state->__pyx_codeobj__31); - Py_VISIT(traverse_module_state->__pyx_codeobj__32); - Py_VISIT(traverse_module_state->__pyx_codeobj__34); - Py_VISIT(traverse_module_state->__pyx_codeobj__35); - Py_VISIT(traverse_module_state->__pyx_codeobj__36); - Py_VISIT(traverse_module_state->__pyx_codeobj__47); - return 0; -} -#endif -/* #### Code section: module_state_defines ### */ -#define __pyx_d __pyx_mstate_global->__pyx_d -#define __pyx_b __pyx_mstate_global->__pyx_b -#define __pyx_cython_runtime __pyx_mstate_global->__pyx_cython_runtime -#define __pyx_empty_tuple __pyx_mstate_global->__pyx_empty_tuple -#define __pyx_empty_bytes __pyx_mstate_global->__pyx_empty_bytes -#define __pyx_empty_unicode __pyx_mstate_global->__pyx_empty_unicode -#ifdef __Pyx_CyFunction_USED -#define __pyx_CyFunctionType __pyx_mstate_global->__pyx_CyFunctionType -#endif -#ifdef __Pyx_FusedFunction_USED -#define __pyx_FusedFunctionType __pyx_mstate_global->__pyx_FusedFunctionType -#endif -#ifdef __Pyx_Generator_USED -#define __pyx_GeneratorType __pyx_mstate_global->__pyx_GeneratorType -#endif -#ifdef __Pyx_IterableCoroutine_USED -#define __pyx_IterableCoroutineType __pyx_mstate_global->__pyx_IterableCoroutineType -#endif -#ifdef __Pyx_Coroutine_USED -#define __pyx_CoroutineAwaitType __pyx_mstate_global->__pyx_CoroutineAwaitType -#endif -#ifdef __Pyx_Coroutine_USED -#define __pyx_CoroutineType __pyx_mstate_global->__pyx_CoroutineType -#endif -#if CYTHON_USE_MODULE_STATE -#endif -#if CYTHON_USE_MODULE_STATE -#endif -#if CYTHON_USE_MODULE_STATE -#endif -#if CYTHON_USE_MODULE_STATE -#endif -#if CYTHON_USE_MODULE_STATE -#endif -#if CYTHON_USE_MODULE_STATE -#endif -#if CYTHON_USE_MODULE_STATE -#endif -#if CYTHON_USE_MODULE_STATE -#endif -#if CYTHON_USE_MODULE_STATE -#endif -#if CYTHON_USE_MODULE_STATE -#endif -#define __pyx_ptype_7cpython_4type_type __pyx_mstate_global->__pyx_ptype_7cpython_4type_type -#if CYTHON_USE_MODULE_STATE -#endif -#if CYTHON_USE_MODULE_STATE -#endif -#if CYTHON_USE_MODULE_STATE -#endif -#if CYTHON_USE_MODULE_STATE -#endif -#if CYTHON_USE_MODULE_STATE -#endif -#define __pyx_ptype_5numpy_dtype __pyx_mstate_global->__pyx_ptype_5numpy_dtype -#define __pyx_ptype_5numpy_flatiter __pyx_mstate_global->__pyx_ptype_5numpy_flatiter -#define __pyx_ptype_5numpy_broadcast __pyx_mstate_global->__pyx_ptype_5numpy_broadcast -#define __pyx_ptype_5numpy_ndarray __pyx_mstate_global->__pyx_ptype_5numpy_ndarray -#define __pyx_ptype_5numpy_generic __pyx_mstate_global->__pyx_ptype_5numpy_generic -#define __pyx_ptype_5numpy_number __pyx_mstate_global->__pyx_ptype_5numpy_number -#define __pyx_ptype_5numpy_integer __pyx_mstate_global->__pyx_ptype_5numpy_integer -#define __pyx_ptype_5numpy_signedinteger __pyx_mstate_global->__pyx_ptype_5numpy_signedinteger -#define __pyx_ptype_5numpy_unsignedinteger __pyx_mstate_global->__pyx_ptype_5numpy_unsignedinteger -#define __pyx_ptype_5numpy_inexact __pyx_mstate_global->__pyx_ptype_5numpy_inexact -#define __pyx_ptype_5numpy_floating __pyx_mstate_global->__pyx_ptype_5numpy_floating -#define __pyx_ptype_5numpy_complexfloating __pyx_mstate_global->__pyx_ptype_5numpy_complexfloating -#define __pyx_ptype_5numpy_flexible __pyx_mstate_global->__pyx_ptype_5numpy_flexible -#define __pyx_ptype_5numpy_character __pyx_mstate_global->__pyx_ptype_5numpy_character -#define __pyx_ptype_5numpy_ufunc __pyx_mstate_global->__pyx_ptype_5numpy_ufunc -#if CYTHON_USE_MODULE_STATE -#define __pyx_type_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx __pyx_mstate_global->__pyx_type_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx -#define __pyx_type___pyx_array __pyx_mstate_global->__pyx_type___pyx_array -#define __pyx_type___pyx_MemviewEnum __pyx_mstate_global->__pyx_type___pyx_MemviewEnum -#define __pyx_type___pyx_memoryview __pyx_mstate_global->__pyx_type___pyx_memoryview -#define __pyx_type___pyx_memoryviewslice __pyx_mstate_global->__pyx_type___pyx_memoryviewslice -#endif -#define __pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx __pyx_mstate_global->__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx -#define __pyx_array_type __pyx_mstate_global->__pyx_array_type -#define __pyx_MemviewEnum_type __pyx_mstate_global->__pyx_MemviewEnum_type -#define __pyx_memoryview_type __pyx_mstate_global->__pyx_memoryview_type -#define __pyx_memoryviewslice_type __pyx_mstate_global->__pyx_memoryviewslice_type -#define __pyx_kp_u_ __pyx_mstate_global->__pyx_kp_u_ -#define __pyx_n_s_ASCII __pyx_mstate_global->__pyx_n_s_ASCII -#define __pyx_kp_s_All_dimensions_preceding_dimensi __pyx_mstate_global->__pyx_kp_s_All_dimensions_preceding_dimensi -#define __pyx_n_s_AssertionError __pyx_mstate_global->__pyx_n_s_AssertionError -#define __pyx_kp_s_Buffer_view_does_not_expose_stri __pyx_mstate_global->__pyx_kp_s_Buffer_view_does_not_expose_stri -#define __pyx_n_u_C __pyx_mstate_global->__pyx_n_u_C -#define __pyx_kp_s_Can_only_create_a_buffer_that_is __pyx_mstate_global->__pyx_kp_s_Can_only_create_a_buffer_that_is -#define __pyx_kp_s_Cannot_assign_to_read_only_memor __pyx_mstate_global->__pyx_kp_s_Cannot_assign_to_read_only_memor -#define __pyx_kp_s_Cannot_create_writable_memory_vi __pyx_mstate_global->__pyx_kp_s_Cannot_create_writable_memory_vi -#define __pyx_kp_u_Cannot_index_with_type __pyx_mstate_global->__pyx_kp_u_Cannot_index_with_type -#define __pyx_kp_s_Cannot_transpose_memoryview_with __pyx_mstate_global->__pyx_kp_s_Cannot_transpose_memoryview_with -#define __pyx_kp_s_Dimension_d_is_not_direct __pyx_mstate_global->__pyx_kp_s_Dimension_d_is_not_direct -#define __pyx_n_s_EKF_sym_pyx __pyx_mstate_global->__pyx_n_s_EKF_sym_pyx -#define __pyx_n_s_EKF_sym_pyx___reduce_cython __pyx_mstate_global->__pyx_n_s_EKF_sym_pyx___reduce_cython -#define __pyx_n_s_EKF_sym_pyx___setstate_cython __pyx_mstate_global->__pyx_n_s_EKF_sym_pyx___setstate_cython -#define __pyx_n_s_EKF_sym_pyx_augment __pyx_mstate_global->__pyx_n_s_EKF_sym_pyx_augment -#define __pyx_n_s_EKF_sym_pyx_covs __pyx_mstate_global->__pyx_n_s_EKF_sym_pyx_covs -#define __pyx_n_s_EKF_sym_pyx_get_augment_times __pyx_mstate_global->__pyx_n_s_EKF_sym_pyx_get_augment_times -#define __pyx_n_s_EKF_sym_pyx_get_filter_time __pyx_mstate_global->__pyx_n_s_EKF_sym_pyx_get_filter_time -#define __pyx_n_s_EKF_sym_pyx_init_state __pyx_mstate_global->__pyx_n_s_EKF_sym_pyx_init_state -#define __pyx_n_s_EKF_sym_pyx_maha_test __pyx_mstate_global->__pyx_n_s_EKF_sym_pyx_maha_test -#define __pyx_n_s_EKF_sym_pyx_predict __pyx_mstate_global->__pyx_n_s_EKF_sym_pyx_predict -#define __pyx_n_s_EKF_sym_pyx_predict_and_update_b __pyx_mstate_global->__pyx_n_s_EKF_sym_pyx_predict_and_update_b -#define __pyx_n_s_EKF_sym_pyx_reset_rewind __pyx_mstate_global->__pyx_n_s_EKF_sym_pyx_reset_rewind -#define __pyx_n_s_EKF_sym_pyx_rts_smooth __pyx_mstate_global->__pyx_n_s_EKF_sym_pyx_rts_smooth -#define __pyx_n_s_EKF_sym_pyx_set_filter_time __pyx_mstate_global->__pyx_n_s_EKF_sym_pyx_set_filter_time -#define __pyx_n_s_EKF_sym_pyx_set_global __pyx_mstate_global->__pyx_n_s_EKF_sym_pyx_set_global -#define __pyx_n_s_EKF_sym_pyx_state __pyx_mstate_global->__pyx_n_s_EKF_sym_pyx_state -#define __pyx_n_s_Ellipsis __pyx_mstate_global->__pyx_n_s_Ellipsis -#define __pyx_kp_s_Empty_shape_tuple_for_cython_arr __pyx_mstate_global->__pyx_kp_s_Empty_shape_tuple_for_cython_arr -#define __pyx_n_s_ImportError __pyx_mstate_global->__pyx_n_s_ImportError -#define __pyx_kp_s_Incompatible_checksums_0x_x_vs_0 __pyx_mstate_global->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0 -#define __pyx_n_s_IndexError __pyx_mstate_global->__pyx_n_s_IndexError -#define __pyx_kp_s_Index_out_of_bounds_axis_d __pyx_mstate_global->__pyx_kp_s_Index_out_of_bounds_axis_d -#define __pyx_kp_s_Indirect_dimensions_not_supporte __pyx_mstate_global->__pyx_kp_s_Indirect_dimensions_not_supporte -#define __pyx_kp_u_Invalid_mode_expected_c_or_fortr __pyx_mstate_global->__pyx_kp_u_Invalid_mode_expected_c_or_fortr -#define __pyx_kp_u_Invalid_shape_in_axis __pyx_mstate_global->__pyx_kp_u_Invalid_shape_in_axis -#define __pyx_n_s_MemoryError __pyx_mstate_global->__pyx_n_s_MemoryError -#define __pyx_kp_s_MemoryView_of_r_at_0x_x __pyx_mstate_global->__pyx_kp_s_MemoryView_of_r_at_0x_x -#define __pyx_kp_s_MemoryView_of_r_object __pyx_mstate_global->__pyx_kp_s_MemoryView_of_r_object -#define __pyx_n_s_N __pyx_mstate_global->__pyx_n_s_N -#define __pyx_n_s_NotImplementedError __pyx_mstate_global->__pyx_n_s_NotImplementedError -#define __pyx_n_b_O __pyx_mstate_global->__pyx_n_b_O -#define __pyx_kp_u_Out_of_bounds_on_buffer_access_a __pyx_mstate_global->__pyx_kp_u_Out_of_bounds_on_buffer_access_a -#define __pyx_n_s_P __pyx_mstate_global->__pyx_n_s_P -#define __pyx_n_s_P_initial __pyx_mstate_global->__pyx_n_s_P_initial -#define __pyx_n_s_PickleError __pyx_mstate_global->__pyx_n_s_PickleError -#define __pyx_n_s_Q __pyx_mstate_global->__pyx_n_s_Q -#define __pyx_n_s_R __pyx_mstate_global->__pyx_n_s_R -#define __pyx_n_s_R_map __pyx_mstate_global->__pyx_n_s_R_map -#define __pyx_n_s_Ri __pyx_mstate_global->__pyx_n_s_Ri -#define __pyx_n_s_Ri_b __pyx_mstate_global->__pyx_n_s_Ri_b -#define __pyx_n_s_Sequence __pyx_mstate_global->__pyx_n_s_Sequence -#define __pyx_kp_s_Step_may_not_be_zero_axis_d __pyx_mstate_global->__pyx_kp_s_Step_may_not_be_zero_axis_d -#define __pyx_kp_b_T __pyx_mstate_global->__pyx_kp_b_T -#define __pyx_n_s_TypeError __pyx_mstate_global->__pyx_n_s_TypeError -#define __pyx_kp_s_Unable_to_convert_item_to_object __pyx_mstate_global->__pyx_kp_s_Unable_to_convert_item_to_object -#define __pyx_n_s_ValueError __pyx_mstate_global->__pyx_n_s_ValueError -#define __pyx_n_s_View_MemoryView __pyx_mstate_global->__pyx_n_s_View_MemoryView -#define __pyx_kp_b__10 __pyx_mstate_global->__pyx_kp_b__10 -#define __pyx_kp_b__11 __pyx_mstate_global->__pyx_kp_b__11 -#define __pyx_kp_b__12 __pyx_mstate_global->__pyx_kp_b__12 -#define __pyx_kp_u__13 __pyx_mstate_global->__pyx_kp_u__13 -#define __pyx_kp_u__14 __pyx_mstate_global->__pyx_kp_u__14 -#define __pyx_kp_u__2 __pyx_mstate_global->__pyx_kp_u__2 -#define __pyx_n_s__3 __pyx_mstate_global->__pyx_n_s__3 -#define __pyx_n_s__58 __pyx_mstate_global->__pyx_n_s__58 -#define __pyx_kp_u__6 __pyx_mstate_global->__pyx_kp_u__6 -#define __pyx_kp_u__7 __pyx_mstate_global->__pyx_kp_u__7 -#define __pyx_kp_b__9 __pyx_mstate_global->__pyx_kp_b__9 -#define __pyx_n_s_a __pyx_mstate_global->__pyx_n_s_a -#define __pyx_n_s_abc __pyx_mstate_global->__pyx_n_s_abc -#define __pyx_n_s_allocate_buffer __pyx_mstate_global->__pyx_n_s_allocate_buffer -#define __pyx_kp_u_and __pyx_mstate_global->__pyx_kp_u_and -#define __pyx_n_s_args __pyx_mstate_global->__pyx_n_s_args -#define __pyx_n_s_args_map __pyx_mstate_global->__pyx_n_s_args_map -#define __pyx_n_s_asarray __pyx_mstate_global->__pyx_n_s_asarray -#define __pyx_n_s_ascontiguousarray __pyx_mstate_global->__pyx_n_s_ascontiguousarray -#define __pyx_n_s_asyncio_coroutines __pyx_mstate_global->__pyx_n_s_asyncio_coroutines -#define __pyx_n_s_augment __pyx_mstate_global->__pyx_n_s_augment -#define __pyx_n_s_base __pyx_mstate_global->__pyx_n_s_base -#define __pyx_n_s_c __pyx_mstate_global->__pyx_n_s_c -#define __pyx_n_u_c __pyx_mstate_global->__pyx_n_u_c -#define __pyx_n_s_class __pyx_mstate_global->__pyx_n_s_class -#define __pyx_n_s_class_getitem __pyx_mstate_global->__pyx_n_s_class_getitem -#define __pyx_n_s_cline_in_traceback __pyx_mstate_global->__pyx_n_s_cline_in_traceback -#define __pyx_n_s_collections __pyx_mstate_global->__pyx_n_s_collections -#define __pyx_kp_s_collections_abc __pyx_mstate_global->__pyx_kp_s_collections_abc -#define __pyx_kp_s_contiguous_and_direct __pyx_mstate_global->__pyx_kp_s_contiguous_and_direct -#define __pyx_kp_s_contiguous_and_indirect __pyx_mstate_global->__pyx_kp_s_contiguous_and_indirect -#define __pyx_n_s_copy __pyx_mstate_global->__pyx_n_s_copy -#define __pyx_n_s_count __pyx_mstate_global->__pyx_n_s_count -#define __pyx_n_s_covs __pyx_mstate_global->__pyx_n_s_covs -#define __pyx_n_s_covs_b __pyx_mstate_global->__pyx_n_s_covs_b -#define __pyx_n_s_dict __pyx_mstate_global->__pyx_n_s_dict -#define __pyx_n_s_dim_augment __pyx_mstate_global->__pyx_n_s_dim_augment -#define __pyx_n_s_dim_augment_err __pyx_mstate_global->__pyx_n_s_dim_augment_err -#define __pyx_n_s_dim_main __pyx_mstate_global->__pyx_n_s_dim_main -#define __pyx_n_s_dim_main_err __pyx_mstate_global->__pyx_n_s_dim_main_err -#define __pyx_kp_u_disable __pyx_mstate_global->__pyx_kp_u_disable -#define __pyx_n_s_double __pyx_mstate_global->__pyx_n_s_double -#define __pyx_n_s_dtype __pyx_mstate_global->__pyx_n_s_dtype -#define __pyx_n_s_dtype_is_object __pyx_mstate_global->__pyx_n_s_dtype_is_object -#define __pyx_kp_u_enable __pyx_mstate_global->__pyx_kp_u_enable -#define __pyx_n_s_encode __pyx_mstate_global->__pyx_n_s_encode -#define __pyx_n_s_enumerate __pyx_mstate_global->__pyx_n_s_enumerate -#define __pyx_n_s_error __pyx_mstate_global->__pyx_n_s_error -#define __pyx_n_s_estimates __pyx_mstate_global->__pyx_n_s_estimates -#define __pyx_n_s_extra_args __pyx_mstate_global->__pyx_n_s_extra_args -#define __pyx_n_s_extra_args_map __pyx_mstate_global->__pyx_n_s_extra_args_map -#define __pyx_n_s_filter_time __pyx_mstate_global->__pyx_n_s_filter_time -#define __pyx_n_s_flags __pyx_mstate_global->__pyx_n_s_flags -#define __pyx_n_s_format __pyx_mstate_global->__pyx_n_s_format -#define __pyx_n_s_fortran __pyx_mstate_global->__pyx_n_s_fortran -#define __pyx_n_u_fortran __pyx_mstate_global->__pyx_n_u_fortran -#define __pyx_kp_u_gc __pyx_mstate_global->__pyx_kp_u_gc -#define __pyx_n_s_gen_dir __pyx_mstate_global->__pyx_n_s_gen_dir -#define __pyx_n_s_get_augment_times __pyx_mstate_global->__pyx_n_s_get_augment_times -#define __pyx_n_s_get_filter_time __pyx_mstate_global->__pyx_n_s_get_filter_time -#define __pyx_n_s_getstate __pyx_mstate_global->__pyx_n_s_getstate -#define __pyx_n_s_global_var __pyx_mstate_global->__pyx_n_s_global_var -#define __pyx_n_s_global_vars __pyx_mstate_global->__pyx_n_s_global_vars -#define __pyx_kp_u_got __pyx_mstate_global->__pyx_kp_u_got -#define __pyx_kp_u_got_differing_extents_in_dimensi __pyx_mstate_global->__pyx_kp_u_got_differing_extents_in_dimensi -#define __pyx_n_s_id __pyx_mstate_global->__pyx_n_s_id -#define __pyx_n_s_import __pyx_mstate_global->__pyx_n_s_import -#define __pyx_n_s_index __pyx_mstate_global->__pyx_n_s_index -#define __pyx_n_s_init_state __pyx_mstate_global->__pyx_n_s_init_state -#define __pyx_n_s_initializing __pyx_mstate_global->__pyx_n_s_initializing -#define __pyx_n_s_is_coroutine __pyx_mstate_global->__pyx_n_s_is_coroutine -#define __pyx_kp_u_isenabled __pyx_mstate_global->__pyx_kp_u_isenabled -#define __pyx_n_s_itemsize __pyx_mstate_global->__pyx_n_s_itemsize -#define __pyx_kp_s_itemsize_0_for_cython_array __pyx_mstate_global->__pyx_kp_s_itemsize_0_for_cython_array -#define __pyx_n_s_join __pyx_mstate_global->__pyx_n_s_join -#define __pyx_n_s_kind __pyx_mstate_global->__pyx_n_s_kind -#define __pyx_n_s_logger __pyx_mstate_global->__pyx_n_s_logger -#define __pyx_n_s_maha_test __pyx_mstate_global->__pyx_n_s_maha_test -#define __pyx_n_s_maha_test_kinds __pyx_mstate_global->__pyx_n_s_maha_test_kinds -#define __pyx_n_s_maha_thresh __pyx_mstate_global->__pyx_n_s_maha_thresh -#define __pyx_n_s_main __pyx_mstate_global->__pyx_n_s_main -#define __pyx_n_s_max_rewind_age __pyx_mstate_global->__pyx_n_s_max_rewind_age -#define __pyx_n_s_memview __pyx_mstate_global->__pyx_n_s_memview -#define __pyx_n_s_mode __pyx_mstate_global->__pyx_n_s_mode -#define __pyx_n_s_name __pyx_mstate_global->__pyx_n_s_name -#define __pyx_n_s_name_2 __pyx_mstate_global->__pyx_n_s_name_2 -#define __pyx_n_s_nan __pyx_mstate_global->__pyx_n_s_nan -#define __pyx_n_s_ndim __pyx_mstate_global->__pyx_n_s_ndim -#define __pyx_n_s_new __pyx_mstate_global->__pyx_n_s_new -#define __pyx_kp_s_no_default___reduce___due_to_non __pyx_mstate_global->__pyx_kp_s_no_default___reduce___due_to_non -#define __pyx_n_s_norm_quats __pyx_mstate_global->__pyx_n_s_norm_quats -#define __pyx_n_s_np __pyx_mstate_global->__pyx_n_s_np -#define __pyx_n_s_numpy __pyx_mstate_global->__pyx_n_s_numpy -#define __pyx_kp_u_numpy_core_multiarray_failed_to __pyx_mstate_global->__pyx_kp_u_numpy_core_multiarray_failed_to -#define __pyx_kp_u_numpy_core_umath_failed_to_impor __pyx_mstate_global->__pyx_kp_u_numpy_core_umath_failed_to_impor -#define __pyx_n_s_obj __pyx_mstate_global->__pyx_n_s_obj -#define __pyx_n_s_order __pyx_mstate_global->__pyx_n_s_order -#define __pyx_n_s_pack __pyx_mstate_global->__pyx_n_s_pack -#define __pyx_n_s_pickle __pyx_mstate_global->__pyx_n_s_pickle -#define __pyx_n_s_predict __pyx_mstate_global->__pyx_n_s_predict -#define __pyx_n_s_predict_and_update_batch __pyx_mstate_global->__pyx_n_s_predict_and_update_batch -#define __pyx_n_s_pyx_PickleError __pyx_mstate_global->__pyx_n_s_pyx_PickleError -#define __pyx_n_s_pyx_checksum __pyx_mstate_global->__pyx_n_s_pyx_checksum -#define __pyx_n_s_pyx_result __pyx_mstate_global->__pyx_n_s_pyx_result -#define __pyx_n_s_pyx_state __pyx_mstate_global->__pyx_n_s_pyx_state -#define __pyx_n_s_pyx_type __pyx_mstate_global->__pyx_n_s_pyx_type -#define __pyx_n_s_pyx_unpickle_Enum __pyx_mstate_global->__pyx_n_s_pyx_unpickle_Enum -#define __pyx_n_s_pyx_vtable __pyx_mstate_global->__pyx_n_s_pyx_vtable -#define __pyx_n_s_quaternion_idxs __pyx_mstate_global->__pyx_n_s_quaternion_idxs -#define __pyx_n_s_range __pyx_mstate_global->__pyx_n_s_range -#define __pyx_n_s_rednose_helpers_ekf_sym_pyx __pyx_mstate_global->__pyx_n_s_rednose_helpers_ekf_sym_pyx -#define __pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx __pyx_mstate_global->__pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx -#define __pyx_n_s_reduce __pyx_mstate_global->__pyx_n_s_reduce -#define __pyx_n_s_reduce_cython __pyx_mstate_global->__pyx_n_s_reduce_cython -#define __pyx_n_s_reduce_ex __pyx_mstate_global->__pyx_n_s_reduce_ex -#define __pyx_n_s_register __pyx_mstate_global->__pyx_n_s_register -#define __pyx_n_s_res __pyx_mstate_global->__pyx_n_s_res -#define __pyx_n_s_reset_rewind __pyx_mstate_global->__pyx_n_s_reset_rewind -#define __pyx_n_s_rts_smooth __pyx_mstate_global->__pyx_n_s_rts_smooth -#define __pyx_n_s_self __pyx_mstate_global->__pyx_n_s_self -#define __pyx_n_s_set_filter_time __pyx_mstate_global->__pyx_n_s_set_filter_time -#define __pyx_n_s_set_global __pyx_mstate_global->__pyx_n_s_set_global -#define __pyx_n_s_setstate __pyx_mstate_global->__pyx_n_s_setstate -#define __pyx_n_s_setstate_cython __pyx_mstate_global->__pyx_n_s_setstate_cython -#define __pyx_n_s_shape __pyx_mstate_global->__pyx_n_s_shape -#define __pyx_n_s_size __pyx_mstate_global->__pyx_n_s_size -#define __pyx_n_s_spec __pyx_mstate_global->__pyx_n_s_spec -#define __pyx_n_s_start __pyx_mstate_global->__pyx_n_s_start -#define __pyx_n_s_state __pyx_mstate_global->__pyx_n_s_state -#define __pyx_n_s_state_b __pyx_mstate_global->__pyx_n_s_state_b -#define __pyx_n_s_step __pyx_mstate_global->__pyx_n_s_step -#define __pyx_n_s_stop __pyx_mstate_global->__pyx_n_s_stop -#define __pyx_kp_s_strided_and_direct __pyx_mstate_global->__pyx_kp_s_strided_and_direct -#define __pyx_kp_s_strided_and_direct_or_indirect __pyx_mstate_global->__pyx_kp_s_strided_and_direct_or_indirect -#define __pyx_kp_s_strided_and_indirect __pyx_mstate_global->__pyx_kp_s_strided_and_indirect -#define __pyx_kp_s_stringsource __pyx_mstate_global->__pyx_kp_s_stringsource -#define __pyx_n_s_struct __pyx_mstate_global->__pyx_n_s_struct -#define __pyx_n_s_sys __pyx_mstate_global->__pyx_n_s_sys -#define __pyx_n_s_t __pyx_mstate_global->__pyx_n_s_t -#define __pyx_n_s_test __pyx_mstate_global->__pyx_n_s_test -#define __pyx_n_s_tmpvec __pyx_mstate_global->__pyx_n_s_tmpvec -#define __pyx_kp_s_unable_to_allocate_array_data __pyx_mstate_global->__pyx_kp_s_unable_to_allocate_array_data -#define __pyx_kp_s_unable_to_allocate_shape_and_str __pyx_mstate_global->__pyx_kp_s_unable_to_allocate_shape_and_str -#define __pyx_n_s_unpack __pyx_mstate_global->__pyx_n_s_unpack -#define __pyx_n_s_update __pyx_mstate_global->__pyx_n_s_update -#define __pyx_n_u_utf8 __pyx_mstate_global->__pyx_n_u_utf8 -#define __pyx_n_s_val __pyx_mstate_global->__pyx_n_s_val -#define __pyx_n_s_version_info __pyx_mstate_global->__pyx_n_s_version_info -#define __pyx_n_s_x __pyx_mstate_global->__pyx_n_s_x -#define __pyx_n_s_x_initial __pyx_mstate_global->__pyx_n_s_x_initial -#define __pyx_n_s_z __pyx_mstate_global->__pyx_n_s_z -#define __pyx_n_s_z_map __pyx_mstate_global->__pyx_n_s_z_map -#define __pyx_n_s_zi __pyx_mstate_global->__pyx_n_s_zi -#define __pyx_n_s_zi_b __pyx_mstate_global->__pyx_n_s_zi_b -#define __pyx_float_0_95 __pyx_mstate_global->__pyx_float_0_95 -#define __pyx_int_0 __pyx_mstate_global->__pyx_int_0 -#define __pyx_int_1 __pyx_mstate_global->__pyx_int_1 -#define __pyx_int_3 __pyx_mstate_global->__pyx_int_3 -#define __pyx_int_112105877 __pyx_mstate_global->__pyx_int_112105877 -#define __pyx_int_136983863 __pyx_mstate_global->__pyx_int_136983863 -#define __pyx_int_184977713 __pyx_mstate_global->__pyx_int_184977713 -#define __pyx_int_neg_1 __pyx_mstate_global->__pyx_int_neg_1 -#define __pyx_k__17 __pyx_mstate_global->__pyx_k__17 -#define __pyx_k__18 __pyx_mstate_global->__pyx_k__18 -#define __pyx_k__19 __pyx_mstate_global->__pyx_k__19 -#define __pyx_k__28 __pyx_mstate_global->__pyx_k__28 -#define __pyx_k__33 __pyx_mstate_global->__pyx_k__33 -#define __pyx_slice__5 __pyx_mstate_global->__pyx_slice__5 -#define __pyx_tuple__4 __pyx_mstate_global->__pyx_tuple__4 -#define __pyx_tuple__8 __pyx_mstate_global->__pyx_tuple__8 -#define __pyx_tuple__15 __pyx_mstate_global->__pyx_tuple__15 -#define __pyx_tuple__16 __pyx_mstate_global->__pyx_tuple__16 -#define __pyx_tuple__37 __pyx_mstate_global->__pyx_tuple__37 -#define __pyx_tuple__38 __pyx_mstate_global->__pyx_tuple__38 -#define __pyx_tuple__39 __pyx_mstate_global->__pyx_tuple__39 -#define __pyx_tuple__40 __pyx_mstate_global->__pyx_tuple__40 -#define __pyx_tuple__41 __pyx_mstate_global->__pyx_tuple__41 -#define __pyx_tuple__42 __pyx_mstate_global->__pyx_tuple__42 -#define __pyx_tuple__43 __pyx_mstate_global->__pyx_tuple__43 -#define __pyx_tuple__44 __pyx_mstate_global->__pyx_tuple__44 -#define __pyx_tuple__45 __pyx_mstate_global->__pyx_tuple__45 -#define __pyx_tuple__46 __pyx_mstate_global->__pyx_tuple__46 -#define __pyx_tuple__48 __pyx_mstate_global->__pyx_tuple__48 -#define __pyx_tuple__49 __pyx_mstate_global->__pyx_tuple__49 -#define __pyx_tuple__50 __pyx_mstate_global->__pyx_tuple__50 -#define __pyx_tuple__51 __pyx_mstate_global->__pyx_tuple__51 -#define __pyx_tuple__52 __pyx_mstate_global->__pyx_tuple__52 -#define __pyx_tuple__53 __pyx_mstate_global->__pyx_tuple__53 -#define __pyx_tuple__54 __pyx_mstate_global->__pyx_tuple__54 -#define __pyx_tuple__55 __pyx_mstate_global->__pyx_tuple__55 -#define __pyx_tuple__56 __pyx_mstate_global->__pyx_tuple__56 -#define __pyx_tuple__57 __pyx_mstate_global->__pyx_tuple__57 -#define __pyx_codeobj__20 __pyx_mstate_global->__pyx_codeobj__20 -#define __pyx_codeobj__21 __pyx_mstate_global->__pyx_codeobj__21 -#define __pyx_codeobj__22 __pyx_mstate_global->__pyx_codeobj__22 -#define __pyx_codeobj__23 __pyx_mstate_global->__pyx_codeobj__23 -#define __pyx_codeobj__24 __pyx_mstate_global->__pyx_codeobj__24 -#define __pyx_codeobj__25 __pyx_mstate_global->__pyx_codeobj__25 -#define __pyx_codeobj__26 __pyx_mstate_global->__pyx_codeobj__26 -#define __pyx_codeobj__27 __pyx_mstate_global->__pyx_codeobj__27 -#define __pyx_codeobj__29 __pyx_mstate_global->__pyx_codeobj__29 -#define __pyx_codeobj__30 __pyx_mstate_global->__pyx_codeobj__30 -#define __pyx_codeobj__31 __pyx_mstate_global->__pyx_codeobj__31 -#define __pyx_codeobj__32 __pyx_mstate_global->__pyx_codeobj__32 -#define __pyx_codeobj__34 __pyx_mstate_global->__pyx_codeobj__34 -#define __pyx_codeobj__35 __pyx_mstate_global->__pyx_codeobj__35 -#define __pyx_codeobj__36 __pyx_mstate_global->__pyx_codeobj__36 -#define __pyx_codeobj__47 __pyx_mstate_global->__pyx_codeobj__47 -/* #### Code section: module_code ### */ - -/* "string.from_py":13 - * - * @cname("__pyx_convert_string_from_py_std__in_string") - * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: # <<<<<<<<<<<<<< - * cdef Py_ssize_t length = 0 - * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) - */ - -static std::string __pyx_convert_string_from_py_std__in_string(PyObject *__pyx_v_o) { - Py_ssize_t __pyx_v_length; - char const *__pyx_v_data; - std::string __pyx_r; - char const *__pyx_t_1; - std::string __pyx_t_2; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - - /* "string.from_py":14 - * @cname("__pyx_convert_string_from_py_std__in_string") - * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: - * cdef Py_ssize_t length = 0 # <<<<<<<<<<<<<< - * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) - * return string(data, length) - */ - __pyx_v_length = 0; - - /* "string.from_py":15 - * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: - * cdef Py_ssize_t length = 0 - * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) # <<<<<<<<<<<<<< - * return string(data, length) - * - */ - __pyx_t_1 = __Pyx_PyObject_AsStringAndSize(__pyx_v_o, (&__pyx_v_length)); if (unlikely(__pyx_t_1 == ((char const *)NULL))) __PYX_ERR(1, 15, __pyx_L1_error) - __pyx_v_data = __pyx_t_1; - - /* "string.from_py":16 - * cdef Py_ssize_t length = 0 - * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) - * return string(data, length) # <<<<<<<<<<<<<< - * - * - */ - try { - __pyx_t_2 = std::string(__pyx_v_data, __pyx_v_length); - } catch(...) { - __Pyx_CppExn2PyErr(); - __PYX_ERR(1, 16, __pyx_L1_error) - } - __pyx_r = __pyx_t_2; - goto __pyx_L0; - - /* "string.from_py":13 - * - * @cname("__pyx_convert_string_from_py_std__in_string") - * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: # <<<<<<<<<<<<<< - * cdef Py_ssize_t length = 0 - * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_AddTraceback("string.from_py.__pyx_convert_string_from_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); - __Pyx_pretend_to_initialize(&__pyx_r); - __pyx_L0:; - return __pyx_r; -} - -/* "vector.from_py":45 - * - * @cname("__pyx_convert_vector_from_py_int") - * cdef vector[X] __pyx_convert_vector_from_py_int(object o) except *: # <<<<<<<<<<<<<< - * cdef vector[X] v - * for item in o: - */ - -static std::vector __pyx_convert_vector_from_py_int(PyObject *__pyx_v_o) { - std::vector __pyx_v_v; - PyObject *__pyx_v_item = NULL; - std::vector __pyx_r; - __Pyx_RefNannyDeclarations - PyObject *__pyx_t_1 = NULL; - Py_ssize_t __pyx_t_2; - PyObject *(*__pyx_t_3)(PyObject *); - PyObject *__pyx_t_4 = NULL; - int __pyx_t_5; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("__pyx_convert_vector_from_py_int", 1); - - /* "vector.from_py":47 - * cdef vector[X] __pyx_convert_vector_from_py_int(object o) except *: - * cdef vector[X] v - * for item in o: # <<<<<<<<<<<<<< - * v.push_back(item) - * return v - */ - if (likely(PyList_CheckExact(__pyx_v_o)) || PyTuple_CheckExact(__pyx_v_o)) { - __pyx_t_1 = __pyx_v_o; __Pyx_INCREF(__pyx_t_1); - __pyx_t_2 = 0; - __pyx_t_3 = NULL; - } else { - __pyx_t_2 = -1; __pyx_t_1 = PyObject_GetIter(__pyx_v_o); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 47, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_3 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 47, __pyx_L1_error) - } - for (;;) { - if (likely(!__pyx_t_3)) { - if (likely(PyList_CheckExact(__pyx_t_1))) { - { - Py_ssize_t __pyx_temp = __Pyx_PyList_GET_SIZE(__pyx_t_1); - #if !CYTHON_ASSUME_SAFE_MACROS - if (unlikely((__pyx_temp < 0))) __PYX_ERR(1, 47, __pyx_L1_error) - #endif - if (__pyx_t_2 >= __pyx_temp) break; - } - #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS - __pyx_t_4 = PyList_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_4); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(1, 47, __pyx_L1_error) - #else - __pyx_t_4 = __Pyx_PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 47, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - #endif - } else { - { - Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_1); - #if !CYTHON_ASSUME_SAFE_MACROS - if (unlikely((__pyx_temp < 0))) __PYX_ERR(1, 47, __pyx_L1_error) - #endif - if (__pyx_t_2 >= __pyx_temp) break; - } - #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS - __pyx_t_4 = PyTuple_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_4); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(1, 47, __pyx_L1_error) - #else - __pyx_t_4 = __Pyx_PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 47, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - #endif - } - } else { - __pyx_t_4 = __pyx_t_3(__pyx_t_1); - if (unlikely(!__pyx_t_4)) { - PyObject* exc_type = PyErr_Occurred(); - if (exc_type) { - if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); - else __PYX_ERR(1, 47, __pyx_L1_error) - } - break; - } - __Pyx_GOTREF(__pyx_t_4); - } - __Pyx_XDECREF_SET(__pyx_v_item, __pyx_t_4); - __pyx_t_4 = 0; - - /* "vector.from_py":48 - * cdef vector[X] v - * for item in o: - * v.push_back(item) # <<<<<<<<<<<<<< - * return v - * - */ - __pyx_t_5 = __Pyx_PyInt_As_int(__pyx_v_item); if (unlikely((__pyx_t_5 == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 48, __pyx_L1_error) - try { - __pyx_v_v.push_back(((int)__pyx_t_5)); - } catch(...) { - __Pyx_CppExn2PyErr(); - __PYX_ERR(1, 48, __pyx_L1_error) - } - - /* "vector.from_py":47 - * cdef vector[X] __pyx_convert_vector_from_py_int(object o) except *: - * cdef vector[X] v - * for item in o: # <<<<<<<<<<<<<< - * v.push_back(item) - * return v - */ - } - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - - /* "vector.from_py":49 - * for item in o: - * v.push_back(item) - * return v # <<<<<<<<<<<<<< - * - * - */ - __pyx_r = __pyx_v_v; - goto __pyx_L0; - - /* "vector.from_py":45 - * - * @cname("__pyx_convert_vector_from_py_int") - * cdef vector[X] __pyx_convert_vector_from_py_int(object o) except *: # <<<<<<<<<<<<<< - * cdef vector[X] v - * for item in o: - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_1); - __Pyx_XDECREF(__pyx_t_4); - __Pyx_AddTraceback("vector.from_py.__pyx_convert_vector_from_py_int", __pyx_clineno, __pyx_lineno, __pyx_filename); - __Pyx_pretend_to_initialize(&__pyx_r); - __pyx_L0:; - __Pyx_XDECREF(__pyx_v_item); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static std::vector __pyx_convert_vector_from_py_std_3a__3a_string(PyObject *__pyx_v_o) { - std::vector __pyx_v_v; - PyObject *__pyx_v_item = NULL; - std::vector __pyx_r; - __Pyx_RefNannyDeclarations - PyObject *__pyx_t_1 = NULL; - Py_ssize_t __pyx_t_2; - PyObject *(*__pyx_t_3)(PyObject *); - PyObject *__pyx_t_4 = NULL; - std::string __pyx_t_5; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("__pyx_convert_vector_from_py_std_3a__3a_string", 1); - - /* "vector.from_py":47 - * cdef vector[X] __pyx_convert_vector_from_py_std_3a__3a_string(object o) except *: - * cdef vector[X] v - * for item in o: # <<<<<<<<<<<<<< - * v.push_back(item) - * return v - */ - if (likely(PyList_CheckExact(__pyx_v_o)) || PyTuple_CheckExact(__pyx_v_o)) { - __pyx_t_1 = __pyx_v_o; __Pyx_INCREF(__pyx_t_1); - __pyx_t_2 = 0; - __pyx_t_3 = NULL; - } else { - __pyx_t_2 = -1; __pyx_t_1 = PyObject_GetIter(__pyx_v_o); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 47, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_3 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 47, __pyx_L1_error) - } - for (;;) { - if (likely(!__pyx_t_3)) { - if (likely(PyList_CheckExact(__pyx_t_1))) { - { - Py_ssize_t __pyx_temp = __Pyx_PyList_GET_SIZE(__pyx_t_1); - #if !CYTHON_ASSUME_SAFE_MACROS - if (unlikely((__pyx_temp < 0))) __PYX_ERR(1, 47, __pyx_L1_error) - #endif - if (__pyx_t_2 >= __pyx_temp) break; - } - #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS - __pyx_t_4 = PyList_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_4); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(1, 47, __pyx_L1_error) - #else - __pyx_t_4 = __Pyx_PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 47, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - #endif - } else { - { - Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_1); - #if !CYTHON_ASSUME_SAFE_MACROS - if (unlikely((__pyx_temp < 0))) __PYX_ERR(1, 47, __pyx_L1_error) - #endif - if (__pyx_t_2 >= __pyx_temp) break; - } - #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS - __pyx_t_4 = PyTuple_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_4); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(1, 47, __pyx_L1_error) - #else - __pyx_t_4 = __Pyx_PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 47, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - #endif - } - } else { - __pyx_t_4 = __pyx_t_3(__pyx_t_1); - if (unlikely(!__pyx_t_4)) { - PyObject* exc_type = PyErr_Occurred(); - if (exc_type) { - if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); - else __PYX_ERR(1, 47, __pyx_L1_error) - } - break; - } - __Pyx_GOTREF(__pyx_t_4); - } - __Pyx_XDECREF_SET(__pyx_v_item, __pyx_t_4); - __pyx_t_4 = 0; - - /* "vector.from_py":48 - * cdef vector[X] v - * for item in o: - * v.push_back(item) # <<<<<<<<<<<<<< - * return v - * - */ - __pyx_t_5 = __pyx_convert_string_from_py_std__in_string(__pyx_v_item); if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 48, __pyx_L1_error) - try { - __pyx_v_v.push_back(((std::string)__pyx_t_5)); - } catch(...) { - __Pyx_CppExn2PyErr(); - __PYX_ERR(1, 48, __pyx_L1_error) - } - - /* "vector.from_py":47 - * cdef vector[X] __pyx_convert_vector_from_py_std_3a__3a_string(object o) except *: - * cdef vector[X] v - * for item in o: # <<<<<<<<<<<<<< - * v.push_back(item) - * return v - */ - } - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - - /* "vector.from_py":49 - * for item in o: - * v.push_back(item) - * return v # <<<<<<<<<<<<<< - * - * - */ - __pyx_r = __pyx_v_v; - goto __pyx_L0; - - /* "vector.from_py":45 - * - * @cname("__pyx_convert_vector_from_py_std_3a__3a_string") - * cdef vector[X] __pyx_convert_vector_from_py_std_3a__3a_string(object o) except *: # <<<<<<<<<<<<<< - * cdef vector[X] v - * for item in o: - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_1); - __Pyx_XDECREF(__pyx_t_4); - __Pyx_AddTraceback("vector.from_py.__pyx_convert_vector_from_py_std_3a__3a_string", __pyx_clineno, __pyx_lineno, __pyx_filename); - __Pyx_pretend_to_initialize(&__pyx_r); - __pyx_L0:; - __Pyx_XDECREF(__pyx_v_item); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "View.MemoryView":131 - * cdef bint dtype_is_object - * - * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, # <<<<<<<<<<<<<< - * mode="c", bint allocate_buffer=True): - * - */ - -/* Python wrapper */ -static int __pyx_array___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ -static int __pyx_array___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { - PyObject *__pyx_v_shape = 0; - Py_ssize_t __pyx_v_itemsize; - PyObject *__pyx_v_format = 0; - PyObject *__pyx_v_mode = 0; - int __pyx_v_allocate_buffer; - CYTHON_UNUSED Py_ssize_t __pyx_nargs; - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - PyObject* values[5] = {0,0,0,0,0}; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - int __pyx_r; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); - #if CYTHON_ASSUME_SAFE_MACROS - __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); - #else - __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return -1; - #endif - __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); - { - PyObject **__pyx_pyargnames[] = {&__pyx_n_s_shape,&__pyx_n_s_itemsize,&__pyx_n_s_format,&__pyx_n_s_mode,&__pyx_n_s_allocate_buffer,0}; - values[3] = __Pyx_Arg_NewRef_VARARGS(((PyObject *)__pyx_n_s_c)); - if (__pyx_kwds) { - Py_ssize_t kw_args; - switch (__pyx_nargs) { - case 5: values[4] = __Pyx_Arg_VARARGS(__pyx_args, 4); - CYTHON_FALLTHROUGH; - case 4: values[3] = __Pyx_Arg_VARARGS(__pyx_args, 3); - CYTHON_FALLTHROUGH; - case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); - CYTHON_FALLTHROUGH; - case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); - CYTHON_FALLTHROUGH; - case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); - CYTHON_FALLTHROUGH; - case 0: break; - default: goto __pyx_L5_argtuple_error; - } - kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); - switch (__pyx_nargs) { - case 0: - if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_shape)) != 0)) { - (void)__Pyx_Arg_NewRef_VARARGS(values[0]); - kw_args--; - } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) - else goto __pyx_L5_argtuple_error; - CYTHON_FALLTHROUGH; - case 1: - if (likely((values[1] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_itemsize)) != 0)) { - (void)__Pyx_Arg_NewRef_VARARGS(values[1]); - kw_args--; - } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) - else { - __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 3, 5, 1); __PYX_ERR(1, 131, __pyx_L3_error) - } - CYTHON_FALLTHROUGH; - case 2: - if (likely((values[2] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_format)) != 0)) { - (void)__Pyx_Arg_NewRef_VARARGS(values[2]); - kw_args--; - } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) - else { - __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 3, 5, 2); __PYX_ERR(1, 131, __pyx_L3_error) - } - CYTHON_FALLTHROUGH; - case 3: - if (kw_args > 0) { - PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_mode); - if (value) { values[3] = __Pyx_Arg_NewRef_VARARGS(value); kw_args--; } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) - } - CYTHON_FALLTHROUGH; - case 4: - if (kw_args > 0) { - PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_allocate_buffer); - if (value) { values[4] = __Pyx_Arg_NewRef_VARARGS(value); kw_args--; } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) - } - } - if (unlikely(kw_args > 0)) { - const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__cinit__") < 0)) __PYX_ERR(1, 131, __pyx_L3_error) - } - } else { - switch (__pyx_nargs) { - case 5: values[4] = __Pyx_Arg_VARARGS(__pyx_args, 4); - CYTHON_FALLTHROUGH; - case 4: values[3] = __Pyx_Arg_VARARGS(__pyx_args, 3); - CYTHON_FALLTHROUGH; - case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); - values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); - values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); - break; - default: goto __pyx_L5_argtuple_error; - } - } - __pyx_v_shape = ((PyObject*)values[0]); - __pyx_v_itemsize = __Pyx_PyIndex_AsSsize_t(values[1]); if (unlikely((__pyx_v_itemsize == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) - __pyx_v_format = values[2]; - __pyx_v_mode = values[3]; - if (values[4]) { - __pyx_v_allocate_buffer = __Pyx_PyObject_IsTrue(values[4]); if (unlikely((__pyx_v_allocate_buffer == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 132, __pyx_L3_error) - } else { - - /* "View.MemoryView":132 - * - * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, - * mode="c", bint allocate_buffer=True): # <<<<<<<<<<<<<< - * - * cdef int idx - */ - __pyx_v_allocate_buffer = ((int)1); - } - } - goto __pyx_L6_skip; - __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 3, 5, __pyx_nargs); __PYX_ERR(1, 131, __pyx_L3_error) - __pyx_L6_skip:; - goto __pyx_L4_argument_unpacking_done; - __pyx_L3_error:; - { - Py_ssize_t __pyx_temp; - for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { - __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); - } - } - __Pyx_AddTraceback("View.MemoryView.array.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); - __Pyx_RefNannyFinishContext(); - return -1; - __pyx_L4_argument_unpacking_done:; - if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_shape), (&PyTuple_Type), 1, "shape", 1))) __PYX_ERR(1, 131, __pyx_L1_error) - if (unlikely(((PyObject *)__pyx_v_format) == Py_None)) { - PyErr_Format(PyExc_TypeError, "Argument '%.200s' must not be None", "format"); __PYX_ERR(1, 131, __pyx_L1_error) - } - __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array___cinit__(((struct __pyx_array_obj *)__pyx_v_self), __pyx_v_shape, __pyx_v_itemsize, __pyx_v_format, __pyx_v_mode, __pyx_v_allocate_buffer); - - /* "View.MemoryView":131 - * cdef bint dtype_is_object - * - * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, # <<<<<<<<<<<<<< - * mode="c", bint allocate_buffer=True): - * - */ - - /* function exit code */ - goto __pyx_L0; - __pyx_L1_error:; - __pyx_r = -1; - __pyx_L0:; - { - Py_ssize_t __pyx_temp; - for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { - __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); - } - } - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array___cinit__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_shape, Py_ssize_t __pyx_v_itemsize, PyObject *__pyx_v_format, PyObject *__pyx_v_mode, int __pyx_v_allocate_buffer) { - int __pyx_v_idx; - Py_ssize_t __pyx_v_dim; - char __pyx_v_order; - int __pyx_r; - __Pyx_RefNannyDeclarations - Py_ssize_t __pyx_t_1; - int __pyx_t_2; - int __pyx_t_3; - PyObject *__pyx_t_4 = NULL; - PyObject *__pyx_t_5 = NULL; - PyObject *__pyx_t_6 = NULL; - int __pyx_t_7; - char *__pyx_t_8; - Py_ssize_t __pyx_t_9; - Py_UCS4 __pyx_t_10; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("__cinit__", 0); - __Pyx_INCREF(__pyx_v_format); - - /* "View.MemoryView":137 - * cdef Py_ssize_t dim - * - * self.ndim = len(shape) # <<<<<<<<<<<<<< - * self.itemsize = itemsize - * - */ - if (unlikely(__pyx_v_shape == Py_None)) { - PyErr_SetString(PyExc_TypeError, "object of type 'NoneType' has no len()"); - __PYX_ERR(1, 137, __pyx_L1_error) - } - __pyx_t_1 = __Pyx_PyTuple_GET_SIZE(__pyx_v_shape); if (unlikely(__pyx_t_1 == ((Py_ssize_t)-1))) __PYX_ERR(1, 137, __pyx_L1_error) - __pyx_v_self->ndim = ((int)__pyx_t_1); - - /* "View.MemoryView":138 - * - * self.ndim = len(shape) - * self.itemsize = itemsize # <<<<<<<<<<<<<< - * - * if not self.ndim: - */ - __pyx_v_self->itemsize = __pyx_v_itemsize; - - /* "View.MemoryView":140 - * self.itemsize = itemsize - * - * if not self.ndim: # <<<<<<<<<<<<<< - * raise ValueError, "Empty shape tuple for cython.array" - * - */ - __pyx_t_2 = (!(__pyx_v_self->ndim != 0)); - if (unlikely(__pyx_t_2)) { - - /* "View.MemoryView":141 - * - * if not self.ndim: - * raise ValueError, "Empty shape tuple for cython.array" # <<<<<<<<<<<<<< - * - * if itemsize <= 0: - */ - __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Empty_shape_tuple_for_cython_arr, 0, 0); - __PYX_ERR(1, 141, __pyx_L1_error) - - /* "View.MemoryView":140 - * self.itemsize = itemsize - * - * if not self.ndim: # <<<<<<<<<<<<<< - * raise ValueError, "Empty shape tuple for cython.array" - * - */ - } - - /* "View.MemoryView":143 - * raise ValueError, "Empty shape tuple for cython.array" - * - * if itemsize <= 0: # <<<<<<<<<<<<<< - * raise ValueError, "itemsize <= 0 for cython.array" - * - */ - __pyx_t_2 = (__pyx_v_itemsize <= 0); - if (unlikely(__pyx_t_2)) { - - /* "View.MemoryView":144 - * - * if itemsize <= 0: - * raise ValueError, "itemsize <= 0 for cython.array" # <<<<<<<<<<<<<< - * - * if not isinstance(format, bytes): - */ - __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_itemsize_0_for_cython_array, 0, 0); - __PYX_ERR(1, 144, __pyx_L1_error) - - /* "View.MemoryView":143 - * raise ValueError, "Empty shape tuple for cython.array" - * - * if itemsize <= 0: # <<<<<<<<<<<<<< - * raise ValueError, "itemsize <= 0 for cython.array" - * - */ - } - - /* "View.MemoryView":146 - * raise ValueError, "itemsize <= 0 for cython.array" - * - * if not isinstance(format, bytes): # <<<<<<<<<<<<<< - * format = format.encode('ASCII') - * self._format = format # keep a reference to the byte string - */ - __pyx_t_2 = PyBytes_Check(__pyx_v_format); - __pyx_t_3 = (!__pyx_t_2); - if (__pyx_t_3) { - - /* "View.MemoryView":147 - * - * if not isinstance(format, bytes): - * format = format.encode('ASCII') # <<<<<<<<<<<<<< - * self._format = format # keep a reference to the byte string - * self.format = self._format - */ - __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_v_format, __pyx_n_s_encode); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 147, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __pyx_t_6 = NULL; - __pyx_t_7 = 0; - #if CYTHON_UNPACK_METHODS - if (likely(PyMethod_Check(__pyx_t_5))) { - __pyx_t_6 = PyMethod_GET_SELF(__pyx_t_5); - if (likely(__pyx_t_6)) { - PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); - __Pyx_INCREF(__pyx_t_6); - __Pyx_INCREF(function); - __Pyx_DECREF_SET(__pyx_t_5, function); - __pyx_t_7 = 1; - } - } - #endif - { - PyObject *__pyx_callargs[2] = {__pyx_t_6, __pyx_n_s_ASCII}; - __pyx_t_4 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_7, 1+__pyx_t_7); - __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; - if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 147, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - } - __Pyx_DECREF_SET(__pyx_v_format, __pyx_t_4); - __pyx_t_4 = 0; - - /* "View.MemoryView":146 - * raise ValueError, "itemsize <= 0 for cython.array" - * - * if not isinstance(format, bytes): # <<<<<<<<<<<<<< - * format = format.encode('ASCII') - * self._format = format # keep a reference to the byte string - */ - } - - /* "View.MemoryView":148 - * if not isinstance(format, bytes): - * format = format.encode('ASCII') - * self._format = format # keep a reference to the byte string # <<<<<<<<<<<<<< - * self.format = self._format - * - */ - if (!(likely(PyBytes_CheckExact(__pyx_v_format))||((__pyx_v_format) == Py_None) || __Pyx_RaiseUnexpectedTypeError("bytes", __pyx_v_format))) __PYX_ERR(1, 148, __pyx_L1_error) - __pyx_t_4 = __pyx_v_format; - __Pyx_INCREF(__pyx_t_4); - __Pyx_GIVEREF(__pyx_t_4); - __Pyx_GOTREF(__pyx_v_self->_format); - __Pyx_DECREF(__pyx_v_self->_format); - __pyx_v_self->_format = ((PyObject*)__pyx_t_4); - __pyx_t_4 = 0; - - /* "View.MemoryView":149 - * format = format.encode('ASCII') - * self._format = format # keep a reference to the byte string - * self.format = self._format # <<<<<<<<<<<<<< - * - * - */ - if (unlikely(__pyx_v_self->_format == Py_None)) { - PyErr_SetString(PyExc_TypeError, "expected bytes, NoneType found"); - __PYX_ERR(1, 149, __pyx_L1_error) - } - __pyx_t_8 = __Pyx_PyBytes_AsWritableString(__pyx_v_self->_format); if (unlikely((!__pyx_t_8) && PyErr_Occurred())) __PYX_ERR(1, 149, __pyx_L1_error) - __pyx_v_self->format = __pyx_t_8; - - /* "View.MemoryView":152 - * - * - * self._shape = PyObject_Malloc(sizeof(Py_ssize_t)*self.ndim*2) # <<<<<<<<<<<<<< - * self._strides = self._shape + self.ndim - * - */ - __pyx_v_self->_shape = ((Py_ssize_t *)PyObject_Malloc((((sizeof(Py_ssize_t)) * __pyx_v_self->ndim) * 2))); - - /* "View.MemoryView":153 - * - * self._shape = PyObject_Malloc(sizeof(Py_ssize_t)*self.ndim*2) - * self._strides = self._shape + self.ndim # <<<<<<<<<<<<<< - * - * if not self._shape: - */ - __pyx_v_self->_strides = (__pyx_v_self->_shape + __pyx_v_self->ndim); - - /* "View.MemoryView":155 - * self._strides = self._shape + self.ndim - * - * if not self._shape: # <<<<<<<<<<<<<< - * raise MemoryError, "unable to allocate shape and strides." - * - */ - __pyx_t_3 = (!(__pyx_v_self->_shape != 0)); - if (unlikely(__pyx_t_3)) { - - /* "View.MemoryView":156 - * - * if not self._shape: - * raise MemoryError, "unable to allocate shape and strides." # <<<<<<<<<<<<<< - * - * - */ - __Pyx_Raise(__pyx_builtin_MemoryError, __pyx_kp_s_unable_to_allocate_shape_and_str, 0, 0); - __PYX_ERR(1, 156, __pyx_L1_error) - - /* "View.MemoryView":155 - * self._strides = self._shape + self.ndim - * - * if not self._shape: # <<<<<<<<<<<<<< - * raise MemoryError, "unable to allocate shape and strides." - * - */ - } - - /* "View.MemoryView":159 - * - * - * for idx, dim in enumerate(shape): # <<<<<<<<<<<<<< - * if dim <= 0: - * raise ValueError, f"Invalid shape in axis {idx}: {dim}." - */ - __pyx_t_7 = 0; - __pyx_t_4 = __pyx_v_shape; __Pyx_INCREF(__pyx_t_4); - __pyx_t_1 = 0; - for (;;) { - { - Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_4); - #if !CYTHON_ASSUME_SAFE_MACROS - if (unlikely((__pyx_temp < 0))) __PYX_ERR(1, 159, __pyx_L1_error) - #endif - if (__pyx_t_1 >= __pyx_temp) break; - } - #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS - __pyx_t_5 = PyTuple_GET_ITEM(__pyx_t_4, __pyx_t_1); __Pyx_INCREF(__pyx_t_5); __pyx_t_1++; if (unlikely((0 < 0))) __PYX_ERR(1, 159, __pyx_L1_error) - #else - __pyx_t_5 = __Pyx_PySequence_ITEM(__pyx_t_4, __pyx_t_1); __pyx_t_1++; if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 159, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - #endif - __pyx_t_9 = __Pyx_PyIndex_AsSsize_t(__pyx_t_5); if (unlikely((__pyx_t_9 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 159, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __pyx_v_dim = __pyx_t_9; - __pyx_v_idx = __pyx_t_7; - __pyx_t_7 = (__pyx_t_7 + 1); - - /* "View.MemoryView":160 - * - * for idx, dim in enumerate(shape): - * if dim <= 0: # <<<<<<<<<<<<<< - * raise ValueError, f"Invalid shape in axis {idx}: {dim}." - * self._shape[idx] = dim - */ - __pyx_t_3 = (__pyx_v_dim <= 0); - if (unlikely(__pyx_t_3)) { - - /* "View.MemoryView":161 - * for idx, dim in enumerate(shape): - * if dim <= 0: - * raise ValueError, f"Invalid shape in axis {idx}: {dim}." # <<<<<<<<<<<<<< - * self._shape[idx] = dim - * - */ - __pyx_t_5 = PyTuple_New(5); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 161, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __pyx_t_9 = 0; - __pyx_t_10 = 127; - __Pyx_INCREF(__pyx_kp_u_Invalid_shape_in_axis); - __pyx_t_9 += 22; - __Pyx_GIVEREF(__pyx_kp_u_Invalid_shape_in_axis); - PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_kp_u_Invalid_shape_in_axis); - __pyx_t_6 = __Pyx_PyUnicode_From_int(__pyx_v_idx, 0, ' ', 'd'); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 161, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_6); - __pyx_t_9 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_6); - __Pyx_GIVEREF(__pyx_t_6); - PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_t_6); - __pyx_t_6 = 0; - __Pyx_INCREF(__pyx_kp_u_); - __pyx_t_9 += 2; - __Pyx_GIVEREF(__pyx_kp_u_); - PyTuple_SET_ITEM(__pyx_t_5, 2, __pyx_kp_u_); - __pyx_t_6 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_dim, 0, ' ', 'd'); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 161, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_6); - __pyx_t_9 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_6); - __Pyx_GIVEREF(__pyx_t_6); - PyTuple_SET_ITEM(__pyx_t_5, 3, __pyx_t_6); - __pyx_t_6 = 0; - __Pyx_INCREF(__pyx_kp_u__2); - __pyx_t_9 += 1; - __Pyx_GIVEREF(__pyx_kp_u__2); - PyTuple_SET_ITEM(__pyx_t_5, 4, __pyx_kp_u__2); - __pyx_t_6 = __Pyx_PyUnicode_Join(__pyx_t_5, 5, __pyx_t_9, __pyx_t_10); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 161, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_6); - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __Pyx_Raise(__pyx_builtin_ValueError, __pyx_t_6, 0, 0); - __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; - __PYX_ERR(1, 161, __pyx_L1_error) - - /* "View.MemoryView":160 - * - * for idx, dim in enumerate(shape): - * if dim <= 0: # <<<<<<<<<<<<<< - * raise ValueError, f"Invalid shape in axis {idx}: {dim}." - * self._shape[idx] = dim - */ - } - - /* "View.MemoryView":162 - * if dim <= 0: - * raise ValueError, f"Invalid shape in axis {idx}: {dim}." - * self._shape[idx] = dim # <<<<<<<<<<<<<< - * - * cdef char order - */ - (__pyx_v_self->_shape[__pyx_v_idx]) = __pyx_v_dim; - - /* "View.MemoryView":159 - * - * - * for idx, dim in enumerate(shape): # <<<<<<<<<<<<<< - * if dim <= 0: - * raise ValueError, f"Invalid shape in axis {idx}: {dim}." - */ - } - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - - /* "View.MemoryView":165 - * - * cdef char order - * if mode == 'c': # <<<<<<<<<<<<<< - * order = b'C' - * self.mode = u'c' - */ - __pyx_t_3 = (__Pyx_PyString_Equals(__pyx_v_mode, __pyx_n_s_c, Py_EQ)); if (unlikely((__pyx_t_3 < 0))) __PYX_ERR(1, 165, __pyx_L1_error) - if (__pyx_t_3) { - - /* "View.MemoryView":166 - * cdef char order - * if mode == 'c': - * order = b'C' # <<<<<<<<<<<<<< - * self.mode = u'c' - * elif mode == 'fortran': - */ - __pyx_v_order = 'C'; - - /* "View.MemoryView":167 - * if mode == 'c': - * order = b'C' - * self.mode = u'c' # <<<<<<<<<<<<<< - * elif mode == 'fortran': - * order = b'F' - */ - __Pyx_INCREF(__pyx_n_u_c); - __Pyx_GIVEREF(__pyx_n_u_c); - __Pyx_GOTREF(__pyx_v_self->mode); - __Pyx_DECREF(__pyx_v_self->mode); - __pyx_v_self->mode = __pyx_n_u_c; - - /* "View.MemoryView":165 - * - * cdef char order - * if mode == 'c': # <<<<<<<<<<<<<< - * order = b'C' - * self.mode = u'c' - */ - goto __pyx_L11; - } - - /* "View.MemoryView":168 - * order = b'C' - * self.mode = u'c' - * elif mode == 'fortran': # <<<<<<<<<<<<<< - * order = b'F' - * self.mode = u'fortran' - */ - __pyx_t_3 = (__Pyx_PyString_Equals(__pyx_v_mode, __pyx_n_s_fortran, Py_EQ)); if (unlikely((__pyx_t_3 < 0))) __PYX_ERR(1, 168, __pyx_L1_error) - if (likely(__pyx_t_3)) { - - /* "View.MemoryView":169 - * self.mode = u'c' - * elif mode == 'fortran': - * order = b'F' # <<<<<<<<<<<<<< - * self.mode = u'fortran' - * else: - */ - __pyx_v_order = 'F'; - - /* "View.MemoryView":170 - * elif mode == 'fortran': - * order = b'F' - * self.mode = u'fortran' # <<<<<<<<<<<<<< - * else: - * raise ValueError, f"Invalid mode, expected 'c' or 'fortran', got {mode}" - */ - __Pyx_INCREF(__pyx_n_u_fortran); - __Pyx_GIVEREF(__pyx_n_u_fortran); - __Pyx_GOTREF(__pyx_v_self->mode); - __Pyx_DECREF(__pyx_v_self->mode); - __pyx_v_self->mode = __pyx_n_u_fortran; - - /* "View.MemoryView":168 - * order = b'C' - * self.mode = u'c' - * elif mode == 'fortran': # <<<<<<<<<<<<<< - * order = b'F' - * self.mode = u'fortran' - */ - goto __pyx_L11; - } - - /* "View.MemoryView":172 - * self.mode = u'fortran' - * else: - * raise ValueError, f"Invalid mode, expected 'c' or 'fortran', got {mode}" # <<<<<<<<<<<<<< - * - * self.len = fill_contig_strides_array(self._shape, self._strides, itemsize, self.ndim, order) - */ - /*else*/ { - __pyx_t_4 = __Pyx_PyObject_FormatSimple(__pyx_v_mode, __pyx_empty_unicode); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 172, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __pyx_t_6 = __Pyx_PyUnicode_Concat(__pyx_kp_u_Invalid_mode_expected_c_or_fortr, __pyx_t_4); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 172, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_6); - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __Pyx_Raise(__pyx_builtin_ValueError, __pyx_t_6, 0, 0); - __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; - __PYX_ERR(1, 172, __pyx_L1_error) - } - __pyx_L11:; - - /* "View.MemoryView":174 - * raise ValueError, f"Invalid mode, expected 'c' or 'fortran', got {mode}" - * - * self.len = fill_contig_strides_array(self._shape, self._strides, itemsize, self.ndim, order) # <<<<<<<<<<<<<< - * - * self.free_data = allocate_buffer - */ - __pyx_v_self->len = __pyx_fill_contig_strides_array(__pyx_v_self->_shape, __pyx_v_self->_strides, __pyx_v_itemsize, __pyx_v_self->ndim, __pyx_v_order); - - /* "View.MemoryView":176 - * self.len = fill_contig_strides_array(self._shape, self._strides, itemsize, self.ndim, order) - * - * self.free_data = allocate_buffer # <<<<<<<<<<<<<< - * self.dtype_is_object = format == b'O' - * - */ - __pyx_v_self->free_data = __pyx_v_allocate_buffer; - - /* "View.MemoryView":177 - * - * self.free_data = allocate_buffer - * self.dtype_is_object = format == b'O' # <<<<<<<<<<<<<< - * - * if allocate_buffer: - */ - __pyx_t_6 = PyObject_RichCompare(__pyx_v_format, __pyx_n_b_O, Py_EQ); __Pyx_XGOTREF(__pyx_t_6); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 177, __pyx_L1_error) - __pyx_t_3 = __Pyx_PyObject_IsTrue(__pyx_t_6); if (unlikely((__pyx_t_3 == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 177, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; - __pyx_v_self->dtype_is_object = __pyx_t_3; - - /* "View.MemoryView":179 - * self.dtype_is_object = format == b'O' - * - * if allocate_buffer: # <<<<<<<<<<<<<< - * _allocate_buffer(self) - * - */ - if (__pyx_v_allocate_buffer) { - - /* "View.MemoryView":180 - * - * if allocate_buffer: - * _allocate_buffer(self) # <<<<<<<<<<<<<< - * - * @cname('getbuffer') - */ - __pyx_t_7 = __pyx_array_allocate_buffer(__pyx_v_self); if (unlikely(__pyx_t_7 == ((int)-1))) __PYX_ERR(1, 180, __pyx_L1_error) - - /* "View.MemoryView":179 - * self.dtype_is_object = format == b'O' - * - * if allocate_buffer: # <<<<<<<<<<<<<< - * _allocate_buffer(self) - * - */ - } - - /* "View.MemoryView":131 - * cdef bint dtype_is_object - * - * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, # <<<<<<<<<<<<<< - * mode="c", bint allocate_buffer=True): - * - */ - - /* function exit code */ - __pyx_r = 0; - goto __pyx_L0; - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_4); - __Pyx_XDECREF(__pyx_t_5); - __Pyx_XDECREF(__pyx_t_6); - __Pyx_AddTraceback("View.MemoryView.array.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = -1; - __pyx_L0:; - __Pyx_XDECREF(__pyx_v_format); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "View.MemoryView":182 - * _allocate_buffer(self) - * - * @cname('getbuffer') # <<<<<<<<<<<<<< - * def __getbuffer__(self, Py_buffer *info, int flags): - * cdef int bufmode = -1 - */ - -/* Python wrapper */ -CYTHON_UNUSED static int __pyx_array_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ -CYTHON_UNUSED static int __pyx_array_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - int __pyx_r; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("__getbuffer__ (wrapper)", 0); - __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); - __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_2__getbuffer__(((struct __pyx_array_obj *)__pyx_v_self), ((Py_buffer *)__pyx_v_info), ((int)__pyx_v_flags)); - - /* function exit code */ - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_2__getbuffer__(struct __pyx_array_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { - int __pyx_v_bufmode; - int __pyx_r; - __Pyx_RefNannyDeclarations - int __pyx_t_1; - char *__pyx_t_2; - Py_ssize_t __pyx_t_3; - int __pyx_t_4; - Py_ssize_t *__pyx_t_5; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - if (unlikely(__pyx_v_info == NULL)) { - PyErr_SetString(PyExc_BufferError, "PyObject_GetBuffer: view==NULL argument is obsolete"); - return -1; - } - __Pyx_RefNannySetupContext("__getbuffer__", 0); - __pyx_v_info->obj = Py_None; __Pyx_INCREF(Py_None); - __Pyx_GIVEREF(__pyx_v_info->obj); - - /* "View.MemoryView":184 - * @cname('getbuffer') - * def __getbuffer__(self, Py_buffer *info, int flags): - * cdef int bufmode = -1 # <<<<<<<<<<<<<< - * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): - * if self.mode == u"c": - */ - __pyx_v_bufmode = -1; - - /* "View.MemoryView":185 - * def __getbuffer__(self, Py_buffer *info, int flags): - * cdef int bufmode = -1 - * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): # <<<<<<<<<<<<<< - * if self.mode == u"c": - * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS - */ - __pyx_t_1 = ((__pyx_v_flags & ((PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS) | PyBUF_ANY_CONTIGUOUS)) != 0); - if (__pyx_t_1) { - - /* "View.MemoryView":186 - * cdef int bufmode = -1 - * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): - * if self.mode == u"c": # <<<<<<<<<<<<<< - * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS - * elif self.mode == u"fortran": - */ - __pyx_t_1 = (__Pyx_PyUnicode_Equals(__pyx_v_self->mode, __pyx_n_u_c, Py_EQ)); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 186, __pyx_L1_error) - if (__pyx_t_1) { - - /* "View.MemoryView":187 - * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): - * if self.mode == u"c": - * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS # <<<<<<<<<<<<<< - * elif self.mode == u"fortran": - * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS - */ - __pyx_v_bufmode = (PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS); - - /* "View.MemoryView":186 - * cdef int bufmode = -1 - * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): - * if self.mode == u"c": # <<<<<<<<<<<<<< - * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS - * elif self.mode == u"fortran": - */ - goto __pyx_L4; - } - - /* "View.MemoryView":188 - * if self.mode == u"c": - * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS - * elif self.mode == u"fortran": # <<<<<<<<<<<<<< - * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS - * if not (flags & bufmode): - */ - __pyx_t_1 = (__Pyx_PyUnicode_Equals(__pyx_v_self->mode, __pyx_n_u_fortran, Py_EQ)); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 188, __pyx_L1_error) - if (__pyx_t_1) { - - /* "View.MemoryView":189 - * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS - * elif self.mode == u"fortran": - * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS # <<<<<<<<<<<<<< - * if not (flags & bufmode): - * raise ValueError, "Can only create a buffer that is contiguous in memory." - */ - __pyx_v_bufmode = (PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS); - - /* "View.MemoryView":188 - * if self.mode == u"c": - * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS - * elif self.mode == u"fortran": # <<<<<<<<<<<<<< - * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS - * if not (flags & bufmode): - */ - } - __pyx_L4:; - - /* "View.MemoryView":190 - * elif self.mode == u"fortran": - * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS - * if not (flags & bufmode): # <<<<<<<<<<<<<< - * raise ValueError, "Can only create a buffer that is contiguous in memory." - * info.buf = self.data - */ - __pyx_t_1 = (!((__pyx_v_flags & __pyx_v_bufmode) != 0)); - if (unlikely(__pyx_t_1)) { - - /* "View.MemoryView":191 - * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS - * if not (flags & bufmode): - * raise ValueError, "Can only create a buffer that is contiguous in memory." # <<<<<<<<<<<<<< - * info.buf = self.data - * info.len = self.len - */ - __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Can_only_create_a_buffer_that_is, 0, 0); - __PYX_ERR(1, 191, __pyx_L1_error) - - /* "View.MemoryView":190 - * elif self.mode == u"fortran": - * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS - * if not (flags & bufmode): # <<<<<<<<<<<<<< - * raise ValueError, "Can only create a buffer that is contiguous in memory." - * info.buf = self.data - */ - } - - /* "View.MemoryView":185 - * def __getbuffer__(self, Py_buffer *info, int flags): - * cdef int bufmode = -1 - * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): # <<<<<<<<<<<<<< - * if self.mode == u"c": - * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS - */ - } - - /* "View.MemoryView":192 - * if not (flags & bufmode): - * raise ValueError, "Can only create a buffer that is contiguous in memory." - * info.buf = self.data # <<<<<<<<<<<<<< - * info.len = self.len - * - */ - __pyx_t_2 = __pyx_v_self->data; - __pyx_v_info->buf = __pyx_t_2; - - /* "View.MemoryView":193 - * raise ValueError, "Can only create a buffer that is contiguous in memory." - * info.buf = self.data - * info.len = self.len # <<<<<<<<<<<<<< - * - * if flags & PyBUF_STRIDES: - */ - __pyx_t_3 = __pyx_v_self->len; - __pyx_v_info->len = __pyx_t_3; - - /* "View.MemoryView":195 - * info.len = self.len - * - * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< - * info.ndim = self.ndim - * info.shape = self._shape - */ - __pyx_t_1 = ((__pyx_v_flags & PyBUF_STRIDES) != 0); - if (__pyx_t_1) { - - /* "View.MemoryView":196 - * - * if flags & PyBUF_STRIDES: - * info.ndim = self.ndim # <<<<<<<<<<<<<< - * info.shape = self._shape - * info.strides = self._strides - */ - __pyx_t_4 = __pyx_v_self->ndim; - __pyx_v_info->ndim = __pyx_t_4; - - /* "View.MemoryView":197 - * if flags & PyBUF_STRIDES: - * info.ndim = self.ndim - * info.shape = self._shape # <<<<<<<<<<<<<< - * info.strides = self._strides - * else: - */ - __pyx_t_5 = __pyx_v_self->_shape; - __pyx_v_info->shape = __pyx_t_5; - - /* "View.MemoryView":198 - * info.ndim = self.ndim - * info.shape = self._shape - * info.strides = self._strides # <<<<<<<<<<<<<< - * else: - * info.ndim = 1 - */ - __pyx_t_5 = __pyx_v_self->_strides; - __pyx_v_info->strides = __pyx_t_5; - - /* "View.MemoryView":195 - * info.len = self.len - * - * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< - * info.ndim = self.ndim - * info.shape = self._shape - */ - goto __pyx_L6; - } - - /* "View.MemoryView":200 - * info.strides = self._strides - * else: - * info.ndim = 1 # <<<<<<<<<<<<<< - * info.shape = &self.len if flags & PyBUF_ND else NULL - * info.strides = NULL - */ - /*else*/ { - __pyx_v_info->ndim = 1; - - /* "View.MemoryView":201 - * else: - * info.ndim = 1 - * info.shape = &self.len if flags & PyBUF_ND else NULL # <<<<<<<<<<<<<< - * info.strides = NULL - * - */ - __pyx_t_1 = ((__pyx_v_flags & PyBUF_ND) != 0); - if (__pyx_t_1) { - __pyx_t_5 = (&__pyx_v_self->len); - } else { - __pyx_t_5 = NULL; - } - __pyx_v_info->shape = __pyx_t_5; - - /* "View.MemoryView":202 - * info.ndim = 1 - * info.shape = &self.len if flags & PyBUF_ND else NULL - * info.strides = NULL # <<<<<<<<<<<<<< - * - * info.suboffsets = NULL - */ - __pyx_v_info->strides = NULL; - } - __pyx_L6:; - - /* "View.MemoryView":204 - * info.strides = NULL - * - * info.suboffsets = NULL # <<<<<<<<<<<<<< - * info.itemsize = self.itemsize - * info.readonly = 0 - */ - __pyx_v_info->suboffsets = NULL; - - /* "View.MemoryView":205 - * - * info.suboffsets = NULL - * info.itemsize = self.itemsize # <<<<<<<<<<<<<< - * info.readonly = 0 - * info.format = self.format if flags & PyBUF_FORMAT else NULL - */ - __pyx_t_3 = __pyx_v_self->itemsize; - __pyx_v_info->itemsize = __pyx_t_3; - - /* "View.MemoryView":206 - * info.suboffsets = NULL - * info.itemsize = self.itemsize - * info.readonly = 0 # <<<<<<<<<<<<<< - * info.format = self.format if flags & PyBUF_FORMAT else NULL - * info.obj = self - */ - __pyx_v_info->readonly = 0; - - /* "View.MemoryView":207 - * info.itemsize = self.itemsize - * info.readonly = 0 - * info.format = self.format if flags & PyBUF_FORMAT else NULL # <<<<<<<<<<<<<< - * info.obj = self - * - */ - __pyx_t_1 = ((__pyx_v_flags & PyBUF_FORMAT) != 0); - if (__pyx_t_1) { - __pyx_t_2 = __pyx_v_self->format; - } else { - __pyx_t_2 = NULL; - } - __pyx_v_info->format = __pyx_t_2; - - /* "View.MemoryView":208 - * info.readonly = 0 - * info.format = self.format if flags & PyBUF_FORMAT else NULL - * info.obj = self # <<<<<<<<<<<<<< - * - * def __dealloc__(array self): - */ - __Pyx_INCREF((PyObject *)__pyx_v_self); - __Pyx_GIVEREF((PyObject *)__pyx_v_self); - __Pyx_GOTREF(__pyx_v_info->obj); - __Pyx_DECREF(__pyx_v_info->obj); - __pyx_v_info->obj = ((PyObject *)__pyx_v_self); - - /* "View.MemoryView":182 - * _allocate_buffer(self) - * - * @cname('getbuffer') # <<<<<<<<<<<<<< - * def __getbuffer__(self, Py_buffer *info, int flags): - * cdef int bufmode = -1 - */ - - /* function exit code */ - __pyx_r = 0; - goto __pyx_L0; - __pyx_L1_error:; - __Pyx_AddTraceback("View.MemoryView.array.__getbuffer__", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = -1; - if (__pyx_v_info->obj != NULL) { - __Pyx_GOTREF(__pyx_v_info->obj); - __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; - } - goto __pyx_L2; - __pyx_L0:; - if (__pyx_v_info->obj == Py_None) { - __Pyx_GOTREF(__pyx_v_info->obj); - __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; - } - __pyx_L2:; - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "View.MemoryView":210 - * info.obj = self - * - * def __dealloc__(array self): # <<<<<<<<<<<<<< - * if self.callback_free_data != NULL: - * self.callback_free_data(self.data) - */ - -/* Python wrapper */ -static void __pyx_array___dealloc__(PyObject *__pyx_v_self); /*proto*/ -static void __pyx_array___dealloc__(PyObject *__pyx_v_self) { - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); - __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); - __pyx_array___pyx_pf_15View_dot_MemoryView_5array_4__dealloc__(((struct __pyx_array_obj *)__pyx_v_self)); - - /* function exit code */ - __Pyx_RefNannyFinishContext(); -} - -static void __pyx_array___pyx_pf_15View_dot_MemoryView_5array_4__dealloc__(struct __pyx_array_obj *__pyx_v_self) { - int __pyx_t_1; - int __pyx_t_2; - - /* "View.MemoryView":211 - * - * def __dealloc__(array self): - * if self.callback_free_data != NULL: # <<<<<<<<<<<<<< - * self.callback_free_data(self.data) - * elif self.free_data and self.data is not NULL: - */ - __pyx_t_1 = (__pyx_v_self->callback_free_data != NULL); - if (__pyx_t_1) { - - /* "View.MemoryView":212 - * def __dealloc__(array self): - * if self.callback_free_data != NULL: - * self.callback_free_data(self.data) # <<<<<<<<<<<<<< - * elif self.free_data and self.data is not NULL: - * if self.dtype_is_object: - */ - __pyx_v_self->callback_free_data(__pyx_v_self->data); - - /* "View.MemoryView":211 - * - * def __dealloc__(array self): - * if self.callback_free_data != NULL: # <<<<<<<<<<<<<< - * self.callback_free_data(self.data) - * elif self.free_data and self.data is not NULL: - */ - goto __pyx_L3; - } - - /* "View.MemoryView":213 - * if self.callback_free_data != NULL: - * self.callback_free_data(self.data) - * elif self.free_data and self.data is not NULL: # <<<<<<<<<<<<<< - * if self.dtype_is_object: - * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) - */ - if (__pyx_v_self->free_data) { - } else { - __pyx_t_1 = __pyx_v_self->free_data; - goto __pyx_L4_bool_binop_done; - } - __pyx_t_2 = (__pyx_v_self->data != NULL); - __pyx_t_1 = __pyx_t_2; - __pyx_L4_bool_binop_done:; - if (__pyx_t_1) { - - /* "View.MemoryView":214 - * self.callback_free_data(self.data) - * elif self.free_data and self.data is not NULL: - * if self.dtype_is_object: # <<<<<<<<<<<<<< - * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) - * free(self.data) - */ - if (__pyx_v_self->dtype_is_object) { - - /* "View.MemoryView":215 - * elif self.free_data and self.data is not NULL: - * if self.dtype_is_object: - * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) # <<<<<<<<<<<<<< - * free(self.data) - * PyObject_Free(self._shape) - */ - __pyx_memoryview_refcount_objects_in_slice(__pyx_v_self->data, __pyx_v_self->_shape, __pyx_v_self->_strides, __pyx_v_self->ndim, 0); - - /* "View.MemoryView":214 - * self.callback_free_data(self.data) - * elif self.free_data and self.data is not NULL: - * if self.dtype_is_object: # <<<<<<<<<<<<<< - * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) - * free(self.data) - */ - } - - /* "View.MemoryView":216 - * if self.dtype_is_object: - * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) - * free(self.data) # <<<<<<<<<<<<<< - * PyObject_Free(self._shape) - * - */ - free(__pyx_v_self->data); - - /* "View.MemoryView":213 - * if self.callback_free_data != NULL: - * self.callback_free_data(self.data) - * elif self.free_data and self.data is not NULL: # <<<<<<<<<<<<<< - * if self.dtype_is_object: - * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) - */ - } - __pyx_L3:; - - /* "View.MemoryView":217 - * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) - * free(self.data) - * PyObject_Free(self._shape) # <<<<<<<<<<<<<< - * - * @property - */ - PyObject_Free(__pyx_v_self->_shape); - - /* "View.MemoryView":210 - * info.obj = self - * - * def __dealloc__(array self): # <<<<<<<<<<<<<< - * if self.callback_free_data != NULL: - * self.callback_free_data(self.data) - */ - - /* function exit code */ -} - -/* "View.MemoryView":219 - * PyObject_Free(self._shape) - * - * @property # <<<<<<<<<<<<<< - * def memview(self): - * return self.get_memview() - */ - -/* Python wrapper */ -static PyObject *__pyx_pw_15View_dot_MemoryView_5array_7memview_1__get__(PyObject *__pyx_v_self); /*proto*/ -static PyObject *__pyx_pw_15View_dot_MemoryView_5array_7memview_1__get__(PyObject *__pyx_v_self) { - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - PyObject *__pyx_r = 0; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); - __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); - __pyx_r = __pyx_pf_15View_dot_MemoryView_5array_7memview___get__(((struct __pyx_array_obj *)__pyx_v_self)); - - /* function exit code */ - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static PyObject *__pyx_pf_15View_dot_MemoryView_5array_7memview___get__(struct __pyx_array_obj *__pyx_v_self) { - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - PyObject *__pyx_t_1 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("__get__", 1); - - /* "View.MemoryView":221 - * @property - * def memview(self): - * return self.get_memview() # <<<<<<<<<<<<<< - * - * @cname('get_memview') - */ - __Pyx_XDECREF(__pyx_r); - __pyx_t_1 = ((struct __pyx_vtabstruct_array *)__pyx_v_self->__pyx_vtab)->get_memview(__pyx_v_self); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 221, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_r = __pyx_t_1; - __pyx_t_1 = 0; - goto __pyx_L0; - - /* "View.MemoryView":219 - * PyObject_Free(self._shape) - * - * @property # <<<<<<<<<<<<<< - * def memview(self): - * return self.get_memview() - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_1); - __Pyx_AddTraceback("View.MemoryView.array.memview.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = NULL; - __pyx_L0:; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "View.MemoryView":224 - * - * @cname('get_memview') - * cdef get_memview(self): # <<<<<<<<<<<<<< - * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE - * return memoryview(self, flags, self.dtype_is_object) - */ - -static PyObject *__pyx_array_get_memview(struct __pyx_array_obj *__pyx_v_self) { - int __pyx_v_flags; - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - PyObject *__pyx_t_1 = NULL; - PyObject *__pyx_t_2 = NULL; - PyObject *__pyx_t_3 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("get_memview", 1); - - /* "View.MemoryView":225 - * @cname('get_memview') - * cdef get_memview(self): - * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE # <<<<<<<<<<<<<< - * return memoryview(self, flags, self.dtype_is_object) - * - */ - __pyx_v_flags = ((PyBUF_ANY_CONTIGUOUS | PyBUF_FORMAT) | PyBUF_WRITABLE); - - /* "View.MemoryView":226 - * cdef get_memview(self): - * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE - * return memoryview(self, flags, self.dtype_is_object) # <<<<<<<<<<<<<< - * - * def __len__(self): - */ - __Pyx_XDECREF(__pyx_r); - __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_flags); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 226, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_v_self->dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 226, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 226, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __Pyx_INCREF((PyObject *)__pyx_v_self); - __Pyx_GIVEREF((PyObject *)__pyx_v_self); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, ((PyObject *)__pyx_v_self))) __PYX_ERR(1, 226, __pyx_L1_error); - __Pyx_GIVEREF(__pyx_t_1); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1)) __PYX_ERR(1, 226, __pyx_L1_error); - __Pyx_GIVEREF(__pyx_t_2); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_t_2)) __PYX_ERR(1, 226, __pyx_L1_error); - __pyx_t_1 = 0; - __pyx_t_2 = 0; - __pyx_t_2 = __Pyx_PyObject_Call(((PyObject *)__pyx_memoryview_type), __pyx_t_3, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 226, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - __pyx_r = __pyx_t_2; - __pyx_t_2 = 0; - goto __pyx_L0; - - /* "View.MemoryView":224 - * - * @cname('get_memview') - * cdef get_memview(self): # <<<<<<<<<<<<<< - * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE - * return memoryview(self, flags, self.dtype_is_object) - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_1); - __Pyx_XDECREF(__pyx_t_2); - __Pyx_XDECREF(__pyx_t_3); - __Pyx_AddTraceback("View.MemoryView.array.get_memview", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = 0; - __pyx_L0:; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "View.MemoryView":228 - * return memoryview(self, flags, self.dtype_is_object) - * - * def __len__(self): # <<<<<<<<<<<<<< - * return self._shape[0] - * - */ - -/* Python wrapper */ -static Py_ssize_t __pyx_array___len__(PyObject *__pyx_v_self); /*proto*/ -static Py_ssize_t __pyx_array___len__(PyObject *__pyx_v_self) { - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - Py_ssize_t __pyx_r; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("__len__ (wrapper)", 0); - __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); - __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_6__len__(((struct __pyx_array_obj *)__pyx_v_self)); - - /* function exit code */ - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static Py_ssize_t __pyx_array___pyx_pf_15View_dot_MemoryView_5array_6__len__(struct __pyx_array_obj *__pyx_v_self) { - Py_ssize_t __pyx_r; - - /* "View.MemoryView":229 - * - * def __len__(self): - * return self._shape[0] # <<<<<<<<<<<<<< - * - * def __getattr__(self, attr): - */ - __pyx_r = (__pyx_v_self->_shape[0]); - goto __pyx_L0; - - /* "View.MemoryView":228 - * return memoryview(self, flags, self.dtype_is_object) - * - * def __len__(self): # <<<<<<<<<<<<<< - * return self._shape[0] - * - */ - - /* function exit code */ - __pyx_L0:; - return __pyx_r; -} - -/* "View.MemoryView":231 - * return self._shape[0] - * - * def __getattr__(self, attr): # <<<<<<<<<<<<<< - * return getattr(self.memview, attr) - * - */ - -/* Python wrapper */ -static PyObject *__pyx_array___getattr__(PyObject *__pyx_v_self, PyObject *__pyx_v_attr); /*proto*/ -static PyObject *__pyx_array___getattr__(PyObject *__pyx_v_self, PyObject *__pyx_v_attr) { - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - PyObject *__pyx_r = 0; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("__getattr__ (wrapper)", 0); - __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); - __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_8__getattr__(((struct __pyx_array_obj *)__pyx_v_self), ((PyObject *)__pyx_v_attr)); - - /* function exit code */ - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_8__getattr__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_attr) { - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - PyObject *__pyx_t_1 = NULL; - PyObject *__pyx_t_2 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("__getattr__", 1); - - /* "View.MemoryView":232 - * - * def __getattr__(self, attr): - * return getattr(self.memview, attr) # <<<<<<<<<<<<<< - * - * def __getitem__(self, item): - */ - __Pyx_XDECREF(__pyx_r); - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_memview); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 232, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_2 = __Pyx_GetAttr(__pyx_t_1, __pyx_v_attr); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 232, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_r = __pyx_t_2; - __pyx_t_2 = 0; - goto __pyx_L0; - - /* "View.MemoryView":231 - * return self._shape[0] - * - * def __getattr__(self, attr): # <<<<<<<<<<<<<< - * return getattr(self.memview, attr) - * - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_1); - __Pyx_XDECREF(__pyx_t_2); - __Pyx_AddTraceback("View.MemoryView.array.__getattr__", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = NULL; - __pyx_L0:; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "View.MemoryView":234 - * return getattr(self.memview, attr) - * - * def __getitem__(self, item): # <<<<<<<<<<<<<< - * return self.memview[item] - * - */ - -/* Python wrapper */ -static PyObject *__pyx_array___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item); /*proto*/ -static PyObject *__pyx_array___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item) { - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - PyObject *__pyx_r = 0; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("__getitem__ (wrapper)", 0); - __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); - __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_10__getitem__(((struct __pyx_array_obj *)__pyx_v_self), ((PyObject *)__pyx_v_item)); - - /* function exit code */ - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_10__getitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item) { - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - PyObject *__pyx_t_1 = NULL; - PyObject *__pyx_t_2 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("__getitem__", 1); - - /* "View.MemoryView":235 - * - * def __getitem__(self, item): - * return self.memview[item] # <<<<<<<<<<<<<< - * - * def __setitem__(self, item, value): - */ - __Pyx_XDECREF(__pyx_r); - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_memview); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 235, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_2 = __Pyx_PyObject_GetItem(__pyx_t_1, __pyx_v_item); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 235, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_r = __pyx_t_2; - __pyx_t_2 = 0; - goto __pyx_L0; - - /* "View.MemoryView":234 - * return getattr(self.memview, attr) - * - * def __getitem__(self, item): # <<<<<<<<<<<<<< - * return self.memview[item] - * - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_1); - __Pyx_XDECREF(__pyx_t_2); - __Pyx_AddTraceback("View.MemoryView.array.__getitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = NULL; - __pyx_L0:; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "View.MemoryView":237 - * return self.memview[item] - * - * def __setitem__(self, item, value): # <<<<<<<<<<<<<< - * self.memview[item] = value - * - */ - -/* Python wrapper */ -static int __pyx_array___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value); /*proto*/ -static int __pyx_array___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value) { - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - int __pyx_r; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("__setitem__ (wrapper)", 0); - __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); - __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_12__setitem__(((struct __pyx_array_obj *)__pyx_v_self), ((PyObject *)__pyx_v_item), ((PyObject *)__pyx_v_value)); - - /* function exit code */ - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_12__setitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value) { - int __pyx_r; - __Pyx_RefNannyDeclarations - PyObject *__pyx_t_1 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("__setitem__", 1); - - /* "View.MemoryView":238 - * - * def __setitem__(self, item, value): - * self.memview[item] = value # <<<<<<<<<<<<<< - * - * - */ - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_memview); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 238, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - if (unlikely((PyObject_SetItem(__pyx_t_1, __pyx_v_item, __pyx_v_value) < 0))) __PYX_ERR(1, 238, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - - /* "View.MemoryView":237 - * return self.memview[item] - * - * def __setitem__(self, item, value): # <<<<<<<<<<<<<< - * self.memview[item] = value - * - */ - - /* function exit code */ - __pyx_r = 0; - goto __pyx_L0; - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_1); - __Pyx_AddTraceback("View.MemoryView.array.__setitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = -1; - __pyx_L0:; - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "(tree fragment)":1 - * def __reduce_cython__(self): # <<<<<<<<<<<<<< - * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" - * def __setstate_cython__(self, __pyx_state): - */ - -/* Python wrapper */ -static PyObject *__pyx_pw___pyx_array_1__reduce_cython__(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -); /*proto*/ -static PyObject *__pyx_pw___pyx_array_1__reduce_cython__(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -) { - #if !CYTHON_METH_FASTCALL - CYTHON_UNUSED Py_ssize_t __pyx_nargs; - #endif - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - PyObject *__pyx_r = 0; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); - #if !CYTHON_METH_FASTCALL - #if CYTHON_ASSUME_SAFE_MACROS - __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); - #else - __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; - #endif - #endif - __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); - if (unlikely(__pyx_nargs > 0)) { - __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} - if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; - __pyx_r = __pyx_pf___pyx_array___reduce_cython__(((struct __pyx_array_obj *)__pyx_v_self)); - - /* function exit code */ - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static PyObject *__pyx_pf___pyx_array___reduce_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self) { - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("__reduce_cython__", 1); - - /* "(tree fragment)":2 - * def __reduce_cython__(self): - * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< - * def __setstate_cython__(self, __pyx_state): - * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" - */ - __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); - __PYX_ERR(1, 2, __pyx_L1_error) - - /* "(tree fragment)":1 - * def __reduce_cython__(self): # <<<<<<<<<<<<<< - * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" - * def __setstate_cython__(self, __pyx_state): - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_AddTraceback("View.MemoryView.array.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = NULL; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "(tree fragment)":3 - * def __reduce_cython__(self): - * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" - * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< - * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" - */ - -/* Python wrapper */ -static PyObject *__pyx_pw___pyx_array_3__setstate_cython__(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -); /*proto*/ -static PyObject *__pyx_pw___pyx_array_3__setstate_cython__(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -) { - CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; - #if !CYTHON_METH_FASTCALL - CYTHON_UNUSED Py_ssize_t __pyx_nargs; - #endif - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - PyObject* values[1] = {0}; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - PyObject *__pyx_r = 0; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); - #if !CYTHON_METH_FASTCALL - #if CYTHON_ASSUME_SAFE_MACROS - __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); - #else - __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; - #endif - #endif - __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); - { - PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; - if (__pyx_kwds) { - Py_ssize_t kw_args; - switch (__pyx_nargs) { - case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); - CYTHON_FALLTHROUGH; - case 0: break; - default: goto __pyx_L5_argtuple_error; - } - kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); - switch (__pyx_nargs) { - case 0: - if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { - (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); - kw_args--; - } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) - else goto __pyx_L5_argtuple_error; - } - if (unlikely(kw_args > 0)) { - const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) - } - } else if (unlikely(__pyx_nargs != 1)) { - goto __pyx_L5_argtuple_error; - } else { - values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); - } - __pyx_v___pyx_state = values[0]; - } - goto __pyx_L6_skip; - __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) - __pyx_L6_skip:; - goto __pyx_L4_argument_unpacking_done; - __pyx_L3_error:; - { - Py_ssize_t __pyx_temp; - for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { - __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); - } - } - __Pyx_AddTraceback("View.MemoryView.array.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); - __Pyx_RefNannyFinishContext(); - return NULL; - __pyx_L4_argument_unpacking_done:; - __pyx_r = __pyx_pf___pyx_array_2__setstate_cython__(((struct __pyx_array_obj *)__pyx_v_self), __pyx_v___pyx_state); - - /* function exit code */ - { - Py_ssize_t __pyx_temp; - for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { - __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); - } - } - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static PyObject *__pyx_pf___pyx_array_2__setstate_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("__setstate_cython__", 1); - - /* "(tree fragment)":4 - * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" - * def __setstate_cython__(self, __pyx_state): - * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< - */ - __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); - __PYX_ERR(1, 4, __pyx_L1_error) - - /* "(tree fragment)":3 - * def __reduce_cython__(self): - * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" - * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< - * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_AddTraceback("View.MemoryView.array.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = NULL; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "View.MemoryView":248 - * - * @cname("__pyx_array_allocate_buffer") - * cdef int _allocate_buffer(array self) except -1: # <<<<<<<<<<<<<< - * - * - */ - -static int __pyx_array_allocate_buffer(struct __pyx_array_obj *__pyx_v_self) { - Py_ssize_t __pyx_v_i; - PyObject **__pyx_v_p; - int __pyx_r; - int __pyx_t_1; - Py_ssize_t __pyx_t_2; - Py_ssize_t __pyx_t_3; - Py_ssize_t __pyx_t_4; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - - /* "View.MemoryView":254 - * cdef PyObject **p - * - * self.free_data = True # <<<<<<<<<<<<<< - * self.data = malloc(self.len) - * if not self.data: - */ - __pyx_v_self->free_data = 1; - - /* "View.MemoryView":255 - * - * self.free_data = True - * self.data = malloc(self.len) # <<<<<<<<<<<<<< - * if not self.data: - * raise MemoryError, "unable to allocate array data." - */ - __pyx_v_self->data = ((char *)malloc(__pyx_v_self->len)); - - /* "View.MemoryView":256 - * self.free_data = True - * self.data = malloc(self.len) - * if not self.data: # <<<<<<<<<<<<<< - * raise MemoryError, "unable to allocate array data." - * - */ - __pyx_t_1 = (!(__pyx_v_self->data != 0)); - if (unlikely(__pyx_t_1)) { - - /* "View.MemoryView":257 - * self.data = malloc(self.len) - * if not self.data: - * raise MemoryError, "unable to allocate array data." # <<<<<<<<<<<<<< - * - * if self.dtype_is_object: - */ - __Pyx_Raise(__pyx_builtin_MemoryError, __pyx_kp_s_unable_to_allocate_array_data, 0, 0); - __PYX_ERR(1, 257, __pyx_L1_error) - - /* "View.MemoryView":256 - * self.free_data = True - * self.data = malloc(self.len) - * if not self.data: # <<<<<<<<<<<<<< - * raise MemoryError, "unable to allocate array data." - * - */ - } - - /* "View.MemoryView":259 - * raise MemoryError, "unable to allocate array data." - * - * if self.dtype_is_object: # <<<<<<<<<<<<<< - * p = self.data - * for i in range(self.len // self.itemsize): - */ - if (__pyx_v_self->dtype_is_object) { - - /* "View.MemoryView":260 - * - * if self.dtype_is_object: - * p = self.data # <<<<<<<<<<<<<< - * for i in range(self.len // self.itemsize): - * p[i] = Py_None - */ - __pyx_v_p = ((PyObject **)__pyx_v_self->data); - - /* "View.MemoryView":261 - * if self.dtype_is_object: - * p = self.data - * for i in range(self.len // self.itemsize): # <<<<<<<<<<<<<< - * p[i] = Py_None - * Py_INCREF(Py_None) - */ - if (unlikely(__pyx_v_self->itemsize == 0)) { - PyErr_SetString(PyExc_ZeroDivisionError, "integer division or modulo by zero"); - __PYX_ERR(1, 261, __pyx_L1_error) - } - else if (sizeof(Py_ssize_t) == sizeof(long) && (!(((Py_ssize_t)-1) > 0)) && unlikely(__pyx_v_self->itemsize == (Py_ssize_t)-1) && unlikely(__Pyx_UNARY_NEG_WOULD_OVERFLOW(__pyx_v_self->len))) { - PyErr_SetString(PyExc_OverflowError, "value too large to perform division"); - __PYX_ERR(1, 261, __pyx_L1_error) - } - __pyx_t_2 = __Pyx_div_Py_ssize_t(__pyx_v_self->len, __pyx_v_self->itemsize); - __pyx_t_3 = __pyx_t_2; - for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { - __pyx_v_i = __pyx_t_4; - - /* "View.MemoryView":262 - * p = self.data - * for i in range(self.len // self.itemsize): - * p[i] = Py_None # <<<<<<<<<<<<<< - * Py_INCREF(Py_None) - * return 0 - */ - (__pyx_v_p[__pyx_v_i]) = Py_None; - - /* "View.MemoryView":263 - * for i in range(self.len // self.itemsize): - * p[i] = Py_None - * Py_INCREF(Py_None) # <<<<<<<<<<<<<< - * return 0 - * - */ - Py_INCREF(Py_None); - } - - /* "View.MemoryView":259 - * raise MemoryError, "unable to allocate array data." - * - * if self.dtype_is_object: # <<<<<<<<<<<<<< - * p = self.data - * for i in range(self.len // self.itemsize): - */ - } - - /* "View.MemoryView":264 - * p[i] = Py_None - * Py_INCREF(Py_None) - * return 0 # <<<<<<<<<<<<<< - * - * - */ - __pyx_r = 0; - goto __pyx_L0; - - /* "View.MemoryView":248 - * - * @cname("__pyx_array_allocate_buffer") - * cdef int _allocate_buffer(array self) except -1: # <<<<<<<<<<<<<< - * - * - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_AddTraceback("View.MemoryView._allocate_buffer", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = -1; - __pyx_L0:; - return __pyx_r; -} - -/* "View.MemoryView":268 - * - * @cname("__pyx_array_new") - * cdef array array_cwrapper(tuple shape, Py_ssize_t itemsize, char *format, char *c_mode, char *buf): # <<<<<<<<<<<<<< - * cdef array result - * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. - */ - -static struct __pyx_array_obj *__pyx_array_new(PyObject *__pyx_v_shape, Py_ssize_t __pyx_v_itemsize, char *__pyx_v_format, char *__pyx_v_c_mode, char *__pyx_v_buf) { - struct __pyx_array_obj *__pyx_v_result = 0; - PyObject *__pyx_v_mode = 0; - struct __pyx_array_obj *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - PyObject *__pyx_t_1 = NULL; - int __pyx_t_2; - PyObject *__pyx_t_3 = NULL; - PyObject *__pyx_t_4 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("array_cwrapper", 1); - - /* "View.MemoryView":270 - * cdef array array_cwrapper(tuple shape, Py_ssize_t itemsize, char *format, char *c_mode, char *buf): - * cdef array result - * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. # <<<<<<<<<<<<<< - * - * if buf is NULL: - */ - __pyx_t_2 = ((__pyx_v_c_mode[0]) == 'f'); - if (__pyx_t_2) { - __Pyx_INCREF(__pyx_n_s_fortran); - __pyx_t_1 = __pyx_n_s_fortran; - } else { - __Pyx_INCREF(__pyx_n_s_c); - __pyx_t_1 = __pyx_n_s_c; - } - __pyx_v_mode = ((PyObject*)__pyx_t_1); - __pyx_t_1 = 0; - - /* "View.MemoryView":272 - * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. - * - * if buf is NULL: # <<<<<<<<<<<<<< - * result = array.__new__(array, shape, itemsize, format, mode) - * else: - */ - __pyx_t_2 = (__pyx_v_buf == NULL); - if (__pyx_t_2) { - - /* "View.MemoryView":273 - * - * if buf is NULL: - * result = array.__new__(array, shape, itemsize, format, mode) # <<<<<<<<<<<<<< - * else: - * result = array.__new__(array, shape, itemsize, format, mode, allocate_buffer=False) - */ - __pyx_t_1 = PyInt_FromSsize_t(__pyx_v_itemsize); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 273, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_3 = __Pyx_PyBytes_FromString(__pyx_v_format); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 273, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __pyx_t_4 = PyTuple_New(4); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 273, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __Pyx_INCREF(__pyx_v_shape); - __Pyx_GIVEREF(__pyx_v_shape); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_v_shape)) __PYX_ERR(1, 273, __pyx_L1_error); - __Pyx_GIVEREF(__pyx_t_1); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 1, __pyx_t_1)) __PYX_ERR(1, 273, __pyx_L1_error); - __Pyx_GIVEREF(__pyx_t_3); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 2, __pyx_t_3)) __PYX_ERR(1, 273, __pyx_L1_error); - __Pyx_INCREF(__pyx_v_mode); - __Pyx_GIVEREF(__pyx_v_mode); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 3, __pyx_v_mode)) __PYX_ERR(1, 273, __pyx_L1_error); - __pyx_t_1 = 0; - __pyx_t_3 = 0; - __pyx_t_3 = ((PyObject *)__pyx_tp_new_array(((PyTypeObject *)__pyx_array_type), __pyx_t_4, NULL)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 273, __pyx_L1_error) - __Pyx_GOTREF((PyObject *)__pyx_t_3); - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __pyx_v_result = ((struct __pyx_array_obj *)__pyx_t_3); - __pyx_t_3 = 0; - - /* "View.MemoryView":272 - * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. - * - * if buf is NULL: # <<<<<<<<<<<<<< - * result = array.__new__(array, shape, itemsize, format, mode) - * else: - */ - goto __pyx_L3; - } - - /* "View.MemoryView":275 - * result = array.__new__(array, shape, itemsize, format, mode) - * else: - * result = array.__new__(array, shape, itemsize, format, mode, allocate_buffer=False) # <<<<<<<<<<<<<< - * result.data = buf - * - */ - /*else*/ { - __pyx_t_3 = PyInt_FromSsize_t(__pyx_v_itemsize); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 275, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __pyx_t_4 = __Pyx_PyBytes_FromString(__pyx_v_format); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 275, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __pyx_t_1 = PyTuple_New(4); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 275, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __Pyx_INCREF(__pyx_v_shape); - __Pyx_GIVEREF(__pyx_v_shape); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v_shape)) __PYX_ERR(1, 275, __pyx_L1_error); - __Pyx_GIVEREF(__pyx_t_3); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_t_3)) __PYX_ERR(1, 275, __pyx_L1_error); - __Pyx_GIVEREF(__pyx_t_4); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_t_4)) __PYX_ERR(1, 275, __pyx_L1_error); - __Pyx_INCREF(__pyx_v_mode); - __Pyx_GIVEREF(__pyx_v_mode); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 3, __pyx_v_mode)) __PYX_ERR(1, 275, __pyx_L1_error); - __pyx_t_3 = 0; - __pyx_t_4 = 0; - __pyx_t_4 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 275, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - if (PyDict_SetItem(__pyx_t_4, __pyx_n_s_allocate_buffer, Py_False) < 0) __PYX_ERR(1, 275, __pyx_L1_error) - __pyx_t_3 = ((PyObject *)__pyx_tp_new_array(((PyTypeObject *)__pyx_array_type), __pyx_t_1, __pyx_t_4)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 275, __pyx_L1_error) - __Pyx_GOTREF((PyObject *)__pyx_t_3); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __pyx_v_result = ((struct __pyx_array_obj *)__pyx_t_3); - __pyx_t_3 = 0; - - /* "View.MemoryView":276 - * else: - * result = array.__new__(array, shape, itemsize, format, mode, allocate_buffer=False) - * result.data = buf # <<<<<<<<<<<<<< - * - * return result - */ - __pyx_v_result->data = __pyx_v_buf; - } - __pyx_L3:; - - /* "View.MemoryView":278 - * result.data = buf - * - * return result # <<<<<<<<<<<<<< - * - * - */ - __Pyx_XDECREF((PyObject *)__pyx_r); - __Pyx_INCREF((PyObject *)__pyx_v_result); - __pyx_r = __pyx_v_result; - goto __pyx_L0; - - /* "View.MemoryView":268 - * - * @cname("__pyx_array_new") - * cdef array array_cwrapper(tuple shape, Py_ssize_t itemsize, char *format, char *c_mode, char *buf): # <<<<<<<<<<<<<< - * cdef array result - * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_1); - __Pyx_XDECREF(__pyx_t_3); - __Pyx_XDECREF(__pyx_t_4); - __Pyx_AddTraceback("View.MemoryView.array_cwrapper", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = 0; - __pyx_L0:; - __Pyx_XDECREF((PyObject *)__pyx_v_result); - __Pyx_XDECREF(__pyx_v_mode); - __Pyx_XGIVEREF((PyObject *)__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "View.MemoryView":304 - * cdef class Enum(object): - * cdef object name - * def __init__(self, name): # <<<<<<<<<<<<<< - * self.name = name - * def __repr__(self): - */ - -/* Python wrapper */ -static int __pyx_MemviewEnum___init__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ -static int __pyx_MemviewEnum___init__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { - PyObject *__pyx_v_name = 0; - CYTHON_UNUSED Py_ssize_t __pyx_nargs; - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - PyObject* values[1] = {0}; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - int __pyx_r; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("__init__ (wrapper)", 0); - #if CYTHON_ASSUME_SAFE_MACROS - __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); - #else - __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return -1; - #endif - __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); - { - PyObject **__pyx_pyargnames[] = {&__pyx_n_s_name,0}; - if (__pyx_kwds) { - Py_ssize_t kw_args; - switch (__pyx_nargs) { - case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); - CYTHON_FALLTHROUGH; - case 0: break; - default: goto __pyx_L5_argtuple_error; - } - kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); - switch (__pyx_nargs) { - case 0: - if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_name)) != 0)) { - (void)__Pyx_Arg_NewRef_VARARGS(values[0]); - kw_args--; - } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 304, __pyx_L3_error) - else goto __pyx_L5_argtuple_error; - } - if (unlikely(kw_args > 0)) { - const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__init__") < 0)) __PYX_ERR(1, 304, __pyx_L3_error) - } - } else if (unlikely(__pyx_nargs != 1)) { - goto __pyx_L5_argtuple_error; - } else { - values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); - } - __pyx_v_name = values[0]; - } - goto __pyx_L6_skip; - __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("__init__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 304, __pyx_L3_error) - __pyx_L6_skip:; - goto __pyx_L4_argument_unpacking_done; - __pyx_L3_error:; - { - Py_ssize_t __pyx_temp; - for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { - __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); - } - } - __Pyx_AddTraceback("View.MemoryView.Enum.__init__", __pyx_clineno, __pyx_lineno, __pyx_filename); - __Pyx_RefNannyFinishContext(); - return -1; - __pyx_L4_argument_unpacking_done:; - __pyx_r = __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum___init__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self), __pyx_v_name); - - /* function exit code */ - { - Py_ssize_t __pyx_temp; - for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { - __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); - } - } - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static int __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum___init__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v_name) { - int __pyx_r; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("__init__", 1); - - /* "View.MemoryView":305 - * cdef object name - * def __init__(self, name): - * self.name = name # <<<<<<<<<<<<<< - * def __repr__(self): - * return self.name - */ - __Pyx_INCREF(__pyx_v_name); - __Pyx_GIVEREF(__pyx_v_name); - __Pyx_GOTREF(__pyx_v_self->name); - __Pyx_DECREF(__pyx_v_self->name); - __pyx_v_self->name = __pyx_v_name; - - /* "View.MemoryView":304 - * cdef class Enum(object): - * cdef object name - * def __init__(self, name): # <<<<<<<<<<<<<< - * self.name = name - * def __repr__(self): - */ - - /* function exit code */ - __pyx_r = 0; - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "View.MemoryView":306 - * def __init__(self, name): - * self.name = name - * def __repr__(self): # <<<<<<<<<<<<<< - * return self.name - * - */ - -/* Python wrapper */ -static PyObject *__pyx_MemviewEnum___repr__(PyObject *__pyx_v_self); /*proto*/ -static PyObject *__pyx_MemviewEnum___repr__(PyObject *__pyx_v_self) { - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - PyObject *__pyx_r = 0; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("__repr__ (wrapper)", 0); - __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); - __pyx_r = __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum_2__repr__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self)); - - /* function exit code */ - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static PyObject *__pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum_2__repr__(struct __pyx_MemviewEnum_obj *__pyx_v_self) { - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("__repr__", 1); - - /* "View.MemoryView":307 - * self.name = name - * def __repr__(self): - * return self.name # <<<<<<<<<<<<<< - * - * cdef generic = Enum("") - */ - __Pyx_XDECREF(__pyx_r); - __Pyx_INCREF(__pyx_v_self->name); - __pyx_r = __pyx_v_self->name; - goto __pyx_L0; - - /* "View.MemoryView":306 - * def __init__(self, name): - * self.name = name - * def __repr__(self): # <<<<<<<<<<<<<< - * return self.name - * - */ - - /* function exit code */ - __pyx_L0:; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "(tree fragment)":1 - * def __reduce_cython__(self): # <<<<<<<<<<<<<< - * cdef tuple state - * cdef object _dict - */ - -/* Python wrapper */ -static PyObject *__pyx_pw___pyx_MemviewEnum_1__reduce_cython__(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -); /*proto*/ -static PyObject *__pyx_pw___pyx_MemviewEnum_1__reduce_cython__(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -) { - #if !CYTHON_METH_FASTCALL - CYTHON_UNUSED Py_ssize_t __pyx_nargs; - #endif - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - PyObject *__pyx_r = 0; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); - #if !CYTHON_METH_FASTCALL - #if CYTHON_ASSUME_SAFE_MACROS - __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); - #else - __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; - #endif - #endif - __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); - if (unlikely(__pyx_nargs > 0)) { - __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} - if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; - __pyx_r = __pyx_pf___pyx_MemviewEnum___reduce_cython__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self)); - - /* function exit code */ - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static PyObject *__pyx_pf___pyx_MemviewEnum___reduce_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self) { - PyObject *__pyx_v_state = 0; - PyObject *__pyx_v__dict = 0; - int __pyx_v_use_setstate; - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - PyObject *__pyx_t_1 = NULL; - int __pyx_t_2; - PyObject *__pyx_t_3 = NULL; - PyObject *__pyx_t_4 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("__reduce_cython__", 1); - - /* "(tree fragment)":5 - * cdef object _dict - * cdef bint use_setstate - * state = (self.name,) # <<<<<<<<<<<<<< - * _dict = getattr(self, '__dict__', None) - * if _dict is not None: - */ - __pyx_t_1 = PyTuple_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 5, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __Pyx_INCREF(__pyx_v_self->name); - __Pyx_GIVEREF(__pyx_v_self->name); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v_self->name)) __PYX_ERR(1, 5, __pyx_L1_error); - __pyx_v_state = ((PyObject*)__pyx_t_1); - __pyx_t_1 = 0; - - /* "(tree fragment)":6 - * cdef bint use_setstate - * state = (self.name,) - * _dict = getattr(self, '__dict__', None) # <<<<<<<<<<<<<< - * if _dict is not None: - * state += (_dict,) - */ - __pyx_t_1 = __Pyx_GetAttr3(((PyObject *)__pyx_v_self), __pyx_n_s_dict, Py_None); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 6, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_v__dict = __pyx_t_1; - __pyx_t_1 = 0; - - /* "(tree fragment)":7 - * state = (self.name,) - * _dict = getattr(self, '__dict__', None) - * if _dict is not None: # <<<<<<<<<<<<<< - * state += (_dict,) - * use_setstate = True - */ - __pyx_t_2 = (__pyx_v__dict != Py_None); - if (__pyx_t_2) { - - /* "(tree fragment)":8 - * _dict = getattr(self, '__dict__', None) - * if _dict is not None: - * state += (_dict,) # <<<<<<<<<<<<<< - * use_setstate = True - * else: - */ - __pyx_t_1 = PyTuple_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 8, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __Pyx_INCREF(__pyx_v__dict); - __Pyx_GIVEREF(__pyx_v__dict); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v__dict)) __PYX_ERR(1, 8, __pyx_L1_error); - __pyx_t_3 = PyNumber_InPlaceAdd(__pyx_v_state, __pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 8, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __Pyx_DECREF_SET(__pyx_v_state, ((PyObject*)__pyx_t_3)); - __pyx_t_3 = 0; - - /* "(tree fragment)":9 - * if _dict is not None: - * state += (_dict,) - * use_setstate = True # <<<<<<<<<<<<<< - * else: - * use_setstate = self.name is not None - */ - __pyx_v_use_setstate = 1; - - /* "(tree fragment)":7 - * state = (self.name,) - * _dict = getattr(self, '__dict__', None) - * if _dict is not None: # <<<<<<<<<<<<<< - * state += (_dict,) - * use_setstate = True - */ - goto __pyx_L3; - } - - /* "(tree fragment)":11 - * use_setstate = True - * else: - * use_setstate = self.name is not None # <<<<<<<<<<<<<< - * if use_setstate: - * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state - */ - /*else*/ { - __pyx_t_2 = (__pyx_v_self->name != Py_None); - __pyx_v_use_setstate = __pyx_t_2; - } - __pyx_L3:; - - /* "(tree fragment)":12 - * else: - * use_setstate = self.name is not None - * if use_setstate: # <<<<<<<<<<<<<< - * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state - * else: - */ - if (__pyx_v_use_setstate) { - - /* "(tree fragment)":13 - * use_setstate = self.name is not None - * if use_setstate: - * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state # <<<<<<<<<<<<<< - * else: - * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) - */ - __Pyx_XDECREF(__pyx_r); - __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_pyx_unpickle_Enum); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 13, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __pyx_t_1 = PyTuple_New(3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 13, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __Pyx_INCREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); - __Pyx_GIVEREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, ((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self))))) __PYX_ERR(1, 13, __pyx_L1_error); - __Pyx_INCREF(__pyx_int_136983863); - __Pyx_GIVEREF(__pyx_int_136983863); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_int_136983863)) __PYX_ERR(1, 13, __pyx_L1_error); - __Pyx_INCREF(Py_None); - __Pyx_GIVEREF(Py_None); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 2, Py_None)) __PYX_ERR(1, 13, __pyx_L1_error); - __pyx_t_4 = PyTuple_New(3); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 13, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __Pyx_GIVEREF(__pyx_t_3); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_3)) __PYX_ERR(1, 13, __pyx_L1_error); - __Pyx_GIVEREF(__pyx_t_1); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 1, __pyx_t_1)) __PYX_ERR(1, 13, __pyx_L1_error); - __Pyx_INCREF(__pyx_v_state); - __Pyx_GIVEREF(__pyx_v_state); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 2, __pyx_v_state)) __PYX_ERR(1, 13, __pyx_L1_error); - __pyx_t_3 = 0; - __pyx_t_1 = 0; - __pyx_r = __pyx_t_4; - __pyx_t_4 = 0; - goto __pyx_L0; - - /* "(tree fragment)":12 - * else: - * use_setstate = self.name is not None - * if use_setstate: # <<<<<<<<<<<<<< - * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state - * else: - */ - } - - /* "(tree fragment)":15 - * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state - * else: - * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) # <<<<<<<<<<<<<< - * def __setstate_cython__(self, __pyx_state): - * __pyx_unpickle_Enum__set_state(self, __pyx_state) - */ - /*else*/ { - __Pyx_XDECREF(__pyx_r); - __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_pyx_unpickle_Enum); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 15, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __pyx_t_1 = PyTuple_New(3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 15, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __Pyx_INCREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); - __Pyx_GIVEREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, ((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self))))) __PYX_ERR(1, 15, __pyx_L1_error); - __Pyx_INCREF(__pyx_int_136983863); - __Pyx_GIVEREF(__pyx_int_136983863); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_int_136983863)) __PYX_ERR(1, 15, __pyx_L1_error); - __Pyx_INCREF(__pyx_v_state); - __Pyx_GIVEREF(__pyx_v_state); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_v_state)) __PYX_ERR(1, 15, __pyx_L1_error); - __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 15, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __Pyx_GIVEREF(__pyx_t_4); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_4)) __PYX_ERR(1, 15, __pyx_L1_error); - __Pyx_GIVEREF(__pyx_t_1); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1)) __PYX_ERR(1, 15, __pyx_L1_error); - __pyx_t_4 = 0; - __pyx_t_1 = 0; - __pyx_r = __pyx_t_3; - __pyx_t_3 = 0; - goto __pyx_L0; - } - - /* "(tree fragment)":1 - * def __reduce_cython__(self): # <<<<<<<<<<<<<< - * cdef tuple state - * cdef object _dict - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_1); - __Pyx_XDECREF(__pyx_t_3); - __Pyx_XDECREF(__pyx_t_4); - __Pyx_AddTraceback("View.MemoryView.Enum.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = NULL; - __pyx_L0:; - __Pyx_XDECREF(__pyx_v_state); - __Pyx_XDECREF(__pyx_v__dict); - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "(tree fragment)":16 - * else: - * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) - * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< - * __pyx_unpickle_Enum__set_state(self, __pyx_state) - */ - -/* Python wrapper */ -static PyObject *__pyx_pw___pyx_MemviewEnum_3__setstate_cython__(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -); /*proto*/ -static PyObject *__pyx_pw___pyx_MemviewEnum_3__setstate_cython__(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -) { - PyObject *__pyx_v___pyx_state = 0; - #if !CYTHON_METH_FASTCALL - CYTHON_UNUSED Py_ssize_t __pyx_nargs; - #endif - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - PyObject* values[1] = {0}; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - PyObject *__pyx_r = 0; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); - #if !CYTHON_METH_FASTCALL - #if CYTHON_ASSUME_SAFE_MACROS - __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); - #else - __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; - #endif - #endif - __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); - { - PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; - if (__pyx_kwds) { - Py_ssize_t kw_args; - switch (__pyx_nargs) { - case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); - CYTHON_FALLTHROUGH; - case 0: break; - default: goto __pyx_L5_argtuple_error; - } - kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); - switch (__pyx_nargs) { - case 0: - if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { - (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); - kw_args--; - } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 16, __pyx_L3_error) - else goto __pyx_L5_argtuple_error; - } - if (unlikely(kw_args > 0)) { - const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 16, __pyx_L3_error) - } - } else if (unlikely(__pyx_nargs != 1)) { - goto __pyx_L5_argtuple_error; - } else { - values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); - } - __pyx_v___pyx_state = values[0]; - } - goto __pyx_L6_skip; - __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 16, __pyx_L3_error) - __pyx_L6_skip:; - goto __pyx_L4_argument_unpacking_done; - __pyx_L3_error:; - { - Py_ssize_t __pyx_temp; - for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { - __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); - } - } - __Pyx_AddTraceback("View.MemoryView.Enum.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); - __Pyx_RefNannyFinishContext(); - return NULL; - __pyx_L4_argument_unpacking_done:; - __pyx_r = __pyx_pf___pyx_MemviewEnum_2__setstate_cython__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self), __pyx_v___pyx_state); - - /* function exit code */ - { - Py_ssize_t __pyx_temp; - for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { - __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); - } - } - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static PyObject *__pyx_pf___pyx_MemviewEnum_2__setstate_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v___pyx_state) { - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - PyObject *__pyx_t_1 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("__setstate_cython__", 1); - - /* "(tree fragment)":17 - * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) - * def __setstate_cython__(self, __pyx_state): - * __pyx_unpickle_Enum__set_state(self, __pyx_state) # <<<<<<<<<<<<<< - */ - if (!(likely(PyTuple_CheckExact(__pyx_v___pyx_state))||((__pyx_v___pyx_state) == Py_None) || __Pyx_RaiseUnexpectedTypeError("tuple", __pyx_v___pyx_state))) __PYX_ERR(1, 17, __pyx_L1_error) - __pyx_t_1 = __pyx_unpickle_Enum__set_state(__pyx_v_self, ((PyObject*)__pyx_v___pyx_state)); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 17, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - - /* "(tree fragment)":16 - * else: - * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) - * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< - * __pyx_unpickle_Enum__set_state(self, __pyx_state) - */ - - /* function exit code */ - __pyx_r = Py_None; __Pyx_INCREF(Py_None); - goto __pyx_L0; - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_1); - __Pyx_AddTraceback("View.MemoryView.Enum.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = NULL; - __pyx_L0:; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "View.MemoryView":349 - * cdef __Pyx_TypeInfo *typeinfo - * - * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): # <<<<<<<<<<<<<< - * self.obj = obj - * self.flags = flags - */ - -/* Python wrapper */ -static int __pyx_memoryview___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ -static int __pyx_memoryview___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { - PyObject *__pyx_v_obj = 0; - int __pyx_v_flags; - int __pyx_v_dtype_is_object; - CYTHON_UNUSED Py_ssize_t __pyx_nargs; - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - PyObject* values[3] = {0,0,0}; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - int __pyx_r; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); - #if CYTHON_ASSUME_SAFE_MACROS - __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); - #else - __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return -1; - #endif - __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); - { - PyObject **__pyx_pyargnames[] = {&__pyx_n_s_obj,&__pyx_n_s_flags,&__pyx_n_s_dtype_is_object,0}; - if (__pyx_kwds) { - Py_ssize_t kw_args; - switch (__pyx_nargs) { - case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); - CYTHON_FALLTHROUGH; - case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); - CYTHON_FALLTHROUGH; - case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); - CYTHON_FALLTHROUGH; - case 0: break; - default: goto __pyx_L5_argtuple_error; - } - kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); - switch (__pyx_nargs) { - case 0: - if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_obj)) != 0)) { - (void)__Pyx_Arg_NewRef_VARARGS(values[0]); - kw_args--; - } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 349, __pyx_L3_error) - else goto __pyx_L5_argtuple_error; - CYTHON_FALLTHROUGH; - case 1: - if (likely((values[1] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_flags)) != 0)) { - (void)__Pyx_Arg_NewRef_VARARGS(values[1]); - kw_args--; - } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 349, __pyx_L3_error) - else { - __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 2, 3, 1); __PYX_ERR(1, 349, __pyx_L3_error) - } - CYTHON_FALLTHROUGH; - case 2: - if (kw_args > 0) { - PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_dtype_is_object); - if (value) { values[2] = __Pyx_Arg_NewRef_VARARGS(value); kw_args--; } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 349, __pyx_L3_error) - } - } - if (unlikely(kw_args > 0)) { - const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__cinit__") < 0)) __PYX_ERR(1, 349, __pyx_L3_error) - } - } else { - switch (__pyx_nargs) { - case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); - CYTHON_FALLTHROUGH; - case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); - values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); - break; - default: goto __pyx_L5_argtuple_error; - } - } - __pyx_v_obj = values[0]; - __pyx_v_flags = __Pyx_PyInt_As_int(values[1]); if (unlikely((__pyx_v_flags == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 349, __pyx_L3_error) - if (values[2]) { - __pyx_v_dtype_is_object = __Pyx_PyObject_IsTrue(values[2]); if (unlikely((__pyx_v_dtype_is_object == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 349, __pyx_L3_error) - } else { - __pyx_v_dtype_is_object = ((int)0); - } - } - goto __pyx_L6_skip; - __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 2, 3, __pyx_nargs); __PYX_ERR(1, 349, __pyx_L3_error) - __pyx_L6_skip:; - goto __pyx_L4_argument_unpacking_done; - __pyx_L3_error:; - { - Py_ssize_t __pyx_temp; - for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { - __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); - } - } - __Pyx_AddTraceback("View.MemoryView.memoryview.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); - __Pyx_RefNannyFinishContext(); - return -1; - __pyx_L4_argument_unpacking_done:; - __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview___cinit__(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v_obj, __pyx_v_flags, __pyx_v_dtype_is_object); - - /* function exit code */ - { - Py_ssize_t __pyx_temp; - for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { - __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); - } - } - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview___cinit__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj, int __pyx_v_flags, int __pyx_v_dtype_is_object) { - int __pyx_r; - __Pyx_RefNannyDeclarations - int __pyx_t_1; - int __pyx_t_2; - int __pyx_t_3; - Py_intptr_t __pyx_t_4; - size_t __pyx_t_5; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("__cinit__", 1); - - /* "View.MemoryView":350 - * - * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): - * self.obj = obj # <<<<<<<<<<<<<< - * self.flags = flags - * if type(self) is memoryview or obj is not None: - */ - __Pyx_INCREF(__pyx_v_obj); - __Pyx_GIVEREF(__pyx_v_obj); - __Pyx_GOTREF(__pyx_v_self->obj); - __Pyx_DECREF(__pyx_v_self->obj); - __pyx_v_self->obj = __pyx_v_obj; - - /* "View.MemoryView":351 - * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): - * self.obj = obj - * self.flags = flags # <<<<<<<<<<<<<< - * if type(self) is memoryview or obj is not None: - * __Pyx_GetBuffer(obj, &self.view, flags) - */ - __pyx_v_self->flags = __pyx_v_flags; - - /* "View.MemoryView":352 - * self.obj = obj - * self.flags = flags - * if type(self) is memoryview or obj is not None: # <<<<<<<<<<<<<< - * __Pyx_GetBuffer(obj, &self.view, flags) - * if self.view.obj == NULL: - */ - __pyx_t_2 = (((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self))) == ((PyObject *)__pyx_memoryview_type)); - if (!__pyx_t_2) { - } else { - __pyx_t_1 = __pyx_t_2; - goto __pyx_L4_bool_binop_done; - } - __pyx_t_2 = (__pyx_v_obj != Py_None); - __pyx_t_1 = __pyx_t_2; - __pyx_L4_bool_binop_done:; - if (__pyx_t_1) { - - /* "View.MemoryView":353 - * self.flags = flags - * if type(self) is memoryview or obj is not None: - * __Pyx_GetBuffer(obj, &self.view, flags) # <<<<<<<<<<<<<< - * if self.view.obj == NULL: - * (<__pyx_buffer *> &self.view).obj = Py_None - */ - __pyx_t_3 = __Pyx_GetBuffer(__pyx_v_obj, (&__pyx_v_self->view), __pyx_v_flags); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(1, 353, __pyx_L1_error) - - /* "View.MemoryView":354 - * if type(self) is memoryview or obj is not None: - * __Pyx_GetBuffer(obj, &self.view, flags) - * if self.view.obj == NULL: # <<<<<<<<<<<<<< - * (<__pyx_buffer *> &self.view).obj = Py_None - * Py_INCREF(Py_None) - */ - __pyx_t_1 = (((PyObject *)__pyx_v_self->view.obj) == NULL); - if (__pyx_t_1) { - - /* "View.MemoryView":355 - * __Pyx_GetBuffer(obj, &self.view, flags) - * if self.view.obj == NULL: - * (<__pyx_buffer *> &self.view).obj = Py_None # <<<<<<<<<<<<<< - * Py_INCREF(Py_None) - * - */ - ((Py_buffer *)(&__pyx_v_self->view))->obj = Py_None; - - /* "View.MemoryView":356 - * if self.view.obj == NULL: - * (<__pyx_buffer *> &self.view).obj = Py_None - * Py_INCREF(Py_None) # <<<<<<<<<<<<<< - * - * if not __PYX_CYTHON_ATOMICS_ENABLED(): - */ - Py_INCREF(Py_None); - - /* "View.MemoryView":354 - * if type(self) is memoryview or obj is not None: - * __Pyx_GetBuffer(obj, &self.view, flags) - * if self.view.obj == NULL: # <<<<<<<<<<<<<< - * (<__pyx_buffer *> &self.view).obj = Py_None - * Py_INCREF(Py_None) - */ - } - - /* "View.MemoryView":352 - * self.obj = obj - * self.flags = flags - * if type(self) is memoryview or obj is not None: # <<<<<<<<<<<<<< - * __Pyx_GetBuffer(obj, &self.view, flags) - * if self.view.obj == NULL: - */ - } - - /* "View.MemoryView":358 - * Py_INCREF(Py_None) - * - * if not __PYX_CYTHON_ATOMICS_ENABLED(): # <<<<<<<<<<<<<< - * global __pyx_memoryview_thread_locks_used - * if __pyx_memoryview_thread_locks_used < 8: - */ - __pyx_t_1 = (!__PYX_CYTHON_ATOMICS_ENABLED()); - if (__pyx_t_1) { - - /* "View.MemoryView":360 - * if not __PYX_CYTHON_ATOMICS_ENABLED(): - * global __pyx_memoryview_thread_locks_used - * if __pyx_memoryview_thread_locks_used < 8: # <<<<<<<<<<<<<< - * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] - * __pyx_memoryview_thread_locks_used += 1 - */ - __pyx_t_1 = (__pyx_memoryview_thread_locks_used < 8); - if (__pyx_t_1) { - - /* "View.MemoryView":361 - * global __pyx_memoryview_thread_locks_used - * if __pyx_memoryview_thread_locks_used < 8: - * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] # <<<<<<<<<<<<<< - * __pyx_memoryview_thread_locks_used += 1 - * if self.lock is NULL: - */ - __pyx_v_self->lock = (__pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used]); - - /* "View.MemoryView":362 - * if __pyx_memoryview_thread_locks_used < 8: - * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] - * __pyx_memoryview_thread_locks_used += 1 # <<<<<<<<<<<<<< - * if self.lock is NULL: - * self.lock = PyThread_allocate_lock() - */ - __pyx_memoryview_thread_locks_used = (__pyx_memoryview_thread_locks_used + 1); - - /* "View.MemoryView":360 - * if not __PYX_CYTHON_ATOMICS_ENABLED(): - * global __pyx_memoryview_thread_locks_used - * if __pyx_memoryview_thread_locks_used < 8: # <<<<<<<<<<<<<< - * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] - * __pyx_memoryview_thread_locks_used += 1 - */ - } - - /* "View.MemoryView":363 - * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] - * __pyx_memoryview_thread_locks_used += 1 - * if self.lock is NULL: # <<<<<<<<<<<<<< - * self.lock = PyThread_allocate_lock() - * if self.lock is NULL: - */ - __pyx_t_1 = (__pyx_v_self->lock == NULL); - if (__pyx_t_1) { - - /* "View.MemoryView":364 - * __pyx_memoryview_thread_locks_used += 1 - * if self.lock is NULL: - * self.lock = PyThread_allocate_lock() # <<<<<<<<<<<<<< - * if self.lock is NULL: - * raise MemoryError - */ - __pyx_v_self->lock = PyThread_allocate_lock(); - - /* "View.MemoryView":365 - * if self.lock is NULL: - * self.lock = PyThread_allocate_lock() - * if self.lock is NULL: # <<<<<<<<<<<<<< - * raise MemoryError - * - */ - __pyx_t_1 = (__pyx_v_self->lock == NULL); - if (unlikely(__pyx_t_1)) { - - /* "View.MemoryView":366 - * self.lock = PyThread_allocate_lock() - * if self.lock is NULL: - * raise MemoryError # <<<<<<<<<<<<<< - * - * if flags & PyBUF_FORMAT: - */ - PyErr_NoMemory(); __PYX_ERR(1, 366, __pyx_L1_error) - - /* "View.MemoryView":365 - * if self.lock is NULL: - * self.lock = PyThread_allocate_lock() - * if self.lock is NULL: # <<<<<<<<<<<<<< - * raise MemoryError - * - */ - } - - /* "View.MemoryView":363 - * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] - * __pyx_memoryview_thread_locks_used += 1 - * if self.lock is NULL: # <<<<<<<<<<<<<< - * self.lock = PyThread_allocate_lock() - * if self.lock is NULL: - */ - } - - /* "View.MemoryView":358 - * Py_INCREF(Py_None) - * - * if not __PYX_CYTHON_ATOMICS_ENABLED(): # <<<<<<<<<<<<<< - * global __pyx_memoryview_thread_locks_used - * if __pyx_memoryview_thread_locks_used < 8: - */ - } - - /* "View.MemoryView":368 - * raise MemoryError - * - * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< - * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') - * else: - */ - __pyx_t_1 = ((__pyx_v_flags & PyBUF_FORMAT) != 0); - if (__pyx_t_1) { - - /* "View.MemoryView":369 - * - * if flags & PyBUF_FORMAT: - * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') # <<<<<<<<<<<<<< - * else: - * self.dtype_is_object = dtype_is_object - */ - __pyx_t_2 = ((__pyx_v_self->view.format[0]) == 'O'); - if (__pyx_t_2) { - } else { - __pyx_t_1 = __pyx_t_2; - goto __pyx_L12_bool_binop_done; - } - __pyx_t_2 = ((__pyx_v_self->view.format[1]) == '\x00'); - __pyx_t_1 = __pyx_t_2; - __pyx_L12_bool_binop_done:; - __pyx_v_self->dtype_is_object = __pyx_t_1; - - /* "View.MemoryView":368 - * raise MemoryError - * - * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< - * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') - * else: - */ - goto __pyx_L11; - } - - /* "View.MemoryView":371 - * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') - * else: - * self.dtype_is_object = dtype_is_object # <<<<<<<<<<<<<< - * - * assert (&self.acquisition_count) % sizeof(__pyx_atomic_int_type) == 0 - */ - /*else*/ { - __pyx_v_self->dtype_is_object = __pyx_v_dtype_is_object; - } - __pyx_L11:; - - /* "View.MemoryView":373 - * self.dtype_is_object = dtype_is_object - * - * assert (&self.acquisition_count) % sizeof(__pyx_atomic_int_type) == 0 # <<<<<<<<<<<<<< - * self.typeinfo = NULL - * - */ - #ifndef CYTHON_WITHOUT_ASSERTIONS - if (unlikely(__pyx_assertions_enabled())) { - __pyx_t_4 = ((Py_intptr_t)((void *)(&__pyx_v_self->acquisition_count))); - __pyx_t_5 = (sizeof(__pyx_atomic_int_type)); - if (unlikely(__pyx_t_5 == 0)) { - PyErr_SetString(PyExc_ZeroDivisionError, "integer division or modulo by zero"); - __PYX_ERR(1, 373, __pyx_L1_error) - } - __pyx_t_1 = ((__pyx_t_4 % __pyx_t_5) == 0); - if (unlikely(!__pyx_t_1)) { - __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); - __PYX_ERR(1, 373, __pyx_L1_error) - } - } - #else - if ((1)); else __PYX_ERR(1, 373, __pyx_L1_error) - #endif - - /* "View.MemoryView":374 - * - * assert (&self.acquisition_count) % sizeof(__pyx_atomic_int_type) == 0 - * self.typeinfo = NULL # <<<<<<<<<<<<<< - * - * def __dealloc__(memoryview self): - */ - __pyx_v_self->typeinfo = NULL; - - /* "View.MemoryView":349 - * cdef __Pyx_TypeInfo *typeinfo - * - * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): # <<<<<<<<<<<<<< - * self.obj = obj - * self.flags = flags - */ - - /* function exit code */ - __pyx_r = 0; - goto __pyx_L0; - __pyx_L1_error:; - __Pyx_AddTraceback("View.MemoryView.memoryview.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = -1; - __pyx_L0:; - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "View.MemoryView":376 - * self.typeinfo = NULL - * - * def __dealloc__(memoryview self): # <<<<<<<<<<<<<< - * if self.obj is not None: - * __Pyx_ReleaseBuffer(&self.view) - */ - -/* Python wrapper */ -static void __pyx_memoryview___dealloc__(PyObject *__pyx_v_self); /*proto*/ -static void __pyx_memoryview___dealloc__(PyObject *__pyx_v_self) { - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); - __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); - __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_2__dealloc__(((struct __pyx_memoryview_obj *)__pyx_v_self)); - - /* function exit code */ - __Pyx_RefNannyFinishContext(); -} - -static void __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_2__dealloc__(struct __pyx_memoryview_obj *__pyx_v_self) { - int __pyx_v_i; - int __pyx_t_1; - int __pyx_t_2; - int __pyx_t_3; - int __pyx_t_4; - PyThread_type_lock __pyx_t_5; - PyThread_type_lock __pyx_t_6; - - /* "View.MemoryView":377 - * - * def __dealloc__(memoryview self): - * if self.obj is not None: # <<<<<<<<<<<<<< - * __Pyx_ReleaseBuffer(&self.view) - * elif (<__pyx_buffer *> &self.view).obj == Py_None: - */ - __pyx_t_1 = (__pyx_v_self->obj != Py_None); - if (__pyx_t_1) { - - /* "View.MemoryView":378 - * def __dealloc__(memoryview self): - * if self.obj is not None: - * __Pyx_ReleaseBuffer(&self.view) # <<<<<<<<<<<<<< - * elif (<__pyx_buffer *> &self.view).obj == Py_None: - * - */ - __Pyx_ReleaseBuffer((&__pyx_v_self->view)); - - /* "View.MemoryView":377 - * - * def __dealloc__(memoryview self): - * if self.obj is not None: # <<<<<<<<<<<<<< - * __Pyx_ReleaseBuffer(&self.view) - * elif (<__pyx_buffer *> &self.view).obj == Py_None: - */ - goto __pyx_L3; - } - - /* "View.MemoryView":379 - * if self.obj is not None: - * __Pyx_ReleaseBuffer(&self.view) - * elif (<__pyx_buffer *> &self.view).obj == Py_None: # <<<<<<<<<<<<<< - * - * (<__pyx_buffer *> &self.view).obj = NULL - */ - __pyx_t_1 = (((Py_buffer *)(&__pyx_v_self->view))->obj == Py_None); - if (__pyx_t_1) { - - /* "View.MemoryView":381 - * elif (<__pyx_buffer *> &self.view).obj == Py_None: - * - * (<__pyx_buffer *> &self.view).obj = NULL # <<<<<<<<<<<<<< - * Py_DECREF(Py_None) - * - */ - ((Py_buffer *)(&__pyx_v_self->view))->obj = NULL; - - /* "View.MemoryView":382 - * - * (<__pyx_buffer *> &self.view).obj = NULL - * Py_DECREF(Py_None) # <<<<<<<<<<<<<< - * - * cdef int i - */ - Py_DECREF(Py_None); - - /* "View.MemoryView":379 - * if self.obj is not None: - * __Pyx_ReleaseBuffer(&self.view) - * elif (<__pyx_buffer *> &self.view).obj == Py_None: # <<<<<<<<<<<<<< - * - * (<__pyx_buffer *> &self.view).obj = NULL - */ - } - __pyx_L3:; - - /* "View.MemoryView":386 - * cdef int i - * global __pyx_memoryview_thread_locks_used - * if self.lock != NULL: # <<<<<<<<<<<<<< - * for i in range(__pyx_memoryview_thread_locks_used): - * if __pyx_memoryview_thread_locks[i] is self.lock: - */ - __pyx_t_1 = (__pyx_v_self->lock != NULL); - if (__pyx_t_1) { - - /* "View.MemoryView":387 - * global __pyx_memoryview_thread_locks_used - * if self.lock != NULL: - * for i in range(__pyx_memoryview_thread_locks_used): # <<<<<<<<<<<<<< - * if __pyx_memoryview_thread_locks[i] is self.lock: - * __pyx_memoryview_thread_locks_used -= 1 - */ - __pyx_t_2 = __pyx_memoryview_thread_locks_used; - __pyx_t_3 = __pyx_t_2; - for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { - __pyx_v_i = __pyx_t_4; - - /* "View.MemoryView":388 - * if self.lock != NULL: - * for i in range(__pyx_memoryview_thread_locks_used): - * if __pyx_memoryview_thread_locks[i] is self.lock: # <<<<<<<<<<<<<< - * __pyx_memoryview_thread_locks_used -= 1 - * if i != __pyx_memoryview_thread_locks_used: - */ - __pyx_t_1 = ((__pyx_memoryview_thread_locks[__pyx_v_i]) == __pyx_v_self->lock); - if (__pyx_t_1) { - - /* "View.MemoryView":389 - * for i in range(__pyx_memoryview_thread_locks_used): - * if __pyx_memoryview_thread_locks[i] is self.lock: - * __pyx_memoryview_thread_locks_used -= 1 # <<<<<<<<<<<<<< - * if i != __pyx_memoryview_thread_locks_used: - * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( - */ - __pyx_memoryview_thread_locks_used = (__pyx_memoryview_thread_locks_used - 1); - - /* "View.MemoryView":390 - * if __pyx_memoryview_thread_locks[i] is self.lock: - * __pyx_memoryview_thread_locks_used -= 1 - * if i != __pyx_memoryview_thread_locks_used: # <<<<<<<<<<<<<< - * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( - * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) - */ - __pyx_t_1 = (__pyx_v_i != __pyx_memoryview_thread_locks_used); - if (__pyx_t_1) { - - /* "View.MemoryView":392 - * if i != __pyx_memoryview_thread_locks_used: - * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( - * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) # <<<<<<<<<<<<<< - * break - * else: - */ - __pyx_t_5 = (__pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used]); - __pyx_t_6 = (__pyx_memoryview_thread_locks[__pyx_v_i]); - - /* "View.MemoryView":391 - * __pyx_memoryview_thread_locks_used -= 1 - * if i != __pyx_memoryview_thread_locks_used: - * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( # <<<<<<<<<<<<<< - * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) - * break - */ - (__pyx_memoryview_thread_locks[__pyx_v_i]) = __pyx_t_5; - (__pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used]) = __pyx_t_6; - - /* "View.MemoryView":390 - * if __pyx_memoryview_thread_locks[i] is self.lock: - * __pyx_memoryview_thread_locks_used -= 1 - * if i != __pyx_memoryview_thread_locks_used: # <<<<<<<<<<<<<< - * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( - * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) - */ - } - - /* "View.MemoryView":393 - * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( - * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) - * break # <<<<<<<<<<<<<< - * else: - * PyThread_free_lock(self.lock) - */ - goto __pyx_L6_break; - - /* "View.MemoryView":388 - * if self.lock != NULL: - * for i in range(__pyx_memoryview_thread_locks_used): - * if __pyx_memoryview_thread_locks[i] is self.lock: # <<<<<<<<<<<<<< - * __pyx_memoryview_thread_locks_used -= 1 - * if i != __pyx_memoryview_thread_locks_used: - */ - } - } - /*else*/ { - - /* "View.MemoryView":395 - * break - * else: - * PyThread_free_lock(self.lock) # <<<<<<<<<<<<<< - * - * cdef char *get_item_pointer(memoryview self, object index) except NULL: - */ - PyThread_free_lock(__pyx_v_self->lock); - } - __pyx_L6_break:; - - /* "View.MemoryView":386 - * cdef int i - * global __pyx_memoryview_thread_locks_used - * if self.lock != NULL: # <<<<<<<<<<<<<< - * for i in range(__pyx_memoryview_thread_locks_used): - * if __pyx_memoryview_thread_locks[i] is self.lock: - */ - } - - /* "View.MemoryView":376 - * self.typeinfo = NULL - * - * def __dealloc__(memoryview self): # <<<<<<<<<<<<<< - * if self.obj is not None: - * __Pyx_ReleaseBuffer(&self.view) - */ - - /* function exit code */ -} - -/* "View.MemoryView":397 - * PyThread_free_lock(self.lock) - * - * cdef char *get_item_pointer(memoryview self, object index) except NULL: # <<<<<<<<<<<<<< - * cdef Py_ssize_t dim - * cdef char *itemp = self.view.buf - */ - -static char *__pyx_memoryview_get_item_pointer(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index) { - Py_ssize_t __pyx_v_dim; - char *__pyx_v_itemp; - PyObject *__pyx_v_idx = NULL; - char *__pyx_r; - __Pyx_RefNannyDeclarations - Py_ssize_t __pyx_t_1; - PyObject *__pyx_t_2 = NULL; - Py_ssize_t __pyx_t_3; - PyObject *(*__pyx_t_4)(PyObject *); - PyObject *__pyx_t_5 = NULL; - Py_ssize_t __pyx_t_6; - char *__pyx_t_7; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("get_item_pointer", 1); - - /* "View.MemoryView":399 - * cdef char *get_item_pointer(memoryview self, object index) except NULL: - * cdef Py_ssize_t dim - * cdef char *itemp = self.view.buf # <<<<<<<<<<<<<< - * - * for dim, idx in enumerate(index): - */ - __pyx_v_itemp = ((char *)__pyx_v_self->view.buf); - - /* "View.MemoryView":401 - * cdef char *itemp = self.view.buf - * - * for dim, idx in enumerate(index): # <<<<<<<<<<<<<< - * itemp = pybuffer_index(&self.view, itemp, idx, dim) - * - */ - __pyx_t_1 = 0; - if (likely(PyList_CheckExact(__pyx_v_index)) || PyTuple_CheckExact(__pyx_v_index)) { - __pyx_t_2 = __pyx_v_index; __Pyx_INCREF(__pyx_t_2); - __pyx_t_3 = 0; - __pyx_t_4 = NULL; - } else { - __pyx_t_3 = -1; __pyx_t_2 = PyObject_GetIter(__pyx_v_index); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 401, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __pyx_t_4 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_2); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 401, __pyx_L1_error) - } - for (;;) { - if (likely(!__pyx_t_4)) { - if (likely(PyList_CheckExact(__pyx_t_2))) { - { - Py_ssize_t __pyx_temp = __Pyx_PyList_GET_SIZE(__pyx_t_2); - #if !CYTHON_ASSUME_SAFE_MACROS - if (unlikely((__pyx_temp < 0))) __PYX_ERR(1, 401, __pyx_L1_error) - #endif - if (__pyx_t_3 >= __pyx_temp) break; - } - #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS - __pyx_t_5 = PyList_GET_ITEM(__pyx_t_2, __pyx_t_3); __Pyx_INCREF(__pyx_t_5); __pyx_t_3++; if (unlikely((0 < 0))) __PYX_ERR(1, 401, __pyx_L1_error) - #else - __pyx_t_5 = __Pyx_PySequence_ITEM(__pyx_t_2, __pyx_t_3); __pyx_t_3++; if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 401, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - #endif - } else { - { - Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_2); - #if !CYTHON_ASSUME_SAFE_MACROS - if (unlikely((__pyx_temp < 0))) __PYX_ERR(1, 401, __pyx_L1_error) - #endif - if (__pyx_t_3 >= __pyx_temp) break; - } - #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS - __pyx_t_5 = PyTuple_GET_ITEM(__pyx_t_2, __pyx_t_3); __Pyx_INCREF(__pyx_t_5); __pyx_t_3++; if (unlikely((0 < 0))) __PYX_ERR(1, 401, __pyx_L1_error) - #else - __pyx_t_5 = __Pyx_PySequence_ITEM(__pyx_t_2, __pyx_t_3); __pyx_t_3++; if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 401, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - #endif - } - } else { - __pyx_t_5 = __pyx_t_4(__pyx_t_2); - if (unlikely(!__pyx_t_5)) { - PyObject* exc_type = PyErr_Occurred(); - if (exc_type) { - if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); - else __PYX_ERR(1, 401, __pyx_L1_error) - } - break; - } - __Pyx_GOTREF(__pyx_t_5); - } - __Pyx_XDECREF_SET(__pyx_v_idx, __pyx_t_5); - __pyx_t_5 = 0; - __pyx_v_dim = __pyx_t_1; - __pyx_t_1 = (__pyx_t_1 + 1); - - /* "View.MemoryView":402 - * - * for dim, idx in enumerate(index): - * itemp = pybuffer_index(&self.view, itemp, idx, dim) # <<<<<<<<<<<<<< - * - * return itemp - */ - __pyx_t_6 = __Pyx_PyIndex_AsSsize_t(__pyx_v_idx); if (unlikely((__pyx_t_6 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 402, __pyx_L1_error) - __pyx_t_7 = __pyx_pybuffer_index((&__pyx_v_self->view), __pyx_v_itemp, __pyx_t_6, __pyx_v_dim); if (unlikely(__pyx_t_7 == ((char *)NULL))) __PYX_ERR(1, 402, __pyx_L1_error) - __pyx_v_itemp = __pyx_t_7; - - /* "View.MemoryView":401 - * cdef char *itemp = self.view.buf - * - * for dim, idx in enumerate(index): # <<<<<<<<<<<<<< - * itemp = pybuffer_index(&self.view, itemp, idx, dim) - * - */ - } - __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - - /* "View.MemoryView":404 - * itemp = pybuffer_index(&self.view, itemp, idx, dim) - * - * return itemp # <<<<<<<<<<<<<< - * - * - */ - __pyx_r = __pyx_v_itemp; - goto __pyx_L0; - - /* "View.MemoryView":397 - * PyThread_free_lock(self.lock) - * - * cdef char *get_item_pointer(memoryview self, object index) except NULL: # <<<<<<<<<<<<<< - * cdef Py_ssize_t dim - * cdef char *itemp = self.view.buf - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_2); - __Pyx_XDECREF(__pyx_t_5); - __Pyx_AddTraceback("View.MemoryView.memoryview.get_item_pointer", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = NULL; - __pyx_L0:; - __Pyx_XDECREF(__pyx_v_idx); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "View.MemoryView":407 - * - * - * def __getitem__(memoryview self, object index): # <<<<<<<<<<<<<< - * if index is Ellipsis: - * return self - */ - -/* Python wrapper */ -static PyObject *__pyx_memoryview___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index); /*proto*/ -static PyObject *__pyx_memoryview___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index) { - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - PyObject *__pyx_r = 0; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("__getitem__ (wrapper)", 0); - __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); - __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_4__getitem__(((struct __pyx_memoryview_obj *)__pyx_v_self), ((PyObject *)__pyx_v_index)); - - /* function exit code */ - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_4__getitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index) { - PyObject *__pyx_v_have_slices = NULL; - PyObject *__pyx_v_indices = NULL; - char *__pyx_v_itemp; - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - int __pyx_t_1; - PyObject *__pyx_t_2 = NULL; - PyObject *__pyx_t_3 = NULL; - PyObject *__pyx_t_4 = NULL; - char *__pyx_t_5; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("__getitem__", 1); - - /* "View.MemoryView":408 - * - * def __getitem__(memoryview self, object index): - * if index is Ellipsis: # <<<<<<<<<<<<<< - * return self - * - */ - __pyx_t_1 = (__pyx_v_index == __pyx_builtin_Ellipsis); - if (__pyx_t_1) { - - /* "View.MemoryView":409 - * def __getitem__(memoryview self, object index): - * if index is Ellipsis: - * return self # <<<<<<<<<<<<<< - * - * have_slices, indices = _unellipsify(index, self.view.ndim) - */ - __Pyx_XDECREF(__pyx_r); - __Pyx_INCREF((PyObject *)__pyx_v_self); - __pyx_r = ((PyObject *)__pyx_v_self); - goto __pyx_L0; - - /* "View.MemoryView":408 - * - * def __getitem__(memoryview self, object index): - * if index is Ellipsis: # <<<<<<<<<<<<<< - * return self - * - */ - } - - /* "View.MemoryView":411 - * return self - * - * have_slices, indices = _unellipsify(index, self.view.ndim) # <<<<<<<<<<<<<< - * - * cdef char *itemp - */ - __pyx_t_2 = _unellipsify(__pyx_v_index, __pyx_v_self->view.ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 411, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - if (likely(__pyx_t_2 != Py_None)) { - PyObject* sequence = __pyx_t_2; - Py_ssize_t size = __Pyx_PySequence_SIZE(sequence); - if (unlikely(size != 2)) { - if (size > 2) __Pyx_RaiseTooManyValuesError(2); - else if (size >= 0) __Pyx_RaiseNeedMoreValuesError(size); - __PYX_ERR(1, 411, __pyx_L1_error) - } - #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS - __pyx_t_3 = PyTuple_GET_ITEM(sequence, 0); - __pyx_t_4 = PyTuple_GET_ITEM(sequence, 1); - __Pyx_INCREF(__pyx_t_3); - __Pyx_INCREF(__pyx_t_4); - #else - __pyx_t_3 = PySequence_ITEM(sequence, 0); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 411, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __pyx_t_4 = PySequence_ITEM(sequence, 1); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 411, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - #endif - __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - } else { - __Pyx_RaiseNoneNotIterableError(); __PYX_ERR(1, 411, __pyx_L1_error) - } - __pyx_v_have_slices = __pyx_t_3; - __pyx_t_3 = 0; - __pyx_v_indices = __pyx_t_4; - __pyx_t_4 = 0; - - /* "View.MemoryView":414 - * - * cdef char *itemp - * if have_slices: # <<<<<<<<<<<<<< - * return memview_slice(self, indices) - * else: - */ - __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_v_have_slices); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 414, __pyx_L1_error) - if (__pyx_t_1) { - - /* "View.MemoryView":415 - * cdef char *itemp - * if have_slices: - * return memview_slice(self, indices) # <<<<<<<<<<<<<< - * else: - * itemp = self.get_item_pointer(indices) - */ - __Pyx_XDECREF(__pyx_r); - __pyx_t_2 = ((PyObject *)__pyx_memview_slice(__pyx_v_self, __pyx_v_indices)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 415, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __pyx_r = __pyx_t_2; - __pyx_t_2 = 0; - goto __pyx_L0; - - /* "View.MemoryView":414 - * - * cdef char *itemp - * if have_slices: # <<<<<<<<<<<<<< - * return memview_slice(self, indices) - * else: - */ - } - - /* "View.MemoryView":417 - * return memview_slice(self, indices) - * else: - * itemp = self.get_item_pointer(indices) # <<<<<<<<<<<<<< - * return self.convert_item_to_object(itemp) - * - */ - /*else*/ { - __pyx_t_5 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->get_item_pointer(__pyx_v_self, __pyx_v_indices); if (unlikely(__pyx_t_5 == ((char *)NULL))) __PYX_ERR(1, 417, __pyx_L1_error) - __pyx_v_itemp = __pyx_t_5; - - /* "View.MemoryView":418 - * else: - * itemp = self.get_item_pointer(indices) - * return self.convert_item_to_object(itemp) # <<<<<<<<<<<<<< - * - * def __setitem__(memoryview self, object index, object value): - */ - __Pyx_XDECREF(__pyx_r); - __pyx_t_2 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->convert_item_to_object(__pyx_v_self, __pyx_v_itemp); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 418, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __pyx_r = __pyx_t_2; - __pyx_t_2 = 0; - goto __pyx_L0; - } - - /* "View.MemoryView":407 - * - * - * def __getitem__(memoryview self, object index): # <<<<<<<<<<<<<< - * if index is Ellipsis: - * return self - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_2); - __Pyx_XDECREF(__pyx_t_3); - __Pyx_XDECREF(__pyx_t_4); - __Pyx_AddTraceback("View.MemoryView.memoryview.__getitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = NULL; - __pyx_L0:; - __Pyx_XDECREF(__pyx_v_have_slices); - __Pyx_XDECREF(__pyx_v_indices); - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "View.MemoryView":420 - * return self.convert_item_to_object(itemp) - * - * def __setitem__(memoryview self, object index, object value): # <<<<<<<<<<<<<< - * if self.view.readonly: - * raise TypeError, "Cannot assign to read-only memoryview" - */ - -/* Python wrapper */ -static int __pyx_memoryview___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value); /*proto*/ -static int __pyx_memoryview___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value) { - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - int __pyx_r; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("__setitem__ (wrapper)", 0); - __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); - __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_6__setitem__(((struct __pyx_memoryview_obj *)__pyx_v_self), ((PyObject *)__pyx_v_index), ((PyObject *)__pyx_v_value)); - - /* function exit code */ - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_6__setitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value) { - PyObject *__pyx_v_have_slices = NULL; - PyObject *__pyx_v_obj = NULL; - int __pyx_r; - __Pyx_RefNannyDeclarations - PyObject *__pyx_t_1 = NULL; - PyObject *__pyx_t_2 = NULL; - PyObject *__pyx_t_3 = NULL; - int __pyx_t_4; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("__setitem__", 0); - __Pyx_INCREF(__pyx_v_index); - - /* "View.MemoryView":421 - * - * def __setitem__(memoryview self, object index, object value): - * if self.view.readonly: # <<<<<<<<<<<<<< - * raise TypeError, "Cannot assign to read-only memoryview" - * - */ - if (unlikely(__pyx_v_self->view.readonly)) { - - /* "View.MemoryView":422 - * def __setitem__(memoryview self, object index, object value): - * if self.view.readonly: - * raise TypeError, "Cannot assign to read-only memoryview" # <<<<<<<<<<<<<< - * - * have_slices, index = _unellipsify(index, self.view.ndim) - */ - __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_Cannot_assign_to_read_only_memor, 0, 0); - __PYX_ERR(1, 422, __pyx_L1_error) - - /* "View.MemoryView":421 - * - * def __setitem__(memoryview self, object index, object value): - * if self.view.readonly: # <<<<<<<<<<<<<< - * raise TypeError, "Cannot assign to read-only memoryview" - * - */ - } - - /* "View.MemoryView":424 - * raise TypeError, "Cannot assign to read-only memoryview" - * - * have_slices, index = _unellipsify(index, self.view.ndim) # <<<<<<<<<<<<<< - * - * if have_slices: - */ - __pyx_t_1 = _unellipsify(__pyx_v_index, __pyx_v_self->view.ndim); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 424, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - if (likely(__pyx_t_1 != Py_None)) { - PyObject* sequence = __pyx_t_1; - Py_ssize_t size = __Pyx_PySequence_SIZE(sequence); - if (unlikely(size != 2)) { - if (size > 2) __Pyx_RaiseTooManyValuesError(2); - else if (size >= 0) __Pyx_RaiseNeedMoreValuesError(size); - __PYX_ERR(1, 424, __pyx_L1_error) - } - #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS - __pyx_t_2 = PyTuple_GET_ITEM(sequence, 0); - __pyx_t_3 = PyTuple_GET_ITEM(sequence, 1); - __Pyx_INCREF(__pyx_t_2); - __Pyx_INCREF(__pyx_t_3); - #else - __pyx_t_2 = PySequence_ITEM(sequence, 0); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 424, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __pyx_t_3 = PySequence_ITEM(sequence, 1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 424, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - #endif - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - } else { - __Pyx_RaiseNoneNotIterableError(); __PYX_ERR(1, 424, __pyx_L1_error) - } - __pyx_v_have_slices = __pyx_t_2; - __pyx_t_2 = 0; - __Pyx_DECREF_SET(__pyx_v_index, __pyx_t_3); - __pyx_t_3 = 0; - - /* "View.MemoryView":426 - * have_slices, index = _unellipsify(index, self.view.ndim) - * - * if have_slices: # <<<<<<<<<<<<<< - * obj = self.is_slice(value) - * if obj: - */ - __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_v_have_slices); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(1, 426, __pyx_L1_error) - if (__pyx_t_4) { - - /* "View.MemoryView":427 - * - * if have_slices: - * obj = self.is_slice(value) # <<<<<<<<<<<<<< - * if obj: - * self.setitem_slice_assignment(self[index], obj) - */ - __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->is_slice(__pyx_v_self, __pyx_v_value); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 427, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_v_obj = __pyx_t_1; - __pyx_t_1 = 0; - - /* "View.MemoryView":428 - * if have_slices: - * obj = self.is_slice(value) - * if obj: # <<<<<<<<<<<<<< - * self.setitem_slice_assignment(self[index], obj) - * else: - */ - __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_v_obj); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(1, 428, __pyx_L1_error) - if (__pyx_t_4) { - - /* "View.MemoryView":429 - * obj = self.is_slice(value) - * if obj: - * self.setitem_slice_assignment(self[index], obj) # <<<<<<<<<<<<<< - * else: - * self.setitem_slice_assign_scalar(self[index], value) - */ - __pyx_t_1 = __Pyx_PyObject_GetItem(((PyObject *)__pyx_v_self), __pyx_v_index); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 429, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_3 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->setitem_slice_assignment(__pyx_v_self, __pyx_t_1, __pyx_v_obj); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 429, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - - /* "View.MemoryView":428 - * if have_slices: - * obj = self.is_slice(value) - * if obj: # <<<<<<<<<<<<<< - * self.setitem_slice_assignment(self[index], obj) - * else: - */ - goto __pyx_L5; - } - - /* "View.MemoryView":431 - * self.setitem_slice_assignment(self[index], obj) - * else: - * self.setitem_slice_assign_scalar(self[index], value) # <<<<<<<<<<<<<< - * else: - * self.setitem_indexed(index, value) - */ - /*else*/ { - __pyx_t_3 = __Pyx_PyObject_GetItem(((PyObject *)__pyx_v_self), __pyx_v_index); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 431, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - if (!(likely(((__pyx_t_3) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_3, __pyx_memoryview_type))))) __PYX_ERR(1, 431, __pyx_L1_error) - __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->setitem_slice_assign_scalar(__pyx_v_self, ((struct __pyx_memoryview_obj *)__pyx_t_3), __pyx_v_value); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 431, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - } - __pyx_L5:; - - /* "View.MemoryView":426 - * have_slices, index = _unellipsify(index, self.view.ndim) - * - * if have_slices: # <<<<<<<<<<<<<< - * obj = self.is_slice(value) - * if obj: - */ - goto __pyx_L4; - } - - /* "View.MemoryView":433 - * self.setitem_slice_assign_scalar(self[index], value) - * else: - * self.setitem_indexed(index, value) # <<<<<<<<<<<<<< - * - * cdef is_slice(self, obj): - */ - /*else*/ { - __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->setitem_indexed(__pyx_v_self, __pyx_v_index, __pyx_v_value); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 433, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - } - __pyx_L4:; - - /* "View.MemoryView":420 - * return self.convert_item_to_object(itemp) - * - * def __setitem__(memoryview self, object index, object value): # <<<<<<<<<<<<<< - * if self.view.readonly: - * raise TypeError, "Cannot assign to read-only memoryview" - */ - - /* function exit code */ - __pyx_r = 0; - goto __pyx_L0; - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_1); - __Pyx_XDECREF(__pyx_t_2); - __Pyx_XDECREF(__pyx_t_3); - __Pyx_AddTraceback("View.MemoryView.memoryview.__setitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = -1; - __pyx_L0:; - __Pyx_XDECREF(__pyx_v_have_slices); - __Pyx_XDECREF(__pyx_v_obj); - __Pyx_XDECREF(__pyx_v_index); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "View.MemoryView":435 - * self.setitem_indexed(index, value) - * - * cdef is_slice(self, obj): # <<<<<<<<<<<<<< - * if not isinstance(obj, memoryview): - * try: - */ - -static PyObject *__pyx_memoryview_is_slice(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj) { - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - int __pyx_t_1; - int __pyx_t_2; - PyObject *__pyx_t_3 = NULL; - PyObject *__pyx_t_4 = NULL; - PyObject *__pyx_t_5 = NULL; - PyObject *__pyx_t_6 = NULL; - PyObject *__pyx_t_7 = NULL; - PyObject *__pyx_t_8 = NULL; - int __pyx_t_9; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("is_slice", 0); - __Pyx_INCREF(__pyx_v_obj); - - /* "View.MemoryView":436 - * - * cdef is_slice(self, obj): - * if not isinstance(obj, memoryview): # <<<<<<<<<<<<<< - * try: - * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, - */ - __pyx_t_1 = __Pyx_TypeCheck(__pyx_v_obj, __pyx_memoryview_type); - __pyx_t_2 = (!__pyx_t_1); - if (__pyx_t_2) { - - /* "View.MemoryView":437 - * cdef is_slice(self, obj): - * if not isinstance(obj, memoryview): - * try: # <<<<<<<<<<<<<< - * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, - * self.dtype_is_object) - */ - { - __Pyx_PyThreadState_declare - __Pyx_PyThreadState_assign - __Pyx_ExceptionSave(&__pyx_t_3, &__pyx_t_4, &__pyx_t_5); - __Pyx_XGOTREF(__pyx_t_3); - __Pyx_XGOTREF(__pyx_t_4); - __Pyx_XGOTREF(__pyx_t_5); - /*try:*/ { - - /* "View.MemoryView":438 - * if not isinstance(obj, memoryview): - * try: - * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, # <<<<<<<<<<<<<< - * self.dtype_is_object) - * except TypeError: - */ - __pyx_t_6 = __Pyx_PyInt_From_int(((__pyx_v_self->flags & (~PyBUF_WRITABLE)) | PyBUF_ANY_CONTIGUOUS)); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 438, __pyx_L4_error) - __Pyx_GOTREF(__pyx_t_6); - - /* "View.MemoryView":439 - * try: - * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, - * self.dtype_is_object) # <<<<<<<<<<<<<< - * except TypeError: - * return None - */ - __pyx_t_7 = __Pyx_PyBool_FromLong(__pyx_v_self->dtype_is_object); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 439, __pyx_L4_error) - __Pyx_GOTREF(__pyx_t_7); - - /* "View.MemoryView":438 - * if not isinstance(obj, memoryview): - * try: - * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, # <<<<<<<<<<<<<< - * self.dtype_is_object) - * except TypeError: - */ - __pyx_t_8 = PyTuple_New(3); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 438, __pyx_L4_error) - __Pyx_GOTREF(__pyx_t_8); - __Pyx_INCREF(__pyx_v_obj); - __Pyx_GIVEREF(__pyx_v_obj); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_8, 0, __pyx_v_obj)) __PYX_ERR(1, 438, __pyx_L4_error); - __Pyx_GIVEREF(__pyx_t_6); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_8, 1, __pyx_t_6)) __PYX_ERR(1, 438, __pyx_L4_error); - __Pyx_GIVEREF(__pyx_t_7); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_8, 2, __pyx_t_7)) __PYX_ERR(1, 438, __pyx_L4_error); - __pyx_t_6 = 0; - __pyx_t_7 = 0; - __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_memoryview_type), __pyx_t_8, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 438, __pyx_L4_error) - __Pyx_GOTREF(__pyx_t_7); - __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; - __Pyx_DECREF_SET(__pyx_v_obj, __pyx_t_7); - __pyx_t_7 = 0; - - /* "View.MemoryView":437 - * cdef is_slice(self, obj): - * if not isinstance(obj, memoryview): - * try: # <<<<<<<<<<<<<< - * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, - * self.dtype_is_object) - */ - } - __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; - __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; - __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; - goto __pyx_L9_try_end; - __pyx_L4_error:; - __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; - __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; - __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; - - /* "View.MemoryView":440 - * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, - * self.dtype_is_object) - * except TypeError: # <<<<<<<<<<<<<< - * return None - * - */ - __pyx_t_9 = __Pyx_PyErr_ExceptionMatches(__pyx_builtin_TypeError); - if (__pyx_t_9) { - __Pyx_AddTraceback("View.MemoryView.memoryview.is_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); - if (__Pyx_GetException(&__pyx_t_7, &__pyx_t_8, &__pyx_t_6) < 0) __PYX_ERR(1, 440, __pyx_L6_except_error) - __Pyx_XGOTREF(__pyx_t_7); - __Pyx_XGOTREF(__pyx_t_8); - __Pyx_XGOTREF(__pyx_t_6); - - /* "View.MemoryView":441 - * self.dtype_is_object) - * except TypeError: - * return None # <<<<<<<<<<<<<< - * - * return obj - */ - __Pyx_XDECREF(__pyx_r); - __pyx_r = Py_None; __Pyx_INCREF(Py_None); - __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; - goto __pyx_L7_except_return; - } - goto __pyx_L6_except_error; - - /* "View.MemoryView":437 - * cdef is_slice(self, obj): - * if not isinstance(obj, memoryview): - * try: # <<<<<<<<<<<<<< - * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, - * self.dtype_is_object) - */ - __pyx_L6_except_error:; - __Pyx_XGIVEREF(__pyx_t_3); - __Pyx_XGIVEREF(__pyx_t_4); - __Pyx_XGIVEREF(__pyx_t_5); - __Pyx_ExceptionReset(__pyx_t_3, __pyx_t_4, __pyx_t_5); - goto __pyx_L1_error; - __pyx_L7_except_return:; - __Pyx_XGIVEREF(__pyx_t_3); - __Pyx_XGIVEREF(__pyx_t_4); - __Pyx_XGIVEREF(__pyx_t_5); - __Pyx_ExceptionReset(__pyx_t_3, __pyx_t_4, __pyx_t_5); - goto __pyx_L0; - __pyx_L9_try_end:; - } - - /* "View.MemoryView":436 - * - * cdef is_slice(self, obj): - * if not isinstance(obj, memoryview): # <<<<<<<<<<<<<< - * try: - * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, - */ - } - - /* "View.MemoryView":443 - * return None - * - * return obj # <<<<<<<<<<<<<< - * - * cdef setitem_slice_assignment(self, dst, src): - */ - __Pyx_XDECREF(__pyx_r); - __Pyx_INCREF(__pyx_v_obj); - __pyx_r = __pyx_v_obj; - goto __pyx_L0; - - /* "View.MemoryView":435 - * self.setitem_indexed(index, value) - * - * cdef is_slice(self, obj): # <<<<<<<<<<<<<< - * if not isinstance(obj, memoryview): - * try: - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_6); - __Pyx_XDECREF(__pyx_t_7); - __Pyx_XDECREF(__pyx_t_8); - __Pyx_AddTraceback("View.MemoryView.memoryview.is_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = 0; - __pyx_L0:; - __Pyx_XDECREF(__pyx_v_obj); - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "View.MemoryView":445 - * return obj - * - * cdef setitem_slice_assignment(self, dst, src): # <<<<<<<<<<<<<< - * cdef __Pyx_memviewslice dst_slice - * cdef __Pyx_memviewslice src_slice - */ - -static PyObject *__pyx_memoryview_setitem_slice_assignment(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_dst, PyObject *__pyx_v_src) { - __Pyx_memviewslice __pyx_v_dst_slice; - __Pyx_memviewslice __pyx_v_src_slice; - __Pyx_memviewslice __pyx_v_msrc; - __Pyx_memviewslice __pyx_v_mdst; - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - __Pyx_memviewslice *__pyx_t_1; - PyObject *__pyx_t_2 = NULL; - int __pyx_t_3; - int __pyx_t_4; - int __pyx_t_5; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("setitem_slice_assignment", 1); - - /* "View.MemoryView":448 - * cdef __Pyx_memviewslice dst_slice - * cdef __Pyx_memviewslice src_slice - * cdef __Pyx_memviewslice msrc = get_slice_from_memview(src, &src_slice)[0] # <<<<<<<<<<<<<< - * cdef __Pyx_memviewslice mdst = get_slice_from_memview(dst, &dst_slice)[0] - * - */ - if (!(likely(((__pyx_v_src) == Py_None) || likely(__Pyx_TypeTest(__pyx_v_src, __pyx_memoryview_type))))) __PYX_ERR(1, 448, __pyx_L1_error) - __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(((struct __pyx_memoryview_obj *)__pyx_v_src), (&__pyx_v_src_slice)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(1, 448, __pyx_L1_error) - __pyx_v_msrc = (__pyx_t_1[0]); - - /* "View.MemoryView":449 - * cdef __Pyx_memviewslice src_slice - * cdef __Pyx_memviewslice msrc = get_slice_from_memview(src, &src_slice)[0] - * cdef __Pyx_memviewslice mdst = get_slice_from_memview(dst, &dst_slice)[0] # <<<<<<<<<<<<<< - * - * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) - */ - if (!(likely(((__pyx_v_dst) == Py_None) || likely(__Pyx_TypeTest(__pyx_v_dst, __pyx_memoryview_type))))) __PYX_ERR(1, 449, __pyx_L1_error) - __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(((struct __pyx_memoryview_obj *)__pyx_v_dst), (&__pyx_v_dst_slice)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(1, 449, __pyx_L1_error) - __pyx_v_mdst = (__pyx_t_1[0]); - - /* "View.MemoryView":451 - * cdef __Pyx_memviewslice mdst = get_slice_from_memview(dst, &dst_slice)[0] - * - * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) # <<<<<<<<<<<<<< - * - * cdef setitem_slice_assign_scalar(self, memoryview dst, value): - */ - __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_src, __pyx_n_s_ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 451, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __pyx_t_3 = __Pyx_PyInt_As_int(__pyx_t_2); if (unlikely((__pyx_t_3 == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 451, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_dst, __pyx_n_s_ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 451, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __pyx_t_4 = __Pyx_PyInt_As_int(__pyx_t_2); if (unlikely((__pyx_t_4 == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 451, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - __pyx_t_5 = __pyx_memoryview_copy_contents(__pyx_v_msrc, __pyx_v_mdst, __pyx_t_3, __pyx_t_4, __pyx_v_self->dtype_is_object); if (unlikely(__pyx_t_5 == ((int)-1))) __PYX_ERR(1, 451, __pyx_L1_error) - - /* "View.MemoryView":445 - * return obj - * - * cdef setitem_slice_assignment(self, dst, src): # <<<<<<<<<<<<<< - * cdef __Pyx_memviewslice dst_slice - * cdef __Pyx_memviewslice src_slice - */ - - /* function exit code */ - __pyx_r = Py_None; __Pyx_INCREF(Py_None); - goto __pyx_L0; - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_2); - __Pyx_AddTraceback("View.MemoryView.memoryview.setitem_slice_assignment", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = 0; - __pyx_L0:; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "View.MemoryView":453 - * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) - * - * cdef setitem_slice_assign_scalar(self, memoryview dst, value): # <<<<<<<<<<<<<< - * cdef int array[128] - * cdef void *tmp = NULL - */ - -static PyObject *__pyx_memoryview_setitem_slice_assign_scalar(struct __pyx_memoryview_obj *__pyx_v_self, struct __pyx_memoryview_obj *__pyx_v_dst, PyObject *__pyx_v_value) { - int __pyx_v_array[0x80]; - void *__pyx_v_tmp; - void *__pyx_v_item; - __Pyx_memviewslice *__pyx_v_dst_slice; - __Pyx_memviewslice __pyx_v_tmp_slice; - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - __Pyx_memviewslice *__pyx_t_1; - int __pyx_t_2; - PyObject *__pyx_t_3 = NULL; - int __pyx_t_4; - int __pyx_t_5; - char const *__pyx_t_6; - PyObject *__pyx_t_7 = NULL; - PyObject *__pyx_t_8 = NULL; - PyObject *__pyx_t_9 = NULL; - PyObject *__pyx_t_10 = NULL; - PyObject *__pyx_t_11 = NULL; - PyObject *__pyx_t_12 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("setitem_slice_assign_scalar", 1); - - /* "View.MemoryView":455 - * cdef setitem_slice_assign_scalar(self, memoryview dst, value): - * cdef int array[128] - * cdef void *tmp = NULL # <<<<<<<<<<<<<< - * cdef void *item - * - */ - __pyx_v_tmp = NULL; - - /* "View.MemoryView":460 - * cdef __Pyx_memviewslice *dst_slice - * cdef __Pyx_memviewslice tmp_slice - * dst_slice = get_slice_from_memview(dst, &tmp_slice) # <<<<<<<<<<<<<< - * - * if self.view.itemsize > sizeof(array): - */ - __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(__pyx_v_dst, (&__pyx_v_tmp_slice)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(1, 460, __pyx_L1_error) - __pyx_v_dst_slice = __pyx_t_1; - - /* "View.MemoryView":462 - * dst_slice = get_slice_from_memview(dst, &tmp_slice) - * - * if self.view.itemsize > sizeof(array): # <<<<<<<<<<<<<< - * tmp = PyMem_Malloc(self.view.itemsize) - * if tmp == NULL: - */ - __pyx_t_2 = (((size_t)__pyx_v_self->view.itemsize) > (sizeof(__pyx_v_array))); - if (__pyx_t_2) { - - /* "View.MemoryView":463 - * - * if self.view.itemsize > sizeof(array): - * tmp = PyMem_Malloc(self.view.itemsize) # <<<<<<<<<<<<<< - * if tmp == NULL: - * raise MemoryError - */ - __pyx_v_tmp = PyMem_Malloc(__pyx_v_self->view.itemsize); - - /* "View.MemoryView":464 - * if self.view.itemsize > sizeof(array): - * tmp = PyMem_Malloc(self.view.itemsize) - * if tmp == NULL: # <<<<<<<<<<<<<< - * raise MemoryError - * item = tmp - */ - __pyx_t_2 = (__pyx_v_tmp == NULL); - if (unlikely(__pyx_t_2)) { - - /* "View.MemoryView":465 - * tmp = PyMem_Malloc(self.view.itemsize) - * if tmp == NULL: - * raise MemoryError # <<<<<<<<<<<<<< - * item = tmp - * else: - */ - PyErr_NoMemory(); __PYX_ERR(1, 465, __pyx_L1_error) - - /* "View.MemoryView":464 - * if self.view.itemsize > sizeof(array): - * tmp = PyMem_Malloc(self.view.itemsize) - * if tmp == NULL: # <<<<<<<<<<<<<< - * raise MemoryError - * item = tmp - */ - } - - /* "View.MemoryView":466 - * if tmp == NULL: - * raise MemoryError - * item = tmp # <<<<<<<<<<<<<< - * else: - * item = array - */ - __pyx_v_item = __pyx_v_tmp; - - /* "View.MemoryView":462 - * dst_slice = get_slice_from_memview(dst, &tmp_slice) - * - * if self.view.itemsize > sizeof(array): # <<<<<<<<<<<<<< - * tmp = PyMem_Malloc(self.view.itemsize) - * if tmp == NULL: - */ - goto __pyx_L3; - } - - /* "View.MemoryView":468 - * item = tmp - * else: - * item = array # <<<<<<<<<<<<<< - * - * try: - */ - /*else*/ { - __pyx_v_item = ((void *)__pyx_v_array); - } - __pyx_L3:; - - /* "View.MemoryView":470 - * item = array - * - * try: # <<<<<<<<<<<<<< - * if self.dtype_is_object: - * ( item)[0] = value - */ - /*try:*/ { - - /* "View.MemoryView":471 - * - * try: - * if self.dtype_is_object: # <<<<<<<<<<<<<< - * ( item)[0] = value - * else: - */ - if (__pyx_v_self->dtype_is_object) { - - /* "View.MemoryView":472 - * try: - * if self.dtype_is_object: - * ( item)[0] = value # <<<<<<<<<<<<<< - * else: - * self.assign_item_from_object( item, value) - */ - (((PyObject **)__pyx_v_item)[0]) = ((PyObject *)__pyx_v_value); - - /* "View.MemoryView":471 - * - * try: - * if self.dtype_is_object: # <<<<<<<<<<<<<< - * ( item)[0] = value - * else: - */ - goto __pyx_L8; - } - - /* "View.MemoryView":474 - * ( item)[0] = value - * else: - * self.assign_item_from_object( item, value) # <<<<<<<<<<<<<< - * - * - */ - /*else*/ { - __pyx_t_3 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->assign_item_from_object(__pyx_v_self, ((char *)__pyx_v_item), __pyx_v_value); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 474, __pyx_L6_error) - __Pyx_GOTREF(__pyx_t_3); - __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - } - __pyx_L8:; - - /* "View.MemoryView":478 - * - * - * if self.view.suboffsets != NULL: # <<<<<<<<<<<<<< - * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) - * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, - */ - __pyx_t_2 = (__pyx_v_self->view.suboffsets != NULL); - if (__pyx_t_2) { - - /* "View.MemoryView":479 - * - * if self.view.suboffsets != NULL: - * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) # <<<<<<<<<<<<<< - * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, - * item, self.dtype_is_object) - */ - __pyx_t_4 = assert_direct_dimensions(__pyx_v_self->view.suboffsets, __pyx_v_self->view.ndim); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(1, 479, __pyx_L6_error) - - /* "View.MemoryView":478 - * - * - * if self.view.suboffsets != NULL: # <<<<<<<<<<<<<< - * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) - * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, - */ - } - - /* "View.MemoryView":480 - * if self.view.suboffsets != NULL: - * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) - * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, # <<<<<<<<<<<<<< - * item, self.dtype_is_object) - * finally: - */ - __pyx_memoryview_slice_assign_scalar(__pyx_v_dst_slice, __pyx_v_dst->view.ndim, __pyx_v_self->view.itemsize, __pyx_v_item, __pyx_v_self->dtype_is_object); - } - - /* "View.MemoryView":483 - * item, self.dtype_is_object) - * finally: - * PyMem_Free(tmp) # <<<<<<<<<<<<<< - * - * cdef setitem_indexed(self, index, value): - */ - /*finally:*/ { - /*normal exit:*/{ - PyMem_Free(__pyx_v_tmp); - goto __pyx_L7; - } - __pyx_L6_error:; - /*exception exit:*/{ - __Pyx_PyThreadState_declare - __Pyx_PyThreadState_assign - __pyx_t_7 = 0; __pyx_t_8 = 0; __pyx_t_9 = 0; __pyx_t_10 = 0; __pyx_t_11 = 0; __pyx_t_12 = 0; - __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; - if (PY_MAJOR_VERSION >= 3) __Pyx_ExceptionSwap(&__pyx_t_10, &__pyx_t_11, &__pyx_t_12); - if ((PY_MAJOR_VERSION < 3) || unlikely(__Pyx_GetException(&__pyx_t_7, &__pyx_t_8, &__pyx_t_9) < 0)) __Pyx_ErrFetch(&__pyx_t_7, &__pyx_t_8, &__pyx_t_9); - __Pyx_XGOTREF(__pyx_t_7); - __Pyx_XGOTREF(__pyx_t_8); - __Pyx_XGOTREF(__pyx_t_9); - __Pyx_XGOTREF(__pyx_t_10); - __Pyx_XGOTREF(__pyx_t_11); - __Pyx_XGOTREF(__pyx_t_12); - __pyx_t_4 = __pyx_lineno; __pyx_t_5 = __pyx_clineno; __pyx_t_6 = __pyx_filename; - { - PyMem_Free(__pyx_v_tmp); - } - if (PY_MAJOR_VERSION >= 3) { - __Pyx_XGIVEREF(__pyx_t_10); - __Pyx_XGIVEREF(__pyx_t_11); - __Pyx_XGIVEREF(__pyx_t_12); - __Pyx_ExceptionReset(__pyx_t_10, __pyx_t_11, __pyx_t_12); - } - __Pyx_XGIVEREF(__pyx_t_7); - __Pyx_XGIVEREF(__pyx_t_8); - __Pyx_XGIVEREF(__pyx_t_9); - __Pyx_ErrRestore(__pyx_t_7, __pyx_t_8, __pyx_t_9); - __pyx_t_7 = 0; __pyx_t_8 = 0; __pyx_t_9 = 0; __pyx_t_10 = 0; __pyx_t_11 = 0; __pyx_t_12 = 0; - __pyx_lineno = __pyx_t_4; __pyx_clineno = __pyx_t_5; __pyx_filename = __pyx_t_6; - goto __pyx_L1_error; - } - __pyx_L7:; - } - - /* "View.MemoryView":453 - * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) - * - * cdef setitem_slice_assign_scalar(self, memoryview dst, value): # <<<<<<<<<<<<<< - * cdef int array[128] - * cdef void *tmp = NULL - */ - - /* function exit code */ - __pyx_r = Py_None; __Pyx_INCREF(Py_None); - goto __pyx_L0; - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_3); - __Pyx_AddTraceback("View.MemoryView.memoryview.setitem_slice_assign_scalar", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = 0; - __pyx_L0:; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "View.MemoryView":485 - * PyMem_Free(tmp) - * - * cdef setitem_indexed(self, index, value): # <<<<<<<<<<<<<< - * cdef char *itemp = self.get_item_pointer(index) - * self.assign_item_from_object(itemp, value) - */ - -static PyObject *__pyx_memoryview_setitem_indexed(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value) { - char *__pyx_v_itemp; - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - char *__pyx_t_1; - PyObject *__pyx_t_2 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("setitem_indexed", 1); - - /* "View.MemoryView":486 - * - * cdef setitem_indexed(self, index, value): - * cdef char *itemp = self.get_item_pointer(index) # <<<<<<<<<<<<<< - * self.assign_item_from_object(itemp, value) - * - */ - __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->get_item_pointer(__pyx_v_self, __pyx_v_index); if (unlikely(__pyx_t_1 == ((char *)NULL))) __PYX_ERR(1, 486, __pyx_L1_error) - __pyx_v_itemp = __pyx_t_1; - - /* "View.MemoryView":487 - * cdef setitem_indexed(self, index, value): - * cdef char *itemp = self.get_item_pointer(index) - * self.assign_item_from_object(itemp, value) # <<<<<<<<<<<<<< - * - * cdef convert_item_to_object(self, char *itemp): - */ - __pyx_t_2 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->assign_item_from_object(__pyx_v_self, __pyx_v_itemp, __pyx_v_value); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 487, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - - /* "View.MemoryView":485 - * PyMem_Free(tmp) - * - * cdef setitem_indexed(self, index, value): # <<<<<<<<<<<<<< - * cdef char *itemp = self.get_item_pointer(index) - * self.assign_item_from_object(itemp, value) - */ - - /* function exit code */ - __pyx_r = Py_None; __Pyx_INCREF(Py_None); - goto __pyx_L0; - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_2); - __Pyx_AddTraceback("View.MemoryView.memoryview.setitem_indexed", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = 0; - __pyx_L0:; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "View.MemoryView":489 - * self.assign_item_from_object(itemp, value) - * - * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< - * """Only used if instantiated manually by the user, or if Cython doesn't - * know how to convert the type""" - */ - -static PyObject *__pyx_memoryview_convert_item_to_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp) { - PyObject *__pyx_v_struct = NULL; - PyObject *__pyx_v_bytesitem = 0; - PyObject *__pyx_v_result = NULL; - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - PyObject *__pyx_t_1 = NULL; - PyObject *__pyx_t_2 = NULL; - PyObject *__pyx_t_3 = NULL; - PyObject *__pyx_t_4 = NULL; - PyObject *__pyx_t_5 = NULL; - PyObject *__pyx_t_6 = NULL; - PyObject *__pyx_t_7 = NULL; - int __pyx_t_8; - Py_ssize_t __pyx_t_9; - int __pyx_t_10; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("convert_item_to_object", 1); - - /* "View.MemoryView":492 - * """Only used if instantiated manually by the user, or if Cython doesn't - * know how to convert the type""" - * import struct # <<<<<<<<<<<<<< - * cdef bytes bytesitem - * - */ - __pyx_t_1 = __Pyx_ImportDottedModule(__pyx_n_s_struct, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 492, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_v_struct = __pyx_t_1; - __pyx_t_1 = 0; - - /* "View.MemoryView":495 - * cdef bytes bytesitem - * - * bytesitem = itemp[:self.view.itemsize] # <<<<<<<<<<<<<< - * try: - * result = struct.unpack(self.view.format, bytesitem) - */ - __pyx_t_1 = __Pyx_PyBytes_FromStringAndSize(__pyx_v_itemp + 0, __pyx_v_self->view.itemsize - 0); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 495, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_v_bytesitem = ((PyObject*)__pyx_t_1); - __pyx_t_1 = 0; - - /* "View.MemoryView":496 - * - * bytesitem = itemp[:self.view.itemsize] - * try: # <<<<<<<<<<<<<< - * result = struct.unpack(self.view.format, bytesitem) - * except struct.error: - */ - { - __Pyx_PyThreadState_declare - __Pyx_PyThreadState_assign - __Pyx_ExceptionSave(&__pyx_t_2, &__pyx_t_3, &__pyx_t_4); - __Pyx_XGOTREF(__pyx_t_2); - __Pyx_XGOTREF(__pyx_t_3); - __Pyx_XGOTREF(__pyx_t_4); - /*try:*/ { - - /* "View.MemoryView":497 - * bytesitem = itemp[:self.view.itemsize] - * try: - * result = struct.unpack(self.view.format, bytesitem) # <<<<<<<<<<<<<< - * except struct.error: - * raise ValueError, "Unable to convert item to object" - */ - __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_unpack); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 497, __pyx_L3_error) - __Pyx_GOTREF(__pyx_t_5); - __pyx_t_6 = __Pyx_PyBytes_FromString(__pyx_v_self->view.format); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 497, __pyx_L3_error) - __Pyx_GOTREF(__pyx_t_6); - __pyx_t_7 = NULL; - __pyx_t_8 = 0; - #if CYTHON_UNPACK_METHODS - if (likely(PyMethod_Check(__pyx_t_5))) { - __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_5); - if (likely(__pyx_t_7)) { - PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); - __Pyx_INCREF(__pyx_t_7); - __Pyx_INCREF(function); - __Pyx_DECREF_SET(__pyx_t_5, function); - __pyx_t_8 = 1; - } - } - #endif - { - PyObject *__pyx_callargs[3] = {__pyx_t_7, __pyx_t_6, __pyx_v_bytesitem}; - __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_8, 2+__pyx_t_8); - __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; - __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; - if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 497, __pyx_L3_error) - __Pyx_GOTREF(__pyx_t_1); - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - } - __pyx_v_result = __pyx_t_1; - __pyx_t_1 = 0; - - /* "View.MemoryView":496 - * - * bytesitem = itemp[:self.view.itemsize] - * try: # <<<<<<<<<<<<<< - * result = struct.unpack(self.view.format, bytesitem) - * except struct.error: - */ - } - - /* "View.MemoryView":501 - * raise ValueError, "Unable to convert item to object" - * else: - * if len(self.view.format) == 1: # <<<<<<<<<<<<<< - * return result[0] - * return result - */ - /*else:*/ { - __pyx_t_9 = __Pyx_ssize_strlen(__pyx_v_self->view.format); if (unlikely(__pyx_t_9 == ((Py_ssize_t)-1))) __PYX_ERR(1, 501, __pyx_L5_except_error) - __pyx_t_10 = (__pyx_t_9 == 1); - if (__pyx_t_10) { - - /* "View.MemoryView":502 - * else: - * if len(self.view.format) == 1: - * return result[0] # <<<<<<<<<<<<<< - * return result - * - */ - __Pyx_XDECREF(__pyx_r); - __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_result, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 502, __pyx_L5_except_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_r = __pyx_t_1; - __pyx_t_1 = 0; - goto __pyx_L6_except_return; - - /* "View.MemoryView":501 - * raise ValueError, "Unable to convert item to object" - * else: - * if len(self.view.format) == 1: # <<<<<<<<<<<<<< - * return result[0] - * return result - */ - } - - /* "View.MemoryView":503 - * if len(self.view.format) == 1: - * return result[0] - * return result # <<<<<<<<<<<<<< - * - * cdef assign_item_from_object(self, char *itemp, object value): - */ - __Pyx_XDECREF(__pyx_r); - __Pyx_INCREF(__pyx_v_result); - __pyx_r = __pyx_v_result; - goto __pyx_L6_except_return; - } - __pyx_L3_error:; - __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; - __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; - __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; - __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; - - /* "View.MemoryView":498 - * try: - * result = struct.unpack(self.view.format, bytesitem) - * except struct.error: # <<<<<<<<<<<<<< - * raise ValueError, "Unable to convert item to object" - * else: - */ - __Pyx_ErrFetch(&__pyx_t_1, &__pyx_t_5, &__pyx_t_6); - __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_error); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 498, __pyx_L5_except_error) - __Pyx_GOTREF(__pyx_t_7); - __pyx_t_8 = __Pyx_PyErr_GivenExceptionMatches(__pyx_t_1, __pyx_t_7); - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - __Pyx_ErrRestore(__pyx_t_1, __pyx_t_5, __pyx_t_6); - __pyx_t_1 = 0; __pyx_t_5 = 0; __pyx_t_6 = 0; - if (__pyx_t_8) { - __Pyx_AddTraceback("View.MemoryView.memoryview.convert_item_to_object", __pyx_clineno, __pyx_lineno, __pyx_filename); - if (__Pyx_GetException(&__pyx_t_6, &__pyx_t_5, &__pyx_t_1) < 0) __PYX_ERR(1, 498, __pyx_L5_except_error) - __Pyx_XGOTREF(__pyx_t_6); - __Pyx_XGOTREF(__pyx_t_5); - __Pyx_XGOTREF(__pyx_t_1); - - /* "View.MemoryView":499 - * result = struct.unpack(self.view.format, bytesitem) - * except struct.error: - * raise ValueError, "Unable to convert item to object" # <<<<<<<<<<<<<< - * else: - * if len(self.view.format) == 1: - */ - __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Unable_to_convert_item_to_object, 0, 0); - __PYX_ERR(1, 499, __pyx_L5_except_error) - } - goto __pyx_L5_except_error; - - /* "View.MemoryView":496 - * - * bytesitem = itemp[:self.view.itemsize] - * try: # <<<<<<<<<<<<<< - * result = struct.unpack(self.view.format, bytesitem) - * except struct.error: - */ - __pyx_L5_except_error:; - __Pyx_XGIVEREF(__pyx_t_2); - __Pyx_XGIVEREF(__pyx_t_3); - __Pyx_XGIVEREF(__pyx_t_4); - __Pyx_ExceptionReset(__pyx_t_2, __pyx_t_3, __pyx_t_4); - goto __pyx_L1_error; - __pyx_L6_except_return:; - __Pyx_XGIVEREF(__pyx_t_2); - __Pyx_XGIVEREF(__pyx_t_3); - __Pyx_XGIVEREF(__pyx_t_4); - __Pyx_ExceptionReset(__pyx_t_2, __pyx_t_3, __pyx_t_4); - goto __pyx_L0; - } - - /* "View.MemoryView":489 - * self.assign_item_from_object(itemp, value) - * - * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< - * """Only used if instantiated manually by the user, or if Cython doesn't - * know how to convert the type""" - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_1); - __Pyx_XDECREF(__pyx_t_5); - __Pyx_XDECREF(__pyx_t_6); - __Pyx_XDECREF(__pyx_t_7); - __Pyx_AddTraceback("View.MemoryView.memoryview.convert_item_to_object", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = 0; - __pyx_L0:; - __Pyx_XDECREF(__pyx_v_struct); - __Pyx_XDECREF(__pyx_v_bytesitem); - __Pyx_XDECREF(__pyx_v_result); - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "View.MemoryView":505 - * return result - * - * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< - * """Only used if instantiated manually by the user, or if Cython doesn't - * know how to convert the type""" - */ - -static PyObject *__pyx_memoryview_assign_item_from_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value) { - PyObject *__pyx_v_struct = NULL; - char __pyx_v_c; - PyObject *__pyx_v_bytesvalue = 0; - Py_ssize_t __pyx_v_i; - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - PyObject *__pyx_t_1 = NULL; - int __pyx_t_2; - PyObject *__pyx_t_3 = NULL; - PyObject *__pyx_t_4 = NULL; - PyObject *__pyx_t_5 = NULL; - int __pyx_t_6; - Py_ssize_t __pyx_t_7; - PyObject *__pyx_t_8 = NULL; - char *__pyx_t_9; - char *__pyx_t_10; - char *__pyx_t_11; - char *__pyx_t_12; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("assign_item_from_object", 1); - - /* "View.MemoryView":508 - * """Only used if instantiated manually by the user, or if Cython doesn't - * know how to convert the type""" - * import struct # <<<<<<<<<<<<<< - * cdef char c - * cdef bytes bytesvalue - */ - __pyx_t_1 = __Pyx_ImportDottedModule(__pyx_n_s_struct, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 508, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_v_struct = __pyx_t_1; - __pyx_t_1 = 0; - - /* "View.MemoryView":513 - * cdef Py_ssize_t i - * - * if isinstance(value, tuple): # <<<<<<<<<<<<<< - * bytesvalue = struct.pack(self.view.format, *value) - * else: - */ - __pyx_t_2 = PyTuple_Check(__pyx_v_value); - if (__pyx_t_2) { - - /* "View.MemoryView":514 - * - * if isinstance(value, tuple): - * bytesvalue = struct.pack(self.view.format, *value) # <<<<<<<<<<<<<< - * else: - * bytesvalue = struct.pack(self.view.format, value) - */ - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_pack); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 514, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_3 = __Pyx_PyBytes_FromString(__pyx_v_self->view.format); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 514, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __pyx_t_4 = PyTuple_New(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 514, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __Pyx_GIVEREF(__pyx_t_3); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_3)) __PYX_ERR(1, 514, __pyx_L1_error); - __pyx_t_3 = 0; - __pyx_t_3 = __Pyx_PySequence_Tuple(__pyx_v_value); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 514, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __pyx_t_5 = PyNumber_Add(__pyx_t_4, __pyx_t_3); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 514, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - __pyx_t_3 = __Pyx_PyObject_Call(__pyx_t_1, __pyx_t_5, NULL); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 514, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - if (!(likely(PyBytes_CheckExact(__pyx_t_3))||((__pyx_t_3) == Py_None) || __Pyx_RaiseUnexpectedTypeError("bytes", __pyx_t_3))) __PYX_ERR(1, 514, __pyx_L1_error) - __pyx_v_bytesvalue = ((PyObject*)__pyx_t_3); - __pyx_t_3 = 0; - - /* "View.MemoryView":513 - * cdef Py_ssize_t i - * - * if isinstance(value, tuple): # <<<<<<<<<<<<<< - * bytesvalue = struct.pack(self.view.format, *value) - * else: - */ - goto __pyx_L3; - } - - /* "View.MemoryView":516 - * bytesvalue = struct.pack(self.view.format, *value) - * else: - * bytesvalue = struct.pack(self.view.format, value) # <<<<<<<<<<<<<< - * - * for i, c in enumerate(bytesvalue): - */ - /*else*/ { - __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_pack); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 516, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __pyx_t_1 = __Pyx_PyBytes_FromString(__pyx_v_self->view.format); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 516, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_4 = NULL; - __pyx_t_6 = 0; - #if CYTHON_UNPACK_METHODS - if (likely(PyMethod_Check(__pyx_t_5))) { - __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_5); - if (likely(__pyx_t_4)) { - PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); - __Pyx_INCREF(__pyx_t_4); - __Pyx_INCREF(function); - __Pyx_DECREF_SET(__pyx_t_5, function); - __pyx_t_6 = 1; - } - } - #endif - { - PyObject *__pyx_callargs[3] = {__pyx_t_4, __pyx_t_1, __pyx_v_value}; - __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); - __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 516, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - } - if (!(likely(PyBytes_CheckExact(__pyx_t_3))||((__pyx_t_3) == Py_None) || __Pyx_RaiseUnexpectedTypeError("bytes", __pyx_t_3))) __PYX_ERR(1, 516, __pyx_L1_error) - __pyx_v_bytesvalue = ((PyObject*)__pyx_t_3); - __pyx_t_3 = 0; - } - __pyx_L3:; - - /* "View.MemoryView":518 - * bytesvalue = struct.pack(self.view.format, value) - * - * for i, c in enumerate(bytesvalue): # <<<<<<<<<<<<<< - * itemp[i] = c - * - */ - __pyx_t_7 = 0; - if (unlikely(__pyx_v_bytesvalue == Py_None)) { - PyErr_SetString(PyExc_TypeError, "'NoneType' is not iterable"); - __PYX_ERR(1, 518, __pyx_L1_error) - } - __Pyx_INCREF(__pyx_v_bytesvalue); - __pyx_t_8 = __pyx_v_bytesvalue; - __pyx_t_10 = PyBytes_AS_STRING(__pyx_t_8); - __pyx_t_11 = (__pyx_t_10 + PyBytes_GET_SIZE(__pyx_t_8)); - for (__pyx_t_12 = __pyx_t_10; __pyx_t_12 < __pyx_t_11; __pyx_t_12++) { - __pyx_t_9 = __pyx_t_12; - __pyx_v_c = (__pyx_t_9[0]); - - /* "View.MemoryView":519 - * - * for i, c in enumerate(bytesvalue): - * itemp[i] = c # <<<<<<<<<<<<<< - * - * @cname('getbuffer') - */ - __pyx_v_i = __pyx_t_7; - - /* "View.MemoryView":518 - * bytesvalue = struct.pack(self.view.format, value) - * - * for i, c in enumerate(bytesvalue): # <<<<<<<<<<<<<< - * itemp[i] = c - * - */ - __pyx_t_7 = (__pyx_t_7 + 1); - - /* "View.MemoryView":519 - * - * for i, c in enumerate(bytesvalue): - * itemp[i] = c # <<<<<<<<<<<<<< - * - * @cname('getbuffer') - */ - (__pyx_v_itemp[__pyx_v_i]) = __pyx_v_c; - } - __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; - - /* "View.MemoryView":505 - * return result - * - * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< - * """Only used if instantiated manually by the user, or if Cython doesn't - * know how to convert the type""" - */ - - /* function exit code */ - __pyx_r = Py_None; __Pyx_INCREF(Py_None); - goto __pyx_L0; - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_1); - __Pyx_XDECREF(__pyx_t_3); - __Pyx_XDECREF(__pyx_t_4); - __Pyx_XDECREF(__pyx_t_5); - __Pyx_XDECREF(__pyx_t_8); - __Pyx_AddTraceback("View.MemoryView.memoryview.assign_item_from_object", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = 0; - __pyx_L0:; - __Pyx_XDECREF(__pyx_v_struct); - __Pyx_XDECREF(__pyx_v_bytesvalue); - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "View.MemoryView":521 - * itemp[i] = c - * - * @cname('getbuffer') # <<<<<<<<<<<<<< - * def __getbuffer__(self, Py_buffer *info, int flags): - * if flags & PyBUF_WRITABLE and self.view.readonly: - */ - -/* Python wrapper */ -CYTHON_UNUSED static int __pyx_memoryview_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ -CYTHON_UNUSED static int __pyx_memoryview_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - int __pyx_r; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("__getbuffer__ (wrapper)", 0); - __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); - __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_8__getbuffer__(((struct __pyx_memoryview_obj *)__pyx_v_self), ((Py_buffer *)__pyx_v_info), ((int)__pyx_v_flags)); - - /* function exit code */ - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_8__getbuffer__(struct __pyx_memoryview_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { - int __pyx_r; - __Pyx_RefNannyDeclarations - int __pyx_t_1; - int __pyx_t_2; - Py_ssize_t *__pyx_t_3; - char *__pyx_t_4; - void *__pyx_t_5; - int __pyx_t_6; - Py_ssize_t __pyx_t_7; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - if (unlikely(__pyx_v_info == NULL)) { - PyErr_SetString(PyExc_BufferError, "PyObject_GetBuffer: view==NULL argument is obsolete"); - return -1; - } - __Pyx_RefNannySetupContext("__getbuffer__", 0); - __pyx_v_info->obj = Py_None; __Pyx_INCREF(Py_None); - __Pyx_GIVEREF(__pyx_v_info->obj); - - /* "View.MemoryView":523 - * @cname('getbuffer') - * def __getbuffer__(self, Py_buffer *info, int flags): - * if flags & PyBUF_WRITABLE and self.view.readonly: # <<<<<<<<<<<<<< - * raise ValueError, "Cannot create writable memory view from read-only memoryview" - * - */ - __pyx_t_2 = ((__pyx_v_flags & PyBUF_WRITABLE) != 0); - if (__pyx_t_2) { - } else { - __pyx_t_1 = __pyx_t_2; - goto __pyx_L4_bool_binop_done; - } - __pyx_t_1 = __pyx_v_self->view.readonly; - __pyx_L4_bool_binop_done:; - if (unlikely(__pyx_t_1)) { - - /* "View.MemoryView":524 - * def __getbuffer__(self, Py_buffer *info, int flags): - * if flags & PyBUF_WRITABLE and self.view.readonly: - * raise ValueError, "Cannot create writable memory view from read-only memoryview" # <<<<<<<<<<<<<< - * - * if flags & PyBUF_ND: - */ - __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Cannot_create_writable_memory_vi, 0, 0); - __PYX_ERR(1, 524, __pyx_L1_error) - - /* "View.MemoryView":523 - * @cname('getbuffer') - * def __getbuffer__(self, Py_buffer *info, int flags): - * if flags & PyBUF_WRITABLE and self.view.readonly: # <<<<<<<<<<<<<< - * raise ValueError, "Cannot create writable memory view from read-only memoryview" - * - */ - } - - /* "View.MemoryView":526 - * raise ValueError, "Cannot create writable memory view from read-only memoryview" - * - * if flags & PyBUF_ND: # <<<<<<<<<<<<<< - * info.shape = self.view.shape - * else: - */ - __pyx_t_1 = ((__pyx_v_flags & PyBUF_ND) != 0); - if (__pyx_t_1) { - - /* "View.MemoryView":527 - * - * if flags & PyBUF_ND: - * info.shape = self.view.shape # <<<<<<<<<<<<<< - * else: - * info.shape = NULL - */ - __pyx_t_3 = __pyx_v_self->view.shape; - __pyx_v_info->shape = __pyx_t_3; - - /* "View.MemoryView":526 - * raise ValueError, "Cannot create writable memory view from read-only memoryview" - * - * if flags & PyBUF_ND: # <<<<<<<<<<<<<< - * info.shape = self.view.shape - * else: - */ - goto __pyx_L6; - } - - /* "View.MemoryView":529 - * info.shape = self.view.shape - * else: - * info.shape = NULL # <<<<<<<<<<<<<< - * - * if flags & PyBUF_STRIDES: - */ - /*else*/ { - __pyx_v_info->shape = NULL; - } - __pyx_L6:; - - /* "View.MemoryView":531 - * info.shape = NULL - * - * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< - * info.strides = self.view.strides - * else: - */ - __pyx_t_1 = ((__pyx_v_flags & PyBUF_STRIDES) != 0); - if (__pyx_t_1) { - - /* "View.MemoryView":532 - * - * if flags & PyBUF_STRIDES: - * info.strides = self.view.strides # <<<<<<<<<<<<<< - * else: - * info.strides = NULL - */ - __pyx_t_3 = __pyx_v_self->view.strides; - __pyx_v_info->strides = __pyx_t_3; - - /* "View.MemoryView":531 - * info.shape = NULL - * - * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< - * info.strides = self.view.strides - * else: - */ - goto __pyx_L7; - } - - /* "View.MemoryView":534 - * info.strides = self.view.strides - * else: - * info.strides = NULL # <<<<<<<<<<<<<< - * - * if flags & PyBUF_INDIRECT: - */ - /*else*/ { - __pyx_v_info->strides = NULL; - } - __pyx_L7:; - - /* "View.MemoryView":536 - * info.strides = NULL - * - * if flags & PyBUF_INDIRECT: # <<<<<<<<<<<<<< - * info.suboffsets = self.view.suboffsets - * else: - */ - __pyx_t_1 = ((__pyx_v_flags & PyBUF_INDIRECT) != 0); - if (__pyx_t_1) { - - /* "View.MemoryView":537 - * - * if flags & PyBUF_INDIRECT: - * info.suboffsets = self.view.suboffsets # <<<<<<<<<<<<<< - * else: - * info.suboffsets = NULL - */ - __pyx_t_3 = __pyx_v_self->view.suboffsets; - __pyx_v_info->suboffsets = __pyx_t_3; - - /* "View.MemoryView":536 - * info.strides = NULL - * - * if flags & PyBUF_INDIRECT: # <<<<<<<<<<<<<< - * info.suboffsets = self.view.suboffsets - * else: - */ - goto __pyx_L8; - } - - /* "View.MemoryView":539 - * info.suboffsets = self.view.suboffsets - * else: - * info.suboffsets = NULL # <<<<<<<<<<<<<< - * - * if flags & PyBUF_FORMAT: - */ - /*else*/ { - __pyx_v_info->suboffsets = NULL; - } - __pyx_L8:; - - /* "View.MemoryView":541 - * info.suboffsets = NULL - * - * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< - * info.format = self.view.format - * else: - */ - __pyx_t_1 = ((__pyx_v_flags & PyBUF_FORMAT) != 0); - if (__pyx_t_1) { - - /* "View.MemoryView":542 - * - * if flags & PyBUF_FORMAT: - * info.format = self.view.format # <<<<<<<<<<<<<< - * else: - * info.format = NULL - */ - __pyx_t_4 = __pyx_v_self->view.format; - __pyx_v_info->format = __pyx_t_4; - - /* "View.MemoryView":541 - * info.suboffsets = NULL - * - * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< - * info.format = self.view.format - * else: - */ - goto __pyx_L9; - } - - /* "View.MemoryView":544 - * info.format = self.view.format - * else: - * info.format = NULL # <<<<<<<<<<<<<< - * - * info.buf = self.view.buf - */ - /*else*/ { - __pyx_v_info->format = NULL; - } - __pyx_L9:; - - /* "View.MemoryView":546 - * info.format = NULL - * - * info.buf = self.view.buf # <<<<<<<<<<<<<< - * info.ndim = self.view.ndim - * info.itemsize = self.view.itemsize - */ - __pyx_t_5 = __pyx_v_self->view.buf; - __pyx_v_info->buf = __pyx_t_5; - - /* "View.MemoryView":547 - * - * info.buf = self.view.buf - * info.ndim = self.view.ndim # <<<<<<<<<<<<<< - * info.itemsize = self.view.itemsize - * info.len = self.view.len - */ - __pyx_t_6 = __pyx_v_self->view.ndim; - __pyx_v_info->ndim = __pyx_t_6; - - /* "View.MemoryView":548 - * info.buf = self.view.buf - * info.ndim = self.view.ndim - * info.itemsize = self.view.itemsize # <<<<<<<<<<<<<< - * info.len = self.view.len - * info.readonly = self.view.readonly - */ - __pyx_t_7 = __pyx_v_self->view.itemsize; - __pyx_v_info->itemsize = __pyx_t_7; - - /* "View.MemoryView":549 - * info.ndim = self.view.ndim - * info.itemsize = self.view.itemsize - * info.len = self.view.len # <<<<<<<<<<<<<< - * info.readonly = self.view.readonly - * info.obj = self - */ - __pyx_t_7 = __pyx_v_self->view.len; - __pyx_v_info->len = __pyx_t_7; - - /* "View.MemoryView":550 - * info.itemsize = self.view.itemsize - * info.len = self.view.len - * info.readonly = self.view.readonly # <<<<<<<<<<<<<< - * info.obj = self - * - */ - __pyx_t_1 = __pyx_v_self->view.readonly; - __pyx_v_info->readonly = __pyx_t_1; - - /* "View.MemoryView":551 - * info.len = self.view.len - * info.readonly = self.view.readonly - * info.obj = self # <<<<<<<<<<<<<< - * - * - */ - __Pyx_INCREF((PyObject *)__pyx_v_self); - __Pyx_GIVEREF((PyObject *)__pyx_v_self); - __Pyx_GOTREF(__pyx_v_info->obj); - __Pyx_DECREF(__pyx_v_info->obj); - __pyx_v_info->obj = ((PyObject *)__pyx_v_self); - - /* "View.MemoryView":521 - * itemp[i] = c - * - * @cname('getbuffer') # <<<<<<<<<<<<<< - * def __getbuffer__(self, Py_buffer *info, int flags): - * if flags & PyBUF_WRITABLE and self.view.readonly: - */ - - /* function exit code */ - __pyx_r = 0; - goto __pyx_L0; - __pyx_L1_error:; - __Pyx_AddTraceback("View.MemoryView.memoryview.__getbuffer__", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = -1; - if (__pyx_v_info->obj != NULL) { - __Pyx_GOTREF(__pyx_v_info->obj); - __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; - } - goto __pyx_L2; - __pyx_L0:; - if (__pyx_v_info->obj == Py_None) { - __Pyx_GOTREF(__pyx_v_info->obj); - __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; - } - __pyx_L2:; - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "View.MemoryView":554 - * - * - * @property # <<<<<<<<<<<<<< - * def T(self): - * cdef _memoryviewslice result = memoryview_copy(self) - */ - -/* Python wrapper */ -static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_1T_1__get__(PyObject *__pyx_v_self); /*proto*/ -static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_1T_1__get__(PyObject *__pyx_v_self) { - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - PyObject *__pyx_r = 0; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); - __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); - __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_1T___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); - - /* function exit code */ - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_1T___get__(struct __pyx_memoryview_obj *__pyx_v_self) { - struct __pyx_memoryviewslice_obj *__pyx_v_result = 0; - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - PyObject *__pyx_t_1 = NULL; - int __pyx_t_2; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("__get__", 1); - - /* "View.MemoryView":556 - * @property - * def T(self): - * cdef _memoryviewslice result = memoryview_copy(self) # <<<<<<<<<<<<<< - * transpose_memslice(&result.from_slice) - * return result - */ - __pyx_t_1 = __pyx_memoryview_copy_object(__pyx_v_self); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 556, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - if (!(likely(((__pyx_t_1) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_1, __pyx_memoryviewslice_type))))) __PYX_ERR(1, 556, __pyx_L1_error) - __pyx_v_result = ((struct __pyx_memoryviewslice_obj *)__pyx_t_1); - __pyx_t_1 = 0; - - /* "View.MemoryView":557 - * def T(self): - * cdef _memoryviewslice result = memoryview_copy(self) - * transpose_memslice(&result.from_slice) # <<<<<<<<<<<<<< - * return result - * - */ - __pyx_t_2 = __pyx_memslice_transpose((&__pyx_v_result->from_slice)); if (unlikely(__pyx_t_2 == ((int)-1))) __PYX_ERR(1, 557, __pyx_L1_error) - - /* "View.MemoryView":558 - * cdef _memoryviewslice result = memoryview_copy(self) - * transpose_memslice(&result.from_slice) - * return result # <<<<<<<<<<<<<< - * - * @property - */ - __Pyx_XDECREF(__pyx_r); - __Pyx_INCREF((PyObject *)__pyx_v_result); - __pyx_r = ((PyObject *)__pyx_v_result); - goto __pyx_L0; - - /* "View.MemoryView":554 - * - * - * @property # <<<<<<<<<<<<<< - * def T(self): - * cdef _memoryviewslice result = memoryview_copy(self) - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_1); - __Pyx_AddTraceback("View.MemoryView.memoryview.T.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = NULL; - __pyx_L0:; - __Pyx_XDECREF((PyObject *)__pyx_v_result); - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "View.MemoryView":560 - * return result - * - * @property # <<<<<<<<<<<<<< - * def base(self): - * return self._get_base() - */ - -/* Python wrapper */ -static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4base_1__get__(PyObject *__pyx_v_self); /*proto*/ -static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4base_1__get__(PyObject *__pyx_v_self) { - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - PyObject *__pyx_r = 0; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); - __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); - __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_4base___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); - - /* function exit code */ - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4base___get__(struct __pyx_memoryview_obj *__pyx_v_self) { - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - PyObject *__pyx_t_1 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("__get__", 1); - - /* "View.MemoryView":562 - * @property - * def base(self): - * return self._get_base() # <<<<<<<<<<<<<< - * - * cdef _get_base(self): - */ - __Pyx_XDECREF(__pyx_r); - __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->_get_base(__pyx_v_self); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 562, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_r = __pyx_t_1; - __pyx_t_1 = 0; - goto __pyx_L0; - - /* "View.MemoryView":560 - * return result - * - * @property # <<<<<<<<<<<<<< - * def base(self): - * return self._get_base() - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_1); - __Pyx_AddTraceback("View.MemoryView.memoryview.base.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = NULL; - __pyx_L0:; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "View.MemoryView":564 - * return self._get_base() - * - * cdef _get_base(self): # <<<<<<<<<<<<<< - * return self.obj - * - */ - -static PyObject *__pyx_memoryview__get_base(struct __pyx_memoryview_obj *__pyx_v_self) { - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("_get_base", 1); - - /* "View.MemoryView":565 - * - * cdef _get_base(self): - * return self.obj # <<<<<<<<<<<<<< - * - * @property - */ - __Pyx_XDECREF(__pyx_r); - __Pyx_INCREF(__pyx_v_self->obj); - __pyx_r = __pyx_v_self->obj; - goto __pyx_L0; - - /* "View.MemoryView":564 - * return self._get_base() - * - * cdef _get_base(self): # <<<<<<<<<<<<<< - * return self.obj - * - */ - - /* function exit code */ - __pyx_L0:; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "View.MemoryView":567 - * return self.obj - * - * @property # <<<<<<<<<<<<<< - * def shape(self): - * return tuple([length for length in self.view.shape[:self.view.ndim]]) - */ - -/* Python wrapper */ -static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_5shape_1__get__(PyObject *__pyx_v_self); /*proto*/ -static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_5shape_1__get__(PyObject *__pyx_v_self) { - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - PyObject *__pyx_r = 0; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); - __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); - __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_5shape___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); - - /* function exit code */ - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_5shape___get__(struct __pyx_memoryview_obj *__pyx_v_self) { - Py_ssize_t __pyx_7genexpr__pyx_v_length; - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - PyObject *__pyx_t_1 = NULL; - Py_ssize_t *__pyx_t_2; - Py_ssize_t *__pyx_t_3; - Py_ssize_t *__pyx_t_4; - PyObject *__pyx_t_5 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("__get__", 1); - - /* "View.MemoryView":569 - * @property - * def shape(self): - * return tuple([length for length in self.view.shape[:self.view.ndim]]) # <<<<<<<<<<<<<< - * - * @property - */ - __Pyx_XDECREF(__pyx_r); - { /* enter inner scope */ - __pyx_t_1 = PyList_New(0); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 569, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_3 = (__pyx_v_self->view.shape + __pyx_v_self->view.ndim); - for (__pyx_t_4 = __pyx_v_self->view.shape; __pyx_t_4 < __pyx_t_3; __pyx_t_4++) { - __pyx_t_2 = __pyx_t_4; - __pyx_7genexpr__pyx_v_length = (__pyx_t_2[0]); - __pyx_t_5 = PyInt_FromSsize_t(__pyx_7genexpr__pyx_v_length); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 569, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - if (unlikely(__Pyx_ListComp_Append(__pyx_t_1, (PyObject*)__pyx_t_5))) __PYX_ERR(1, 569, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - } - } /* exit inner scope */ - __pyx_t_5 = PyList_AsTuple(((PyObject*)__pyx_t_1)); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 569, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_r = __pyx_t_5; - __pyx_t_5 = 0; - goto __pyx_L0; - - /* "View.MemoryView":567 - * return self.obj - * - * @property # <<<<<<<<<<<<<< - * def shape(self): - * return tuple([length for length in self.view.shape[:self.view.ndim]]) - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_1); - __Pyx_XDECREF(__pyx_t_5); - __Pyx_AddTraceback("View.MemoryView.memoryview.shape.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = NULL; - __pyx_L0:; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "View.MemoryView":571 - * return tuple([length for length in self.view.shape[:self.view.ndim]]) - * - * @property # <<<<<<<<<<<<<< - * def strides(self): - * if self.view.strides == NULL: - */ - -/* Python wrapper */ -static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_7strides_1__get__(PyObject *__pyx_v_self); /*proto*/ -static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_7strides_1__get__(PyObject *__pyx_v_self) { - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - PyObject *__pyx_r = 0; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); - __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); - __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_7strides___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); - - /* function exit code */ - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_7strides___get__(struct __pyx_memoryview_obj *__pyx_v_self) { - Py_ssize_t __pyx_8genexpr1__pyx_v_stride; - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - int __pyx_t_1; - PyObject *__pyx_t_2 = NULL; - Py_ssize_t *__pyx_t_3; - Py_ssize_t *__pyx_t_4; - Py_ssize_t *__pyx_t_5; - PyObject *__pyx_t_6 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("__get__", 1); - - /* "View.MemoryView":573 - * @property - * def strides(self): - * if self.view.strides == NULL: # <<<<<<<<<<<<<< - * - * raise ValueError, "Buffer view does not expose strides" - */ - __pyx_t_1 = (__pyx_v_self->view.strides == NULL); - if (unlikely(__pyx_t_1)) { - - /* "View.MemoryView":575 - * if self.view.strides == NULL: - * - * raise ValueError, "Buffer view does not expose strides" # <<<<<<<<<<<<<< - * - * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) - */ - __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Buffer_view_does_not_expose_stri, 0, 0); - __PYX_ERR(1, 575, __pyx_L1_error) - - /* "View.MemoryView":573 - * @property - * def strides(self): - * if self.view.strides == NULL: # <<<<<<<<<<<<<< - * - * raise ValueError, "Buffer view does not expose strides" - */ - } - - /* "View.MemoryView":577 - * raise ValueError, "Buffer view does not expose strides" - * - * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) # <<<<<<<<<<<<<< - * - * @property - */ - __Pyx_XDECREF(__pyx_r); - { /* enter inner scope */ - __pyx_t_2 = PyList_New(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 577, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __pyx_t_4 = (__pyx_v_self->view.strides + __pyx_v_self->view.ndim); - for (__pyx_t_5 = __pyx_v_self->view.strides; __pyx_t_5 < __pyx_t_4; __pyx_t_5++) { - __pyx_t_3 = __pyx_t_5; - __pyx_8genexpr1__pyx_v_stride = (__pyx_t_3[0]); - __pyx_t_6 = PyInt_FromSsize_t(__pyx_8genexpr1__pyx_v_stride); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 577, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_6); - if (unlikely(__Pyx_ListComp_Append(__pyx_t_2, (PyObject*)__pyx_t_6))) __PYX_ERR(1, 577, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; - } - } /* exit inner scope */ - __pyx_t_6 = PyList_AsTuple(((PyObject*)__pyx_t_2)); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 577, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_6); - __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - __pyx_r = __pyx_t_6; - __pyx_t_6 = 0; - goto __pyx_L0; - - /* "View.MemoryView":571 - * return tuple([length for length in self.view.shape[:self.view.ndim]]) - * - * @property # <<<<<<<<<<<<<< - * def strides(self): - * if self.view.strides == NULL: - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_2); - __Pyx_XDECREF(__pyx_t_6); - __Pyx_AddTraceback("View.MemoryView.memoryview.strides.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = NULL; - __pyx_L0:; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "View.MemoryView":579 - * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) - * - * @property # <<<<<<<<<<<<<< - * def suboffsets(self): - * if self.view.suboffsets == NULL: - */ - -/* Python wrapper */ -static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_10suboffsets_1__get__(PyObject *__pyx_v_self); /*proto*/ -static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_10suboffsets_1__get__(PyObject *__pyx_v_self) { - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - PyObject *__pyx_r = 0; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); - __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); - __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_10suboffsets___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); - - /* function exit code */ - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_10suboffsets___get__(struct __pyx_memoryview_obj *__pyx_v_self) { - Py_ssize_t __pyx_8genexpr2__pyx_v_suboffset; - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - int __pyx_t_1; - PyObject *__pyx_t_2 = NULL; - Py_ssize_t *__pyx_t_3; - Py_ssize_t *__pyx_t_4; - Py_ssize_t *__pyx_t_5; - PyObject *__pyx_t_6 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("__get__", 1); - - /* "View.MemoryView":581 - * @property - * def suboffsets(self): - * if self.view.suboffsets == NULL: # <<<<<<<<<<<<<< - * return (-1,) * self.view.ndim - * - */ - __pyx_t_1 = (__pyx_v_self->view.suboffsets == NULL); - if (__pyx_t_1) { - - /* "View.MemoryView":582 - * def suboffsets(self): - * if self.view.suboffsets == NULL: - * return (-1,) * self.view.ndim # <<<<<<<<<<<<<< - * - * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) - */ - __Pyx_XDECREF(__pyx_r); - __pyx_t_2 = __Pyx_PySequence_Multiply(__pyx_tuple__4, __pyx_v_self->view.ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 582, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __pyx_r = __pyx_t_2; - __pyx_t_2 = 0; - goto __pyx_L0; - - /* "View.MemoryView":581 - * @property - * def suboffsets(self): - * if self.view.suboffsets == NULL: # <<<<<<<<<<<<<< - * return (-1,) * self.view.ndim - * - */ - } - - /* "View.MemoryView":584 - * return (-1,) * self.view.ndim - * - * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) # <<<<<<<<<<<<<< - * - * @property - */ - __Pyx_XDECREF(__pyx_r); - { /* enter inner scope */ - __pyx_t_2 = PyList_New(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 584, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __pyx_t_4 = (__pyx_v_self->view.suboffsets + __pyx_v_self->view.ndim); - for (__pyx_t_5 = __pyx_v_self->view.suboffsets; __pyx_t_5 < __pyx_t_4; __pyx_t_5++) { - __pyx_t_3 = __pyx_t_5; - __pyx_8genexpr2__pyx_v_suboffset = (__pyx_t_3[0]); - __pyx_t_6 = PyInt_FromSsize_t(__pyx_8genexpr2__pyx_v_suboffset); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 584, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_6); - if (unlikely(__Pyx_ListComp_Append(__pyx_t_2, (PyObject*)__pyx_t_6))) __PYX_ERR(1, 584, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; - } - } /* exit inner scope */ - __pyx_t_6 = PyList_AsTuple(((PyObject*)__pyx_t_2)); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 584, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_6); - __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - __pyx_r = __pyx_t_6; - __pyx_t_6 = 0; - goto __pyx_L0; - - /* "View.MemoryView":579 - * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) - * - * @property # <<<<<<<<<<<<<< - * def suboffsets(self): - * if self.view.suboffsets == NULL: - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_2); - __Pyx_XDECREF(__pyx_t_6); - __Pyx_AddTraceback("View.MemoryView.memoryview.suboffsets.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = NULL; - __pyx_L0:; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "View.MemoryView":586 - * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) - * - * @property # <<<<<<<<<<<<<< - * def ndim(self): - * return self.view.ndim - */ - -/* Python wrapper */ -static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4ndim_1__get__(PyObject *__pyx_v_self); /*proto*/ -static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4ndim_1__get__(PyObject *__pyx_v_self) { - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - PyObject *__pyx_r = 0; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); - __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); - __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_4ndim___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); - - /* function exit code */ - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4ndim___get__(struct __pyx_memoryview_obj *__pyx_v_self) { - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - PyObject *__pyx_t_1 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("__get__", 1); - - /* "View.MemoryView":588 - * @property - * def ndim(self): - * return self.view.ndim # <<<<<<<<<<<<<< - * - * @property - */ - __Pyx_XDECREF(__pyx_r); - __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_self->view.ndim); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 588, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_r = __pyx_t_1; - __pyx_t_1 = 0; - goto __pyx_L0; - - /* "View.MemoryView":586 - * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) - * - * @property # <<<<<<<<<<<<<< - * def ndim(self): - * return self.view.ndim - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_1); - __Pyx_AddTraceback("View.MemoryView.memoryview.ndim.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = NULL; - __pyx_L0:; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "View.MemoryView":590 - * return self.view.ndim - * - * @property # <<<<<<<<<<<<<< - * def itemsize(self): - * return self.view.itemsize - */ - -/* Python wrapper */ -static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_8itemsize_1__get__(PyObject *__pyx_v_self); /*proto*/ -static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_8itemsize_1__get__(PyObject *__pyx_v_self) { - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - PyObject *__pyx_r = 0; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); - __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); - __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_8itemsize___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); - - /* function exit code */ - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_8itemsize___get__(struct __pyx_memoryview_obj *__pyx_v_self) { - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - PyObject *__pyx_t_1 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("__get__", 1); - - /* "View.MemoryView":592 - * @property - * def itemsize(self): - * return self.view.itemsize # <<<<<<<<<<<<<< - * - * @property - */ - __Pyx_XDECREF(__pyx_r); - __pyx_t_1 = PyInt_FromSsize_t(__pyx_v_self->view.itemsize); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 592, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_r = __pyx_t_1; - __pyx_t_1 = 0; - goto __pyx_L0; - - /* "View.MemoryView":590 - * return self.view.ndim - * - * @property # <<<<<<<<<<<<<< - * def itemsize(self): - * return self.view.itemsize - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_1); - __Pyx_AddTraceback("View.MemoryView.memoryview.itemsize.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = NULL; - __pyx_L0:; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "View.MemoryView":594 - * return self.view.itemsize - * - * @property # <<<<<<<<<<<<<< - * def nbytes(self): - * return self.size * self.view.itemsize - */ - -/* Python wrapper */ -static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_6nbytes_1__get__(PyObject *__pyx_v_self); /*proto*/ -static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_6nbytes_1__get__(PyObject *__pyx_v_self) { - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - PyObject *__pyx_r = 0; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); - __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); - __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_6nbytes___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); - - /* function exit code */ - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_6nbytes___get__(struct __pyx_memoryview_obj *__pyx_v_self) { - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - PyObject *__pyx_t_1 = NULL; - PyObject *__pyx_t_2 = NULL; - PyObject *__pyx_t_3 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("__get__", 1); - - /* "View.MemoryView":596 - * @property - * def nbytes(self): - * return self.size * self.view.itemsize # <<<<<<<<<<<<<< - * - * @property - */ - __Pyx_XDECREF(__pyx_r); - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_size); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 596, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_2 = PyInt_FromSsize_t(__pyx_v_self->view.itemsize); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 596, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __pyx_t_3 = PyNumber_Multiply(__pyx_t_1, __pyx_t_2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 596, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - __pyx_r = __pyx_t_3; - __pyx_t_3 = 0; - goto __pyx_L0; - - /* "View.MemoryView":594 - * return self.view.itemsize - * - * @property # <<<<<<<<<<<<<< - * def nbytes(self): - * return self.size * self.view.itemsize - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_1); - __Pyx_XDECREF(__pyx_t_2); - __Pyx_XDECREF(__pyx_t_3); - __Pyx_AddTraceback("View.MemoryView.memoryview.nbytes.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = NULL; - __pyx_L0:; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "View.MemoryView":598 - * return self.size * self.view.itemsize - * - * @property # <<<<<<<<<<<<<< - * def size(self): - * if self._size is None: - */ - -/* Python wrapper */ -static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4size_1__get__(PyObject *__pyx_v_self); /*proto*/ -static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4size_1__get__(PyObject *__pyx_v_self) { - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - PyObject *__pyx_r = 0; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); - __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); - __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_4size___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); - - /* function exit code */ - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4size___get__(struct __pyx_memoryview_obj *__pyx_v_self) { - PyObject *__pyx_v_result = NULL; - PyObject *__pyx_v_length = NULL; - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - int __pyx_t_1; - Py_ssize_t *__pyx_t_2; - Py_ssize_t *__pyx_t_3; - Py_ssize_t *__pyx_t_4; - PyObject *__pyx_t_5 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("__get__", 1); - - /* "View.MemoryView":600 - * @property - * def size(self): - * if self._size is None: # <<<<<<<<<<<<<< - * result = 1 - * - */ - __pyx_t_1 = (__pyx_v_self->_size == Py_None); - if (__pyx_t_1) { - - /* "View.MemoryView":601 - * def size(self): - * if self._size is None: - * result = 1 # <<<<<<<<<<<<<< - * - * for length in self.view.shape[:self.view.ndim]: - */ - __Pyx_INCREF(__pyx_int_1); - __pyx_v_result = __pyx_int_1; - - /* "View.MemoryView":603 - * result = 1 - * - * for length in self.view.shape[:self.view.ndim]: # <<<<<<<<<<<<<< - * result *= length - * - */ - __pyx_t_3 = (__pyx_v_self->view.shape + __pyx_v_self->view.ndim); - for (__pyx_t_4 = __pyx_v_self->view.shape; __pyx_t_4 < __pyx_t_3; __pyx_t_4++) { - __pyx_t_2 = __pyx_t_4; - __pyx_t_5 = PyInt_FromSsize_t((__pyx_t_2[0])); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 603, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __Pyx_XDECREF_SET(__pyx_v_length, __pyx_t_5); - __pyx_t_5 = 0; - - /* "View.MemoryView":604 - * - * for length in self.view.shape[:self.view.ndim]: - * result *= length # <<<<<<<<<<<<<< - * - * self._size = result - */ - __pyx_t_5 = PyNumber_InPlaceMultiply(__pyx_v_result, __pyx_v_length); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 604, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __Pyx_DECREF_SET(__pyx_v_result, __pyx_t_5); - __pyx_t_5 = 0; - } - - /* "View.MemoryView":606 - * result *= length - * - * self._size = result # <<<<<<<<<<<<<< - * - * return self._size - */ - __Pyx_INCREF(__pyx_v_result); - __Pyx_GIVEREF(__pyx_v_result); - __Pyx_GOTREF(__pyx_v_self->_size); - __Pyx_DECREF(__pyx_v_self->_size); - __pyx_v_self->_size = __pyx_v_result; - - /* "View.MemoryView":600 - * @property - * def size(self): - * if self._size is None: # <<<<<<<<<<<<<< - * result = 1 - * - */ - } - - /* "View.MemoryView":608 - * self._size = result - * - * return self._size # <<<<<<<<<<<<<< - * - * def __len__(self): - */ - __Pyx_XDECREF(__pyx_r); - __Pyx_INCREF(__pyx_v_self->_size); - __pyx_r = __pyx_v_self->_size; - goto __pyx_L0; - - /* "View.MemoryView":598 - * return self.size * self.view.itemsize - * - * @property # <<<<<<<<<<<<<< - * def size(self): - * if self._size is None: - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_5); - __Pyx_AddTraceback("View.MemoryView.memoryview.size.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = NULL; - __pyx_L0:; - __Pyx_XDECREF(__pyx_v_result); - __Pyx_XDECREF(__pyx_v_length); - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "View.MemoryView":610 - * return self._size - * - * def __len__(self): # <<<<<<<<<<<<<< - * if self.view.ndim >= 1: - * return self.view.shape[0] - */ - -/* Python wrapper */ -static Py_ssize_t __pyx_memoryview___len__(PyObject *__pyx_v_self); /*proto*/ -static Py_ssize_t __pyx_memoryview___len__(PyObject *__pyx_v_self) { - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - Py_ssize_t __pyx_r; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("__len__ (wrapper)", 0); - __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); - __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_10__len__(((struct __pyx_memoryview_obj *)__pyx_v_self)); - - /* function exit code */ - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static Py_ssize_t __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_10__len__(struct __pyx_memoryview_obj *__pyx_v_self) { - Py_ssize_t __pyx_r; - int __pyx_t_1; - - /* "View.MemoryView":611 - * - * def __len__(self): - * if self.view.ndim >= 1: # <<<<<<<<<<<<<< - * return self.view.shape[0] - * - */ - __pyx_t_1 = (__pyx_v_self->view.ndim >= 1); - if (__pyx_t_1) { - - /* "View.MemoryView":612 - * def __len__(self): - * if self.view.ndim >= 1: - * return self.view.shape[0] # <<<<<<<<<<<<<< - * - * return 0 - */ - __pyx_r = (__pyx_v_self->view.shape[0]); - goto __pyx_L0; - - /* "View.MemoryView":611 - * - * def __len__(self): - * if self.view.ndim >= 1: # <<<<<<<<<<<<<< - * return self.view.shape[0] - * - */ - } - - /* "View.MemoryView":614 - * return self.view.shape[0] - * - * return 0 # <<<<<<<<<<<<<< - * - * def __repr__(self): - */ - __pyx_r = 0; - goto __pyx_L0; - - /* "View.MemoryView":610 - * return self._size - * - * def __len__(self): # <<<<<<<<<<<<<< - * if self.view.ndim >= 1: - * return self.view.shape[0] - */ - - /* function exit code */ - __pyx_L0:; - return __pyx_r; -} - -/* "View.MemoryView":616 - * return 0 - * - * def __repr__(self): # <<<<<<<<<<<<<< - * return "" % (self.base.__class__.__name__, - * id(self)) - */ - -/* Python wrapper */ -static PyObject *__pyx_memoryview___repr__(PyObject *__pyx_v_self); /*proto*/ -static PyObject *__pyx_memoryview___repr__(PyObject *__pyx_v_self) { - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - PyObject *__pyx_r = 0; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("__repr__ (wrapper)", 0); - __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); - __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_12__repr__(((struct __pyx_memoryview_obj *)__pyx_v_self)); - - /* function exit code */ - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_12__repr__(struct __pyx_memoryview_obj *__pyx_v_self) { - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - PyObject *__pyx_t_1 = NULL; - PyObject *__pyx_t_2 = NULL; - PyObject *__pyx_t_3 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("__repr__", 1); - - /* "View.MemoryView":617 - * - * def __repr__(self): - * return "" % (self.base.__class__.__name__, # <<<<<<<<<<<<<< - * id(self)) - * - */ - __Pyx_XDECREF(__pyx_r); - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_base); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 617, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_class); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 617, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_name_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 617, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - - /* "View.MemoryView":618 - * def __repr__(self): - * return "" % (self.base.__class__.__name__, - * id(self)) # <<<<<<<<<<<<<< - * - * def __str__(self): - */ - __pyx_t_2 = __Pyx_PyObject_CallOneArg(__pyx_builtin_id, ((PyObject *)__pyx_v_self)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 618, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - - /* "View.MemoryView":617 - * - * def __repr__(self): - * return "" % (self.base.__class__.__name__, # <<<<<<<<<<<<<< - * id(self)) - * - */ - __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 617, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __Pyx_GIVEREF(__pyx_t_1); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_1)) __PYX_ERR(1, 617, __pyx_L1_error); - __Pyx_GIVEREF(__pyx_t_2); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_2)) __PYX_ERR(1, 617, __pyx_L1_error); - __pyx_t_1 = 0; - __pyx_t_2 = 0; - __pyx_t_2 = __Pyx_PyString_Format(__pyx_kp_s_MemoryView_of_r_at_0x_x, __pyx_t_3); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 617, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - __pyx_r = __pyx_t_2; - __pyx_t_2 = 0; - goto __pyx_L0; - - /* "View.MemoryView":616 - * return 0 - * - * def __repr__(self): # <<<<<<<<<<<<<< - * return "" % (self.base.__class__.__name__, - * id(self)) - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_1); - __Pyx_XDECREF(__pyx_t_2); - __Pyx_XDECREF(__pyx_t_3); - __Pyx_AddTraceback("View.MemoryView.memoryview.__repr__", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = NULL; - __pyx_L0:; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "View.MemoryView":620 - * id(self)) - * - * def __str__(self): # <<<<<<<<<<<<<< - * return "" % (self.base.__class__.__name__,) - * - */ - -/* Python wrapper */ -static PyObject *__pyx_memoryview___str__(PyObject *__pyx_v_self); /*proto*/ -static PyObject *__pyx_memoryview___str__(PyObject *__pyx_v_self) { - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - PyObject *__pyx_r = 0; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("__str__ (wrapper)", 0); - __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); - __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_14__str__(((struct __pyx_memoryview_obj *)__pyx_v_self)); - - /* function exit code */ - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_14__str__(struct __pyx_memoryview_obj *__pyx_v_self) { - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - PyObject *__pyx_t_1 = NULL; - PyObject *__pyx_t_2 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("__str__", 1); - - /* "View.MemoryView":621 - * - * def __str__(self): - * return "" % (self.base.__class__.__name__,) # <<<<<<<<<<<<<< - * - * - */ - __Pyx_XDECREF(__pyx_r); - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_base); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 621, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_class); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 621, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_name_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 621, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - __pyx_t_2 = PyTuple_New(1); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 621, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __Pyx_GIVEREF(__pyx_t_1); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_2, 0, __pyx_t_1)) __PYX_ERR(1, 621, __pyx_L1_error); - __pyx_t_1 = 0; - __pyx_t_1 = __Pyx_PyString_Format(__pyx_kp_s_MemoryView_of_r_object, __pyx_t_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 621, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - __pyx_r = __pyx_t_1; - __pyx_t_1 = 0; - goto __pyx_L0; - - /* "View.MemoryView":620 - * id(self)) - * - * def __str__(self): # <<<<<<<<<<<<<< - * return "" % (self.base.__class__.__name__,) - * - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_1); - __Pyx_XDECREF(__pyx_t_2); - __Pyx_AddTraceback("View.MemoryView.memoryview.__str__", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = NULL; - __pyx_L0:; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "View.MemoryView":624 - * - * - * def is_c_contig(self): # <<<<<<<<<<<<<< - * cdef __Pyx_memviewslice *mslice - * cdef __Pyx_memviewslice tmp - */ - -/* Python wrapper */ -static PyObject *__pyx_memoryview_is_c_contig(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -); /*proto*/ -static PyObject *__pyx_memoryview_is_c_contig(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -) { - #if !CYTHON_METH_FASTCALL - CYTHON_UNUSED Py_ssize_t __pyx_nargs; - #endif - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - PyObject *__pyx_r = 0; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("is_c_contig (wrapper)", 0); - #if !CYTHON_METH_FASTCALL - #if CYTHON_ASSUME_SAFE_MACROS - __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); - #else - __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; - #endif - #endif - __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); - if (unlikely(__pyx_nargs > 0)) { - __Pyx_RaiseArgtupleInvalid("is_c_contig", 1, 0, 0, __pyx_nargs); return NULL;} - if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "is_c_contig", 0))) return NULL; - __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_16is_c_contig(((struct __pyx_memoryview_obj *)__pyx_v_self)); - - /* function exit code */ - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_16is_c_contig(struct __pyx_memoryview_obj *__pyx_v_self) { - __Pyx_memviewslice *__pyx_v_mslice; - __Pyx_memviewslice __pyx_v_tmp; - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - __Pyx_memviewslice *__pyx_t_1; - PyObject *__pyx_t_2 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("is_c_contig", 1); - - /* "View.MemoryView":627 - * cdef __Pyx_memviewslice *mslice - * cdef __Pyx_memviewslice tmp - * mslice = get_slice_from_memview(self, &tmp) # <<<<<<<<<<<<<< - * return slice_is_contig(mslice[0], 'C', self.view.ndim) - * - */ - __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(__pyx_v_self, (&__pyx_v_tmp)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(1, 627, __pyx_L1_error) - __pyx_v_mslice = __pyx_t_1; - - /* "View.MemoryView":628 - * cdef __Pyx_memviewslice tmp - * mslice = get_slice_from_memview(self, &tmp) - * return slice_is_contig(mslice[0], 'C', self.view.ndim) # <<<<<<<<<<<<<< - * - * def is_f_contig(self): - */ - __Pyx_XDECREF(__pyx_r); - __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_memviewslice_is_contig((__pyx_v_mslice[0]), 'C', __pyx_v_self->view.ndim)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 628, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __pyx_r = __pyx_t_2; - __pyx_t_2 = 0; - goto __pyx_L0; - - /* "View.MemoryView":624 - * - * - * def is_c_contig(self): # <<<<<<<<<<<<<< - * cdef __Pyx_memviewslice *mslice - * cdef __Pyx_memviewslice tmp - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_2); - __Pyx_AddTraceback("View.MemoryView.memoryview.is_c_contig", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = NULL; - __pyx_L0:; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "View.MemoryView":630 - * return slice_is_contig(mslice[0], 'C', self.view.ndim) - * - * def is_f_contig(self): # <<<<<<<<<<<<<< - * cdef __Pyx_memviewslice *mslice - * cdef __Pyx_memviewslice tmp - */ - -/* Python wrapper */ -static PyObject *__pyx_memoryview_is_f_contig(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -); /*proto*/ -static PyObject *__pyx_memoryview_is_f_contig(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -) { - #if !CYTHON_METH_FASTCALL - CYTHON_UNUSED Py_ssize_t __pyx_nargs; - #endif - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - PyObject *__pyx_r = 0; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("is_f_contig (wrapper)", 0); - #if !CYTHON_METH_FASTCALL - #if CYTHON_ASSUME_SAFE_MACROS - __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); - #else - __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; - #endif - #endif - __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); - if (unlikely(__pyx_nargs > 0)) { - __Pyx_RaiseArgtupleInvalid("is_f_contig", 1, 0, 0, __pyx_nargs); return NULL;} - if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "is_f_contig", 0))) return NULL; - __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_18is_f_contig(((struct __pyx_memoryview_obj *)__pyx_v_self)); - - /* function exit code */ - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_18is_f_contig(struct __pyx_memoryview_obj *__pyx_v_self) { - __Pyx_memviewslice *__pyx_v_mslice; - __Pyx_memviewslice __pyx_v_tmp; - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - __Pyx_memviewslice *__pyx_t_1; - PyObject *__pyx_t_2 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("is_f_contig", 1); - - /* "View.MemoryView":633 - * cdef __Pyx_memviewslice *mslice - * cdef __Pyx_memviewslice tmp - * mslice = get_slice_from_memview(self, &tmp) # <<<<<<<<<<<<<< - * return slice_is_contig(mslice[0], 'F', self.view.ndim) - * - */ - __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(__pyx_v_self, (&__pyx_v_tmp)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(1, 633, __pyx_L1_error) - __pyx_v_mslice = __pyx_t_1; - - /* "View.MemoryView":634 - * cdef __Pyx_memviewslice tmp - * mslice = get_slice_from_memview(self, &tmp) - * return slice_is_contig(mslice[0], 'F', self.view.ndim) # <<<<<<<<<<<<<< - * - * def copy(self): - */ - __Pyx_XDECREF(__pyx_r); - __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_memviewslice_is_contig((__pyx_v_mslice[0]), 'F', __pyx_v_self->view.ndim)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 634, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __pyx_r = __pyx_t_2; - __pyx_t_2 = 0; - goto __pyx_L0; - - /* "View.MemoryView":630 - * return slice_is_contig(mslice[0], 'C', self.view.ndim) - * - * def is_f_contig(self): # <<<<<<<<<<<<<< - * cdef __Pyx_memviewslice *mslice - * cdef __Pyx_memviewslice tmp - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_2); - __Pyx_AddTraceback("View.MemoryView.memoryview.is_f_contig", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = NULL; - __pyx_L0:; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "View.MemoryView":636 - * return slice_is_contig(mslice[0], 'F', self.view.ndim) - * - * def copy(self): # <<<<<<<<<<<<<< - * cdef __Pyx_memviewslice mslice - * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS - */ - -/* Python wrapper */ -static PyObject *__pyx_memoryview_copy(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -); /*proto*/ -static PyObject *__pyx_memoryview_copy(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -) { - #if !CYTHON_METH_FASTCALL - CYTHON_UNUSED Py_ssize_t __pyx_nargs; - #endif - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - PyObject *__pyx_r = 0; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("copy (wrapper)", 0); - #if !CYTHON_METH_FASTCALL - #if CYTHON_ASSUME_SAFE_MACROS - __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); - #else - __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; - #endif - #endif - __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); - if (unlikely(__pyx_nargs > 0)) { - __Pyx_RaiseArgtupleInvalid("copy", 1, 0, 0, __pyx_nargs); return NULL;} - if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "copy", 0))) return NULL; - __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_20copy(((struct __pyx_memoryview_obj *)__pyx_v_self)); - - /* function exit code */ - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_20copy(struct __pyx_memoryview_obj *__pyx_v_self) { - __Pyx_memviewslice __pyx_v_mslice; - int __pyx_v_flags; - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - __Pyx_memviewslice __pyx_t_1; - PyObject *__pyx_t_2 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("copy", 1); - - /* "View.MemoryView":638 - * def copy(self): - * cdef __Pyx_memviewslice mslice - * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS # <<<<<<<<<<<<<< - * - * slice_copy(self, &mslice) - */ - __pyx_v_flags = (__pyx_v_self->flags & (~PyBUF_F_CONTIGUOUS)); - - /* "View.MemoryView":640 - * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS - * - * slice_copy(self, &mslice) # <<<<<<<<<<<<<< - * mslice = slice_copy_contig(&mslice, "c", self.view.ndim, - * self.view.itemsize, - */ - __pyx_memoryview_slice_copy(__pyx_v_self, (&__pyx_v_mslice)); - - /* "View.MemoryView":641 - * - * slice_copy(self, &mslice) - * mslice = slice_copy_contig(&mslice, "c", self.view.ndim, # <<<<<<<<<<<<<< - * self.view.itemsize, - * flags|PyBUF_C_CONTIGUOUS, - */ - __pyx_t_1 = __pyx_memoryview_copy_new_contig((&__pyx_v_mslice), ((char *)"c"), __pyx_v_self->view.ndim, __pyx_v_self->view.itemsize, (__pyx_v_flags | PyBUF_C_CONTIGUOUS), __pyx_v_self->dtype_is_object); if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 641, __pyx_L1_error) - __pyx_v_mslice = __pyx_t_1; - - /* "View.MemoryView":646 - * self.dtype_is_object) - * - * return memoryview_copy_from_slice(self, &mslice) # <<<<<<<<<<<<<< - * - * def copy_fortran(self): - */ - __Pyx_XDECREF(__pyx_r); - __pyx_t_2 = __pyx_memoryview_copy_object_from_slice(__pyx_v_self, (&__pyx_v_mslice)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 646, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __pyx_r = __pyx_t_2; - __pyx_t_2 = 0; - goto __pyx_L0; - - /* "View.MemoryView":636 - * return slice_is_contig(mslice[0], 'F', self.view.ndim) - * - * def copy(self): # <<<<<<<<<<<<<< - * cdef __Pyx_memviewslice mslice - * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_2); - __Pyx_AddTraceback("View.MemoryView.memoryview.copy", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = NULL; - __pyx_L0:; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "View.MemoryView":648 - * return memoryview_copy_from_slice(self, &mslice) - * - * def copy_fortran(self): # <<<<<<<<<<<<<< - * cdef __Pyx_memviewslice src, dst - * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS - */ - -/* Python wrapper */ -static PyObject *__pyx_memoryview_copy_fortran(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -); /*proto*/ -static PyObject *__pyx_memoryview_copy_fortran(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -) { - #if !CYTHON_METH_FASTCALL - CYTHON_UNUSED Py_ssize_t __pyx_nargs; - #endif - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - PyObject *__pyx_r = 0; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("copy_fortran (wrapper)", 0); - #if !CYTHON_METH_FASTCALL - #if CYTHON_ASSUME_SAFE_MACROS - __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); - #else - __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; - #endif - #endif - __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); - if (unlikely(__pyx_nargs > 0)) { - __Pyx_RaiseArgtupleInvalid("copy_fortran", 1, 0, 0, __pyx_nargs); return NULL;} - if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "copy_fortran", 0))) return NULL; - __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_22copy_fortran(((struct __pyx_memoryview_obj *)__pyx_v_self)); - - /* function exit code */ - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_22copy_fortran(struct __pyx_memoryview_obj *__pyx_v_self) { - __Pyx_memviewslice __pyx_v_src; - __Pyx_memviewslice __pyx_v_dst; - int __pyx_v_flags; - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - __Pyx_memviewslice __pyx_t_1; - PyObject *__pyx_t_2 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("copy_fortran", 1); - - /* "View.MemoryView":650 - * def copy_fortran(self): - * cdef __Pyx_memviewslice src, dst - * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS # <<<<<<<<<<<<<< - * - * slice_copy(self, &src) - */ - __pyx_v_flags = (__pyx_v_self->flags & (~PyBUF_C_CONTIGUOUS)); - - /* "View.MemoryView":652 - * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS - * - * slice_copy(self, &src) # <<<<<<<<<<<<<< - * dst = slice_copy_contig(&src, "fortran", self.view.ndim, - * self.view.itemsize, - */ - __pyx_memoryview_slice_copy(__pyx_v_self, (&__pyx_v_src)); - - /* "View.MemoryView":653 - * - * slice_copy(self, &src) - * dst = slice_copy_contig(&src, "fortran", self.view.ndim, # <<<<<<<<<<<<<< - * self.view.itemsize, - * flags|PyBUF_F_CONTIGUOUS, - */ - __pyx_t_1 = __pyx_memoryview_copy_new_contig((&__pyx_v_src), ((char *)"fortran"), __pyx_v_self->view.ndim, __pyx_v_self->view.itemsize, (__pyx_v_flags | PyBUF_F_CONTIGUOUS), __pyx_v_self->dtype_is_object); if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 653, __pyx_L1_error) - __pyx_v_dst = __pyx_t_1; - - /* "View.MemoryView":658 - * self.dtype_is_object) - * - * return memoryview_copy_from_slice(self, &dst) # <<<<<<<<<<<<<< - * - * - */ - __Pyx_XDECREF(__pyx_r); - __pyx_t_2 = __pyx_memoryview_copy_object_from_slice(__pyx_v_self, (&__pyx_v_dst)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 658, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __pyx_r = __pyx_t_2; - __pyx_t_2 = 0; - goto __pyx_L0; - - /* "View.MemoryView":648 - * return memoryview_copy_from_slice(self, &mslice) - * - * def copy_fortran(self): # <<<<<<<<<<<<<< - * cdef __Pyx_memviewslice src, dst - * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_2); - __Pyx_AddTraceback("View.MemoryView.memoryview.copy_fortran", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = NULL; - __pyx_L0:; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "(tree fragment)":1 - * def __reduce_cython__(self): # <<<<<<<<<<<<<< - * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" - * def __setstate_cython__(self, __pyx_state): - */ - -/* Python wrapper */ -static PyObject *__pyx_pw___pyx_memoryview_1__reduce_cython__(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -); /*proto*/ -static PyObject *__pyx_pw___pyx_memoryview_1__reduce_cython__(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -) { - #if !CYTHON_METH_FASTCALL - CYTHON_UNUSED Py_ssize_t __pyx_nargs; - #endif - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - PyObject *__pyx_r = 0; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); - #if !CYTHON_METH_FASTCALL - #if CYTHON_ASSUME_SAFE_MACROS - __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); - #else - __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; - #endif - #endif - __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); - if (unlikely(__pyx_nargs > 0)) { - __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} - if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; - __pyx_r = __pyx_pf___pyx_memoryview___reduce_cython__(((struct __pyx_memoryview_obj *)__pyx_v_self)); - - /* function exit code */ - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static PyObject *__pyx_pf___pyx_memoryview___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self) { - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("__reduce_cython__", 1); - - /* "(tree fragment)":2 - * def __reduce_cython__(self): - * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< - * def __setstate_cython__(self, __pyx_state): - * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" - */ - __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); - __PYX_ERR(1, 2, __pyx_L1_error) - - /* "(tree fragment)":1 - * def __reduce_cython__(self): # <<<<<<<<<<<<<< - * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" - * def __setstate_cython__(self, __pyx_state): - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_AddTraceback("View.MemoryView.memoryview.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = NULL; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "(tree fragment)":3 - * def __reduce_cython__(self): - * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" - * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< - * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" - */ - -/* Python wrapper */ -static PyObject *__pyx_pw___pyx_memoryview_3__setstate_cython__(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -); /*proto*/ -static PyObject *__pyx_pw___pyx_memoryview_3__setstate_cython__(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -) { - CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; - #if !CYTHON_METH_FASTCALL - CYTHON_UNUSED Py_ssize_t __pyx_nargs; - #endif - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - PyObject* values[1] = {0}; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - PyObject *__pyx_r = 0; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); - #if !CYTHON_METH_FASTCALL - #if CYTHON_ASSUME_SAFE_MACROS - __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); - #else - __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; - #endif - #endif - __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); - { - PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; - if (__pyx_kwds) { - Py_ssize_t kw_args; - switch (__pyx_nargs) { - case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); - CYTHON_FALLTHROUGH; - case 0: break; - default: goto __pyx_L5_argtuple_error; - } - kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); - switch (__pyx_nargs) { - case 0: - if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { - (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); - kw_args--; - } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) - else goto __pyx_L5_argtuple_error; - } - if (unlikely(kw_args > 0)) { - const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) - } - } else if (unlikely(__pyx_nargs != 1)) { - goto __pyx_L5_argtuple_error; - } else { - values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); - } - __pyx_v___pyx_state = values[0]; - } - goto __pyx_L6_skip; - __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) - __pyx_L6_skip:; - goto __pyx_L4_argument_unpacking_done; - __pyx_L3_error:; - { - Py_ssize_t __pyx_temp; - for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { - __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); - } - } - __Pyx_AddTraceback("View.MemoryView.memoryview.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); - __Pyx_RefNannyFinishContext(); - return NULL; - __pyx_L4_argument_unpacking_done:; - __pyx_r = __pyx_pf___pyx_memoryview_2__setstate_cython__(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v___pyx_state); - - /* function exit code */ - { - Py_ssize_t __pyx_temp; - for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { - __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); - } - } - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static PyObject *__pyx_pf___pyx_memoryview_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("__setstate_cython__", 1); - - /* "(tree fragment)":4 - * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" - * def __setstate_cython__(self, __pyx_state): - * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< - */ - __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); - __PYX_ERR(1, 4, __pyx_L1_error) - - /* "(tree fragment)":3 - * def __reduce_cython__(self): - * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" - * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< - * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_AddTraceback("View.MemoryView.memoryview.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = NULL; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "View.MemoryView":662 - * - * @cname('__pyx_memoryview_new') - * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): # <<<<<<<<<<<<<< - * cdef memoryview result = memoryview(o, flags, dtype_is_object) - * result.typeinfo = typeinfo - */ - -static PyObject *__pyx_memoryview_new(PyObject *__pyx_v_o, int __pyx_v_flags, int __pyx_v_dtype_is_object, __Pyx_TypeInfo *__pyx_v_typeinfo) { - struct __pyx_memoryview_obj *__pyx_v_result = 0; - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - PyObject *__pyx_t_1 = NULL; - PyObject *__pyx_t_2 = NULL; - PyObject *__pyx_t_3 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("memoryview_cwrapper", 1); - - /* "View.MemoryView":663 - * @cname('__pyx_memoryview_new') - * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): - * cdef memoryview result = memoryview(o, flags, dtype_is_object) # <<<<<<<<<<<<<< - * result.typeinfo = typeinfo - * return result - */ - __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_flags); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 663, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_v_dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 663, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 663, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __Pyx_INCREF(__pyx_v_o); - __Pyx_GIVEREF(__pyx_v_o); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_v_o)) __PYX_ERR(1, 663, __pyx_L1_error); - __Pyx_GIVEREF(__pyx_t_1); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1)) __PYX_ERR(1, 663, __pyx_L1_error); - __Pyx_GIVEREF(__pyx_t_2); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_t_2)) __PYX_ERR(1, 663, __pyx_L1_error); - __pyx_t_1 = 0; - __pyx_t_2 = 0; - __pyx_t_2 = __Pyx_PyObject_Call(((PyObject *)__pyx_memoryview_type), __pyx_t_3, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 663, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - __pyx_v_result = ((struct __pyx_memoryview_obj *)__pyx_t_2); - __pyx_t_2 = 0; - - /* "View.MemoryView":664 - * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): - * cdef memoryview result = memoryview(o, flags, dtype_is_object) - * result.typeinfo = typeinfo # <<<<<<<<<<<<<< - * return result - * - */ - __pyx_v_result->typeinfo = __pyx_v_typeinfo; - - /* "View.MemoryView":665 - * cdef memoryview result = memoryview(o, flags, dtype_is_object) - * result.typeinfo = typeinfo - * return result # <<<<<<<<<<<<<< - * - * @cname('__pyx_memoryview_check') - */ - __Pyx_XDECREF(__pyx_r); - __Pyx_INCREF((PyObject *)__pyx_v_result); - __pyx_r = ((PyObject *)__pyx_v_result); - goto __pyx_L0; - - /* "View.MemoryView":662 - * - * @cname('__pyx_memoryview_new') - * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): # <<<<<<<<<<<<<< - * cdef memoryview result = memoryview(o, flags, dtype_is_object) - * result.typeinfo = typeinfo - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_1); - __Pyx_XDECREF(__pyx_t_2); - __Pyx_XDECREF(__pyx_t_3); - __Pyx_AddTraceback("View.MemoryView.memoryview_cwrapper", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = 0; - __pyx_L0:; - __Pyx_XDECREF((PyObject *)__pyx_v_result); - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "View.MemoryView":668 - * - * @cname('__pyx_memoryview_check') - * cdef inline bint memoryview_check(object o) noexcept: # <<<<<<<<<<<<<< - * return isinstance(o, memoryview) - * - */ - -static CYTHON_INLINE int __pyx_memoryview_check(PyObject *__pyx_v_o) { - int __pyx_r; - int __pyx_t_1; - - /* "View.MemoryView":669 - * @cname('__pyx_memoryview_check') - * cdef inline bint memoryview_check(object o) noexcept: - * return isinstance(o, memoryview) # <<<<<<<<<<<<<< - * - * cdef tuple _unellipsify(object index, int ndim): - */ - __pyx_t_1 = __Pyx_TypeCheck(__pyx_v_o, __pyx_memoryview_type); - __pyx_r = __pyx_t_1; - goto __pyx_L0; - - /* "View.MemoryView":668 - * - * @cname('__pyx_memoryview_check') - * cdef inline bint memoryview_check(object o) noexcept: # <<<<<<<<<<<<<< - * return isinstance(o, memoryview) - * - */ - - /* function exit code */ - __pyx_L0:; - return __pyx_r; -} - -/* "View.MemoryView":671 - * return isinstance(o, memoryview) - * - * cdef tuple _unellipsify(object index, int ndim): # <<<<<<<<<<<<<< - * """ - * Replace all ellipses with full slices and fill incomplete indices with - */ - -static PyObject *_unellipsify(PyObject *__pyx_v_index, int __pyx_v_ndim) { - Py_ssize_t __pyx_v_idx; - PyObject *__pyx_v_tup = NULL; - PyObject *__pyx_v_result = NULL; - int __pyx_v_have_slices; - int __pyx_v_seen_ellipsis; - PyObject *__pyx_v_item = NULL; - Py_ssize_t __pyx_v_nslices; - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - PyObject *__pyx_t_1 = NULL; - int __pyx_t_2; - PyObject *__pyx_t_3 = NULL; - Py_ssize_t __pyx_t_4; - Py_ssize_t __pyx_t_5; - Py_UCS4 __pyx_t_6; - PyObject *__pyx_t_7 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("_unellipsify", 1); - - /* "View.MemoryView":677 - * """ - * cdef Py_ssize_t idx - * tup = index if isinstance(index, tuple) else (index,) # <<<<<<<<<<<<<< - * - * result = [slice(None)] * ndim - */ - __pyx_t_2 = PyTuple_Check(__pyx_v_index); - if (__pyx_t_2) { - __Pyx_INCREF(((PyObject*)__pyx_v_index)); - __pyx_t_1 = __pyx_v_index; - } else { - __pyx_t_3 = PyTuple_New(1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 677, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __Pyx_INCREF(__pyx_v_index); - __Pyx_GIVEREF(__pyx_v_index); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_v_index)) __PYX_ERR(1, 677, __pyx_L1_error); - __pyx_t_1 = __pyx_t_3; - __pyx_t_3 = 0; - } - __pyx_v_tup = ((PyObject*)__pyx_t_1); - __pyx_t_1 = 0; - - /* "View.MemoryView":679 - * tup = index if isinstance(index, tuple) else (index,) - * - * result = [slice(None)] * ndim # <<<<<<<<<<<<<< - * have_slices = False - * seen_ellipsis = False - */ - __pyx_t_1 = PyList_New(1 * ((__pyx_v_ndim<0) ? 0:__pyx_v_ndim)); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 679, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - { Py_ssize_t __pyx_temp; - for (__pyx_temp=0; __pyx_temp < __pyx_v_ndim; __pyx_temp++) { - __Pyx_INCREF(__pyx_slice__5); - __Pyx_GIVEREF(__pyx_slice__5); - if (__Pyx_PyList_SET_ITEM(__pyx_t_1, __pyx_temp, __pyx_slice__5)) __PYX_ERR(1, 679, __pyx_L1_error); - } - } - __pyx_v_result = ((PyObject*)__pyx_t_1); - __pyx_t_1 = 0; - - /* "View.MemoryView":680 - * - * result = [slice(None)] * ndim - * have_slices = False # <<<<<<<<<<<<<< - * seen_ellipsis = False - * idx = 0 - */ - __pyx_v_have_slices = 0; - - /* "View.MemoryView":681 - * result = [slice(None)] * ndim - * have_slices = False - * seen_ellipsis = False # <<<<<<<<<<<<<< - * idx = 0 - * for item in tup: - */ - __pyx_v_seen_ellipsis = 0; - - /* "View.MemoryView":682 - * have_slices = False - * seen_ellipsis = False - * idx = 0 # <<<<<<<<<<<<<< - * for item in tup: - * if item is Ellipsis: - */ - __pyx_v_idx = 0; - - /* "View.MemoryView":683 - * seen_ellipsis = False - * idx = 0 - * for item in tup: # <<<<<<<<<<<<<< - * if item is Ellipsis: - * if not seen_ellipsis: - */ - if (unlikely(__pyx_v_tup == Py_None)) { - PyErr_SetString(PyExc_TypeError, "'NoneType' object is not iterable"); - __PYX_ERR(1, 683, __pyx_L1_error) - } - __pyx_t_1 = __pyx_v_tup; __Pyx_INCREF(__pyx_t_1); - __pyx_t_4 = 0; - for (;;) { - { - Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_1); - #if !CYTHON_ASSUME_SAFE_MACROS - if (unlikely((__pyx_temp < 0))) __PYX_ERR(1, 683, __pyx_L1_error) - #endif - if (__pyx_t_4 >= __pyx_temp) break; - } - #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS - __pyx_t_3 = PyTuple_GET_ITEM(__pyx_t_1, __pyx_t_4); __Pyx_INCREF(__pyx_t_3); __pyx_t_4++; if (unlikely((0 < 0))) __PYX_ERR(1, 683, __pyx_L1_error) - #else - __pyx_t_3 = __Pyx_PySequence_ITEM(__pyx_t_1, __pyx_t_4); __pyx_t_4++; if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 683, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - #endif - __Pyx_XDECREF_SET(__pyx_v_item, __pyx_t_3); - __pyx_t_3 = 0; - - /* "View.MemoryView":684 - * idx = 0 - * for item in tup: - * if item is Ellipsis: # <<<<<<<<<<<<<< - * if not seen_ellipsis: - * idx += ndim - len(tup) - */ - __pyx_t_2 = (__pyx_v_item == __pyx_builtin_Ellipsis); - if (__pyx_t_2) { - - /* "View.MemoryView":685 - * for item in tup: - * if item is Ellipsis: - * if not seen_ellipsis: # <<<<<<<<<<<<<< - * idx += ndim - len(tup) - * seen_ellipsis = True - */ - __pyx_t_2 = (!__pyx_v_seen_ellipsis); - if (__pyx_t_2) { - - /* "View.MemoryView":686 - * if item is Ellipsis: - * if not seen_ellipsis: - * idx += ndim - len(tup) # <<<<<<<<<<<<<< - * seen_ellipsis = True - * have_slices = True - */ - if (unlikely(__pyx_v_tup == Py_None)) { - PyErr_SetString(PyExc_TypeError, "object of type 'NoneType' has no len()"); - __PYX_ERR(1, 686, __pyx_L1_error) - } - __pyx_t_5 = __Pyx_PyTuple_GET_SIZE(__pyx_v_tup); if (unlikely(__pyx_t_5 == ((Py_ssize_t)-1))) __PYX_ERR(1, 686, __pyx_L1_error) - __pyx_v_idx = (__pyx_v_idx + (__pyx_v_ndim - __pyx_t_5)); - - /* "View.MemoryView":687 - * if not seen_ellipsis: - * idx += ndim - len(tup) - * seen_ellipsis = True # <<<<<<<<<<<<<< - * have_slices = True - * else: - */ - __pyx_v_seen_ellipsis = 1; - - /* "View.MemoryView":685 - * for item in tup: - * if item is Ellipsis: - * if not seen_ellipsis: # <<<<<<<<<<<<<< - * idx += ndim - len(tup) - * seen_ellipsis = True - */ - } - - /* "View.MemoryView":688 - * idx += ndim - len(tup) - * seen_ellipsis = True - * have_slices = True # <<<<<<<<<<<<<< - * else: - * if isinstance(item, slice): - */ - __pyx_v_have_slices = 1; - - /* "View.MemoryView":684 - * idx = 0 - * for item in tup: - * if item is Ellipsis: # <<<<<<<<<<<<<< - * if not seen_ellipsis: - * idx += ndim - len(tup) - */ - goto __pyx_L5; - } - - /* "View.MemoryView":690 - * have_slices = True - * else: - * if isinstance(item, slice): # <<<<<<<<<<<<<< - * have_slices = True - * elif not PyIndex_Check(item): - */ - /*else*/ { - __pyx_t_2 = PySlice_Check(__pyx_v_item); - if (__pyx_t_2) { - - /* "View.MemoryView":691 - * else: - * if isinstance(item, slice): - * have_slices = True # <<<<<<<<<<<<<< - * elif not PyIndex_Check(item): - * raise TypeError, f"Cannot index with type '{type(item)}'" - */ - __pyx_v_have_slices = 1; - - /* "View.MemoryView":690 - * have_slices = True - * else: - * if isinstance(item, slice): # <<<<<<<<<<<<<< - * have_slices = True - * elif not PyIndex_Check(item): - */ - goto __pyx_L7; - } - - /* "View.MemoryView":692 - * if isinstance(item, slice): - * have_slices = True - * elif not PyIndex_Check(item): # <<<<<<<<<<<<<< - * raise TypeError, f"Cannot index with type '{type(item)}'" - * result[idx] = item - */ - __pyx_t_2 = (!(PyIndex_Check(__pyx_v_item) != 0)); - if (unlikely(__pyx_t_2)) { - - /* "View.MemoryView":693 - * have_slices = True - * elif not PyIndex_Check(item): - * raise TypeError, f"Cannot index with type '{type(item)}'" # <<<<<<<<<<<<<< - * result[idx] = item - * idx += 1 - */ - __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 693, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __pyx_t_5 = 0; - __pyx_t_6 = 127; - __Pyx_INCREF(__pyx_kp_u_Cannot_index_with_type); - __pyx_t_5 += 24; - __Pyx_GIVEREF(__pyx_kp_u_Cannot_index_with_type); - PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_kp_u_Cannot_index_with_type); - __pyx_t_7 = __Pyx_PyObject_FormatSimple(((PyObject *)Py_TYPE(__pyx_v_item)), __pyx_empty_unicode); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 693, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_7) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_7) : __pyx_t_6; - __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_7); - __Pyx_GIVEREF(__pyx_t_7); - PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_7); - __pyx_t_7 = 0; - __Pyx_INCREF(__pyx_kp_u__6); - __pyx_t_5 += 1; - __Pyx_GIVEREF(__pyx_kp_u__6); - PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_kp_u__6); - __pyx_t_7 = __Pyx_PyUnicode_Join(__pyx_t_3, 3, __pyx_t_5, __pyx_t_6); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 693, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - __Pyx_Raise(__pyx_builtin_TypeError, __pyx_t_7, 0, 0); - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - __PYX_ERR(1, 693, __pyx_L1_error) - - /* "View.MemoryView":692 - * if isinstance(item, slice): - * have_slices = True - * elif not PyIndex_Check(item): # <<<<<<<<<<<<<< - * raise TypeError, f"Cannot index with type '{type(item)}'" - * result[idx] = item - */ - } - __pyx_L7:; - - /* "View.MemoryView":694 - * elif not PyIndex_Check(item): - * raise TypeError, f"Cannot index with type '{type(item)}'" - * result[idx] = item # <<<<<<<<<<<<<< - * idx += 1 - * - */ - if (unlikely((__Pyx_SetItemInt(__pyx_v_result, __pyx_v_idx, __pyx_v_item, Py_ssize_t, 1, PyInt_FromSsize_t, 1, 1, 1) < 0))) __PYX_ERR(1, 694, __pyx_L1_error) - } - __pyx_L5:; - - /* "View.MemoryView":695 - * raise TypeError, f"Cannot index with type '{type(item)}'" - * result[idx] = item - * idx += 1 # <<<<<<<<<<<<<< - * - * nslices = ndim - idx - */ - __pyx_v_idx = (__pyx_v_idx + 1); - - /* "View.MemoryView":683 - * seen_ellipsis = False - * idx = 0 - * for item in tup: # <<<<<<<<<<<<<< - * if item is Ellipsis: - * if not seen_ellipsis: - */ - } - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - - /* "View.MemoryView":697 - * idx += 1 - * - * nslices = ndim - idx # <<<<<<<<<<<<<< - * return have_slices or nslices, tuple(result) - * - */ - __pyx_v_nslices = (__pyx_v_ndim - __pyx_v_idx); - - /* "View.MemoryView":698 - * - * nslices = ndim - idx - * return have_slices or nslices, tuple(result) # <<<<<<<<<<<<<< - * - * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: - */ - __Pyx_XDECREF(__pyx_r); - if (!__pyx_v_have_slices) { - } else { - __pyx_t_7 = __Pyx_PyBool_FromLong(__pyx_v_have_slices); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 698, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __pyx_t_1 = __pyx_t_7; - __pyx_t_7 = 0; - goto __pyx_L9_bool_binop_done; - } - __pyx_t_7 = PyInt_FromSsize_t(__pyx_v_nslices); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 698, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __pyx_t_1 = __pyx_t_7; - __pyx_t_7 = 0; - __pyx_L9_bool_binop_done:; - __pyx_t_7 = PyList_AsTuple(__pyx_v_result); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 698, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 698, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __Pyx_GIVEREF(__pyx_t_1); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_1)) __PYX_ERR(1, 698, __pyx_L1_error); - __Pyx_GIVEREF(__pyx_t_7); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_7)) __PYX_ERR(1, 698, __pyx_L1_error); - __pyx_t_1 = 0; - __pyx_t_7 = 0; - __pyx_r = ((PyObject*)__pyx_t_3); - __pyx_t_3 = 0; - goto __pyx_L0; - - /* "View.MemoryView":671 - * return isinstance(o, memoryview) - * - * cdef tuple _unellipsify(object index, int ndim): # <<<<<<<<<<<<<< - * """ - * Replace all ellipses with full slices and fill incomplete indices with - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_1); - __Pyx_XDECREF(__pyx_t_3); - __Pyx_XDECREF(__pyx_t_7); - __Pyx_AddTraceback("View.MemoryView._unellipsify", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = 0; - __pyx_L0:; - __Pyx_XDECREF(__pyx_v_tup); - __Pyx_XDECREF(__pyx_v_result); - __Pyx_XDECREF(__pyx_v_item); - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "View.MemoryView":700 - * return have_slices or nslices, tuple(result) - * - * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: # <<<<<<<<<<<<<< - * for suboffset in suboffsets[:ndim]: - * if suboffset >= 0: - */ - -static int assert_direct_dimensions(Py_ssize_t *__pyx_v_suboffsets, int __pyx_v_ndim) { - Py_ssize_t __pyx_v_suboffset; - int __pyx_r; - Py_ssize_t *__pyx_t_1; - Py_ssize_t *__pyx_t_2; - Py_ssize_t *__pyx_t_3; - int __pyx_t_4; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - - /* "View.MemoryView":701 - * - * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: - * for suboffset in suboffsets[:ndim]: # <<<<<<<<<<<<<< - * if suboffset >= 0: - * raise ValueError, "Indirect dimensions not supported" - */ - __pyx_t_2 = (__pyx_v_suboffsets + __pyx_v_ndim); - for (__pyx_t_3 = __pyx_v_suboffsets; __pyx_t_3 < __pyx_t_2; __pyx_t_3++) { - __pyx_t_1 = __pyx_t_3; - __pyx_v_suboffset = (__pyx_t_1[0]); - - /* "View.MemoryView":702 - * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: - * for suboffset in suboffsets[:ndim]: - * if suboffset >= 0: # <<<<<<<<<<<<<< - * raise ValueError, "Indirect dimensions not supported" - * return 0 # return type just used as an error flag - */ - __pyx_t_4 = (__pyx_v_suboffset >= 0); - if (unlikely(__pyx_t_4)) { - - /* "View.MemoryView":703 - * for suboffset in suboffsets[:ndim]: - * if suboffset >= 0: - * raise ValueError, "Indirect dimensions not supported" # <<<<<<<<<<<<<< - * return 0 # return type just used as an error flag - * - */ - __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Indirect_dimensions_not_supporte, 0, 0); - __PYX_ERR(1, 703, __pyx_L1_error) - - /* "View.MemoryView":702 - * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: - * for suboffset in suboffsets[:ndim]: - * if suboffset >= 0: # <<<<<<<<<<<<<< - * raise ValueError, "Indirect dimensions not supported" - * return 0 # return type just used as an error flag - */ - } - } - - /* "View.MemoryView":704 - * if suboffset >= 0: - * raise ValueError, "Indirect dimensions not supported" - * return 0 # return type just used as an error flag # <<<<<<<<<<<<<< - * - * - */ - __pyx_r = 0; - goto __pyx_L0; - - /* "View.MemoryView":700 - * return have_slices or nslices, tuple(result) - * - * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: # <<<<<<<<<<<<<< - * for suboffset in suboffsets[:ndim]: - * if suboffset >= 0: - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_AddTraceback("View.MemoryView.assert_direct_dimensions", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = -1; - __pyx_L0:; - return __pyx_r; -} - -/* "View.MemoryView":711 - * - * @cname('__pyx_memview_slice') - * cdef memoryview memview_slice(memoryview memview, object indices): # <<<<<<<<<<<<<< - * cdef int new_ndim = 0, suboffset_dim = -1, dim - * cdef bint negative_step - */ - -static struct __pyx_memoryview_obj *__pyx_memview_slice(struct __pyx_memoryview_obj *__pyx_v_memview, PyObject *__pyx_v_indices) { - int __pyx_v_new_ndim; - int __pyx_v_suboffset_dim; - int __pyx_v_dim; - __Pyx_memviewslice __pyx_v_src; - __Pyx_memviewslice __pyx_v_dst; - __Pyx_memviewslice *__pyx_v_p_src; - struct __pyx_memoryviewslice_obj *__pyx_v_memviewsliceobj = 0; - __Pyx_memviewslice *__pyx_v_p_dst; - int *__pyx_v_p_suboffset_dim; - Py_ssize_t __pyx_v_start; - Py_ssize_t __pyx_v_stop; - Py_ssize_t __pyx_v_step; - Py_ssize_t __pyx_v_cindex; - int __pyx_v_have_start; - int __pyx_v_have_stop; - int __pyx_v_have_step; - PyObject *__pyx_v_index = NULL; - struct __pyx_memoryview_obj *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - int __pyx_t_1; - PyObject *__pyx_t_2 = NULL; - struct __pyx_memoryview_obj *__pyx_t_3; - char *__pyx_t_4; - int __pyx_t_5; - Py_ssize_t __pyx_t_6; - PyObject *(*__pyx_t_7)(PyObject *); - PyObject *__pyx_t_8 = NULL; - Py_ssize_t __pyx_t_9; - int __pyx_t_10; - Py_ssize_t __pyx_t_11; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("memview_slice", 1); - - /* "View.MemoryView":712 - * @cname('__pyx_memview_slice') - * cdef memoryview memview_slice(memoryview memview, object indices): - * cdef int new_ndim = 0, suboffset_dim = -1, dim # <<<<<<<<<<<<<< - * cdef bint negative_step - * cdef __Pyx_memviewslice src, dst - */ - __pyx_v_new_ndim = 0; - __pyx_v_suboffset_dim = -1; - - /* "View.MemoryView":719 - * - * - * memset(&dst, 0, sizeof(dst)) # <<<<<<<<<<<<<< - * - * cdef _memoryviewslice memviewsliceobj - */ - (void)(memset((&__pyx_v_dst), 0, (sizeof(__pyx_v_dst)))); - - /* "View.MemoryView":723 - * cdef _memoryviewslice memviewsliceobj - * - * assert memview.view.ndim > 0 # <<<<<<<<<<<<<< - * - * if isinstance(memview, _memoryviewslice): - */ - #ifndef CYTHON_WITHOUT_ASSERTIONS - if (unlikely(__pyx_assertions_enabled())) { - __pyx_t_1 = (__pyx_v_memview->view.ndim > 0); - if (unlikely(!__pyx_t_1)) { - __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); - __PYX_ERR(1, 723, __pyx_L1_error) - } - } - #else - if ((1)); else __PYX_ERR(1, 723, __pyx_L1_error) - #endif - - /* "View.MemoryView":725 - * assert memview.view.ndim > 0 - * - * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< - * memviewsliceobj = memview - * p_src = &memviewsliceobj.from_slice - */ - __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); - if (__pyx_t_1) { - - /* "View.MemoryView":726 - * - * if isinstance(memview, _memoryviewslice): - * memviewsliceobj = memview # <<<<<<<<<<<<<< - * p_src = &memviewsliceobj.from_slice - * else: - */ - if (!(likely(((((PyObject *)__pyx_v_memview)) == Py_None) || likely(__Pyx_TypeTest(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type))))) __PYX_ERR(1, 726, __pyx_L1_error) - __pyx_t_2 = ((PyObject *)__pyx_v_memview); - __Pyx_INCREF(__pyx_t_2); - __pyx_v_memviewsliceobj = ((struct __pyx_memoryviewslice_obj *)__pyx_t_2); - __pyx_t_2 = 0; - - /* "View.MemoryView":727 - * if isinstance(memview, _memoryviewslice): - * memviewsliceobj = memview - * p_src = &memviewsliceobj.from_slice # <<<<<<<<<<<<<< - * else: - * slice_copy(memview, &src) - */ - __pyx_v_p_src = (&__pyx_v_memviewsliceobj->from_slice); - - /* "View.MemoryView":725 - * assert memview.view.ndim > 0 - * - * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< - * memviewsliceobj = memview - * p_src = &memviewsliceobj.from_slice - */ - goto __pyx_L3; - } - - /* "View.MemoryView":729 - * p_src = &memviewsliceobj.from_slice - * else: - * slice_copy(memview, &src) # <<<<<<<<<<<<<< - * p_src = &src - * - */ - /*else*/ { - __pyx_memoryview_slice_copy(__pyx_v_memview, (&__pyx_v_src)); - - /* "View.MemoryView":730 - * else: - * slice_copy(memview, &src) - * p_src = &src # <<<<<<<<<<<<<< - * - * - */ - __pyx_v_p_src = (&__pyx_v_src); - } - __pyx_L3:; - - /* "View.MemoryView":736 - * - * - * dst.memview = p_src.memview # <<<<<<<<<<<<<< - * dst.data = p_src.data - * - */ - __pyx_t_3 = __pyx_v_p_src->memview; - __pyx_v_dst.memview = __pyx_t_3; - - /* "View.MemoryView":737 - * - * dst.memview = p_src.memview - * dst.data = p_src.data # <<<<<<<<<<<<<< - * - * - */ - __pyx_t_4 = __pyx_v_p_src->data; - __pyx_v_dst.data = __pyx_t_4; - - /* "View.MemoryView":742 - * - * - * cdef __Pyx_memviewslice *p_dst = &dst # <<<<<<<<<<<<<< - * cdef int *p_suboffset_dim = &suboffset_dim - * cdef Py_ssize_t start, stop, step, cindex - */ - __pyx_v_p_dst = (&__pyx_v_dst); - - /* "View.MemoryView":743 - * - * cdef __Pyx_memviewslice *p_dst = &dst - * cdef int *p_suboffset_dim = &suboffset_dim # <<<<<<<<<<<<<< - * cdef Py_ssize_t start, stop, step, cindex - * cdef bint have_start, have_stop, have_step - */ - __pyx_v_p_suboffset_dim = (&__pyx_v_suboffset_dim); - - /* "View.MemoryView":747 - * cdef bint have_start, have_stop, have_step - * - * for dim, index in enumerate(indices): # <<<<<<<<<<<<<< - * if PyIndex_Check(index): - * cindex = index - */ - __pyx_t_5 = 0; - if (likely(PyList_CheckExact(__pyx_v_indices)) || PyTuple_CheckExact(__pyx_v_indices)) { - __pyx_t_2 = __pyx_v_indices; __Pyx_INCREF(__pyx_t_2); - __pyx_t_6 = 0; - __pyx_t_7 = NULL; - } else { - __pyx_t_6 = -1; __pyx_t_2 = PyObject_GetIter(__pyx_v_indices); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 747, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __pyx_t_7 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_2); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 747, __pyx_L1_error) - } - for (;;) { - if (likely(!__pyx_t_7)) { - if (likely(PyList_CheckExact(__pyx_t_2))) { - { - Py_ssize_t __pyx_temp = __Pyx_PyList_GET_SIZE(__pyx_t_2); - #if !CYTHON_ASSUME_SAFE_MACROS - if (unlikely((__pyx_temp < 0))) __PYX_ERR(1, 747, __pyx_L1_error) - #endif - if (__pyx_t_6 >= __pyx_temp) break; - } - #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS - __pyx_t_8 = PyList_GET_ITEM(__pyx_t_2, __pyx_t_6); __Pyx_INCREF(__pyx_t_8); __pyx_t_6++; if (unlikely((0 < 0))) __PYX_ERR(1, 747, __pyx_L1_error) - #else - __pyx_t_8 = __Pyx_PySequence_ITEM(__pyx_t_2, __pyx_t_6); __pyx_t_6++; if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 747, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_8); - #endif - } else { - { - Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_2); - #if !CYTHON_ASSUME_SAFE_MACROS - if (unlikely((__pyx_temp < 0))) __PYX_ERR(1, 747, __pyx_L1_error) - #endif - if (__pyx_t_6 >= __pyx_temp) break; - } - #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS - __pyx_t_8 = PyTuple_GET_ITEM(__pyx_t_2, __pyx_t_6); __Pyx_INCREF(__pyx_t_8); __pyx_t_6++; if (unlikely((0 < 0))) __PYX_ERR(1, 747, __pyx_L1_error) - #else - __pyx_t_8 = __Pyx_PySequence_ITEM(__pyx_t_2, __pyx_t_6); __pyx_t_6++; if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 747, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_8); - #endif - } - } else { - __pyx_t_8 = __pyx_t_7(__pyx_t_2); - if (unlikely(!__pyx_t_8)) { - PyObject* exc_type = PyErr_Occurred(); - if (exc_type) { - if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); - else __PYX_ERR(1, 747, __pyx_L1_error) - } - break; - } - __Pyx_GOTREF(__pyx_t_8); - } - __Pyx_XDECREF_SET(__pyx_v_index, __pyx_t_8); - __pyx_t_8 = 0; - __pyx_v_dim = __pyx_t_5; - __pyx_t_5 = (__pyx_t_5 + 1); - - /* "View.MemoryView":748 - * - * for dim, index in enumerate(indices): - * if PyIndex_Check(index): # <<<<<<<<<<<<<< - * cindex = index - * slice_memviewslice( - */ - __pyx_t_1 = (PyIndex_Check(__pyx_v_index) != 0); - if (__pyx_t_1) { - - /* "View.MemoryView":749 - * for dim, index in enumerate(indices): - * if PyIndex_Check(index): - * cindex = index # <<<<<<<<<<<<<< - * slice_memviewslice( - * p_dst, p_src.shape[dim], p_src.strides[dim], p_src.suboffsets[dim], - */ - __pyx_t_9 = __Pyx_PyIndex_AsSsize_t(__pyx_v_index); if (unlikely((__pyx_t_9 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 749, __pyx_L1_error) - __pyx_v_cindex = __pyx_t_9; - - /* "View.MemoryView":750 - * if PyIndex_Check(index): - * cindex = index - * slice_memviewslice( # <<<<<<<<<<<<<< - * p_dst, p_src.shape[dim], p_src.strides[dim], p_src.suboffsets[dim], - * dim, new_ndim, p_suboffset_dim, - */ - __pyx_t_10 = __pyx_memoryview_slice_memviewslice(__pyx_v_p_dst, (__pyx_v_p_src->shape[__pyx_v_dim]), (__pyx_v_p_src->strides[__pyx_v_dim]), (__pyx_v_p_src->suboffsets[__pyx_v_dim]), __pyx_v_dim, __pyx_v_new_ndim, __pyx_v_p_suboffset_dim, __pyx_v_cindex, 0, 0, 0, 0, 0, 0); if (unlikely(__pyx_t_10 == ((int)-1))) __PYX_ERR(1, 750, __pyx_L1_error) - - /* "View.MemoryView":748 - * - * for dim, index in enumerate(indices): - * if PyIndex_Check(index): # <<<<<<<<<<<<<< - * cindex = index - * slice_memviewslice( - */ - goto __pyx_L6; - } - - /* "View.MemoryView":756 - * 0, 0, 0, # have_{start,stop,step} - * False) - * elif index is None: # <<<<<<<<<<<<<< - * p_dst.shape[new_ndim] = 1 - * p_dst.strides[new_ndim] = 0 - */ - __pyx_t_1 = (__pyx_v_index == Py_None); - if (__pyx_t_1) { - - /* "View.MemoryView":757 - * False) - * elif index is None: - * p_dst.shape[new_ndim] = 1 # <<<<<<<<<<<<<< - * p_dst.strides[new_ndim] = 0 - * p_dst.suboffsets[new_ndim] = -1 - */ - (__pyx_v_p_dst->shape[__pyx_v_new_ndim]) = 1; - - /* "View.MemoryView":758 - * elif index is None: - * p_dst.shape[new_ndim] = 1 - * p_dst.strides[new_ndim] = 0 # <<<<<<<<<<<<<< - * p_dst.suboffsets[new_ndim] = -1 - * new_ndim += 1 - */ - (__pyx_v_p_dst->strides[__pyx_v_new_ndim]) = 0; - - /* "View.MemoryView":759 - * p_dst.shape[new_ndim] = 1 - * p_dst.strides[new_ndim] = 0 - * p_dst.suboffsets[new_ndim] = -1 # <<<<<<<<<<<<<< - * new_ndim += 1 - * else: - */ - (__pyx_v_p_dst->suboffsets[__pyx_v_new_ndim]) = -1L; - - /* "View.MemoryView":760 - * p_dst.strides[new_ndim] = 0 - * p_dst.suboffsets[new_ndim] = -1 - * new_ndim += 1 # <<<<<<<<<<<<<< - * else: - * start = index.start or 0 - */ - __pyx_v_new_ndim = (__pyx_v_new_ndim + 1); - - /* "View.MemoryView":756 - * 0, 0, 0, # have_{start,stop,step} - * False) - * elif index is None: # <<<<<<<<<<<<<< - * p_dst.shape[new_ndim] = 1 - * p_dst.strides[new_ndim] = 0 - */ - goto __pyx_L6; - } - - /* "View.MemoryView":762 - * new_ndim += 1 - * else: - * start = index.start or 0 # <<<<<<<<<<<<<< - * stop = index.stop or 0 - * step = index.step or 0 - */ - /*else*/ { - __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_start); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 762, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_8); - __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_t_8); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 762, __pyx_L1_error) - if (!__pyx_t_1) { - __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; - } else { - __pyx_t_11 = __Pyx_PyIndex_AsSsize_t(__pyx_t_8); if (unlikely((__pyx_t_11 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 762, __pyx_L1_error) - __pyx_t_9 = __pyx_t_11; - __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; - goto __pyx_L7_bool_binop_done; - } - __pyx_t_9 = 0; - __pyx_L7_bool_binop_done:; - __pyx_v_start = __pyx_t_9; - - /* "View.MemoryView":763 - * else: - * start = index.start or 0 - * stop = index.stop or 0 # <<<<<<<<<<<<<< - * step = index.step or 0 - * - */ - __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_stop); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 763, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_8); - __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_t_8); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 763, __pyx_L1_error) - if (!__pyx_t_1) { - __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; - } else { - __pyx_t_11 = __Pyx_PyIndex_AsSsize_t(__pyx_t_8); if (unlikely((__pyx_t_11 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 763, __pyx_L1_error) - __pyx_t_9 = __pyx_t_11; - __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; - goto __pyx_L9_bool_binop_done; - } - __pyx_t_9 = 0; - __pyx_L9_bool_binop_done:; - __pyx_v_stop = __pyx_t_9; - - /* "View.MemoryView":764 - * start = index.start or 0 - * stop = index.stop or 0 - * step = index.step or 0 # <<<<<<<<<<<<<< - * - * have_start = index.start is not None - */ - __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_step); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 764, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_8); - __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_t_8); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 764, __pyx_L1_error) - if (!__pyx_t_1) { - __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; - } else { - __pyx_t_11 = __Pyx_PyIndex_AsSsize_t(__pyx_t_8); if (unlikely((__pyx_t_11 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 764, __pyx_L1_error) - __pyx_t_9 = __pyx_t_11; - __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; - goto __pyx_L11_bool_binop_done; - } - __pyx_t_9 = 0; - __pyx_L11_bool_binop_done:; - __pyx_v_step = __pyx_t_9; - - /* "View.MemoryView":766 - * step = index.step or 0 - * - * have_start = index.start is not None # <<<<<<<<<<<<<< - * have_stop = index.stop is not None - * have_step = index.step is not None - */ - __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_start); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 766, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_8); - __pyx_t_1 = (__pyx_t_8 != Py_None); - __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; - __pyx_v_have_start = __pyx_t_1; - - /* "View.MemoryView":767 - * - * have_start = index.start is not None - * have_stop = index.stop is not None # <<<<<<<<<<<<<< - * have_step = index.step is not None - * - */ - __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_stop); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 767, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_8); - __pyx_t_1 = (__pyx_t_8 != Py_None); - __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; - __pyx_v_have_stop = __pyx_t_1; - - /* "View.MemoryView":768 - * have_start = index.start is not None - * have_stop = index.stop is not None - * have_step = index.step is not None # <<<<<<<<<<<<<< - * - * slice_memviewslice( - */ - __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_step); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 768, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_8); - __pyx_t_1 = (__pyx_t_8 != Py_None); - __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; - __pyx_v_have_step = __pyx_t_1; - - /* "View.MemoryView":770 - * have_step = index.step is not None - * - * slice_memviewslice( # <<<<<<<<<<<<<< - * p_dst, p_src.shape[dim], p_src.strides[dim], p_src.suboffsets[dim], - * dim, new_ndim, p_suboffset_dim, - */ - __pyx_t_10 = __pyx_memoryview_slice_memviewslice(__pyx_v_p_dst, (__pyx_v_p_src->shape[__pyx_v_dim]), (__pyx_v_p_src->strides[__pyx_v_dim]), (__pyx_v_p_src->suboffsets[__pyx_v_dim]), __pyx_v_dim, __pyx_v_new_ndim, __pyx_v_p_suboffset_dim, __pyx_v_start, __pyx_v_stop, __pyx_v_step, __pyx_v_have_start, __pyx_v_have_stop, __pyx_v_have_step, 1); if (unlikely(__pyx_t_10 == ((int)-1))) __PYX_ERR(1, 770, __pyx_L1_error) - - /* "View.MemoryView":776 - * have_start, have_stop, have_step, - * True) - * new_ndim += 1 # <<<<<<<<<<<<<< - * - * if isinstance(memview, _memoryviewslice): - */ - __pyx_v_new_ndim = (__pyx_v_new_ndim + 1); - } - __pyx_L6:; - - /* "View.MemoryView":747 - * cdef bint have_start, have_stop, have_step - * - * for dim, index in enumerate(indices): # <<<<<<<<<<<<<< - * if PyIndex_Check(index): - * cindex = index - */ - } - __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - - /* "View.MemoryView":778 - * new_ndim += 1 - * - * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< - * return memoryview_fromslice(dst, new_ndim, - * memviewsliceobj.to_object_func, - */ - __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); - if (__pyx_t_1) { - - /* "View.MemoryView":779 - * - * if isinstance(memview, _memoryviewslice): - * return memoryview_fromslice(dst, new_ndim, # <<<<<<<<<<<<<< - * memviewsliceobj.to_object_func, - * memviewsliceobj.to_dtype_func, - */ - __Pyx_XDECREF((PyObject *)__pyx_r); - - /* "View.MemoryView":780 - * if isinstance(memview, _memoryviewslice): - * return memoryview_fromslice(dst, new_ndim, - * memviewsliceobj.to_object_func, # <<<<<<<<<<<<<< - * memviewsliceobj.to_dtype_func, - * memview.dtype_is_object) - */ - if (unlikely(!__pyx_v_memviewsliceobj)) { __Pyx_RaiseUnboundLocalError("memviewsliceobj"); __PYX_ERR(1, 780, __pyx_L1_error) } - - /* "View.MemoryView":781 - * return memoryview_fromslice(dst, new_ndim, - * memviewsliceobj.to_object_func, - * memviewsliceobj.to_dtype_func, # <<<<<<<<<<<<<< - * memview.dtype_is_object) - * else: - */ - if (unlikely(!__pyx_v_memviewsliceobj)) { __Pyx_RaiseUnboundLocalError("memviewsliceobj"); __PYX_ERR(1, 781, __pyx_L1_error) } - - /* "View.MemoryView":779 - * - * if isinstance(memview, _memoryviewslice): - * return memoryview_fromslice(dst, new_ndim, # <<<<<<<<<<<<<< - * memviewsliceobj.to_object_func, - * memviewsliceobj.to_dtype_func, - */ - __pyx_t_2 = __pyx_memoryview_fromslice(__pyx_v_dst, __pyx_v_new_ndim, __pyx_v_memviewsliceobj->to_object_func, __pyx_v_memviewsliceobj->to_dtype_func, __pyx_v_memview->dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 779, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - if (!(likely(((__pyx_t_2) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_2, __pyx_memoryview_type))))) __PYX_ERR(1, 779, __pyx_L1_error) - __pyx_r = ((struct __pyx_memoryview_obj *)__pyx_t_2); - __pyx_t_2 = 0; - goto __pyx_L0; - - /* "View.MemoryView":778 - * new_ndim += 1 - * - * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< - * return memoryview_fromslice(dst, new_ndim, - * memviewsliceobj.to_object_func, - */ - } - - /* "View.MemoryView":784 - * memview.dtype_is_object) - * else: - * return memoryview_fromslice(dst, new_ndim, NULL, NULL, # <<<<<<<<<<<<<< - * memview.dtype_is_object) - * - */ - /*else*/ { - __Pyx_XDECREF((PyObject *)__pyx_r); - - /* "View.MemoryView":785 - * else: - * return memoryview_fromslice(dst, new_ndim, NULL, NULL, - * memview.dtype_is_object) # <<<<<<<<<<<<<< - * - * - */ - __pyx_t_2 = __pyx_memoryview_fromslice(__pyx_v_dst, __pyx_v_new_ndim, NULL, NULL, __pyx_v_memview->dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 784, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - - /* "View.MemoryView":784 - * memview.dtype_is_object) - * else: - * return memoryview_fromslice(dst, new_ndim, NULL, NULL, # <<<<<<<<<<<<<< - * memview.dtype_is_object) - * - */ - if (!(likely(((__pyx_t_2) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_2, __pyx_memoryview_type))))) __PYX_ERR(1, 784, __pyx_L1_error) - __pyx_r = ((struct __pyx_memoryview_obj *)__pyx_t_2); - __pyx_t_2 = 0; - goto __pyx_L0; - } - - /* "View.MemoryView":711 - * - * @cname('__pyx_memview_slice') - * cdef memoryview memview_slice(memoryview memview, object indices): # <<<<<<<<<<<<<< - * cdef int new_ndim = 0, suboffset_dim = -1, dim - * cdef bint negative_step - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_2); - __Pyx_XDECREF(__pyx_t_8); - __Pyx_AddTraceback("View.MemoryView.memview_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = 0; - __pyx_L0:; - __Pyx_XDECREF((PyObject *)__pyx_v_memviewsliceobj); - __Pyx_XDECREF(__pyx_v_index); - __Pyx_XGIVEREF((PyObject *)__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "View.MemoryView":793 - * - * @cname('__pyx_memoryview_slice_memviewslice') - * cdef int slice_memviewslice( # <<<<<<<<<<<<<< - * __Pyx_memviewslice *dst, - * Py_ssize_t shape, Py_ssize_t stride, Py_ssize_t suboffset, - */ - -static int __pyx_memoryview_slice_memviewslice(__Pyx_memviewslice *__pyx_v_dst, Py_ssize_t __pyx_v_shape, Py_ssize_t __pyx_v_stride, Py_ssize_t __pyx_v_suboffset, int __pyx_v_dim, int __pyx_v_new_ndim, int *__pyx_v_suboffset_dim, Py_ssize_t __pyx_v_start, Py_ssize_t __pyx_v_stop, Py_ssize_t __pyx_v_step, int __pyx_v_have_start, int __pyx_v_have_stop, int __pyx_v_have_step, int __pyx_v_is_slice) { - Py_ssize_t __pyx_v_new_shape; - int __pyx_v_negative_step; - int __pyx_r; - int __pyx_t_1; - int __pyx_t_2; - int __pyx_t_3; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - #ifdef WITH_THREAD - PyGILState_STATE __pyx_gilstate_save; - #endif - - /* "View.MemoryView":813 - * cdef bint negative_step - * - * if not is_slice: # <<<<<<<<<<<<<< - * - * if start < 0: - */ - __pyx_t_1 = (!__pyx_v_is_slice); - if (__pyx_t_1) { - - /* "View.MemoryView":815 - * if not is_slice: - * - * if start < 0: # <<<<<<<<<<<<<< - * start += shape - * if not 0 <= start < shape: - */ - __pyx_t_1 = (__pyx_v_start < 0); - if (__pyx_t_1) { - - /* "View.MemoryView":816 - * - * if start < 0: - * start += shape # <<<<<<<<<<<<<< - * if not 0 <= start < shape: - * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) - */ - __pyx_v_start = (__pyx_v_start + __pyx_v_shape); - - /* "View.MemoryView":815 - * if not is_slice: - * - * if start < 0: # <<<<<<<<<<<<<< - * start += shape - * if not 0 <= start < shape: - */ - } - - /* "View.MemoryView":817 - * if start < 0: - * start += shape - * if not 0 <= start < shape: # <<<<<<<<<<<<<< - * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) - * else: - */ - __pyx_t_1 = (0 <= __pyx_v_start); - if (__pyx_t_1) { - __pyx_t_1 = (__pyx_v_start < __pyx_v_shape); - } - __pyx_t_2 = (!__pyx_t_1); - if (__pyx_t_2) { - - /* "View.MemoryView":818 - * start += shape - * if not 0 <= start < shape: - * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) # <<<<<<<<<<<<<< - * else: - * - */ - __pyx_t_3 = __pyx_memoryview_err_dim(PyExc_IndexError, __pyx_kp_s_Index_out_of_bounds_axis_d, __pyx_v_dim); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(1, 818, __pyx_L1_error) - - /* "View.MemoryView":817 - * if start < 0: - * start += shape - * if not 0 <= start < shape: # <<<<<<<<<<<<<< - * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) - * else: - */ - } - - /* "View.MemoryView":813 - * cdef bint negative_step - * - * if not is_slice: # <<<<<<<<<<<<<< - * - * if start < 0: - */ - goto __pyx_L3; - } - - /* "View.MemoryView":821 - * else: - * - * if have_step: # <<<<<<<<<<<<<< - * negative_step = step < 0 - * if step == 0: - */ - /*else*/ { - __pyx_t_2 = (__pyx_v_have_step != 0); - if (__pyx_t_2) { - - /* "View.MemoryView":822 - * - * if have_step: - * negative_step = step < 0 # <<<<<<<<<<<<<< - * if step == 0: - * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) - */ - __pyx_v_negative_step = (__pyx_v_step < 0); - - /* "View.MemoryView":823 - * if have_step: - * negative_step = step < 0 - * if step == 0: # <<<<<<<<<<<<<< - * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) - * else: - */ - __pyx_t_2 = (__pyx_v_step == 0); - if (__pyx_t_2) { - - /* "View.MemoryView":824 - * negative_step = step < 0 - * if step == 0: - * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) # <<<<<<<<<<<<<< - * else: - * negative_step = False - */ - __pyx_t_3 = __pyx_memoryview_err_dim(PyExc_ValueError, __pyx_kp_s_Step_may_not_be_zero_axis_d, __pyx_v_dim); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(1, 824, __pyx_L1_error) - - /* "View.MemoryView":823 - * if have_step: - * negative_step = step < 0 - * if step == 0: # <<<<<<<<<<<<<< - * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) - * else: - */ - } - - /* "View.MemoryView":821 - * else: - * - * if have_step: # <<<<<<<<<<<<<< - * negative_step = step < 0 - * if step == 0: - */ - goto __pyx_L6; - } - - /* "View.MemoryView":826 - * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) - * else: - * negative_step = False # <<<<<<<<<<<<<< - * step = 1 - * - */ - /*else*/ { - __pyx_v_negative_step = 0; - - /* "View.MemoryView":827 - * else: - * negative_step = False - * step = 1 # <<<<<<<<<<<<<< - * - * - */ - __pyx_v_step = 1; - } - __pyx_L6:; - - /* "View.MemoryView":830 - * - * - * if have_start: # <<<<<<<<<<<<<< - * if start < 0: - * start += shape - */ - __pyx_t_2 = (__pyx_v_have_start != 0); - if (__pyx_t_2) { - - /* "View.MemoryView":831 - * - * if have_start: - * if start < 0: # <<<<<<<<<<<<<< - * start += shape - * if start < 0: - */ - __pyx_t_2 = (__pyx_v_start < 0); - if (__pyx_t_2) { - - /* "View.MemoryView":832 - * if have_start: - * if start < 0: - * start += shape # <<<<<<<<<<<<<< - * if start < 0: - * start = 0 - */ - __pyx_v_start = (__pyx_v_start + __pyx_v_shape); - - /* "View.MemoryView":833 - * if start < 0: - * start += shape - * if start < 0: # <<<<<<<<<<<<<< - * start = 0 - * elif start >= shape: - */ - __pyx_t_2 = (__pyx_v_start < 0); - if (__pyx_t_2) { - - /* "View.MemoryView":834 - * start += shape - * if start < 0: - * start = 0 # <<<<<<<<<<<<<< - * elif start >= shape: - * if negative_step: - */ - __pyx_v_start = 0; - - /* "View.MemoryView":833 - * if start < 0: - * start += shape - * if start < 0: # <<<<<<<<<<<<<< - * start = 0 - * elif start >= shape: - */ - } - - /* "View.MemoryView":831 - * - * if have_start: - * if start < 0: # <<<<<<<<<<<<<< - * start += shape - * if start < 0: - */ - goto __pyx_L9; - } - - /* "View.MemoryView":835 - * if start < 0: - * start = 0 - * elif start >= shape: # <<<<<<<<<<<<<< - * if negative_step: - * start = shape - 1 - */ - __pyx_t_2 = (__pyx_v_start >= __pyx_v_shape); - if (__pyx_t_2) { - - /* "View.MemoryView":836 - * start = 0 - * elif start >= shape: - * if negative_step: # <<<<<<<<<<<<<< - * start = shape - 1 - * else: - */ - if (__pyx_v_negative_step) { - - /* "View.MemoryView":837 - * elif start >= shape: - * if negative_step: - * start = shape - 1 # <<<<<<<<<<<<<< - * else: - * start = shape - */ - __pyx_v_start = (__pyx_v_shape - 1); - - /* "View.MemoryView":836 - * start = 0 - * elif start >= shape: - * if negative_step: # <<<<<<<<<<<<<< - * start = shape - 1 - * else: - */ - goto __pyx_L11; - } - - /* "View.MemoryView":839 - * start = shape - 1 - * else: - * start = shape # <<<<<<<<<<<<<< - * else: - * if negative_step: - */ - /*else*/ { - __pyx_v_start = __pyx_v_shape; - } - __pyx_L11:; - - /* "View.MemoryView":835 - * if start < 0: - * start = 0 - * elif start >= shape: # <<<<<<<<<<<<<< - * if negative_step: - * start = shape - 1 - */ - } - __pyx_L9:; - - /* "View.MemoryView":830 - * - * - * if have_start: # <<<<<<<<<<<<<< - * if start < 0: - * start += shape - */ - goto __pyx_L8; - } - - /* "View.MemoryView":841 - * start = shape - * else: - * if negative_step: # <<<<<<<<<<<<<< - * start = shape - 1 - * else: - */ - /*else*/ { - if (__pyx_v_negative_step) { - - /* "View.MemoryView":842 - * else: - * if negative_step: - * start = shape - 1 # <<<<<<<<<<<<<< - * else: - * start = 0 - */ - __pyx_v_start = (__pyx_v_shape - 1); - - /* "View.MemoryView":841 - * start = shape - * else: - * if negative_step: # <<<<<<<<<<<<<< - * start = shape - 1 - * else: - */ - goto __pyx_L12; - } - - /* "View.MemoryView":844 - * start = shape - 1 - * else: - * start = 0 # <<<<<<<<<<<<<< - * - * if have_stop: - */ - /*else*/ { - __pyx_v_start = 0; - } - __pyx_L12:; - } - __pyx_L8:; - - /* "View.MemoryView":846 - * start = 0 - * - * if have_stop: # <<<<<<<<<<<<<< - * if stop < 0: - * stop += shape - */ - __pyx_t_2 = (__pyx_v_have_stop != 0); - if (__pyx_t_2) { - - /* "View.MemoryView":847 - * - * if have_stop: - * if stop < 0: # <<<<<<<<<<<<<< - * stop += shape - * if stop < 0: - */ - __pyx_t_2 = (__pyx_v_stop < 0); - if (__pyx_t_2) { - - /* "View.MemoryView":848 - * if have_stop: - * if stop < 0: - * stop += shape # <<<<<<<<<<<<<< - * if stop < 0: - * stop = 0 - */ - __pyx_v_stop = (__pyx_v_stop + __pyx_v_shape); - - /* "View.MemoryView":849 - * if stop < 0: - * stop += shape - * if stop < 0: # <<<<<<<<<<<<<< - * stop = 0 - * elif stop > shape: - */ - __pyx_t_2 = (__pyx_v_stop < 0); - if (__pyx_t_2) { - - /* "View.MemoryView":850 - * stop += shape - * if stop < 0: - * stop = 0 # <<<<<<<<<<<<<< - * elif stop > shape: - * stop = shape - */ - __pyx_v_stop = 0; - - /* "View.MemoryView":849 - * if stop < 0: - * stop += shape - * if stop < 0: # <<<<<<<<<<<<<< - * stop = 0 - * elif stop > shape: - */ - } - - /* "View.MemoryView":847 - * - * if have_stop: - * if stop < 0: # <<<<<<<<<<<<<< - * stop += shape - * if stop < 0: - */ - goto __pyx_L14; - } - - /* "View.MemoryView":851 - * if stop < 0: - * stop = 0 - * elif stop > shape: # <<<<<<<<<<<<<< - * stop = shape - * else: - */ - __pyx_t_2 = (__pyx_v_stop > __pyx_v_shape); - if (__pyx_t_2) { - - /* "View.MemoryView":852 - * stop = 0 - * elif stop > shape: - * stop = shape # <<<<<<<<<<<<<< - * else: - * if negative_step: - */ - __pyx_v_stop = __pyx_v_shape; - - /* "View.MemoryView":851 - * if stop < 0: - * stop = 0 - * elif stop > shape: # <<<<<<<<<<<<<< - * stop = shape - * else: - */ - } - __pyx_L14:; - - /* "View.MemoryView":846 - * start = 0 - * - * if have_stop: # <<<<<<<<<<<<<< - * if stop < 0: - * stop += shape - */ - goto __pyx_L13; - } - - /* "View.MemoryView":854 - * stop = shape - * else: - * if negative_step: # <<<<<<<<<<<<<< - * stop = -1 - * else: - */ - /*else*/ { - if (__pyx_v_negative_step) { - - /* "View.MemoryView":855 - * else: - * if negative_step: - * stop = -1 # <<<<<<<<<<<<<< - * else: - * stop = shape - */ - __pyx_v_stop = -1L; - - /* "View.MemoryView":854 - * stop = shape - * else: - * if negative_step: # <<<<<<<<<<<<<< - * stop = -1 - * else: - */ - goto __pyx_L16; - } - - /* "View.MemoryView":857 - * stop = -1 - * else: - * stop = shape # <<<<<<<<<<<<<< - * - * - */ - /*else*/ { - __pyx_v_stop = __pyx_v_shape; - } - __pyx_L16:; - } - __pyx_L13:; - - /* "View.MemoryView":861 - * - * with cython.cdivision(True): - * new_shape = (stop - start) // step # <<<<<<<<<<<<<< - * - * if (stop - start) - step * new_shape: - */ - __pyx_v_new_shape = ((__pyx_v_stop - __pyx_v_start) / __pyx_v_step); - - /* "View.MemoryView":863 - * new_shape = (stop - start) // step - * - * if (stop - start) - step * new_shape: # <<<<<<<<<<<<<< - * new_shape += 1 - * - */ - __pyx_t_2 = (((__pyx_v_stop - __pyx_v_start) - (__pyx_v_step * __pyx_v_new_shape)) != 0); - if (__pyx_t_2) { - - /* "View.MemoryView":864 - * - * if (stop - start) - step * new_shape: - * new_shape += 1 # <<<<<<<<<<<<<< - * - * if new_shape < 0: - */ - __pyx_v_new_shape = (__pyx_v_new_shape + 1); - - /* "View.MemoryView":863 - * new_shape = (stop - start) // step - * - * if (stop - start) - step * new_shape: # <<<<<<<<<<<<<< - * new_shape += 1 - * - */ - } - - /* "View.MemoryView":866 - * new_shape += 1 - * - * if new_shape < 0: # <<<<<<<<<<<<<< - * new_shape = 0 - * - */ - __pyx_t_2 = (__pyx_v_new_shape < 0); - if (__pyx_t_2) { - - /* "View.MemoryView":867 - * - * if new_shape < 0: - * new_shape = 0 # <<<<<<<<<<<<<< - * - * - */ - __pyx_v_new_shape = 0; - - /* "View.MemoryView":866 - * new_shape += 1 - * - * if new_shape < 0: # <<<<<<<<<<<<<< - * new_shape = 0 - * - */ - } - - /* "View.MemoryView":870 - * - * - * dst.strides[new_ndim] = stride * step # <<<<<<<<<<<<<< - * dst.shape[new_ndim] = new_shape - * dst.suboffsets[new_ndim] = suboffset - */ - (__pyx_v_dst->strides[__pyx_v_new_ndim]) = (__pyx_v_stride * __pyx_v_step); - - /* "View.MemoryView":871 - * - * dst.strides[new_ndim] = stride * step - * dst.shape[new_ndim] = new_shape # <<<<<<<<<<<<<< - * dst.suboffsets[new_ndim] = suboffset - * - */ - (__pyx_v_dst->shape[__pyx_v_new_ndim]) = __pyx_v_new_shape; - - /* "View.MemoryView":872 - * dst.strides[new_ndim] = stride * step - * dst.shape[new_ndim] = new_shape - * dst.suboffsets[new_ndim] = suboffset # <<<<<<<<<<<<<< - * - * - */ - (__pyx_v_dst->suboffsets[__pyx_v_new_ndim]) = __pyx_v_suboffset; - } - __pyx_L3:; - - /* "View.MemoryView":875 - * - * - * if suboffset_dim[0] < 0: # <<<<<<<<<<<<<< - * dst.data += start * stride - * else: - */ - __pyx_t_2 = ((__pyx_v_suboffset_dim[0]) < 0); - if (__pyx_t_2) { - - /* "View.MemoryView":876 - * - * if suboffset_dim[0] < 0: - * dst.data += start * stride # <<<<<<<<<<<<<< - * else: - * dst.suboffsets[suboffset_dim[0]] += start * stride - */ - __pyx_v_dst->data = (__pyx_v_dst->data + (__pyx_v_start * __pyx_v_stride)); - - /* "View.MemoryView":875 - * - * - * if suboffset_dim[0] < 0: # <<<<<<<<<<<<<< - * dst.data += start * stride - * else: - */ - goto __pyx_L19; - } - - /* "View.MemoryView":878 - * dst.data += start * stride - * else: - * dst.suboffsets[suboffset_dim[0]] += start * stride # <<<<<<<<<<<<<< - * - * if suboffset >= 0: - */ - /*else*/ { - __pyx_t_3 = (__pyx_v_suboffset_dim[0]); - (__pyx_v_dst->suboffsets[__pyx_t_3]) = ((__pyx_v_dst->suboffsets[__pyx_t_3]) + (__pyx_v_start * __pyx_v_stride)); - } - __pyx_L19:; - - /* "View.MemoryView":880 - * dst.suboffsets[suboffset_dim[0]] += start * stride - * - * if suboffset >= 0: # <<<<<<<<<<<<<< - * if not is_slice: - * if new_ndim == 0: - */ - __pyx_t_2 = (__pyx_v_suboffset >= 0); - if (__pyx_t_2) { - - /* "View.MemoryView":881 - * - * if suboffset >= 0: - * if not is_slice: # <<<<<<<<<<<<<< - * if new_ndim == 0: - * dst.data = ( dst.data)[0] + suboffset - */ - __pyx_t_2 = (!__pyx_v_is_slice); - if (__pyx_t_2) { - - /* "View.MemoryView":882 - * if suboffset >= 0: - * if not is_slice: - * if new_ndim == 0: # <<<<<<<<<<<<<< - * dst.data = ( dst.data)[0] + suboffset - * else: - */ - __pyx_t_2 = (__pyx_v_new_ndim == 0); - if (__pyx_t_2) { - - /* "View.MemoryView":883 - * if not is_slice: - * if new_ndim == 0: - * dst.data = ( dst.data)[0] + suboffset # <<<<<<<<<<<<<< - * else: - * _err_dim(PyExc_IndexError, "All dimensions preceding dimension %d " - */ - __pyx_v_dst->data = ((((char **)__pyx_v_dst->data)[0]) + __pyx_v_suboffset); - - /* "View.MemoryView":882 - * if suboffset >= 0: - * if not is_slice: - * if new_ndim == 0: # <<<<<<<<<<<<<< - * dst.data = ( dst.data)[0] + suboffset - * else: - */ - goto __pyx_L22; - } - - /* "View.MemoryView":885 - * dst.data = ( dst.data)[0] + suboffset - * else: - * _err_dim(PyExc_IndexError, "All dimensions preceding dimension %d " # <<<<<<<<<<<<<< - * "must be indexed and not sliced", dim) - * else: - */ - /*else*/ { - - /* "View.MemoryView":886 - * else: - * _err_dim(PyExc_IndexError, "All dimensions preceding dimension %d " - * "must be indexed and not sliced", dim) # <<<<<<<<<<<<<< - * else: - * suboffset_dim[0] = new_ndim - */ - __pyx_t_3 = __pyx_memoryview_err_dim(PyExc_IndexError, __pyx_kp_s_All_dimensions_preceding_dimensi, __pyx_v_dim); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(1, 885, __pyx_L1_error) - } - __pyx_L22:; - - /* "View.MemoryView":881 - * - * if suboffset >= 0: - * if not is_slice: # <<<<<<<<<<<<<< - * if new_ndim == 0: - * dst.data = ( dst.data)[0] + suboffset - */ - goto __pyx_L21; - } - - /* "View.MemoryView":888 - * "must be indexed and not sliced", dim) - * else: - * suboffset_dim[0] = new_ndim # <<<<<<<<<<<<<< - * - * return 0 - */ - /*else*/ { - (__pyx_v_suboffset_dim[0]) = __pyx_v_new_ndim; - } - __pyx_L21:; - - /* "View.MemoryView":880 - * dst.suboffsets[suboffset_dim[0]] += start * stride - * - * if suboffset >= 0: # <<<<<<<<<<<<<< - * if not is_slice: - * if new_ndim == 0: - */ - } - - /* "View.MemoryView":890 - * suboffset_dim[0] = new_ndim - * - * return 0 # <<<<<<<<<<<<<< - * - * - */ - __pyx_r = 0; - goto __pyx_L0; - - /* "View.MemoryView":793 - * - * @cname('__pyx_memoryview_slice_memviewslice') - * cdef int slice_memviewslice( # <<<<<<<<<<<<<< - * __Pyx_memviewslice *dst, - * Py_ssize_t shape, Py_ssize_t stride, Py_ssize_t suboffset, - */ - - /* function exit code */ - __pyx_L1_error:; - #ifdef WITH_THREAD - __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); - #endif - __Pyx_AddTraceback("View.MemoryView.slice_memviewslice", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = -1; - #ifdef WITH_THREAD - __Pyx_PyGILState_Release(__pyx_gilstate_save); - #endif - __pyx_L0:; - return __pyx_r; -} - -/* "View.MemoryView":896 - * - * @cname('__pyx_pybuffer_index') - * cdef char *pybuffer_index(Py_buffer *view, char *bufp, Py_ssize_t index, # <<<<<<<<<<<<<< - * Py_ssize_t dim) except NULL: - * cdef Py_ssize_t shape, stride, suboffset = -1 - */ - -static char *__pyx_pybuffer_index(Py_buffer *__pyx_v_view, char *__pyx_v_bufp, Py_ssize_t __pyx_v_index, Py_ssize_t __pyx_v_dim) { - Py_ssize_t __pyx_v_shape; - Py_ssize_t __pyx_v_stride; - Py_ssize_t __pyx_v_suboffset; - Py_ssize_t __pyx_v_itemsize; - char *__pyx_v_resultp; - char *__pyx_r; - __Pyx_RefNannyDeclarations - Py_ssize_t __pyx_t_1; - int __pyx_t_2; - PyObject *__pyx_t_3 = NULL; - Py_UCS4 __pyx_t_4; - PyObject *__pyx_t_5 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("pybuffer_index", 1); - - /* "View.MemoryView":898 - * cdef char *pybuffer_index(Py_buffer *view, char *bufp, Py_ssize_t index, - * Py_ssize_t dim) except NULL: - * cdef Py_ssize_t shape, stride, suboffset = -1 # <<<<<<<<<<<<<< - * cdef Py_ssize_t itemsize = view.itemsize - * cdef char *resultp - */ - __pyx_v_suboffset = -1L; - - /* "View.MemoryView":899 - * Py_ssize_t dim) except NULL: - * cdef Py_ssize_t shape, stride, suboffset = -1 - * cdef Py_ssize_t itemsize = view.itemsize # <<<<<<<<<<<<<< - * cdef char *resultp - * - */ - __pyx_t_1 = __pyx_v_view->itemsize; - __pyx_v_itemsize = __pyx_t_1; - - /* "View.MemoryView":902 - * cdef char *resultp - * - * if view.ndim == 0: # <<<<<<<<<<<<<< - * shape = view.len // itemsize - * stride = itemsize - */ - __pyx_t_2 = (__pyx_v_view->ndim == 0); - if (__pyx_t_2) { - - /* "View.MemoryView":903 - * - * if view.ndim == 0: - * shape = view.len // itemsize # <<<<<<<<<<<<<< - * stride = itemsize - * else: - */ - if (unlikely(__pyx_v_itemsize == 0)) { - PyErr_SetString(PyExc_ZeroDivisionError, "integer division or modulo by zero"); - __PYX_ERR(1, 903, __pyx_L1_error) - } - else if (sizeof(Py_ssize_t) == sizeof(long) && (!(((Py_ssize_t)-1) > 0)) && unlikely(__pyx_v_itemsize == (Py_ssize_t)-1) && unlikely(__Pyx_UNARY_NEG_WOULD_OVERFLOW(__pyx_v_view->len))) { - PyErr_SetString(PyExc_OverflowError, "value too large to perform division"); - __PYX_ERR(1, 903, __pyx_L1_error) - } - __pyx_v_shape = __Pyx_div_Py_ssize_t(__pyx_v_view->len, __pyx_v_itemsize); - - /* "View.MemoryView":904 - * if view.ndim == 0: - * shape = view.len // itemsize - * stride = itemsize # <<<<<<<<<<<<<< - * else: - * shape = view.shape[dim] - */ - __pyx_v_stride = __pyx_v_itemsize; - - /* "View.MemoryView":902 - * cdef char *resultp - * - * if view.ndim == 0: # <<<<<<<<<<<<<< - * shape = view.len // itemsize - * stride = itemsize - */ - goto __pyx_L3; - } - - /* "View.MemoryView":906 - * stride = itemsize - * else: - * shape = view.shape[dim] # <<<<<<<<<<<<<< - * stride = view.strides[dim] - * if view.suboffsets != NULL: - */ - /*else*/ { - __pyx_v_shape = (__pyx_v_view->shape[__pyx_v_dim]); - - /* "View.MemoryView":907 - * else: - * shape = view.shape[dim] - * stride = view.strides[dim] # <<<<<<<<<<<<<< - * if view.suboffsets != NULL: - * suboffset = view.suboffsets[dim] - */ - __pyx_v_stride = (__pyx_v_view->strides[__pyx_v_dim]); - - /* "View.MemoryView":908 - * shape = view.shape[dim] - * stride = view.strides[dim] - * if view.suboffsets != NULL: # <<<<<<<<<<<<<< - * suboffset = view.suboffsets[dim] - * - */ - __pyx_t_2 = (__pyx_v_view->suboffsets != NULL); - if (__pyx_t_2) { - - /* "View.MemoryView":909 - * stride = view.strides[dim] - * if view.suboffsets != NULL: - * suboffset = view.suboffsets[dim] # <<<<<<<<<<<<<< - * - * if index < 0: - */ - __pyx_v_suboffset = (__pyx_v_view->suboffsets[__pyx_v_dim]); - - /* "View.MemoryView":908 - * shape = view.shape[dim] - * stride = view.strides[dim] - * if view.suboffsets != NULL: # <<<<<<<<<<<<<< - * suboffset = view.suboffsets[dim] - * - */ - } - } - __pyx_L3:; - - /* "View.MemoryView":911 - * suboffset = view.suboffsets[dim] - * - * if index < 0: # <<<<<<<<<<<<<< - * index += view.shape[dim] - * if index < 0: - */ - __pyx_t_2 = (__pyx_v_index < 0); - if (__pyx_t_2) { - - /* "View.MemoryView":912 - * - * if index < 0: - * index += view.shape[dim] # <<<<<<<<<<<<<< - * if index < 0: - * raise IndexError, f"Out of bounds on buffer access (axis {dim})" - */ - __pyx_v_index = (__pyx_v_index + (__pyx_v_view->shape[__pyx_v_dim])); - - /* "View.MemoryView":913 - * if index < 0: - * index += view.shape[dim] - * if index < 0: # <<<<<<<<<<<<<< - * raise IndexError, f"Out of bounds on buffer access (axis {dim})" - * - */ - __pyx_t_2 = (__pyx_v_index < 0); - if (unlikely(__pyx_t_2)) { - - /* "View.MemoryView":914 - * index += view.shape[dim] - * if index < 0: - * raise IndexError, f"Out of bounds on buffer access (axis {dim})" # <<<<<<<<<<<<<< - * - * if index >= shape: - */ - __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 914, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __pyx_t_1 = 0; - __pyx_t_4 = 127; - __Pyx_INCREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); - __pyx_t_1 += 37; - __Pyx_GIVEREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); - PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_kp_u_Out_of_bounds_on_buffer_access_a); - __pyx_t_5 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_dim, 0, ' ', 'd'); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 914, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __pyx_t_1 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_5); - __Pyx_GIVEREF(__pyx_t_5); - PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_5); - __pyx_t_5 = 0; - __Pyx_INCREF(__pyx_kp_u__7); - __pyx_t_1 += 1; - __Pyx_GIVEREF(__pyx_kp_u__7); - PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_kp_u__7); - __pyx_t_5 = __Pyx_PyUnicode_Join(__pyx_t_3, 3, __pyx_t_1, __pyx_t_4); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 914, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - __Pyx_Raise(__pyx_builtin_IndexError, __pyx_t_5, 0, 0); - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __PYX_ERR(1, 914, __pyx_L1_error) - - /* "View.MemoryView":913 - * if index < 0: - * index += view.shape[dim] - * if index < 0: # <<<<<<<<<<<<<< - * raise IndexError, f"Out of bounds on buffer access (axis {dim})" - * - */ - } - - /* "View.MemoryView":911 - * suboffset = view.suboffsets[dim] - * - * if index < 0: # <<<<<<<<<<<<<< - * index += view.shape[dim] - * if index < 0: - */ - } - - /* "View.MemoryView":916 - * raise IndexError, f"Out of bounds on buffer access (axis {dim})" - * - * if index >= shape: # <<<<<<<<<<<<<< - * raise IndexError, f"Out of bounds on buffer access (axis {dim})" - * - */ - __pyx_t_2 = (__pyx_v_index >= __pyx_v_shape); - if (unlikely(__pyx_t_2)) { - - /* "View.MemoryView":917 - * - * if index >= shape: - * raise IndexError, f"Out of bounds on buffer access (axis {dim})" # <<<<<<<<<<<<<< - * - * resultp = bufp + index * stride - */ - __pyx_t_5 = PyTuple_New(3); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 917, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __pyx_t_1 = 0; - __pyx_t_4 = 127; - __Pyx_INCREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); - __pyx_t_1 += 37; - __Pyx_GIVEREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); - PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_kp_u_Out_of_bounds_on_buffer_access_a); - __pyx_t_3 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_dim, 0, ' ', 'd'); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 917, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __pyx_t_1 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_3); - __Pyx_GIVEREF(__pyx_t_3); - PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_t_3); - __pyx_t_3 = 0; - __Pyx_INCREF(__pyx_kp_u__7); - __pyx_t_1 += 1; - __Pyx_GIVEREF(__pyx_kp_u__7); - PyTuple_SET_ITEM(__pyx_t_5, 2, __pyx_kp_u__7); - __pyx_t_3 = __Pyx_PyUnicode_Join(__pyx_t_5, 3, __pyx_t_1, __pyx_t_4); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 917, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __Pyx_Raise(__pyx_builtin_IndexError, __pyx_t_3, 0, 0); - __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - __PYX_ERR(1, 917, __pyx_L1_error) - - /* "View.MemoryView":916 - * raise IndexError, f"Out of bounds on buffer access (axis {dim})" - * - * if index >= shape: # <<<<<<<<<<<<<< - * raise IndexError, f"Out of bounds on buffer access (axis {dim})" - * - */ - } - - /* "View.MemoryView":919 - * raise IndexError, f"Out of bounds on buffer access (axis {dim})" - * - * resultp = bufp + index * stride # <<<<<<<<<<<<<< - * if suboffset >= 0: - * resultp = ( resultp)[0] + suboffset - */ - __pyx_v_resultp = (__pyx_v_bufp + (__pyx_v_index * __pyx_v_stride)); - - /* "View.MemoryView":920 - * - * resultp = bufp + index * stride - * if suboffset >= 0: # <<<<<<<<<<<<<< - * resultp = ( resultp)[0] + suboffset - * - */ - __pyx_t_2 = (__pyx_v_suboffset >= 0); - if (__pyx_t_2) { - - /* "View.MemoryView":921 - * resultp = bufp + index * stride - * if suboffset >= 0: - * resultp = ( resultp)[0] + suboffset # <<<<<<<<<<<<<< - * - * return resultp - */ - __pyx_v_resultp = ((((char **)__pyx_v_resultp)[0]) + __pyx_v_suboffset); - - /* "View.MemoryView":920 - * - * resultp = bufp + index * stride - * if suboffset >= 0: # <<<<<<<<<<<<<< - * resultp = ( resultp)[0] + suboffset - * - */ - } - - /* "View.MemoryView":923 - * resultp = ( resultp)[0] + suboffset - * - * return resultp # <<<<<<<<<<<<<< - * - * - */ - __pyx_r = __pyx_v_resultp; - goto __pyx_L0; - - /* "View.MemoryView":896 - * - * @cname('__pyx_pybuffer_index') - * cdef char *pybuffer_index(Py_buffer *view, char *bufp, Py_ssize_t index, # <<<<<<<<<<<<<< - * Py_ssize_t dim) except NULL: - * cdef Py_ssize_t shape, stride, suboffset = -1 - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_3); - __Pyx_XDECREF(__pyx_t_5); - __Pyx_AddTraceback("View.MemoryView.pybuffer_index", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = NULL; - __pyx_L0:; - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "View.MemoryView":929 - * - * @cname('__pyx_memslice_transpose') - * cdef int transpose_memslice(__Pyx_memviewslice *memslice) except -1 nogil: # <<<<<<<<<<<<<< - * cdef int ndim = memslice.memview.view.ndim - * - */ - -static int __pyx_memslice_transpose(__Pyx_memviewslice *__pyx_v_memslice) { - int __pyx_v_ndim; - Py_ssize_t *__pyx_v_shape; - Py_ssize_t *__pyx_v_strides; - int __pyx_v_i; - int __pyx_v_j; - int __pyx_r; - int __pyx_t_1; - Py_ssize_t *__pyx_t_2; - long __pyx_t_3; - long __pyx_t_4; - Py_ssize_t __pyx_t_5; - Py_ssize_t __pyx_t_6; - int __pyx_t_7; - int __pyx_t_8; - int __pyx_t_9; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - #ifdef WITH_THREAD - PyGILState_STATE __pyx_gilstate_save; - #endif - - /* "View.MemoryView":930 - * @cname('__pyx_memslice_transpose') - * cdef int transpose_memslice(__Pyx_memviewslice *memslice) except -1 nogil: - * cdef int ndim = memslice.memview.view.ndim # <<<<<<<<<<<<<< - * - * cdef Py_ssize_t *shape = memslice.shape - */ - __pyx_t_1 = __pyx_v_memslice->memview->view.ndim; - __pyx_v_ndim = __pyx_t_1; - - /* "View.MemoryView":932 - * cdef int ndim = memslice.memview.view.ndim - * - * cdef Py_ssize_t *shape = memslice.shape # <<<<<<<<<<<<<< - * cdef Py_ssize_t *strides = memslice.strides - * - */ - __pyx_t_2 = __pyx_v_memslice->shape; - __pyx_v_shape = __pyx_t_2; - - /* "View.MemoryView":933 - * - * cdef Py_ssize_t *shape = memslice.shape - * cdef Py_ssize_t *strides = memslice.strides # <<<<<<<<<<<<<< - * - * - */ - __pyx_t_2 = __pyx_v_memslice->strides; - __pyx_v_strides = __pyx_t_2; - - /* "View.MemoryView":937 - * - * cdef int i, j - * for i in range(ndim // 2): # <<<<<<<<<<<<<< - * j = ndim - 1 - i - * strides[i], strides[j] = strides[j], strides[i] - */ - __pyx_t_3 = __Pyx_div_long(__pyx_v_ndim, 2); - __pyx_t_4 = __pyx_t_3; - for (__pyx_t_1 = 0; __pyx_t_1 < __pyx_t_4; __pyx_t_1+=1) { - __pyx_v_i = __pyx_t_1; - - /* "View.MemoryView":938 - * cdef int i, j - * for i in range(ndim // 2): - * j = ndim - 1 - i # <<<<<<<<<<<<<< - * strides[i], strides[j] = strides[j], strides[i] - * shape[i], shape[j] = shape[j], shape[i] - */ - __pyx_v_j = ((__pyx_v_ndim - 1) - __pyx_v_i); - - /* "View.MemoryView":939 - * for i in range(ndim // 2): - * j = ndim - 1 - i - * strides[i], strides[j] = strides[j], strides[i] # <<<<<<<<<<<<<< - * shape[i], shape[j] = shape[j], shape[i] - * - */ - __pyx_t_5 = (__pyx_v_strides[__pyx_v_j]); - __pyx_t_6 = (__pyx_v_strides[__pyx_v_i]); - (__pyx_v_strides[__pyx_v_i]) = __pyx_t_5; - (__pyx_v_strides[__pyx_v_j]) = __pyx_t_6; - - /* "View.MemoryView":940 - * j = ndim - 1 - i - * strides[i], strides[j] = strides[j], strides[i] - * shape[i], shape[j] = shape[j], shape[i] # <<<<<<<<<<<<<< - * - * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: - */ - __pyx_t_6 = (__pyx_v_shape[__pyx_v_j]); - __pyx_t_5 = (__pyx_v_shape[__pyx_v_i]); - (__pyx_v_shape[__pyx_v_i]) = __pyx_t_6; - (__pyx_v_shape[__pyx_v_j]) = __pyx_t_5; - - /* "View.MemoryView":942 - * shape[i], shape[j] = shape[j], shape[i] - * - * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: # <<<<<<<<<<<<<< - * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") - * - */ - __pyx_t_8 = ((__pyx_v_memslice->suboffsets[__pyx_v_i]) >= 0); - if (!__pyx_t_8) { - } else { - __pyx_t_7 = __pyx_t_8; - goto __pyx_L6_bool_binop_done; - } - __pyx_t_8 = ((__pyx_v_memslice->suboffsets[__pyx_v_j]) >= 0); - __pyx_t_7 = __pyx_t_8; - __pyx_L6_bool_binop_done:; - if (__pyx_t_7) { - - /* "View.MemoryView":943 - * - * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: - * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") # <<<<<<<<<<<<<< - * - * return 0 - */ - __pyx_t_9 = __pyx_memoryview_err(PyExc_ValueError, __pyx_kp_s_Cannot_transpose_memoryview_with); if (unlikely(__pyx_t_9 == ((int)-1))) __PYX_ERR(1, 943, __pyx_L1_error) - - /* "View.MemoryView":942 - * shape[i], shape[j] = shape[j], shape[i] - * - * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: # <<<<<<<<<<<<<< - * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") - * - */ - } - } - - /* "View.MemoryView":945 - * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") - * - * return 0 # <<<<<<<<<<<<<< - * - * - */ - __pyx_r = 0; - goto __pyx_L0; - - /* "View.MemoryView":929 - * - * @cname('__pyx_memslice_transpose') - * cdef int transpose_memslice(__Pyx_memviewslice *memslice) except -1 nogil: # <<<<<<<<<<<<<< - * cdef int ndim = memslice.memview.view.ndim - * - */ - - /* function exit code */ - __pyx_L1_error:; - #ifdef WITH_THREAD - __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); - #endif - __Pyx_AddTraceback("View.MemoryView.transpose_memslice", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = -1; - #ifdef WITH_THREAD - __Pyx_PyGILState_Release(__pyx_gilstate_save); - #endif - __pyx_L0:; - return __pyx_r; -} - -/* "View.MemoryView":963 - * cdef int (*to_dtype_func)(char *, object) except 0 - * - * def __dealloc__(self): # <<<<<<<<<<<<<< - * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) - * - */ - -/* Python wrapper */ -static void __pyx_memoryviewslice___dealloc__(PyObject *__pyx_v_self); /*proto*/ -static void __pyx_memoryviewslice___dealloc__(PyObject *__pyx_v_self) { - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); - __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); - __pyx_memoryviewslice___pyx_pf_15View_dot_MemoryView_16_memoryviewslice___dealloc__(((struct __pyx_memoryviewslice_obj *)__pyx_v_self)); - - /* function exit code */ - __Pyx_RefNannyFinishContext(); -} - -static void __pyx_memoryviewslice___pyx_pf_15View_dot_MemoryView_16_memoryviewslice___dealloc__(struct __pyx_memoryviewslice_obj *__pyx_v_self) { - - /* "View.MemoryView":964 - * - * def __dealloc__(self): - * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) # <<<<<<<<<<<<<< - * - * cdef convert_item_to_object(self, char *itemp): - */ - __PYX_XCLEAR_MEMVIEW((&__pyx_v_self->from_slice), 1); - - /* "View.MemoryView":963 - * cdef int (*to_dtype_func)(char *, object) except 0 - * - * def __dealloc__(self): # <<<<<<<<<<<<<< - * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) - * - */ - - /* function exit code */ -} - -/* "View.MemoryView":966 - * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) - * - * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< - * if self.to_object_func != NULL: - * return self.to_object_func(itemp) - */ - -static PyObject *__pyx_memoryviewslice_convert_item_to_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp) { - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - int __pyx_t_1; - PyObject *__pyx_t_2 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("convert_item_to_object", 1); - - /* "View.MemoryView":967 - * - * cdef convert_item_to_object(self, char *itemp): - * if self.to_object_func != NULL: # <<<<<<<<<<<<<< - * return self.to_object_func(itemp) - * else: - */ - __pyx_t_1 = (__pyx_v_self->to_object_func != NULL); - if (__pyx_t_1) { - - /* "View.MemoryView":968 - * cdef convert_item_to_object(self, char *itemp): - * if self.to_object_func != NULL: - * return self.to_object_func(itemp) # <<<<<<<<<<<<<< - * else: - * return memoryview.convert_item_to_object(self, itemp) - */ - __Pyx_XDECREF(__pyx_r); - __pyx_t_2 = __pyx_v_self->to_object_func(__pyx_v_itemp); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 968, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __pyx_r = __pyx_t_2; - __pyx_t_2 = 0; - goto __pyx_L0; - - /* "View.MemoryView":967 - * - * cdef convert_item_to_object(self, char *itemp): - * if self.to_object_func != NULL: # <<<<<<<<<<<<<< - * return self.to_object_func(itemp) - * else: - */ - } - - /* "View.MemoryView":970 - * return self.to_object_func(itemp) - * else: - * return memoryview.convert_item_to_object(self, itemp) # <<<<<<<<<<<<<< - * - * cdef assign_item_from_object(self, char *itemp, object value): - */ - /*else*/ { - __Pyx_XDECREF(__pyx_r); - __pyx_t_2 = __pyx_memoryview_convert_item_to_object(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v_itemp); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 970, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __pyx_r = __pyx_t_2; - __pyx_t_2 = 0; - goto __pyx_L0; - } - - /* "View.MemoryView":966 - * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) - * - * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< - * if self.to_object_func != NULL: - * return self.to_object_func(itemp) - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_2); - __Pyx_AddTraceback("View.MemoryView._memoryviewslice.convert_item_to_object", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = 0; - __pyx_L0:; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "View.MemoryView":972 - * return memoryview.convert_item_to_object(self, itemp) - * - * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< - * if self.to_dtype_func != NULL: - * self.to_dtype_func(itemp, value) - */ - -static PyObject *__pyx_memoryviewslice_assign_item_from_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value) { - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - int __pyx_t_1; - int __pyx_t_2; - PyObject *__pyx_t_3 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("assign_item_from_object", 1); - - /* "View.MemoryView":973 - * - * cdef assign_item_from_object(self, char *itemp, object value): - * if self.to_dtype_func != NULL: # <<<<<<<<<<<<<< - * self.to_dtype_func(itemp, value) - * else: - */ - __pyx_t_1 = (__pyx_v_self->to_dtype_func != NULL); - if (__pyx_t_1) { - - /* "View.MemoryView":974 - * cdef assign_item_from_object(self, char *itemp, object value): - * if self.to_dtype_func != NULL: - * self.to_dtype_func(itemp, value) # <<<<<<<<<<<<<< - * else: - * memoryview.assign_item_from_object(self, itemp, value) - */ - __pyx_t_2 = __pyx_v_self->to_dtype_func(__pyx_v_itemp, __pyx_v_value); if (unlikely(__pyx_t_2 == ((int)0))) __PYX_ERR(1, 974, __pyx_L1_error) - - /* "View.MemoryView":973 - * - * cdef assign_item_from_object(self, char *itemp, object value): - * if self.to_dtype_func != NULL: # <<<<<<<<<<<<<< - * self.to_dtype_func(itemp, value) - * else: - */ - goto __pyx_L3; - } - - /* "View.MemoryView":976 - * self.to_dtype_func(itemp, value) - * else: - * memoryview.assign_item_from_object(self, itemp, value) # <<<<<<<<<<<<<< - * - * cdef _get_base(self): - */ - /*else*/ { - __pyx_t_3 = __pyx_memoryview_assign_item_from_object(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v_itemp, __pyx_v_value); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 976, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - } - __pyx_L3:; - - /* "View.MemoryView":972 - * return memoryview.convert_item_to_object(self, itemp) - * - * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< - * if self.to_dtype_func != NULL: - * self.to_dtype_func(itemp, value) - */ - - /* function exit code */ - __pyx_r = Py_None; __Pyx_INCREF(Py_None); - goto __pyx_L0; - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_3); - __Pyx_AddTraceback("View.MemoryView._memoryviewslice.assign_item_from_object", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = 0; - __pyx_L0:; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "View.MemoryView":978 - * memoryview.assign_item_from_object(self, itemp, value) - * - * cdef _get_base(self): # <<<<<<<<<<<<<< - * return self.from_object - * - */ - -static PyObject *__pyx_memoryviewslice__get_base(struct __pyx_memoryviewslice_obj *__pyx_v_self) { - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("_get_base", 1); - - /* "View.MemoryView":979 - * - * cdef _get_base(self): - * return self.from_object # <<<<<<<<<<<<<< - * - * - */ - __Pyx_XDECREF(__pyx_r); - __Pyx_INCREF(__pyx_v_self->from_object); - __pyx_r = __pyx_v_self->from_object; - goto __pyx_L0; - - /* "View.MemoryView":978 - * memoryview.assign_item_from_object(self, itemp, value) - * - * cdef _get_base(self): # <<<<<<<<<<<<<< - * return self.from_object - * - */ - - /* function exit code */ - __pyx_L0:; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "(tree fragment)":1 - * def __reduce_cython__(self): # <<<<<<<<<<<<<< - * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" - * def __setstate_cython__(self, __pyx_state): - */ - -/* Python wrapper */ -static PyObject *__pyx_pw___pyx_memoryviewslice_1__reduce_cython__(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -); /*proto*/ -static PyObject *__pyx_pw___pyx_memoryviewslice_1__reduce_cython__(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -) { - #if !CYTHON_METH_FASTCALL - CYTHON_UNUSED Py_ssize_t __pyx_nargs; - #endif - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - PyObject *__pyx_r = 0; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); - #if !CYTHON_METH_FASTCALL - #if CYTHON_ASSUME_SAFE_MACROS - __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); - #else - __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; - #endif - #endif - __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); - if (unlikely(__pyx_nargs > 0)) { - __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} - if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; - __pyx_r = __pyx_pf___pyx_memoryviewslice___reduce_cython__(((struct __pyx_memoryviewslice_obj *)__pyx_v_self)); - - /* function exit code */ - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static PyObject *__pyx_pf___pyx_memoryviewslice___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self) { - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("__reduce_cython__", 1); - - /* "(tree fragment)":2 - * def __reduce_cython__(self): - * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< - * def __setstate_cython__(self, __pyx_state): - * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" - */ - __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); - __PYX_ERR(1, 2, __pyx_L1_error) - - /* "(tree fragment)":1 - * def __reduce_cython__(self): # <<<<<<<<<<<<<< - * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" - * def __setstate_cython__(self, __pyx_state): - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_AddTraceback("View.MemoryView._memoryviewslice.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = NULL; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "(tree fragment)":3 - * def __reduce_cython__(self): - * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" - * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< - * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" - */ - -/* Python wrapper */ -static PyObject *__pyx_pw___pyx_memoryviewslice_3__setstate_cython__(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -); /*proto*/ -static PyObject *__pyx_pw___pyx_memoryviewslice_3__setstate_cython__(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -) { - CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; - #if !CYTHON_METH_FASTCALL - CYTHON_UNUSED Py_ssize_t __pyx_nargs; - #endif - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - PyObject* values[1] = {0}; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - PyObject *__pyx_r = 0; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); - #if !CYTHON_METH_FASTCALL - #if CYTHON_ASSUME_SAFE_MACROS - __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); - #else - __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; - #endif - #endif - __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); - { - PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; - if (__pyx_kwds) { - Py_ssize_t kw_args; - switch (__pyx_nargs) { - case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); - CYTHON_FALLTHROUGH; - case 0: break; - default: goto __pyx_L5_argtuple_error; - } - kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); - switch (__pyx_nargs) { - case 0: - if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { - (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); - kw_args--; - } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) - else goto __pyx_L5_argtuple_error; - } - if (unlikely(kw_args > 0)) { - const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) - } - } else if (unlikely(__pyx_nargs != 1)) { - goto __pyx_L5_argtuple_error; - } else { - values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); - } - __pyx_v___pyx_state = values[0]; - } - goto __pyx_L6_skip; - __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) - __pyx_L6_skip:; - goto __pyx_L4_argument_unpacking_done; - __pyx_L3_error:; - { - Py_ssize_t __pyx_temp; - for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { - __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); - } - } - __Pyx_AddTraceback("View.MemoryView._memoryviewslice.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); - __Pyx_RefNannyFinishContext(); - return NULL; - __pyx_L4_argument_unpacking_done:; - __pyx_r = __pyx_pf___pyx_memoryviewslice_2__setstate_cython__(((struct __pyx_memoryviewslice_obj *)__pyx_v_self), __pyx_v___pyx_state); - - /* function exit code */ - { - Py_ssize_t __pyx_temp; - for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { - __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); - } - } - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static PyObject *__pyx_pf___pyx_memoryviewslice_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("__setstate_cython__", 1); - - /* "(tree fragment)":4 - * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" - * def __setstate_cython__(self, __pyx_state): - * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< - */ - __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); - __PYX_ERR(1, 4, __pyx_L1_error) - - /* "(tree fragment)":3 - * def __reduce_cython__(self): - * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" - * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< - * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_AddTraceback("View.MemoryView._memoryviewslice.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = NULL; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "View.MemoryView":999 - * - * @cname('__pyx_memoryview_fromslice') - * cdef memoryview_fromslice(__Pyx_memviewslice memviewslice, # <<<<<<<<<<<<<< - * int ndim, - * object (*to_object_func)(char *), - */ - -static PyObject *__pyx_memoryview_fromslice(__Pyx_memviewslice __pyx_v_memviewslice, int __pyx_v_ndim, PyObject *(*__pyx_v_to_object_func)(char *), int (*__pyx_v_to_dtype_func)(char *, PyObject *), int __pyx_v_dtype_is_object) { - struct __pyx_memoryviewslice_obj *__pyx_v_result = 0; - Py_ssize_t __pyx_v_suboffset; - PyObject *__pyx_v_length = NULL; - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - int __pyx_t_1; - PyObject *__pyx_t_2 = NULL; - PyObject *__pyx_t_3 = NULL; - __Pyx_TypeInfo *__pyx_t_4; - Py_buffer __pyx_t_5; - Py_ssize_t *__pyx_t_6; - Py_ssize_t *__pyx_t_7; - Py_ssize_t *__pyx_t_8; - Py_ssize_t __pyx_t_9; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("memoryview_fromslice", 1); - - /* "View.MemoryView":1007 - * cdef _memoryviewslice result - * - * if memviewslice.memview == Py_None: # <<<<<<<<<<<<<< - * return None - * - */ - __pyx_t_1 = (((PyObject *)__pyx_v_memviewslice.memview) == Py_None); - if (__pyx_t_1) { - - /* "View.MemoryView":1008 - * - * if memviewslice.memview == Py_None: - * return None # <<<<<<<<<<<<<< - * - * - */ - __Pyx_XDECREF(__pyx_r); - __pyx_r = Py_None; __Pyx_INCREF(Py_None); - goto __pyx_L0; - - /* "View.MemoryView":1007 - * cdef _memoryviewslice result - * - * if memviewslice.memview == Py_None: # <<<<<<<<<<<<<< - * return None - * - */ - } - - /* "View.MemoryView":1013 - * - * - * result = _memoryviewslice.__new__(_memoryviewslice, None, 0, dtype_is_object) # <<<<<<<<<<<<<< - * - * result.from_slice = memviewslice - */ - __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_v_dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1013, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 1013, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __Pyx_INCREF(Py_None); - __Pyx_GIVEREF(Py_None); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, Py_None)) __PYX_ERR(1, 1013, __pyx_L1_error); - __Pyx_INCREF(__pyx_int_0); - __Pyx_GIVEREF(__pyx_int_0); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_int_0)) __PYX_ERR(1, 1013, __pyx_L1_error); - __Pyx_GIVEREF(__pyx_t_2); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_t_2)) __PYX_ERR(1, 1013, __pyx_L1_error); - __pyx_t_2 = 0; - __pyx_t_2 = ((PyObject *)__pyx_tp_new__memoryviewslice(((PyTypeObject *)__pyx_memoryviewslice_type), __pyx_t_3, NULL)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1013, __pyx_L1_error) - __Pyx_GOTREF((PyObject *)__pyx_t_2); - __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - __pyx_v_result = ((struct __pyx_memoryviewslice_obj *)__pyx_t_2); - __pyx_t_2 = 0; - - /* "View.MemoryView":1015 - * result = _memoryviewslice.__new__(_memoryviewslice, None, 0, dtype_is_object) - * - * result.from_slice = memviewslice # <<<<<<<<<<<<<< - * __PYX_INC_MEMVIEW(&memviewslice, 1) - * - */ - __pyx_v_result->from_slice = __pyx_v_memviewslice; - - /* "View.MemoryView":1016 - * - * result.from_slice = memviewslice - * __PYX_INC_MEMVIEW(&memviewslice, 1) # <<<<<<<<<<<<<< - * - * result.from_object = ( memviewslice.memview)._get_base() - */ - __PYX_INC_MEMVIEW((&__pyx_v_memviewslice), 1); - - /* "View.MemoryView":1018 - * __PYX_INC_MEMVIEW(&memviewslice, 1) - * - * result.from_object = ( memviewslice.memview)._get_base() # <<<<<<<<<<<<<< - * result.typeinfo = memviewslice.memview.typeinfo - * - */ - __pyx_t_2 = ((struct __pyx_vtabstruct_memoryview *)((struct __pyx_memoryview_obj *)__pyx_v_memviewslice.memview)->__pyx_vtab)->_get_base(((struct __pyx_memoryview_obj *)__pyx_v_memviewslice.memview)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1018, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __Pyx_GIVEREF(__pyx_t_2); - __Pyx_GOTREF(__pyx_v_result->from_object); - __Pyx_DECREF(__pyx_v_result->from_object); - __pyx_v_result->from_object = __pyx_t_2; - __pyx_t_2 = 0; - - /* "View.MemoryView":1019 - * - * result.from_object = ( memviewslice.memview)._get_base() - * result.typeinfo = memviewslice.memview.typeinfo # <<<<<<<<<<<<<< - * - * result.view = memviewslice.memview.view - */ - __pyx_t_4 = __pyx_v_memviewslice.memview->typeinfo; - __pyx_v_result->__pyx_base.typeinfo = __pyx_t_4; - - /* "View.MemoryView":1021 - * result.typeinfo = memviewslice.memview.typeinfo - * - * result.view = memviewslice.memview.view # <<<<<<<<<<<<<< - * result.view.buf = memviewslice.data - * result.view.ndim = ndim - */ - __pyx_t_5 = __pyx_v_memviewslice.memview->view; - __pyx_v_result->__pyx_base.view = __pyx_t_5; - - /* "View.MemoryView":1022 - * - * result.view = memviewslice.memview.view - * result.view.buf = memviewslice.data # <<<<<<<<<<<<<< - * result.view.ndim = ndim - * (<__pyx_buffer *> &result.view).obj = Py_None - */ - __pyx_v_result->__pyx_base.view.buf = ((void *)__pyx_v_memviewslice.data); - - /* "View.MemoryView":1023 - * result.view = memviewslice.memview.view - * result.view.buf = memviewslice.data - * result.view.ndim = ndim # <<<<<<<<<<<<<< - * (<__pyx_buffer *> &result.view).obj = Py_None - * Py_INCREF(Py_None) - */ - __pyx_v_result->__pyx_base.view.ndim = __pyx_v_ndim; - - /* "View.MemoryView":1024 - * result.view.buf = memviewslice.data - * result.view.ndim = ndim - * (<__pyx_buffer *> &result.view).obj = Py_None # <<<<<<<<<<<<<< - * Py_INCREF(Py_None) - * - */ - ((Py_buffer *)(&__pyx_v_result->__pyx_base.view))->obj = Py_None; - - /* "View.MemoryView":1025 - * result.view.ndim = ndim - * (<__pyx_buffer *> &result.view).obj = Py_None - * Py_INCREF(Py_None) # <<<<<<<<<<<<<< - * - * if (memviewslice.memview).flags & PyBUF_WRITABLE: - */ - Py_INCREF(Py_None); - - /* "View.MemoryView":1027 - * Py_INCREF(Py_None) - * - * if (memviewslice.memview).flags & PyBUF_WRITABLE: # <<<<<<<<<<<<<< - * result.flags = PyBUF_RECORDS - * else: - */ - __pyx_t_1 = ((((struct __pyx_memoryview_obj *)__pyx_v_memviewslice.memview)->flags & PyBUF_WRITABLE) != 0); - if (__pyx_t_1) { - - /* "View.MemoryView":1028 - * - * if (memviewslice.memview).flags & PyBUF_WRITABLE: - * result.flags = PyBUF_RECORDS # <<<<<<<<<<<<<< - * else: - * result.flags = PyBUF_RECORDS_RO - */ - __pyx_v_result->__pyx_base.flags = PyBUF_RECORDS; - - /* "View.MemoryView":1027 - * Py_INCREF(Py_None) - * - * if (memviewslice.memview).flags & PyBUF_WRITABLE: # <<<<<<<<<<<<<< - * result.flags = PyBUF_RECORDS - * else: - */ - goto __pyx_L4; - } - - /* "View.MemoryView":1030 - * result.flags = PyBUF_RECORDS - * else: - * result.flags = PyBUF_RECORDS_RO # <<<<<<<<<<<<<< - * - * result.view.shape = result.from_slice.shape - */ - /*else*/ { - __pyx_v_result->__pyx_base.flags = PyBUF_RECORDS_RO; - } - __pyx_L4:; - - /* "View.MemoryView":1032 - * result.flags = PyBUF_RECORDS_RO - * - * result.view.shape = result.from_slice.shape # <<<<<<<<<<<<<< - * result.view.strides = result.from_slice.strides - * - */ - __pyx_v_result->__pyx_base.view.shape = ((Py_ssize_t *)__pyx_v_result->from_slice.shape); - - /* "View.MemoryView":1033 - * - * result.view.shape = result.from_slice.shape - * result.view.strides = result.from_slice.strides # <<<<<<<<<<<<<< - * - * - */ - __pyx_v_result->__pyx_base.view.strides = ((Py_ssize_t *)__pyx_v_result->from_slice.strides); - - /* "View.MemoryView":1036 - * - * - * result.view.suboffsets = NULL # <<<<<<<<<<<<<< - * for suboffset in result.from_slice.suboffsets[:ndim]: - * if suboffset >= 0: - */ - __pyx_v_result->__pyx_base.view.suboffsets = NULL; - - /* "View.MemoryView":1037 - * - * result.view.suboffsets = NULL - * for suboffset in result.from_slice.suboffsets[:ndim]: # <<<<<<<<<<<<<< - * if suboffset >= 0: - * result.view.suboffsets = result.from_slice.suboffsets - */ - __pyx_t_7 = (__pyx_v_result->from_slice.suboffsets + __pyx_v_ndim); - for (__pyx_t_8 = __pyx_v_result->from_slice.suboffsets; __pyx_t_8 < __pyx_t_7; __pyx_t_8++) { - __pyx_t_6 = __pyx_t_8; - __pyx_v_suboffset = (__pyx_t_6[0]); - - /* "View.MemoryView":1038 - * result.view.suboffsets = NULL - * for suboffset in result.from_slice.suboffsets[:ndim]: - * if suboffset >= 0: # <<<<<<<<<<<<<< - * result.view.suboffsets = result.from_slice.suboffsets - * break - */ - __pyx_t_1 = (__pyx_v_suboffset >= 0); - if (__pyx_t_1) { - - /* "View.MemoryView":1039 - * for suboffset in result.from_slice.suboffsets[:ndim]: - * if suboffset >= 0: - * result.view.suboffsets = result.from_slice.suboffsets # <<<<<<<<<<<<<< - * break - * - */ - __pyx_v_result->__pyx_base.view.suboffsets = ((Py_ssize_t *)__pyx_v_result->from_slice.suboffsets); - - /* "View.MemoryView":1040 - * if suboffset >= 0: - * result.view.suboffsets = result.from_slice.suboffsets - * break # <<<<<<<<<<<<<< - * - * result.view.len = result.view.itemsize - */ - goto __pyx_L6_break; - - /* "View.MemoryView":1038 - * result.view.suboffsets = NULL - * for suboffset in result.from_slice.suboffsets[:ndim]: - * if suboffset >= 0: # <<<<<<<<<<<<<< - * result.view.suboffsets = result.from_slice.suboffsets - * break - */ - } - } - __pyx_L6_break:; - - /* "View.MemoryView":1042 - * break - * - * result.view.len = result.view.itemsize # <<<<<<<<<<<<<< - * for length in result.view.shape[:ndim]: - * result.view.len *= length - */ - __pyx_t_9 = __pyx_v_result->__pyx_base.view.itemsize; - __pyx_v_result->__pyx_base.view.len = __pyx_t_9; - - /* "View.MemoryView":1043 - * - * result.view.len = result.view.itemsize - * for length in result.view.shape[:ndim]: # <<<<<<<<<<<<<< - * result.view.len *= length - * - */ - __pyx_t_7 = (__pyx_v_result->__pyx_base.view.shape + __pyx_v_ndim); - for (__pyx_t_8 = __pyx_v_result->__pyx_base.view.shape; __pyx_t_8 < __pyx_t_7; __pyx_t_8++) { - __pyx_t_6 = __pyx_t_8; - __pyx_t_2 = PyInt_FromSsize_t((__pyx_t_6[0])); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1043, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __Pyx_XDECREF_SET(__pyx_v_length, __pyx_t_2); - __pyx_t_2 = 0; - - /* "View.MemoryView":1044 - * result.view.len = result.view.itemsize - * for length in result.view.shape[:ndim]: - * result.view.len *= length # <<<<<<<<<<<<<< - * - * result.to_object_func = to_object_func - */ - __pyx_t_2 = PyInt_FromSsize_t(__pyx_v_result->__pyx_base.view.len); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1044, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __pyx_t_3 = PyNumber_InPlaceMultiply(__pyx_t_2, __pyx_v_length); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 1044, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - __pyx_t_9 = __Pyx_PyIndex_AsSsize_t(__pyx_t_3); if (unlikely((__pyx_t_9 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 1044, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - __pyx_v_result->__pyx_base.view.len = __pyx_t_9; - } - - /* "View.MemoryView":1046 - * result.view.len *= length - * - * result.to_object_func = to_object_func # <<<<<<<<<<<<<< - * result.to_dtype_func = to_dtype_func - * - */ - __pyx_v_result->to_object_func = __pyx_v_to_object_func; - - /* "View.MemoryView":1047 - * - * result.to_object_func = to_object_func - * result.to_dtype_func = to_dtype_func # <<<<<<<<<<<<<< - * - * return result - */ - __pyx_v_result->to_dtype_func = __pyx_v_to_dtype_func; - - /* "View.MemoryView":1049 - * result.to_dtype_func = to_dtype_func - * - * return result # <<<<<<<<<<<<<< - * - * @cname('__pyx_memoryview_get_slice_from_memoryview') - */ - __Pyx_XDECREF(__pyx_r); - __Pyx_INCREF((PyObject *)__pyx_v_result); - __pyx_r = ((PyObject *)__pyx_v_result); - goto __pyx_L0; - - /* "View.MemoryView":999 - * - * @cname('__pyx_memoryview_fromslice') - * cdef memoryview_fromslice(__Pyx_memviewslice memviewslice, # <<<<<<<<<<<<<< - * int ndim, - * object (*to_object_func)(char *), - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_2); - __Pyx_XDECREF(__pyx_t_3); - __Pyx_AddTraceback("View.MemoryView.memoryview_fromslice", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = 0; - __pyx_L0:; - __Pyx_XDECREF((PyObject *)__pyx_v_result); - __Pyx_XDECREF(__pyx_v_length); - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "View.MemoryView":1052 - * - * @cname('__pyx_memoryview_get_slice_from_memoryview') - * cdef __Pyx_memviewslice *get_slice_from_memview(memoryview memview, # <<<<<<<<<<<<<< - * __Pyx_memviewslice *mslice) except NULL: - * cdef _memoryviewslice obj - */ - -static __Pyx_memviewslice *__pyx_memoryview_get_slice_from_memoryview(struct __pyx_memoryview_obj *__pyx_v_memview, __Pyx_memviewslice *__pyx_v_mslice) { - struct __pyx_memoryviewslice_obj *__pyx_v_obj = 0; - __Pyx_memviewslice *__pyx_r; - __Pyx_RefNannyDeclarations - int __pyx_t_1; - PyObject *__pyx_t_2 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("get_slice_from_memview", 1); - - /* "View.MemoryView":1055 - * __Pyx_memviewslice *mslice) except NULL: - * cdef _memoryviewslice obj - * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< - * obj = memview - * return &obj.from_slice - */ - __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); - if (__pyx_t_1) { - - /* "View.MemoryView":1056 - * cdef _memoryviewslice obj - * if isinstance(memview, _memoryviewslice): - * obj = memview # <<<<<<<<<<<<<< - * return &obj.from_slice - * else: - */ - if (!(likely(((((PyObject *)__pyx_v_memview)) == Py_None) || likely(__Pyx_TypeTest(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type))))) __PYX_ERR(1, 1056, __pyx_L1_error) - __pyx_t_2 = ((PyObject *)__pyx_v_memview); - __Pyx_INCREF(__pyx_t_2); - __pyx_v_obj = ((struct __pyx_memoryviewslice_obj *)__pyx_t_2); - __pyx_t_2 = 0; - - /* "View.MemoryView":1057 - * if isinstance(memview, _memoryviewslice): - * obj = memview - * return &obj.from_slice # <<<<<<<<<<<<<< - * else: - * slice_copy(memview, mslice) - */ - __pyx_r = (&__pyx_v_obj->from_slice); - goto __pyx_L0; - - /* "View.MemoryView":1055 - * __Pyx_memviewslice *mslice) except NULL: - * cdef _memoryviewslice obj - * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< - * obj = memview - * return &obj.from_slice - */ - } - - /* "View.MemoryView":1059 - * return &obj.from_slice - * else: - * slice_copy(memview, mslice) # <<<<<<<<<<<<<< - * return mslice - * - */ - /*else*/ { - __pyx_memoryview_slice_copy(__pyx_v_memview, __pyx_v_mslice); - - /* "View.MemoryView":1060 - * else: - * slice_copy(memview, mslice) - * return mslice # <<<<<<<<<<<<<< - * - * @cname('__pyx_memoryview_slice_copy') - */ - __pyx_r = __pyx_v_mslice; - goto __pyx_L0; - } - - /* "View.MemoryView":1052 - * - * @cname('__pyx_memoryview_get_slice_from_memoryview') - * cdef __Pyx_memviewslice *get_slice_from_memview(memoryview memview, # <<<<<<<<<<<<<< - * __Pyx_memviewslice *mslice) except NULL: - * cdef _memoryviewslice obj - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_2); - __Pyx_AddTraceback("View.MemoryView.get_slice_from_memview", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = NULL; - __pyx_L0:; - __Pyx_XDECREF((PyObject *)__pyx_v_obj); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "View.MemoryView":1063 - * - * @cname('__pyx_memoryview_slice_copy') - * cdef void slice_copy(memoryview memview, __Pyx_memviewslice *dst) noexcept: # <<<<<<<<<<<<<< - * cdef int dim - * cdef (Py_ssize_t*) shape, strides, suboffsets - */ - -static void __pyx_memoryview_slice_copy(struct __pyx_memoryview_obj *__pyx_v_memview, __Pyx_memviewslice *__pyx_v_dst) { - int __pyx_v_dim; - Py_ssize_t *__pyx_v_shape; - Py_ssize_t *__pyx_v_strides; - Py_ssize_t *__pyx_v_suboffsets; - Py_ssize_t *__pyx_t_1; - int __pyx_t_2; - int __pyx_t_3; - int __pyx_t_4; - Py_ssize_t __pyx_t_5; - int __pyx_t_6; - - /* "View.MemoryView":1067 - * cdef (Py_ssize_t*) shape, strides, suboffsets - * - * shape = memview.view.shape # <<<<<<<<<<<<<< - * strides = memview.view.strides - * suboffsets = memview.view.suboffsets - */ - __pyx_t_1 = __pyx_v_memview->view.shape; - __pyx_v_shape = __pyx_t_1; - - /* "View.MemoryView":1068 - * - * shape = memview.view.shape - * strides = memview.view.strides # <<<<<<<<<<<<<< - * suboffsets = memview.view.suboffsets - * - */ - __pyx_t_1 = __pyx_v_memview->view.strides; - __pyx_v_strides = __pyx_t_1; - - /* "View.MemoryView":1069 - * shape = memview.view.shape - * strides = memview.view.strides - * suboffsets = memview.view.suboffsets # <<<<<<<<<<<<<< - * - * dst.memview = <__pyx_memoryview *> memview - */ - __pyx_t_1 = __pyx_v_memview->view.suboffsets; - __pyx_v_suboffsets = __pyx_t_1; - - /* "View.MemoryView":1071 - * suboffsets = memview.view.suboffsets - * - * dst.memview = <__pyx_memoryview *> memview # <<<<<<<<<<<<<< - * dst.data = memview.view.buf - * - */ - __pyx_v_dst->memview = ((struct __pyx_memoryview_obj *)__pyx_v_memview); - - /* "View.MemoryView":1072 - * - * dst.memview = <__pyx_memoryview *> memview - * dst.data = memview.view.buf # <<<<<<<<<<<<<< - * - * for dim in range(memview.view.ndim): - */ - __pyx_v_dst->data = ((char *)__pyx_v_memview->view.buf); - - /* "View.MemoryView":1074 - * dst.data = memview.view.buf - * - * for dim in range(memview.view.ndim): # <<<<<<<<<<<<<< - * dst.shape[dim] = shape[dim] - * dst.strides[dim] = strides[dim] - */ - __pyx_t_2 = __pyx_v_memview->view.ndim; - __pyx_t_3 = __pyx_t_2; - for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { - __pyx_v_dim = __pyx_t_4; - - /* "View.MemoryView":1075 - * - * for dim in range(memview.view.ndim): - * dst.shape[dim] = shape[dim] # <<<<<<<<<<<<<< - * dst.strides[dim] = strides[dim] - * dst.suboffsets[dim] = suboffsets[dim] if suboffsets else -1 - */ - (__pyx_v_dst->shape[__pyx_v_dim]) = (__pyx_v_shape[__pyx_v_dim]); - - /* "View.MemoryView":1076 - * for dim in range(memview.view.ndim): - * dst.shape[dim] = shape[dim] - * dst.strides[dim] = strides[dim] # <<<<<<<<<<<<<< - * dst.suboffsets[dim] = suboffsets[dim] if suboffsets else -1 - * - */ - (__pyx_v_dst->strides[__pyx_v_dim]) = (__pyx_v_strides[__pyx_v_dim]); - - /* "View.MemoryView":1077 - * dst.shape[dim] = shape[dim] - * dst.strides[dim] = strides[dim] - * dst.suboffsets[dim] = suboffsets[dim] if suboffsets else -1 # <<<<<<<<<<<<<< - * - * @cname('__pyx_memoryview_copy_object') - */ - __pyx_t_6 = (__pyx_v_suboffsets != 0); - if (__pyx_t_6) { - __pyx_t_5 = (__pyx_v_suboffsets[__pyx_v_dim]); - } else { - __pyx_t_5 = -1L; - } - (__pyx_v_dst->suboffsets[__pyx_v_dim]) = __pyx_t_5; - } - - /* "View.MemoryView":1063 - * - * @cname('__pyx_memoryview_slice_copy') - * cdef void slice_copy(memoryview memview, __Pyx_memviewslice *dst) noexcept: # <<<<<<<<<<<<<< - * cdef int dim - * cdef (Py_ssize_t*) shape, strides, suboffsets - */ - - /* function exit code */ -} - -/* "View.MemoryView":1080 - * - * @cname('__pyx_memoryview_copy_object') - * cdef memoryview_copy(memoryview memview): # <<<<<<<<<<<<<< - * "Create a new memoryview object" - * cdef __Pyx_memviewslice memviewslice - */ - -static PyObject *__pyx_memoryview_copy_object(struct __pyx_memoryview_obj *__pyx_v_memview) { - __Pyx_memviewslice __pyx_v_memviewslice; - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - PyObject *__pyx_t_1 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("memoryview_copy", 1); - - /* "View.MemoryView":1083 - * "Create a new memoryview object" - * cdef __Pyx_memviewslice memviewslice - * slice_copy(memview, &memviewslice) # <<<<<<<<<<<<<< - * return memoryview_copy_from_slice(memview, &memviewslice) - * - */ - __pyx_memoryview_slice_copy(__pyx_v_memview, (&__pyx_v_memviewslice)); - - /* "View.MemoryView":1084 - * cdef __Pyx_memviewslice memviewslice - * slice_copy(memview, &memviewslice) - * return memoryview_copy_from_slice(memview, &memviewslice) # <<<<<<<<<<<<<< - * - * @cname('__pyx_memoryview_copy_object_from_slice') - */ - __Pyx_XDECREF(__pyx_r); - __pyx_t_1 = __pyx_memoryview_copy_object_from_slice(__pyx_v_memview, (&__pyx_v_memviewslice)); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 1084, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_r = __pyx_t_1; - __pyx_t_1 = 0; - goto __pyx_L0; - - /* "View.MemoryView":1080 - * - * @cname('__pyx_memoryview_copy_object') - * cdef memoryview_copy(memoryview memview): # <<<<<<<<<<<<<< - * "Create a new memoryview object" - * cdef __Pyx_memviewslice memviewslice - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_1); - __Pyx_AddTraceback("View.MemoryView.memoryview_copy", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = 0; - __pyx_L0:; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "View.MemoryView":1087 - * - * @cname('__pyx_memoryview_copy_object_from_slice') - * cdef memoryview_copy_from_slice(memoryview memview, __Pyx_memviewslice *memviewslice): # <<<<<<<<<<<<<< - * """ - * Create a new memoryview object from a given memoryview object and slice. - */ - -static PyObject *__pyx_memoryview_copy_object_from_slice(struct __pyx_memoryview_obj *__pyx_v_memview, __Pyx_memviewslice *__pyx_v_memviewslice) { - PyObject *(*__pyx_v_to_object_func)(char *); - int (*__pyx_v_to_dtype_func)(char *, PyObject *); - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - int __pyx_t_1; - PyObject *(*__pyx_t_2)(char *); - int (*__pyx_t_3)(char *, PyObject *); - PyObject *__pyx_t_4 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("memoryview_copy_from_slice", 1); - - /* "View.MemoryView":1094 - * cdef int (*to_dtype_func)(char *, object) except 0 - * - * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< - * to_object_func = (<_memoryviewslice> memview).to_object_func - * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func - */ - __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); - if (__pyx_t_1) { - - /* "View.MemoryView":1095 - * - * if isinstance(memview, _memoryviewslice): - * to_object_func = (<_memoryviewslice> memview).to_object_func # <<<<<<<<<<<<<< - * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func - * else: - */ - __pyx_t_2 = ((struct __pyx_memoryviewslice_obj *)__pyx_v_memview)->to_object_func; - __pyx_v_to_object_func = __pyx_t_2; - - /* "View.MemoryView":1096 - * if isinstance(memview, _memoryviewslice): - * to_object_func = (<_memoryviewslice> memview).to_object_func - * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func # <<<<<<<<<<<<<< - * else: - * to_object_func = NULL - */ - __pyx_t_3 = ((struct __pyx_memoryviewslice_obj *)__pyx_v_memview)->to_dtype_func; - __pyx_v_to_dtype_func = __pyx_t_3; - - /* "View.MemoryView":1094 - * cdef int (*to_dtype_func)(char *, object) except 0 - * - * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< - * to_object_func = (<_memoryviewslice> memview).to_object_func - * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func - */ - goto __pyx_L3; - } - - /* "View.MemoryView":1098 - * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func - * else: - * to_object_func = NULL # <<<<<<<<<<<<<< - * to_dtype_func = NULL - * - */ - /*else*/ { - __pyx_v_to_object_func = NULL; - - /* "View.MemoryView":1099 - * else: - * to_object_func = NULL - * to_dtype_func = NULL # <<<<<<<<<<<<<< - * - * return memoryview_fromslice(memviewslice[0], memview.view.ndim, - */ - __pyx_v_to_dtype_func = NULL; - } - __pyx_L3:; - - /* "View.MemoryView":1101 - * to_dtype_func = NULL - * - * return memoryview_fromslice(memviewslice[0], memview.view.ndim, # <<<<<<<<<<<<<< - * to_object_func, to_dtype_func, - * memview.dtype_is_object) - */ - __Pyx_XDECREF(__pyx_r); - - /* "View.MemoryView":1103 - * return memoryview_fromslice(memviewslice[0], memview.view.ndim, - * to_object_func, to_dtype_func, - * memview.dtype_is_object) # <<<<<<<<<<<<<< - * - * - */ - __pyx_t_4 = __pyx_memoryview_fromslice((__pyx_v_memviewslice[0]), __pyx_v_memview->view.ndim, __pyx_v_to_object_func, __pyx_v_to_dtype_func, __pyx_v_memview->dtype_is_object); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1101, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __pyx_r = __pyx_t_4; - __pyx_t_4 = 0; - goto __pyx_L0; - - /* "View.MemoryView":1087 - * - * @cname('__pyx_memoryview_copy_object_from_slice') - * cdef memoryview_copy_from_slice(memoryview memview, __Pyx_memviewslice *memviewslice): # <<<<<<<<<<<<<< - * """ - * Create a new memoryview object from a given memoryview object and slice. - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_4); - __Pyx_AddTraceback("View.MemoryView.memoryview_copy_from_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = 0; - __pyx_L0:; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "View.MemoryView":1109 - * - * - * cdef Py_ssize_t abs_py_ssize_t(Py_ssize_t arg) noexcept nogil: # <<<<<<<<<<<<<< - * return -arg if arg < 0 else arg - * - */ - -static Py_ssize_t abs_py_ssize_t(Py_ssize_t __pyx_v_arg) { - Py_ssize_t __pyx_r; - Py_ssize_t __pyx_t_1; - int __pyx_t_2; - - /* "View.MemoryView":1110 - * - * cdef Py_ssize_t abs_py_ssize_t(Py_ssize_t arg) noexcept nogil: - * return -arg if arg < 0 else arg # <<<<<<<<<<<<<< - * - * @cname('__pyx_get_best_slice_order') - */ - __pyx_t_2 = (__pyx_v_arg < 0); - if (__pyx_t_2) { - __pyx_t_1 = (-__pyx_v_arg); - } else { - __pyx_t_1 = __pyx_v_arg; - } - __pyx_r = __pyx_t_1; - goto __pyx_L0; - - /* "View.MemoryView":1109 - * - * - * cdef Py_ssize_t abs_py_ssize_t(Py_ssize_t arg) noexcept nogil: # <<<<<<<<<<<<<< - * return -arg if arg < 0 else arg - * - */ - - /* function exit code */ - __pyx_L0:; - return __pyx_r; -} - -/* "View.MemoryView":1113 - * - * @cname('__pyx_get_best_slice_order') - * cdef char get_best_order(__Pyx_memviewslice *mslice, int ndim) noexcept nogil: # <<<<<<<<<<<<<< - * """ - * Figure out the best memory access order for a given slice. - */ - -static char __pyx_get_best_slice_order(__Pyx_memviewslice *__pyx_v_mslice, int __pyx_v_ndim) { - int __pyx_v_i; - Py_ssize_t __pyx_v_c_stride; - Py_ssize_t __pyx_v_f_stride; - char __pyx_r; - int __pyx_t_1; - int __pyx_t_2; - int __pyx_t_3; - int __pyx_t_4; - - /* "View.MemoryView":1118 - * """ - * cdef int i - * cdef Py_ssize_t c_stride = 0 # <<<<<<<<<<<<<< - * cdef Py_ssize_t f_stride = 0 - * - */ - __pyx_v_c_stride = 0; - - /* "View.MemoryView":1119 - * cdef int i - * cdef Py_ssize_t c_stride = 0 - * cdef Py_ssize_t f_stride = 0 # <<<<<<<<<<<<<< - * - * for i in range(ndim - 1, -1, -1): - */ - __pyx_v_f_stride = 0; - - /* "View.MemoryView":1121 - * cdef Py_ssize_t f_stride = 0 - * - * for i in range(ndim - 1, -1, -1): # <<<<<<<<<<<<<< - * if mslice.shape[i] > 1: - * c_stride = mslice.strides[i] - */ - for (__pyx_t_1 = (__pyx_v_ndim - 1); __pyx_t_1 > -1; __pyx_t_1-=1) { - __pyx_v_i = __pyx_t_1; - - /* "View.MemoryView":1122 - * - * for i in range(ndim - 1, -1, -1): - * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< - * c_stride = mslice.strides[i] - * break - */ - __pyx_t_2 = ((__pyx_v_mslice->shape[__pyx_v_i]) > 1); - if (__pyx_t_2) { - - /* "View.MemoryView":1123 - * for i in range(ndim - 1, -1, -1): - * if mslice.shape[i] > 1: - * c_stride = mslice.strides[i] # <<<<<<<<<<<<<< - * break - * - */ - __pyx_v_c_stride = (__pyx_v_mslice->strides[__pyx_v_i]); - - /* "View.MemoryView":1124 - * if mslice.shape[i] > 1: - * c_stride = mslice.strides[i] - * break # <<<<<<<<<<<<<< - * - * for i in range(ndim): - */ - goto __pyx_L4_break; - - /* "View.MemoryView":1122 - * - * for i in range(ndim - 1, -1, -1): - * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< - * c_stride = mslice.strides[i] - * break - */ - } - } - __pyx_L4_break:; - - /* "View.MemoryView":1126 - * break - * - * for i in range(ndim): # <<<<<<<<<<<<<< - * if mslice.shape[i] > 1: - * f_stride = mslice.strides[i] - */ - __pyx_t_1 = __pyx_v_ndim; - __pyx_t_3 = __pyx_t_1; - for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { - __pyx_v_i = __pyx_t_4; - - /* "View.MemoryView":1127 - * - * for i in range(ndim): - * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< - * f_stride = mslice.strides[i] - * break - */ - __pyx_t_2 = ((__pyx_v_mslice->shape[__pyx_v_i]) > 1); - if (__pyx_t_2) { - - /* "View.MemoryView":1128 - * for i in range(ndim): - * if mslice.shape[i] > 1: - * f_stride = mslice.strides[i] # <<<<<<<<<<<<<< - * break - * - */ - __pyx_v_f_stride = (__pyx_v_mslice->strides[__pyx_v_i]); - - /* "View.MemoryView":1129 - * if mslice.shape[i] > 1: - * f_stride = mslice.strides[i] - * break # <<<<<<<<<<<<<< - * - * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): - */ - goto __pyx_L7_break; - - /* "View.MemoryView":1127 - * - * for i in range(ndim): - * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< - * f_stride = mslice.strides[i] - * break - */ - } - } - __pyx_L7_break:; - - /* "View.MemoryView":1131 - * break - * - * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): # <<<<<<<<<<<<<< - * return 'C' - * else: - */ - __pyx_t_2 = (abs_py_ssize_t(__pyx_v_c_stride) <= abs_py_ssize_t(__pyx_v_f_stride)); - if (__pyx_t_2) { - - /* "View.MemoryView":1132 - * - * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): - * return 'C' # <<<<<<<<<<<<<< - * else: - * return 'F' - */ - __pyx_r = 'C'; - goto __pyx_L0; - - /* "View.MemoryView":1131 - * break - * - * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): # <<<<<<<<<<<<<< - * return 'C' - * else: - */ - } - - /* "View.MemoryView":1134 - * return 'C' - * else: - * return 'F' # <<<<<<<<<<<<<< - * - * @cython.cdivision(True) - */ - /*else*/ { - __pyx_r = 'F'; - goto __pyx_L0; - } - - /* "View.MemoryView":1113 - * - * @cname('__pyx_get_best_slice_order') - * cdef char get_best_order(__Pyx_memviewslice *mslice, int ndim) noexcept nogil: # <<<<<<<<<<<<<< - * """ - * Figure out the best memory access order for a given slice. - */ - - /* function exit code */ - __pyx_L0:; - return __pyx_r; -} - -/* "View.MemoryView":1137 - * - * @cython.cdivision(True) - * cdef void _copy_strided_to_strided(char *src_data, Py_ssize_t *src_strides, # <<<<<<<<<<<<<< - * char *dst_data, Py_ssize_t *dst_strides, - * Py_ssize_t *src_shape, Py_ssize_t *dst_shape, - */ - -static void _copy_strided_to_strided(char *__pyx_v_src_data, Py_ssize_t *__pyx_v_src_strides, char *__pyx_v_dst_data, Py_ssize_t *__pyx_v_dst_strides, Py_ssize_t *__pyx_v_src_shape, Py_ssize_t *__pyx_v_dst_shape, int __pyx_v_ndim, size_t __pyx_v_itemsize) { - CYTHON_UNUSED Py_ssize_t __pyx_v_i; - CYTHON_UNUSED Py_ssize_t __pyx_v_src_extent; - Py_ssize_t __pyx_v_dst_extent; - Py_ssize_t __pyx_v_src_stride; - Py_ssize_t __pyx_v_dst_stride; - int __pyx_t_1; - int __pyx_t_2; - Py_ssize_t __pyx_t_3; - Py_ssize_t __pyx_t_4; - Py_ssize_t __pyx_t_5; - - /* "View.MemoryView":1144 - * - * cdef Py_ssize_t i - * cdef Py_ssize_t src_extent = src_shape[0] # <<<<<<<<<<<<<< - * cdef Py_ssize_t dst_extent = dst_shape[0] - * cdef Py_ssize_t src_stride = src_strides[0] - */ - __pyx_v_src_extent = (__pyx_v_src_shape[0]); - - /* "View.MemoryView":1145 - * cdef Py_ssize_t i - * cdef Py_ssize_t src_extent = src_shape[0] - * cdef Py_ssize_t dst_extent = dst_shape[0] # <<<<<<<<<<<<<< - * cdef Py_ssize_t src_stride = src_strides[0] - * cdef Py_ssize_t dst_stride = dst_strides[0] - */ - __pyx_v_dst_extent = (__pyx_v_dst_shape[0]); - - /* "View.MemoryView":1146 - * cdef Py_ssize_t src_extent = src_shape[0] - * cdef Py_ssize_t dst_extent = dst_shape[0] - * cdef Py_ssize_t src_stride = src_strides[0] # <<<<<<<<<<<<<< - * cdef Py_ssize_t dst_stride = dst_strides[0] - * - */ - __pyx_v_src_stride = (__pyx_v_src_strides[0]); - - /* "View.MemoryView":1147 - * cdef Py_ssize_t dst_extent = dst_shape[0] - * cdef Py_ssize_t src_stride = src_strides[0] - * cdef Py_ssize_t dst_stride = dst_strides[0] # <<<<<<<<<<<<<< - * - * if ndim == 1: - */ - __pyx_v_dst_stride = (__pyx_v_dst_strides[0]); - - /* "View.MemoryView":1149 - * cdef Py_ssize_t dst_stride = dst_strides[0] - * - * if ndim == 1: # <<<<<<<<<<<<<< - * if (src_stride > 0 and dst_stride > 0 and - * src_stride == itemsize == dst_stride): - */ - __pyx_t_1 = (__pyx_v_ndim == 1); - if (__pyx_t_1) { - - /* "View.MemoryView":1150 - * - * if ndim == 1: - * if (src_stride > 0 and dst_stride > 0 and # <<<<<<<<<<<<<< - * src_stride == itemsize == dst_stride): - * memcpy(dst_data, src_data, itemsize * dst_extent) - */ - __pyx_t_2 = (__pyx_v_src_stride > 0); - if (__pyx_t_2) { - } else { - __pyx_t_1 = __pyx_t_2; - goto __pyx_L5_bool_binop_done; - } - __pyx_t_2 = (__pyx_v_dst_stride > 0); - if (__pyx_t_2) { - } else { - __pyx_t_1 = __pyx_t_2; - goto __pyx_L5_bool_binop_done; - } - - /* "View.MemoryView":1151 - * if ndim == 1: - * if (src_stride > 0 and dst_stride > 0 and - * src_stride == itemsize == dst_stride): # <<<<<<<<<<<<<< - * memcpy(dst_data, src_data, itemsize * dst_extent) - * else: - */ - __pyx_t_2 = (((size_t)__pyx_v_src_stride) == __pyx_v_itemsize); - if (__pyx_t_2) { - __pyx_t_2 = (__pyx_v_itemsize == ((size_t)__pyx_v_dst_stride)); - } - __pyx_t_1 = __pyx_t_2; - __pyx_L5_bool_binop_done:; - - /* "View.MemoryView":1150 - * - * if ndim == 1: - * if (src_stride > 0 and dst_stride > 0 and # <<<<<<<<<<<<<< - * src_stride == itemsize == dst_stride): - * memcpy(dst_data, src_data, itemsize * dst_extent) - */ - if (__pyx_t_1) { - - /* "View.MemoryView":1152 - * if (src_stride > 0 and dst_stride > 0 and - * src_stride == itemsize == dst_stride): - * memcpy(dst_data, src_data, itemsize * dst_extent) # <<<<<<<<<<<<<< - * else: - * for i in range(dst_extent): - */ - (void)(memcpy(__pyx_v_dst_data, __pyx_v_src_data, (__pyx_v_itemsize * __pyx_v_dst_extent))); - - /* "View.MemoryView":1150 - * - * if ndim == 1: - * if (src_stride > 0 and dst_stride > 0 and # <<<<<<<<<<<<<< - * src_stride == itemsize == dst_stride): - * memcpy(dst_data, src_data, itemsize * dst_extent) - */ - goto __pyx_L4; - } - - /* "View.MemoryView":1154 - * memcpy(dst_data, src_data, itemsize * dst_extent) - * else: - * for i in range(dst_extent): # <<<<<<<<<<<<<< - * memcpy(dst_data, src_data, itemsize) - * src_data += src_stride - */ - /*else*/ { - __pyx_t_3 = __pyx_v_dst_extent; - __pyx_t_4 = __pyx_t_3; - for (__pyx_t_5 = 0; __pyx_t_5 < __pyx_t_4; __pyx_t_5+=1) { - __pyx_v_i = __pyx_t_5; - - /* "View.MemoryView":1155 - * else: - * for i in range(dst_extent): - * memcpy(dst_data, src_data, itemsize) # <<<<<<<<<<<<<< - * src_data += src_stride - * dst_data += dst_stride - */ - (void)(memcpy(__pyx_v_dst_data, __pyx_v_src_data, __pyx_v_itemsize)); - - /* "View.MemoryView":1156 - * for i in range(dst_extent): - * memcpy(dst_data, src_data, itemsize) - * src_data += src_stride # <<<<<<<<<<<<<< - * dst_data += dst_stride - * else: - */ - __pyx_v_src_data = (__pyx_v_src_data + __pyx_v_src_stride); - - /* "View.MemoryView":1157 - * memcpy(dst_data, src_data, itemsize) - * src_data += src_stride - * dst_data += dst_stride # <<<<<<<<<<<<<< - * else: - * for i in range(dst_extent): - */ - __pyx_v_dst_data = (__pyx_v_dst_data + __pyx_v_dst_stride); - } - } - __pyx_L4:; - - /* "View.MemoryView":1149 - * cdef Py_ssize_t dst_stride = dst_strides[0] - * - * if ndim == 1: # <<<<<<<<<<<<<< - * if (src_stride > 0 and dst_stride > 0 and - * src_stride == itemsize == dst_stride): - */ - goto __pyx_L3; - } - - /* "View.MemoryView":1159 - * dst_data += dst_stride - * else: - * for i in range(dst_extent): # <<<<<<<<<<<<<< - * _copy_strided_to_strided(src_data, src_strides + 1, - * dst_data, dst_strides + 1, - */ - /*else*/ { - __pyx_t_3 = __pyx_v_dst_extent; - __pyx_t_4 = __pyx_t_3; - for (__pyx_t_5 = 0; __pyx_t_5 < __pyx_t_4; __pyx_t_5+=1) { - __pyx_v_i = __pyx_t_5; - - /* "View.MemoryView":1160 - * else: - * for i in range(dst_extent): - * _copy_strided_to_strided(src_data, src_strides + 1, # <<<<<<<<<<<<<< - * dst_data, dst_strides + 1, - * src_shape + 1, dst_shape + 1, - */ - _copy_strided_to_strided(__pyx_v_src_data, (__pyx_v_src_strides + 1), __pyx_v_dst_data, (__pyx_v_dst_strides + 1), (__pyx_v_src_shape + 1), (__pyx_v_dst_shape + 1), (__pyx_v_ndim - 1), __pyx_v_itemsize); - - /* "View.MemoryView":1164 - * src_shape + 1, dst_shape + 1, - * ndim - 1, itemsize) - * src_data += src_stride # <<<<<<<<<<<<<< - * dst_data += dst_stride - * - */ - __pyx_v_src_data = (__pyx_v_src_data + __pyx_v_src_stride); - - /* "View.MemoryView":1165 - * ndim - 1, itemsize) - * src_data += src_stride - * dst_data += dst_stride # <<<<<<<<<<<<<< - * - * cdef void copy_strided_to_strided(__Pyx_memviewslice *src, - */ - __pyx_v_dst_data = (__pyx_v_dst_data + __pyx_v_dst_stride); - } - } - __pyx_L3:; - - /* "View.MemoryView":1137 - * - * @cython.cdivision(True) - * cdef void _copy_strided_to_strided(char *src_data, Py_ssize_t *src_strides, # <<<<<<<<<<<<<< - * char *dst_data, Py_ssize_t *dst_strides, - * Py_ssize_t *src_shape, Py_ssize_t *dst_shape, - */ - - /* function exit code */ -} - -/* "View.MemoryView":1167 - * dst_data += dst_stride - * - * cdef void copy_strided_to_strided(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< - * __Pyx_memviewslice *dst, - * int ndim, size_t itemsize) noexcept nogil: - */ - -static void copy_strided_to_strided(__Pyx_memviewslice *__pyx_v_src, __Pyx_memviewslice *__pyx_v_dst, int __pyx_v_ndim, size_t __pyx_v_itemsize) { - - /* "View.MemoryView":1170 - * __Pyx_memviewslice *dst, - * int ndim, size_t itemsize) noexcept nogil: - * _copy_strided_to_strided(src.data, src.strides, dst.data, dst.strides, # <<<<<<<<<<<<<< - * src.shape, dst.shape, ndim, itemsize) - * - */ - _copy_strided_to_strided(__pyx_v_src->data, __pyx_v_src->strides, __pyx_v_dst->data, __pyx_v_dst->strides, __pyx_v_src->shape, __pyx_v_dst->shape, __pyx_v_ndim, __pyx_v_itemsize); - - /* "View.MemoryView":1167 - * dst_data += dst_stride - * - * cdef void copy_strided_to_strided(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< - * __Pyx_memviewslice *dst, - * int ndim, size_t itemsize) noexcept nogil: - */ - - /* function exit code */ -} - -/* "View.MemoryView":1174 - * - * @cname('__pyx_memoryview_slice_get_size') - * cdef Py_ssize_t slice_get_size(__Pyx_memviewslice *src, int ndim) noexcept nogil: # <<<<<<<<<<<<<< - * "Return the size of the memory occupied by the slice in number of bytes" - * cdef Py_ssize_t shape, size = src.memview.view.itemsize - */ - -static Py_ssize_t __pyx_memoryview_slice_get_size(__Pyx_memviewslice *__pyx_v_src, int __pyx_v_ndim) { - Py_ssize_t __pyx_v_shape; - Py_ssize_t __pyx_v_size; - Py_ssize_t __pyx_r; - Py_ssize_t __pyx_t_1; - Py_ssize_t *__pyx_t_2; - Py_ssize_t *__pyx_t_3; - Py_ssize_t *__pyx_t_4; - - /* "View.MemoryView":1176 - * cdef Py_ssize_t slice_get_size(__Pyx_memviewslice *src, int ndim) noexcept nogil: - * "Return the size of the memory occupied by the slice in number of bytes" - * cdef Py_ssize_t shape, size = src.memview.view.itemsize # <<<<<<<<<<<<<< - * - * for shape in src.shape[:ndim]: - */ - __pyx_t_1 = __pyx_v_src->memview->view.itemsize; - __pyx_v_size = __pyx_t_1; - - /* "View.MemoryView":1178 - * cdef Py_ssize_t shape, size = src.memview.view.itemsize - * - * for shape in src.shape[:ndim]: # <<<<<<<<<<<<<< - * size *= shape - * - */ - __pyx_t_3 = (__pyx_v_src->shape + __pyx_v_ndim); - for (__pyx_t_4 = __pyx_v_src->shape; __pyx_t_4 < __pyx_t_3; __pyx_t_4++) { - __pyx_t_2 = __pyx_t_4; - __pyx_v_shape = (__pyx_t_2[0]); - - /* "View.MemoryView":1179 - * - * for shape in src.shape[:ndim]: - * size *= shape # <<<<<<<<<<<<<< - * - * return size - */ - __pyx_v_size = (__pyx_v_size * __pyx_v_shape); - } - - /* "View.MemoryView":1181 - * size *= shape - * - * return size # <<<<<<<<<<<<<< - * - * @cname('__pyx_fill_contig_strides_array') - */ - __pyx_r = __pyx_v_size; - goto __pyx_L0; - - /* "View.MemoryView":1174 - * - * @cname('__pyx_memoryview_slice_get_size') - * cdef Py_ssize_t slice_get_size(__Pyx_memviewslice *src, int ndim) noexcept nogil: # <<<<<<<<<<<<<< - * "Return the size of the memory occupied by the slice in number of bytes" - * cdef Py_ssize_t shape, size = src.memview.view.itemsize - */ - - /* function exit code */ - __pyx_L0:; - return __pyx_r; -} - -/* "View.MemoryView":1184 - * - * @cname('__pyx_fill_contig_strides_array') - * cdef Py_ssize_t fill_contig_strides_array( # <<<<<<<<<<<<<< - * Py_ssize_t *shape, Py_ssize_t *strides, Py_ssize_t stride, - * int ndim, char order) noexcept nogil: - */ - -static Py_ssize_t __pyx_fill_contig_strides_array(Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, Py_ssize_t __pyx_v_stride, int __pyx_v_ndim, char __pyx_v_order) { - int __pyx_v_idx; - Py_ssize_t __pyx_r; - int __pyx_t_1; - int __pyx_t_2; - int __pyx_t_3; - int __pyx_t_4; - - /* "View.MemoryView":1193 - * cdef int idx - * - * if order == 'F': # <<<<<<<<<<<<<< - * for idx in range(ndim): - * strides[idx] = stride - */ - __pyx_t_1 = (__pyx_v_order == 'F'); - if (__pyx_t_1) { - - /* "View.MemoryView":1194 - * - * if order == 'F': - * for idx in range(ndim): # <<<<<<<<<<<<<< - * strides[idx] = stride - * stride *= shape[idx] - */ - __pyx_t_2 = __pyx_v_ndim; - __pyx_t_3 = __pyx_t_2; - for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { - __pyx_v_idx = __pyx_t_4; - - /* "View.MemoryView":1195 - * if order == 'F': - * for idx in range(ndim): - * strides[idx] = stride # <<<<<<<<<<<<<< - * stride *= shape[idx] - * else: - */ - (__pyx_v_strides[__pyx_v_idx]) = __pyx_v_stride; - - /* "View.MemoryView":1196 - * for idx in range(ndim): - * strides[idx] = stride - * stride *= shape[idx] # <<<<<<<<<<<<<< - * else: - * for idx in range(ndim - 1, -1, -1): - */ - __pyx_v_stride = (__pyx_v_stride * (__pyx_v_shape[__pyx_v_idx])); - } - - /* "View.MemoryView":1193 - * cdef int idx - * - * if order == 'F': # <<<<<<<<<<<<<< - * for idx in range(ndim): - * strides[idx] = stride - */ - goto __pyx_L3; - } - - /* "View.MemoryView":1198 - * stride *= shape[idx] - * else: - * for idx in range(ndim - 1, -1, -1): # <<<<<<<<<<<<<< - * strides[idx] = stride - * stride *= shape[idx] - */ - /*else*/ { - for (__pyx_t_2 = (__pyx_v_ndim - 1); __pyx_t_2 > -1; __pyx_t_2-=1) { - __pyx_v_idx = __pyx_t_2; - - /* "View.MemoryView":1199 - * else: - * for idx in range(ndim - 1, -1, -1): - * strides[idx] = stride # <<<<<<<<<<<<<< - * stride *= shape[idx] - * - */ - (__pyx_v_strides[__pyx_v_idx]) = __pyx_v_stride; - - /* "View.MemoryView":1200 - * for idx in range(ndim - 1, -1, -1): - * strides[idx] = stride - * stride *= shape[idx] # <<<<<<<<<<<<<< - * - * return stride - */ - __pyx_v_stride = (__pyx_v_stride * (__pyx_v_shape[__pyx_v_idx])); - } - } - __pyx_L3:; - - /* "View.MemoryView":1202 - * stride *= shape[idx] - * - * return stride # <<<<<<<<<<<<<< - * - * @cname('__pyx_memoryview_copy_data_to_temp') - */ - __pyx_r = __pyx_v_stride; - goto __pyx_L0; - - /* "View.MemoryView":1184 - * - * @cname('__pyx_fill_contig_strides_array') - * cdef Py_ssize_t fill_contig_strides_array( # <<<<<<<<<<<<<< - * Py_ssize_t *shape, Py_ssize_t *strides, Py_ssize_t stride, - * int ndim, char order) noexcept nogil: - */ - - /* function exit code */ - __pyx_L0:; - return __pyx_r; -} - -/* "View.MemoryView":1205 - * - * @cname('__pyx_memoryview_copy_data_to_temp') - * cdef void *copy_data_to_temp(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< - * __Pyx_memviewslice *tmpslice, - * char order, - */ - -static void *__pyx_memoryview_copy_data_to_temp(__Pyx_memviewslice *__pyx_v_src, __Pyx_memviewslice *__pyx_v_tmpslice, char __pyx_v_order, int __pyx_v_ndim) { - int __pyx_v_i; - void *__pyx_v_result; - size_t __pyx_v_itemsize; - size_t __pyx_v_size; - void *__pyx_r; - Py_ssize_t __pyx_t_1; - int __pyx_t_2; - int __pyx_t_3; - struct __pyx_memoryview_obj *__pyx_t_4; - int __pyx_t_5; - int __pyx_t_6; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - #ifdef WITH_THREAD - PyGILState_STATE __pyx_gilstate_save; - #endif - - /* "View.MemoryView":1216 - * cdef void *result - * - * cdef size_t itemsize = src.memview.view.itemsize # <<<<<<<<<<<<<< - * cdef size_t size = slice_get_size(src, ndim) - * - */ - __pyx_t_1 = __pyx_v_src->memview->view.itemsize; - __pyx_v_itemsize = __pyx_t_1; - - /* "View.MemoryView":1217 - * - * cdef size_t itemsize = src.memview.view.itemsize - * cdef size_t size = slice_get_size(src, ndim) # <<<<<<<<<<<<<< - * - * result = malloc(size) - */ - __pyx_v_size = __pyx_memoryview_slice_get_size(__pyx_v_src, __pyx_v_ndim); - - /* "View.MemoryView":1219 - * cdef size_t size = slice_get_size(src, ndim) - * - * result = malloc(size) # <<<<<<<<<<<<<< - * if not result: - * _err_no_memory() - */ - __pyx_v_result = malloc(__pyx_v_size); - - /* "View.MemoryView":1220 - * - * result = malloc(size) - * if not result: # <<<<<<<<<<<<<< - * _err_no_memory() - * - */ - __pyx_t_2 = (!(__pyx_v_result != 0)); - if (__pyx_t_2) { - - /* "View.MemoryView":1221 - * result = malloc(size) - * if not result: - * _err_no_memory() # <<<<<<<<<<<<<< - * - * - */ - __pyx_t_3 = __pyx_memoryview_err_no_memory(); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(1, 1221, __pyx_L1_error) - - /* "View.MemoryView":1220 - * - * result = malloc(size) - * if not result: # <<<<<<<<<<<<<< - * _err_no_memory() - * - */ - } - - /* "View.MemoryView":1224 - * - * - * tmpslice.data = result # <<<<<<<<<<<<<< - * tmpslice.memview = src.memview - * for i in range(ndim): - */ - __pyx_v_tmpslice->data = ((char *)__pyx_v_result); - - /* "View.MemoryView":1225 - * - * tmpslice.data = result - * tmpslice.memview = src.memview # <<<<<<<<<<<<<< - * for i in range(ndim): - * tmpslice.shape[i] = src.shape[i] - */ - __pyx_t_4 = __pyx_v_src->memview; - __pyx_v_tmpslice->memview = __pyx_t_4; - - /* "View.MemoryView":1226 - * tmpslice.data = result - * tmpslice.memview = src.memview - * for i in range(ndim): # <<<<<<<<<<<<<< - * tmpslice.shape[i] = src.shape[i] - * tmpslice.suboffsets[i] = -1 - */ - __pyx_t_3 = __pyx_v_ndim; - __pyx_t_5 = __pyx_t_3; - for (__pyx_t_6 = 0; __pyx_t_6 < __pyx_t_5; __pyx_t_6+=1) { - __pyx_v_i = __pyx_t_6; - - /* "View.MemoryView":1227 - * tmpslice.memview = src.memview - * for i in range(ndim): - * tmpslice.shape[i] = src.shape[i] # <<<<<<<<<<<<<< - * tmpslice.suboffsets[i] = -1 - * - */ - (__pyx_v_tmpslice->shape[__pyx_v_i]) = (__pyx_v_src->shape[__pyx_v_i]); - - /* "View.MemoryView":1228 - * for i in range(ndim): - * tmpslice.shape[i] = src.shape[i] - * tmpslice.suboffsets[i] = -1 # <<<<<<<<<<<<<< - * - * fill_contig_strides_array(&tmpslice.shape[0], &tmpslice.strides[0], itemsize, ndim, order) - */ - (__pyx_v_tmpslice->suboffsets[__pyx_v_i]) = -1L; - } - - /* "View.MemoryView":1230 - * tmpslice.suboffsets[i] = -1 - * - * fill_contig_strides_array(&tmpslice.shape[0], &tmpslice.strides[0], itemsize, ndim, order) # <<<<<<<<<<<<<< - * - * - */ - (void)(__pyx_fill_contig_strides_array((&(__pyx_v_tmpslice->shape[0])), (&(__pyx_v_tmpslice->strides[0])), __pyx_v_itemsize, __pyx_v_ndim, __pyx_v_order)); - - /* "View.MemoryView":1233 - * - * - * for i in range(ndim): # <<<<<<<<<<<<<< - * if tmpslice.shape[i] == 1: - * tmpslice.strides[i] = 0 - */ - __pyx_t_3 = __pyx_v_ndim; - __pyx_t_5 = __pyx_t_3; - for (__pyx_t_6 = 0; __pyx_t_6 < __pyx_t_5; __pyx_t_6+=1) { - __pyx_v_i = __pyx_t_6; - - /* "View.MemoryView":1234 - * - * for i in range(ndim): - * if tmpslice.shape[i] == 1: # <<<<<<<<<<<<<< - * tmpslice.strides[i] = 0 - * - */ - __pyx_t_2 = ((__pyx_v_tmpslice->shape[__pyx_v_i]) == 1); - if (__pyx_t_2) { - - /* "View.MemoryView":1235 - * for i in range(ndim): - * if tmpslice.shape[i] == 1: - * tmpslice.strides[i] = 0 # <<<<<<<<<<<<<< - * - * if slice_is_contig(src[0], order, ndim): - */ - (__pyx_v_tmpslice->strides[__pyx_v_i]) = 0; - - /* "View.MemoryView":1234 - * - * for i in range(ndim): - * if tmpslice.shape[i] == 1: # <<<<<<<<<<<<<< - * tmpslice.strides[i] = 0 - * - */ - } - } - - /* "View.MemoryView":1237 - * tmpslice.strides[i] = 0 - * - * if slice_is_contig(src[0], order, ndim): # <<<<<<<<<<<<<< - * memcpy(result, src.data, size) - * else: - */ - __pyx_t_2 = __pyx_memviewslice_is_contig((__pyx_v_src[0]), __pyx_v_order, __pyx_v_ndim); - if (__pyx_t_2) { - - /* "View.MemoryView":1238 - * - * if slice_is_contig(src[0], order, ndim): - * memcpy(result, src.data, size) # <<<<<<<<<<<<<< - * else: - * copy_strided_to_strided(src, tmpslice, ndim, itemsize) - */ - (void)(memcpy(__pyx_v_result, __pyx_v_src->data, __pyx_v_size)); - - /* "View.MemoryView":1237 - * tmpslice.strides[i] = 0 - * - * if slice_is_contig(src[0], order, ndim): # <<<<<<<<<<<<<< - * memcpy(result, src.data, size) - * else: - */ - goto __pyx_L9; - } - - /* "View.MemoryView":1240 - * memcpy(result, src.data, size) - * else: - * copy_strided_to_strided(src, tmpslice, ndim, itemsize) # <<<<<<<<<<<<<< - * - * return result - */ - /*else*/ { - copy_strided_to_strided(__pyx_v_src, __pyx_v_tmpslice, __pyx_v_ndim, __pyx_v_itemsize); - } - __pyx_L9:; - - /* "View.MemoryView":1242 - * copy_strided_to_strided(src, tmpslice, ndim, itemsize) - * - * return result # <<<<<<<<<<<<<< - * - * - */ - __pyx_r = __pyx_v_result; - goto __pyx_L0; - - /* "View.MemoryView":1205 - * - * @cname('__pyx_memoryview_copy_data_to_temp') - * cdef void *copy_data_to_temp(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< - * __Pyx_memviewslice *tmpslice, - * char order, - */ - - /* function exit code */ - __pyx_L1_error:; - #ifdef WITH_THREAD - __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); - #endif - __Pyx_AddTraceback("View.MemoryView.copy_data_to_temp", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = NULL; - #ifdef WITH_THREAD - __Pyx_PyGILState_Release(__pyx_gilstate_save); - #endif - __pyx_L0:; - return __pyx_r; -} - -/* "View.MemoryView":1247 - * - * @cname('__pyx_memoryview_err_extents') - * cdef int _err_extents(int i, Py_ssize_t extent1, # <<<<<<<<<<<<<< - * Py_ssize_t extent2) except -1 with gil: - * raise ValueError, f"got differing extents in dimension {i} (got {extent1} and {extent2})" - */ - -static int __pyx_memoryview_err_extents(int __pyx_v_i, Py_ssize_t __pyx_v_extent1, Py_ssize_t __pyx_v_extent2) { - int __pyx_r; - __Pyx_RefNannyDeclarations - PyObject *__pyx_t_1 = NULL; - Py_ssize_t __pyx_t_2; - Py_UCS4 __pyx_t_3; - PyObject *__pyx_t_4 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - #ifdef WITH_THREAD - PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); - #endif - __Pyx_RefNannySetupContext("_err_extents", 0); - - /* "View.MemoryView":1249 - * cdef int _err_extents(int i, Py_ssize_t extent1, - * Py_ssize_t extent2) except -1 with gil: - * raise ValueError, f"got differing extents in dimension {i} (got {extent1} and {extent2})" # <<<<<<<<<<<<<< - * - * @cname('__pyx_memoryview_err_dim') - */ - __pyx_t_1 = PyTuple_New(7); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 1249, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_2 = 0; - __pyx_t_3 = 127; - __Pyx_INCREF(__pyx_kp_u_got_differing_extents_in_dimensi); - __pyx_t_2 += 35; - __Pyx_GIVEREF(__pyx_kp_u_got_differing_extents_in_dimensi); - PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_kp_u_got_differing_extents_in_dimensi); - __pyx_t_4 = __Pyx_PyUnicode_From_int(__pyx_v_i, 0, ' ', 'd'); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1249, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __pyx_t_2 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_4); - __Pyx_GIVEREF(__pyx_t_4); - PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_t_4); - __pyx_t_4 = 0; - __Pyx_INCREF(__pyx_kp_u_got); - __pyx_t_2 += 6; - __Pyx_GIVEREF(__pyx_kp_u_got); - PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_kp_u_got); - __pyx_t_4 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_extent1, 0, ' ', 'd'); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1249, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __pyx_t_2 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_4); - __Pyx_GIVEREF(__pyx_t_4); - PyTuple_SET_ITEM(__pyx_t_1, 3, __pyx_t_4); - __pyx_t_4 = 0; - __Pyx_INCREF(__pyx_kp_u_and); - __pyx_t_2 += 5; - __Pyx_GIVEREF(__pyx_kp_u_and); - PyTuple_SET_ITEM(__pyx_t_1, 4, __pyx_kp_u_and); - __pyx_t_4 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_extent2, 0, ' ', 'd'); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1249, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __pyx_t_2 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_4); - __Pyx_GIVEREF(__pyx_t_4); - PyTuple_SET_ITEM(__pyx_t_1, 5, __pyx_t_4); - __pyx_t_4 = 0; - __Pyx_INCREF(__pyx_kp_u__7); - __pyx_t_2 += 1; - __Pyx_GIVEREF(__pyx_kp_u__7); - PyTuple_SET_ITEM(__pyx_t_1, 6, __pyx_kp_u__7); - __pyx_t_4 = __Pyx_PyUnicode_Join(__pyx_t_1, 7, __pyx_t_2, __pyx_t_3); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1249, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __Pyx_Raise(__pyx_builtin_ValueError, __pyx_t_4, 0, 0); - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __PYX_ERR(1, 1249, __pyx_L1_error) - - /* "View.MemoryView":1247 - * - * @cname('__pyx_memoryview_err_extents') - * cdef int _err_extents(int i, Py_ssize_t extent1, # <<<<<<<<<<<<<< - * Py_ssize_t extent2) except -1 with gil: - * raise ValueError, f"got differing extents in dimension {i} (got {extent1} and {extent2})" - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_1); - __Pyx_XDECREF(__pyx_t_4); - __Pyx_AddTraceback("View.MemoryView._err_extents", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = -1; - __Pyx_RefNannyFinishContext(); - #ifdef WITH_THREAD - __Pyx_PyGILState_Release(__pyx_gilstate_save); - #endif - return __pyx_r; -} - -/* "View.MemoryView":1252 - * - * @cname('__pyx_memoryview_err_dim') - * cdef int _err_dim(PyObject *error, str msg, int dim) except -1 with gil: # <<<<<<<<<<<<<< - * raise error, msg % dim - * - */ - -static int __pyx_memoryview_err_dim(PyObject *__pyx_v_error, PyObject *__pyx_v_msg, int __pyx_v_dim) { - int __pyx_r; - __Pyx_RefNannyDeclarations - PyObject *__pyx_t_1 = NULL; - PyObject *__pyx_t_2 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - #ifdef WITH_THREAD - PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); - #endif - __Pyx_RefNannySetupContext("_err_dim", 0); - __Pyx_INCREF(__pyx_v_msg); - - /* "View.MemoryView":1253 - * @cname('__pyx_memoryview_err_dim') - * cdef int _err_dim(PyObject *error, str msg, int dim) except -1 with gil: - * raise error, msg % dim # <<<<<<<<<<<<<< - * - * @cname('__pyx_memoryview_err') - */ - __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_dim); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 1253, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_2 = __Pyx_PyString_FormatSafe(__pyx_v_msg, __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1253, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __Pyx_Raise(((PyObject *)__pyx_v_error), __pyx_t_2, 0, 0); - __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - __PYX_ERR(1, 1253, __pyx_L1_error) - - /* "View.MemoryView":1252 - * - * @cname('__pyx_memoryview_err_dim') - * cdef int _err_dim(PyObject *error, str msg, int dim) except -1 with gil: # <<<<<<<<<<<<<< - * raise error, msg % dim - * - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_1); - __Pyx_XDECREF(__pyx_t_2); - __Pyx_AddTraceback("View.MemoryView._err_dim", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = -1; - __Pyx_XDECREF(__pyx_v_msg); - __Pyx_RefNannyFinishContext(); - #ifdef WITH_THREAD - __Pyx_PyGILState_Release(__pyx_gilstate_save); - #endif - return __pyx_r; -} - -/* "View.MemoryView":1256 - * - * @cname('__pyx_memoryview_err') - * cdef int _err(PyObject *error, str msg) except -1 with gil: # <<<<<<<<<<<<<< - * raise error, msg - * - */ - -static int __pyx_memoryview_err(PyObject *__pyx_v_error, PyObject *__pyx_v_msg) { - int __pyx_r; - __Pyx_RefNannyDeclarations - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - #ifdef WITH_THREAD - PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); - #endif - __Pyx_RefNannySetupContext("_err", 0); - __Pyx_INCREF(__pyx_v_msg); - - /* "View.MemoryView":1257 - * @cname('__pyx_memoryview_err') - * cdef int _err(PyObject *error, str msg) except -1 with gil: - * raise error, msg # <<<<<<<<<<<<<< - * - * @cname('__pyx_memoryview_err_no_memory') - */ - __Pyx_Raise(((PyObject *)__pyx_v_error), __pyx_v_msg, 0, 0); - __PYX_ERR(1, 1257, __pyx_L1_error) - - /* "View.MemoryView":1256 - * - * @cname('__pyx_memoryview_err') - * cdef int _err(PyObject *error, str msg) except -1 with gil: # <<<<<<<<<<<<<< - * raise error, msg - * - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_AddTraceback("View.MemoryView._err", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = -1; - __Pyx_XDECREF(__pyx_v_msg); - __Pyx_RefNannyFinishContext(); - #ifdef WITH_THREAD - __Pyx_PyGILState_Release(__pyx_gilstate_save); - #endif - return __pyx_r; -} - -/* "View.MemoryView":1260 - * - * @cname('__pyx_memoryview_err_no_memory') - * cdef int _err_no_memory() except -1 with gil: # <<<<<<<<<<<<<< - * raise MemoryError - * - */ - -static int __pyx_memoryview_err_no_memory(void) { - int __pyx_r; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - #ifdef WITH_THREAD - PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); - #endif - - /* "View.MemoryView":1261 - * @cname('__pyx_memoryview_err_no_memory') - * cdef int _err_no_memory() except -1 with gil: - * raise MemoryError # <<<<<<<<<<<<<< - * - * - */ - PyErr_NoMemory(); __PYX_ERR(1, 1261, __pyx_L1_error) - - /* "View.MemoryView":1260 - * - * @cname('__pyx_memoryview_err_no_memory') - * cdef int _err_no_memory() except -1 with gil: # <<<<<<<<<<<<<< - * raise MemoryError - * - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_AddTraceback("View.MemoryView._err_no_memory", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = -1; - #ifdef WITH_THREAD - __Pyx_PyGILState_Release(__pyx_gilstate_save); - #endif - return __pyx_r; -} - -/* "View.MemoryView":1265 - * - * @cname('__pyx_memoryview_copy_contents') - * cdef int memoryview_copy_contents(__Pyx_memviewslice src, # <<<<<<<<<<<<<< - * __Pyx_memviewslice dst, - * int src_ndim, int dst_ndim, - */ - -static int __pyx_memoryview_copy_contents(__Pyx_memviewslice __pyx_v_src, __Pyx_memviewslice __pyx_v_dst, int __pyx_v_src_ndim, int __pyx_v_dst_ndim, int __pyx_v_dtype_is_object) { - void *__pyx_v_tmpdata; - size_t __pyx_v_itemsize; - int __pyx_v_i; - char __pyx_v_order; - int __pyx_v_broadcasting; - int __pyx_v_direct_copy; - __Pyx_memviewslice __pyx_v_tmp; - int __pyx_v_ndim; - int __pyx_r; - Py_ssize_t __pyx_t_1; - int __pyx_t_2; - int __pyx_t_3; - int __pyx_t_4; - int __pyx_t_5; - int __pyx_t_6; - void *__pyx_t_7; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - #ifdef WITH_THREAD - PyGILState_STATE __pyx_gilstate_save; - #endif - - /* "View.MemoryView":1273 - * Check for overlapping memory and verify the shapes. - * """ - * cdef void *tmpdata = NULL # <<<<<<<<<<<<<< - * cdef size_t itemsize = src.memview.view.itemsize - * cdef int i - */ - __pyx_v_tmpdata = NULL; - - /* "View.MemoryView":1274 - * """ - * cdef void *tmpdata = NULL - * cdef size_t itemsize = src.memview.view.itemsize # <<<<<<<<<<<<<< - * cdef int i - * cdef char order = get_best_order(&src, src_ndim) - */ - __pyx_t_1 = __pyx_v_src.memview->view.itemsize; - __pyx_v_itemsize = __pyx_t_1; - - /* "View.MemoryView":1276 - * cdef size_t itemsize = src.memview.view.itemsize - * cdef int i - * cdef char order = get_best_order(&src, src_ndim) # <<<<<<<<<<<<<< - * cdef bint broadcasting = False - * cdef bint direct_copy = False - */ - __pyx_v_order = __pyx_get_best_slice_order((&__pyx_v_src), __pyx_v_src_ndim); - - /* "View.MemoryView":1277 - * cdef int i - * cdef char order = get_best_order(&src, src_ndim) - * cdef bint broadcasting = False # <<<<<<<<<<<<<< - * cdef bint direct_copy = False - * cdef __Pyx_memviewslice tmp - */ - __pyx_v_broadcasting = 0; - - /* "View.MemoryView":1278 - * cdef char order = get_best_order(&src, src_ndim) - * cdef bint broadcasting = False - * cdef bint direct_copy = False # <<<<<<<<<<<<<< - * cdef __Pyx_memviewslice tmp - * - */ - __pyx_v_direct_copy = 0; - - /* "View.MemoryView":1281 - * cdef __Pyx_memviewslice tmp - * - * if src_ndim < dst_ndim: # <<<<<<<<<<<<<< - * broadcast_leading(&src, src_ndim, dst_ndim) - * elif dst_ndim < src_ndim: - */ - __pyx_t_2 = (__pyx_v_src_ndim < __pyx_v_dst_ndim); - if (__pyx_t_2) { - - /* "View.MemoryView":1282 - * - * if src_ndim < dst_ndim: - * broadcast_leading(&src, src_ndim, dst_ndim) # <<<<<<<<<<<<<< - * elif dst_ndim < src_ndim: - * broadcast_leading(&dst, dst_ndim, src_ndim) - */ - __pyx_memoryview_broadcast_leading((&__pyx_v_src), __pyx_v_src_ndim, __pyx_v_dst_ndim); - - /* "View.MemoryView":1281 - * cdef __Pyx_memviewslice tmp - * - * if src_ndim < dst_ndim: # <<<<<<<<<<<<<< - * broadcast_leading(&src, src_ndim, dst_ndim) - * elif dst_ndim < src_ndim: - */ - goto __pyx_L3; - } - - /* "View.MemoryView":1283 - * if src_ndim < dst_ndim: - * broadcast_leading(&src, src_ndim, dst_ndim) - * elif dst_ndim < src_ndim: # <<<<<<<<<<<<<< - * broadcast_leading(&dst, dst_ndim, src_ndim) - * - */ - __pyx_t_2 = (__pyx_v_dst_ndim < __pyx_v_src_ndim); - if (__pyx_t_2) { - - /* "View.MemoryView":1284 - * broadcast_leading(&src, src_ndim, dst_ndim) - * elif dst_ndim < src_ndim: - * broadcast_leading(&dst, dst_ndim, src_ndim) # <<<<<<<<<<<<<< - * - * cdef int ndim = max(src_ndim, dst_ndim) - */ - __pyx_memoryview_broadcast_leading((&__pyx_v_dst), __pyx_v_dst_ndim, __pyx_v_src_ndim); - - /* "View.MemoryView":1283 - * if src_ndim < dst_ndim: - * broadcast_leading(&src, src_ndim, dst_ndim) - * elif dst_ndim < src_ndim: # <<<<<<<<<<<<<< - * broadcast_leading(&dst, dst_ndim, src_ndim) - * - */ - } - __pyx_L3:; - - /* "View.MemoryView":1286 - * broadcast_leading(&dst, dst_ndim, src_ndim) - * - * cdef int ndim = max(src_ndim, dst_ndim) # <<<<<<<<<<<<<< - * - * for i in range(ndim): - */ - __pyx_t_3 = __pyx_v_dst_ndim; - __pyx_t_4 = __pyx_v_src_ndim; - __pyx_t_2 = (__pyx_t_3 > __pyx_t_4); - if (__pyx_t_2) { - __pyx_t_5 = __pyx_t_3; - } else { - __pyx_t_5 = __pyx_t_4; - } - __pyx_v_ndim = __pyx_t_5; - - /* "View.MemoryView":1288 - * cdef int ndim = max(src_ndim, dst_ndim) - * - * for i in range(ndim): # <<<<<<<<<<<<<< - * if src.shape[i] != dst.shape[i]: - * if src.shape[i] == 1: - */ - __pyx_t_5 = __pyx_v_ndim; - __pyx_t_3 = __pyx_t_5; - for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { - __pyx_v_i = __pyx_t_4; - - /* "View.MemoryView":1289 - * - * for i in range(ndim): - * if src.shape[i] != dst.shape[i]: # <<<<<<<<<<<<<< - * if src.shape[i] == 1: - * broadcasting = True - */ - __pyx_t_2 = ((__pyx_v_src.shape[__pyx_v_i]) != (__pyx_v_dst.shape[__pyx_v_i])); - if (__pyx_t_2) { - - /* "View.MemoryView":1290 - * for i in range(ndim): - * if src.shape[i] != dst.shape[i]: - * if src.shape[i] == 1: # <<<<<<<<<<<<<< - * broadcasting = True - * src.strides[i] = 0 - */ - __pyx_t_2 = ((__pyx_v_src.shape[__pyx_v_i]) == 1); - if (__pyx_t_2) { - - /* "View.MemoryView":1291 - * if src.shape[i] != dst.shape[i]: - * if src.shape[i] == 1: - * broadcasting = True # <<<<<<<<<<<<<< - * src.strides[i] = 0 - * else: - */ - __pyx_v_broadcasting = 1; - - /* "View.MemoryView":1292 - * if src.shape[i] == 1: - * broadcasting = True - * src.strides[i] = 0 # <<<<<<<<<<<<<< - * else: - * _err_extents(i, dst.shape[i], src.shape[i]) - */ - (__pyx_v_src.strides[__pyx_v_i]) = 0; - - /* "View.MemoryView":1290 - * for i in range(ndim): - * if src.shape[i] != dst.shape[i]: - * if src.shape[i] == 1: # <<<<<<<<<<<<<< - * broadcasting = True - * src.strides[i] = 0 - */ - goto __pyx_L7; - } - - /* "View.MemoryView":1294 - * src.strides[i] = 0 - * else: - * _err_extents(i, dst.shape[i], src.shape[i]) # <<<<<<<<<<<<<< - * - * if src.suboffsets[i] >= 0: - */ - /*else*/ { - __pyx_t_6 = __pyx_memoryview_err_extents(__pyx_v_i, (__pyx_v_dst.shape[__pyx_v_i]), (__pyx_v_src.shape[__pyx_v_i])); if (unlikely(__pyx_t_6 == ((int)-1))) __PYX_ERR(1, 1294, __pyx_L1_error) - } - __pyx_L7:; - - /* "View.MemoryView":1289 - * - * for i in range(ndim): - * if src.shape[i] != dst.shape[i]: # <<<<<<<<<<<<<< - * if src.shape[i] == 1: - * broadcasting = True - */ - } - - /* "View.MemoryView":1296 - * _err_extents(i, dst.shape[i], src.shape[i]) - * - * if src.suboffsets[i] >= 0: # <<<<<<<<<<<<<< - * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) - * - */ - __pyx_t_2 = ((__pyx_v_src.suboffsets[__pyx_v_i]) >= 0); - if (__pyx_t_2) { - - /* "View.MemoryView":1297 - * - * if src.suboffsets[i] >= 0: - * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) # <<<<<<<<<<<<<< - * - * if slices_overlap(&src, &dst, ndim, itemsize): - */ - __pyx_t_6 = __pyx_memoryview_err_dim(PyExc_ValueError, __pyx_kp_s_Dimension_d_is_not_direct, __pyx_v_i); if (unlikely(__pyx_t_6 == ((int)-1))) __PYX_ERR(1, 1297, __pyx_L1_error) - - /* "View.MemoryView":1296 - * _err_extents(i, dst.shape[i], src.shape[i]) - * - * if src.suboffsets[i] >= 0: # <<<<<<<<<<<<<< - * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) - * - */ - } - } - - /* "View.MemoryView":1299 - * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) - * - * if slices_overlap(&src, &dst, ndim, itemsize): # <<<<<<<<<<<<<< - * - * if not slice_is_contig(src, order, ndim): - */ - __pyx_t_2 = __pyx_slices_overlap((&__pyx_v_src), (&__pyx_v_dst), __pyx_v_ndim, __pyx_v_itemsize); - if (__pyx_t_2) { - - /* "View.MemoryView":1301 - * if slices_overlap(&src, &dst, ndim, itemsize): - * - * if not slice_is_contig(src, order, ndim): # <<<<<<<<<<<<<< - * order = get_best_order(&dst, ndim) - * - */ - __pyx_t_2 = (!__pyx_memviewslice_is_contig(__pyx_v_src, __pyx_v_order, __pyx_v_ndim)); - if (__pyx_t_2) { - - /* "View.MemoryView":1302 - * - * if not slice_is_contig(src, order, ndim): - * order = get_best_order(&dst, ndim) # <<<<<<<<<<<<<< - * - * tmpdata = copy_data_to_temp(&src, &tmp, order, ndim) - */ - __pyx_v_order = __pyx_get_best_slice_order((&__pyx_v_dst), __pyx_v_ndim); - - /* "View.MemoryView":1301 - * if slices_overlap(&src, &dst, ndim, itemsize): - * - * if not slice_is_contig(src, order, ndim): # <<<<<<<<<<<<<< - * order = get_best_order(&dst, ndim) - * - */ - } - - /* "View.MemoryView":1304 - * order = get_best_order(&dst, ndim) - * - * tmpdata = copy_data_to_temp(&src, &tmp, order, ndim) # <<<<<<<<<<<<<< - * src = tmp - * - */ - __pyx_t_7 = __pyx_memoryview_copy_data_to_temp((&__pyx_v_src), (&__pyx_v_tmp), __pyx_v_order, __pyx_v_ndim); if (unlikely(__pyx_t_7 == ((void *)NULL))) __PYX_ERR(1, 1304, __pyx_L1_error) - __pyx_v_tmpdata = __pyx_t_7; - - /* "View.MemoryView":1305 - * - * tmpdata = copy_data_to_temp(&src, &tmp, order, ndim) - * src = tmp # <<<<<<<<<<<<<< - * - * if not broadcasting: - */ - __pyx_v_src = __pyx_v_tmp; - - /* "View.MemoryView":1299 - * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) - * - * if slices_overlap(&src, &dst, ndim, itemsize): # <<<<<<<<<<<<<< - * - * if not slice_is_contig(src, order, ndim): - */ - } - - /* "View.MemoryView":1307 - * src = tmp - * - * if not broadcasting: # <<<<<<<<<<<<<< - * - * - */ - __pyx_t_2 = (!__pyx_v_broadcasting); - if (__pyx_t_2) { - - /* "View.MemoryView":1310 - * - * - * if slice_is_contig(src, 'C', ndim): # <<<<<<<<<<<<<< - * direct_copy = slice_is_contig(dst, 'C', ndim) - * elif slice_is_contig(src, 'F', ndim): - */ - __pyx_t_2 = __pyx_memviewslice_is_contig(__pyx_v_src, 'C', __pyx_v_ndim); - if (__pyx_t_2) { - - /* "View.MemoryView":1311 - * - * if slice_is_contig(src, 'C', ndim): - * direct_copy = slice_is_contig(dst, 'C', ndim) # <<<<<<<<<<<<<< - * elif slice_is_contig(src, 'F', ndim): - * direct_copy = slice_is_contig(dst, 'F', ndim) - */ - __pyx_v_direct_copy = __pyx_memviewslice_is_contig(__pyx_v_dst, 'C', __pyx_v_ndim); - - /* "View.MemoryView":1310 - * - * - * if slice_is_contig(src, 'C', ndim): # <<<<<<<<<<<<<< - * direct_copy = slice_is_contig(dst, 'C', ndim) - * elif slice_is_contig(src, 'F', ndim): - */ - goto __pyx_L12; - } - - /* "View.MemoryView":1312 - * if slice_is_contig(src, 'C', ndim): - * direct_copy = slice_is_contig(dst, 'C', ndim) - * elif slice_is_contig(src, 'F', ndim): # <<<<<<<<<<<<<< - * direct_copy = slice_is_contig(dst, 'F', ndim) - * - */ - __pyx_t_2 = __pyx_memviewslice_is_contig(__pyx_v_src, 'F', __pyx_v_ndim); - if (__pyx_t_2) { - - /* "View.MemoryView":1313 - * direct_copy = slice_is_contig(dst, 'C', ndim) - * elif slice_is_contig(src, 'F', ndim): - * direct_copy = slice_is_contig(dst, 'F', ndim) # <<<<<<<<<<<<<< - * - * if direct_copy: - */ - __pyx_v_direct_copy = __pyx_memviewslice_is_contig(__pyx_v_dst, 'F', __pyx_v_ndim); - - /* "View.MemoryView":1312 - * if slice_is_contig(src, 'C', ndim): - * direct_copy = slice_is_contig(dst, 'C', ndim) - * elif slice_is_contig(src, 'F', ndim): # <<<<<<<<<<<<<< - * direct_copy = slice_is_contig(dst, 'F', ndim) - * - */ - } - __pyx_L12:; - - /* "View.MemoryView":1315 - * direct_copy = slice_is_contig(dst, 'F', ndim) - * - * if direct_copy: # <<<<<<<<<<<<<< - * - * refcount_copying(&dst, dtype_is_object, ndim, inc=False) - */ - if (__pyx_v_direct_copy) { - - /* "View.MemoryView":1317 - * if direct_copy: - * - * refcount_copying(&dst, dtype_is_object, ndim, inc=False) # <<<<<<<<<<<<<< - * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) - * refcount_copying(&dst, dtype_is_object, ndim, inc=True) - */ - __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 0); - - /* "View.MemoryView":1318 - * - * refcount_copying(&dst, dtype_is_object, ndim, inc=False) - * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) # <<<<<<<<<<<<<< - * refcount_copying(&dst, dtype_is_object, ndim, inc=True) - * free(tmpdata) - */ - (void)(memcpy(__pyx_v_dst.data, __pyx_v_src.data, __pyx_memoryview_slice_get_size((&__pyx_v_src), __pyx_v_ndim))); - - /* "View.MemoryView":1319 - * refcount_copying(&dst, dtype_is_object, ndim, inc=False) - * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) - * refcount_copying(&dst, dtype_is_object, ndim, inc=True) # <<<<<<<<<<<<<< - * free(tmpdata) - * return 0 - */ - __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 1); - - /* "View.MemoryView":1320 - * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) - * refcount_copying(&dst, dtype_is_object, ndim, inc=True) - * free(tmpdata) # <<<<<<<<<<<<<< - * return 0 - * - */ - free(__pyx_v_tmpdata); - - /* "View.MemoryView":1321 - * refcount_copying(&dst, dtype_is_object, ndim, inc=True) - * free(tmpdata) - * return 0 # <<<<<<<<<<<<<< - * - * if order == 'F' == get_best_order(&dst, ndim): - */ - __pyx_r = 0; - goto __pyx_L0; - - /* "View.MemoryView":1315 - * direct_copy = slice_is_contig(dst, 'F', ndim) - * - * if direct_copy: # <<<<<<<<<<<<<< - * - * refcount_copying(&dst, dtype_is_object, ndim, inc=False) - */ - } - - /* "View.MemoryView":1307 - * src = tmp - * - * if not broadcasting: # <<<<<<<<<<<<<< - * - * - */ - } - - /* "View.MemoryView":1323 - * return 0 - * - * if order == 'F' == get_best_order(&dst, ndim): # <<<<<<<<<<<<<< - * - * - */ - __pyx_t_2 = (__pyx_v_order == 'F'); - if (__pyx_t_2) { - __pyx_t_2 = ('F' == __pyx_get_best_slice_order((&__pyx_v_dst), __pyx_v_ndim)); - } - if (__pyx_t_2) { - - /* "View.MemoryView":1326 - * - * - * transpose_memslice(&src) # <<<<<<<<<<<<<< - * transpose_memslice(&dst) - * - */ - __pyx_t_5 = __pyx_memslice_transpose((&__pyx_v_src)); if (unlikely(__pyx_t_5 == ((int)-1))) __PYX_ERR(1, 1326, __pyx_L1_error) - - /* "View.MemoryView":1327 - * - * transpose_memslice(&src) - * transpose_memslice(&dst) # <<<<<<<<<<<<<< - * - * refcount_copying(&dst, dtype_is_object, ndim, inc=False) - */ - __pyx_t_5 = __pyx_memslice_transpose((&__pyx_v_dst)); if (unlikely(__pyx_t_5 == ((int)-1))) __PYX_ERR(1, 1327, __pyx_L1_error) - - /* "View.MemoryView":1323 - * return 0 - * - * if order == 'F' == get_best_order(&dst, ndim): # <<<<<<<<<<<<<< - * - * - */ - } - - /* "View.MemoryView":1329 - * transpose_memslice(&dst) - * - * refcount_copying(&dst, dtype_is_object, ndim, inc=False) # <<<<<<<<<<<<<< - * copy_strided_to_strided(&src, &dst, ndim, itemsize) - * refcount_copying(&dst, dtype_is_object, ndim, inc=True) - */ - __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 0); - - /* "View.MemoryView":1330 - * - * refcount_copying(&dst, dtype_is_object, ndim, inc=False) - * copy_strided_to_strided(&src, &dst, ndim, itemsize) # <<<<<<<<<<<<<< - * refcount_copying(&dst, dtype_is_object, ndim, inc=True) - * - */ - copy_strided_to_strided((&__pyx_v_src), (&__pyx_v_dst), __pyx_v_ndim, __pyx_v_itemsize); - - /* "View.MemoryView":1331 - * refcount_copying(&dst, dtype_is_object, ndim, inc=False) - * copy_strided_to_strided(&src, &dst, ndim, itemsize) - * refcount_copying(&dst, dtype_is_object, ndim, inc=True) # <<<<<<<<<<<<<< - * - * free(tmpdata) - */ - __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 1); - - /* "View.MemoryView":1333 - * refcount_copying(&dst, dtype_is_object, ndim, inc=True) - * - * free(tmpdata) # <<<<<<<<<<<<<< - * return 0 - * - */ - free(__pyx_v_tmpdata); - - /* "View.MemoryView":1334 - * - * free(tmpdata) - * return 0 # <<<<<<<<<<<<<< - * - * @cname('__pyx_memoryview_broadcast_leading') - */ - __pyx_r = 0; - goto __pyx_L0; - - /* "View.MemoryView":1265 - * - * @cname('__pyx_memoryview_copy_contents') - * cdef int memoryview_copy_contents(__Pyx_memviewslice src, # <<<<<<<<<<<<<< - * __Pyx_memviewslice dst, - * int src_ndim, int dst_ndim, - */ - - /* function exit code */ - __pyx_L1_error:; - #ifdef WITH_THREAD - __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); - #endif - __Pyx_AddTraceback("View.MemoryView.memoryview_copy_contents", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = -1; - #ifdef WITH_THREAD - __Pyx_PyGILState_Release(__pyx_gilstate_save); - #endif - __pyx_L0:; - return __pyx_r; -} - -/* "View.MemoryView":1337 - * - * @cname('__pyx_memoryview_broadcast_leading') - * cdef void broadcast_leading(__Pyx_memviewslice *mslice, # <<<<<<<<<<<<<< - * int ndim, - * int ndim_other) noexcept nogil: - */ - -static void __pyx_memoryview_broadcast_leading(__Pyx_memviewslice *__pyx_v_mslice, int __pyx_v_ndim, int __pyx_v_ndim_other) { - int __pyx_v_i; - int __pyx_v_offset; - int __pyx_t_1; - int __pyx_t_2; - int __pyx_t_3; - - /* "View.MemoryView":1341 - * int ndim_other) noexcept nogil: - * cdef int i - * cdef int offset = ndim_other - ndim # <<<<<<<<<<<<<< - * - * for i in range(ndim - 1, -1, -1): - */ - __pyx_v_offset = (__pyx_v_ndim_other - __pyx_v_ndim); - - /* "View.MemoryView":1343 - * cdef int offset = ndim_other - ndim - * - * for i in range(ndim - 1, -1, -1): # <<<<<<<<<<<<<< - * mslice.shape[i + offset] = mslice.shape[i] - * mslice.strides[i + offset] = mslice.strides[i] - */ - for (__pyx_t_1 = (__pyx_v_ndim - 1); __pyx_t_1 > -1; __pyx_t_1-=1) { - __pyx_v_i = __pyx_t_1; - - /* "View.MemoryView":1344 - * - * for i in range(ndim - 1, -1, -1): - * mslice.shape[i + offset] = mslice.shape[i] # <<<<<<<<<<<<<< - * mslice.strides[i + offset] = mslice.strides[i] - * mslice.suboffsets[i + offset] = mslice.suboffsets[i] - */ - (__pyx_v_mslice->shape[(__pyx_v_i + __pyx_v_offset)]) = (__pyx_v_mslice->shape[__pyx_v_i]); - - /* "View.MemoryView":1345 - * for i in range(ndim - 1, -1, -1): - * mslice.shape[i + offset] = mslice.shape[i] - * mslice.strides[i + offset] = mslice.strides[i] # <<<<<<<<<<<<<< - * mslice.suboffsets[i + offset] = mslice.suboffsets[i] - * - */ - (__pyx_v_mslice->strides[(__pyx_v_i + __pyx_v_offset)]) = (__pyx_v_mslice->strides[__pyx_v_i]); - - /* "View.MemoryView":1346 - * mslice.shape[i + offset] = mslice.shape[i] - * mslice.strides[i + offset] = mslice.strides[i] - * mslice.suboffsets[i + offset] = mslice.suboffsets[i] # <<<<<<<<<<<<<< - * - * for i in range(offset): - */ - (__pyx_v_mslice->suboffsets[(__pyx_v_i + __pyx_v_offset)]) = (__pyx_v_mslice->suboffsets[__pyx_v_i]); - } - - /* "View.MemoryView":1348 - * mslice.suboffsets[i + offset] = mslice.suboffsets[i] - * - * for i in range(offset): # <<<<<<<<<<<<<< - * mslice.shape[i] = 1 - * mslice.strides[i] = mslice.strides[0] - */ - __pyx_t_1 = __pyx_v_offset; - __pyx_t_2 = __pyx_t_1; - for (__pyx_t_3 = 0; __pyx_t_3 < __pyx_t_2; __pyx_t_3+=1) { - __pyx_v_i = __pyx_t_3; - - /* "View.MemoryView":1349 - * - * for i in range(offset): - * mslice.shape[i] = 1 # <<<<<<<<<<<<<< - * mslice.strides[i] = mslice.strides[0] - * mslice.suboffsets[i] = -1 - */ - (__pyx_v_mslice->shape[__pyx_v_i]) = 1; - - /* "View.MemoryView":1350 - * for i in range(offset): - * mslice.shape[i] = 1 - * mslice.strides[i] = mslice.strides[0] # <<<<<<<<<<<<<< - * mslice.suboffsets[i] = -1 - * - */ - (__pyx_v_mslice->strides[__pyx_v_i]) = (__pyx_v_mslice->strides[0]); - - /* "View.MemoryView":1351 - * mslice.shape[i] = 1 - * mslice.strides[i] = mslice.strides[0] - * mslice.suboffsets[i] = -1 # <<<<<<<<<<<<<< - * - * - */ - (__pyx_v_mslice->suboffsets[__pyx_v_i]) = -1L; - } - - /* "View.MemoryView":1337 - * - * @cname('__pyx_memoryview_broadcast_leading') - * cdef void broadcast_leading(__Pyx_memviewslice *mslice, # <<<<<<<<<<<<<< - * int ndim, - * int ndim_other) noexcept nogil: - */ - - /* function exit code */ -} - -/* "View.MemoryView":1359 - * - * @cname('__pyx_memoryview_refcount_copying') - * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: # <<<<<<<<<<<<<< - * - * if dtype_is_object: - */ - -static void __pyx_memoryview_refcount_copying(__Pyx_memviewslice *__pyx_v_dst, int __pyx_v_dtype_is_object, int __pyx_v_ndim, int __pyx_v_inc) { - - /* "View.MemoryView":1361 - * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: - * - * if dtype_is_object: # <<<<<<<<<<<<<< - * refcount_objects_in_slice_with_gil(dst.data, dst.shape, dst.strides, ndim, inc) - * - */ - if (__pyx_v_dtype_is_object) { - - /* "View.MemoryView":1362 - * - * if dtype_is_object: - * refcount_objects_in_slice_with_gil(dst.data, dst.shape, dst.strides, ndim, inc) # <<<<<<<<<<<<<< - * - * @cname('__pyx_memoryview_refcount_objects_in_slice_with_gil') - */ - __pyx_memoryview_refcount_objects_in_slice_with_gil(__pyx_v_dst->data, __pyx_v_dst->shape, __pyx_v_dst->strides, __pyx_v_ndim, __pyx_v_inc); - - /* "View.MemoryView":1361 - * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: - * - * if dtype_is_object: # <<<<<<<<<<<<<< - * refcount_objects_in_slice_with_gil(dst.data, dst.shape, dst.strides, ndim, inc) - * - */ - } - - /* "View.MemoryView":1359 - * - * @cname('__pyx_memoryview_refcount_copying') - * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: # <<<<<<<<<<<<<< - * - * if dtype_is_object: - */ - - /* function exit code */ -} - -/* "View.MemoryView":1365 - * - * @cname('__pyx_memoryview_refcount_objects_in_slice_with_gil') - * cdef void refcount_objects_in_slice_with_gil(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< - * Py_ssize_t *strides, int ndim, - * bint inc) noexcept with gil: - */ - -static void __pyx_memoryview_refcount_objects_in_slice_with_gil(char *__pyx_v_data, Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, int __pyx_v_ndim, int __pyx_v_inc) { - #ifdef WITH_THREAD - PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); - #endif - - /* "View.MemoryView":1368 - * Py_ssize_t *strides, int ndim, - * bint inc) noexcept with gil: - * refcount_objects_in_slice(data, shape, strides, ndim, inc) # <<<<<<<<<<<<<< - * - * @cname('__pyx_memoryview_refcount_objects_in_slice') - */ - __pyx_memoryview_refcount_objects_in_slice(__pyx_v_data, __pyx_v_shape, __pyx_v_strides, __pyx_v_ndim, __pyx_v_inc); - - /* "View.MemoryView":1365 - * - * @cname('__pyx_memoryview_refcount_objects_in_slice_with_gil') - * cdef void refcount_objects_in_slice_with_gil(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< - * Py_ssize_t *strides, int ndim, - * bint inc) noexcept with gil: - */ - - /* function exit code */ - #ifdef WITH_THREAD - __Pyx_PyGILState_Release(__pyx_gilstate_save); - #endif -} - -/* "View.MemoryView":1371 - * - * @cname('__pyx_memoryview_refcount_objects_in_slice') - * cdef void refcount_objects_in_slice(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< - * Py_ssize_t *strides, int ndim, bint inc) noexcept: - * cdef Py_ssize_t i - */ - -static void __pyx_memoryview_refcount_objects_in_slice(char *__pyx_v_data, Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, int __pyx_v_ndim, int __pyx_v_inc) { - CYTHON_UNUSED Py_ssize_t __pyx_v_i; - Py_ssize_t __pyx_v_stride; - Py_ssize_t __pyx_t_1; - Py_ssize_t __pyx_t_2; - Py_ssize_t __pyx_t_3; - int __pyx_t_4; - - /* "View.MemoryView":1374 - * Py_ssize_t *strides, int ndim, bint inc) noexcept: - * cdef Py_ssize_t i - * cdef Py_ssize_t stride = strides[0] # <<<<<<<<<<<<<< - * - * for i in range(shape[0]): - */ - __pyx_v_stride = (__pyx_v_strides[0]); - - /* "View.MemoryView":1376 - * cdef Py_ssize_t stride = strides[0] - * - * for i in range(shape[0]): # <<<<<<<<<<<<<< - * if ndim == 1: - * if inc: - */ - __pyx_t_1 = (__pyx_v_shape[0]); - __pyx_t_2 = __pyx_t_1; - for (__pyx_t_3 = 0; __pyx_t_3 < __pyx_t_2; __pyx_t_3+=1) { - __pyx_v_i = __pyx_t_3; - - /* "View.MemoryView":1377 - * - * for i in range(shape[0]): - * if ndim == 1: # <<<<<<<<<<<<<< - * if inc: - * Py_INCREF(( data)[0]) - */ - __pyx_t_4 = (__pyx_v_ndim == 1); - if (__pyx_t_4) { - - /* "View.MemoryView":1378 - * for i in range(shape[0]): - * if ndim == 1: - * if inc: # <<<<<<<<<<<<<< - * Py_INCREF(( data)[0]) - * else: - */ - if (__pyx_v_inc) { - - /* "View.MemoryView":1379 - * if ndim == 1: - * if inc: - * Py_INCREF(( data)[0]) # <<<<<<<<<<<<<< - * else: - * Py_DECREF(( data)[0]) - */ - Py_INCREF((((PyObject **)__pyx_v_data)[0])); - - /* "View.MemoryView":1378 - * for i in range(shape[0]): - * if ndim == 1: - * if inc: # <<<<<<<<<<<<<< - * Py_INCREF(( data)[0]) - * else: - */ - goto __pyx_L6; - } - - /* "View.MemoryView":1381 - * Py_INCREF(( data)[0]) - * else: - * Py_DECREF(( data)[0]) # <<<<<<<<<<<<<< - * else: - * refcount_objects_in_slice(data, shape + 1, strides + 1, ndim - 1, inc) - */ - /*else*/ { - Py_DECREF((((PyObject **)__pyx_v_data)[0])); - } - __pyx_L6:; - - /* "View.MemoryView":1377 - * - * for i in range(shape[0]): - * if ndim == 1: # <<<<<<<<<<<<<< - * if inc: - * Py_INCREF(( data)[0]) - */ - goto __pyx_L5; - } - - /* "View.MemoryView":1383 - * Py_DECREF(( data)[0]) - * else: - * refcount_objects_in_slice(data, shape + 1, strides + 1, ndim - 1, inc) # <<<<<<<<<<<<<< - * - * data += stride - */ - /*else*/ { - __pyx_memoryview_refcount_objects_in_slice(__pyx_v_data, (__pyx_v_shape + 1), (__pyx_v_strides + 1), (__pyx_v_ndim - 1), __pyx_v_inc); - } - __pyx_L5:; - - /* "View.MemoryView":1385 - * refcount_objects_in_slice(data, shape + 1, strides + 1, ndim - 1, inc) - * - * data += stride # <<<<<<<<<<<<<< - * - * - */ - __pyx_v_data = (__pyx_v_data + __pyx_v_stride); - } - - /* "View.MemoryView":1371 - * - * @cname('__pyx_memoryview_refcount_objects_in_slice') - * cdef void refcount_objects_in_slice(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< - * Py_ssize_t *strides, int ndim, bint inc) noexcept: - * cdef Py_ssize_t i - */ - - /* function exit code */ -} - -/* "View.MemoryView":1391 - * - * @cname('__pyx_memoryview_slice_assign_scalar') - * cdef void slice_assign_scalar(__Pyx_memviewslice *dst, int ndim, # <<<<<<<<<<<<<< - * size_t itemsize, void *item, - * bint dtype_is_object) noexcept nogil: - */ - -static void __pyx_memoryview_slice_assign_scalar(__Pyx_memviewslice *__pyx_v_dst, int __pyx_v_ndim, size_t __pyx_v_itemsize, void *__pyx_v_item, int __pyx_v_dtype_is_object) { - - /* "View.MemoryView":1394 - * size_t itemsize, void *item, - * bint dtype_is_object) noexcept nogil: - * refcount_copying(dst, dtype_is_object, ndim, inc=False) # <<<<<<<<<<<<<< - * _slice_assign_scalar(dst.data, dst.shape, dst.strides, ndim, itemsize, item) - * refcount_copying(dst, dtype_is_object, ndim, inc=True) - */ - __pyx_memoryview_refcount_copying(__pyx_v_dst, __pyx_v_dtype_is_object, __pyx_v_ndim, 0); - - /* "View.MemoryView":1395 - * bint dtype_is_object) noexcept nogil: - * refcount_copying(dst, dtype_is_object, ndim, inc=False) - * _slice_assign_scalar(dst.data, dst.shape, dst.strides, ndim, itemsize, item) # <<<<<<<<<<<<<< - * refcount_copying(dst, dtype_is_object, ndim, inc=True) - * - */ - __pyx_memoryview__slice_assign_scalar(__pyx_v_dst->data, __pyx_v_dst->shape, __pyx_v_dst->strides, __pyx_v_ndim, __pyx_v_itemsize, __pyx_v_item); - - /* "View.MemoryView":1396 - * refcount_copying(dst, dtype_is_object, ndim, inc=False) - * _slice_assign_scalar(dst.data, dst.shape, dst.strides, ndim, itemsize, item) - * refcount_copying(dst, dtype_is_object, ndim, inc=True) # <<<<<<<<<<<<<< - * - * - */ - __pyx_memoryview_refcount_copying(__pyx_v_dst, __pyx_v_dtype_is_object, __pyx_v_ndim, 1); - - /* "View.MemoryView":1391 - * - * @cname('__pyx_memoryview_slice_assign_scalar') - * cdef void slice_assign_scalar(__Pyx_memviewslice *dst, int ndim, # <<<<<<<<<<<<<< - * size_t itemsize, void *item, - * bint dtype_is_object) noexcept nogil: - */ - - /* function exit code */ -} - -/* "View.MemoryView":1400 - * - * @cname('__pyx_memoryview__slice_assign_scalar') - * cdef void _slice_assign_scalar(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< - * Py_ssize_t *strides, int ndim, - * size_t itemsize, void *item) noexcept nogil: - */ - -static void __pyx_memoryview__slice_assign_scalar(char *__pyx_v_data, Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, int __pyx_v_ndim, size_t __pyx_v_itemsize, void *__pyx_v_item) { - CYTHON_UNUSED Py_ssize_t __pyx_v_i; - Py_ssize_t __pyx_v_stride; - Py_ssize_t __pyx_v_extent; - int __pyx_t_1; - Py_ssize_t __pyx_t_2; - Py_ssize_t __pyx_t_3; - Py_ssize_t __pyx_t_4; - - /* "View.MemoryView":1404 - * size_t itemsize, void *item) noexcept nogil: - * cdef Py_ssize_t i - * cdef Py_ssize_t stride = strides[0] # <<<<<<<<<<<<<< - * cdef Py_ssize_t extent = shape[0] - * - */ - __pyx_v_stride = (__pyx_v_strides[0]); - - /* "View.MemoryView":1405 - * cdef Py_ssize_t i - * cdef Py_ssize_t stride = strides[0] - * cdef Py_ssize_t extent = shape[0] # <<<<<<<<<<<<<< - * - * if ndim == 1: - */ - __pyx_v_extent = (__pyx_v_shape[0]); - - /* "View.MemoryView":1407 - * cdef Py_ssize_t extent = shape[0] - * - * if ndim == 1: # <<<<<<<<<<<<<< - * for i in range(extent): - * memcpy(data, item, itemsize) - */ - __pyx_t_1 = (__pyx_v_ndim == 1); - if (__pyx_t_1) { - - /* "View.MemoryView":1408 - * - * if ndim == 1: - * for i in range(extent): # <<<<<<<<<<<<<< - * memcpy(data, item, itemsize) - * data += stride - */ - __pyx_t_2 = __pyx_v_extent; - __pyx_t_3 = __pyx_t_2; - for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { - __pyx_v_i = __pyx_t_4; - - /* "View.MemoryView":1409 - * if ndim == 1: - * for i in range(extent): - * memcpy(data, item, itemsize) # <<<<<<<<<<<<<< - * data += stride - * else: - */ - (void)(memcpy(__pyx_v_data, __pyx_v_item, __pyx_v_itemsize)); - - /* "View.MemoryView":1410 - * for i in range(extent): - * memcpy(data, item, itemsize) - * data += stride # <<<<<<<<<<<<<< - * else: - * for i in range(extent): - */ - __pyx_v_data = (__pyx_v_data + __pyx_v_stride); - } - - /* "View.MemoryView":1407 - * cdef Py_ssize_t extent = shape[0] - * - * if ndim == 1: # <<<<<<<<<<<<<< - * for i in range(extent): - * memcpy(data, item, itemsize) - */ - goto __pyx_L3; - } - - /* "View.MemoryView":1412 - * data += stride - * else: - * for i in range(extent): # <<<<<<<<<<<<<< - * _slice_assign_scalar(data, shape + 1, strides + 1, ndim - 1, itemsize, item) - * data += stride - */ - /*else*/ { - __pyx_t_2 = __pyx_v_extent; - __pyx_t_3 = __pyx_t_2; - for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { - __pyx_v_i = __pyx_t_4; - - /* "View.MemoryView":1413 - * else: - * for i in range(extent): - * _slice_assign_scalar(data, shape + 1, strides + 1, ndim - 1, itemsize, item) # <<<<<<<<<<<<<< - * data += stride - * - */ - __pyx_memoryview__slice_assign_scalar(__pyx_v_data, (__pyx_v_shape + 1), (__pyx_v_strides + 1), (__pyx_v_ndim - 1), __pyx_v_itemsize, __pyx_v_item); - - /* "View.MemoryView":1414 - * for i in range(extent): - * _slice_assign_scalar(data, shape + 1, strides + 1, ndim - 1, itemsize, item) - * data += stride # <<<<<<<<<<<<<< - * - * - */ - __pyx_v_data = (__pyx_v_data + __pyx_v_stride); - } - } - __pyx_L3:; - - /* "View.MemoryView":1400 - * - * @cname('__pyx_memoryview__slice_assign_scalar') - * cdef void _slice_assign_scalar(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< - * Py_ssize_t *strides, int ndim, - * size_t itemsize, void *item) noexcept nogil: - */ - - /* function exit code */ -} - -/* "(tree fragment)":1 - * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< - * cdef object __pyx_PickleError - * cdef object __pyx_result - */ - -/* Python wrapper */ -static PyObject *__pyx_pw_15View_dot_MemoryView_1__pyx_unpickle_Enum(PyObject *__pyx_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -); /*proto*/ -static PyMethodDef __pyx_mdef_15View_dot_MemoryView_1__pyx_unpickle_Enum = {"__pyx_unpickle_Enum", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15View_dot_MemoryView_1__pyx_unpickle_Enum, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; -static PyObject *__pyx_pw_15View_dot_MemoryView_1__pyx_unpickle_Enum(PyObject *__pyx_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -) { - PyObject *__pyx_v___pyx_type = 0; - long __pyx_v___pyx_checksum; - PyObject *__pyx_v___pyx_state = 0; - #if !CYTHON_METH_FASTCALL - CYTHON_UNUSED Py_ssize_t __pyx_nargs; - #endif - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - PyObject* values[3] = {0,0,0}; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - PyObject *__pyx_r = 0; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("__pyx_unpickle_Enum (wrapper)", 0); - #if !CYTHON_METH_FASTCALL - #if CYTHON_ASSUME_SAFE_MACROS - __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); - #else - __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; - #endif - #endif - __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); - { - PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_type,&__pyx_n_s_pyx_checksum,&__pyx_n_s_pyx_state,0}; - if (__pyx_kwds) { - Py_ssize_t kw_args; - switch (__pyx_nargs) { - case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); - CYTHON_FALLTHROUGH; - case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); - CYTHON_FALLTHROUGH; - case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); - CYTHON_FALLTHROUGH; - case 0: break; - default: goto __pyx_L5_argtuple_error; - } - kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); - switch (__pyx_nargs) { - case 0: - if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_type)) != 0)) { - (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); - kw_args--; - } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) - else goto __pyx_L5_argtuple_error; - CYTHON_FALLTHROUGH; - case 1: - if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_checksum)) != 0)) { - (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); - kw_args--; - } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) - else { - __Pyx_RaiseArgtupleInvalid("__pyx_unpickle_Enum", 1, 3, 3, 1); __PYX_ERR(1, 1, __pyx_L3_error) - } - CYTHON_FALLTHROUGH; - case 2: - if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { - (void)__Pyx_Arg_NewRef_FASTCALL(values[2]); - kw_args--; - } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) - else { - __Pyx_RaiseArgtupleInvalid("__pyx_unpickle_Enum", 1, 3, 3, 2); __PYX_ERR(1, 1, __pyx_L3_error) - } - } - if (unlikely(kw_args > 0)) { - const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__pyx_unpickle_Enum") < 0)) __PYX_ERR(1, 1, __pyx_L3_error) - } - } else if (unlikely(__pyx_nargs != 3)) { - goto __pyx_L5_argtuple_error; - } else { - values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); - values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); - values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); - } - __pyx_v___pyx_type = values[0]; - __pyx_v___pyx_checksum = __Pyx_PyInt_As_long(values[1]); if (unlikely((__pyx_v___pyx_checksum == (long)-1) && PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) - __pyx_v___pyx_state = values[2]; - } - goto __pyx_L6_skip; - __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("__pyx_unpickle_Enum", 1, 3, 3, __pyx_nargs); __PYX_ERR(1, 1, __pyx_L3_error) - __pyx_L6_skip:; - goto __pyx_L4_argument_unpacking_done; - __pyx_L3_error:; - { - Py_ssize_t __pyx_temp; - for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { - __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); - } - } - __Pyx_AddTraceback("View.MemoryView.__pyx_unpickle_Enum", __pyx_clineno, __pyx_lineno, __pyx_filename); - __Pyx_RefNannyFinishContext(); - return NULL; - __pyx_L4_argument_unpacking_done:; - __pyx_r = __pyx_pf_15View_dot_MemoryView___pyx_unpickle_Enum(__pyx_self, __pyx_v___pyx_type, __pyx_v___pyx_checksum, __pyx_v___pyx_state); - - /* function exit code */ - { - Py_ssize_t __pyx_temp; - for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { - __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); - } - } - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static PyObject *__pyx_pf_15View_dot_MemoryView___pyx_unpickle_Enum(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v___pyx_type, long __pyx_v___pyx_checksum, PyObject *__pyx_v___pyx_state) { - PyObject *__pyx_v___pyx_PickleError = 0; - PyObject *__pyx_v___pyx_result = 0; - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - PyObject *__pyx_t_1 = NULL; - int __pyx_t_2; - PyObject *__pyx_t_3 = NULL; - PyObject *__pyx_t_4 = NULL; - int __pyx_t_5; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("__pyx_unpickle_Enum", 1); - - /* "(tree fragment)":4 - * cdef object __pyx_PickleError - * cdef object __pyx_result - * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): # <<<<<<<<<<<<<< - * from pickle import PickleError as __pyx_PickleError - * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum - */ - __pyx_t_1 = __Pyx_PyInt_From_long(__pyx_v___pyx_checksum); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 4, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_2 = (__Pyx_PySequence_ContainsTF(__pyx_t_1, __pyx_tuple__8, Py_NE)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(1, 4, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - if (__pyx_t_2) { - - /* "(tree fragment)":5 - * cdef object __pyx_result - * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): - * from pickle import PickleError as __pyx_PickleError # <<<<<<<<<<<<<< - * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum - * __pyx_result = Enum.__new__(__pyx_type) - */ - __pyx_t_1 = PyList_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 5, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __Pyx_INCREF(__pyx_n_s_PickleError); - __Pyx_GIVEREF(__pyx_n_s_PickleError); - if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_s_PickleError)) __PYX_ERR(1, 5, __pyx_L1_error); - __pyx_t_3 = __Pyx_Import(__pyx_n_s_pickle, __pyx_t_1, 0); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 5, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_t_1 = __Pyx_ImportFrom(__pyx_t_3, __pyx_n_s_PickleError); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 5, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __Pyx_INCREF(__pyx_t_1); - __pyx_v___pyx_PickleError = __pyx_t_1; - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - - /* "(tree fragment)":6 - * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): - * from pickle import PickleError as __pyx_PickleError - * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum # <<<<<<<<<<<<<< - * __pyx_result = Enum.__new__(__pyx_type) - * if __pyx_state is not None: - */ - __pyx_t_3 = __Pyx_PyInt_From_long(__pyx_v___pyx_checksum); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 6, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __pyx_t_1 = __Pyx_PyString_Format(__pyx_kp_s_Incompatible_checksums_0x_x_vs_0, __pyx_t_3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 6, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - __Pyx_Raise(__pyx_v___pyx_PickleError, __pyx_t_1, 0, 0); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __PYX_ERR(1, 6, __pyx_L1_error) - - /* "(tree fragment)":4 - * cdef object __pyx_PickleError - * cdef object __pyx_result - * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): # <<<<<<<<<<<<<< - * from pickle import PickleError as __pyx_PickleError - * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum - */ - } - - /* "(tree fragment)":7 - * from pickle import PickleError as __pyx_PickleError - * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum - * __pyx_result = Enum.__new__(__pyx_type) # <<<<<<<<<<<<<< - * if __pyx_state is not None: - * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) - */ - __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_MemviewEnum_type), __pyx_n_s_new); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 7, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __pyx_t_4 = NULL; - __pyx_t_5 = 0; - #if CYTHON_UNPACK_METHODS - if (likely(PyMethod_Check(__pyx_t_3))) { - __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_3); - if (likely(__pyx_t_4)) { - PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); - __Pyx_INCREF(__pyx_t_4); - __Pyx_INCREF(function); - __Pyx_DECREF_SET(__pyx_t_3, function); - __pyx_t_5 = 1; - } - } - #endif - { - PyObject *__pyx_callargs[2] = {__pyx_t_4, __pyx_v___pyx_type}; - __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_5, 1+__pyx_t_5); - __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; - if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 7, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - } - __pyx_v___pyx_result = __pyx_t_1; - __pyx_t_1 = 0; - - /* "(tree fragment)":8 - * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum - * __pyx_result = Enum.__new__(__pyx_type) - * if __pyx_state is not None: # <<<<<<<<<<<<<< - * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) - * return __pyx_result - */ - __pyx_t_2 = (__pyx_v___pyx_state != Py_None); - if (__pyx_t_2) { - - /* "(tree fragment)":9 - * __pyx_result = Enum.__new__(__pyx_type) - * if __pyx_state is not None: - * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) # <<<<<<<<<<<<<< - * return __pyx_result - * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): - */ - if (!(likely(PyTuple_CheckExact(__pyx_v___pyx_state))||((__pyx_v___pyx_state) == Py_None) || __Pyx_RaiseUnexpectedTypeError("tuple", __pyx_v___pyx_state))) __PYX_ERR(1, 9, __pyx_L1_error) - __pyx_t_1 = __pyx_unpickle_Enum__set_state(((struct __pyx_MemviewEnum_obj *)__pyx_v___pyx_result), ((PyObject*)__pyx_v___pyx_state)); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 9, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - - /* "(tree fragment)":8 - * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum - * __pyx_result = Enum.__new__(__pyx_type) - * if __pyx_state is not None: # <<<<<<<<<<<<<< - * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) - * return __pyx_result - */ - } - - /* "(tree fragment)":10 - * if __pyx_state is not None: - * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) - * return __pyx_result # <<<<<<<<<<<<<< - * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): - * __pyx_result.name = __pyx_state[0] - */ - __Pyx_XDECREF(__pyx_r); - __Pyx_INCREF(__pyx_v___pyx_result); - __pyx_r = __pyx_v___pyx_result; - goto __pyx_L0; - - /* "(tree fragment)":1 - * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< - * cdef object __pyx_PickleError - * cdef object __pyx_result - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_1); - __Pyx_XDECREF(__pyx_t_3); - __Pyx_XDECREF(__pyx_t_4); - __Pyx_AddTraceback("View.MemoryView.__pyx_unpickle_Enum", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = NULL; - __pyx_L0:; - __Pyx_XDECREF(__pyx_v___pyx_PickleError); - __Pyx_XDECREF(__pyx_v___pyx_result); - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "(tree fragment)":11 - * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) - * return __pyx_result - * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): # <<<<<<<<<<<<<< - * __pyx_result.name = __pyx_state[0] - * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): - */ - -static PyObject *__pyx_unpickle_Enum__set_state(struct __pyx_MemviewEnum_obj *__pyx_v___pyx_result, PyObject *__pyx_v___pyx_state) { - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - PyObject *__pyx_t_1 = NULL; - int __pyx_t_2; - Py_ssize_t __pyx_t_3; - int __pyx_t_4; - PyObject *__pyx_t_5 = NULL; - PyObject *__pyx_t_6 = NULL; - PyObject *__pyx_t_7 = NULL; - int __pyx_t_8; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("__pyx_unpickle_Enum__set_state", 1); - - /* "(tree fragment)":12 - * return __pyx_result - * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): - * __pyx_result.name = __pyx_state[0] # <<<<<<<<<<<<<< - * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): - * __pyx_result.__dict__.update(__pyx_state[1]) - */ - if (unlikely(__pyx_v___pyx_state == Py_None)) { - PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); - __PYX_ERR(1, 12, __pyx_L1_error) - } - __pyx_t_1 = __Pyx_GetItemInt_Tuple(__pyx_v___pyx_state, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 12, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __Pyx_GIVEREF(__pyx_t_1); - __Pyx_GOTREF(__pyx_v___pyx_result->name); - __Pyx_DECREF(__pyx_v___pyx_result->name); - __pyx_v___pyx_result->name = __pyx_t_1; - __pyx_t_1 = 0; - - /* "(tree fragment)":13 - * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): - * __pyx_result.name = __pyx_state[0] - * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): # <<<<<<<<<<<<<< - * __pyx_result.__dict__.update(__pyx_state[1]) - */ - if (unlikely(__pyx_v___pyx_state == Py_None)) { - PyErr_SetString(PyExc_TypeError, "object of type 'NoneType' has no len()"); - __PYX_ERR(1, 13, __pyx_L1_error) - } - __pyx_t_3 = __Pyx_PyTuple_GET_SIZE(__pyx_v___pyx_state); if (unlikely(__pyx_t_3 == ((Py_ssize_t)-1))) __PYX_ERR(1, 13, __pyx_L1_error) - __pyx_t_4 = (__pyx_t_3 > 1); - if (__pyx_t_4) { - } else { - __pyx_t_2 = __pyx_t_4; - goto __pyx_L4_bool_binop_done; - } - __pyx_t_4 = __Pyx_HasAttr(((PyObject *)__pyx_v___pyx_result), __pyx_n_s_dict); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(1, 13, __pyx_L1_error) - __pyx_t_2 = __pyx_t_4; - __pyx_L4_bool_binop_done:; - if (__pyx_t_2) { - - /* "(tree fragment)":14 - * __pyx_result.name = __pyx_state[0] - * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): - * __pyx_result.__dict__.update(__pyx_state[1]) # <<<<<<<<<<<<<< - */ - __pyx_t_5 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v___pyx_result), __pyx_n_s_dict); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 14, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_update); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 14, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_6); - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - if (unlikely(__pyx_v___pyx_state == Py_None)) { - PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); - __PYX_ERR(1, 14, __pyx_L1_error) - } - __pyx_t_5 = __Pyx_GetItemInt_Tuple(__pyx_v___pyx_state, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 14, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __pyx_t_7 = NULL; - __pyx_t_8 = 0; - #if CYTHON_UNPACK_METHODS - if (likely(PyMethod_Check(__pyx_t_6))) { - __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_6); - if (likely(__pyx_t_7)) { - PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_6); - __Pyx_INCREF(__pyx_t_7); - __Pyx_INCREF(function); - __Pyx_DECREF_SET(__pyx_t_6, function); - __pyx_t_8 = 1; - } - } - #endif - { - PyObject *__pyx_callargs[2] = {__pyx_t_7, __pyx_t_5}; - __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_6, __pyx_callargs+1-__pyx_t_8, 1+__pyx_t_8); - __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 14, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; - } - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - - /* "(tree fragment)":13 - * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): - * __pyx_result.name = __pyx_state[0] - * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): # <<<<<<<<<<<<<< - * __pyx_result.__dict__.update(__pyx_state[1]) - */ - } - - /* "(tree fragment)":11 - * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) - * return __pyx_result - * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): # <<<<<<<<<<<<<< - * __pyx_result.name = __pyx_state[0] - * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): - */ - - /* function exit code */ - __pyx_r = Py_None; __Pyx_INCREF(Py_None); - goto __pyx_L0; - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_1); - __Pyx_XDECREF(__pyx_t_5); - __Pyx_XDECREF(__pyx_t_6); - __Pyx_XDECREF(__pyx_t_7); - __Pyx_AddTraceback("View.MemoryView.__pyx_unpickle_Enum__set_state", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = 0; - __pyx_L0:; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "BufferFormatFromTypeInfo":1450 - * - * @cname('__pyx_format_from_typeinfo') - * cdef bytes format_from_typeinfo(__Pyx_TypeInfo *type): # <<<<<<<<<<<<<< - * cdef __Pyx_StructField *field - * cdef __pyx_typeinfo_string fmt - */ - -static PyObject *__pyx_format_from_typeinfo(__Pyx_TypeInfo *__pyx_v_type) { - __Pyx_StructField *__pyx_v_field; - struct __pyx_typeinfo_string __pyx_v_fmt; - PyObject *__pyx_v_part = 0; - PyObject *__pyx_v_result = 0; - PyObject *__pyx_v_alignment = NULL; - PyObject *__pyx_v_parts = NULL; - PyObject *__pyx_v_extents = NULL; - Py_ssize_t __pyx_7genexpr__pyx_v_i; - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - int __pyx_t_1; - PyObject *__pyx_t_2 = NULL; - __Pyx_StructField *__pyx_t_3; - PyObject *__pyx_t_4 = NULL; - PyObject *__pyx_t_5 = NULL; - int __pyx_t_6; - int __pyx_t_7; - int __pyx_t_8; - Py_ssize_t __pyx_t_9; - Py_UCS4 __pyx_t_10; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("format_from_typeinfo", 1); - - /* "BufferFormatFromTypeInfo":1456 - * cdef Py_ssize_t i - * - * if type.typegroup == 'S': # <<<<<<<<<<<<<< - * assert type.fields != NULL - * assert type.fields.type != NULL - */ - __pyx_t_1 = (__pyx_v_type->typegroup == 'S'); - if (__pyx_t_1) { - - /* "BufferFormatFromTypeInfo":1457 - * - * if type.typegroup == 'S': - * assert type.fields != NULL # <<<<<<<<<<<<<< - * assert type.fields.type != NULL - * - */ - #ifndef CYTHON_WITHOUT_ASSERTIONS - if (unlikely(__pyx_assertions_enabled())) { - __pyx_t_1 = (__pyx_v_type->fields != NULL); - if (unlikely(!__pyx_t_1)) { - __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); - __PYX_ERR(1, 1457, __pyx_L1_error) - } - } - #else - if ((1)); else __PYX_ERR(1, 1457, __pyx_L1_error) - #endif - - /* "BufferFormatFromTypeInfo":1458 - * if type.typegroup == 'S': - * assert type.fields != NULL - * assert type.fields.type != NULL # <<<<<<<<<<<<<< - * - * if type.flags & __PYX_BUF_FLAGS_PACKED_STRUCT: - */ - #ifndef CYTHON_WITHOUT_ASSERTIONS - if (unlikely(__pyx_assertions_enabled())) { - __pyx_t_1 = (__pyx_v_type->fields->type != NULL); - if (unlikely(!__pyx_t_1)) { - __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); - __PYX_ERR(1, 1458, __pyx_L1_error) - } - } - #else - if ((1)); else __PYX_ERR(1, 1458, __pyx_L1_error) - #endif - - /* "BufferFormatFromTypeInfo":1460 - * assert type.fields.type != NULL - * - * if type.flags & __PYX_BUF_FLAGS_PACKED_STRUCT: # <<<<<<<<<<<<<< - * alignment = b'^' - * else: - */ - __pyx_t_1 = ((__pyx_v_type->flags & __PYX_BUF_FLAGS_PACKED_STRUCT) != 0); - if (__pyx_t_1) { - - /* "BufferFormatFromTypeInfo":1461 - * - * if type.flags & __PYX_BUF_FLAGS_PACKED_STRUCT: - * alignment = b'^' # <<<<<<<<<<<<<< - * else: - * alignment = b'' - */ - __Pyx_INCREF(__pyx_kp_b__9); - __pyx_v_alignment = __pyx_kp_b__9; - - /* "BufferFormatFromTypeInfo":1460 - * assert type.fields.type != NULL - * - * if type.flags & __PYX_BUF_FLAGS_PACKED_STRUCT: # <<<<<<<<<<<<<< - * alignment = b'^' - * else: - */ - goto __pyx_L4; - } - - /* "BufferFormatFromTypeInfo":1463 - * alignment = b'^' - * else: - * alignment = b'' # <<<<<<<<<<<<<< - * - * parts = [b"T{"] - */ - /*else*/ { - __Pyx_INCREF(__pyx_kp_b__10); - __pyx_v_alignment = __pyx_kp_b__10; - } - __pyx_L4:; - - /* "BufferFormatFromTypeInfo":1465 - * alignment = b'' - * - * parts = [b"T{"] # <<<<<<<<<<<<<< - * field = type.fields - * - */ - __pyx_t_2 = PyList_New(1); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1465, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __Pyx_INCREF(__pyx_kp_b_T); - __Pyx_GIVEREF(__pyx_kp_b_T); - if (__Pyx_PyList_SET_ITEM(__pyx_t_2, 0, __pyx_kp_b_T)) __PYX_ERR(1, 1465, __pyx_L1_error); - __pyx_v_parts = ((PyObject*)__pyx_t_2); - __pyx_t_2 = 0; - - /* "BufferFormatFromTypeInfo":1466 - * - * parts = [b"T{"] - * field = type.fields # <<<<<<<<<<<<<< - * - * while field.type: - */ - __pyx_t_3 = __pyx_v_type->fields; - __pyx_v_field = __pyx_t_3; - - /* "BufferFormatFromTypeInfo":1468 - * field = type.fields - * - * while field.type: # <<<<<<<<<<<<<< - * part = format_from_typeinfo(field.type) - * parts.append(part + b':' + field.name + b':') - */ - while (1) { - __pyx_t_1 = (__pyx_v_field->type != 0); - if (!__pyx_t_1) break; - - /* "BufferFormatFromTypeInfo":1469 - * - * while field.type: - * part = format_from_typeinfo(field.type) # <<<<<<<<<<<<<< - * parts.append(part + b':' + field.name + b':') - * field += 1 - */ - __pyx_t_2 = __pyx_format_from_typeinfo(__pyx_v_field->type); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1469, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __Pyx_XDECREF_SET(__pyx_v_part, ((PyObject*)__pyx_t_2)); - __pyx_t_2 = 0; - - /* "BufferFormatFromTypeInfo":1470 - * while field.type: - * part = format_from_typeinfo(field.type) - * parts.append(part + b':' + field.name + b':') # <<<<<<<<<<<<<< - * field += 1 - * - */ - __pyx_t_2 = PyNumber_Add(__pyx_v_part, __pyx_kp_b__11); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1470, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __pyx_t_4 = __Pyx_PyBytes_FromString(__pyx_v_field->name); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1470, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __pyx_t_5 = PyNumber_Add(__pyx_t_2, __pyx_t_4); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 1470, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __pyx_t_4 = PyNumber_Add(__pyx_t_5, __pyx_kp_b__11); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1470, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __pyx_t_6 = __Pyx_PyList_Append(__pyx_v_parts, __pyx_t_4); if (unlikely(__pyx_t_6 == ((int)-1))) __PYX_ERR(1, 1470, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - - /* "BufferFormatFromTypeInfo":1471 - * part = format_from_typeinfo(field.type) - * parts.append(part + b':' + field.name + b':') - * field += 1 # <<<<<<<<<<<<<< - * - * result = alignment.join(parts) + b'}' - */ - __pyx_v_field = (__pyx_v_field + 1); - } - - /* "BufferFormatFromTypeInfo":1473 - * field += 1 - * - * result = alignment.join(parts) + b'}' # <<<<<<<<<<<<<< - * else: - * fmt = __Pyx_TypeInfoToFormat(type) - */ - __pyx_t_4 = __Pyx_PyBytes_Join(__pyx_v_alignment, __pyx_v_parts); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1473, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __pyx_t_5 = PyNumber_Add(__pyx_t_4, __pyx_kp_b__12); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 1473, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - if (!(likely(PyBytes_CheckExact(__pyx_t_5))||((__pyx_t_5) == Py_None) || __Pyx_RaiseUnexpectedTypeError("bytes", __pyx_t_5))) __PYX_ERR(1, 1473, __pyx_L1_error) - __pyx_v_result = ((PyObject*)__pyx_t_5); - __pyx_t_5 = 0; - - /* "BufferFormatFromTypeInfo":1456 - * cdef Py_ssize_t i - * - * if type.typegroup == 'S': # <<<<<<<<<<<<<< - * assert type.fields != NULL - * assert type.fields.type != NULL - */ - goto __pyx_L3; - } - - /* "BufferFormatFromTypeInfo":1475 - * result = alignment.join(parts) + b'}' - * else: - * fmt = __Pyx_TypeInfoToFormat(type) # <<<<<<<<<<<<<< - * result = fmt.string - * if type.arraysize[0]: - */ - /*else*/ { - __pyx_v_fmt = __Pyx_TypeInfoToFormat(__pyx_v_type); - - /* "BufferFormatFromTypeInfo":1476 - * else: - * fmt = __Pyx_TypeInfoToFormat(type) - * result = fmt.string # <<<<<<<<<<<<<< - * if type.arraysize[0]: - * extents = [f"{type.arraysize[i]}" for i in range(type.ndim)] - */ - __pyx_t_5 = __Pyx_PyObject_FromString(__pyx_v_fmt.string); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 1476, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __pyx_v_result = ((PyObject*)__pyx_t_5); - __pyx_t_5 = 0; - - /* "BufferFormatFromTypeInfo":1477 - * fmt = __Pyx_TypeInfoToFormat(type) - * result = fmt.string - * if type.arraysize[0]: # <<<<<<<<<<<<<< - * extents = [f"{type.arraysize[i]}" for i in range(type.ndim)] - * result = f"({u','.join(extents)})".encode('ascii') + result - */ - __pyx_t_1 = ((__pyx_v_type->arraysize[0]) != 0); - if (__pyx_t_1) { - - /* "BufferFormatFromTypeInfo":1478 - * result = fmt.string - * if type.arraysize[0]: - * extents = [f"{type.arraysize[i]}" for i in range(type.ndim)] # <<<<<<<<<<<<<< - * result = f"({u','.join(extents)})".encode('ascii') + result - * - */ - { /* enter inner scope */ - __pyx_t_5 = PyList_New(0); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 1478, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __pyx_t_7 = __pyx_v_type->ndim; - __pyx_t_8 = __pyx_t_7; - for (__pyx_t_9 = 0; __pyx_t_9 < __pyx_t_8; __pyx_t_9+=1) { - __pyx_7genexpr__pyx_v_i = __pyx_t_9; - __pyx_t_4 = __Pyx_PyUnicode_From_size_t((__pyx_v_type->arraysize[__pyx_7genexpr__pyx_v_i]), 0, ' ', 'd'); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1478, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - if (unlikely(__Pyx_ListComp_Append(__pyx_t_5, (PyObject*)__pyx_t_4))) __PYX_ERR(1, 1478, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - } - } /* exit inner scope */ - __pyx_v_extents = ((PyObject*)__pyx_t_5); - __pyx_t_5 = 0; - - /* "BufferFormatFromTypeInfo":1479 - * if type.arraysize[0]: - * extents = [f"{type.arraysize[i]}" for i in range(type.ndim)] - * result = f"({u','.join(extents)})".encode('ascii') + result # <<<<<<<<<<<<<< - * - * return result - */ - __pyx_t_5 = PyTuple_New(3); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 1479, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __pyx_t_9 = 0; - __pyx_t_10 = 127; - __Pyx_INCREF(__pyx_kp_u__13); - __pyx_t_9 += 1; - __Pyx_GIVEREF(__pyx_kp_u__13); - PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_kp_u__13); - __pyx_t_4 = PyUnicode_Join(__pyx_kp_u__14, __pyx_v_extents); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1479, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __pyx_t_10 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_4) > __pyx_t_10) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_4) : __pyx_t_10; - __pyx_t_9 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_4); - __Pyx_GIVEREF(__pyx_t_4); - PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_t_4); - __pyx_t_4 = 0; - __Pyx_INCREF(__pyx_kp_u__7); - __pyx_t_9 += 1; - __Pyx_GIVEREF(__pyx_kp_u__7); - PyTuple_SET_ITEM(__pyx_t_5, 2, __pyx_kp_u__7); - __pyx_t_4 = __Pyx_PyUnicode_Join(__pyx_t_5, 3, __pyx_t_9, __pyx_t_10); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1479, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __pyx_t_5 = PyUnicode_AsASCIIString(((PyObject*)__pyx_t_4)); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 1479, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __pyx_t_4 = PyNumber_Add(__pyx_t_5, __pyx_v_result); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1479, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - if (!(likely(PyBytes_CheckExact(__pyx_t_4)) || __Pyx_RaiseUnexpectedTypeError("bytes", __pyx_t_4))) __PYX_ERR(1, 1479, __pyx_L1_error) - __Pyx_DECREF_SET(__pyx_v_result, ((PyObject*)__pyx_t_4)); - __pyx_t_4 = 0; - - /* "BufferFormatFromTypeInfo":1477 - * fmt = __Pyx_TypeInfoToFormat(type) - * result = fmt.string - * if type.arraysize[0]: # <<<<<<<<<<<<<< - * extents = [f"{type.arraysize[i]}" for i in range(type.ndim)] - * result = f"({u','.join(extents)})".encode('ascii') + result - */ - } - } - __pyx_L3:; - - /* "BufferFormatFromTypeInfo":1481 - * result = f"({u','.join(extents)})".encode('ascii') + result - * - * return result # <<<<<<<<<<<<<< - */ - __Pyx_XDECREF(__pyx_r); - __Pyx_INCREF(__pyx_v_result); - __pyx_r = __pyx_v_result; - goto __pyx_L0; - - /* "BufferFormatFromTypeInfo":1450 - * - * @cname('__pyx_format_from_typeinfo') - * cdef bytes format_from_typeinfo(__Pyx_TypeInfo *type): # <<<<<<<<<<<<<< - * cdef __Pyx_StructField *field - * cdef __pyx_typeinfo_string fmt - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_2); - __Pyx_XDECREF(__pyx_t_4); - __Pyx_XDECREF(__pyx_t_5); - __Pyx_AddTraceback("BufferFormatFromTypeInfo.format_from_typeinfo", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = 0; - __pyx_L0:; - __Pyx_XDECREF(__pyx_v_part); - __Pyx_XDECREF(__pyx_v_result); - __Pyx_XDECREF(__pyx_v_alignment); - __Pyx_XDECREF(__pyx_v_parts); - __Pyx_XDECREF(__pyx_v_extents); - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":245 - * - * @property - * cdef inline PyObject* base(self) nogil: # <<<<<<<<<<<<<< - * """Returns a borrowed reference to the object owning the data/memory. - * """ - */ - -static CYTHON_INLINE PyObject *__pyx_f_5numpy_7ndarray_4base_base(PyArrayObject *__pyx_v_self) { - PyObject *__pyx_r; - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":248 - * """Returns a borrowed reference to the object owning the data/memory. - * """ - * return PyArray_BASE(self) # <<<<<<<<<<<<<< - * - * @property - */ - __pyx_r = PyArray_BASE(__pyx_v_self); - goto __pyx_L0; - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":245 - * - * @property - * cdef inline PyObject* base(self) nogil: # <<<<<<<<<<<<<< - * """Returns a borrowed reference to the object owning the data/memory. - * """ - */ - - /* function exit code */ - __pyx_L0:; - return __pyx_r; -} - -/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":251 - * - * @property - * cdef inline dtype descr(self): # <<<<<<<<<<<<<< - * """Returns an owned reference to the dtype of the array. - * """ - */ - -static CYTHON_INLINE PyArray_Descr *__pyx_f_5numpy_7ndarray_5descr_descr(PyArrayObject *__pyx_v_self) { - PyArray_Descr *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - PyArray_Descr *__pyx_t_1; - __Pyx_RefNannySetupContext("descr", 1); - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":254 - * """Returns an owned reference to the dtype of the array. - * """ - * return PyArray_DESCR(self) # <<<<<<<<<<<<<< - * - * @property - */ - __Pyx_XDECREF((PyObject *)__pyx_r); - __pyx_t_1 = PyArray_DESCR(__pyx_v_self); - __Pyx_INCREF((PyObject *)((PyArray_Descr *)__pyx_t_1)); - __pyx_r = ((PyArray_Descr *)__pyx_t_1); - goto __pyx_L0; - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":251 - * - * @property - * cdef inline dtype descr(self): # <<<<<<<<<<<<<< - * """Returns an owned reference to the dtype of the array. - * """ - */ - - /* function exit code */ - __pyx_L0:; - __Pyx_XGIVEREF((PyObject *)__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":257 - * - * @property - * cdef inline int ndim(self) nogil: # <<<<<<<<<<<<<< - * """Returns the number of dimensions in the array. - * """ - */ - -static CYTHON_INLINE int __pyx_f_5numpy_7ndarray_4ndim_ndim(PyArrayObject *__pyx_v_self) { - int __pyx_r; - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":260 - * """Returns the number of dimensions in the array. - * """ - * return PyArray_NDIM(self) # <<<<<<<<<<<<<< - * - * @property - */ - __pyx_r = PyArray_NDIM(__pyx_v_self); - goto __pyx_L0; - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":257 - * - * @property - * cdef inline int ndim(self) nogil: # <<<<<<<<<<<<<< - * """Returns the number of dimensions in the array. - * """ - */ - - /* function exit code */ - __pyx_L0:; - return __pyx_r; -} - -/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":263 - * - * @property - * cdef inline npy_intp *shape(self) nogil: # <<<<<<<<<<<<<< - * """Returns a pointer to the dimensions/shape of the array. - * The number of elements matches the number of dimensions of the array (ndim). - */ - -static CYTHON_INLINE npy_intp *__pyx_f_5numpy_7ndarray_5shape_shape(PyArrayObject *__pyx_v_self) { - npy_intp *__pyx_r; - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":268 - * Can return NULL for 0-dimensional arrays. - * """ - * return PyArray_DIMS(self) # <<<<<<<<<<<<<< - * - * @property - */ - __pyx_r = PyArray_DIMS(__pyx_v_self); - goto __pyx_L0; - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":263 - * - * @property - * cdef inline npy_intp *shape(self) nogil: # <<<<<<<<<<<<<< - * """Returns a pointer to the dimensions/shape of the array. - * The number of elements matches the number of dimensions of the array (ndim). - */ - - /* function exit code */ - __pyx_L0:; - return __pyx_r; -} - -/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":271 - * - * @property - * cdef inline npy_intp *strides(self) nogil: # <<<<<<<<<<<<<< - * """Returns a pointer to the strides of the array. - * The number of elements matches the number of dimensions of the array (ndim). - */ - -static CYTHON_INLINE npy_intp *__pyx_f_5numpy_7ndarray_7strides_strides(PyArrayObject *__pyx_v_self) { - npy_intp *__pyx_r; - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":275 - * The number of elements matches the number of dimensions of the array (ndim). - * """ - * return PyArray_STRIDES(self) # <<<<<<<<<<<<<< - * - * @property - */ - __pyx_r = PyArray_STRIDES(__pyx_v_self); - goto __pyx_L0; - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":271 - * - * @property - * cdef inline npy_intp *strides(self) nogil: # <<<<<<<<<<<<<< - * """Returns a pointer to the strides of the array. - * The number of elements matches the number of dimensions of the array (ndim). - */ - - /* function exit code */ - __pyx_L0:; - return __pyx_r; -} - -/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":278 - * - * @property - * cdef inline npy_intp size(self) nogil: # <<<<<<<<<<<<<< - * """Returns the total size (in number of elements) of the array. - * """ - */ - -static CYTHON_INLINE npy_intp __pyx_f_5numpy_7ndarray_4size_size(PyArrayObject *__pyx_v_self) { - npy_intp __pyx_r; - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":281 - * """Returns the total size (in number of elements) of the array. - * """ - * return PyArray_SIZE(self) # <<<<<<<<<<<<<< - * - * @property - */ - __pyx_r = PyArray_SIZE(__pyx_v_self); - goto __pyx_L0; - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":278 - * - * @property - * cdef inline npy_intp size(self) nogil: # <<<<<<<<<<<<<< - * """Returns the total size (in number of elements) of the array. - * """ - */ - - /* function exit code */ - __pyx_L0:; - return __pyx_r; -} - -/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":284 - * - * @property - * cdef inline char* data(self) nogil: # <<<<<<<<<<<<<< - * """The pointer to the data buffer as a char*. - * This is provided for legacy reasons to avoid direct struct field access. - */ - -static CYTHON_INLINE char *__pyx_f_5numpy_7ndarray_4data_data(PyArrayObject *__pyx_v_self) { - char *__pyx_r; - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":290 - * of `PyArray_DATA()` instead, which returns a 'void*'. - * """ - * return PyArray_BYTES(self) # <<<<<<<<<<<<<< - * - * ctypedef unsigned char npy_bool - */ - __pyx_r = PyArray_BYTES(__pyx_v_self); - goto __pyx_L0; - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":284 - * - * @property - * cdef inline char* data(self) nogil: # <<<<<<<<<<<<<< - * """The pointer to the data buffer as a char*. - * This is provided for legacy reasons to avoid direct struct field access. - */ - - /* function exit code */ - __pyx_L0:; - return __pyx_r; -} - -/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":773 - * ctypedef npy_cdouble complex_t - * - * cdef inline object PyArray_MultiIterNew1(a): # <<<<<<<<<<<<<< - * return PyArray_MultiIterNew(1, a) - * - */ - -static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew1(PyObject *__pyx_v_a) { - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - PyObject *__pyx_t_1 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("PyArray_MultiIterNew1", 1); - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":774 - * - * cdef inline object PyArray_MultiIterNew1(a): - * return PyArray_MultiIterNew(1, a) # <<<<<<<<<<<<<< - * - * cdef inline object PyArray_MultiIterNew2(a, b): - */ - __Pyx_XDECREF(__pyx_r); - __pyx_t_1 = PyArray_MultiIterNew(1, ((void *)__pyx_v_a)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 774, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_r = __pyx_t_1; - __pyx_t_1 = 0; - goto __pyx_L0; - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":773 - * ctypedef npy_cdouble complex_t - * - * cdef inline object PyArray_MultiIterNew1(a): # <<<<<<<<<<<<<< - * return PyArray_MultiIterNew(1, a) - * - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_1); - __Pyx_AddTraceback("numpy.PyArray_MultiIterNew1", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = 0; - __pyx_L0:; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":776 - * return PyArray_MultiIterNew(1, a) - * - * cdef inline object PyArray_MultiIterNew2(a, b): # <<<<<<<<<<<<<< - * return PyArray_MultiIterNew(2, a, b) - * - */ - -static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew2(PyObject *__pyx_v_a, PyObject *__pyx_v_b) { - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - PyObject *__pyx_t_1 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("PyArray_MultiIterNew2", 1); - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":777 - * - * cdef inline object PyArray_MultiIterNew2(a, b): - * return PyArray_MultiIterNew(2, a, b) # <<<<<<<<<<<<<< - * - * cdef inline object PyArray_MultiIterNew3(a, b, c): - */ - __Pyx_XDECREF(__pyx_r); - __pyx_t_1 = PyArray_MultiIterNew(2, ((void *)__pyx_v_a), ((void *)__pyx_v_b)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 777, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_r = __pyx_t_1; - __pyx_t_1 = 0; - goto __pyx_L0; - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":776 - * return PyArray_MultiIterNew(1, a) - * - * cdef inline object PyArray_MultiIterNew2(a, b): # <<<<<<<<<<<<<< - * return PyArray_MultiIterNew(2, a, b) - * - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_1); - __Pyx_AddTraceback("numpy.PyArray_MultiIterNew2", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = 0; - __pyx_L0:; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":779 - * return PyArray_MultiIterNew(2, a, b) - * - * cdef inline object PyArray_MultiIterNew3(a, b, c): # <<<<<<<<<<<<<< - * return PyArray_MultiIterNew(3, a, b, c) - * - */ - -static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew3(PyObject *__pyx_v_a, PyObject *__pyx_v_b, PyObject *__pyx_v_c) { - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - PyObject *__pyx_t_1 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("PyArray_MultiIterNew3", 1); - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":780 - * - * cdef inline object PyArray_MultiIterNew3(a, b, c): - * return PyArray_MultiIterNew(3, a, b, c) # <<<<<<<<<<<<<< - * - * cdef inline object PyArray_MultiIterNew4(a, b, c, d): - */ - __Pyx_XDECREF(__pyx_r); - __pyx_t_1 = PyArray_MultiIterNew(3, ((void *)__pyx_v_a), ((void *)__pyx_v_b), ((void *)__pyx_v_c)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 780, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_r = __pyx_t_1; - __pyx_t_1 = 0; - goto __pyx_L0; - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":779 - * return PyArray_MultiIterNew(2, a, b) - * - * cdef inline object PyArray_MultiIterNew3(a, b, c): # <<<<<<<<<<<<<< - * return PyArray_MultiIterNew(3, a, b, c) - * - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_1); - __Pyx_AddTraceback("numpy.PyArray_MultiIterNew3", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = 0; - __pyx_L0:; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":782 - * return PyArray_MultiIterNew(3, a, b, c) - * - * cdef inline object PyArray_MultiIterNew4(a, b, c, d): # <<<<<<<<<<<<<< - * return PyArray_MultiIterNew(4, a, b, c, d) - * - */ - -static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew4(PyObject *__pyx_v_a, PyObject *__pyx_v_b, PyObject *__pyx_v_c, PyObject *__pyx_v_d) { - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - PyObject *__pyx_t_1 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("PyArray_MultiIterNew4", 1); - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":783 - * - * cdef inline object PyArray_MultiIterNew4(a, b, c, d): - * return PyArray_MultiIterNew(4, a, b, c, d) # <<<<<<<<<<<<<< - * - * cdef inline object PyArray_MultiIterNew5(a, b, c, d, e): - */ - __Pyx_XDECREF(__pyx_r); - __pyx_t_1 = PyArray_MultiIterNew(4, ((void *)__pyx_v_a), ((void *)__pyx_v_b), ((void *)__pyx_v_c), ((void *)__pyx_v_d)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 783, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_r = __pyx_t_1; - __pyx_t_1 = 0; - goto __pyx_L0; - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":782 - * return PyArray_MultiIterNew(3, a, b, c) - * - * cdef inline object PyArray_MultiIterNew4(a, b, c, d): # <<<<<<<<<<<<<< - * return PyArray_MultiIterNew(4, a, b, c, d) - * - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_1); - __Pyx_AddTraceback("numpy.PyArray_MultiIterNew4", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = 0; - __pyx_L0:; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":785 - * return PyArray_MultiIterNew(4, a, b, c, d) - * - * cdef inline object PyArray_MultiIterNew5(a, b, c, d, e): # <<<<<<<<<<<<<< - * return PyArray_MultiIterNew(5, a, b, c, d, e) - * - */ - -static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew5(PyObject *__pyx_v_a, PyObject *__pyx_v_b, PyObject *__pyx_v_c, PyObject *__pyx_v_d, PyObject *__pyx_v_e) { - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - PyObject *__pyx_t_1 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("PyArray_MultiIterNew5", 1); - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":786 - * - * cdef inline object PyArray_MultiIterNew5(a, b, c, d, e): - * return PyArray_MultiIterNew(5, a, b, c, d, e) # <<<<<<<<<<<<<< - * - * cdef inline tuple PyDataType_SHAPE(dtype d): - */ - __Pyx_XDECREF(__pyx_r); - __pyx_t_1 = PyArray_MultiIterNew(5, ((void *)__pyx_v_a), ((void *)__pyx_v_b), ((void *)__pyx_v_c), ((void *)__pyx_v_d), ((void *)__pyx_v_e)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 786, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_r = __pyx_t_1; - __pyx_t_1 = 0; - goto __pyx_L0; - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":785 - * return PyArray_MultiIterNew(4, a, b, c, d) - * - * cdef inline object PyArray_MultiIterNew5(a, b, c, d, e): # <<<<<<<<<<<<<< - * return PyArray_MultiIterNew(5, a, b, c, d, e) - * - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_1); - __Pyx_AddTraceback("numpy.PyArray_MultiIterNew5", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = 0; - __pyx_L0:; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":788 - * return PyArray_MultiIterNew(5, a, b, c, d, e) - * - * cdef inline tuple PyDataType_SHAPE(dtype d): # <<<<<<<<<<<<<< - * if PyDataType_HASSUBARRAY(d): - * return d.subarray.shape - */ - -static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyDataType_SHAPE(PyArray_Descr *__pyx_v_d) { - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - int __pyx_t_1; - __Pyx_RefNannySetupContext("PyDataType_SHAPE", 1); - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":789 - * - * cdef inline tuple PyDataType_SHAPE(dtype d): - * if PyDataType_HASSUBARRAY(d): # <<<<<<<<<<<<<< - * return d.subarray.shape - * else: - */ - __pyx_t_1 = PyDataType_HASSUBARRAY(__pyx_v_d); - if (__pyx_t_1) { - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":790 - * cdef inline tuple PyDataType_SHAPE(dtype d): - * if PyDataType_HASSUBARRAY(d): - * return d.subarray.shape # <<<<<<<<<<<<<< - * else: - * return () - */ - __Pyx_XDECREF(__pyx_r); - __Pyx_INCREF(((PyObject*)__pyx_v_d->subarray->shape)); - __pyx_r = ((PyObject*)__pyx_v_d->subarray->shape); - goto __pyx_L0; - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":789 - * - * cdef inline tuple PyDataType_SHAPE(dtype d): - * if PyDataType_HASSUBARRAY(d): # <<<<<<<<<<<<<< - * return d.subarray.shape - * else: - */ - } - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":792 - * return d.subarray.shape - * else: - * return () # <<<<<<<<<<<<<< - * - * - */ - /*else*/ { - __Pyx_XDECREF(__pyx_r); - __Pyx_INCREF(__pyx_empty_tuple); - __pyx_r = __pyx_empty_tuple; - goto __pyx_L0; - } - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":788 - * return PyArray_MultiIterNew(5, a, b, c, d, e) - * - * cdef inline tuple PyDataType_SHAPE(dtype d): # <<<<<<<<<<<<<< - * if PyDataType_HASSUBARRAY(d): - * return d.subarray.shape - */ - - /* function exit code */ - __pyx_L0:; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":968 - * int _import_umath() except -1 - * - * cdef inline void set_array_base(ndarray arr, object base): # <<<<<<<<<<<<<< - * Py_INCREF(base) # important to do this before stealing the reference below! - * PyArray_SetBaseObject(arr, base) - */ - -static CYTHON_INLINE void __pyx_f_5numpy_set_array_base(PyArrayObject *__pyx_v_arr, PyObject *__pyx_v_base) { - int __pyx_t_1; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":969 - * - * cdef inline void set_array_base(ndarray arr, object base): - * Py_INCREF(base) # important to do this before stealing the reference below! # <<<<<<<<<<<<<< - * PyArray_SetBaseObject(arr, base) - * - */ - Py_INCREF(__pyx_v_base); - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":970 - * cdef inline void set_array_base(ndarray arr, object base): - * Py_INCREF(base) # important to do this before stealing the reference below! - * PyArray_SetBaseObject(arr, base) # <<<<<<<<<<<<<< - * - * cdef inline object get_array_base(ndarray arr): - */ - __pyx_t_1 = PyArray_SetBaseObject(__pyx_v_arr, __pyx_v_base); if (unlikely(__pyx_t_1 == ((int)-1))) __PYX_ERR(2, 970, __pyx_L1_error) - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":968 - * int _import_umath() except -1 - * - * cdef inline void set_array_base(ndarray arr, object base): # <<<<<<<<<<<<<< - * Py_INCREF(base) # important to do this before stealing the reference below! - * PyArray_SetBaseObject(arr, base) - */ - - /* function exit code */ - goto __pyx_L0; - __pyx_L1_error:; - __Pyx_AddTraceback("numpy.set_array_base", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_L0:; -} - -/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":972 - * PyArray_SetBaseObject(arr, base) - * - * cdef inline object get_array_base(ndarray arr): # <<<<<<<<<<<<<< - * base = PyArray_BASE(arr) - * if base is NULL: - */ - -static CYTHON_INLINE PyObject *__pyx_f_5numpy_get_array_base(PyArrayObject *__pyx_v_arr) { - PyObject *__pyx_v_base; - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - int __pyx_t_1; - __Pyx_RefNannySetupContext("get_array_base", 1); - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":973 - * - * cdef inline object get_array_base(ndarray arr): - * base = PyArray_BASE(arr) # <<<<<<<<<<<<<< - * if base is NULL: - * return None - */ - __pyx_v_base = PyArray_BASE(__pyx_v_arr); - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":974 - * cdef inline object get_array_base(ndarray arr): - * base = PyArray_BASE(arr) - * if base is NULL: # <<<<<<<<<<<<<< - * return None - * return base - */ - __pyx_t_1 = (__pyx_v_base == NULL); - if (__pyx_t_1) { - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":975 - * base = PyArray_BASE(arr) - * if base is NULL: - * return None # <<<<<<<<<<<<<< - * return base - * - */ - __Pyx_XDECREF(__pyx_r); - __pyx_r = Py_None; __Pyx_INCREF(Py_None); - goto __pyx_L0; - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":974 - * cdef inline object get_array_base(ndarray arr): - * base = PyArray_BASE(arr) - * if base is NULL: # <<<<<<<<<<<<<< - * return None - * return base - */ - } - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":976 - * if base is NULL: - * return None - * return base # <<<<<<<<<<<<<< - * - * # Versions of the import_* functions which are more suitable for - */ - __Pyx_XDECREF(__pyx_r); - __Pyx_INCREF(((PyObject *)__pyx_v_base)); - __pyx_r = ((PyObject *)__pyx_v_base); - goto __pyx_L0; - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":972 - * PyArray_SetBaseObject(arr, base) - * - * cdef inline object get_array_base(ndarray arr): # <<<<<<<<<<<<<< - * base = PyArray_BASE(arr) - * if base is NULL: - */ - - /* function exit code */ - __pyx_L0:; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":980 - * # Versions of the import_* functions which are more suitable for - * # Cython code. - * cdef inline int import_array() except -1: # <<<<<<<<<<<<<< - * try: - * __pyx_import_array() - */ - -static CYTHON_INLINE int __pyx_f_5numpy_import_array(void) { - int __pyx_r; - __Pyx_RefNannyDeclarations - PyObject *__pyx_t_1 = NULL; - PyObject *__pyx_t_2 = NULL; - PyObject *__pyx_t_3 = NULL; - int __pyx_t_4; - PyObject *__pyx_t_5 = NULL; - PyObject *__pyx_t_6 = NULL; - PyObject *__pyx_t_7 = NULL; - PyObject *__pyx_t_8 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("import_array", 1); - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":981 - * # Cython code. - * cdef inline int import_array() except -1: - * try: # <<<<<<<<<<<<<< - * __pyx_import_array() - * except Exception: - */ - { - __Pyx_PyThreadState_declare - __Pyx_PyThreadState_assign - __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); - __Pyx_XGOTREF(__pyx_t_1); - __Pyx_XGOTREF(__pyx_t_2); - __Pyx_XGOTREF(__pyx_t_3); - /*try:*/ { - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":982 - * cdef inline int import_array() except -1: - * try: - * __pyx_import_array() # <<<<<<<<<<<<<< - * except Exception: - * raise ImportError("numpy.core.multiarray failed to import") - */ - __pyx_t_4 = _import_array(); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(2, 982, __pyx_L3_error) - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":981 - * # Cython code. - * cdef inline int import_array() except -1: - * try: # <<<<<<<<<<<<<< - * __pyx_import_array() - * except Exception: - */ - } - __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; - __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; - __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; - goto __pyx_L8_try_end; - __pyx_L3_error:; - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":983 - * try: - * __pyx_import_array() - * except Exception: # <<<<<<<<<<<<<< - * raise ImportError("numpy.core.multiarray failed to import") - * - */ - __pyx_t_4 = __Pyx_PyErr_ExceptionMatches(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0]))); - if (__pyx_t_4) { - __Pyx_AddTraceback("numpy.import_array", __pyx_clineno, __pyx_lineno, __pyx_filename); - if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_6, &__pyx_t_7) < 0) __PYX_ERR(2, 983, __pyx_L5_except_error) - __Pyx_XGOTREF(__pyx_t_5); - __Pyx_XGOTREF(__pyx_t_6); - __Pyx_XGOTREF(__pyx_t_7); - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":984 - * __pyx_import_array() - * except Exception: - * raise ImportError("numpy.core.multiarray failed to import") # <<<<<<<<<<<<<< - * - * cdef inline int import_umath() except -1: - */ - __pyx_t_8 = __Pyx_PyObject_Call(__pyx_builtin_ImportError, __pyx_tuple__15, NULL); if (unlikely(!__pyx_t_8)) __PYX_ERR(2, 984, __pyx_L5_except_error) - __Pyx_GOTREF(__pyx_t_8); - __Pyx_Raise(__pyx_t_8, 0, 0, 0); - __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; - __PYX_ERR(2, 984, __pyx_L5_except_error) - } - goto __pyx_L5_except_error; - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":981 - * # Cython code. - * cdef inline int import_array() except -1: - * try: # <<<<<<<<<<<<<< - * __pyx_import_array() - * except Exception: - */ - __pyx_L5_except_error:; - __Pyx_XGIVEREF(__pyx_t_1); - __Pyx_XGIVEREF(__pyx_t_2); - __Pyx_XGIVEREF(__pyx_t_3); - __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); - goto __pyx_L1_error; - __pyx_L8_try_end:; - } - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":980 - * # Versions of the import_* functions which are more suitable for - * # Cython code. - * cdef inline int import_array() except -1: # <<<<<<<<<<<<<< - * try: - * __pyx_import_array() - */ - - /* function exit code */ - __pyx_r = 0; - goto __pyx_L0; - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_5); - __Pyx_XDECREF(__pyx_t_6); - __Pyx_XDECREF(__pyx_t_7); - __Pyx_XDECREF(__pyx_t_8); - __Pyx_AddTraceback("numpy.import_array", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = -1; - __pyx_L0:; - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":986 - * raise ImportError("numpy.core.multiarray failed to import") - * - * cdef inline int import_umath() except -1: # <<<<<<<<<<<<<< - * try: - * _import_umath() - */ - -static CYTHON_INLINE int __pyx_f_5numpy_import_umath(void) { - int __pyx_r; - __Pyx_RefNannyDeclarations - PyObject *__pyx_t_1 = NULL; - PyObject *__pyx_t_2 = NULL; - PyObject *__pyx_t_3 = NULL; - int __pyx_t_4; - PyObject *__pyx_t_5 = NULL; - PyObject *__pyx_t_6 = NULL; - PyObject *__pyx_t_7 = NULL; - PyObject *__pyx_t_8 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("import_umath", 1); - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":987 - * - * cdef inline int import_umath() except -1: - * try: # <<<<<<<<<<<<<< - * _import_umath() - * except Exception: - */ - { - __Pyx_PyThreadState_declare - __Pyx_PyThreadState_assign - __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); - __Pyx_XGOTREF(__pyx_t_1); - __Pyx_XGOTREF(__pyx_t_2); - __Pyx_XGOTREF(__pyx_t_3); - /*try:*/ { - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":988 - * cdef inline int import_umath() except -1: - * try: - * _import_umath() # <<<<<<<<<<<<<< - * except Exception: - * raise ImportError("numpy.core.umath failed to import") - */ - __pyx_t_4 = _import_umath(); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(2, 988, __pyx_L3_error) - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":987 - * - * cdef inline int import_umath() except -1: - * try: # <<<<<<<<<<<<<< - * _import_umath() - * except Exception: - */ - } - __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; - __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; - __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; - goto __pyx_L8_try_end; - __pyx_L3_error:; - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":989 - * try: - * _import_umath() - * except Exception: # <<<<<<<<<<<<<< - * raise ImportError("numpy.core.umath failed to import") - * - */ - __pyx_t_4 = __Pyx_PyErr_ExceptionMatches(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0]))); - if (__pyx_t_4) { - __Pyx_AddTraceback("numpy.import_umath", __pyx_clineno, __pyx_lineno, __pyx_filename); - if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_6, &__pyx_t_7) < 0) __PYX_ERR(2, 989, __pyx_L5_except_error) - __Pyx_XGOTREF(__pyx_t_5); - __Pyx_XGOTREF(__pyx_t_6); - __Pyx_XGOTREF(__pyx_t_7); - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":990 - * _import_umath() - * except Exception: - * raise ImportError("numpy.core.umath failed to import") # <<<<<<<<<<<<<< - * - * cdef inline int import_ufunc() except -1: - */ - __pyx_t_8 = __Pyx_PyObject_Call(__pyx_builtin_ImportError, __pyx_tuple__16, NULL); if (unlikely(!__pyx_t_8)) __PYX_ERR(2, 990, __pyx_L5_except_error) - __Pyx_GOTREF(__pyx_t_8); - __Pyx_Raise(__pyx_t_8, 0, 0, 0); - __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; - __PYX_ERR(2, 990, __pyx_L5_except_error) - } - goto __pyx_L5_except_error; - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":987 - * - * cdef inline int import_umath() except -1: - * try: # <<<<<<<<<<<<<< - * _import_umath() - * except Exception: - */ - __pyx_L5_except_error:; - __Pyx_XGIVEREF(__pyx_t_1); - __Pyx_XGIVEREF(__pyx_t_2); - __Pyx_XGIVEREF(__pyx_t_3); - __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); - goto __pyx_L1_error; - __pyx_L8_try_end:; - } - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":986 - * raise ImportError("numpy.core.multiarray failed to import") - * - * cdef inline int import_umath() except -1: # <<<<<<<<<<<<<< - * try: - * _import_umath() - */ - - /* function exit code */ - __pyx_r = 0; - goto __pyx_L0; - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_5); - __Pyx_XDECREF(__pyx_t_6); - __Pyx_XDECREF(__pyx_t_7); - __Pyx_XDECREF(__pyx_t_8); - __Pyx_AddTraceback("numpy.import_umath", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = -1; - __pyx_L0:; - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":992 - * raise ImportError("numpy.core.umath failed to import") - * - * cdef inline int import_ufunc() except -1: # <<<<<<<<<<<<<< - * try: - * _import_umath() - */ - -static CYTHON_INLINE int __pyx_f_5numpy_import_ufunc(void) { - int __pyx_r; - __Pyx_RefNannyDeclarations - PyObject *__pyx_t_1 = NULL; - PyObject *__pyx_t_2 = NULL; - PyObject *__pyx_t_3 = NULL; - int __pyx_t_4; - PyObject *__pyx_t_5 = NULL; - PyObject *__pyx_t_6 = NULL; - PyObject *__pyx_t_7 = NULL; - PyObject *__pyx_t_8 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("import_ufunc", 1); - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":993 - * - * cdef inline int import_ufunc() except -1: - * try: # <<<<<<<<<<<<<< - * _import_umath() - * except Exception: - */ - { - __Pyx_PyThreadState_declare - __Pyx_PyThreadState_assign - __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); - __Pyx_XGOTREF(__pyx_t_1); - __Pyx_XGOTREF(__pyx_t_2); - __Pyx_XGOTREF(__pyx_t_3); - /*try:*/ { - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":994 - * cdef inline int import_ufunc() except -1: - * try: - * _import_umath() # <<<<<<<<<<<<<< - * except Exception: - * raise ImportError("numpy.core.umath failed to import") - */ - __pyx_t_4 = _import_umath(); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(2, 994, __pyx_L3_error) - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":993 - * - * cdef inline int import_ufunc() except -1: - * try: # <<<<<<<<<<<<<< - * _import_umath() - * except Exception: - */ - } - __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; - __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; - __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; - goto __pyx_L8_try_end; - __pyx_L3_error:; - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":995 - * try: - * _import_umath() - * except Exception: # <<<<<<<<<<<<<< - * raise ImportError("numpy.core.umath failed to import") - * - */ - __pyx_t_4 = __Pyx_PyErr_ExceptionMatches(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0]))); - if (__pyx_t_4) { - __Pyx_AddTraceback("numpy.import_ufunc", __pyx_clineno, __pyx_lineno, __pyx_filename); - if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_6, &__pyx_t_7) < 0) __PYX_ERR(2, 995, __pyx_L5_except_error) - __Pyx_XGOTREF(__pyx_t_5); - __Pyx_XGOTREF(__pyx_t_6); - __Pyx_XGOTREF(__pyx_t_7); - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":996 - * _import_umath() - * except Exception: - * raise ImportError("numpy.core.umath failed to import") # <<<<<<<<<<<<<< - * - * - */ - __pyx_t_8 = __Pyx_PyObject_Call(__pyx_builtin_ImportError, __pyx_tuple__16, NULL); if (unlikely(!__pyx_t_8)) __PYX_ERR(2, 996, __pyx_L5_except_error) - __Pyx_GOTREF(__pyx_t_8); - __Pyx_Raise(__pyx_t_8, 0, 0, 0); - __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; - __PYX_ERR(2, 996, __pyx_L5_except_error) - } - goto __pyx_L5_except_error; - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":993 - * - * cdef inline int import_ufunc() except -1: - * try: # <<<<<<<<<<<<<< - * _import_umath() - * except Exception: - */ - __pyx_L5_except_error:; - __Pyx_XGIVEREF(__pyx_t_1); - __Pyx_XGIVEREF(__pyx_t_2); - __Pyx_XGIVEREF(__pyx_t_3); - __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); - goto __pyx_L1_error; - __pyx_L8_try_end:; - } - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":992 - * raise ImportError("numpy.core.umath failed to import") - * - * cdef inline int import_ufunc() except -1: # <<<<<<<<<<<<<< - * try: - * _import_umath() - */ - - /* function exit code */ - __pyx_r = 0; - goto __pyx_L0; - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_5); - __Pyx_XDECREF(__pyx_t_6); - __Pyx_XDECREF(__pyx_t_7); - __Pyx_XDECREF(__pyx_t_8); - __Pyx_AddTraceback("numpy.import_ufunc", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = -1; - __pyx_L0:; - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":999 - * - * - * cdef inline bint is_timedelta64_object(object obj): # <<<<<<<<<<<<<< - * """ - * Cython equivalent of `isinstance(obj, np.timedelta64)` - */ - -static CYTHON_INLINE int __pyx_f_5numpy_is_timedelta64_object(PyObject *__pyx_v_obj) { - int __pyx_r; - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1011 - * bool - * """ - * return PyObject_TypeCheck(obj, &PyTimedeltaArrType_Type) # <<<<<<<<<<<<<< - * - * - */ - __pyx_r = PyObject_TypeCheck(__pyx_v_obj, (&PyTimedeltaArrType_Type)); - goto __pyx_L0; - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":999 - * - * - * cdef inline bint is_timedelta64_object(object obj): # <<<<<<<<<<<<<< - * """ - * Cython equivalent of `isinstance(obj, np.timedelta64)` - */ - - /* function exit code */ - __pyx_L0:; - return __pyx_r; -} - -/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1014 - * - * - * cdef inline bint is_datetime64_object(object obj): # <<<<<<<<<<<<<< - * """ - * Cython equivalent of `isinstance(obj, np.datetime64)` - */ - -static CYTHON_INLINE int __pyx_f_5numpy_is_datetime64_object(PyObject *__pyx_v_obj) { - int __pyx_r; - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1026 - * bool - * """ - * return PyObject_TypeCheck(obj, &PyDatetimeArrType_Type) # <<<<<<<<<<<<<< - * - * - */ - __pyx_r = PyObject_TypeCheck(__pyx_v_obj, (&PyDatetimeArrType_Type)); - goto __pyx_L0; - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1014 - * - * - * cdef inline bint is_datetime64_object(object obj): # <<<<<<<<<<<<<< - * """ - * Cython equivalent of `isinstance(obj, np.datetime64)` - */ - - /* function exit code */ - __pyx_L0:; - return __pyx_r; -} - -/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1029 - * - * - * cdef inline npy_datetime get_datetime64_value(object obj) nogil: # <<<<<<<<<<<<<< - * """ - * returns the int64 value underlying scalar numpy datetime64 object - */ - -static CYTHON_INLINE npy_datetime __pyx_f_5numpy_get_datetime64_value(PyObject *__pyx_v_obj) { - npy_datetime __pyx_r; - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1036 - * also needed. That can be found using `get_datetime64_unit`. - * """ - * return (obj).obval # <<<<<<<<<<<<<< - * - * - */ - __pyx_r = ((PyDatetimeScalarObject *)__pyx_v_obj)->obval; - goto __pyx_L0; - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1029 - * - * - * cdef inline npy_datetime get_datetime64_value(object obj) nogil: # <<<<<<<<<<<<<< - * """ - * returns the int64 value underlying scalar numpy datetime64 object - */ - - /* function exit code */ - __pyx_L0:; - return __pyx_r; -} - -/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1039 - * - * - * cdef inline npy_timedelta get_timedelta64_value(object obj) nogil: # <<<<<<<<<<<<<< - * """ - * returns the int64 value underlying scalar numpy timedelta64 object - */ - -static CYTHON_INLINE npy_timedelta __pyx_f_5numpy_get_timedelta64_value(PyObject *__pyx_v_obj) { - npy_timedelta __pyx_r; - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1043 - * returns the int64 value underlying scalar numpy timedelta64 object - * """ - * return (obj).obval # <<<<<<<<<<<<<< - * - * - */ - __pyx_r = ((PyTimedeltaScalarObject *)__pyx_v_obj)->obval; - goto __pyx_L0; - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1039 - * - * - * cdef inline npy_timedelta get_timedelta64_value(object obj) nogil: # <<<<<<<<<<<<<< - * """ - * returns the int64 value underlying scalar numpy timedelta64 object - */ - - /* function exit code */ - __pyx_L0:; - return __pyx_r; -} - -/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1046 - * - * - * cdef inline NPY_DATETIMEUNIT get_datetime64_unit(object obj) nogil: # <<<<<<<<<<<<<< - * """ - * returns the unit part of the dtype for a numpy datetime64 object. - */ - -static CYTHON_INLINE NPY_DATETIMEUNIT __pyx_f_5numpy_get_datetime64_unit(PyObject *__pyx_v_obj) { - NPY_DATETIMEUNIT __pyx_r; - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1050 - * returns the unit part of the dtype for a numpy datetime64 object. - * """ - * return (obj).obmeta.base # <<<<<<<<<<<<<< - */ - __pyx_r = ((NPY_DATETIMEUNIT)((PyDatetimeScalarObject *)__pyx_v_obj)->obmeta.base); - goto __pyx_L0; - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1046 - * - * - * cdef inline NPY_DATETIMEUNIT get_datetime64_unit(object obj) nogil: # <<<<<<<<<<<<<< - * """ - * returns the unit part of the dtype for a numpy datetime64 object. - */ - - /* function exit code */ - __pyx_L0:; - return __pyx_r; -} - -/* "rednose/helpers/ekf_sym_pyx.pyx":75 - * @cython.wraparound(False) - * @cython.boundscheck(False) - * cdef np.ndarray[np.float64_t, ndim=2, mode="c"] matrix_to_numpy(MatrixXdr arr): # <<<<<<<<<<<<<< - * cdef double[:,:] mem_view = arr.data() - * return np.copy(np.asarray(mem_view, dtype=np.double, order="C")) - */ - -static PyArrayObject *__pyx_f_7rednose_7helpers_11ekf_sym_pyx_matrix_to_numpy(Eigen::Matrix __pyx_v_arr) { - __Pyx_memviewslice __pyx_v_mem_view = { 0, 0, { 0 }, { 0 }, { 0 } }; - PyArrayObject *__pyx_r = NULL; - __Pyx_TraceDeclarations - __Pyx_RefNannyDeclarations - double *__pyx_t_1; - struct __pyx_array_obj *__pyx_t_2 = NULL; - PyObject *__pyx_t_3 = NULL; - PyObject *__pyx_t_4 = NULL; - __Pyx_memviewslice __pyx_t_5 = { 0, 0, { 0 }, { 0 }, { 0 } }; - PyObject *__pyx_t_6 = NULL; - PyObject *__pyx_t_7 = NULL; - PyObject *__pyx_t_8 = NULL; - PyObject *__pyx_t_9 = NULL; - PyObject *__pyx_t_10 = NULL; - int __pyx_t_11; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("matrix_to_numpy", 1); - __Pyx_TraceCall("matrix_to_numpy", __pyx_f[0], 75, 0, __PYX_ERR(0, 75, __pyx_L1_error)); - - /* "rednose/helpers/ekf_sym_pyx.pyx":76 - * @cython.boundscheck(False) - * cdef np.ndarray[np.float64_t, ndim=2, mode="c"] matrix_to_numpy(MatrixXdr arr): - * cdef double[:,:] mem_view = arr.data() # <<<<<<<<<<<<<< - * return np.copy(np.asarray(mem_view, dtype=np.double, order="C")) - * - */ - __pyx_t_1 = __pyx_v_arr.data(); - if (!__pyx_t_1) { - PyErr_SetString(PyExc_ValueError,"Cannot create cython.array from NULL pointer"); - __PYX_ERR(0, 76, __pyx_L1_error) - } - __pyx_t_4 = __pyx_format_from_typeinfo(&__Pyx_TypeInfo_double); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 76, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __pyx_t_3 = Py_BuildValue((char*) "(" __PYX_BUILD_PY_SSIZE_T __PYX_BUILD_PY_SSIZE_T ")", ((Py_ssize_t)__pyx_v_arr.rows()), ((Py_ssize_t)__pyx_v_arr.cols())); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 76, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __pyx_t_2 = __pyx_array_new(__pyx_t_3, sizeof(double), PyBytes_AS_STRING(__pyx_t_4), (char *) "c", (char *) __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 76, __pyx_L1_error) - __Pyx_GOTREF((PyObject *)__pyx_t_2); - __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __pyx_t_5 = __Pyx_PyObject_to_MemoryviewSlice_dsds_double(((PyObject *)__pyx_t_2), PyBUF_WRITABLE); if (unlikely(!__pyx_t_5.memview)) __PYX_ERR(0, 76, __pyx_L1_error) - __Pyx_DECREF((PyObject *)__pyx_t_2); __pyx_t_2 = 0; - __pyx_v_mem_view = __pyx_t_5; - __pyx_t_5.memview = NULL; - __pyx_t_5.data = NULL; - - /* "rednose/helpers/ekf_sym_pyx.pyx":77 - * cdef np.ndarray[np.float64_t, ndim=2, mode="c"] matrix_to_numpy(MatrixXdr arr): - * cdef double[:,:] mem_view = arr.data() - * return np.copy(np.asarray(mem_view, dtype=np.double, order="C")) # <<<<<<<<<<<<<< - * - * @cython.wraparound(False) - */ - __Pyx_XDECREF((PyObject *)__pyx_r); - __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_np); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 77, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_copy); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 77, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_6); - __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_np); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 77, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_asarray); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 77, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - __pyx_t_3 = __pyx_memoryview_fromslice(__pyx_v_mem_view, 2, (PyObject *(*)(char *)) __pyx_memview_get_double, (int (*)(char *, PyObject *)) __pyx_memview_set_double, 0);; if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 77, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __pyx_t_8 = PyTuple_New(1); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 77, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_8); - __Pyx_GIVEREF(__pyx_t_3); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_8, 0, __pyx_t_3)) __PYX_ERR(0, 77, __pyx_L1_error); - __pyx_t_3 = 0; - __pyx_t_3 = __Pyx_PyDict_NewPresized(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 77, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __Pyx_GetModuleGlobalName(__pyx_t_9, __pyx_n_s_np); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 77, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_9); - __pyx_t_10 = __Pyx_PyObject_GetAttrStr(__pyx_t_9, __pyx_n_s_double); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 77, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_10); - __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; - if (PyDict_SetItem(__pyx_t_3, __pyx_n_s_dtype, __pyx_t_10) < 0) __PYX_ERR(0, 77, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; - if (PyDict_SetItem(__pyx_t_3, __pyx_n_s_order, __pyx_n_u_C) < 0) __PYX_ERR(0, 77, __pyx_L1_error) - __pyx_t_10 = __Pyx_PyObject_Call(__pyx_t_7, __pyx_t_8, __pyx_t_3); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 77, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_10); - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; - __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - __pyx_t_3 = NULL; - __pyx_t_11 = 0; - #if CYTHON_UNPACK_METHODS - if (unlikely(PyMethod_Check(__pyx_t_6))) { - __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_6); - if (likely(__pyx_t_3)) { - PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_6); - __Pyx_INCREF(__pyx_t_3); - __Pyx_INCREF(function); - __Pyx_DECREF_SET(__pyx_t_6, function); - __pyx_t_11 = 1; - } - } - #endif - { - PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_t_10}; - __pyx_t_4 = __Pyx_PyObject_FastCall(__pyx_t_6, __pyx_callargs+1-__pyx_t_11, 1+__pyx_t_11); - __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; - __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; - if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 77, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; - } - if (!(likely(((__pyx_t_4) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_4, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 77, __pyx_L1_error) - __pyx_r = ((PyArrayObject *)__pyx_t_4); - __pyx_t_4 = 0; - goto __pyx_L0; - - /* "rednose/helpers/ekf_sym_pyx.pyx":75 - * @cython.wraparound(False) - * @cython.boundscheck(False) - * cdef np.ndarray[np.float64_t, ndim=2, mode="c"] matrix_to_numpy(MatrixXdr arr): # <<<<<<<<<<<<<< - * cdef double[:,:] mem_view = arr.data() - * return np.copy(np.asarray(mem_view, dtype=np.double, order="C")) - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF((PyObject *)__pyx_t_2); - __Pyx_XDECREF(__pyx_t_3); - __Pyx_XDECREF(__pyx_t_4); - __PYX_XCLEAR_MEMVIEW(&__pyx_t_5, 1); - __Pyx_XDECREF(__pyx_t_6); - __Pyx_XDECREF(__pyx_t_7); - __Pyx_XDECREF(__pyx_t_8); - __Pyx_XDECREF(__pyx_t_9); - __Pyx_XDECREF(__pyx_t_10); - __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.matrix_to_numpy", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = 0; - __pyx_L0:; - __PYX_XCLEAR_MEMVIEW(&__pyx_v_mem_view, 1); - __Pyx_XGIVEREF((PyObject *)__pyx_r); - __Pyx_TraceReturn(__pyx_r, 0); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "rednose/helpers/ekf_sym_pyx.pyx":81 - * @cython.wraparound(False) - * @cython.boundscheck(False) - * cdef np.ndarray[np.float64_t, ndim=1, mode="c"] vector_to_numpy(VectorXd arr): # <<<<<<<<<<<<<< - * cdef double[:] mem_view = arr.data() - * return np.copy(np.asarray(mem_view, dtype=np.double, order="C")) - */ - -static PyArrayObject *__pyx_f_7rednose_7helpers_11ekf_sym_pyx_vector_to_numpy(Eigen::VectorXd __pyx_v_arr) { - __Pyx_memviewslice __pyx_v_mem_view = { 0, 0, { 0 }, { 0 }, { 0 } }; - PyArrayObject *__pyx_r = NULL; - __Pyx_TraceDeclarations - __Pyx_RefNannyDeclarations - double *__pyx_t_1; - struct __pyx_array_obj *__pyx_t_2 = NULL; - PyObject *__pyx_t_3 = NULL; - PyObject *__pyx_t_4 = NULL; - __Pyx_memviewslice __pyx_t_5 = { 0, 0, { 0 }, { 0 }, { 0 } }; - PyObject *__pyx_t_6 = NULL; - PyObject *__pyx_t_7 = NULL; - PyObject *__pyx_t_8 = NULL; - PyObject *__pyx_t_9 = NULL; - PyObject *__pyx_t_10 = NULL; - int __pyx_t_11; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("vector_to_numpy", 1); - __Pyx_TraceCall("vector_to_numpy", __pyx_f[0], 81, 0, __PYX_ERR(0, 81, __pyx_L1_error)); - - /* "rednose/helpers/ekf_sym_pyx.pyx":82 - * @cython.boundscheck(False) - * cdef np.ndarray[np.float64_t, ndim=1, mode="c"] vector_to_numpy(VectorXd arr): - * cdef double[:] mem_view = arr.data() # <<<<<<<<<<<<<< - * return np.copy(np.asarray(mem_view, dtype=np.double, order="C")) - * - */ - __pyx_t_1 = __pyx_v_arr.data(); - if (!__pyx_t_1) { - PyErr_SetString(PyExc_ValueError,"Cannot create cython.array from NULL pointer"); - __PYX_ERR(0, 82, __pyx_L1_error) - } - __pyx_t_4 = __pyx_format_from_typeinfo(&__Pyx_TypeInfo_double); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 82, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __pyx_t_3 = Py_BuildValue((char*) "(" __PYX_BUILD_PY_SSIZE_T ")", ((Py_ssize_t)__pyx_v_arr.rows())); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 82, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __pyx_t_2 = __pyx_array_new(__pyx_t_3, sizeof(double), PyBytes_AS_STRING(__pyx_t_4), (char *) "c", (char *) __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 82, __pyx_L1_error) - __Pyx_GOTREF((PyObject *)__pyx_t_2); - __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __pyx_t_5 = __Pyx_PyObject_to_MemoryviewSlice_ds_double(((PyObject *)__pyx_t_2), PyBUF_WRITABLE); if (unlikely(!__pyx_t_5.memview)) __PYX_ERR(0, 82, __pyx_L1_error) - __Pyx_DECREF((PyObject *)__pyx_t_2); __pyx_t_2 = 0; - __pyx_v_mem_view = __pyx_t_5; - __pyx_t_5.memview = NULL; - __pyx_t_5.data = NULL; - - /* "rednose/helpers/ekf_sym_pyx.pyx":83 - * cdef np.ndarray[np.float64_t, ndim=1, mode="c"] vector_to_numpy(VectorXd arr): - * cdef double[:] mem_view = arr.data() - * return np.copy(np.asarray(mem_view, dtype=np.double, order="C")) # <<<<<<<<<<<<<< - * - * cdef class EKF_sym_pyx: - */ - __Pyx_XDECREF((PyObject *)__pyx_r); - __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_np); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 83, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_copy); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 83, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_6); - __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_np); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 83, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_asarray); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 83, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - __pyx_t_3 = __pyx_memoryview_fromslice(__pyx_v_mem_view, 1, (PyObject *(*)(char *)) __pyx_memview_get_double, (int (*)(char *, PyObject *)) __pyx_memview_set_double, 0);; if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 83, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __pyx_t_8 = PyTuple_New(1); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 83, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_8); - __Pyx_GIVEREF(__pyx_t_3); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_8, 0, __pyx_t_3)) __PYX_ERR(0, 83, __pyx_L1_error); - __pyx_t_3 = 0; - __pyx_t_3 = __Pyx_PyDict_NewPresized(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 83, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __Pyx_GetModuleGlobalName(__pyx_t_9, __pyx_n_s_np); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 83, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_9); - __pyx_t_10 = __Pyx_PyObject_GetAttrStr(__pyx_t_9, __pyx_n_s_double); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 83, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_10); - __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; - if (PyDict_SetItem(__pyx_t_3, __pyx_n_s_dtype, __pyx_t_10) < 0) __PYX_ERR(0, 83, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; - if (PyDict_SetItem(__pyx_t_3, __pyx_n_s_order, __pyx_n_u_C) < 0) __PYX_ERR(0, 83, __pyx_L1_error) - __pyx_t_10 = __Pyx_PyObject_Call(__pyx_t_7, __pyx_t_8, __pyx_t_3); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 83, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_10); - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; - __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - __pyx_t_3 = NULL; - __pyx_t_11 = 0; - #if CYTHON_UNPACK_METHODS - if (unlikely(PyMethod_Check(__pyx_t_6))) { - __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_6); - if (likely(__pyx_t_3)) { - PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_6); - __Pyx_INCREF(__pyx_t_3); - __Pyx_INCREF(function); - __Pyx_DECREF_SET(__pyx_t_6, function); - __pyx_t_11 = 1; - } - } - #endif - { - PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_t_10}; - __pyx_t_4 = __Pyx_PyObject_FastCall(__pyx_t_6, __pyx_callargs+1-__pyx_t_11, 1+__pyx_t_11); - __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; - __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; - if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 83, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; - } - if (!(likely(((__pyx_t_4) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_4, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 83, __pyx_L1_error) - __pyx_r = ((PyArrayObject *)__pyx_t_4); - __pyx_t_4 = 0; - goto __pyx_L0; - - /* "rednose/helpers/ekf_sym_pyx.pyx":81 - * @cython.wraparound(False) - * @cython.boundscheck(False) - * cdef np.ndarray[np.float64_t, ndim=1, mode="c"] vector_to_numpy(VectorXd arr): # <<<<<<<<<<<<<< - * cdef double[:] mem_view = arr.data() - * return np.copy(np.asarray(mem_view, dtype=np.double, order="C")) - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF((PyObject *)__pyx_t_2); - __Pyx_XDECREF(__pyx_t_3); - __Pyx_XDECREF(__pyx_t_4); - __PYX_XCLEAR_MEMVIEW(&__pyx_t_5, 1); - __Pyx_XDECREF(__pyx_t_6); - __Pyx_XDECREF(__pyx_t_7); - __Pyx_XDECREF(__pyx_t_8); - __Pyx_XDECREF(__pyx_t_9); - __Pyx_XDECREF(__pyx_t_10); - __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.vector_to_numpy", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = 0; - __pyx_L0:; - __PYX_XCLEAR_MEMVIEW(&__pyx_v_mem_view, 1); - __Pyx_XGIVEREF((PyObject *)__pyx_r); - __Pyx_TraceReturn(__pyx_r, 0); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "rednose/helpers/ekf_sym_pyx.pyx":87 - * cdef class EKF_sym_pyx: - * cdef EKFSym* ekf - * def __cinit__(self, str gen_dir, str name, np.ndarray[np.float64_t, ndim=2] Q, # <<<<<<<<<<<<<< - * np.ndarray[np.float64_t, ndim=1] x_initial, np.ndarray[np.float64_t, ndim=2] P_initial, int dim_main, - * int dim_main_err, int N=0, int dim_augment=0, int dim_augment_err=0, list maha_test_kinds=[], - */ - -/* Python wrapper */ -static int __pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ -static int __pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { - PyObject *__pyx_v_gen_dir = 0; - PyObject *__pyx_v_name = 0; - PyArrayObject *__pyx_v_Q = 0; - PyArrayObject *__pyx_v_x_initial = 0; - PyArrayObject *__pyx_v_P_initial = 0; - int __pyx_v_dim_main; - int __pyx_v_dim_main_err; - int __pyx_v_N; - int __pyx_v_dim_augment; - int __pyx_v_dim_augment_err; - PyObject *__pyx_v_maha_test_kinds = 0; - PyObject *__pyx_v_quaternion_idxs = 0; - PyObject *__pyx_v_global_vars = 0; - double __pyx_v_max_rewind_age; - CYTHON_UNUSED PyObject *__pyx_v_logger = 0; - CYTHON_UNUSED Py_ssize_t __pyx_nargs; - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - PyObject* values[15] = {0,0,0,0,0,0,0,0,0,0,0,0,0,0,0}; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - int __pyx_r; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); - #if CYTHON_ASSUME_SAFE_MACROS - __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); - #else - __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return -1; - #endif - __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); - { - PyObject **__pyx_pyargnames[] = {&__pyx_n_s_gen_dir,&__pyx_n_s_name,&__pyx_n_s_Q,&__pyx_n_s_x_initial,&__pyx_n_s_P_initial,&__pyx_n_s_dim_main,&__pyx_n_s_dim_main_err,&__pyx_n_s_N,&__pyx_n_s_dim_augment,&__pyx_n_s_dim_augment_err,&__pyx_n_s_maha_test_kinds,&__pyx_n_s_quaternion_idxs,&__pyx_n_s_global_vars,&__pyx_n_s_max_rewind_age,&__pyx_n_s_logger,0}; - values[10] = __Pyx_Arg_NewRef_VARARGS(__pyx_k__17); - values[11] = __Pyx_Arg_NewRef_VARARGS(__pyx_k__18); - values[12] = __Pyx_Arg_NewRef_VARARGS(__pyx_k__19); - - /* "rednose/helpers/ekf_sym_pyx.pyx":90 - * np.ndarray[np.float64_t, ndim=1] x_initial, np.ndarray[np.float64_t, ndim=2] P_initial, int dim_main, - * int dim_main_err, int N=0, int dim_augment=0, int dim_augment_err=0, list maha_test_kinds=[], - * list quaternion_idxs=[], list global_vars=[], double max_rewind_age=1.0, logger=None): # <<<<<<<<<<<<<< - * # TODO logger - * ekf_load_and_register(gen_dir.encode('utf8'), name.encode('utf8')) - */ - values[14] = __Pyx_Arg_NewRef_VARARGS(((PyObject *)Py_None)); - if (__pyx_kwds) { - Py_ssize_t kw_args; - switch (__pyx_nargs) { - case 15: values[14] = __Pyx_Arg_VARARGS(__pyx_args, 14); - CYTHON_FALLTHROUGH; - case 14: values[13] = __Pyx_Arg_VARARGS(__pyx_args, 13); - CYTHON_FALLTHROUGH; - case 13: values[12] = __Pyx_Arg_VARARGS(__pyx_args, 12); - CYTHON_FALLTHROUGH; - case 12: values[11] = __Pyx_Arg_VARARGS(__pyx_args, 11); - CYTHON_FALLTHROUGH; - case 11: values[10] = __Pyx_Arg_VARARGS(__pyx_args, 10); - CYTHON_FALLTHROUGH; - case 10: values[9] = __Pyx_Arg_VARARGS(__pyx_args, 9); - CYTHON_FALLTHROUGH; - case 9: values[8] = __Pyx_Arg_VARARGS(__pyx_args, 8); - CYTHON_FALLTHROUGH; - case 8: values[7] = __Pyx_Arg_VARARGS(__pyx_args, 7); - CYTHON_FALLTHROUGH; - case 7: values[6] = __Pyx_Arg_VARARGS(__pyx_args, 6); - CYTHON_FALLTHROUGH; - case 6: values[5] = __Pyx_Arg_VARARGS(__pyx_args, 5); - CYTHON_FALLTHROUGH; - case 5: values[4] = __Pyx_Arg_VARARGS(__pyx_args, 4); - CYTHON_FALLTHROUGH; - case 4: values[3] = __Pyx_Arg_VARARGS(__pyx_args, 3); - CYTHON_FALLTHROUGH; - case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); - CYTHON_FALLTHROUGH; - case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); - CYTHON_FALLTHROUGH; - case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); - CYTHON_FALLTHROUGH; - case 0: break; - default: goto __pyx_L5_argtuple_error; - } - kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); - switch (__pyx_nargs) { - case 0: - if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_gen_dir)) != 0)) { - (void)__Pyx_Arg_NewRef_VARARGS(values[0]); - kw_args--; - } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 87, __pyx_L3_error) - else goto __pyx_L5_argtuple_error; - CYTHON_FALLTHROUGH; - case 1: - if (likely((values[1] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_name)) != 0)) { - (void)__Pyx_Arg_NewRef_VARARGS(values[1]); - kw_args--; - } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 87, __pyx_L3_error) - else { - __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 7, 15, 1); __PYX_ERR(0, 87, __pyx_L3_error) - } - CYTHON_FALLTHROUGH; - case 2: - if (likely((values[2] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_Q)) != 0)) { - (void)__Pyx_Arg_NewRef_VARARGS(values[2]); - kw_args--; - } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 87, __pyx_L3_error) - else { - __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 7, 15, 2); __PYX_ERR(0, 87, __pyx_L3_error) - } - CYTHON_FALLTHROUGH; - case 3: - if (likely((values[3] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_x_initial)) != 0)) { - (void)__Pyx_Arg_NewRef_VARARGS(values[3]); - kw_args--; - } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 87, __pyx_L3_error) - else { - __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 7, 15, 3); __PYX_ERR(0, 87, __pyx_L3_error) - } - CYTHON_FALLTHROUGH; - case 4: - if (likely((values[4] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_P_initial)) != 0)) { - (void)__Pyx_Arg_NewRef_VARARGS(values[4]); - kw_args--; - } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 87, __pyx_L3_error) - else { - __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 7, 15, 4); __PYX_ERR(0, 87, __pyx_L3_error) - } - CYTHON_FALLTHROUGH; - case 5: - if (likely((values[5] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_dim_main)) != 0)) { - (void)__Pyx_Arg_NewRef_VARARGS(values[5]); - kw_args--; - } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 87, __pyx_L3_error) - else { - __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 7, 15, 5); __PYX_ERR(0, 87, __pyx_L3_error) - } - CYTHON_FALLTHROUGH; - case 6: - if (likely((values[6] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_dim_main_err)) != 0)) { - (void)__Pyx_Arg_NewRef_VARARGS(values[6]); - kw_args--; - } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 87, __pyx_L3_error) - else { - __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 7, 15, 6); __PYX_ERR(0, 87, __pyx_L3_error) - } - CYTHON_FALLTHROUGH; - case 7: - if (kw_args > 0) { - PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_N); - if (value) { values[7] = __Pyx_Arg_NewRef_VARARGS(value); kw_args--; } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 87, __pyx_L3_error) - } - CYTHON_FALLTHROUGH; - case 8: - if (kw_args > 0) { - PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_dim_augment); - if (value) { values[8] = __Pyx_Arg_NewRef_VARARGS(value); kw_args--; } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 87, __pyx_L3_error) - } - CYTHON_FALLTHROUGH; - case 9: - if (kw_args > 0) { - PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_dim_augment_err); - if (value) { values[9] = __Pyx_Arg_NewRef_VARARGS(value); kw_args--; } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 87, __pyx_L3_error) - } - CYTHON_FALLTHROUGH; - case 10: - if (kw_args > 0) { - PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_maha_test_kinds); - if (value) { values[10] = __Pyx_Arg_NewRef_VARARGS(value); kw_args--; } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 87, __pyx_L3_error) - } - CYTHON_FALLTHROUGH; - case 11: - if (kw_args > 0) { - PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_quaternion_idxs); - if (value) { values[11] = __Pyx_Arg_NewRef_VARARGS(value); kw_args--; } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 87, __pyx_L3_error) - } - CYTHON_FALLTHROUGH; - case 12: - if (kw_args > 0) { - PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_global_vars); - if (value) { values[12] = __Pyx_Arg_NewRef_VARARGS(value); kw_args--; } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 87, __pyx_L3_error) - } - CYTHON_FALLTHROUGH; - case 13: - if (kw_args > 0) { - PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_max_rewind_age); - if (value) { values[13] = __Pyx_Arg_NewRef_VARARGS(value); kw_args--; } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 87, __pyx_L3_error) - } - CYTHON_FALLTHROUGH; - case 14: - if (kw_args > 0) { - PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_logger); - if (value) { values[14] = __Pyx_Arg_NewRef_VARARGS(value); kw_args--; } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 87, __pyx_L3_error) - } - } - if (unlikely(kw_args > 0)) { - const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__cinit__") < 0)) __PYX_ERR(0, 87, __pyx_L3_error) - } - } else { - switch (__pyx_nargs) { - case 15: values[14] = __Pyx_Arg_VARARGS(__pyx_args, 14); - CYTHON_FALLTHROUGH; - case 14: values[13] = __Pyx_Arg_VARARGS(__pyx_args, 13); - CYTHON_FALLTHROUGH; - case 13: values[12] = __Pyx_Arg_VARARGS(__pyx_args, 12); - CYTHON_FALLTHROUGH; - case 12: values[11] = __Pyx_Arg_VARARGS(__pyx_args, 11); - CYTHON_FALLTHROUGH; - case 11: values[10] = __Pyx_Arg_VARARGS(__pyx_args, 10); - CYTHON_FALLTHROUGH; - case 10: values[9] = __Pyx_Arg_VARARGS(__pyx_args, 9); - CYTHON_FALLTHROUGH; - case 9: values[8] = __Pyx_Arg_VARARGS(__pyx_args, 8); - CYTHON_FALLTHROUGH; - case 8: values[7] = __Pyx_Arg_VARARGS(__pyx_args, 7); - CYTHON_FALLTHROUGH; - case 7: values[6] = __Pyx_Arg_VARARGS(__pyx_args, 6); - values[5] = __Pyx_Arg_VARARGS(__pyx_args, 5); - values[4] = __Pyx_Arg_VARARGS(__pyx_args, 4); - values[3] = __Pyx_Arg_VARARGS(__pyx_args, 3); - values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); - values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); - values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); - break; - default: goto __pyx_L5_argtuple_error; - } - } - __pyx_v_gen_dir = ((PyObject*)values[0]); - __pyx_v_name = ((PyObject*)values[1]); - __pyx_v_Q = ((PyArrayObject *)values[2]); - __pyx_v_x_initial = ((PyArrayObject *)values[3]); - __pyx_v_P_initial = ((PyArrayObject *)values[4]); - __pyx_v_dim_main = __Pyx_PyInt_As_int(values[5]); if (unlikely((__pyx_v_dim_main == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 88, __pyx_L3_error) - __pyx_v_dim_main_err = __Pyx_PyInt_As_int(values[6]); if (unlikely((__pyx_v_dim_main_err == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 89, __pyx_L3_error) - if (values[7]) { - __pyx_v_N = __Pyx_PyInt_As_int(values[7]); if (unlikely((__pyx_v_N == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 89, __pyx_L3_error) - } else { - __pyx_v_N = ((int)0); - } - if (values[8]) { - __pyx_v_dim_augment = __Pyx_PyInt_As_int(values[8]); if (unlikely((__pyx_v_dim_augment == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 89, __pyx_L3_error) - } else { - __pyx_v_dim_augment = ((int)0); - } - if (values[9]) { - __pyx_v_dim_augment_err = __Pyx_PyInt_As_int(values[9]); if (unlikely((__pyx_v_dim_augment_err == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 89, __pyx_L3_error) - } else { - __pyx_v_dim_augment_err = ((int)0); - } - __pyx_v_maha_test_kinds = ((PyObject*)values[10]); - __pyx_v_quaternion_idxs = ((PyObject*)values[11]); - __pyx_v_global_vars = ((PyObject*)values[12]); - if (values[13]) { - __pyx_v_max_rewind_age = __pyx_PyFloat_AsDouble(values[13]); if (unlikely((__pyx_v_max_rewind_age == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 90, __pyx_L3_error) - } else { - __pyx_v_max_rewind_age = ((double)1.0); - } - __pyx_v_logger = values[14]; - } - goto __pyx_L6_skip; - __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 7, 15, __pyx_nargs); __PYX_ERR(0, 87, __pyx_L3_error) - __pyx_L6_skip:; - goto __pyx_L4_argument_unpacking_done; - __pyx_L3_error:; - { - Py_ssize_t __pyx_temp; - for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { - __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); - } - } - __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); - __Pyx_RefNannyFinishContext(); - return -1; - __pyx_L4_argument_unpacking_done:; - if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_gen_dir), (&PyUnicode_Type), 1, "gen_dir", 1))) __PYX_ERR(0, 87, __pyx_L1_error) - if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_name), (&PyUnicode_Type), 1, "name", 1))) __PYX_ERR(0, 87, __pyx_L1_error) - if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_Q), __pyx_ptype_5numpy_ndarray, 1, "Q", 0))) __PYX_ERR(0, 87, __pyx_L1_error) - if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_x_initial), __pyx_ptype_5numpy_ndarray, 1, "x_initial", 0))) __PYX_ERR(0, 88, __pyx_L1_error) - if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_P_initial), __pyx_ptype_5numpy_ndarray, 1, "P_initial", 0))) __PYX_ERR(0, 88, __pyx_L1_error) - if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_maha_test_kinds), (&PyList_Type), 1, "maha_test_kinds", 1))) __PYX_ERR(0, 89, __pyx_L1_error) - if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_quaternion_idxs), (&PyList_Type), 1, "quaternion_idxs", 1))) __PYX_ERR(0, 90, __pyx_L1_error) - if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_global_vars), (&PyList_Type), 1, "global_vars", 1))) __PYX_ERR(0, 90, __pyx_L1_error) - __pyx_r = __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx___cinit__(((struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *)__pyx_v_self), __pyx_v_gen_dir, __pyx_v_name, __pyx_v_Q, __pyx_v_x_initial, __pyx_v_P_initial, __pyx_v_dim_main, __pyx_v_dim_main_err, __pyx_v_N, __pyx_v_dim_augment, __pyx_v_dim_augment_err, __pyx_v_maha_test_kinds, __pyx_v_quaternion_idxs, __pyx_v_global_vars, __pyx_v_max_rewind_age, __pyx_v_logger); - - /* "rednose/helpers/ekf_sym_pyx.pyx":87 - * cdef class EKF_sym_pyx: - * cdef EKFSym* ekf - * def __cinit__(self, str gen_dir, str name, np.ndarray[np.float64_t, ndim=2] Q, # <<<<<<<<<<<<<< - * np.ndarray[np.float64_t, ndim=1] x_initial, np.ndarray[np.float64_t, ndim=2] P_initial, int dim_main, - * int dim_main_err, int N=0, int dim_augment=0, int dim_augment_err=0, list maha_test_kinds=[], - */ - - /* function exit code */ - goto __pyx_L0; - __pyx_L1_error:; - __pyx_r = -1; - __pyx_L0:; - { - Py_ssize_t __pyx_temp; - for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { - __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); - } - } - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static int __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx___cinit__(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, PyObject *__pyx_v_gen_dir, PyObject *__pyx_v_name, PyArrayObject *__pyx_v_Q, PyArrayObject *__pyx_v_x_initial, PyArrayObject *__pyx_v_P_initial, int __pyx_v_dim_main, int __pyx_v_dim_main_err, int __pyx_v_N, int __pyx_v_dim_augment, int __pyx_v_dim_augment_err, PyObject *__pyx_v_maha_test_kinds, PyObject *__pyx_v_quaternion_idxs, PyObject *__pyx_v_global_vars, double __pyx_v_max_rewind_age, CYTHON_UNUSED PyObject *__pyx_v_logger) { - PyArrayObject *__pyx_v_Q_b = 0; - PyArrayObject *__pyx_v_x_initial_b = 0; - PyArrayObject *__pyx_v_P_initial_b = 0; - PyObject *__pyx_7genexpr__pyx_v_x = NULL; - __Pyx_LocalBuf_ND __pyx_pybuffernd_P_initial; - __Pyx_Buffer __pyx_pybuffer_P_initial; - __Pyx_LocalBuf_ND __pyx_pybuffernd_P_initial_b; - __Pyx_Buffer __pyx_pybuffer_P_initial_b; - __Pyx_LocalBuf_ND __pyx_pybuffernd_Q; - __Pyx_Buffer __pyx_pybuffer_Q; - __Pyx_LocalBuf_ND __pyx_pybuffernd_Q_b; - __Pyx_Buffer __pyx_pybuffer_Q_b; - __Pyx_LocalBuf_ND __pyx_pybuffernd_x_initial; - __Pyx_Buffer __pyx_pybuffer_x_initial; - __Pyx_LocalBuf_ND __pyx_pybuffernd_x_initial_b; - __Pyx_Buffer __pyx_pybuffer_x_initial_b; - int __pyx_r; - __Pyx_TraceDeclarations - __Pyx_RefNannyDeclarations - PyObject *__pyx_t_1 = NULL; - std::string __pyx_t_2; - std::string __pyx_t_3; - PyObject *__pyx_t_4 = NULL; - PyObject *__pyx_t_5 = NULL; - PyObject *__pyx_t_6 = NULL; - PyObject *__pyx_t_7 = NULL; - PyArrayObject *__pyx_t_8 = NULL; - PyArrayObject *__pyx_t_9 = NULL; - PyArrayObject *__pyx_t_10 = NULL; - char *__pyx_t_11; - npy_intp *__pyx_t_12; - npy_intp *__pyx_t_13; - char *__pyx_t_14; - npy_intp *__pyx_t_15; - char *__pyx_t_16; - npy_intp *__pyx_t_17; - npy_intp *__pyx_t_18; - std::vector __pyx_t_19; - std::vector __pyx_t_20; - Py_ssize_t __pyx_t_21; - int __pyx_t_22; - std::vector __pyx_t_23; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("__cinit__", 1); - __Pyx_TraceCall("__cinit__", __pyx_f[0], 87, 0, __PYX_ERR(0, 87, __pyx_L1_error)); - __pyx_pybuffer_Q_b.pybuffer.buf = NULL; - __pyx_pybuffer_Q_b.refcount = 0; - __pyx_pybuffernd_Q_b.data = NULL; - __pyx_pybuffernd_Q_b.rcbuffer = &__pyx_pybuffer_Q_b; - __pyx_pybuffer_x_initial_b.pybuffer.buf = NULL; - __pyx_pybuffer_x_initial_b.refcount = 0; - __pyx_pybuffernd_x_initial_b.data = NULL; - __pyx_pybuffernd_x_initial_b.rcbuffer = &__pyx_pybuffer_x_initial_b; - __pyx_pybuffer_P_initial_b.pybuffer.buf = NULL; - __pyx_pybuffer_P_initial_b.refcount = 0; - __pyx_pybuffernd_P_initial_b.data = NULL; - __pyx_pybuffernd_P_initial_b.rcbuffer = &__pyx_pybuffer_P_initial_b; - __pyx_pybuffer_Q.pybuffer.buf = NULL; - __pyx_pybuffer_Q.refcount = 0; - __pyx_pybuffernd_Q.data = NULL; - __pyx_pybuffernd_Q.rcbuffer = &__pyx_pybuffer_Q; - __pyx_pybuffer_x_initial.pybuffer.buf = NULL; - __pyx_pybuffer_x_initial.refcount = 0; - __pyx_pybuffernd_x_initial.data = NULL; - __pyx_pybuffernd_x_initial.rcbuffer = &__pyx_pybuffer_x_initial; - __pyx_pybuffer_P_initial.pybuffer.buf = NULL; - __pyx_pybuffer_P_initial.refcount = 0; - __pyx_pybuffernd_P_initial.data = NULL; - __pyx_pybuffernd_P_initial.rcbuffer = &__pyx_pybuffer_P_initial; - { - __Pyx_BufFmt_StackElem __pyx_stack[1]; - if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_Q.rcbuffer->pybuffer, (PyObject*)__pyx_v_Q, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 2, 0, __pyx_stack) == -1)) __PYX_ERR(0, 87, __pyx_L1_error) - } - __pyx_pybuffernd_Q.diminfo[0].strides = __pyx_pybuffernd_Q.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_Q.diminfo[0].shape = __pyx_pybuffernd_Q.rcbuffer->pybuffer.shape[0]; __pyx_pybuffernd_Q.diminfo[1].strides = __pyx_pybuffernd_Q.rcbuffer->pybuffer.strides[1]; __pyx_pybuffernd_Q.diminfo[1].shape = __pyx_pybuffernd_Q.rcbuffer->pybuffer.shape[1]; - { - __Pyx_BufFmt_StackElem __pyx_stack[1]; - if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_x_initial.rcbuffer->pybuffer, (PyObject*)__pyx_v_x_initial, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 1, 0, __pyx_stack) == -1)) __PYX_ERR(0, 87, __pyx_L1_error) - } - __pyx_pybuffernd_x_initial.diminfo[0].strides = __pyx_pybuffernd_x_initial.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_x_initial.diminfo[0].shape = __pyx_pybuffernd_x_initial.rcbuffer->pybuffer.shape[0]; - { - __Pyx_BufFmt_StackElem __pyx_stack[1]; - if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_P_initial.rcbuffer->pybuffer, (PyObject*)__pyx_v_P_initial, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 2, 0, __pyx_stack) == -1)) __PYX_ERR(0, 87, __pyx_L1_error) - } - __pyx_pybuffernd_P_initial.diminfo[0].strides = __pyx_pybuffernd_P_initial.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_P_initial.diminfo[0].shape = __pyx_pybuffernd_P_initial.rcbuffer->pybuffer.shape[0]; __pyx_pybuffernd_P_initial.diminfo[1].strides = __pyx_pybuffernd_P_initial.rcbuffer->pybuffer.strides[1]; __pyx_pybuffernd_P_initial.diminfo[1].shape = __pyx_pybuffernd_P_initial.rcbuffer->pybuffer.shape[1]; - - /* "rednose/helpers/ekf_sym_pyx.pyx":92 - * list quaternion_idxs=[], list global_vars=[], double max_rewind_age=1.0, logger=None): - * # TODO logger - * ekf_load_and_register(gen_dir.encode('utf8'), name.encode('utf8')) # <<<<<<<<<<<<<< - * - * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] Q_b = np.ascontiguousarray(Q, dtype=np.double) - */ - if (unlikely(__pyx_v_gen_dir == Py_None)) { - PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "encode"); - __PYX_ERR(0, 92, __pyx_L1_error) - } - __pyx_t_1 = PyUnicode_AsUTF8String(__pyx_v_gen_dir); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 92, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_2 = __pyx_convert_string_from_py_std__in_string(__pyx_t_1); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 92, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - if (unlikely(__pyx_v_name == Py_None)) { - PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "encode"); - __PYX_ERR(0, 92, __pyx_L1_error) - } - __pyx_t_1 = PyUnicode_AsUTF8String(__pyx_v_name); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 92, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_3 = __pyx_convert_string_from_py_std__in_string(__pyx_t_1); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 92, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - ekf_load_and_register(__PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_2), __PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_3)); - - /* "rednose/helpers/ekf_sym_pyx.pyx":94 - * ekf_load_and_register(gen_dir.encode('utf8'), name.encode('utf8')) - * - * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] Q_b = np.ascontiguousarray(Q, dtype=np.double) # <<<<<<<<<<<<<< - * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] x_initial_b = np.ascontiguousarray(x_initial, dtype=np.double) - * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] P_initial_b = np.ascontiguousarray(P_initial, dtype=np.double) - */ - __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 94, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 94, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_t_1 = PyTuple_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 94, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __Pyx_INCREF((PyObject *)__pyx_v_Q); - __Pyx_GIVEREF((PyObject *)__pyx_v_Q); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, ((PyObject *)__pyx_v_Q))) __PYX_ERR(0, 94, __pyx_L1_error); - __pyx_t_5 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 94, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __Pyx_GetModuleGlobalName(__pyx_t_6, __pyx_n_s_np); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 94, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_6); - __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_t_6, __pyx_n_s_double); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 94, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; - if (PyDict_SetItem(__pyx_t_5, __pyx_n_s_dtype, __pyx_t_7) < 0) __PYX_ERR(0, 94, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - __pyx_t_7 = __Pyx_PyObject_Call(__pyx_t_4, __pyx_t_1, __pyx_t_5); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 94, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - if (!(likely(((__pyx_t_7) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_7, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 94, __pyx_L1_error) - __pyx_t_8 = ((PyArrayObject *)__pyx_t_7); - { - __Pyx_BufFmt_StackElem __pyx_stack[1]; - if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_Q_b.rcbuffer->pybuffer, (PyObject*)__pyx_t_8, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_C_CONTIGUOUS, 2, 0, __pyx_stack) == -1)) { - __pyx_v_Q_b = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_Q_b.rcbuffer->pybuffer.buf = NULL; - __PYX_ERR(0, 94, __pyx_L1_error) - } else {__pyx_pybuffernd_Q_b.diminfo[0].strides = __pyx_pybuffernd_Q_b.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_Q_b.diminfo[0].shape = __pyx_pybuffernd_Q_b.rcbuffer->pybuffer.shape[0]; __pyx_pybuffernd_Q_b.diminfo[1].strides = __pyx_pybuffernd_Q_b.rcbuffer->pybuffer.strides[1]; __pyx_pybuffernd_Q_b.diminfo[1].shape = __pyx_pybuffernd_Q_b.rcbuffer->pybuffer.shape[1]; - } - } - __pyx_t_8 = 0; - __pyx_v_Q_b = ((PyArrayObject *)__pyx_t_7); - __pyx_t_7 = 0; - - /* "rednose/helpers/ekf_sym_pyx.pyx":95 - * - * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] Q_b = np.ascontiguousarray(Q, dtype=np.double) - * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] x_initial_b = np.ascontiguousarray(x_initial, dtype=np.double) # <<<<<<<<<<<<<< - * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] P_initial_b = np.ascontiguousarray(P_initial, dtype=np.double) - * self.ekf = new EKFSym( - */ - __Pyx_GetModuleGlobalName(__pyx_t_7, __pyx_n_s_np); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 95, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_7, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 95, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - __pyx_t_7 = PyTuple_New(1); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 95, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __Pyx_INCREF((PyObject *)__pyx_v_x_initial); - __Pyx_GIVEREF((PyObject *)__pyx_v_x_initial); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_7, 0, ((PyObject *)__pyx_v_x_initial))) __PYX_ERR(0, 95, __pyx_L1_error); - __pyx_t_1 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 95, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_np); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 95, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_double); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 95, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_6); - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - if (PyDict_SetItem(__pyx_t_1, __pyx_n_s_dtype, __pyx_t_6) < 0) __PYX_ERR(0, 95, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; - __pyx_t_6 = __Pyx_PyObject_Call(__pyx_t_5, __pyx_t_7, __pyx_t_1); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 95, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_6); - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - if (!(likely(((__pyx_t_6) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_6, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 95, __pyx_L1_error) - __pyx_t_9 = ((PyArrayObject *)__pyx_t_6); - { - __Pyx_BufFmt_StackElem __pyx_stack[1]; - if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_x_initial_b.rcbuffer->pybuffer, (PyObject*)__pyx_t_9, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_C_CONTIGUOUS, 1, 0, __pyx_stack) == -1)) { - __pyx_v_x_initial_b = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_x_initial_b.rcbuffer->pybuffer.buf = NULL; - __PYX_ERR(0, 95, __pyx_L1_error) - } else {__pyx_pybuffernd_x_initial_b.diminfo[0].strides = __pyx_pybuffernd_x_initial_b.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_x_initial_b.diminfo[0].shape = __pyx_pybuffernd_x_initial_b.rcbuffer->pybuffer.shape[0]; - } - } - __pyx_t_9 = 0; - __pyx_v_x_initial_b = ((PyArrayObject *)__pyx_t_6); - __pyx_t_6 = 0; - - /* "rednose/helpers/ekf_sym_pyx.pyx":96 - * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] Q_b = np.ascontiguousarray(Q, dtype=np.double) - * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] x_initial_b = np.ascontiguousarray(x_initial, dtype=np.double) - * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] P_initial_b = np.ascontiguousarray(P_initial, dtype=np.double) # <<<<<<<<<<<<<< - * self.ekf = new EKFSym( - * name.encode('utf8'), - */ - __Pyx_GetModuleGlobalName(__pyx_t_6, __pyx_n_s_np); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 96, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_6); - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_6, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 96, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; - __pyx_t_6 = PyTuple_New(1); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 96, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_6); - __Pyx_INCREF((PyObject *)__pyx_v_P_initial); - __Pyx_GIVEREF((PyObject *)__pyx_v_P_initial); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_6, 0, ((PyObject *)__pyx_v_P_initial))) __PYX_ERR(0, 96, __pyx_L1_error); - __pyx_t_7 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 96, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __Pyx_GetModuleGlobalName(__pyx_t_5, __pyx_n_s_np); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 96, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_double); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 96, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - if (PyDict_SetItem(__pyx_t_7, __pyx_n_s_dtype, __pyx_t_4) < 0) __PYX_ERR(0, 96, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __pyx_t_4 = __Pyx_PyObject_Call(__pyx_t_1, __pyx_t_6, __pyx_t_7); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 96, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - if (!(likely(((__pyx_t_4) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_4, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 96, __pyx_L1_error) - __pyx_t_10 = ((PyArrayObject *)__pyx_t_4); - { - __Pyx_BufFmt_StackElem __pyx_stack[1]; - if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_P_initial_b.rcbuffer->pybuffer, (PyObject*)__pyx_t_10, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_C_CONTIGUOUS, 2, 0, __pyx_stack) == -1)) { - __pyx_v_P_initial_b = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_P_initial_b.rcbuffer->pybuffer.buf = NULL; - __PYX_ERR(0, 96, __pyx_L1_error) - } else {__pyx_pybuffernd_P_initial_b.diminfo[0].strides = __pyx_pybuffernd_P_initial_b.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_P_initial_b.diminfo[0].shape = __pyx_pybuffernd_P_initial_b.rcbuffer->pybuffer.shape[0]; __pyx_pybuffernd_P_initial_b.diminfo[1].strides = __pyx_pybuffernd_P_initial_b.rcbuffer->pybuffer.strides[1]; __pyx_pybuffernd_P_initial_b.diminfo[1].shape = __pyx_pybuffernd_P_initial_b.rcbuffer->pybuffer.shape[1]; - } - } - __pyx_t_10 = 0; - __pyx_v_P_initial_b = ((PyArrayObject *)__pyx_t_4); - __pyx_t_4 = 0; - - /* "rednose/helpers/ekf_sym_pyx.pyx":98 - * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] P_initial_b = np.ascontiguousarray(P_initial, dtype=np.double) - * self.ekf = new EKFSym( - * name.encode('utf8'), # <<<<<<<<<<<<<< - * MapMatrixXdr( Q_b.data, Q.shape[0], Q.shape[1]), - * MapVectorXd( x_initial_b.data, x_initial.shape[0]), - */ - if (unlikely(__pyx_v_name == Py_None)) { - PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "encode"); - __PYX_ERR(0, 98, __pyx_L1_error) - } - __pyx_t_4 = PyUnicode_AsUTF8String(__pyx_v_name); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 98, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __pyx_t_3 = __pyx_convert_string_from_py_std__in_string(__pyx_t_4); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 98, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - - /* "rednose/helpers/ekf_sym_pyx.pyx":99 - * self.ekf = new EKFSym( - * name.encode('utf8'), - * MapMatrixXdr( Q_b.data, Q.shape[0], Q.shape[1]), # <<<<<<<<<<<<<< - * MapVectorXd( x_initial_b.data, x_initial.shape[0]), - * MapMatrixXdr( P_initial_b.data, P_initial.shape[0], P_initial.shape[1]), - */ - __pyx_t_11 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_Q_b)); if (unlikely(__pyx_t_11 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 99, __pyx_L1_error) - __pyx_t_12 = __pyx_f_5numpy_7ndarray_5shape_shape(((PyArrayObject *)__pyx_v_Q)); if (unlikely(__pyx_t_12 == ((npy_intp *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 99, __pyx_L1_error) - __pyx_t_13 = __pyx_f_5numpy_7ndarray_5shape_shape(((PyArrayObject *)__pyx_v_Q)); if (unlikely(__pyx_t_13 == ((npy_intp *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 99, __pyx_L1_error) - - /* "rednose/helpers/ekf_sym_pyx.pyx":100 - * name.encode('utf8'), - * MapMatrixXdr( Q_b.data, Q.shape[0], Q.shape[1]), - * MapVectorXd( x_initial_b.data, x_initial.shape[0]), # <<<<<<<<<<<<<< - * MapMatrixXdr( P_initial_b.data, P_initial.shape[0], P_initial.shape[1]), - * dim_main, - */ - __pyx_t_14 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_x_initial_b)); if (unlikely(__pyx_t_14 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 100, __pyx_L1_error) - __pyx_t_15 = __pyx_f_5numpy_7ndarray_5shape_shape(((PyArrayObject *)__pyx_v_x_initial)); if (unlikely(__pyx_t_15 == ((npy_intp *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 100, __pyx_L1_error) - - /* "rednose/helpers/ekf_sym_pyx.pyx":101 - * MapMatrixXdr( Q_b.data, Q.shape[0], Q.shape[1]), - * MapVectorXd( x_initial_b.data, x_initial.shape[0]), - * MapMatrixXdr( P_initial_b.data, P_initial.shape[0], P_initial.shape[1]), # <<<<<<<<<<<<<< - * dim_main, - * dim_main_err, - */ - __pyx_t_16 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_P_initial_b)); if (unlikely(__pyx_t_16 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 101, __pyx_L1_error) - __pyx_t_17 = __pyx_f_5numpy_7ndarray_5shape_shape(((PyArrayObject *)__pyx_v_P_initial)); if (unlikely(__pyx_t_17 == ((npy_intp *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 101, __pyx_L1_error) - __pyx_t_18 = __pyx_f_5numpy_7ndarray_5shape_shape(((PyArrayObject *)__pyx_v_P_initial)); if (unlikely(__pyx_t_18 == ((npy_intp *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 101, __pyx_L1_error) - - /* "rednose/helpers/ekf_sym_pyx.pyx":107 - * dim_augment, - * dim_augment_err, - * maha_test_kinds, # <<<<<<<<<<<<<< - * quaternion_idxs, - * [x.encode('utf8') for x in global_vars], - */ - __pyx_t_19 = __pyx_convert_vector_from_py_int(__pyx_v_maha_test_kinds); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 107, __pyx_L1_error) - - /* "rednose/helpers/ekf_sym_pyx.pyx":108 - * dim_augment_err, - * maha_test_kinds, - * quaternion_idxs, # <<<<<<<<<<<<<< - * [x.encode('utf8') for x in global_vars], - * max_rewind_age - */ - __pyx_t_20 = __pyx_convert_vector_from_py_int(__pyx_v_quaternion_idxs); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 108, __pyx_L1_error) - { /* enter inner scope */ - - /* "rednose/helpers/ekf_sym_pyx.pyx":109 - * maha_test_kinds, - * quaternion_idxs, - * [x.encode('utf8') for x in global_vars], # <<<<<<<<<<<<<< - * max_rewind_age - * ) - */ - __pyx_t_4 = PyList_New(0); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 109, __pyx_L5_error) - __Pyx_GOTREF(__pyx_t_4); - if (unlikely(__pyx_v_global_vars == Py_None)) { - PyErr_SetString(PyExc_TypeError, "'NoneType' object is not iterable"); - __PYX_ERR(0, 109, __pyx_L5_error) - } - __pyx_t_7 = __pyx_v_global_vars; __Pyx_INCREF(__pyx_t_7); - __pyx_t_21 = 0; - for (;;) { - { - Py_ssize_t __pyx_temp = __Pyx_PyList_GET_SIZE(__pyx_t_7); - #if !CYTHON_ASSUME_SAFE_MACROS - if (unlikely((__pyx_temp < 0))) __PYX_ERR(0, 109, __pyx_L5_error) - #endif - if (__pyx_t_21 >= __pyx_temp) break; - } - #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS - __pyx_t_6 = PyList_GET_ITEM(__pyx_t_7, __pyx_t_21); __Pyx_INCREF(__pyx_t_6); __pyx_t_21++; if (unlikely((0 < 0))) __PYX_ERR(0, 109, __pyx_L5_error) - #else - __pyx_t_6 = __Pyx_PySequence_ITEM(__pyx_t_7, __pyx_t_21); __pyx_t_21++; if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 109, __pyx_L5_error) - __Pyx_GOTREF(__pyx_t_6); - #endif - __Pyx_XDECREF_SET(__pyx_7genexpr__pyx_v_x, __pyx_t_6); - __pyx_t_6 = 0; - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_7genexpr__pyx_v_x, __pyx_n_s_encode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 109, __pyx_L5_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_5 = NULL; - __pyx_t_22 = 0; - #if CYTHON_UNPACK_METHODS - if (likely(PyMethod_Check(__pyx_t_1))) { - __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); - if (likely(__pyx_t_5)) { - PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); - __Pyx_INCREF(__pyx_t_5); - __Pyx_INCREF(function); - __Pyx_DECREF_SET(__pyx_t_1, function); - __pyx_t_22 = 1; - } - } - #endif - { - PyObject *__pyx_callargs[2] = {__pyx_t_5, __pyx_n_u_utf8}; - __pyx_t_6 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_22, 1+__pyx_t_22); - __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; - if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 109, __pyx_L5_error) - __Pyx_GOTREF(__pyx_t_6); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - } - if (unlikely(__Pyx_ListComp_Append(__pyx_t_4, (PyObject*)__pyx_t_6))) __PYX_ERR(0, 109, __pyx_L5_error) - __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; - } - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - __Pyx_XDECREF(__pyx_7genexpr__pyx_v_x); __pyx_7genexpr__pyx_v_x = 0; - goto __pyx_L9_exit_scope; - __pyx_L5_error:; - __Pyx_XDECREF(__pyx_7genexpr__pyx_v_x); __pyx_7genexpr__pyx_v_x = 0; - goto __pyx_L1_error; - __pyx_L9_exit_scope:; - } /* exit inner scope */ - __pyx_t_23 = __pyx_convert_vector_from_py_std_3a__3a_string(__pyx_t_4); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 109, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - - /* "rednose/helpers/ekf_sym_pyx.pyx":97 - * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] x_initial_b = np.ascontiguousarray(x_initial, dtype=np.double) - * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] P_initial_b = np.ascontiguousarray(P_initial, dtype=np.double) - * self.ekf = new EKFSym( # <<<<<<<<<<<<<< - * name.encode('utf8'), - * MapMatrixXdr( Q_b.data, Q.shape[0], Q.shape[1]), - */ - __pyx_v_self->ekf = new EKFS::EKFSym(__pyx_t_3, Eigen::Map >(((double *)__pyx_t_11), (__pyx_t_12[0]), (__pyx_t_13[1])), Eigen::Map(((double *)__pyx_t_14), (__pyx_t_15[0])), Eigen::Map >(((double *)__pyx_t_16), (__pyx_t_17[0]), (__pyx_t_18[1])), __pyx_v_dim_main, __pyx_v_dim_main_err, __pyx_v_N, __pyx_v_dim_augment, __pyx_v_dim_augment_err, __pyx_t_19, __pyx_t_20, __pyx_t_23, __pyx_v_max_rewind_age); - - /* "rednose/helpers/ekf_sym_pyx.pyx":87 - * cdef class EKF_sym_pyx: - * cdef EKFSym* ekf - * def __cinit__(self, str gen_dir, str name, np.ndarray[np.float64_t, ndim=2] Q, # <<<<<<<<<<<<<< - * np.ndarray[np.float64_t, ndim=1] x_initial, np.ndarray[np.float64_t, ndim=2] P_initial, int dim_main, - * int dim_main_err, int N=0, int dim_augment=0, int dim_augment_err=0, list maha_test_kinds=[], - */ - - /* function exit code */ - __pyx_r = 0; - goto __pyx_L0; - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_1); - __Pyx_XDECREF(__pyx_t_4); - __Pyx_XDECREF(__pyx_t_5); - __Pyx_XDECREF(__pyx_t_6); - __Pyx_XDECREF(__pyx_t_7); - { PyObject *__pyx_type, *__pyx_value, *__pyx_tb; - __Pyx_PyThreadState_declare - __Pyx_PyThreadState_assign - __Pyx_ErrFetch(&__pyx_type, &__pyx_value, &__pyx_tb); - __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_P_initial.rcbuffer->pybuffer); - __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_P_initial_b.rcbuffer->pybuffer); - __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_Q.rcbuffer->pybuffer); - __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_Q_b.rcbuffer->pybuffer); - __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_x_initial.rcbuffer->pybuffer); - __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_x_initial_b.rcbuffer->pybuffer); - __Pyx_ErrRestore(__pyx_type, __pyx_value, __pyx_tb);} - __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = -1; - goto __pyx_L2; - __pyx_L0:; - __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_P_initial.rcbuffer->pybuffer); - __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_P_initial_b.rcbuffer->pybuffer); - __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_Q.rcbuffer->pybuffer); - __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_Q_b.rcbuffer->pybuffer); - __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_x_initial.rcbuffer->pybuffer); - __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_x_initial_b.rcbuffer->pybuffer); - __pyx_L2:; - __Pyx_XDECREF((PyObject *)__pyx_v_Q_b); - __Pyx_XDECREF((PyObject *)__pyx_v_x_initial_b); - __Pyx_XDECREF((PyObject *)__pyx_v_P_initial_b); - __Pyx_XDECREF(__pyx_7genexpr__pyx_v_x); - __Pyx_TraceReturn(Py_None, 0); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "rednose/helpers/ekf_sym_pyx.pyx":113 - * ) - * - * def init_state(self, np.ndarray[np.float64_t, ndim=1] state, np.ndarray[np.float64_t, ndim=2] covs, filter_time): # <<<<<<<<<<<<<< - * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] state_b = np.ascontiguousarray(state, dtype=np.double) - * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] covs_b = np.ascontiguousarray(covs, dtype=np.double) - */ - -/* Python wrapper */ -static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_3init_state(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -); /*proto*/ -static PyMethodDef __pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_3init_state = {"init_state", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_3init_state, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; -static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_3init_state(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -) { - PyArrayObject *__pyx_v_state = 0; - PyArrayObject *__pyx_v_covs = 0; - PyObject *__pyx_v_filter_time = 0; - #if !CYTHON_METH_FASTCALL - CYTHON_UNUSED Py_ssize_t __pyx_nargs; - #endif - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - PyObject* values[3] = {0,0,0}; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - PyObject *__pyx_r = 0; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("init_state (wrapper)", 0); - #if !CYTHON_METH_FASTCALL - #if CYTHON_ASSUME_SAFE_MACROS - __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); - #else - __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; - #endif - #endif - __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); - { - PyObject **__pyx_pyargnames[] = {&__pyx_n_s_state,&__pyx_n_s_covs,&__pyx_n_s_filter_time,0}; - if (__pyx_kwds) { - Py_ssize_t kw_args; - switch (__pyx_nargs) { - case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); - CYTHON_FALLTHROUGH; - case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); - CYTHON_FALLTHROUGH; - case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); - CYTHON_FALLTHROUGH; - case 0: break; - default: goto __pyx_L5_argtuple_error; - } - kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); - switch (__pyx_nargs) { - case 0: - if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_state)) != 0)) { - (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); - kw_args--; - } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 113, __pyx_L3_error) - else goto __pyx_L5_argtuple_error; - CYTHON_FALLTHROUGH; - case 1: - if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_covs)) != 0)) { - (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); - kw_args--; - } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 113, __pyx_L3_error) - else { - __Pyx_RaiseArgtupleInvalid("init_state", 1, 3, 3, 1); __PYX_ERR(0, 113, __pyx_L3_error) - } - CYTHON_FALLTHROUGH; - case 2: - if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_filter_time)) != 0)) { - (void)__Pyx_Arg_NewRef_FASTCALL(values[2]); - kw_args--; - } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 113, __pyx_L3_error) - else { - __Pyx_RaiseArgtupleInvalid("init_state", 1, 3, 3, 2); __PYX_ERR(0, 113, __pyx_L3_error) - } - } - if (unlikely(kw_args > 0)) { - const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "init_state") < 0)) __PYX_ERR(0, 113, __pyx_L3_error) - } - } else if (unlikely(__pyx_nargs != 3)) { - goto __pyx_L5_argtuple_error; - } else { - values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); - values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); - values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); - } - __pyx_v_state = ((PyArrayObject *)values[0]); - __pyx_v_covs = ((PyArrayObject *)values[1]); - __pyx_v_filter_time = values[2]; - } - goto __pyx_L6_skip; - __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("init_state", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 113, __pyx_L3_error) - __pyx_L6_skip:; - goto __pyx_L4_argument_unpacking_done; - __pyx_L3_error:; - { - Py_ssize_t __pyx_temp; - for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { - __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); - } - } - __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.init_state", __pyx_clineno, __pyx_lineno, __pyx_filename); - __Pyx_RefNannyFinishContext(); - return NULL; - __pyx_L4_argument_unpacking_done:; - if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_state), __pyx_ptype_5numpy_ndarray, 1, "state", 0))) __PYX_ERR(0, 113, __pyx_L1_error) - if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_covs), __pyx_ptype_5numpy_ndarray, 1, "covs", 0))) __PYX_ERR(0, 113, __pyx_L1_error) - __pyx_r = __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_2init_state(((struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *)__pyx_v_self), __pyx_v_state, __pyx_v_covs, __pyx_v_filter_time); - - /* function exit code */ - goto __pyx_L0; - __pyx_L1_error:; - __pyx_r = NULL; - __pyx_L0:; - { - Py_ssize_t __pyx_temp; - for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { - __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); - } - } - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_2init_state(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, PyArrayObject *__pyx_v_state, PyArrayObject *__pyx_v_covs, PyObject *__pyx_v_filter_time) { - PyArrayObject *__pyx_v_state_b = 0; - PyArrayObject *__pyx_v_covs_b = 0; - __Pyx_LocalBuf_ND __pyx_pybuffernd_covs; - __Pyx_Buffer __pyx_pybuffer_covs; - __Pyx_LocalBuf_ND __pyx_pybuffernd_covs_b; - __Pyx_Buffer __pyx_pybuffer_covs_b; - __Pyx_LocalBuf_ND __pyx_pybuffernd_state; - __Pyx_Buffer __pyx_pybuffer_state; - __Pyx_LocalBuf_ND __pyx_pybuffernd_state_b; - __Pyx_Buffer __pyx_pybuffer_state_b; - PyObject *__pyx_r = NULL; - __Pyx_TraceDeclarations - __Pyx_RefNannyDeclarations - PyObject *__pyx_t_1 = NULL; - PyObject *__pyx_t_2 = NULL; - PyObject *__pyx_t_3 = NULL; - PyObject *__pyx_t_4 = NULL; - PyObject *__pyx_t_5 = NULL; - PyArrayObject *__pyx_t_6 = NULL; - PyArrayObject *__pyx_t_7 = NULL; - char *__pyx_t_8; - npy_intp *__pyx_t_9; - char *__pyx_t_10; - npy_intp *__pyx_t_11; - npy_intp *__pyx_t_12; - double __pyx_t_13; - int __pyx_t_14; - double __pyx_t_15; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_TraceFrameInit(__pyx_codeobj__20) - __Pyx_RefNannySetupContext("init_state", 1); - __Pyx_TraceCall("init_state", __pyx_f[0], 113, 0, __PYX_ERR(0, 113, __pyx_L1_error)); - __pyx_pybuffer_state_b.pybuffer.buf = NULL; - __pyx_pybuffer_state_b.refcount = 0; - __pyx_pybuffernd_state_b.data = NULL; - __pyx_pybuffernd_state_b.rcbuffer = &__pyx_pybuffer_state_b; - __pyx_pybuffer_covs_b.pybuffer.buf = NULL; - __pyx_pybuffer_covs_b.refcount = 0; - __pyx_pybuffernd_covs_b.data = NULL; - __pyx_pybuffernd_covs_b.rcbuffer = &__pyx_pybuffer_covs_b; - __pyx_pybuffer_state.pybuffer.buf = NULL; - __pyx_pybuffer_state.refcount = 0; - __pyx_pybuffernd_state.data = NULL; - __pyx_pybuffernd_state.rcbuffer = &__pyx_pybuffer_state; - __pyx_pybuffer_covs.pybuffer.buf = NULL; - __pyx_pybuffer_covs.refcount = 0; - __pyx_pybuffernd_covs.data = NULL; - __pyx_pybuffernd_covs.rcbuffer = &__pyx_pybuffer_covs; - { - __Pyx_BufFmt_StackElem __pyx_stack[1]; - if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_state.rcbuffer->pybuffer, (PyObject*)__pyx_v_state, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 1, 0, __pyx_stack) == -1)) __PYX_ERR(0, 113, __pyx_L1_error) - } - __pyx_pybuffernd_state.diminfo[0].strides = __pyx_pybuffernd_state.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_state.diminfo[0].shape = __pyx_pybuffernd_state.rcbuffer->pybuffer.shape[0]; - { - __Pyx_BufFmt_StackElem __pyx_stack[1]; - if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_covs.rcbuffer->pybuffer, (PyObject*)__pyx_v_covs, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 2, 0, __pyx_stack) == -1)) __PYX_ERR(0, 113, __pyx_L1_error) - } - __pyx_pybuffernd_covs.diminfo[0].strides = __pyx_pybuffernd_covs.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_covs.diminfo[0].shape = __pyx_pybuffernd_covs.rcbuffer->pybuffer.shape[0]; __pyx_pybuffernd_covs.diminfo[1].strides = __pyx_pybuffernd_covs.rcbuffer->pybuffer.strides[1]; __pyx_pybuffernd_covs.diminfo[1].shape = __pyx_pybuffernd_covs.rcbuffer->pybuffer.shape[1]; - - /* "rednose/helpers/ekf_sym_pyx.pyx":114 - * - * def init_state(self, np.ndarray[np.float64_t, ndim=1] state, np.ndarray[np.float64_t, ndim=2] covs, filter_time): - * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] state_b = np.ascontiguousarray(state, dtype=np.double) # <<<<<<<<<<<<<< - * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] covs_b = np.ascontiguousarray(covs, dtype=np.double) - * self.ekf.init_state( - */ - __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 114, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 114, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_t_1 = PyTuple_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 114, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __Pyx_INCREF((PyObject *)__pyx_v_state); - __Pyx_GIVEREF((PyObject *)__pyx_v_state); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, ((PyObject *)__pyx_v_state))) __PYX_ERR(0, 114, __pyx_L1_error); - __pyx_t_3 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 114, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_np); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 114, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_double); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 114, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - if (PyDict_SetItem(__pyx_t_3, __pyx_n_s_dtype, __pyx_t_5) < 0) __PYX_ERR(0, 114, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __pyx_t_5 = __Pyx_PyObject_Call(__pyx_t_2, __pyx_t_1, __pyx_t_3); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 114, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - if (!(likely(((__pyx_t_5) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_5, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 114, __pyx_L1_error) - __pyx_t_6 = ((PyArrayObject *)__pyx_t_5); - { - __Pyx_BufFmt_StackElem __pyx_stack[1]; - if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_state_b.rcbuffer->pybuffer, (PyObject*)__pyx_t_6, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_C_CONTIGUOUS, 1, 0, __pyx_stack) == -1)) { - __pyx_v_state_b = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_state_b.rcbuffer->pybuffer.buf = NULL; - __PYX_ERR(0, 114, __pyx_L1_error) - } else {__pyx_pybuffernd_state_b.diminfo[0].strides = __pyx_pybuffernd_state_b.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_state_b.diminfo[0].shape = __pyx_pybuffernd_state_b.rcbuffer->pybuffer.shape[0]; - } - } - __pyx_t_6 = 0; - __pyx_v_state_b = ((PyArrayObject *)__pyx_t_5); - __pyx_t_5 = 0; - - /* "rednose/helpers/ekf_sym_pyx.pyx":115 - * def init_state(self, np.ndarray[np.float64_t, ndim=1] state, np.ndarray[np.float64_t, ndim=2] covs, filter_time): - * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] state_b = np.ascontiguousarray(state, dtype=np.double) - * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] covs_b = np.ascontiguousarray(covs, dtype=np.double) # <<<<<<<<<<<<<< - * self.ekf.init_state( - * MapVectorXd( state_b.data, state.shape[0]), - */ - __Pyx_GetModuleGlobalName(__pyx_t_5, __pyx_n_s_np); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 115, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 115, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __pyx_t_5 = PyTuple_New(1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 115, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __Pyx_INCREF((PyObject *)__pyx_v_covs); - __Pyx_GIVEREF((PyObject *)__pyx_v_covs); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_5, 0, ((PyObject *)__pyx_v_covs))) __PYX_ERR(0, 115, __pyx_L1_error); - __pyx_t_1 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 115, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_np); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 115, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_double); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 115, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - if (PyDict_SetItem(__pyx_t_1, __pyx_n_s_dtype, __pyx_t_4) < 0) __PYX_ERR(0, 115, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __pyx_t_4 = __Pyx_PyObject_Call(__pyx_t_3, __pyx_t_5, __pyx_t_1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 115, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - if (!(likely(((__pyx_t_4) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_4, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 115, __pyx_L1_error) - __pyx_t_7 = ((PyArrayObject *)__pyx_t_4); - { - __Pyx_BufFmt_StackElem __pyx_stack[1]; - if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_covs_b.rcbuffer->pybuffer, (PyObject*)__pyx_t_7, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_C_CONTIGUOUS, 2, 0, __pyx_stack) == -1)) { - __pyx_v_covs_b = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_covs_b.rcbuffer->pybuffer.buf = NULL; - __PYX_ERR(0, 115, __pyx_L1_error) - } else {__pyx_pybuffernd_covs_b.diminfo[0].strides = __pyx_pybuffernd_covs_b.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_covs_b.diminfo[0].shape = __pyx_pybuffernd_covs_b.rcbuffer->pybuffer.shape[0]; __pyx_pybuffernd_covs_b.diminfo[1].strides = __pyx_pybuffernd_covs_b.rcbuffer->pybuffer.strides[1]; __pyx_pybuffernd_covs_b.diminfo[1].shape = __pyx_pybuffernd_covs_b.rcbuffer->pybuffer.shape[1]; - } - } - __pyx_t_7 = 0; - __pyx_v_covs_b = ((PyArrayObject *)__pyx_t_4); - __pyx_t_4 = 0; - - /* "rednose/helpers/ekf_sym_pyx.pyx":117 - * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] covs_b = np.ascontiguousarray(covs, dtype=np.double) - * self.ekf.init_state( - * MapVectorXd( state_b.data, state.shape[0]), # <<<<<<<<<<<<<< - * MapMatrixXdr( covs_b.data, covs.shape[0], covs.shape[1]), - * np.nan if filter_time is None else filter_time - */ - __pyx_t_8 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_state_b)); if (unlikely(__pyx_t_8 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 117, __pyx_L1_error) - __pyx_t_9 = __pyx_f_5numpy_7ndarray_5shape_shape(((PyArrayObject *)__pyx_v_state)); if (unlikely(__pyx_t_9 == ((npy_intp *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 117, __pyx_L1_error) - - /* "rednose/helpers/ekf_sym_pyx.pyx":118 - * self.ekf.init_state( - * MapVectorXd( state_b.data, state.shape[0]), - * MapMatrixXdr( covs_b.data, covs.shape[0], covs.shape[1]), # <<<<<<<<<<<<<< - * np.nan if filter_time is None else filter_time - * ) - */ - __pyx_t_10 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_covs_b)); if (unlikely(__pyx_t_10 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 118, __pyx_L1_error) - __pyx_t_11 = __pyx_f_5numpy_7ndarray_5shape_shape(((PyArrayObject *)__pyx_v_covs)); if (unlikely(__pyx_t_11 == ((npy_intp *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 118, __pyx_L1_error) - __pyx_t_12 = __pyx_f_5numpy_7ndarray_5shape_shape(((PyArrayObject *)__pyx_v_covs)); if (unlikely(__pyx_t_12 == ((npy_intp *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 118, __pyx_L1_error) - - /* "rednose/helpers/ekf_sym_pyx.pyx":119 - * MapVectorXd( state_b.data, state.shape[0]), - * MapMatrixXdr( covs_b.data, covs.shape[0], covs.shape[1]), - * np.nan if filter_time is None else filter_time # <<<<<<<<<<<<<< - * ) - * - */ - __pyx_t_14 = (__pyx_v_filter_time == Py_None); - if (__pyx_t_14) { - __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_np); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 119, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_nan); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 119, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __pyx_t_15 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_15 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 119, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_t_13 = __pyx_t_15; - } else { - __pyx_t_15 = __pyx_PyFloat_AsDouble(__pyx_v_filter_time); if (unlikely((__pyx_t_15 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 119, __pyx_L1_error) - __pyx_t_13 = __pyx_t_15; - } - - /* "rednose/helpers/ekf_sym_pyx.pyx":116 - * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] state_b = np.ascontiguousarray(state, dtype=np.double) - * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] covs_b = np.ascontiguousarray(covs, dtype=np.double) - * self.ekf.init_state( # <<<<<<<<<<<<<< - * MapVectorXd( state_b.data, state.shape[0]), - * MapMatrixXdr( covs_b.data, covs.shape[0], covs.shape[1]), - */ - __pyx_v_self->ekf->init_state(Eigen::Map(((double *)__pyx_t_8), (__pyx_t_9[0])), Eigen::Map >(((double *)__pyx_t_10), (__pyx_t_11[0]), (__pyx_t_12[1])), __pyx_t_13); - - /* "rednose/helpers/ekf_sym_pyx.pyx":113 - * ) - * - * def init_state(self, np.ndarray[np.float64_t, ndim=1] state, np.ndarray[np.float64_t, ndim=2] covs, filter_time): # <<<<<<<<<<<<<< - * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] state_b = np.ascontiguousarray(state, dtype=np.double) - * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] covs_b = np.ascontiguousarray(covs, dtype=np.double) - */ - - /* function exit code */ - __pyx_r = Py_None; __Pyx_INCREF(Py_None); - goto __pyx_L0; - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_1); - __Pyx_XDECREF(__pyx_t_2); - __Pyx_XDECREF(__pyx_t_3); - __Pyx_XDECREF(__pyx_t_4); - __Pyx_XDECREF(__pyx_t_5); - { PyObject *__pyx_type, *__pyx_value, *__pyx_tb; - __Pyx_PyThreadState_declare - __Pyx_PyThreadState_assign - __Pyx_ErrFetch(&__pyx_type, &__pyx_value, &__pyx_tb); - __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_covs.rcbuffer->pybuffer); - __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_covs_b.rcbuffer->pybuffer); - __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_state.rcbuffer->pybuffer); - __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_state_b.rcbuffer->pybuffer); - __Pyx_ErrRestore(__pyx_type, __pyx_value, __pyx_tb);} - __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.init_state", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = NULL; - goto __pyx_L2; - __pyx_L0:; - __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_covs.rcbuffer->pybuffer); - __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_covs_b.rcbuffer->pybuffer); - __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_state.rcbuffer->pybuffer); - __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_state_b.rcbuffer->pybuffer); - __pyx_L2:; - __Pyx_XDECREF((PyObject *)__pyx_v_state_b); - __Pyx_XDECREF((PyObject *)__pyx_v_covs_b); - __Pyx_XGIVEREF(__pyx_r); - __Pyx_TraceReturn(__pyx_r, 0); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "rednose/helpers/ekf_sym_pyx.pyx":122 - * ) - * - * def state(self): # <<<<<<<<<<<<<< - * cdef np.ndarray res = vector_to_numpy(self.ekf.state()) - * return res - */ - -/* Python wrapper */ -static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_5state(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -); /*proto*/ -static PyMethodDef __pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_5state = {"state", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_5state, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; -static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_5state(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -) { - #if !CYTHON_METH_FASTCALL - CYTHON_UNUSED Py_ssize_t __pyx_nargs; - #endif - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - PyObject *__pyx_r = 0; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("state (wrapper)", 0); - #if !CYTHON_METH_FASTCALL - #if CYTHON_ASSUME_SAFE_MACROS - __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); - #else - __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; - #endif - #endif - __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); - if (unlikely(__pyx_nargs > 0)) { - __Pyx_RaiseArgtupleInvalid("state", 1, 0, 0, __pyx_nargs); return NULL;} - if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "state", 0))) return NULL; - __pyx_r = __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_4state(((struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *)__pyx_v_self)); - - /* function exit code */ - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_4state(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self) { - PyArrayObject *__pyx_v_res = 0; - PyObject *__pyx_r = NULL; - __Pyx_TraceDeclarations - __Pyx_RefNannyDeclarations - PyObject *__pyx_t_1 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_TraceFrameInit(__pyx_codeobj__21) - __Pyx_RefNannySetupContext("state", 1); - __Pyx_TraceCall("state", __pyx_f[0], 122, 0, __PYX_ERR(0, 122, __pyx_L1_error)); - - /* "rednose/helpers/ekf_sym_pyx.pyx":123 - * - * def state(self): - * cdef np.ndarray res = vector_to_numpy(self.ekf.state()) # <<<<<<<<<<<<<< - * return res - * - */ - __pyx_t_1 = ((PyObject *)__pyx_f_7rednose_7helpers_11ekf_sym_pyx_vector_to_numpy(__pyx_v_self->ekf->state())); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 123, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_v_res = ((PyArrayObject *)__pyx_t_1); - __pyx_t_1 = 0; - - /* "rednose/helpers/ekf_sym_pyx.pyx":124 - * def state(self): - * cdef np.ndarray res = vector_to_numpy(self.ekf.state()) - * return res # <<<<<<<<<<<<<< - * - * def covs(self): - */ - __Pyx_XDECREF(__pyx_r); - __Pyx_INCREF((PyObject *)__pyx_v_res); - __pyx_r = ((PyObject *)__pyx_v_res); - goto __pyx_L0; - - /* "rednose/helpers/ekf_sym_pyx.pyx":122 - * ) - * - * def state(self): # <<<<<<<<<<<<<< - * cdef np.ndarray res = vector_to_numpy(self.ekf.state()) - * return res - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_1); - __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.state", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = NULL; - __pyx_L0:; - __Pyx_XDECREF((PyObject *)__pyx_v_res); - __Pyx_XGIVEREF(__pyx_r); - __Pyx_TraceReturn(__pyx_r, 0); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "rednose/helpers/ekf_sym_pyx.pyx":126 - * return res - * - * def covs(self): # <<<<<<<<<<<<<< - * return matrix_to_numpy(self.ekf.covs()) - * - */ - -/* Python wrapper */ -static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_7covs(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -); /*proto*/ -static PyMethodDef __pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_7covs = {"covs", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_7covs, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; -static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_7covs(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -) { - #if !CYTHON_METH_FASTCALL - CYTHON_UNUSED Py_ssize_t __pyx_nargs; - #endif - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - PyObject *__pyx_r = 0; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("covs (wrapper)", 0); - #if !CYTHON_METH_FASTCALL - #if CYTHON_ASSUME_SAFE_MACROS - __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); - #else - __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; - #endif - #endif - __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); - if (unlikely(__pyx_nargs > 0)) { - __Pyx_RaiseArgtupleInvalid("covs", 1, 0, 0, __pyx_nargs); return NULL;} - if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "covs", 0))) return NULL; - __pyx_r = __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_6covs(((struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *)__pyx_v_self)); - - /* function exit code */ - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_6covs(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self) { - PyObject *__pyx_r = NULL; - __Pyx_TraceDeclarations - __Pyx_RefNannyDeclarations - PyObject *__pyx_t_1 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_TraceFrameInit(__pyx_codeobj__22) - __Pyx_RefNannySetupContext("covs", 1); - __Pyx_TraceCall("covs", __pyx_f[0], 126, 0, __PYX_ERR(0, 126, __pyx_L1_error)); - - /* "rednose/helpers/ekf_sym_pyx.pyx":127 - * - * def covs(self): - * return matrix_to_numpy(self.ekf.covs()) # <<<<<<<<<<<<<< - * - * def set_filter_time(self, double t): - */ - __Pyx_XDECREF(__pyx_r); - __pyx_t_1 = ((PyObject *)__pyx_f_7rednose_7helpers_11ekf_sym_pyx_matrix_to_numpy(__pyx_v_self->ekf->covs())); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 127, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_r = __pyx_t_1; - __pyx_t_1 = 0; - goto __pyx_L0; - - /* "rednose/helpers/ekf_sym_pyx.pyx":126 - * return res - * - * def covs(self): # <<<<<<<<<<<<<< - * return matrix_to_numpy(self.ekf.covs()) - * - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_1); - __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.covs", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = NULL; - __pyx_L0:; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_TraceReturn(__pyx_r, 0); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "rednose/helpers/ekf_sym_pyx.pyx":129 - * return matrix_to_numpy(self.ekf.covs()) - * - * def set_filter_time(self, double t): # <<<<<<<<<<<<<< - * self.ekf.set_filter_time(t) - * - */ - -/* Python wrapper */ -static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_9set_filter_time(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -); /*proto*/ -static PyMethodDef __pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_9set_filter_time = {"set_filter_time", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_9set_filter_time, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; -static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_9set_filter_time(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -) { - double __pyx_v_t; - #if !CYTHON_METH_FASTCALL - CYTHON_UNUSED Py_ssize_t __pyx_nargs; - #endif - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - PyObject* values[1] = {0}; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - PyObject *__pyx_r = 0; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("set_filter_time (wrapper)", 0); - #if !CYTHON_METH_FASTCALL - #if CYTHON_ASSUME_SAFE_MACROS - __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); - #else - __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; - #endif - #endif - __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); - { - PyObject **__pyx_pyargnames[] = {&__pyx_n_s_t,0}; - if (__pyx_kwds) { - Py_ssize_t kw_args; - switch (__pyx_nargs) { - case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); - CYTHON_FALLTHROUGH; - case 0: break; - default: goto __pyx_L5_argtuple_error; - } - kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); - switch (__pyx_nargs) { - case 0: - if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_t)) != 0)) { - (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); - kw_args--; - } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 129, __pyx_L3_error) - else goto __pyx_L5_argtuple_error; - } - if (unlikely(kw_args > 0)) { - const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "set_filter_time") < 0)) __PYX_ERR(0, 129, __pyx_L3_error) - } - } else if (unlikely(__pyx_nargs != 1)) { - goto __pyx_L5_argtuple_error; - } else { - values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); - } - __pyx_v_t = __pyx_PyFloat_AsDouble(values[0]); if (unlikely((__pyx_v_t == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 129, __pyx_L3_error) - } - goto __pyx_L6_skip; - __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("set_filter_time", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 129, __pyx_L3_error) - __pyx_L6_skip:; - goto __pyx_L4_argument_unpacking_done; - __pyx_L3_error:; - { - Py_ssize_t __pyx_temp; - for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { - __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); - } - } - __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.set_filter_time", __pyx_clineno, __pyx_lineno, __pyx_filename); - __Pyx_RefNannyFinishContext(); - return NULL; - __pyx_L4_argument_unpacking_done:; - __pyx_r = __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_8set_filter_time(((struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *)__pyx_v_self), __pyx_v_t); - - /* function exit code */ - { - Py_ssize_t __pyx_temp; - for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { - __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); - } - } - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_8set_filter_time(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, double __pyx_v_t) { - PyObject *__pyx_r = NULL; - __Pyx_TraceDeclarations - __Pyx_RefNannyDeclarations - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_TraceFrameInit(__pyx_codeobj__23) - __Pyx_RefNannySetupContext("set_filter_time", 1); - __Pyx_TraceCall("set_filter_time", __pyx_f[0], 129, 0, __PYX_ERR(0, 129, __pyx_L1_error)); - - /* "rednose/helpers/ekf_sym_pyx.pyx":130 - * - * def set_filter_time(self, double t): - * self.ekf.set_filter_time(t) # <<<<<<<<<<<<<< - * - * def get_filter_time(self): - */ - __pyx_v_self->ekf->set_filter_time(__pyx_v_t); - - /* "rednose/helpers/ekf_sym_pyx.pyx":129 - * return matrix_to_numpy(self.ekf.covs()) - * - * def set_filter_time(self, double t): # <<<<<<<<<<<<<< - * self.ekf.set_filter_time(t) - * - */ - - /* function exit code */ - __pyx_r = Py_None; __Pyx_INCREF(Py_None); - goto __pyx_L0; - __pyx_L1_error:; - __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.set_filter_time", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = NULL; - __pyx_L0:; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_TraceReturn(__pyx_r, 0); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "rednose/helpers/ekf_sym_pyx.pyx":132 - * self.ekf.set_filter_time(t) - * - * def get_filter_time(self): # <<<<<<<<<<<<<< - * return self.ekf.get_filter_time() - * - */ - -/* Python wrapper */ -static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_11get_filter_time(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -); /*proto*/ -static PyMethodDef __pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_11get_filter_time = {"get_filter_time", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_11get_filter_time, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; -static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_11get_filter_time(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -) { - #if !CYTHON_METH_FASTCALL - CYTHON_UNUSED Py_ssize_t __pyx_nargs; - #endif - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - PyObject *__pyx_r = 0; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("get_filter_time (wrapper)", 0); - #if !CYTHON_METH_FASTCALL - #if CYTHON_ASSUME_SAFE_MACROS - __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); - #else - __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; - #endif - #endif - __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); - if (unlikely(__pyx_nargs > 0)) { - __Pyx_RaiseArgtupleInvalid("get_filter_time", 1, 0, 0, __pyx_nargs); return NULL;} - if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "get_filter_time", 0))) return NULL; - __pyx_r = __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_10get_filter_time(((struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *)__pyx_v_self)); - - /* function exit code */ - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_10get_filter_time(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self) { - PyObject *__pyx_r = NULL; - __Pyx_TraceDeclarations - __Pyx_RefNannyDeclarations - PyObject *__pyx_t_1 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_TraceFrameInit(__pyx_codeobj__24) - __Pyx_RefNannySetupContext("get_filter_time", 1); - __Pyx_TraceCall("get_filter_time", __pyx_f[0], 132, 0, __PYX_ERR(0, 132, __pyx_L1_error)); - - /* "rednose/helpers/ekf_sym_pyx.pyx":133 - * - * def get_filter_time(self): - * return self.ekf.get_filter_time() # <<<<<<<<<<<<<< - * - * def set_global(self, str global_var, double val): - */ - __Pyx_XDECREF(__pyx_r); - __pyx_t_1 = PyFloat_FromDouble(__pyx_v_self->ekf->get_filter_time()); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 133, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_r = __pyx_t_1; - __pyx_t_1 = 0; - goto __pyx_L0; - - /* "rednose/helpers/ekf_sym_pyx.pyx":132 - * self.ekf.set_filter_time(t) - * - * def get_filter_time(self): # <<<<<<<<<<<<<< - * return self.ekf.get_filter_time() - * - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_1); - __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.get_filter_time", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = NULL; - __pyx_L0:; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_TraceReturn(__pyx_r, 0); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "rednose/helpers/ekf_sym_pyx.pyx":135 - * return self.ekf.get_filter_time() - * - * def set_global(self, str global_var, double val): # <<<<<<<<<<<<<< - * self.ekf.set_global(global_var.encode('utf8'), val) - * - */ - -/* Python wrapper */ -static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_13set_global(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -); /*proto*/ -static PyMethodDef __pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_13set_global = {"set_global", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_13set_global, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; -static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_13set_global(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -) { - PyObject *__pyx_v_global_var = 0; - double __pyx_v_val; - #if !CYTHON_METH_FASTCALL - CYTHON_UNUSED Py_ssize_t __pyx_nargs; - #endif - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - PyObject* values[2] = {0,0}; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - PyObject *__pyx_r = 0; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("set_global (wrapper)", 0); - #if !CYTHON_METH_FASTCALL - #if CYTHON_ASSUME_SAFE_MACROS - __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); - #else - __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; - #endif - #endif - __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); - { - PyObject **__pyx_pyargnames[] = {&__pyx_n_s_global_var,&__pyx_n_s_val,0}; - if (__pyx_kwds) { - Py_ssize_t kw_args; - switch (__pyx_nargs) { - case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); - CYTHON_FALLTHROUGH; - case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); - CYTHON_FALLTHROUGH; - case 0: break; - default: goto __pyx_L5_argtuple_error; - } - kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); - switch (__pyx_nargs) { - case 0: - if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_global_var)) != 0)) { - (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); - kw_args--; - } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 135, __pyx_L3_error) - else goto __pyx_L5_argtuple_error; - CYTHON_FALLTHROUGH; - case 1: - if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_val)) != 0)) { - (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); - kw_args--; - } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 135, __pyx_L3_error) - else { - __Pyx_RaiseArgtupleInvalid("set_global", 1, 2, 2, 1); __PYX_ERR(0, 135, __pyx_L3_error) - } - } - if (unlikely(kw_args > 0)) { - const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "set_global") < 0)) __PYX_ERR(0, 135, __pyx_L3_error) - } - } else if (unlikely(__pyx_nargs != 2)) { - goto __pyx_L5_argtuple_error; - } else { - values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); - values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); - } - __pyx_v_global_var = ((PyObject*)values[0]); - __pyx_v_val = __pyx_PyFloat_AsDouble(values[1]); if (unlikely((__pyx_v_val == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 135, __pyx_L3_error) - } - goto __pyx_L6_skip; - __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("set_global", 1, 2, 2, __pyx_nargs); __PYX_ERR(0, 135, __pyx_L3_error) - __pyx_L6_skip:; - goto __pyx_L4_argument_unpacking_done; - __pyx_L3_error:; - { - Py_ssize_t __pyx_temp; - for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { - __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); - } - } - __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.set_global", __pyx_clineno, __pyx_lineno, __pyx_filename); - __Pyx_RefNannyFinishContext(); - return NULL; - __pyx_L4_argument_unpacking_done:; - if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_global_var), (&PyUnicode_Type), 1, "global_var", 1))) __PYX_ERR(0, 135, __pyx_L1_error) - __pyx_r = __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_12set_global(((struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *)__pyx_v_self), __pyx_v_global_var, __pyx_v_val); - - /* function exit code */ - goto __pyx_L0; - __pyx_L1_error:; - __pyx_r = NULL; - __pyx_L0:; - { - Py_ssize_t __pyx_temp; - for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { - __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); - } - } - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_12set_global(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, PyObject *__pyx_v_global_var, double __pyx_v_val) { - PyObject *__pyx_r = NULL; - __Pyx_TraceDeclarations - __Pyx_RefNannyDeclarations - PyObject *__pyx_t_1 = NULL; - std::string __pyx_t_2; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_TraceFrameInit(__pyx_codeobj__25) - __Pyx_RefNannySetupContext("set_global", 1); - __Pyx_TraceCall("set_global", __pyx_f[0], 135, 0, __PYX_ERR(0, 135, __pyx_L1_error)); - - /* "rednose/helpers/ekf_sym_pyx.pyx":136 - * - * def set_global(self, str global_var, double val): - * self.ekf.set_global(global_var.encode('utf8'), val) # <<<<<<<<<<<<<< - * - * def reset_rewind(self): - */ - if (unlikely(__pyx_v_global_var == Py_None)) { - PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "encode"); - __PYX_ERR(0, 136, __pyx_L1_error) - } - __pyx_t_1 = PyUnicode_AsUTF8String(__pyx_v_global_var); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 136, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_2 = __pyx_convert_string_from_py_std__in_string(__pyx_t_1); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 136, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_v_self->ekf->set_global(__PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_2), __pyx_v_val); - - /* "rednose/helpers/ekf_sym_pyx.pyx":135 - * return self.ekf.get_filter_time() - * - * def set_global(self, str global_var, double val): # <<<<<<<<<<<<<< - * self.ekf.set_global(global_var.encode('utf8'), val) - * - */ - - /* function exit code */ - __pyx_r = Py_None; __Pyx_INCREF(Py_None); - goto __pyx_L0; - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_1); - __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.set_global", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = NULL; - __pyx_L0:; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_TraceReturn(__pyx_r, 0); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "rednose/helpers/ekf_sym_pyx.pyx":138 - * self.ekf.set_global(global_var.encode('utf8'), val) - * - * def reset_rewind(self): # <<<<<<<<<<<<<< - * self.ekf.reset_rewind() - * - */ - -/* Python wrapper */ -static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_15reset_rewind(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -); /*proto*/ -static PyMethodDef __pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_15reset_rewind = {"reset_rewind", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_15reset_rewind, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; -static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_15reset_rewind(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -) { - #if !CYTHON_METH_FASTCALL - CYTHON_UNUSED Py_ssize_t __pyx_nargs; - #endif - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - PyObject *__pyx_r = 0; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("reset_rewind (wrapper)", 0); - #if !CYTHON_METH_FASTCALL - #if CYTHON_ASSUME_SAFE_MACROS - __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); - #else - __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; - #endif - #endif - __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); - if (unlikely(__pyx_nargs > 0)) { - __Pyx_RaiseArgtupleInvalid("reset_rewind", 1, 0, 0, __pyx_nargs); return NULL;} - if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "reset_rewind", 0))) return NULL; - __pyx_r = __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_14reset_rewind(((struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *)__pyx_v_self)); - - /* function exit code */ - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_14reset_rewind(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self) { - PyObject *__pyx_r = NULL; - __Pyx_TraceDeclarations - __Pyx_RefNannyDeclarations - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_TraceFrameInit(__pyx_codeobj__26) - __Pyx_RefNannySetupContext("reset_rewind", 1); - __Pyx_TraceCall("reset_rewind", __pyx_f[0], 138, 0, __PYX_ERR(0, 138, __pyx_L1_error)); - - /* "rednose/helpers/ekf_sym_pyx.pyx":139 - * - * def reset_rewind(self): - * self.ekf.reset_rewind() # <<<<<<<<<<<<<< - * - * def predict(self, double t): - */ - __pyx_v_self->ekf->reset_rewind(); - - /* "rednose/helpers/ekf_sym_pyx.pyx":138 - * self.ekf.set_global(global_var.encode('utf8'), val) - * - * def reset_rewind(self): # <<<<<<<<<<<<<< - * self.ekf.reset_rewind() - * - */ - - /* function exit code */ - __pyx_r = Py_None; __Pyx_INCREF(Py_None); - goto __pyx_L0; - __pyx_L1_error:; - __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.reset_rewind", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = NULL; - __pyx_L0:; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_TraceReturn(__pyx_r, 0); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "rednose/helpers/ekf_sym_pyx.pyx":141 - * self.ekf.reset_rewind() - * - * def predict(self, double t): # <<<<<<<<<<<<<< - * self.ekf.predict(t) - * - */ - -/* Python wrapper */ -static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_17predict(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -); /*proto*/ -static PyMethodDef __pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_17predict = {"predict", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_17predict, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; -static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_17predict(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -) { - double __pyx_v_t; - #if !CYTHON_METH_FASTCALL - CYTHON_UNUSED Py_ssize_t __pyx_nargs; - #endif - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - PyObject* values[1] = {0}; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - PyObject *__pyx_r = 0; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("predict (wrapper)", 0); - #if !CYTHON_METH_FASTCALL - #if CYTHON_ASSUME_SAFE_MACROS - __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); - #else - __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; - #endif - #endif - __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); - { - PyObject **__pyx_pyargnames[] = {&__pyx_n_s_t,0}; - if (__pyx_kwds) { - Py_ssize_t kw_args; - switch (__pyx_nargs) { - case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); - CYTHON_FALLTHROUGH; - case 0: break; - default: goto __pyx_L5_argtuple_error; - } - kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); - switch (__pyx_nargs) { - case 0: - if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_t)) != 0)) { - (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); - kw_args--; - } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 141, __pyx_L3_error) - else goto __pyx_L5_argtuple_error; - } - if (unlikely(kw_args > 0)) { - const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "predict") < 0)) __PYX_ERR(0, 141, __pyx_L3_error) - } - } else if (unlikely(__pyx_nargs != 1)) { - goto __pyx_L5_argtuple_error; - } else { - values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); - } - __pyx_v_t = __pyx_PyFloat_AsDouble(values[0]); if (unlikely((__pyx_v_t == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 141, __pyx_L3_error) - } - goto __pyx_L6_skip; - __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("predict", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 141, __pyx_L3_error) - __pyx_L6_skip:; - goto __pyx_L4_argument_unpacking_done; - __pyx_L3_error:; - { - Py_ssize_t __pyx_temp; - for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { - __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); - } - } - __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.predict", __pyx_clineno, __pyx_lineno, __pyx_filename); - __Pyx_RefNannyFinishContext(); - return NULL; - __pyx_L4_argument_unpacking_done:; - __pyx_r = __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_16predict(((struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *)__pyx_v_self), __pyx_v_t); - - /* function exit code */ - { - Py_ssize_t __pyx_temp; - for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { - __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); - } - } - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_16predict(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, double __pyx_v_t) { - PyObject *__pyx_r = NULL; - __Pyx_TraceDeclarations - __Pyx_RefNannyDeclarations - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_TraceFrameInit(__pyx_codeobj__27) - __Pyx_RefNannySetupContext("predict", 1); - __Pyx_TraceCall("predict", __pyx_f[0], 141, 0, __PYX_ERR(0, 141, __pyx_L1_error)); - - /* "rednose/helpers/ekf_sym_pyx.pyx":142 - * - * def predict(self, double t): - * self.ekf.predict(t) # <<<<<<<<<<<<<< - * - * def predict_and_update_batch(self, double t, int kind, z, R, extra_args=[[]], bool augment=False): - */ - __pyx_v_self->ekf->predict(__pyx_v_t); - - /* "rednose/helpers/ekf_sym_pyx.pyx":141 - * self.ekf.reset_rewind() - * - * def predict(self, double t): # <<<<<<<<<<<<<< - * self.ekf.predict(t) - * - */ - - /* function exit code */ - __pyx_r = Py_None; __Pyx_INCREF(Py_None); - goto __pyx_L0; - __pyx_L1_error:; - __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.predict", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = NULL; - __pyx_L0:; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_TraceReturn(__pyx_r, 0); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "rednose/helpers/ekf_sym_pyx.pyx":144 - * self.ekf.predict(t) - * - * def predict_and_update_batch(self, double t, int kind, z, R, extra_args=[[]], bool augment=False): # <<<<<<<<<<<<<< - * cdef vector[MapVectorXd] z_map - * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] zi_b - */ - -/* Python wrapper */ -static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_19predict_and_update_batch(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -); /*proto*/ -static PyMethodDef __pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_19predict_and_update_batch = {"predict_and_update_batch", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_19predict_and_update_batch, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; -static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_19predict_and_update_batch(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -) { - double __pyx_v_t; - int __pyx_v_kind; - PyObject *__pyx_v_z = 0; - PyObject *__pyx_v_R = 0; - PyObject *__pyx_v_extra_args = 0; - bool __pyx_v_augment; - #if !CYTHON_METH_FASTCALL - CYTHON_UNUSED Py_ssize_t __pyx_nargs; - #endif - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - PyObject* values[6] = {0,0,0,0,0,0}; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - PyObject *__pyx_r = 0; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("predict_and_update_batch (wrapper)", 0); - #if !CYTHON_METH_FASTCALL - #if CYTHON_ASSUME_SAFE_MACROS - __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); - #else - __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; - #endif - #endif - __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); - { - PyObject **__pyx_pyargnames[] = {&__pyx_n_s_t,&__pyx_n_s_kind,&__pyx_n_s_z,&__pyx_n_s_R,&__pyx_n_s_extra_args,&__pyx_n_s_augment,0}; - values[4] = __Pyx_Arg_NewRef_FASTCALL(__pyx_k__28); - if (__pyx_kwds) { - Py_ssize_t kw_args; - switch (__pyx_nargs) { - case 6: values[5] = __Pyx_Arg_FASTCALL(__pyx_args, 5); - CYTHON_FALLTHROUGH; - case 5: values[4] = __Pyx_Arg_FASTCALL(__pyx_args, 4); - CYTHON_FALLTHROUGH; - case 4: values[3] = __Pyx_Arg_FASTCALL(__pyx_args, 3); - CYTHON_FALLTHROUGH; - case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); - CYTHON_FALLTHROUGH; - case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); - CYTHON_FALLTHROUGH; - case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); - CYTHON_FALLTHROUGH; - case 0: break; - default: goto __pyx_L5_argtuple_error; - } - kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); - switch (__pyx_nargs) { - case 0: - if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_t)) != 0)) { - (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); - kw_args--; - } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 144, __pyx_L3_error) - else goto __pyx_L5_argtuple_error; - CYTHON_FALLTHROUGH; - case 1: - if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_kind)) != 0)) { - (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); - kw_args--; - } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 144, __pyx_L3_error) - else { - __Pyx_RaiseArgtupleInvalid("predict_and_update_batch", 0, 4, 6, 1); __PYX_ERR(0, 144, __pyx_L3_error) - } - CYTHON_FALLTHROUGH; - case 2: - if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_z)) != 0)) { - (void)__Pyx_Arg_NewRef_FASTCALL(values[2]); - kw_args--; - } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 144, __pyx_L3_error) - else { - __Pyx_RaiseArgtupleInvalid("predict_and_update_batch", 0, 4, 6, 2); __PYX_ERR(0, 144, __pyx_L3_error) - } - CYTHON_FALLTHROUGH; - case 3: - if (likely((values[3] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_R)) != 0)) { - (void)__Pyx_Arg_NewRef_FASTCALL(values[3]); - kw_args--; - } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 144, __pyx_L3_error) - else { - __Pyx_RaiseArgtupleInvalid("predict_and_update_batch", 0, 4, 6, 3); __PYX_ERR(0, 144, __pyx_L3_error) - } - CYTHON_FALLTHROUGH; - case 4: - if (kw_args > 0) { - PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_extra_args); - if (value) { values[4] = __Pyx_Arg_NewRef_FASTCALL(value); kw_args--; } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 144, __pyx_L3_error) - } - CYTHON_FALLTHROUGH; - case 5: - if (kw_args > 0) { - PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_augment); - if (value) { values[5] = __Pyx_Arg_NewRef_FASTCALL(value); kw_args--; } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 144, __pyx_L3_error) - } - } - if (unlikely(kw_args > 0)) { - const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "predict_and_update_batch") < 0)) __PYX_ERR(0, 144, __pyx_L3_error) - } - } else { - switch (__pyx_nargs) { - case 6: values[5] = __Pyx_Arg_FASTCALL(__pyx_args, 5); - CYTHON_FALLTHROUGH; - case 5: values[4] = __Pyx_Arg_FASTCALL(__pyx_args, 4); - CYTHON_FALLTHROUGH; - case 4: values[3] = __Pyx_Arg_FASTCALL(__pyx_args, 3); - values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); - values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); - values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); - break; - default: goto __pyx_L5_argtuple_error; - } - } - __pyx_v_t = __pyx_PyFloat_AsDouble(values[0]); if (unlikely((__pyx_v_t == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 144, __pyx_L3_error) - __pyx_v_kind = __Pyx_PyInt_As_int(values[1]); if (unlikely((__pyx_v_kind == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 144, __pyx_L3_error) - __pyx_v_z = values[2]; - __pyx_v_R = values[3]; - __pyx_v_extra_args = values[4]; - if (values[5]) { - __pyx_v_augment = __Pyx_PyObject_IsTrue(values[5]); if (unlikely((__pyx_v_augment == ((bool)-1)) && PyErr_Occurred())) __PYX_ERR(0, 144, __pyx_L3_error) - } else { - __pyx_v_augment = ((bool)0); - } - } - goto __pyx_L6_skip; - __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("predict_and_update_batch", 0, 4, 6, __pyx_nargs); __PYX_ERR(0, 144, __pyx_L3_error) - __pyx_L6_skip:; - goto __pyx_L4_argument_unpacking_done; - __pyx_L3_error:; - { - Py_ssize_t __pyx_temp; - for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { - __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); - } - } - __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.predict_and_update_batch", __pyx_clineno, __pyx_lineno, __pyx_filename); - __Pyx_RefNannyFinishContext(); - return NULL; - __pyx_L4_argument_unpacking_done:; - __pyx_r = __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_18predict_and_update_batch(((struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *)__pyx_v_self), __pyx_v_t, __pyx_v_kind, __pyx_v_z, __pyx_v_R, __pyx_v_extra_args, __pyx_v_augment); - - /* function exit code */ - { - Py_ssize_t __pyx_temp; - for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { - __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); - } - } - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_18predict_and_update_batch(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, double __pyx_v_t, int __pyx_v_kind, PyObject *__pyx_v_z, PyObject *__pyx_v_R, PyObject *__pyx_v_extra_args, bool __pyx_v_augment) { - std::vector> __pyx_v_z_map; - PyArrayObject *__pyx_v_zi_b = 0; - PyObject *__pyx_v_zi = NULL; - std::vector >> __pyx_v_R_map; - PyArrayObject *__pyx_v_Ri_b = 0; - PyObject *__pyx_v_Ri = NULL; - std::vector > __pyx_v_extra_args_map; - std::vector __pyx_v_args_map; - PyObject *__pyx_v_args = NULL; - PyObject *__pyx_v_a = NULL; - std::optional __pyx_v_res; - Eigen::VectorXd __pyx_8genexpr1__pyx_v_tmpvec; - __Pyx_LocalBuf_ND __pyx_pybuffernd_Ri_b; - __Pyx_Buffer __pyx_pybuffer_Ri_b; - __Pyx_LocalBuf_ND __pyx_pybuffernd_zi_b; - __Pyx_Buffer __pyx_pybuffer_zi_b; - PyObject *__pyx_r = NULL; - __Pyx_TraceDeclarations - __Pyx_RefNannyDeclarations - PyObject *__pyx_t_1 = NULL; - Py_ssize_t __pyx_t_2; - PyObject *(*__pyx_t_3)(PyObject *); - PyObject *__pyx_t_4 = NULL; - PyObject *__pyx_t_5 = NULL; - PyObject *__pyx_t_6 = NULL; - PyObject *__pyx_t_7 = NULL; - PyObject *__pyx_t_8 = NULL; - PyArrayObject *__pyx_t_9 = NULL; - int __pyx_t_10; - PyObject *__pyx_t_11 = NULL; - PyObject *__pyx_t_12 = NULL; - PyObject *__pyx_t_13 = NULL; - char *__pyx_t_14; - PyArrayObject *__pyx_t_15 = NULL; - int __pyx_t_16; - Py_ssize_t __pyx_t_17; - PyObject *(*__pyx_t_18)(PyObject *); - double __pyx_t_19; - int __pyx_t_20; - PyObject *__pyx_t_21 = NULL; - std::vector ::iterator __pyx_t_22; - std::vector __pyx_t_23; - Eigen::VectorXd __pyx_t_24; - PyObject *__pyx_t_25 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_TraceFrameInit(__pyx_codeobj__29) - __Pyx_RefNannySetupContext("predict_and_update_batch", 1); - __Pyx_TraceCall("predict_and_update_batch", __pyx_f[0], 144, 0, __PYX_ERR(0, 144, __pyx_L1_error)); - __pyx_pybuffer_zi_b.pybuffer.buf = NULL; - __pyx_pybuffer_zi_b.refcount = 0; - __pyx_pybuffernd_zi_b.data = NULL; - __pyx_pybuffernd_zi_b.rcbuffer = &__pyx_pybuffer_zi_b; - __pyx_pybuffer_Ri_b.pybuffer.buf = NULL; - __pyx_pybuffer_Ri_b.refcount = 0; - __pyx_pybuffernd_Ri_b.data = NULL; - __pyx_pybuffernd_Ri_b.rcbuffer = &__pyx_pybuffer_Ri_b; - - /* "rednose/helpers/ekf_sym_pyx.pyx":147 - * cdef vector[MapVectorXd] z_map - * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] zi_b - * for zi in z: # <<<<<<<<<<<<<< - * zi_b = np.ascontiguousarray(zi, dtype=np.double) - * z_map.push_back(MapVectorXd( zi_b.data, zi.shape[0])) - */ - if (likely(PyList_CheckExact(__pyx_v_z)) || PyTuple_CheckExact(__pyx_v_z)) { - __pyx_t_1 = __pyx_v_z; __Pyx_INCREF(__pyx_t_1); - __pyx_t_2 = 0; - __pyx_t_3 = NULL; - } else { - __pyx_t_2 = -1; __pyx_t_1 = PyObject_GetIter(__pyx_v_z); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 147, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_3 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 147, __pyx_L1_error) - } - for (;;) { - if (likely(!__pyx_t_3)) { - if (likely(PyList_CheckExact(__pyx_t_1))) { - { - Py_ssize_t __pyx_temp = __Pyx_PyList_GET_SIZE(__pyx_t_1); - #if !CYTHON_ASSUME_SAFE_MACROS - if (unlikely((__pyx_temp < 0))) __PYX_ERR(0, 147, __pyx_L1_error) - #endif - if (__pyx_t_2 >= __pyx_temp) break; - } - #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS - __pyx_t_4 = PyList_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_4); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(0, 147, __pyx_L1_error) - #else - __pyx_t_4 = __Pyx_PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 147, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - #endif - } else { - { - Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_1); - #if !CYTHON_ASSUME_SAFE_MACROS - if (unlikely((__pyx_temp < 0))) __PYX_ERR(0, 147, __pyx_L1_error) - #endif - if (__pyx_t_2 >= __pyx_temp) break; - } - #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS - __pyx_t_4 = PyTuple_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_4); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(0, 147, __pyx_L1_error) - #else - __pyx_t_4 = __Pyx_PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 147, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - #endif - } - } else { - __pyx_t_4 = __pyx_t_3(__pyx_t_1); - if (unlikely(!__pyx_t_4)) { - PyObject* exc_type = PyErr_Occurred(); - if (exc_type) { - if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); - else __PYX_ERR(0, 147, __pyx_L1_error) - } - break; - } - __Pyx_GOTREF(__pyx_t_4); - } - __Pyx_XDECREF_SET(__pyx_v_zi, __pyx_t_4); - __pyx_t_4 = 0; - - /* "rednose/helpers/ekf_sym_pyx.pyx":148 - * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] zi_b - * for zi in z: - * zi_b = np.ascontiguousarray(zi, dtype=np.double) # <<<<<<<<<<<<<< - * z_map.push_back(MapVectorXd( zi_b.data, zi.shape[0])) - * - */ - __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_np); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 148, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 148, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __pyx_t_4 = PyTuple_New(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 148, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __Pyx_INCREF(__pyx_v_zi); - __Pyx_GIVEREF(__pyx_v_zi); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_v_zi)) __PYX_ERR(0, 148, __pyx_L1_error); - __pyx_t_6 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 148, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_6); - __Pyx_GetModuleGlobalName(__pyx_t_7, __pyx_n_s_np); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 148, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_t_7, __pyx_n_s_double); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 148, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_8); - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - if (PyDict_SetItem(__pyx_t_6, __pyx_n_s_dtype, __pyx_t_8) < 0) __PYX_ERR(0, 148, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; - __pyx_t_8 = __Pyx_PyObject_Call(__pyx_t_5, __pyx_t_4, __pyx_t_6); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 148, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_8); - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; - if (!(likely(((__pyx_t_8) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_8, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 148, __pyx_L1_error) - __pyx_t_9 = ((PyArrayObject *)__pyx_t_8); - { - __Pyx_BufFmt_StackElem __pyx_stack[1]; - __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_zi_b.rcbuffer->pybuffer); - __pyx_t_10 = __Pyx_GetBufferAndValidate(&__pyx_pybuffernd_zi_b.rcbuffer->pybuffer, (PyObject*)__pyx_t_9, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_C_CONTIGUOUS, 1, 0, __pyx_stack); - if (unlikely(__pyx_t_10 < 0)) { - PyErr_Fetch(&__pyx_t_11, &__pyx_t_12, &__pyx_t_13); - if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_zi_b.rcbuffer->pybuffer, (PyObject*)__pyx_v_zi_b, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_C_CONTIGUOUS, 1, 0, __pyx_stack) == -1)) { - Py_XDECREF(__pyx_t_11); Py_XDECREF(__pyx_t_12); Py_XDECREF(__pyx_t_13); - __Pyx_RaiseBufferFallbackError(); - } else { - PyErr_Restore(__pyx_t_11, __pyx_t_12, __pyx_t_13); - } - __pyx_t_11 = __pyx_t_12 = __pyx_t_13 = 0; - } - __pyx_pybuffernd_zi_b.diminfo[0].strides = __pyx_pybuffernd_zi_b.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_zi_b.diminfo[0].shape = __pyx_pybuffernd_zi_b.rcbuffer->pybuffer.shape[0]; - if (unlikely((__pyx_t_10 < 0))) __PYX_ERR(0, 148, __pyx_L1_error) - } - __pyx_t_9 = 0; - __Pyx_XDECREF_SET(__pyx_v_zi_b, ((PyArrayObject *)__pyx_t_8)); - __pyx_t_8 = 0; - - /* "rednose/helpers/ekf_sym_pyx.pyx":149 - * for zi in z: - * zi_b = np.ascontiguousarray(zi, dtype=np.double) - * z_map.push_back(MapVectorXd( zi_b.data, zi.shape[0])) # <<<<<<<<<<<<<< - * - * cdef vector[MapMatrixXdr] R_map - */ - __pyx_t_14 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_zi_b)); if (unlikely(__pyx_t_14 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 149, __pyx_L1_error) - __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_zi, __pyx_n_s_shape); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 149, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_8); - __pyx_t_6 = __Pyx_GetItemInt(__pyx_t_8, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 149, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_6); - __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; - __pyx_t_10 = __Pyx_PyInt_As_int(__pyx_t_6); if (unlikely((__pyx_t_10 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 149, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; - try { - __pyx_v_z_map.push_back(Eigen::Map(((double *)__pyx_t_14), __pyx_t_10)); - } catch(...) { - __Pyx_CppExn2PyErr(); - __PYX_ERR(0, 149, __pyx_L1_error) - } - - /* "rednose/helpers/ekf_sym_pyx.pyx":147 - * cdef vector[MapVectorXd] z_map - * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] zi_b - * for zi in z: # <<<<<<<<<<<<<< - * zi_b = np.ascontiguousarray(zi, dtype=np.double) - * z_map.push_back(MapVectorXd( zi_b.data, zi.shape[0])) - */ - } - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - - /* "rednose/helpers/ekf_sym_pyx.pyx":153 - * cdef vector[MapMatrixXdr] R_map - * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] Ri_b - * for Ri in R: # <<<<<<<<<<<<<< - * Ri_b = np.ascontiguousarray(Ri, dtype=np.double) - * R_map.push_back(MapMatrixXdr( Ri_b.data, Ri.shape[0], Ri.shape[1])) - */ - if (likely(PyList_CheckExact(__pyx_v_R)) || PyTuple_CheckExact(__pyx_v_R)) { - __pyx_t_1 = __pyx_v_R; __Pyx_INCREF(__pyx_t_1); - __pyx_t_2 = 0; - __pyx_t_3 = NULL; - } else { - __pyx_t_2 = -1; __pyx_t_1 = PyObject_GetIter(__pyx_v_R); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 153, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_3 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 153, __pyx_L1_error) - } - for (;;) { - if (likely(!__pyx_t_3)) { - if (likely(PyList_CheckExact(__pyx_t_1))) { - { - Py_ssize_t __pyx_temp = __Pyx_PyList_GET_SIZE(__pyx_t_1); - #if !CYTHON_ASSUME_SAFE_MACROS - if (unlikely((__pyx_temp < 0))) __PYX_ERR(0, 153, __pyx_L1_error) - #endif - if (__pyx_t_2 >= __pyx_temp) break; - } - #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS - __pyx_t_6 = PyList_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_6); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(0, 153, __pyx_L1_error) - #else - __pyx_t_6 = __Pyx_PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 153, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_6); - #endif - } else { - { - Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_1); - #if !CYTHON_ASSUME_SAFE_MACROS - if (unlikely((__pyx_temp < 0))) __PYX_ERR(0, 153, __pyx_L1_error) - #endif - if (__pyx_t_2 >= __pyx_temp) break; - } - #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS - __pyx_t_6 = PyTuple_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_6); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(0, 153, __pyx_L1_error) - #else - __pyx_t_6 = __Pyx_PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 153, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_6); - #endif - } - } else { - __pyx_t_6 = __pyx_t_3(__pyx_t_1); - if (unlikely(!__pyx_t_6)) { - PyObject* exc_type = PyErr_Occurred(); - if (exc_type) { - if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); - else __PYX_ERR(0, 153, __pyx_L1_error) - } - break; - } - __Pyx_GOTREF(__pyx_t_6); - } - __Pyx_XDECREF_SET(__pyx_v_Ri, __pyx_t_6); - __pyx_t_6 = 0; - - /* "rednose/helpers/ekf_sym_pyx.pyx":154 - * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] Ri_b - * for Ri in R: - * Ri_b = np.ascontiguousarray(Ri, dtype=np.double) # <<<<<<<<<<<<<< - * R_map.push_back(MapMatrixXdr( Ri_b.data, Ri.shape[0], Ri.shape[1])) - * - */ - __Pyx_GetModuleGlobalName(__pyx_t_6, __pyx_n_s_np); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 154, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_6); - __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_t_6, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 154, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_8); - __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; - __pyx_t_6 = PyTuple_New(1); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 154, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_6); - __Pyx_INCREF(__pyx_v_Ri); - __Pyx_GIVEREF(__pyx_v_Ri); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_6, 0, __pyx_v_Ri)) __PYX_ERR(0, 154, __pyx_L1_error); - __pyx_t_4 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 154, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __Pyx_GetModuleGlobalName(__pyx_t_5, __pyx_n_s_np); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 154, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_double); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 154, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - if (PyDict_SetItem(__pyx_t_4, __pyx_n_s_dtype, __pyx_t_7) < 0) __PYX_ERR(0, 154, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - __pyx_t_7 = __Pyx_PyObject_Call(__pyx_t_8, __pyx_t_6, __pyx_t_4); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 154, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; - __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - if (!(likely(((__pyx_t_7) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_7, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 154, __pyx_L1_error) - __pyx_t_15 = ((PyArrayObject *)__pyx_t_7); - { - __Pyx_BufFmt_StackElem __pyx_stack[1]; - __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_Ri_b.rcbuffer->pybuffer); - __pyx_t_10 = __Pyx_GetBufferAndValidate(&__pyx_pybuffernd_Ri_b.rcbuffer->pybuffer, (PyObject*)__pyx_t_15, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_C_CONTIGUOUS, 2, 0, __pyx_stack); - if (unlikely(__pyx_t_10 < 0)) { - PyErr_Fetch(&__pyx_t_13, &__pyx_t_12, &__pyx_t_11); - if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_Ri_b.rcbuffer->pybuffer, (PyObject*)__pyx_v_Ri_b, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_C_CONTIGUOUS, 2, 0, __pyx_stack) == -1)) { - Py_XDECREF(__pyx_t_13); Py_XDECREF(__pyx_t_12); Py_XDECREF(__pyx_t_11); - __Pyx_RaiseBufferFallbackError(); - } else { - PyErr_Restore(__pyx_t_13, __pyx_t_12, __pyx_t_11); - } - __pyx_t_13 = __pyx_t_12 = __pyx_t_11 = 0; - } - __pyx_pybuffernd_Ri_b.diminfo[0].strides = __pyx_pybuffernd_Ri_b.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_Ri_b.diminfo[0].shape = __pyx_pybuffernd_Ri_b.rcbuffer->pybuffer.shape[0]; __pyx_pybuffernd_Ri_b.diminfo[1].strides = __pyx_pybuffernd_Ri_b.rcbuffer->pybuffer.strides[1]; __pyx_pybuffernd_Ri_b.diminfo[1].shape = __pyx_pybuffernd_Ri_b.rcbuffer->pybuffer.shape[1]; - if (unlikely((__pyx_t_10 < 0))) __PYX_ERR(0, 154, __pyx_L1_error) - } - __pyx_t_15 = 0; - __Pyx_XDECREF_SET(__pyx_v_Ri_b, ((PyArrayObject *)__pyx_t_7)); - __pyx_t_7 = 0; - - /* "rednose/helpers/ekf_sym_pyx.pyx":155 - * for Ri in R: - * Ri_b = np.ascontiguousarray(Ri, dtype=np.double) - * R_map.push_back(MapMatrixXdr( Ri_b.data, Ri.shape[0], Ri.shape[1])) # <<<<<<<<<<<<<< - * - * cdef vector[vector[double]] extra_args_map - */ - __pyx_t_14 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_Ri_b)); if (unlikely(__pyx_t_14 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 155, __pyx_L1_error) - __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_v_Ri, __pyx_n_s_shape); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 155, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __pyx_t_4 = __Pyx_GetItemInt(__pyx_t_7, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 155, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - __pyx_t_10 = __Pyx_PyInt_As_int(__pyx_t_4); if (unlikely((__pyx_t_10 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 155, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_v_Ri, __pyx_n_s_shape); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 155, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __pyx_t_7 = __Pyx_GetItemInt(__pyx_t_4, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 155, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __pyx_t_16 = __Pyx_PyInt_As_int(__pyx_t_7); if (unlikely((__pyx_t_16 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 155, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - try { - __pyx_v_R_map.push_back(Eigen::Map >(((double *)__pyx_t_14), __pyx_t_10, __pyx_t_16)); - } catch(...) { - __Pyx_CppExn2PyErr(); - __PYX_ERR(0, 155, __pyx_L1_error) - } - - /* "rednose/helpers/ekf_sym_pyx.pyx":153 - * cdef vector[MapMatrixXdr] R_map - * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] Ri_b - * for Ri in R: # <<<<<<<<<<<<<< - * Ri_b = np.ascontiguousarray(Ri, dtype=np.double) - * R_map.push_back(MapMatrixXdr( Ri_b.data, Ri.shape[0], Ri.shape[1])) - */ - } - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - - /* "rednose/helpers/ekf_sym_pyx.pyx":159 - * cdef vector[vector[double]] extra_args_map - * cdef vector[double] args_map - * for args in extra_args: # <<<<<<<<<<<<<< - * args_map.clear() - * for a in args: - */ - if (likely(PyList_CheckExact(__pyx_v_extra_args)) || PyTuple_CheckExact(__pyx_v_extra_args)) { - __pyx_t_1 = __pyx_v_extra_args; __Pyx_INCREF(__pyx_t_1); - __pyx_t_2 = 0; - __pyx_t_3 = NULL; - } else { - __pyx_t_2 = -1; __pyx_t_1 = PyObject_GetIter(__pyx_v_extra_args); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 159, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_3 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 159, __pyx_L1_error) - } - for (;;) { - if (likely(!__pyx_t_3)) { - if (likely(PyList_CheckExact(__pyx_t_1))) { - { - Py_ssize_t __pyx_temp = __Pyx_PyList_GET_SIZE(__pyx_t_1); - #if !CYTHON_ASSUME_SAFE_MACROS - if (unlikely((__pyx_temp < 0))) __PYX_ERR(0, 159, __pyx_L1_error) - #endif - if (__pyx_t_2 >= __pyx_temp) break; - } - #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS - __pyx_t_7 = PyList_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_7); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(0, 159, __pyx_L1_error) - #else - __pyx_t_7 = __Pyx_PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 159, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - #endif - } else { - { - Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_1); - #if !CYTHON_ASSUME_SAFE_MACROS - if (unlikely((__pyx_temp < 0))) __PYX_ERR(0, 159, __pyx_L1_error) - #endif - if (__pyx_t_2 >= __pyx_temp) break; - } - #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS - __pyx_t_7 = PyTuple_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_7); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(0, 159, __pyx_L1_error) - #else - __pyx_t_7 = __Pyx_PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 159, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - #endif - } - } else { - __pyx_t_7 = __pyx_t_3(__pyx_t_1); - if (unlikely(!__pyx_t_7)) { - PyObject* exc_type = PyErr_Occurred(); - if (exc_type) { - if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); - else __PYX_ERR(0, 159, __pyx_L1_error) - } - break; - } - __Pyx_GOTREF(__pyx_t_7); - } - __Pyx_XDECREF_SET(__pyx_v_args, __pyx_t_7); - __pyx_t_7 = 0; - - /* "rednose/helpers/ekf_sym_pyx.pyx":160 - * cdef vector[double] args_map - * for args in extra_args: - * args_map.clear() # <<<<<<<<<<<<<< - * for a in args: - * args_map.push_back(a) - */ - __pyx_v_args_map.clear(); - - /* "rednose/helpers/ekf_sym_pyx.pyx":161 - * for args in extra_args: - * args_map.clear() - * for a in args: # <<<<<<<<<<<<<< - * args_map.push_back(a) - * extra_args_map.push_back(args_map) - */ - if (likely(PyList_CheckExact(__pyx_v_args)) || PyTuple_CheckExact(__pyx_v_args)) { - __pyx_t_7 = __pyx_v_args; __Pyx_INCREF(__pyx_t_7); - __pyx_t_17 = 0; - __pyx_t_18 = NULL; - } else { - __pyx_t_17 = -1; __pyx_t_7 = PyObject_GetIter(__pyx_v_args); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 161, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __pyx_t_18 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_7); if (unlikely(!__pyx_t_18)) __PYX_ERR(0, 161, __pyx_L1_error) - } - for (;;) { - if (likely(!__pyx_t_18)) { - if (likely(PyList_CheckExact(__pyx_t_7))) { - { - Py_ssize_t __pyx_temp = __Pyx_PyList_GET_SIZE(__pyx_t_7); - #if !CYTHON_ASSUME_SAFE_MACROS - if (unlikely((__pyx_temp < 0))) __PYX_ERR(0, 161, __pyx_L1_error) - #endif - if (__pyx_t_17 >= __pyx_temp) break; - } - #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS - __pyx_t_4 = PyList_GET_ITEM(__pyx_t_7, __pyx_t_17); __Pyx_INCREF(__pyx_t_4); __pyx_t_17++; if (unlikely((0 < 0))) __PYX_ERR(0, 161, __pyx_L1_error) - #else - __pyx_t_4 = __Pyx_PySequence_ITEM(__pyx_t_7, __pyx_t_17); __pyx_t_17++; if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 161, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - #endif - } else { - { - Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_7); - #if !CYTHON_ASSUME_SAFE_MACROS - if (unlikely((__pyx_temp < 0))) __PYX_ERR(0, 161, __pyx_L1_error) - #endif - if (__pyx_t_17 >= __pyx_temp) break; - } - #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS - __pyx_t_4 = PyTuple_GET_ITEM(__pyx_t_7, __pyx_t_17); __Pyx_INCREF(__pyx_t_4); __pyx_t_17++; if (unlikely((0 < 0))) __PYX_ERR(0, 161, __pyx_L1_error) - #else - __pyx_t_4 = __Pyx_PySequence_ITEM(__pyx_t_7, __pyx_t_17); __pyx_t_17++; if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 161, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - #endif - } - } else { - __pyx_t_4 = __pyx_t_18(__pyx_t_7); - if (unlikely(!__pyx_t_4)) { - PyObject* exc_type = PyErr_Occurred(); - if (exc_type) { - if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); - else __PYX_ERR(0, 161, __pyx_L1_error) - } - break; - } - __Pyx_GOTREF(__pyx_t_4); - } - __Pyx_XDECREF_SET(__pyx_v_a, __pyx_t_4); - __pyx_t_4 = 0; - - /* "rednose/helpers/ekf_sym_pyx.pyx":162 - * args_map.clear() - * for a in args: - * args_map.push_back(a) # <<<<<<<<<<<<<< - * extra_args_map.push_back(args_map) - * - */ - __pyx_t_19 = __pyx_PyFloat_AsDouble(__pyx_v_a); if (unlikely((__pyx_t_19 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 162, __pyx_L1_error) - try { - __pyx_v_args_map.push_back(__pyx_t_19); - } catch(...) { - __Pyx_CppExn2PyErr(); - __PYX_ERR(0, 162, __pyx_L1_error) - } - - /* "rednose/helpers/ekf_sym_pyx.pyx":161 - * for args in extra_args: - * args_map.clear() - * for a in args: # <<<<<<<<<<<<<< - * args_map.push_back(a) - * extra_args_map.push_back(args_map) - */ - } - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - - /* "rednose/helpers/ekf_sym_pyx.pyx":163 - * for a in args: - * args_map.push_back(a) - * extra_args_map.push_back(args_map) # <<<<<<<<<<<<<< - * - * cdef optional[Estimate] res = self.ekf.predict_and_update_batch(t, kind, z_map, R_map, extra_args_map, augment) - */ - try { - __pyx_v_extra_args_map.push_back(__pyx_v_args_map); - } catch(...) { - __Pyx_CppExn2PyErr(); - __PYX_ERR(0, 163, __pyx_L1_error) - } - - /* "rednose/helpers/ekf_sym_pyx.pyx":159 - * cdef vector[vector[double]] extra_args_map - * cdef vector[double] args_map - * for args in extra_args: # <<<<<<<<<<<<<< - * args_map.clear() - * for a in args: - */ - } - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - - /* "rednose/helpers/ekf_sym_pyx.pyx":165 - * extra_args_map.push_back(args_map) - * - * cdef optional[Estimate] res = self.ekf.predict_and_update_batch(t, kind, z_map, R_map, extra_args_map, augment) # <<<<<<<<<<<<<< - * if not res.has_value(): - * return None - */ - __pyx_v_res = __pyx_v_self->ekf->predict_and_update_batch(__pyx_v_t, __pyx_v_kind, __pyx_v_z_map, __pyx_v_R_map, __pyx_v_extra_args_map, __pyx_v_augment); - - /* "rednose/helpers/ekf_sym_pyx.pyx":166 - * - * cdef optional[Estimate] res = self.ekf.predict_and_update_batch(t, kind, z_map, R_map, extra_args_map, augment) - * if not res.has_value(): # <<<<<<<<<<<<<< - * return None - * - */ - __pyx_t_20 = (!(__pyx_v_res.has_value() != 0)); - if (__pyx_t_20) { - - /* "rednose/helpers/ekf_sym_pyx.pyx":167 - * cdef optional[Estimate] res = self.ekf.predict_and_update_batch(t, kind, z_map, R_map, extra_args_map, augment) - * if not res.has_value(): - * return None # <<<<<<<<<<<<<< - * - * cdef VectorXd tmpvec - */ - __Pyx_XDECREF(__pyx_r); - __pyx_r = Py_None; __Pyx_INCREF(Py_None); - goto __pyx_L0; - - /* "rednose/helpers/ekf_sym_pyx.pyx":166 - * - * cdef optional[Estimate] res = self.ekf.predict_and_update_batch(t, kind, z_map, R_map, extra_args_map, augment) - * if not res.has_value(): # <<<<<<<<<<<<<< - * return None - * - */ - } - - /* "rednose/helpers/ekf_sym_pyx.pyx":170 - * - * cdef VectorXd tmpvec - * return ( # <<<<<<<<<<<<<< - * vector_to_numpy(res.value().xk1), - * vector_to_numpy(res.value().xk), - */ - __Pyx_XDECREF(__pyx_r); - - /* "rednose/helpers/ekf_sym_pyx.pyx":171 - * cdef VectorXd tmpvec - * return ( - * vector_to_numpy(res.value().xk1), # <<<<<<<<<<<<<< - * vector_to_numpy(res.value().xk), - * matrix_to_numpy(res.value().Pk1), - */ - __pyx_t_1 = ((PyObject *)__pyx_f_7rednose_7helpers_11ekf_sym_pyx_vector_to_numpy(__pyx_v_res.value().xk1)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 171, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - - /* "rednose/helpers/ekf_sym_pyx.pyx":172 - * return ( - * vector_to_numpy(res.value().xk1), - * vector_to_numpy(res.value().xk), # <<<<<<<<<<<<<< - * matrix_to_numpy(res.value().Pk1), - * matrix_to_numpy(res.value().Pk), - */ - __pyx_t_7 = ((PyObject *)__pyx_f_7rednose_7helpers_11ekf_sym_pyx_vector_to_numpy(__pyx_v_res.value().xk)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 172, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - - /* "rednose/helpers/ekf_sym_pyx.pyx":173 - * vector_to_numpy(res.value().xk1), - * vector_to_numpy(res.value().xk), - * matrix_to_numpy(res.value().Pk1), # <<<<<<<<<<<<<< - * matrix_to_numpy(res.value().Pk), - * res.value().t, - */ - __pyx_t_4 = ((PyObject *)__pyx_f_7rednose_7helpers_11ekf_sym_pyx_matrix_to_numpy(__pyx_v_res.value().Pk1)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 173, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - - /* "rednose/helpers/ekf_sym_pyx.pyx":174 - * vector_to_numpy(res.value().xk), - * matrix_to_numpy(res.value().Pk1), - * matrix_to_numpy(res.value().Pk), # <<<<<<<<<<<<<< - * res.value().t, - * res.value().kind, - */ - __pyx_t_6 = ((PyObject *)__pyx_f_7rednose_7helpers_11ekf_sym_pyx_matrix_to_numpy(__pyx_v_res.value().Pk)); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 174, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_6); - - /* "rednose/helpers/ekf_sym_pyx.pyx":175 - * matrix_to_numpy(res.value().Pk1), - * matrix_to_numpy(res.value().Pk), - * res.value().t, # <<<<<<<<<<<<<< - * res.value().kind, - * [vector_to_numpy(tmpvec) for tmpvec in res.value().y], - */ - __pyx_t_8 = PyFloat_FromDouble(__pyx_v_res.value().t); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 175, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_8); - - /* "rednose/helpers/ekf_sym_pyx.pyx":176 - * matrix_to_numpy(res.value().Pk), - * res.value().t, - * res.value().kind, # <<<<<<<<<<<<<< - * [vector_to_numpy(tmpvec) for tmpvec in res.value().y], - * z, # TODO: take return values? - */ - __pyx_t_5 = __Pyx_PyInt_From_int(__pyx_v_res.value().kind); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 176, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - { /* enter inner scope */ - - /* "rednose/helpers/ekf_sym_pyx.pyx":177 - * res.value().t, - * res.value().kind, - * [vector_to_numpy(tmpvec) for tmpvec in res.value().y], # <<<<<<<<<<<<<< - * z, # TODO: take return values? - * extra_args, - */ - __pyx_t_21 = PyList_New(0); if (unlikely(!__pyx_t_21)) __PYX_ERR(0, 177, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_21); - __pyx_t_23 = __pyx_v_res.value().y; - __pyx_t_22 = __pyx_t_23.begin(); - for (;;) { - if (!(__pyx_t_22 != __pyx_t_23.end())) break; - __pyx_t_24 = *__pyx_t_22; - ++__pyx_t_22; - __pyx_8genexpr1__pyx_v_tmpvec = __PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_24); - __pyx_t_25 = ((PyObject *)__pyx_f_7rednose_7helpers_11ekf_sym_pyx_vector_to_numpy(__pyx_8genexpr1__pyx_v_tmpvec)); if (unlikely(!__pyx_t_25)) __PYX_ERR(0, 177, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_25); - if (unlikely(__Pyx_ListComp_Append(__pyx_t_21, (PyObject*)__pyx_t_25))) __PYX_ERR(0, 177, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_25); __pyx_t_25 = 0; - } - } /* exit inner scope */ - - /* "rednose/helpers/ekf_sym_pyx.pyx":171 - * cdef VectorXd tmpvec - * return ( - * vector_to_numpy(res.value().xk1), # <<<<<<<<<<<<<< - * vector_to_numpy(res.value().xk), - * matrix_to_numpy(res.value().Pk1), - */ - __pyx_t_25 = PyTuple_New(9); if (unlikely(!__pyx_t_25)) __PYX_ERR(0, 171, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_25); - __Pyx_GIVEREF(__pyx_t_1); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_25, 0, __pyx_t_1)) __PYX_ERR(0, 171, __pyx_L1_error); - __Pyx_GIVEREF(__pyx_t_7); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_25, 1, __pyx_t_7)) __PYX_ERR(0, 171, __pyx_L1_error); - __Pyx_GIVEREF(__pyx_t_4); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_25, 2, __pyx_t_4)) __PYX_ERR(0, 171, __pyx_L1_error); - __Pyx_GIVEREF(__pyx_t_6); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_25, 3, __pyx_t_6)) __PYX_ERR(0, 171, __pyx_L1_error); - __Pyx_GIVEREF(__pyx_t_8); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_25, 4, __pyx_t_8)) __PYX_ERR(0, 171, __pyx_L1_error); - __Pyx_GIVEREF(__pyx_t_5); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_25, 5, __pyx_t_5)) __PYX_ERR(0, 171, __pyx_L1_error); - __Pyx_GIVEREF(__pyx_t_21); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_25, 6, __pyx_t_21)) __PYX_ERR(0, 171, __pyx_L1_error); - __Pyx_INCREF(__pyx_v_z); - __Pyx_GIVEREF(__pyx_v_z); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_25, 7, __pyx_v_z)) __PYX_ERR(0, 171, __pyx_L1_error); - __Pyx_INCREF(__pyx_v_extra_args); - __Pyx_GIVEREF(__pyx_v_extra_args); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_25, 8, __pyx_v_extra_args)) __PYX_ERR(0, 171, __pyx_L1_error); - __pyx_t_1 = 0; - __pyx_t_7 = 0; - __pyx_t_4 = 0; - __pyx_t_6 = 0; - __pyx_t_8 = 0; - __pyx_t_5 = 0; - __pyx_t_21 = 0; - __pyx_r = __pyx_t_25; - __pyx_t_25 = 0; - goto __pyx_L0; - - /* "rednose/helpers/ekf_sym_pyx.pyx":144 - * self.ekf.predict(t) - * - * def predict_and_update_batch(self, double t, int kind, z, R, extra_args=[[]], bool augment=False): # <<<<<<<<<<<<<< - * cdef vector[MapVectorXd] z_map - * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] zi_b - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_1); - __Pyx_XDECREF(__pyx_t_4); - __Pyx_XDECREF(__pyx_t_5); - __Pyx_XDECREF(__pyx_t_6); - __Pyx_XDECREF(__pyx_t_7); - __Pyx_XDECREF(__pyx_t_8); - __Pyx_XDECREF(__pyx_t_21); - __Pyx_XDECREF(__pyx_t_25); - { PyObject *__pyx_type, *__pyx_value, *__pyx_tb; - __Pyx_PyThreadState_declare - __Pyx_PyThreadState_assign - __Pyx_ErrFetch(&__pyx_type, &__pyx_value, &__pyx_tb); - __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_Ri_b.rcbuffer->pybuffer); - __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_zi_b.rcbuffer->pybuffer); - __Pyx_ErrRestore(__pyx_type, __pyx_value, __pyx_tb);} - __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.predict_and_update_batch", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = NULL; - goto __pyx_L2; - __pyx_L0:; - __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_Ri_b.rcbuffer->pybuffer); - __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_zi_b.rcbuffer->pybuffer); - __pyx_L2:; - __Pyx_XDECREF((PyObject *)__pyx_v_zi_b); - __Pyx_XDECREF(__pyx_v_zi); - __Pyx_XDECREF((PyObject *)__pyx_v_Ri_b); - __Pyx_XDECREF(__pyx_v_Ri); - __Pyx_XDECREF(__pyx_v_args); - __Pyx_XDECREF(__pyx_v_a); - __Pyx_XGIVEREF(__pyx_r); - __Pyx_TraceReturn(__pyx_r, 0); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "rednose/helpers/ekf_sym_pyx.pyx":182 - * ) - * - * def augment(self): # <<<<<<<<<<<<<< - * raise NotImplementedError() # TODO - * - */ - -/* Python wrapper */ -static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_21augment(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -); /*proto*/ -static PyMethodDef __pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_21augment = {"augment", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_21augment, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; -static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_21augment(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -) { - #if !CYTHON_METH_FASTCALL - CYTHON_UNUSED Py_ssize_t __pyx_nargs; - #endif - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - PyObject *__pyx_r = 0; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("augment (wrapper)", 0); - #if !CYTHON_METH_FASTCALL - #if CYTHON_ASSUME_SAFE_MACROS - __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); - #else - __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; - #endif - #endif - __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); - if (unlikely(__pyx_nargs > 0)) { - __Pyx_RaiseArgtupleInvalid("augment", 1, 0, 0, __pyx_nargs); return NULL;} - if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "augment", 0))) return NULL; - __pyx_r = __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_20augment(((struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *)__pyx_v_self)); - - /* function exit code */ - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_20augment(CYTHON_UNUSED struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self) { - PyObject *__pyx_r = NULL; - __Pyx_TraceDeclarations - __Pyx_RefNannyDeclarations - PyObject *__pyx_t_1 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_TraceFrameInit(__pyx_codeobj__30) - __Pyx_RefNannySetupContext("augment", 1); - __Pyx_TraceCall("augment", __pyx_f[0], 182, 0, __PYX_ERR(0, 182, __pyx_L1_error)); - - /* "rednose/helpers/ekf_sym_pyx.pyx":183 - * - * def augment(self): - * raise NotImplementedError() # TODO # <<<<<<<<<<<<<< - * - * def get_augment_times(self): - */ - __pyx_t_1 = __Pyx_PyObject_CallNoArg(__pyx_builtin_NotImplementedError); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 183, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __Pyx_Raise(__pyx_t_1, 0, 0, 0); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __PYX_ERR(0, 183, __pyx_L1_error) - - /* "rednose/helpers/ekf_sym_pyx.pyx":182 - * ) - * - * def augment(self): # <<<<<<<<<<<<<< - * raise NotImplementedError() # TODO - * - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_1); - __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.augment", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = NULL; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_TraceReturn(__pyx_r, 0); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "rednose/helpers/ekf_sym_pyx.pyx":185 - * raise NotImplementedError() # TODO - * - * def get_augment_times(self): # <<<<<<<<<<<<<< - * raise NotImplementedError() # TODO - * - */ - -/* Python wrapper */ -static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_23get_augment_times(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -); /*proto*/ -static PyMethodDef __pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_23get_augment_times = {"get_augment_times", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_23get_augment_times, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; -static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_23get_augment_times(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -) { - #if !CYTHON_METH_FASTCALL - CYTHON_UNUSED Py_ssize_t __pyx_nargs; - #endif - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - PyObject *__pyx_r = 0; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("get_augment_times (wrapper)", 0); - #if !CYTHON_METH_FASTCALL - #if CYTHON_ASSUME_SAFE_MACROS - __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); - #else - __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; - #endif - #endif - __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); - if (unlikely(__pyx_nargs > 0)) { - __Pyx_RaiseArgtupleInvalid("get_augment_times", 1, 0, 0, __pyx_nargs); return NULL;} - if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "get_augment_times", 0))) return NULL; - __pyx_r = __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_22get_augment_times(((struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *)__pyx_v_self)); - - /* function exit code */ - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_22get_augment_times(CYTHON_UNUSED struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self) { - PyObject *__pyx_r = NULL; - __Pyx_TraceDeclarations - __Pyx_RefNannyDeclarations - PyObject *__pyx_t_1 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_TraceFrameInit(__pyx_codeobj__31) - __Pyx_RefNannySetupContext("get_augment_times", 1); - __Pyx_TraceCall("get_augment_times", __pyx_f[0], 185, 0, __PYX_ERR(0, 185, __pyx_L1_error)); - - /* "rednose/helpers/ekf_sym_pyx.pyx":186 - * - * def get_augment_times(self): - * raise NotImplementedError() # TODO # <<<<<<<<<<<<<< - * - * def rts_smooth(self, estimates, norm_quats=False): - */ - __pyx_t_1 = __Pyx_PyObject_CallNoArg(__pyx_builtin_NotImplementedError); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 186, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __Pyx_Raise(__pyx_t_1, 0, 0, 0); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __PYX_ERR(0, 186, __pyx_L1_error) - - /* "rednose/helpers/ekf_sym_pyx.pyx":185 - * raise NotImplementedError() # TODO - * - * def get_augment_times(self): # <<<<<<<<<<<<<< - * raise NotImplementedError() # TODO - * - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_1); - __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.get_augment_times", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = NULL; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_TraceReturn(__pyx_r, 0); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "rednose/helpers/ekf_sym_pyx.pyx":188 - * raise NotImplementedError() # TODO - * - * def rts_smooth(self, estimates, norm_quats=False): # <<<<<<<<<<<<<< - * raise NotImplementedError() # TODO - * - */ - -/* Python wrapper */ -static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_25rts_smooth(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -); /*proto*/ -static PyMethodDef __pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_25rts_smooth = {"rts_smooth", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_25rts_smooth, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; -static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_25rts_smooth(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -) { - CYTHON_UNUSED PyObject *__pyx_v_estimates = 0; - CYTHON_UNUSED PyObject *__pyx_v_norm_quats = 0; - #if !CYTHON_METH_FASTCALL - CYTHON_UNUSED Py_ssize_t __pyx_nargs; - #endif - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - PyObject* values[2] = {0,0}; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - PyObject *__pyx_r = 0; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("rts_smooth (wrapper)", 0); - #if !CYTHON_METH_FASTCALL - #if CYTHON_ASSUME_SAFE_MACROS - __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); - #else - __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; - #endif - #endif - __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); - { - PyObject **__pyx_pyargnames[] = {&__pyx_n_s_estimates,&__pyx_n_s_norm_quats,0}; - values[1] = __Pyx_Arg_NewRef_FASTCALL(((PyObject *)Py_False)); - if (__pyx_kwds) { - Py_ssize_t kw_args; - switch (__pyx_nargs) { - case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); - CYTHON_FALLTHROUGH; - case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); - CYTHON_FALLTHROUGH; - case 0: break; - default: goto __pyx_L5_argtuple_error; - } - kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); - switch (__pyx_nargs) { - case 0: - if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_estimates)) != 0)) { - (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); - kw_args--; - } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 188, __pyx_L3_error) - else goto __pyx_L5_argtuple_error; - CYTHON_FALLTHROUGH; - case 1: - if (kw_args > 0) { - PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_norm_quats); - if (value) { values[1] = __Pyx_Arg_NewRef_FASTCALL(value); kw_args--; } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 188, __pyx_L3_error) - } - } - if (unlikely(kw_args > 0)) { - const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "rts_smooth") < 0)) __PYX_ERR(0, 188, __pyx_L3_error) - } - } else { - switch (__pyx_nargs) { - case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); - CYTHON_FALLTHROUGH; - case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); - break; - default: goto __pyx_L5_argtuple_error; - } - } - __pyx_v_estimates = values[0]; - __pyx_v_norm_quats = values[1]; - } - goto __pyx_L6_skip; - __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("rts_smooth", 0, 1, 2, __pyx_nargs); __PYX_ERR(0, 188, __pyx_L3_error) - __pyx_L6_skip:; - goto __pyx_L4_argument_unpacking_done; - __pyx_L3_error:; - { - Py_ssize_t __pyx_temp; - for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { - __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); - } - } - __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.rts_smooth", __pyx_clineno, __pyx_lineno, __pyx_filename); - __Pyx_RefNannyFinishContext(); - return NULL; - __pyx_L4_argument_unpacking_done:; - __pyx_r = __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_24rts_smooth(((struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *)__pyx_v_self), __pyx_v_estimates, __pyx_v_norm_quats); - - /* function exit code */ - { - Py_ssize_t __pyx_temp; - for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { - __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); - } - } - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_24rts_smooth(CYTHON_UNUSED struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v_estimates, CYTHON_UNUSED PyObject *__pyx_v_norm_quats) { - PyObject *__pyx_r = NULL; - __Pyx_TraceDeclarations - __Pyx_RefNannyDeclarations - PyObject *__pyx_t_1 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_TraceFrameInit(__pyx_codeobj__32) - __Pyx_RefNannySetupContext("rts_smooth", 1); - __Pyx_TraceCall("rts_smooth", __pyx_f[0], 188, 0, __PYX_ERR(0, 188, __pyx_L1_error)); - - /* "rednose/helpers/ekf_sym_pyx.pyx":189 - * - * def rts_smooth(self, estimates, norm_quats=False): - * raise NotImplementedError() # TODO # <<<<<<<<<<<<<< - * - * def maha_test(self, x, P, kind, z, R, extra_args=[], maha_thresh=0.95): - */ - __pyx_t_1 = __Pyx_PyObject_CallNoArg(__pyx_builtin_NotImplementedError); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 189, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __Pyx_Raise(__pyx_t_1, 0, 0, 0); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __PYX_ERR(0, 189, __pyx_L1_error) - - /* "rednose/helpers/ekf_sym_pyx.pyx":188 - * raise NotImplementedError() # TODO - * - * def rts_smooth(self, estimates, norm_quats=False): # <<<<<<<<<<<<<< - * raise NotImplementedError() # TODO - * - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_1); - __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.rts_smooth", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = NULL; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_TraceReturn(__pyx_r, 0); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "rednose/helpers/ekf_sym_pyx.pyx":191 - * raise NotImplementedError() # TODO - * - * def maha_test(self, x, P, kind, z, R, extra_args=[], maha_thresh=0.95): # <<<<<<<<<<<<<< - * raise NotImplementedError() # TODO - * - */ - -/* Python wrapper */ -static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_27maha_test(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -); /*proto*/ -static PyMethodDef __pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_27maha_test = {"maha_test", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_27maha_test, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; -static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_27maha_test(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -) { - CYTHON_UNUSED PyObject *__pyx_v_x = 0; - CYTHON_UNUSED PyObject *__pyx_v_P = 0; - CYTHON_UNUSED PyObject *__pyx_v_kind = 0; - CYTHON_UNUSED PyObject *__pyx_v_z = 0; - CYTHON_UNUSED PyObject *__pyx_v_R = 0; - CYTHON_UNUSED PyObject *__pyx_v_extra_args = 0; - CYTHON_UNUSED PyObject *__pyx_v_maha_thresh = 0; - #if !CYTHON_METH_FASTCALL - CYTHON_UNUSED Py_ssize_t __pyx_nargs; - #endif - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - PyObject* values[7] = {0,0,0,0,0,0,0}; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - PyObject *__pyx_r = 0; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("maha_test (wrapper)", 0); - #if !CYTHON_METH_FASTCALL - #if CYTHON_ASSUME_SAFE_MACROS - __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); - #else - __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; - #endif - #endif - __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); - { - PyObject **__pyx_pyargnames[] = {&__pyx_n_s_x,&__pyx_n_s_P,&__pyx_n_s_kind,&__pyx_n_s_z,&__pyx_n_s_R,&__pyx_n_s_extra_args,&__pyx_n_s_maha_thresh,0}; - values[5] = __Pyx_Arg_NewRef_FASTCALL(__pyx_k__33); - values[6] = __Pyx_Arg_NewRef_FASTCALL(((PyObject *)__pyx_float_0_95)); - if (__pyx_kwds) { - Py_ssize_t kw_args; - switch (__pyx_nargs) { - case 7: values[6] = __Pyx_Arg_FASTCALL(__pyx_args, 6); - CYTHON_FALLTHROUGH; - case 6: values[5] = __Pyx_Arg_FASTCALL(__pyx_args, 5); - CYTHON_FALLTHROUGH; - case 5: values[4] = __Pyx_Arg_FASTCALL(__pyx_args, 4); - CYTHON_FALLTHROUGH; - case 4: values[3] = __Pyx_Arg_FASTCALL(__pyx_args, 3); - CYTHON_FALLTHROUGH; - case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); - CYTHON_FALLTHROUGH; - case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); - CYTHON_FALLTHROUGH; - case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); - CYTHON_FALLTHROUGH; - case 0: break; - default: goto __pyx_L5_argtuple_error; - } - kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); - switch (__pyx_nargs) { - case 0: - if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_x)) != 0)) { - (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); - kw_args--; - } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 191, __pyx_L3_error) - else goto __pyx_L5_argtuple_error; - CYTHON_FALLTHROUGH; - case 1: - if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_P)) != 0)) { - (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); - kw_args--; - } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 191, __pyx_L3_error) - else { - __Pyx_RaiseArgtupleInvalid("maha_test", 0, 5, 7, 1); __PYX_ERR(0, 191, __pyx_L3_error) - } - CYTHON_FALLTHROUGH; - case 2: - if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_kind)) != 0)) { - (void)__Pyx_Arg_NewRef_FASTCALL(values[2]); - kw_args--; - } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 191, __pyx_L3_error) - else { - __Pyx_RaiseArgtupleInvalid("maha_test", 0, 5, 7, 2); __PYX_ERR(0, 191, __pyx_L3_error) - } - CYTHON_FALLTHROUGH; - case 3: - if (likely((values[3] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_z)) != 0)) { - (void)__Pyx_Arg_NewRef_FASTCALL(values[3]); - kw_args--; - } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 191, __pyx_L3_error) - else { - __Pyx_RaiseArgtupleInvalid("maha_test", 0, 5, 7, 3); __PYX_ERR(0, 191, __pyx_L3_error) - } - CYTHON_FALLTHROUGH; - case 4: - if (likely((values[4] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_R)) != 0)) { - (void)__Pyx_Arg_NewRef_FASTCALL(values[4]); - kw_args--; - } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 191, __pyx_L3_error) - else { - __Pyx_RaiseArgtupleInvalid("maha_test", 0, 5, 7, 4); __PYX_ERR(0, 191, __pyx_L3_error) - } - CYTHON_FALLTHROUGH; - case 5: - if (kw_args > 0) { - PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_extra_args); - if (value) { values[5] = __Pyx_Arg_NewRef_FASTCALL(value); kw_args--; } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 191, __pyx_L3_error) - } - CYTHON_FALLTHROUGH; - case 6: - if (kw_args > 0) { - PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_maha_thresh); - if (value) { values[6] = __Pyx_Arg_NewRef_FASTCALL(value); kw_args--; } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 191, __pyx_L3_error) - } - } - if (unlikely(kw_args > 0)) { - const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "maha_test") < 0)) __PYX_ERR(0, 191, __pyx_L3_error) - } - } else { - switch (__pyx_nargs) { - case 7: values[6] = __Pyx_Arg_FASTCALL(__pyx_args, 6); - CYTHON_FALLTHROUGH; - case 6: values[5] = __Pyx_Arg_FASTCALL(__pyx_args, 5); - CYTHON_FALLTHROUGH; - case 5: values[4] = __Pyx_Arg_FASTCALL(__pyx_args, 4); - values[3] = __Pyx_Arg_FASTCALL(__pyx_args, 3); - values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); - values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); - values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); - break; - default: goto __pyx_L5_argtuple_error; - } - } - __pyx_v_x = values[0]; - __pyx_v_P = values[1]; - __pyx_v_kind = values[2]; - __pyx_v_z = values[3]; - __pyx_v_R = values[4]; - __pyx_v_extra_args = values[5]; - __pyx_v_maha_thresh = values[6]; - } - goto __pyx_L6_skip; - __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("maha_test", 0, 5, 7, __pyx_nargs); __PYX_ERR(0, 191, __pyx_L3_error) - __pyx_L6_skip:; - goto __pyx_L4_argument_unpacking_done; - __pyx_L3_error:; - { - Py_ssize_t __pyx_temp; - for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { - __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); - } - } - __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.maha_test", __pyx_clineno, __pyx_lineno, __pyx_filename); - __Pyx_RefNannyFinishContext(); - return NULL; - __pyx_L4_argument_unpacking_done:; - __pyx_r = __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_26maha_test(((struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *)__pyx_v_self), __pyx_v_x, __pyx_v_P, __pyx_v_kind, __pyx_v_z, __pyx_v_R, __pyx_v_extra_args, __pyx_v_maha_thresh); - - /* function exit code */ - { - Py_ssize_t __pyx_temp; - for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { - __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); - } - } - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_26maha_test(CYTHON_UNUSED struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v_x, CYTHON_UNUSED PyObject *__pyx_v_P, CYTHON_UNUSED PyObject *__pyx_v_kind, CYTHON_UNUSED PyObject *__pyx_v_z, CYTHON_UNUSED PyObject *__pyx_v_R, CYTHON_UNUSED PyObject *__pyx_v_extra_args, CYTHON_UNUSED PyObject *__pyx_v_maha_thresh) { - PyObject *__pyx_r = NULL; - __Pyx_TraceDeclarations - __Pyx_RefNannyDeclarations - PyObject *__pyx_t_1 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_TraceFrameInit(__pyx_codeobj__34) - __Pyx_RefNannySetupContext("maha_test", 1); - __Pyx_TraceCall("maha_test", __pyx_f[0], 191, 0, __PYX_ERR(0, 191, __pyx_L1_error)); - - /* "rednose/helpers/ekf_sym_pyx.pyx":192 - * - * def maha_test(self, x, P, kind, z, R, extra_args=[], maha_thresh=0.95): - * raise NotImplementedError() # TODO # <<<<<<<<<<<<<< - * - * def __dealloc__(self): - */ - __pyx_t_1 = __Pyx_PyObject_CallNoArg(__pyx_builtin_NotImplementedError); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 192, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __Pyx_Raise(__pyx_t_1, 0, 0, 0); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __PYX_ERR(0, 192, __pyx_L1_error) - - /* "rednose/helpers/ekf_sym_pyx.pyx":191 - * raise NotImplementedError() # TODO - * - * def maha_test(self, x, P, kind, z, R, extra_args=[], maha_thresh=0.95): # <<<<<<<<<<<<<< - * raise NotImplementedError() # TODO - * - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_1); - __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.maha_test", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = NULL; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_TraceReturn(__pyx_r, 0); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "rednose/helpers/ekf_sym_pyx.pyx":194 - * raise NotImplementedError() # TODO - * - * def __dealloc__(self): # <<<<<<<<<<<<<< - * del self.ekf - */ - -/* Python wrapper */ -static void __pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_29__dealloc__(PyObject *__pyx_v_self); /*proto*/ -static void __pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_29__dealloc__(PyObject *__pyx_v_self) { - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); - __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); - __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_28__dealloc__(((struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *)__pyx_v_self)); - - /* function exit code */ - __Pyx_RefNannyFinishContext(); -} - -static void __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_28__dealloc__(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self) { - __Pyx_TraceDeclarations - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_TraceCall("__dealloc__", __pyx_f[0], 194, 0, __PYX_ERR(0, 194, __pyx_L1_error)); - - /* "rednose/helpers/ekf_sym_pyx.pyx":195 - * - * def __dealloc__(self): - * del self.ekf # <<<<<<<<<<<<<< - */ - delete __pyx_v_self->ekf; - - /* "rednose/helpers/ekf_sym_pyx.pyx":194 - * raise NotImplementedError() # TODO - * - * def __dealloc__(self): # <<<<<<<<<<<<<< - * del self.ekf - */ - - /* function exit code */ - goto __pyx_L0; - __pyx_L1_error:; - __Pyx_WriteUnraisable("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.__dealloc__", __pyx_clineno, __pyx_lineno, __pyx_filename, 1, 0); - __pyx_L0:; - __Pyx_TraceReturn(Py_None, 0); -} - -/* "(tree fragment)":1 - * def __reduce_cython__(self): # <<<<<<<<<<<<<< - * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" - * def __setstate_cython__(self, __pyx_state): - */ - -/* Python wrapper */ -static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_31__reduce_cython__(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -); /*proto*/ -static PyMethodDef __pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_31__reduce_cython__ = {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_31__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; -static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_31__reduce_cython__(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -) { - #if !CYTHON_METH_FASTCALL - CYTHON_UNUSED Py_ssize_t __pyx_nargs; - #endif - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - PyObject *__pyx_r = 0; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); - #if !CYTHON_METH_FASTCALL - #if CYTHON_ASSUME_SAFE_MACROS - __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); - #else - __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; - #endif - #endif - __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); - if (unlikely(__pyx_nargs > 0)) { - __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} - if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; - __pyx_r = __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_30__reduce_cython__(((struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *)__pyx_v_self)); - - /* function exit code */ - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_30__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self) { - PyObject *__pyx_r = NULL; - __Pyx_TraceDeclarations - __Pyx_RefNannyDeclarations - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_TraceFrameInit(__pyx_codeobj__35) - __Pyx_RefNannySetupContext("__reduce_cython__", 1); - __Pyx_TraceCall("__reduce_cython__", __pyx_f[1], 1, 0, __PYX_ERR(1, 1, __pyx_L1_error)); - - /* "(tree fragment)":2 - * def __reduce_cython__(self): - * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< - * def __setstate_cython__(self, __pyx_state): - * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" - */ - __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); - __PYX_ERR(1, 2, __pyx_L1_error) - - /* "(tree fragment)":1 - * def __reduce_cython__(self): # <<<<<<<<<<<<<< - * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" - * def __setstate_cython__(self, __pyx_state): - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = NULL; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_TraceReturn(__pyx_r, 0); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "(tree fragment)":3 - * def __reduce_cython__(self): - * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" - * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< - * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" - */ - -/* Python wrapper */ -static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_33__setstate_cython__(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -); /*proto*/ -static PyMethodDef __pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_33__setstate_cython__ = {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_33__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; -static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_33__setstate_cython__(PyObject *__pyx_v_self, -#if CYTHON_METH_FASTCALL -PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds -#else -PyObject *__pyx_args, PyObject *__pyx_kwds -#endif -) { - CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; - #if !CYTHON_METH_FASTCALL - CYTHON_UNUSED Py_ssize_t __pyx_nargs; - #endif - CYTHON_UNUSED PyObject *const *__pyx_kwvalues; - PyObject* values[1] = {0}; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - PyObject *__pyx_r = 0; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); - #if !CYTHON_METH_FASTCALL - #if CYTHON_ASSUME_SAFE_MACROS - __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); - #else - __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; - #endif - #endif - __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); - { - PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; - if (__pyx_kwds) { - Py_ssize_t kw_args; - switch (__pyx_nargs) { - case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); - CYTHON_FALLTHROUGH; - case 0: break; - default: goto __pyx_L5_argtuple_error; - } - kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); - switch (__pyx_nargs) { - case 0: - if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { - (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); - kw_args--; - } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) - else goto __pyx_L5_argtuple_error; - } - if (unlikely(kw_args > 0)) { - const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) - } - } else if (unlikely(__pyx_nargs != 1)) { - goto __pyx_L5_argtuple_error; - } else { - values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); - } - __pyx_v___pyx_state = values[0]; - } - goto __pyx_L6_skip; - __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) - __pyx_L6_skip:; - goto __pyx_L4_argument_unpacking_done; - __pyx_L3_error:; - { - Py_ssize_t __pyx_temp; - for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { - __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); - } - } - __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); - __Pyx_RefNannyFinishContext(); - return NULL; - __pyx_L4_argument_unpacking_done:; - __pyx_r = __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_32__setstate_cython__(((struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *)__pyx_v_self), __pyx_v___pyx_state); - - /* function exit code */ - { - Py_ssize_t __pyx_temp; - for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { - __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); - } - } - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_32__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { - PyObject *__pyx_r = NULL; - __Pyx_TraceDeclarations - __Pyx_RefNannyDeclarations - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_TraceFrameInit(__pyx_codeobj__36) - __Pyx_RefNannySetupContext("__setstate_cython__", 1); - __Pyx_TraceCall("__setstate_cython__", __pyx_f[1], 3, 0, __PYX_ERR(1, 3, __pyx_L1_error)); - - /* "(tree fragment)":4 - * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" - * def __setstate_cython__(self, __pyx_state): - * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< - */ - __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); - __PYX_ERR(1, 4, __pyx_L1_error) - - /* "(tree fragment)":3 - * def __reduce_cython__(self): - * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" - * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< - * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" - */ - - /* function exit code */ - __pyx_L1_error:; - __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = NULL; - __Pyx_XGIVEREF(__pyx_r); - __Pyx_TraceReturn(__pyx_r, 0); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static PyObject *__pyx_tp_new_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx(PyTypeObject *t, PyObject *a, PyObject *k) { - PyObject *o; - #if CYTHON_COMPILING_IN_LIMITED_API - allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); - o = alloc_func(t, 0); - #else - if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { - o = (*t->tp_alloc)(t, 0); - } else { - o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); - } - if (unlikely(!o)) return 0; - #endif - if (unlikely(__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_1__cinit__(o, a, k) < 0)) goto bad; - return o; - bad: - Py_DECREF(o); o = 0; - return NULL; -} - -static void __pyx_tp_dealloc_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx(PyObject *o) { - #if CYTHON_USE_TP_FINALIZE - if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && (!PyType_IS_GC(Py_TYPE(o)) || !__Pyx_PyObject_GC_IsFinalized(o))) { - if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx) { - if (PyObject_CallFinalizerFromDealloc(o)) return; - } - } - #endif - { - PyObject *etype, *eval, *etb; - PyErr_Fetch(&etype, &eval, &etb); - __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); - __pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_29__dealloc__(o); - __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); - PyErr_Restore(etype, eval, etb); - } - #if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY - (*Py_TYPE(o)->tp_free)(o); - #else - { - freefunc tp_free = (freefunc)PyType_GetSlot(Py_TYPE(o), Py_tp_free); - if (tp_free) tp_free(o); - } - #endif -} - -static PyMethodDef __pyx_methods_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx[] = { - {"init_state", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_3init_state, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, - {"state", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_5state, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, - {"covs", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_7covs, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, - {"set_filter_time", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_9set_filter_time, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, - {"get_filter_time", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_11get_filter_time, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, - {"set_global", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_13set_global, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, - {"reset_rewind", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_15reset_rewind, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, - {"predict", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_17predict, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, - {"predict_and_update_batch", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_19predict_and_update_batch, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, - {"augment", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_21augment, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, - {"get_augment_times", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_23get_augment_times, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, - {"rts_smooth", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_25rts_smooth, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, - {"maha_test", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_27maha_test, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, - {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_31__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, - {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_33__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, - {0, 0, 0, 0} -}; -#if CYTHON_USE_TYPE_SPECS -static PyType_Slot __pyx_type_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx_slots[] = { - {Py_tp_dealloc, (void *)__pyx_tp_dealloc_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx}, - {Py_tp_methods, (void *)__pyx_methods_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx}, - {Py_tp_new, (void *)__pyx_tp_new_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx}, - {0, 0}, -}; -static PyType_Spec __pyx_type_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx_spec = { - "rednose.helpers.ekf_sym_pyx.EKF_sym_pyx", - sizeof(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx), - 0, - Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, - __pyx_type_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx_slots, -}; -#else - -static PyTypeObject __pyx_type_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx = { - PyVarObject_HEAD_INIT(0, 0) - "rednose.helpers.ekf_sym_pyx.""EKF_sym_pyx", /*tp_name*/ - sizeof(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx), /*tp_basicsize*/ - 0, /*tp_itemsize*/ - __pyx_tp_dealloc_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx, /*tp_dealloc*/ - #if PY_VERSION_HEX < 0x030800b4 - 0, /*tp_print*/ - #endif - #if PY_VERSION_HEX >= 0x030800b4 - 0, /*tp_vectorcall_offset*/ - #endif - 0, /*tp_getattr*/ - 0, /*tp_setattr*/ - #if PY_MAJOR_VERSION < 3 - 0, /*tp_compare*/ - #endif - #if PY_MAJOR_VERSION >= 3 - 0, /*tp_as_async*/ - #endif - 0, /*tp_repr*/ - 0, /*tp_as_number*/ - 0, /*tp_as_sequence*/ - 0, /*tp_as_mapping*/ - 0, /*tp_hash*/ - 0, /*tp_call*/ - 0, /*tp_str*/ - 0, /*tp_getattro*/ - 0, /*tp_setattro*/ - 0, /*tp_as_buffer*/ - Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, /*tp_flags*/ - 0, /*tp_doc*/ - 0, /*tp_traverse*/ - 0, /*tp_clear*/ - 0, /*tp_richcompare*/ - 0, /*tp_weaklistoffset*/ - 0, /*tp_iter*/ - 0, /*tp_iternext*/ - __pyx_methods_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx, /*tp_methods*/ - 0, /*tp_members*/ - 0, /*tp_getset*/ - 0, /*tp_base*/ - 0, /*tp_dict*/ - 0, /*tp_descr_get*/ - 0, /*tp_descr_set*/ - #if !CYTHON_USE_TYPE_SPECS - 0, /*tp_dictoffset*/ - #endif - 0, /*tp_init*/ - 0, /*tp_alloc*/ - __pyx_tp_new_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx, /*tp_new*/ - 0, /*tp_free*/ - 0, /*tp_is_gc*/ - 0, /*tp_bases*/ - 0, /*tp_mro*/ - 0, /*tp_cache*/ - 0, /*tp_subclasses*/ - 0, /*tp_weaklist*/ - 0, /*tp_del*/ - 0, /*tp_version_tag*/ - #if PY_VERSION_HEX >= 0x030400a1 - #if CYTHON_USE_TP_FINALIZE - 0, /*tp_finalize*/ - #else - NULL, /*tp_finalize*/ - #endif - #endif - #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) - 0, /*tp_vectorcall*/ - #endif - #if __PYX_NEED_TP_PRINT_SLOT == 1 - 0, /*tp_print*/ - #endif - #if PY_VERSION_HEX >= 0x030C0000 - 0, /*tp_watched*/ - #endif - #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 - 0, /*tp_pypy_flags*/ - #endif -}; -#endif -static struct __pyx_vtabstruct_array __pyx_vtable_array; - -static PyObject *__pyx_tp_new_array(PyTypeObject *t, PyObject *a, PyObject *k) { - struct __pyx_array_obj *p; - PyObject *o; - #if CYTHON_COMPILING_IN_LIMITED_API - allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); - o = alloc_func(t, 0); - #else - if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { - o = (*t->tp_alloc)(t, 0); - } else { - o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); - } - if (unlikely(!o)) return 0; - #endif - p = ((struct __pyx_array_obj *)o); - p->__pyx_vtab = __pyx_vtabptr_array; - p->mode = ((PyObject*)Py_None); Py_INCREF(Py_None); - p->_format = ((PyObject*)Py_None); Py_INCREF(Py_None); - if (unlikely(__pyx_array___cinit__(o, a, k) < 0)) goto bad; - return o; - bad: - Py_DECREF(o); o = 0; - return NULL; -} - -static void __pyx_tp_dealloc_array(PyObject *o) { - struct __pyx_array_obj *p = (struct __pyx_array_obj *)o; - #if CYTHON_USE_TP_FINALIZE - if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && (!PyType_IS_GC(Py_TYPE(o)) || !__Pyx_PyObject_GC_IsFinalized(o))) { - if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_array) { - if (PyObject_CallFinalizerFromDealloc(o)) return; - } - } - #endif - { - PyObject *etype, *eval, *etb; - PyErr_Fetch(&etype, &eval, &etb); - __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); - __pyx_array___dealloc__(o); - __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); - PyErr_Restore(etype, eval, etb); - } - Py_CLEAR(p->mode); - Py_CLEAR(p->_format); - #if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY - (*Py_TYPE(o)->tp_free)(o); - #else - { - freefunc tp_free = (freefunc)PyType_GetSlot(Py_TYPE(o), Py_tp_free); - if (tp_free) tp_free(o); - } - #endif -} -static PyObject *__pyx_sq_item_array(PyObject *o, Py_ssize_t i) { - PyObject *r; - PyObject *x = PyInt_FromSsize_t(i); if(!x) return 0; - r = Py_TYPE(o)->tp_as_mapping->mp_subscript(o, x); - Py_DECREF(x); - return r; -} - -static int __pyx_mp_ass_subscript_array(PyObject *o, PyObject *i, PyObject *v) { - if (v) { - return __pyx_array___setitem__(o, i, v); - } - else { - __Pyx_TypeName o_type_name; - o_type_name = __Pyx_PyType_GetName(Py_TYPE(o)); - PyErr_Format(PyExc_NotImplementedError, - "Subscript deletion not supported by " __Pyx_FMT_TYPENAME, o_type_name); - __Pyx_DECREF_TypeName(o_type_name); - return -1; - } -} - -static PyObject *__pyx_tp_getattro_array(PyObject *o, PyObject *n) { - PyObject *v = __Pyx_PyObject_GenericGetAttr(o, n); - if (!v && PyErr_ExceptionMatches(PyExc_AttributeError)) { - PyErr_Clear(); - v = __pyx_array___getattr__(o, n); - } - return v; -} - -static PyObject *__pyx_getprop___pyx_array_memview(PyObject *o, CYTHON_UNUSED void *x) { - return __pyx_pw_15View_dot_MemoryView_5array_7memview_1__get__(o); -} - -static PyMethodDef __pyx_methods_array[] = { - {"__getattr__", (PyCFunction)__pyx_array___getattr__, METH_O|METH_COEXIST, 0}, - {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_array_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, - {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_array_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, - {0, 0, 0, 0} -}; - -static struct PyGetSetDef __pyx_getsets_array[] = { - {(char *)"memview", __pyx_getprop___pyx_array_memview, 0, (char *)0, 0}, - {0, 0, 0, 0, 0} -}; -#if CYTHON_USE_TYPE_SPECS -#if !CYTHON_COMPILING_IN_LIMITED_API - -static PyBufferProcs __pyx_tp_as_buffer_array = { - #if PY_MAJOR_VERSION < 3 - 0, /*bf_getreadbuffer*/ - #endif - #if PY_MAJOR_VERSION < 3 - 0, /*bf_getwritebuffer*/ - #endif - #if PY_MAJOR_VERSION < 3 - 0, /*bf_getsegcount*/ - #endif - #if PY_MAJOR_VERSION < 3 - 0, /*bf_getcharbuffer*/ - #endif - __pyx_array_getbuffer, /*bf_getbuffer*/ - 0, /*bf_releasebuffer*/ -}; -#endif -static PyType_Slot __pyx_type___pyx_array_slots[] = { - {Py_tp_dealloc, (void *)__pyx_tp_dealloc_array}, - {Py_sq_length, (void *)__pyx_array___len__}, - {Py_sq_item, (void *)__pyx_sq_item_array}, - {Py_mp_length, (void *)__pyx_array___len__}, - {Py_mp_subscript, (void *)__pyx_array___getitem__}, - {Py_mp_ass_subscript, (void *)__pyx_mp_ass_subscript_array}, - {Py_tp_getattro, (void *)__pyx_tp_getattro_array}, - #if defined(Py_bf_getbuffer) - {Py_bf_getbuffer, (void *)__pyx_array_getbuffer}, - #endif - {Py_tp_methods, (void *)__pyx_methods_array}, - {Py_tp_getset, (void *)__pyx_getsets_array}, - {Py_tp_new, (void *)__pyx_tp_new_array}, - {0, 0}, -}; -static PyType_Spec __pyx_type___pyx_array_spec = { - "rednose.helpers.ekf_sym_pyx.array", - sizeof(struct __pyx_array_obj), - 0, - Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_SEQUENCE, - __pyx_type___pyx_array_slots, -}; -#else - -static PySequenceMethods __pyx_tp_as_sequence_array = { - __pyx_array___len__, /*sq_length*/ - 0, /*sq_concat*/ - 0, /*sq_repeat*/ - __pyx_sq_item_array, /*sq_item*/ - 0, /*sq_slice*/ - 0, /*sq_ass_item*/ - 0, /*sq_ass_slice*/ - 0, /*sq_contains*/ - 0, /*sq_inplace_concat*/ - 0, /*sq_inplace_repeat*/ -}; - -static PyMappingMethods __pyx_tp_as_mapping_array = { - __pyx_array___len__, /*mp_length*/ - __pyx_array___getitem__, /*mp_subscript*/ - __pyx_mp_ass_subscript_array, /*mp_ass_subscript*/ -}; - -static PyBufferProcs __pyx_tp_as_buffer_array = { - #if PY_MAJOR_VERSION < 3 - 0, /*bf_getreadbuffer*/ - #endif - #if PY_MAJOR_VERSION < 3 - 0, /*bf_getwritebuffer*/ - #endif - #if PY_MAJOR_VERSION < 3 - 0, /*bf_getsegcount*/ - #endif - #if PY_MAJOR_VERSION < 3 - 0, /*bf_getcharbuffer*/ - #endif - __pyx_array_getbuffer, /*bf_getbuffer*/ - 0, /*bf_releasebuffer*/ -}; - -static PyTypeObject __pyx_type___pyx_array = { - PyVarObject_HEAD_INIT(0, 0) - "rednose.helpers.ekf_sym_pyx.""array", /*tp_name*/ - sizeof(struct __pyx_array_obj), /*tp_basicsize*/ - 0, /*tp_itemsize*/ - __pyx_tp_dealloc_array, /*tp_dealloc*/ - #if PY_VERSION_HEX < 0x030800b4 - 0, /*tp_print*/ - #endif - #if PY_VERSION_HEX >= 0x030800b4 - 0, /*tp_vectorcall_offset*/ - #endif - 0, /*tp_getattr*/ - 0, /*tp_setattr*/ - #if PY_MAJOR_VERSION < 3 - 0, /*tp_compare*/ - #endif - #if PY_MAJOR_VERSION >= 3 - 0, /*tp_as_async*/ - #endif - 0, /*tp_repr*/ - 0, /*tp_as_number*/ - &__pyx_tp_as_sequence_array, /*tp_as_sequence*/ - &__pyx_tp_as_mapping_array, /*tp_as_mapping*/ - 0, /*tp_hash*/ - 0, /*tp_call*/ - 0, /*tp_str*/ - __pyx_tp_getattro_array, /*tp_getattro*/ - 0, /*tp_setattro*/ - &__pyx_tp_as_buffer_array, /*tp_as_buffer*/ - Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_SEQUENCE, /*tp_flags*/ - 0, /*tp_doc*/ - 0, /*tp_traverse*/ - 0, /*tp_clear*/ - 0, /*tp_richcompare*/ - 0, /*tp_weaklistoffset*/ - 0, /*tp_iter*/ - 0, /*tp_iternext*/ - __pyx_methods_array, /*tp_methods*/ - 0, /*tp_members*/ - __pyx_getsets_array, /*tp_getset*/ - 0, /*tp_base*/ - 0, /*tp_dict*/ - 0, /*tp_descr_get*/ - 0, /*tp_descr_set*/ - #if !CYTHON_USE_TYPE_SPECS - 0, /*tp_dictoffset*/ - #endif - 0, /*tp_init*/ - 0, /*tp_alloc*/ - __pyx_tp_new_array, /*tp_new*/ - 0, /*tp_free*/ - 0, /*tp_is_gc*/ - 0, /*tp_bases*/ - 0, /*tp_mro*/ - 0, /*tp_cache*/ - 0, /*tp_subclasses*/ - 0, /*tp_weaklist*/ - 0, /*tp_del*/ - 0, /*tp_version_tag*/ - #if PY_VERSION_HEX >= 0x030400a1 - #if CYTHON_USE_TP_FINALIZE - 0, /*tp_finalize*/ - #else - NULL, /*tp_finalize*/ - #endif - #endif - #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) - 0, /*tp_vectorcall*/ - #endif - #if __PYX_NEED_TP_PRINT_SLOT == 1 - 0, /*tp_print*/ - #endif - #if PY_VERSION_HEX >= 0x030C0000 - 0, /*tp_watched*/ - #endif - #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 - 0, /*tp_pypy_flags*/ - #endif -}; -#endif - -static PyObject *__pyx_tp_new_Enum(PyTypeObject *t, CYTHON_UNUSED PyObject *a, CYTHON_UNUSED PyObject *k) { - struct __pyx_MemviewEnum_obj *p; - PyObject *o; - #if CYTHON_COMPILING_IN_LIMITED_API - allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); - o = alloc_func(t, 0); - #else - if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { - o = (*t->tp_alloc)(t, 0); - } else { - o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); - } - if (unlikely(!o)) return 0; - #endif - p = ((struct __pyx_MemviewEnum_obj *)o); - p->name = Py_None; Py_INCREF(Py_None); - return o; -} - -static void __pyx_tp_dealloc_Enum(PyObject *o) { - struct __pyx_MemviewEnum_obj *p = (struct __pyx_MemviewEnum_obj *)o; - #if CYTHON_USE_TP_FINALIZE - if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { - if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_Enum) { - if (PyObject_CallFinalizerFromDealloc(o)) return; - } - } - #endif - PyObject_GC_UnTrack(o); - Py_CLEAR(p->name); - #if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY - (*Py_TYPE(o)->tp_free)(o); - #else - { - freefunc tp_free = (freefunc)PyType_GetSlot(Py_TYPE(o), Py_tp_free); - if (tp_free) tp_free(o); - } - #endif -} - -static int __pyx_tp_traverse_Enum(PyObject *o, visitproc v, void *a) { - int e; - struct __pyx_MemviewEnum_obj *p = (struct __pyx_MemviewEnum_obj *)o; - if (p->name) { - e = (*v)(p->name, a); if (e) return e; - } - return 0; -} - -static int __pyx_tp_clear_Enum(PyObject *o) { - PyObject* tmp; - struct __pyx_MemviewEnum_obj *p = (struct __pyx_MemviewEnum_obj *)o; - tmp = ((PyObject*)p->name); - p->name = Py_None; Py_INCREF(Py_None); - Py_XDECREF(tmp); - return 0; -} - -static PyObject *__pyx_specialmethod___pyx_MemviewEnum___repr__(PyObject *self, CYTHON_UNUSED PyObject *arg) { - return __pyx_MemviewEnum___repr__(self); -} - -static PyMethodDef __pyx_methods_Enum[] = { - {"__repr__", (PyCFunction)__pyx_specialmethod___pyx_MemviewEnum___repr__, METH_NOARGS|METH_COEXIST, 0}, - {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_MemviewEnum_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, - {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_MemviewEnum_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, - {0, 0, 0, 0} -}; -#if CYTHON_USE_TYPE_SPECS -static PyType_Slot __pyx_type___pyx_MemviewEnum_slots[] = { - {Py_tp_dealloc, (void *)__pyx_tp_dealloc_Enum}, - {Py_tp_repr, (void *)__pyx_MemviewEnum___repr__}, - {Py_tp_traverse, (void *)__pyx_tp_traverse_Enum}, - {Py_tp_clear, (void *)__pyx_tp_clear_Enum}, - {Py_tp_methods, (void *)__pyx_methods_Enum}, - {Py_tp_init, (void *)__pyx_MemviewEnum___init__}, - {Py_tp_new, (void *)__pyx_tp_new_Enum}, - {0, 0}, -}; -static PyType_Spec __pyx_type___pyx_MemviewEnum_spec = { - "rednose.helpers.ekf_sym_pyx.Enum", - sizeof(struct __pyx_MemviewEnum_obj), - 0, - Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, - __pyx_type___pyx_MemviewEnum_slots, -}; -#else - -static PyTypeObject __pyx_type___pyx_MemviewEnum = { - PyVarObject_HEAD_INIT(0, 0) - "rednose.helpers.ekf_sym_pyx.""Enum", /*tp_name*/ - sizeof(struct __pyx_MemviewEnum_obj), /*tp_basicsize*/ - 0, /*tp_itemsize*/ - __pyx_tp_dealloc_Enum, /*tp_dealloc*/ - #if PY_VERSION_HEX < 0x030800b4 - 0, /*tp_print*/ - #endif - #if PY_VERSION_HEX >= 0x030800b4 - 0, /*tp_vectorcall_offset*/ - #endif - 0, /*tp_getattr*/ - 0, /*tp_setattr*/ - #if PY_MAJOR_VERSION < 3 - 0, /*tp_compare*/ - #endif - #if PY_MAJOR_VERSION >= 3 - 0, /*tp_as_async*/ - #endif - __pyx_MemviewEnum___repr__, /*tp_repr*/ - 0, /*tp_as_number*/ - 0, /*tp_as_sequence*/ - 0, /*tp_as_mapping*/ - 0, /*tp_hash*/ - 0, /*tp_call*/ - 0, /*tp_str*/ - 0, /*tp_getattro*/ - 0, /*tp_setattro*/ - 0, /*tp_as_buffer*/ - Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, /*tp_flags*/ - 0, /*tp_doc*/ - __pyx_tp_traverse_Enum, /*tp_traverse*/ - __pyx_tp_clear_Enum, /*tp_clear*/ - 0, /*tp_richcompare*/ - 0, /*tp_weaklistoffset*/ - 0, /*tp_iter*/ - 0, /*tp_iternext*/ - __pyx_methods_Enum, /*tp_methods*/ - 0, /*tp_members*/ - 0, /*tp_getset*/ - 0, /*tp_base*/ - 0, /*tp_dict*/ - 0, /*tp_descr_get*/ - 0, /*tp_descr_set*/ - #if !CYTHON_USE_TYPE_SPECS - 0, /*tp_dictoffset*/ - #endif - __pyx_MemviewEnum___init__, /*tp_init*/ - 0, /*tp_alloc*/ - __pyx_tp_new_Enum, /*tp_new*/ - 0, /*tp_free*/ - 0, /*tp_is_gc*/ - 0, /*tp_bases*/ - 0, /*tp_mro*/ - 0, /*tp_cache*/ - 0, /*tp_subclasses*/ - 0, /*tp_weaklist*/ - 0, /*tp_del*/ - 0, /*tp_version_tag*/ - #if PY_VERSION_HEX >= 0x030400a1 - #if CYTHON_USE_TP_FINALIZE - 0, /*tp_finalize*/ - #else - NULL, /*tp_finalize*/ - #endif - #endif - #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) - 0, /*tp_vectorcall*/ - #endif - #if __PYX_NEED_TP_PRINT_SLOT == 1 - 0, /*tp_print*/ - #endif - #if PY_VERSION_HEX >= 0x030C0000 - 0, /*tp_watched*/ - #endif - #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 - 0, /*tp_pypy_flags*/ - #endif -}; -#endif -static struct __pyx_vtabstruct_memoryview __pyx_vtable_memoryview; - -static PyObject *__pyx_tp_new_memoryview(PyTypeObject *t, PyObject *a, PyObject *k) { - struct __pyx_memoryview_obj *p; - PyObject *o; - #if CYTHON_COMPILING_IN_LIMITED_API - allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); - o = alloc_func(t, 0); - #else - if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { - o = (*t->tp_alloc)(t, 0); - } else { - o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); - } - if (unlikely(!o)) return 0; - #endif - p = ((struct __pyx_memoryview_obj *)o); - p->__pyx_vtab = __pyx_vtabptr_memoryview; - p->obj = Py_None; Py_INCREF(Py_None); - p->_size = Py_None; Py_INCREF(Py_None); - p->_array_interface = Py_None; Py_INCREF(Py_None); - p->view.obj = NULL; - if (unlikely(__pyx_memoryview___cinit__(o, a, k) < 0)) goto bad; - return o; - bad: - Py_DECREF(o); o = 0; - return NULL; -} - -static void __pyx_tp_dealloc_memoryview(PyObject *o) { - struct __pyx_memoryview_obj *p = (struct __pyx_memoryview_obj *)o; - #if CYTHON_USE_TP_FINALIZE - if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { - if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_memoryview) { - if (PyObject_CallFinalizerFromDealloc(o)) return; - } - } - #endif - PyObject_GC_UnTrack(o); - { - PyObject *etype, *eval, *etb; - PyErr_Fetch(&etype, &eval, &etb); - __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); - __pyx_memoryview___dealloc__(o); - __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); - PyErr_Restore(etype, eval, etb); - } - Py_CLEAR(p->obj); - Py_CLEAR(p->_size); - Py_CLEAR(p->_array_interface); - #if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY - (*Py_TYPE(o)->tp_free)(o); - #else - { - freefunc tp_free = (freefunc)PyType_GetSlot(Py_TYPE(o), Py_tp_free); - if (tp_free) tp_free(o); - } - #endif -} - -static int __pyx_tp_traverse_memoryview(PyObject *o, visitproc v, void *a) { - int e; - struct __pyx_memoryview_obj *p = (struct __pyx_memoryview_obj *)o; - if (p->obj) { - e = (*v)(p->obj, a); if (e) return e; - } - if (p->_size) { - e = (*v)(p->_size, a); if (e) return e; - } - if (p->_array_interface) { - e = (*v)(p->_array_interface, a); if (e) return e; - } - if (p->view.obj) { - e = (*v)(p->view.obj, a); if (e) return e; - } - return 0; -} - -static int __pyx_tp_clear_memoryview(PyObject *o) { - PyObject* tmp; - struct __pyx_memoryview_obj *p = (struct __pyx_memoryview_obj *)o; - tmp = ((PyObject*)p->obj); - p->obj = Py_None; Py_INCREF(Py_None); - Py_XDECREF(tmp); - tmp = ((PyObject*)p->_size); - p->_size = Py_None; Py_INCREF(Py_None); - Py_XDECREF(tmp); - tmp = ((PyObject*)p->_array_interface); - p->_array_interface = Py_None; Py_INCREF(Py_None); - Py_XDECREF(tmp); - Py_CLEAR(p->view.obj); - return 0; -} -static PyObject *__pyx_sq_item_memoryview(PyObject *o, Py_ssize_t i) { - PyObject *r; - PyObject *x = PyInt_FromSsize_t(i); if(!x) return 0; - r = Py_TYPE(o)->tp_as_mapping->mp_subscript(o, x); - Py_DECREF(x); - return r; -} - -static int __pyx_mp_ass_subscript_memoryview(PyObject *o, PyObject *i, PyObject *v) { - if (v) { - return __pyx_memoryview___setitem__(o, i, v); - } - else { - __Pyx_TypeName o_type_name; - o_type_name = __Pyx_PyType_GetName(Py_TYPE(o)); - PyErr_Format(PyExc_NotImplementedError, - "Subscript deletion not supported by " __Pyx_FMT_TYPENAME, o_type_name); - __Pyx_DECREF_TypeName(o_type_name); - return -1; - } -} - -static PyObject *__pyx_getprop___pyx_memoryview_T(PyObject *o, CYTHON_UNUSED void *x) { - return __pyx_pw_15View_dot_MemoryView_10memoryview_1T_1__get__(o); -} - -static PyObject *__pyx_getprop___pyx_memoryview_base(PyObject *o, CYTHON_UNUSED void *x) { - return __pyx_pw_15View_dot_MemoryView_10memoryview_4base_1__get__(o); -} - -static PyObject *__pyx_getprop___pyx_memoryview_shape(PyObject *o, CYTHON_UNUSED void *x) { - return __pyx_pw_15View_dot_MemoryView_10memoryview_5shape_1__get__(o); -} - -static PyObject *__pyx_getprop___pyx_memoryview_strides(PyObject *o, CYTHON_UNUSED void *x) { - return __pyx_pw_15View_dot_MemoryView_10memoryview_7strides_1__get__(o); -} - -static PyObject *__pyx_getprop___pyx_memoryview_suboffsets(PyObject *o, CYTHON_UNUSED void *x) { - return __pyx_pw_15View_dot_MemoryView_10memoryview_10suboffsets_1__get__(o); -} - -static PyObject *__pyx_getprop___pyx_memoryview_ndim(PyObject *o, CYTHON_UNUSED void *x) { - return __pyx_pw_15View_dot_MemoryView_10memoryview_4ndim_1__get__(o); -} - -static PyObject *__pyx_getprop___pyx_memoryview_itemsize(PyObject *o, CYTHON_UNUSED void *x) { - return __pyx_pw_15View_dot_MemoryView_10memoryview_8itemsize_1__get__(o); -} - -static PyObject *__pyx_getprop___pyx_memoryview_nbytes(PyObject *o, CYTHON_UNUSED void *x) { - return __pyx_pw_15View_dot_MemoryView_10memoryview_6nbytes_1__get__(o); -} - -static PyObject *__pyx_getprop___pyx_memoryview_size(PyObject *o, CYTHON_UNUSED void *x) { - return __pyx_pw_15View_dot_MemoryView_10memoryview_4size_1__get__(o); -} - -static PyObject *__pyx_specialmethod___pyx_memoryview___repr__(PyObject *self, CYTHON_UNUSED PyObject *arg) { - return __pyx_memoryview___repr__(self); -} - -static PyMethodDef __pyx_methods_memoryview[] = { - {"__repr__", (PyCFunction)__pyx_specialmethod___pyx_memoryview___repr__, METH_NOARGS|METH_COEXIST, 0}, - {"is_c_contig", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_is_c_contig, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, - {"is_f_contig", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_is_f_contig, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, - {"copy", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_copy, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, - {"copy_fortran", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_copy_fortran, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, - {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryview_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, - {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryview_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, - {0, 0, 0, 0} -}; - -static struct PyGetSetDef __pyx_getsets_memoryview[] = { - {(char *)"T", __pyx_getprop___pyx_memoryview_T, 0, (char *)0, 0}, - {(char *)"base", __pyx_getprop___pyx_memoryview_base, 0, (char *)0, 0}, - {(char *)"shape", __pyx_getprop___pyx_memoryview_shape, 0, (char *)0, 0}, - {(char *)"strides", __pyx_getprop___pyx_memoryview_strides, 0, (char *)0, 0}, - {(char *)"suboffsets", __pyx_getprop___pyx_memoryview_suboffsets, 0, (char *)0, 0}, - {(char *)"ndim", __pyx_getprop___pyx_memoryview_ndim, 0, (char *)0, 0}, - {(char *)"itemsize", __pyx_getprop___pyx_memoryview_itemsize, 0, (char *)0, 0}, - {(char *)"nbytes", __pyx_getprop___pyx_memoryview_nbytes, 0, (char *)0, 0}, - {(char *)"size", __pyx_getprop___pyx_memoryview_size, 0, (char *)0, 0}, - {0, 0, 0, 0, 0} -}; -#if CYTHON_USE_TYPE_SPECS -#if !CYTHON_COMPILING_IN_LIMITED_API - -static PyBufferProcs __pyx_tp_as_buffer_memoryview = { - #if PY_MAJOR_VERSION < 3 - 0, /*bf_getreadbuffer*/ - #endif - #if PY_MAJOR_VERSION < 3 - 0, /*bf_getwritebuffer*/ - #endif - #if PY_MAJOR_VERSION < 3 - 0, /*bf_getsegcount*/ - #endif - #if PY_MAJOR_VERSION < 3 - 0, /*bf_getcharbuffer*/ - #endif - __pyx_memoryview_getbuffer, /*bf_getbuffer*/ - 0, /*bf_releasebuffer*/ -}; -#endif -static PyType_Slot __pyx_type___pyx_memoryview_slots[] = { - {Py_tp_dealloc, (void *)__pyx_tp_dealloc_memoryview}, - {Py_tp_repr, (void *)__pyx_memoryview___repr__}, - {Py_sq_length, (void *)__pyx_memoryview___len__}, - {Py_sq_item, (void *)__pyx_sq_item_memoryview}, - {Py_mp_length, (void *)__pyx_memoryview___len__}, - {Py_mp_subscript, (void *)__pyx_memoryview___getitem__}, - {Py_mp_ass_subscript, (void *)__pyx_mp_ass_subscript_memoryview}, - {Py_tp_str, (void *)__pyx_memoryview___str__}, - #if defined(Py_bf_getbuffer) - {Py_bf_getbuffer, (void *)__pyx_memoryview_getbuffer}, - #endif - {Py_tp_traverse, (void *)__pyx_tp_traverse_memoryview}, - {Py_tp_clear, (void *)__pyx_tp_clear_memoryview}, - {Py_tp_methods, (void *)__pyx_methods_memoryview}, - {Py_tp_getset, (void *)__pyx_getsets_memoryview}, - {Py_tp_new, (void *)__pyx_tp_new_memoryview}, - {0, 0}, -}; -static PyType_Spec __pyx_type___pyx_memoryview_spec = { - "rednose.helpers.ekf_sym_pyx.memoryview", - sizeof(struct __pyx_memoryview_obj), - 0, - Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, - __pyx_type___pyx_memoryview_slots, -}; -#else - -static PySequenceMethods __pyx_tp_as_sequence_memoryview = { - __pyx_memoryview___len__, /*sq_length*/ - 0, /*sq_concat*/ - 0, /*sq_repeat*/ - __pyx_sq_item_memoryview, /*sq_item*/ - 0, /*sq_slice*/ - 0, /*sq_ass_item*/ - 0, /*sq_ass_slice*/ - 0, /*sq_contains*/ - 0, /*sq_inplace_concat*/ - 0, /*sq_inplace_repeat*/ -}; - -static PyMappingMethods __pyx_tp_as_mapping_memoryview = { - __pyx_memoryview___len__, /*mp_length*/ - __pyx_memoryview___getitem__, /*mp_subscript*/ - __pyx_mp_ass_subscript_memoryview, /*mp_ass_subscript*/ -}; - -static PyBufferProcs __pyx_tp_as_buffer_memoryview = { - #if PY_MAJOR_VERSION < 3 - 0, /*bf_getreadbuffer*/ - #endif - #if PY_MAJOR_VERSION < 3 - 0, /*bf_getwritebuffer*/ - #endif - #if PY_MAJOR_VERSION < 3 - 0, /*bf_getsegcount*/ - #endif - #if PY_MAJOR_VERSION < 3 - 0, /*bf_getcharbuffer*/ - #endif - __pyx_memoryview_getbuffer, /*bf_getbuffer*/ - 0, /*bf_releasebuffer*/ -}; - -static PyTypeObject __pyx_type___pyx_memoryview = { - PyVarObject_HEAD_INIT(0, 0) - "rednose.helpers.ekf_sym_pyx.""memoryview", /*tp_name*/ - sizeof(struct __pyx_memoryview_obj), /*tp_basicsize*/ - 0, /*tp_itemsize*/ - __pyx_tp_dealloc_memoryview, /*tp_dealloc*/ - #if PY_VERSION_HEX < 0x030800b4 - 0, /*tp_print*/ - #endif - #if PY_VERSION_HEX >= 0x030800b4 - 0, /*tp_vectorcall_offset*/ - #endif - 0, /*tp_getattr*/ - 0, /*tp_setattr*/ - #if PY_MAJOR_VERSION < 3 - 0, /*tp_compare*/ - #endif - #if PY_MAJOR_VERSION >= 3 - 0, /*tp_as_async*/ - #endif - __pyx_memoryview___repr__, /*tp_repr*/ - 0, /*tp_as_number*/ - &__pyx_tp_as_sequence_memoryview, /*tp_as_sequence*/ - &__pyx_tp_as_mapping_memoryview, /*tp_as_mapping*/ - 0, /*tp_hash*/ - 0, /*tp_call*/ - __pyx_memoryview___str__, /*tp_str*/ - 0, /*tp_getattro*/ - 0, /*tp_setattro*/ - &__pyx_tp_as_buffer_memoryview, /*tp_as_buffer*/ - Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, /*tp_flags*/ - 0, /*tp_doc*/ - __pyx_tp_traverse_memoryview, /*tp_traverse*/ - __pyx_tp_clear_memoryview, /*tp_clear*/ - 0, /*tp_richcompare*/ - 0, /*tp_weaklistoffset*/ - 0, /*tp_iter*/ - 0, /*tp_iternext*/ - __pyx_methods_memoryview, /*tp_methods*/ - 0, /*tp_members*/ - __pyx_getsets_memoryview, /*tp_getset*/ - 0, /*tp_base*/ - 0, /*tp_dict*/ - 0, /*tp_descr_get*/ - 0, /*tp_descr_set*/ - #if !CYTHON_USE_TYPE_SPECS - 0, /*tp_dictoffset*/ - #endif - 0, /*tp_init*/ - 0, /*tp_alloc*/ - __pyx_tp_new_memoryview, /*tp_new*/ - 0, /*tp_free*/ - 0, /*tp_is_gc*/ - 0, /*tp_bases*/ - 0, /*tp_mro*/ - 0, /*tp_cache*/ - 0, /*tp_subclasses*/ - 0, /*tp_weaklist*/ - 0, /*tp_del*/ - 0, /*tp_version_tag*/ - #if PY_VERSION_HEX >= 0x030400a1 - #if CYTHON_USE_TP_FINALIZE - 0, /*tp_finalize*/ - #else - NULL, /*tp_finalize*/ - #endif - #endif - #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) - 0, /*tp_vectorcall*/ - #endif - #if __PYX_NEED_TP_PRINT_SLOT == 1 - 0, /*tp_print*/ - #endif - #if PY_VERSION_HEX >= 0x030C0000 - 0, /*tp_watched*/ - #endif - #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 - 0, /*tp_pypy_flags*/ - #endif -}; -#endif -static struct __pyx_vtabstruct__memoryviewslice __pyx_vtable__memoryviewslice; - -static PyObject *__pyx_tp_new__memoryviewslice(PyTypeObject *t, PyObject *a, PyObject *k) { - struct __pyx_memoryviewslice_obj *p; - PyObject *o = __pyx_tp_new_memoryview(t, a, k); - if (unlikely(!o)) return 0; - p = ((struct __pyx_memoryviewslice_obj *)o); - p->__pyx_base.__pyx_vtab = (struct __pyx_vtabstruct_memoryview*)__pyx_vtabptr__memoryviewslice; - new((void*)&(p->from_slice)) __Pyx_memviewslice(); - p->from_object = Py_None; Py_INCREF(Py_None); - p->from_slice.memview = NULL; - return o; -} - -static void __pyx_tp_dealloc__memoryviewslice(PyObject *o) { - struct __pyx_memoryviewslice_obj *p = (struct __pyx_memoryviewslice_obj *)o; - #if CYTHON_USE_TP_FINALIZE - if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { - if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc__memoryviewslice) { - if (PyObject_CallFinalizerFromDealloc(o)) return; - } - } - #endif - PyObject_GC_UnTrack(o); - { - PyObject *etype, *eval, *etb; - PyErr_Fetch(&etype, &eval, &etb); - __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); - __pyx_memoryviewslice___dealloc__(o); - __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); - PyErr_Restore(etype, eval, etb); - } - __Pyx_call_destructor(p->from_slice); - Py_CLEAR(p->from_object); - PyObject_GC_Track(o); - __pyx_tp_dealloc_memoryview(o); -} - -static int __pyx_tp_traverse__memoryviewslice(PyObject *o, visitproc v, void *a) { - int e; - struct __pyx_memoryviewslice_obj *p = (struct __pyx_memoryviewslice_obj *)o; - e = __pyx_tp_traverse_memoryview(o, v, a); if (e) return e; - if (p->from_object) { - e = (*v)(p->from_object, a); if (e) return e; - } - return 0; -} - -static int __pyx_tp_clear__memoryviewslice(PyObject *o) { - PyObject* tmp; - struct __pyx_memoryviewslice_obj *p = (struct __pyx_memoryviewslice_obj *)o; - __pyx_tp_clear_memoryview(o); - tmp = ((PyObject*)p->from_object); - p->from_object = Py_None; Py_INCREF(Py_None); - Py_XDECREF(tmp); - __PYX_XCLEAR_MEMVIEW(&p->from_slice, 1); - return 0; -} - -static PyMethodDef __pyx_methods__memoryviewslice[] = { - {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryviewslice_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, - {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryviewslice_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, - {0, 0, 0, 0} -}; -#if CYTHON_USE_TYPE_SPECS -static PyType_Slot __pyx_type___pyx_memoryviewslice_slots[] = { - {Py_tp_dealloc, (void *)__pyx_tp_dealloc__memoryviewslice}, - {Py_tp_doc, (void *)PyDoc_STR("Internal class for passing memoryview slices to Python")}, - {Py_tp_traverse, (void *)__pyx_tp_traverse__memoryviewslice}, - {Py_tp_clear, (void *)__pyx_tp_clear__memoryviewslice}, - {Py_tp_methods, (void *)__pyx_methods__memoryviewslice}, - {Py_tp_new, (void *)__pyx_tp_new__memoryviewslice}, - {0, 0}, -}; -static PyType_Spec __pyx_type___pyx_memoryviewslice_spec = { - "rednose.helpers.ekf_sym_pyx._memoryviewslice", - sizeof(struct __pyx_memoryviewslice_obj), - 0, - Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC|Py_TPFLAGS_SEQUENCE, - __pyx_type___pyx_memoryviewslice_slots, -}; -#else - -static PyTypeObject __pyx_type___pyx_memoryviewslice = { - PyVarObject_HEAD_INIT(0, 0) - "rednose.helpers.ekf_sym_pyx.""_memoryviewslice", /*tp_name*/ - sizeof(struct __pyx_memoryviewslice_obj), /*tp_basicsize*/ - 0, /*tp_itemsize*/ - __pyx_tp_dealloc__memoryviewslice, /*tp_dealloc*/ - #if PY_VERSION_HEX < 0x030800b4 - 0, /*tp_print*/ - #endif - #if PY_VERSION_HEX >= 0x030800b4 - 0, /*tp_vectorcall_offset*/ - #endif - 0, /*tp_getattr*/ - 0, /*tp_setattr*/ - #if PY_MAJOR_VERSION < 3 - 0, /*tp_compare*/ - #endif - #if PY_MAJOR_VERSION >= 3 - 0, /*tp_as_async*/ - #endif - #if CYTHON_COMPILING_IN_PYPY || 0 - __pyx_memoryview___repr__, /*tp_repr*/ - #else - 0, /*tp_repr*/ - #endif - 0, /*tp_as_number*/ - 0, /*tp_as_sequence*/ - 0, /*tp_as_mapping*/ - 0, /*tp_hash*/ - 0, /*tp_call*/ - #if CYTHON_COMPILING_IN_PYPY || 0 - __pyx_memoryview___str__, /*tp_str*/ - #else - 0, /*tp_str*/ - #endif - 0, /*tp_getattro*/ - 0, /*tp_setattro*/ - 0, /*tp_as_buffer*/ - Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC|Py_TPFLAGS_SEQUENCE, /*tp_flags*/ - PyDoc_STR("Internal class for passing memoryview slices to Python"), /*tp_doc*/ - __pyx_tp_traverse__memoryviewslice, /*tp_traverse*/ - __pyx_tp_clear__memoryviewslice, /*tp_clear*/ - 0, /*tp_richcompare*/ - 0, /*tp_weaklistoffset*/ - 0, /*tp_iter*/ - 0, /*tp_iternext*/ - __pyx_methods__memoryviewslice, /*tp_methods*/ - 0, /*tp_members*/ - 0, /*tp_getset*/ - 0, /*tp_base*/ - 0, /*tp_dict*/ - 0, /*tp_descr_get*/ - 0, /*tp_descr_set*/ - #if !CYTHON_USE_TYPE_SPECS - 0, /*tp_dictoffset*/ - #endif - 0, /*tp_init*/ - 0, /*tp_alloc*/ - __pyx_tp_new__memoryviewslice, /*tp_new*/ - 0, /*tp_free*/ - 0, /*tp_is_gc*/ - 0, /*tp_bases*/ - 0, /*tp_mro*/ - 0, /*tp_cache*/ - 0, /*tp_subclasses*/ - 0, /*tp_weaklist*/ - 0, /*tp_del*/ - 0, /*tp_version_tag*/ - #if PY_VERSION_HEX >= 0x030400a1 - #if CYTHON_USE_TP_FINALIZE - 0, /*tp_finalize*/ - #else - NULL, /*tp_finalize*/ - #endif - #endif - #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) - 0, /*tp_vectorcall*/ - #endif - #if __PYX_NEED_TP_PRINT_SLOT == 1 - 0, /*tp_print*/ - #endif - #if PY_VERSION_HEX >= 0x030C0000 - 0, /*tp_watched*/ - #endif - #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 - 0, /*tp_pypy_flags*/ - #endif -}; -#endif - -static PyMethodDef __pyx_methods[] = { - {0, 0, 0, 0} -}; -#ifndef CYTHON_SMALL_CODE -#if defined(__clang__) - #define CYTHON_SMALL_CODE -#elif defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 3)) - #define CYTHON_SMALL_CODE __attribute__((cold)) -#else - #define CYTHON_SMALL_CODE -#endif -#endif -/* #### Code section: pystring_table ### */ - -static int __Pyx_CreateStringTabAndInitStrings(void) { - __Pyx_StringTabEntry __pyx_string_tab[] = { - {&__pyx_kp_u_, __pyx_k_, sizeof(__pyx_k_), 0, 1, 0, 0}, - {&__pyx_n_s_ASCII, __pyx_k_ASCII, sizeof(__pyx_k_ASCII), 0, 0, 1, 1}, - {&__pyx_kp_s_All_dimensions_preceding_dimensi, __pyx_k_All_dimensions_preceding_dimensi, sizeof(__pyx_k_All_dimensions_preceding_dimensi), 0, 0, 1, 0}, - {&__pyx_n_s_AssertionError, __pyx_k_AssertionError, sizeof(__pyx_k_AssertionError), 0, 0, 1, 1}, - {&__pyx_kp_s_Buffer_view_does_not_expose_stri, __pyx_k_Buffer_view_does_not_expose_stri, sizeof(__pyx_k_Buffer_view_does_not_expose_stri), 0, 0, 1, 0}, - {&__pyx_n_u_C, __pyx_k_C, sizeof(__pyx_k_C), 0, 1, 0, 1}, - {&__pyx_kp_s_Can_only_create_a_buffer_that_is, __pyx_k_Can_only_create_a_buffer_that_is, sizeof(__pyx_k_Can_only_create_a_buffer_that_is), 0, 0, 1, 0}, - {&__pyx_kp_s_Cannot_assign_to_read_only_memor, __pyx_k_Cannot_assign_to_read_only_memor, sizeof(__pyx_k_Cannot_assign_to_read_only_memor), 0, 0, 1, 0}, - {&__pyx_kp_s_Cannot_create_writable_memory_vi, __pyx_k_Cannot_create_writable_memory_vi, sizeof(__pyx_k_Cannot_create_writable_memory_vi), 0, 0, 1, 0}, - {&__pyx_kp_u_Cannot_index_with_type, __pyx_k_Cannot_index_with_type, sizeof(__pyx_k_Cannot_index_with_type), 0, 1, 0, 0}, - {&__pyx_kp_s_Cannot_transpose_memoryview_with, __pyx_k_Cannot_transpose_memoryview_with, sizeof(__pyx_k_Cannot_transpose_memoryview_with), 0, 0, 1, 0}, - {&__pyx_kp_s_Dimension_d_is_not_direct, __pyx_k_Dimension_d_is_not_direct, sizeof(__pyx_k_Dimension_d_is_not_direct), 0, 0, 1, 0}, - {&__pyx_n_s_EKF_sym_pyx, __pyx_k_EKF_sym_pyx, sizeof(__pyx_k_EKF_sym_pyx), 0, 0, 1, 1}, - {&__pyx_n_s_EKF_sym_pyx___reduce_cython, __pyx_k_EKF_sym_pyx___reduce_cython, sizeof(__pyx_k_EKF_sym_pyx___reduce_cython), 0, 0, 1, 1}, - {&__pyx_n_s_EKF_sym_pyx___setstate_cython, __pyx_k_EKF_sym_pyx___setstate_cython, sizeof(__pyx_k_EKF_sym_pyx___setstate_cython), 0, 0, 1, 1}, - {&__pyx_n_s_EKF_sym_pyx_augment, __pyx_k_EKF_sym_pyx_augment, sizeof(__pyx_k_EKF_sym_pyx_augment), 0, 0, 1, 1}, - {&__pyx_n_s_EKF_sym_pyx_covs, __pyx_k_EKF_sym_pyx_covs, sizeof(__pyx_k_EKF_sym_pyx_covs), 0, 0, 1, 1}, - {&__pyx_n_s_EKF_sym_pyx_get_augment_times, __pyx_k_EKF_sym_pyx_get_augment_times, sizeof(__pyx_k_EKF_sym_pyx_get_augment_times), 0, 0, 1, 1}, - {&__pyx_n_s_EKF_sym_pyx_get_filter_time, __pyx_k_EKF_sym_pyx_get_filter_time, sizeof(__pyx_k_EKF_sym_pyx_get_filter_time), 0, 0, 1, 1}, - {&__pyx_n_s_EKF_sym_pyx_init_state, __pyx_k_EKF_sym_pyx_init_state, sizeof(__pyx_k_EKF_sym_pyx_init_state), 0, 0, 1, 1}, - {&__pyx_n_s_EKF_sym_pyx_maha_test, __pyx_k_EKF_sym_pyx_maha_test, sizeof(__pyx_k_EKF_sym_pyx_maha_test), 0, 0, 1, 1}, - {&__pyx_n_s_EKF_sym_pyx_predict, __pyx_k_EKF_sym_pyx_predict, sizeof(__pyx_k_EKF_sym_pyx_predict), 0, 0, 1, 1}, - {&__pyx_n_s_EKF_sym_pyx_predict_and_update_b, __pyx_k_EKF_sym_pyx_predict_and_update_b, sizeof(__pyx_k_EKF_sym_pyx_predict_and_update_b), 0, 0, 1, 1}, - {&__pyx_n_s_EKF_sym_pyx_reset_rewind, __pyx_k_EKF_sym_pyx_reset_rewind, sizeof(__pyx_k_EKF_sym_pyx_reset_rewind), 0, 0, 1, 1}, - {&__pyx_n_s_EKF_sym_pyx_rts_smooth, __pyx_k_EKF_sym_pyx_rts_smooth, sizeof(__pyx_k_EKF_sym_pyx_rts_smooth), 0, 0, 1, 1}, - {&__pyx_n_s_EKF_sym_pyx_set_filter_time, __pyx_k_EKF_sym_pyx_set_filter_time, sizeof(__pyx_k_EKF_sym_pyx_set_filter_time), 0, 0, 1, 1}, - {&__pyx_n_s_EKF_sym_pyx_set_global, __pyx_k_EKF_sym_pyx_set_global, sizeof(__pyx_k_EKF_sym_pyx_set_global), 0, 0, 1, 1}, - {&__pyx_n_s_EKF_sym_pyx_state, __pyx_k_EKF_sym_pyx_state, sizeof(__pyx_k_EKF_sym_pyx_state), 0, 0, 1, 1}, - {&__pyx_n_s_Ellipsis, __pyx_k_Ellipsis, sizeof(__pyx_k_Ellipsis), 0, 0, 1, 1}, - {&__pyx_kp_s_Empty_shape_tuple_for_cython_arr, __pyx_k_Empty_shape_tuple_for_cython_arr, sizeof(__pyx_k_Empty_shape_tuple_for_cython_arr), 0, 0, 1, 0}, - {&__pyx_n_s_ImportError, __pyx_k_ImportError, sizeof(__pyx_k_ImportError), 0, 0, 1, 1}, - {&__pyx_kp_s_Incompatible_checksums_0x_x_vs_0, __pyx_k_Incompatible_checksums_0x_x_vs_0, sizeof(__pyx_k_Incompatible_checksums_0x_x_vs_0), 0, 0, 1, 0}, - {&__pyx_n_s_IndexError, __pyx_k_IndexError, sizeof(__pyx_k_IndexError), 0, 0, 1, 1}, - {&__pyx_kp_s_Index_out_of_bounds_axis_d, __pyx_k_Index_out_of_bounds_axis_d, sizeof(__pyx_k_Index_out_of_bounds_axis_d), 0, 0, 1, 0}, - {&__pyx_kp_s_Indirect_dimensions_not_supporte, __pyx_k_Indirect_dimensions_not_supporte, sizeof(__pyx_k_Indirect_dimensions_not_supporte), 0, 0, 1, 0}, - {&__pyx_kp_u_Invalid_mode_expected_c_or_fortr, __pyx_k_Invalid_mode_expected_c_or_fortr, sizeof(__pyx_k_Invalid_mode_expected_c_or_fortr), 0, 1, 0, 0}, - {&__pyx_kp_u_Invalid_shape_in_axis, __pyx_k_Invalid_shape_in_axis, sizeof(__pyx_k_Invalid_shape_in_axis), 0, 1, 0, 0}, - {&__pyx_n_s_MemoryError, __pyx_k_MemoryError, sizeof(__pyx_k_MemoryError), 0, 0, 1, 1}, - {&__pyx_kp_s_MemoryView_of_r_at_0x_x, __pyx_k_MemoryView_of_r_at_0x_x, sizeof(__pyx_k_MemoryView_of_r_at_0x_x), 0, 0, 1, 0}, - {&__pyx_kp_s_MemoryView_of_r_object, __pyx_k_MemoryView_of_r_object, sizeof(__pyx_k_MemoryView_of_r_object), 0, 0, 1, 0}, - {&__pyx_n_s_N, __pyx_k_N, sizeof(__pyx_k_N), 0, 0, 1, 1}, - {&__pyx_n_s_NotImplementedError, __pyx_k_NotImplementedError, sizeof(__pyx_k_NotImplementedError), 0, 0, 1, 1}, - {&__pyx_n_b_O, __pyx_k_O, sizeof(__pyx_k_O), 0, 0, 0, 1}, - {&__pyx_kp_u_Out_of_bounds_on_buffer_access_a, __pyx_k_Out_of_bounds_on_buffer_access_a, sizeof(__pyx_k_Out_of_bounds_on_buffer_access_a), 0, 1, 0, 0}, - {&__pyx_n_s_P, __pyx_k_P, sizeof(__pyx_k_P), 0, 0, 1, 1}, - {&__pyx_n_s_P_initial, __pyx_k_P_initial, sizeof(__pyx_k_P_initial), 0, 0, 1, 1}, - {&__pyx_n_s_PickleError, __pyx_k_PickleError, sizeof(__pyx_k_PickleError), 0, 0, 1, 1}, - {&__pyx_n_s_Q, __pyx_k_Q, sizeof(__pyx_k_Q), 0, 0, 1, 1}, - {&__pyx_n_s_R, __pyx_k_R, sizeof(__pyx_k_R), 0, 0, 1, 1}, - {&__pyx_n_s_R_map, __pyx_k_R_map, sizeof(__pyx_k_R_map), 0, 0, 1, 1}, - {&__pyx_n_s_Ri, __pyx_k_Ri, sizeof(__pyx_k_Ri), 0, 0, 1, 1}, - {&__pyx_n_s_Ri_b, __pyx_k_Ri_b, sizeof(__pyx_k_Ri_b), 0, 0, 1, 1}, - {&__pyx_n_s_Sequence, __pyx_k_Sequence, sizeof(__pyx_k_Sequence), 0, 0, 1, 1}, - {&__pyx_kp_s_Step_may_not_be_zero_axis_d, __pyx_k_Step_may_not_be_zero_axis_d, sizeof(__pyx_k_Step_may_not_be_zero_axis_d), 0, 0, 1, 0}, - {&__pyx_kp_b_T, __pyx_k_T, sizeof(__pyx_k_T), 0, 0, 0, 0}, - {&__pyx_n_s_TypeError, __pyx_k_TypeError, sizeof(__pyx_k_TypeError), 0, 0, 1, 1}, - {&__pyx_kp_s_Unable_to_convert_item_to_object, __pyx_k_Unable_to_convert_item_to_object, sizeof(__pyx_k_Unable_to_convert_item_to_object), 0, 0, 1, 0}, - {&__pyx_n_s_ValueError, __pyx_k_ValueError, sizeof(__pyx_k_ValueError), 0, 0, 1, 1}, - {&__pyx_n_s_View_MemoryView, __pyx_k_View_MemoryView, sizeof(__pyx_k_View_MemoryView), 0, 0, 1, 1}, - {&__pyx_kp_b__10, __pyx_k__10, sizeof(__pyx_k__10), 0, 0, 0, 0}, - {&__pyx_kp_b__11, __pyx_k__11, sizeof(__pyx_k__11), 0, 0, 0, 0}, - {&__pyx_kp_b__12, __pyx_k__12, sizeof(__pyx_k__12), 0, 0, 0, 0}, - {&__pyx_kp_u__13, __pyx_k__13, sizeof(__pyx_k__13), 0, 1, 0, 0}, - {&__pyx_kp_u__14, __pyx_k__14, sizeof(__pyx_k__14), 0, 1, 0, 0}, - {&__pyx_kp_u__2, __pyx_k__2, sizeof(__pyx_k__2), 0, 1, 0, 0}, - {&__pyx_n_s__3, __pyx_k__3, sizeof(__pyx_k__3), 0, 0, 1, 1}, - {&__pyx_n_s__58, __pyx_k__58, sizeof(__pyx_k__58), 0, 0, 1, 1}, - {&__pyx_kp_u__6, __pyx_k__6, sizeof(__pyx_k__6), 0, 1, 0, 0}, - {&__pyx_kp_u__7, __pyx_k__7, sizeof(__pyx_k__7), 0, 1, 0, 0}, - {&__pyx_kp_b__9, __pyx_k__9, sizeof(__pyx_k__9), 0, 0, 0, 0}, - {&__pyx_n_s_a, __pyx_k_a, sizeof(__pyx_k_a), 0, 0, 1, 1}, - {&__pyx_n_s_abc, __pyx_k_abc, sizeof(__pyx_k_abc), 0, 0, 1, 1}, - {&__pyx_n_s_allocate_buffer, __pyx_k_allocate_buffer, sizeof(__pyx_k_allocate_buffer), 0, 0, 1, 1}, - {&__pyx_kp_u_and, __pyx_k_and, sizeof(__pyx_k_and), 0, 1, 0, 0}, - {&__pyx_n_s_args, __pyx_k_args, sizeof(__pyx_k_args), 0, 0, 1, 1}, - {&__pyx_n_s_args_map, __pyx_k_args_map, sizeof(__pyx_k_args_map), 0, 0, 1, 1}, - {&__pyx_n_s_asarray, __pyx_k_asarray, sizeof(__pyx_k_asarray), 0, 0, 1, 1}, - {&__pyx_n_s_ascontiguousarray, __pyx_k_ascontiguousarray, sizeof(__pyx_k_ascontiguousarray), 0, 0, 1, 1}, - {&__pyx_n_s_asyncio_coroutines, __pyx_k_asyncio_coroutines, sizeof(__pyx_k_asyncio_coroutines), 0, 0, 1, 1}, - {&__pyx_n_s_augment, __pyx_k_augment, sizeof(__pyx_k_augment), 0, 0, 1, 1}, - {&__pyx_n_s_base, __pyx_k_base, sizeof(__pyx_k_base), 0, 0, 1, 1}, - {&__pyx_n_s_c, __pyx_k_c, sizeof(__pyx_k_c), 0, 0, 1, 1}, - {&__pyx_n_u_c, __pyx_k_c, sizeof(__pyx_k_c), 0, 1, 0, 1}, - {&__pyx_n_s_class, __pyx_k_class, sizeof(__pyx_k_class), 0, 0, 1, 1}, - {&__pyx_n_s_class_getitem, __pyx_k_class_getitem, sizeof(__pyx_k_class_getitem), 0, 0, 1, 1}, - {&__pyx_n_s_cline_in_traceback, __pyx_k_cline_in_traceback, sizeof(__pyx_k_cline_in_traceback), 0, 0, 1, 1}, - {&__pyx_n_s_collections, __pyx_k_collections, sizeof(__pyx_k_collections), 0, 0, 1, 1}, - {&__pyx_kp_s_collections_abc, __pyx_k_collections_abc, sizeof(__pyx_k_collections_abc), 0, 0, 1, 0}, - {&__pyx_kp_s_contiguous_and_direct, __pyx_k_contiguous_and_direct, sizeof(__pyx_k_contiguous_and_direct), 0, 0, 1, 0}, - {&__pyx_kp_s_contiguous_and_indirect, __pyx_k_contiguous_and_indirect, sizeof(__pyx_k_contiguous_and_indirect), 0, 0, 1, 0}, - {&__pyx_n_s_copy, __pyx_k_copy, sizeof(__pyx_k_copy), 0, 0, 1, 1}, - {&__pyx_n_s_count, __pyx_k_count, sizeof(__pyx_k_count), 0, 0, 1, 1}, - {&__pyx_n_s_covs, __pyx_k_covs, sizeof(__pyx_k_covs), 0, 0, 1, 1}, - {&__pyx_n_s_covs_b, __pyx_k_covs_b, sizeof(__pyx_k_covs_b), 0, 0, 1, 1}, - {&__pyx_n_s_dict, __pyx_k_dict, sizeof(__pyx_k_dict), 0, 0, 1, 1}, - {&__pyx_n_s_dim_augment, __pyx_k_dim_augment, sizeof(__pyx_k_dim_augment), 0, 0, 1, 1}, - {&__pyx_n_s_dim_augment_err, __pyx_k_dim_augment_err, sizeof(__pyx_k_dim_augment_err), 0, 0, 1, 1}, - {&__pyx_n_s_dim_main, __pyx_k_dim_main, sizeof(__pyx_k_dim_main), 0, 0, 1, 1}, - {&__pyx_n_s_dim_main_err, __pyx_k_dim_main_err, sizeof(__pyx_k_dim_main_err), 0, 0, 1, 1}, - {&__pyx_kp_u_disable, __pyx_k_disable, sizeof(__pyx_k_disable), 0, 1, 0, 0}, - {&__pyx_n_s_double, __pyx_k_double, sizeof(__pyx_k_double), 0, 0, 1, 1}, - {&__pyx_n_s_dtype, __pyx_k_dtype, sizeof(__pyx_k_dtype), 0, 0, 1, 1}, - {&__pyx_n_s_dtype_is_object, __pyx_k_dtype_is_object, sizeof(__pyx_k_dtype_is_object), 0, 0, 1, 1}, - {&__pyx_kp_u_enable, __pyx_k_enable, sizeof(__pyx_k_enable), 0, 1, 0, 0}, - {&__pyx_n_s_encode, __pyx_k_encode, sizeof(__pyx_k_encode), 0, 0, 1, 1}, - {&__pyx_n_s_enumerate, __pyx_k_enumerate, sizeof(__pyx_k_enumerate), 0, 0, 1, 1}, - {&__pyx_n_s_error, __pyx_k_error, sizeof(__pyx_k_error), 0, 0, 1, 1}, - {&__pyx_n_s_estimates, __pyx_k_estimates, sizeof(__pyx_k_estimates), 0, 0, 1, 1}, - {&__pyx_n_s_extra_args, __pyx_k_extra_args, sizeof(__pyx_k_extra_args), 0, 0, 1, 1}, - {&__pyx_n_s_extra_args_map, __pyx_k_extra_args_map, sizeof(__pyx_k_extra_args_map), 0, 0, 1, 1}, - {&__pyx_n_s_filter_time, __pyx_k_filter_time, sizeof(__pyx_k_filter_time), 0, 0, 1, 1}, - {&__pyx_n_s_flags, __pyx_k_flags, sizeof(__pyx_k_flags), 0, 0, 1, 1}, - {&__pyx_n_s_format, __pyx_k_format, sizeof(__pyx_k_format), 0, 0, 1, 1}, - {&__pyx_n_s_fortran, __pyx_k_fortran, sizeof(__pyx_k_fortran), 0, 0, 1, 1}, - {&__pyx_n_u_fortran, __pyx_k_fortran, sizeof(__pyx_k_fortran), 0, 1, 0, 1}, - {&__pyx_kp_u_gc, __pyx_k_gc, sizeof(__pyx_k_gc), 0, 1, 0, 0}, - {&__pyx_n_s_gen_dir, __pyx_k_gen_dir, sizeof(__pyx_k_gen_dir), 0, 0, 1, 1}, - {&__pyx_n_s_get_augment_times, __pyx_k_get_augment_times, sizeof(__pyx_k_get_augment_times), 0, 0, 1, 1}, - {&__pyx_n_s_get_filter_time, __pyx_k_get_filter_time, sizeof(__pyx_k_get_filter_time), 0, 0, 1, 1}, - {&__pyx_n_s_getstate, __pyx_k_getstate, sizeof(__pyx_k_getstate), 0, 0, 1, 1}, - {&__pyx_n_s_global_var, __pyx_k_global_var, sizeof(__pyx_k_global_var), 0, 0, 1, 1}, - {&__pyx_n_s_global_vars, __pyx_k_global_vars, sizeof(__pyx_k_global_vars), 0, 0, 1, 1}, - {&__pyx_kp_u_got, __pyx_k_got, sizeof(__pyx_k_got), 0, 1, 0, 0}, - {&__pyx_kp_u_got_differing_extents_in_dimensi, __pyx_k_got_differing_extents_in_dimensi, sizeof(__pyx_k_got_differing_extents_in_dimensi), 0, 1, 0, 0}, - {&__pyx_n_s_id, __pyx_k_id, sizeof(__pyx_k_id), 0, 0, 1, 1}, - {&__pyx_n_s_import, __pyx_k_import, sizeof(__pyx_k_import), 0, 0, 1, 1}, - {&__pyx_n_s_index, __pyx_k_index, sizeof(__pyx_k_index), 0, 0, 1, 1}, - {&__pyx_n_s_init_state, __pyx_k_init_state, sizeof(__pyx_k_init_state), 0, 0, 1, 1}, - {&__pyx_n_s_initializing, __pyx_k_initializing, sizeof(__pyx_k_initializing), 0, 0, 1, 1}, - {&__pyx_n_s_is_coroutine, __pyx_k_is_coroutine, sizeof(__pyx_k_is_coroutine), 0, 0, 1, 1}, - {&__pyx_kp_u_isenabled, __pyx_k_isenabled, sizeof(__pyx_k_isenabled), 0, 1, 0, 0}, - {&__pyx_n_s_itemsize, __pyx_k_itemsize, sizeof(__pyx_k_itemsize), 0, 0, 1, 1}, - {&__pyx_kp_s_itemsize_0_for_cython_array, __pyx_k_itemsize_0_for_cython_array, sizeof(__pyx_k_itemsize_0_for_cython_array), 0, 0, 1, 0}, - {&__pyx_n_s_join, __pyx_k_join, sizeof(__pyx_k_join), 0, 0, 1, 1}, - {&__pyx_n_s_kind, __pyx_k_kind, sizeof(__pyx_k_kind), 0, 0, 1, 1}, - {&__pyx_n_s_logger, __pyx_k_logger, sizeof(__pyx_k_logger), 0, 0, 1, 1}, - {&__pyx_n_s_maha_test, __pyx_k_maha_test, sizeof(__pyx_k_maha_test), 0, 0, 1, 1}, - {&__pyx_n_s_maha_test_kinds, __pyx_k_maha_test_kinds, sizeof(__pyx_k_maha_test_kinds), 0, 0, 1, 1}, - {&__pyx_n_s_maha_thresh, __pyx_k_maha_thresh, sizeof(__pyx_k_maha_thresh), 0, 0, 1, 1}, - {&__pyx_n_s_main, __pyx_k_main, sizeof(__pyx_k_main), 0, 0, 1, 1}, - {&__pyx_n_s_max_rewind_age, __pyx_k_max_rewind_age, sizeof(__pyx_k_max_rewind_age), 0, 0, 1, 1}, - {&__pyx_n_s_memview, __pyx_k_memview, sizeof(__pyx_k_memview), 0, 0, 1, 1}, - {&__pyx_n_s_mode, __pyx_k_mode, sizeof(__pyx_k_mode), 0, 0, 1, 1}, - {&__pyx_n_s_name, __pyx_k_name, sizeof(__pyx_k_name), 0, 0, 1, 1}, - {&__pyx_n_s_name_2, __pyx_k_name_2, sizeof(__pyx_k_name_2), 0, 0, 1, 1}, - {&__pyx_n_s_nan, __pyx_k_nan, sizeof(__pyx_k_nan), 0, 0, 1, 1}, - {&__pyx_n_s_ndim, __pyx_k_ndim, sizeof(__pyx_k_ndim), 0, 0, 1, 1}, - {&__pyx_n_s_new, __pyx_k_new, sizeof(__pyx_k_new), 0, 0, 1, 1}, - {&__pyx_kp_s_no_default___reduce___due_to_non, __pyx_k_no_default___reduce___due_to_non, sizeof(__pyx_k_no_default___reduce___due_to_non), 0, 0, 1, 0}, - {&__pyx_n_s_norm_quats, __pyx_k_norm_quats, sizeof(__pyx_k_norm_quats), 0, 0, 1, 1}, - {&__pyx_n_s_np, __pyx_k_np, sizeof(__pyx_k_np), 0, 0, 1, 1}, - {&__pyx_n_s_numpy, __pyx_k_numpy, sizeof(__pyx_k_numpy), 0, 0, 1, 1}, - {&__pyx_kp_u_numpy_core_multiarray_failed_to, __pyx_k_numpy_core_multiarray_failed_to, sizeof(__pyx_k_numpy_core_multiarray_failed_to), 0, 1, 0, 0}, - {&__pyx_kp_u_numpy_core_umath_failed_to_impor, __pyx_k_numpy_core_umath_failed_to_impor, sizeof(__pyx_k_numpy_core_umath_failed_to_impor), 0, 1, 0, 0}, - {&__pyx_n_s_obj, __pyx_k_obj, sizeof(__pyx_k_obj), 0, 0, 1, 1}, - {&__pyx_n_s_order, __pyx_k_order, sizeof(__pyx_k_order), 0, 0, 1, 1}, - {&__pyx_n_s_pack, __pyx_k_pack, sizeof(__pyx_k_pack), 0, 0, 1, 1}, - {&__pyx_n_s_pickle, __pyx_k_pickle, sizeof(__pyx_k_pickle), 0, 0, 1, 1}, - {&__pyx_n_s_predict, __pyx_k_predict, sizeof(__pyx_k_predict), 0, 0, 1, 1}, - {&__pyx_n_s_predict_and_update_batch, __pyx_k_predict_and_update_batch, sizeof(__pyx_k_predict_and_update_batch), 0, 0, 1, 1}, - {&__pyx_n_s_pyx_PickleError, __pyx_k_pyx_PickleError, sizeof(__pyx_k_pyx_PickleError), 0, 0, 1, 1}, - {&__pyx_n_s_pyx_checksum, __pyx_k_pyx_checksum, sizeof(__pyx_k_pyx_checksum), 0, 0, 1, 1}, - {&__pyx_n_s_pyx_result, __pyx_k_pyx_result, sizeof(__pyx_k_pyx_result), 0, 0, 1, 1}, - {&__pyx_n_s_pyx_state, __pyx_k_pyx_state, sizeof(__pyx_k_pyx_state), 0, 0, 1, 1}, - {&__pyx_n_s_pyx_type, __pyx_k_pyx_type, sizeof(__pyx_k_pyx_type), 0, 0, 1, 1}, - {&__pyx_n_s_pyx_unpickle_Enum, __pyx_k_pyx_unpickle_Enum, sizeof(__pyx_k_pyx_unpickle_Enum), 0, 0, 1, 1}, - {&__pyx_n_s_pyx_vtable, __pyx_k_pyx_vtable, sizeof(__pyx_k_pyx_vtable), 0, 0, 1, 1}, - {&__pyx_n_s_quaternion_idxs, __pyx_k_quaternion_idxs, sizeof(__pyx_k_quaternion_idxs), 0, 0, 1, 1}, - {&__pyx_n_s_range, __pyx_k_range, sizeof(__pyx_k_range), 0, 0, 1, 1}, - {&__pyx_n_s_rednose_helpers_ekf_sym_pyx, __pyx_k_rednose_helpers_ekf_sym_pyx, sizeof(__pyx_k_rednose_helpers_ekf_sym_pyx), 0, 0, 1, 1}, - {&__pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx, __pyx_k_rednose_helpers_ekf_sym_pyx_pyx, sizeof(__pyx_k_rednose_helpers_ekf_sym_pyx_pyx), 0, 0, 1, 0}, - {&__pyx_n_s_reduce, __pyx_k_reduce, sizeof(__pyx_k_reduce), 0, 0, 1, 1}, - {&__pyx_n_s_reduce_cython, __pyx_k_reduce_cython, sizeof(__pyx_k_reduce_cython), 0, 0, 1, 1}, - {&__pyx_n_s_reduce_ex, __pyx_k_reduce_ex, sizeof(__pyx_k_reduce_ex), 0, 0, 1, 1}, - {&__pyx_n_s_register, __pyx_k_register, sizeof(__pyx_k_register), 0, 0, 1, 1}, - {&__pyx_n_s_res, __pyx_k_res, sizeof(__pyx_k_res), 0, 0, 1, 1}, - {&__pyx_n_s_reset_rewind, __pyx_k_reset_rewind, sizeof(__pyx_k_reset_rewind), 0, 0, 1, 1}, - {&__pyx_n_s_rts_smooth, __pyx_k_rts_smooth, sizeof(__pyx_k_rts_smooth), 0, 0, 1, 1}, - {&__pyx_n_s_self, __pyx_k_self, sizeof(__pyx_k_self), 0, 0, 1, 1}, - {&__pyx_n_s_set_filter_time, __pyx_k_set_filter_time, sizeof(__pyx_k_set_filter_time), 0, 0, 1, 1}, - {&__pyx_n_s_set_global, __pyx_k_set_global, sizeof(__pyx_k_set_global), 0, 0, 1, 1}, - {&__pyx_n_s_setstate, __pyx_k_setstate, sizeof(__pyx_k_setstate), 0, 0, 1, 1}, - {&__pyx_n_s_setstate_cython, __pyx_k_setstate_cython, sizeof(__pyx_k_setstate_cython), 0, 0, 1, 1}, - {&__pyx_n_s_shape, __pyx_k_shape, sizeof(__pyx_k_shape), 0, 0, 1, 1}, - {&__pyx_n_s_size, __pyx_k_size, sizeof(__pyx_k_size), 0, 0, 1, 1}, - {&__pyx_n_s_spec, __pyx_k_spec, sizeof(__pyx_k_spec), 0, 0, 1, 1}, - {&__pyx_n_s_start, __pyx_k_start, sizeof(__pyx_k_start), 0, 0, 1, 1}, - {&__pyx_n_s_state, __pyx_k_state, sizeof(__pyx_k_state), 0, 0, 1, 1}, - {&__pyx_n_s_state_b, __pyx_k_state_b, sizeof(__pyx_k_state_b), 0, 0, 1, 1}, - {&__pyx_n_s_step, __pyx_k_step, sizeof(__pyx_k_step), 0, 0, 1, 1}, - {&__pyx_n_s_stop, __pyx_k_stop, sizeof(__pyx_k_stop), 0, 0, 1, 1}, - {&__pyx_kp_s_strided_and_direct, __pyx_k_strided_and_direct, sizeof(__pyx_k_strided_and_direct), 0, 0, 1, 0}, - {&__pyx_kp_s_strided_and_direct_or_indirect, __pyx_k_strided_and_direct_or_indirect, sizeof(__pyx_k_strided_and_direct_or_indirect), 0, 0, 1, 0}, - {&__pyx_kp_s_strided_and_indirect, __pyx_k_strided_and_indirect, sizeof(__pyx_k_strided_and_indirect), 0, 0, 1, 0}, - {&__pyx_kp_s_stringsource, __pyx_k_stringsource, sizeof(__pyx_k_stringsource), 0, 0, 1, 0}, - {&__pyx_n_s_struct, __pyx_k_struct, sizeof(__pyx_k_struct), 0, 0, 1, 1}, - {&__pyx_n_s_sys, __pyx_k_sys, sizeof(__pyx_k_sys), 0, 0, 1, 1}, - {&__pyx_n_s_t, __pyx_k_t, sizeof(__pyx_k_t), 0, 0, 1, 1}, - {&__pyx_n_s_test, __pyx_k_test, sizeof(__pyx_k_test), 0, 0, 1, 1}, - {&__pyx_n_s_tmpvec, __pyx_k_tmpvec, sizeof(__pyx_k_tmpvec), 0, 0, 1, 1}, - {&__pyx_kp_s_unable_to_allocate_array_data, __pyx_k_unable_to_allocate_array_data, sizeof(__pyx_k_unable_to_allocate_array_data), 0, 0, 1, 0}, - {&__pyx_kp_s_unable_to_allocate_shape_and_str, __pyx_k_unable_to_allocate_shape_and_str, sizeof(__pyx_k_unable_to_allocate_shape_and_str), 0, 0, 1, 0}, - {&__pyx_n_s_unpack, __pyx_k_unpack, sizeof(__pyx_k_unpack), 0, 0, 1, 1}, - {&__pyx_n_s_update, __pyx_k_update, sizeof(__pyx_k_update), 0, 0, 1, 1}, - {&__pyx_n_u_utf8, __pyx_k_utf8, sizeof(__pyx_k_utf8), 0, 1, 0, 1}, - {&__pyx_n_s_val, __pyx_k_val, sizeof(__pyx_k_val), 0, 0, 1, 1}, - {&__pyx_n_s_version_info, __pyx_k_version_info, sizeof(__pyx_k_version_info), 0, 0, 1, 1}, - {&__pyx_n_s_x, __pyx_k_x, sizeof(__pyx_k_x), 0, 0, 1, 1}, - {&__pyx_n_s_x_initial, __pyx_k_x_initial, sizeof(__pyx_k_x_initial), 0, 0, 1, 1}, - {&__pyx_n_s_z, __pyx_k_z, sizeof(__pyx_k_z), 0, 0, 1, 1}, - {&__pyx_n_s_z_map, __pyx_k_z_map, sizeof(__pyx_k_z_map), 0, 0, 1, 1}, - {&__pyx_n_s_zi, __pyx_k_zi, sizeof(__pyx_k_zi), 0, 0, 1, 1}, - {&__pyx_n_s_zi_b, __pyx_k_zi_b, sizeof(__pyx_k_zi_b), 0, 0, 1, 1}, - {0, 0, 0, 0, 0, 0, 0} - }; - return __Pyx_InitStrings(__pyx_string_tab); -} -/* #### Code section: cached_builtins ### */ -static CYTHON_SMALL_CODE int __Pyx_InitCachedBuiltins(void) { - __pyx_builtin_NotImplementedError = __Pyx_GetBuiltinName(__pyx_n_s_NotImplementedError); if (!__pyx_builtin_NotImplementedError) __PYX_ERR(0, 183, __pyx_L1_error) - __pyx_builtin_TypeError = __Pyx_GetBuiltinName(__pyx_n_s_TypeError); if (!__pyx_builtin_TypeError) __PYX_ERR(1, 2, __pyx_L1_error) - __pyx_builtin___import__ = __Pyx_GetBuiltinName(__pyx_n_s_import); if (!__pyx_builtin___import__) __PYX_ERR(1, 100, __pyx_L1_error) - __pyx_builtin_ValueError = __Pyx_GetBuiltinName(__pyx_n_s_ValueError); if (!__pyx_builtin_ValueError) __PYX_ERR(1, 141, __pyx_L1_error) - __pyx_builtin_MemoryError = __Pyx_GetBuiltinName(__pyx_n_s_MemoryError); if (!__pyx_builtin_MemoryError) __PYX_ERR(1, 156, __pyx_L1_error) - __pyx_builtin_enumerate = __Pyx_GetBuiltinName(__pyx_n_s_enumerate); if (!__pyx_builtin_enumerate) __PYX_ERR(1, 159, __pyx_L1_error) - __pyx_builtin_range = __Pyx_GetBuiltinName(__pyx_n_s_range); if (!__pyx_builtin_range) __PYX_ERR(1, 261, __pyx_L1_error) - __pyx_builtin_AssertionError = __Pyx_GetBuiltinName(__pyx_n_s_AssertionError); if (!__pyx_builtin_AssertionError) __PYX_ERR(1, 373, __pyx_L1_error) - __pyx_builtin_Ellipsis = __Pyx_GetBuiltinName(__pyx_n_s_Ellipsis); if (!__pyx_builtin_Ellipsis) __PYX_ERR(1, 408, __pyx_L1_error) - __pyx_builtin_id = __Pyx_GetBuiltinName(__pyx_n_s_id); if (!__pyx_builtin_id) __PYX_ERR(1, 618, __pyx_L1_error) - __pyx_builtin_IndexError = __Pyx_GetBuiltinName(__pyx_n_s_IndexError); if (!__pyx_builtin_IndexError) __PYX_ERR(1, 914, __pyx_L1_error) - __pyx_builtin_ImportError = __Pyx_GetBuiltinName(__pyx_n_s_ImportError); if (!__pyx_builtin_ImportError) __PYX_ERR(2, 984, __pyx_L1_error) - return 0; - __pyx_L1_error:; - return -1; -} -/* #### Code section: cached_constants ### */ - -static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("__Pyx_InitCachedConstants", 0); - - /* "View.MemoryView":582 - * def suboffsets(self): - * if self.view.suboffsets == NULL: - * return (-1,) * self.view.ndim # <<<<<<<<<<<<<< - * - * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) - */ - __pyx_tuple__4 = PyTuple_New(1); if (unlikely(!__pyx_tuple__4)) __PYX_ERR(1, 582, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__4); - __Pyx_INCREF(__pyx_int_neg_1); - __Pyx_GIVEREF(__pyx_int_neg_1); - if (__Pyx_PyTuple_SET_ITEM(__pyx_tuple__4, 0, __pyx_int_neg_1)) __PYX_ERR(1, 582, __pyx_L1_error); - __Pyx_GIVEREF(__pyx_tuple__4); - - /* "View.MemoryView":679 - * tup = index if isinstance(index, tuple) else (index,) - * - * result = [slice(None)] * ndim # <<<<<<<<<<<<<< - * have_slices = False - * seen_ellipsis = False - */ - __pyx_slice__5 = PySlice_New(Py_None, Py_None, Py_None); if (unlikely(!__pyx_slice__5)) __PYX_ERR(1, 679, __pyx_L1_error) - __Pyx_GOTREF(__pyx_slice__5); - __Pyx_GIVEREF(__pyx_slice__5); - - /* "(tree fragment)":4 - * cdef object __pyx_PickleError - * cdef object __pyx_result - * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): # <<<<<<<<<<<<<< - * from pickle import PickleError as __pyx_PickleError - * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum - */ - __pyx_tuple__8 = PyTuple_Pack(3, __pyx_int_136983863, __pyx_int_112105877, __pyx_int_184977713); if (unlikely(!__pyx_tuple__8)) __PYX_ERR(1, 4, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__8); - __Pyx_GIVEREF(__pyx_tuple__8); - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":984 - * __pyx_import_array() - * except Exception: - * raise ImportError("numpy.core.multiarray failed to import") # <<<<<<<<<<<<<< - * - * cdef inline int import_umath() except -1: - */ - __pyx_tuple__15 = PyTuple_Pack(1, __pyx_kp_u_numpy_core_multiarray_failed_to); if (unlikely(!__pyx_tuple__15)) __PYX_ERR(2, 984, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__15); - __Pyx_GIVEREF(__pyx_tuple__15); - - /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":990 - * _import_umath() - * except Exception: - * raise ImportError("numpy.core.umath failed to import") # <<<<<<<<<<<<<< - * - * cdef inline int import_ufunc() except -1: - */ - __pyx_tuple__16 = PyTuple_Pack(1, __pyx_kp_u_numpy_core_umath_failed_to_impor); if (unlikely(!__pyx_tuple__16)) __PYX_ERR(2, 990, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__16); - __Pyx_GIVEREF(__pyx_tuple__16); - - /* "View.MemoryView":100 - * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" - * try: - * if __import__("sys").version_info >= (3, 3): # <<<<<<<<<<<<<< - * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence - * else: - */ - __pyx_tuple__37 = PyTuple_Pack(1, __pyx_n_s_sys); if (unlikely(!__pyx_tuple__37)) __PYX_ERR(1, 100, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__37); - __Pyx_GIVEREF(__pyx_tuple__37); - __pyx_tuple__38 = PyTuple_Pack(2, __pyx_int_3, __pyx_int_3); if (unlikely(!__pyx_tuple__38)) __PYX_ERR(1, 100, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__38); - __Pyx_GIVEREF(__pyx_tuple__38); - - /* "View.MemoryView":101 - * try: - * if __import__("sys").version_info >= (3, 3): - * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence # <<<<<<<<<<<<<< - * else: - * __pyx_collections_abc_Sequence = __import__("collections").Sequence - */ - __pyx_tuple__39 = PyTuple_Pack(1, __pyx_kp_s_collections_abc); if (unlikely(!__pyx_tuple__39)) __PYX_ERR(1, 101, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__39); - __Pyx_GIVEREF(__pyx_tuple__39); - - /* "View.MemoryView":103 - * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence - * else: - * __pyx_collections_abc_Sequence = __import__("collections").Sequence # <<<<<<<<<<<<<< - * except: - * - */ - __pyx_tuple__40 = PyTuple_Pack(1, __pyx_n_s_collections); if (unlikely(!__pyx_tuple__40)) __PYX_ERR(1, 103, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__40); - __Pyx_GIVEREF(__pyx_tuple__40); - - /* "View.MemoryView":309 - * return self.name - * - * cdef generic = Enum("") # <<<<<<<<<<<<<< - * cdef strided = Enum("") # default - * cdef indirect = Enum("") - */ - __pyx_tuple__41 = PyTuple_Pack(1, __pyx_kp_s_strided_and_direct_or_indirect); if (unlikely(!__pyx_tuple__41)) __PYX_ERR(1, 309, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__41); - __Pyx_GIVEREF(__pyx_tuple__41); - - /* "View.MemoryView":310 - * - * cdef generic = Enum("") - * cdef strided = Enum("") # default # <<<<<<<<<<<<<< - * cdef indirect = Enum("") - * - */ - __pyx_tuple__42 = PyTuple_Pack(1, __pyx_kp_s_strided_and_direct); if (unlikely(!__pyx_tuple__42)) __PYX_ERR(1, 310, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__42); - __Pyx_GIVEREF(__pyx_tuple__42); - - /* "View.MemoryView":311 - * cdef generic = Enum("") - * cdef strided = Enum("") # default - * cdef indirect = Enum("") # <<<<<<<<<<<<<< - * - * - */ - __pyx_tuple__43 = PyTuple_Pack(1, __pyx_kp_s_strided_and_indirect); if (unlikely(!__pyx_tuple__43)) __PYX_ERR(1, 311, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__43); - __Pyx_GIVEREF(__pyx_tuple__43); - - /* "View.MemoryView":314 - * - * - * cdef contiguous = Enum("") # <<<<<<<<<<<<<< - * cdef indirect_contiguous = Enum("") - * - */ - __pyx_tuple__44 = PyTuple_Pack(1, __pyx_kp_s_contiguous_and_direct); if (unlikely(!__pyx_tuple__44)) __PYX_ERR(1, 314, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__44); - __Pyx_GIVEREF(__pyx_tuple__44); - - /* "View.MemoryView":315 - * - * cdef contiguous = Enum("") - * cdef indirect_contiguous = Enum("") # <<<<<<<<<<<<<< - * - * - */ - __pyx_tuple__45 = PyTuple_Pack(1, __pyx_kp_s_contiguous_and_indirect); if (unlikely(!__pyx_tuple__45)) __PYX_ERR(1, 315, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__45); - __Pyx_GIVEREF(__pyx_tuple__45); - - /* "(tree fragment)":1 - * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< - * cdef object __pyx_PickleError - * cdef object __pyx_result - */ - __pyx_tuple__46 = PyTuple_Pack(5, __pyx_n_s_pyx_type, __pyx_n_s_pyx_checksum, __pyx_n_s_pyx_state, __pyx_n_s_pyx_PickleError, __pyx_n_s_pyx_result); if (unlikely(!__pyx_tuple__46)) __PYX_ERR(1, 1, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__46); - __Pyx_GIVEREF(__pyx_tuple__46); - __pyx_codeobj__47 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__46, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_pyx_unpickle_Enum, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__47)) __PYX_ERR(1, 1, __pyx_L1_error) - - /* "rednose/helpers/ekf_sym_pyx.pyx":113 - * ) - * - * def init_state(self, np.ndarray[np.float64_t, ndim=1] state, np.ndarray[np.float64_t, ndim=2] covs, filter_time): # <<<<<<<<<<<<<< - * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] state_b = np.ascontiguousarray(state, dtype=np.double) - * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] covs_b = np.ascontiguousarray(covs, dtype=np.double) - */ - __pyx_tuple__48 = PyTuple_Pack(6, __pyx_n_s_self, __pyx_n_s_state, __pyx_n_s_covs, __pyx_n_s_filter_time, __pyx_n_s_state_b, __pyx_n_s_covs_b); if (unlikely(!__pyx_tuple__48)) __PYX_ERR(0, 113, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__48); - __Pyx_GIVEREF(__pyx_tuple__48); - __pyx_codeobj__20 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 6, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__48, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx, __pyx_n_s_init_state, 113, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__20)) __PYX_ERR(0, 113, __pyx_L1_error) - - /* "rednose/helpers/ekf_sym_pyx.pyx":122 - * ) - * - * def state(self): # <<<<<<<<<<<<<< - * cdef np.ndarray res = vector_to_numpy(self.ekf.state()) - * return res - */ - __pyx_tuple__49 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_res); if (unlikely(!__pyx_tuple__49)) __PYX_ERR(0, 122, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__49); - __Pyx_GIVEREF(__pyx_tuple__49); - __pyx_codeobj__21 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__49, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx, __pyx_n_s_state, 122, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__21)) __PYX_ERR(0, 122, __pyx_L1_error) - - /* "rednose/helpers/ekf_sym_pyx.pyx":126 - * return res - * - * def covs(self): # <<<<<<<<<<<<<< - * return matrix_to_numpy(self.ekf.covs()) - * - */ - __pyx_tuple__50 = PyTuple_Pack(1, __pyx_n_s_self); if (unlikely(!__pyx_tuple__50)) __PYX_ERR(0, 126, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__50); - __Pyx_GIVEREF(__pyx_tuple__50); - __pyx_codeobj__22 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__50, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx, __pyx_n_s_covs, 126, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__22)) __PYX_ERR(0, 126, __pyx_L1_error) - - /* "rednose/helpers/ekf_sym_pyx.pyx":129 - * return matrix_to_numpy(self.ekf.covs()) - * - * def set_filter_time(self, double t): # <<<<<<<<<<<<<< - * self.ekf.set_filter_time(t) - * - */ - __pyx_tuple__51 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_t); if (unlikely(!__pyx_tuple__51)) __PYX_ERR(0, 129, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__51); - __Pyx_GIVEREF(__pyx_tuple__51); - __pyx_codeobj__23 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__51, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx, __pyx_n_s_set_filter_time, 129, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__23)) __PYX_ERR(0, 129, __pyx_L1_error) - - /* "rednose/helpers/ekf_sym_pyx.pyx":132 - * self.ekf.set_filter_time(t) - * - * def get_filter_time(self): # <<<<<<<<<<<<<< - * return self.ekf.get_filter_time() - * - */ - __pyx_codeobj__24 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__50, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx, __pyx_n_s_get_filter_time, 132, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__24)) __PYX_ERR(0, 132, __pyx_L1_error) - - /* "rednose/helpers/ekf_sym_pyx.pyx":135 - * return self.ekf.get_filter_time() - * - * def set_global(self, str global_var, double val): # <<<<<<<<<<<<<< - * self.ekf.set_global(global_var.encode('utf8'), val) - * - */ - __pyx_tuple__52 = PyTuple_Pack(3, __pyx_n_s_self, __pyx_n_s_global_var, __pyx_n_s_val); if (unlikely(!__pyx_tuple__52)) __PYX_ERR(0, 135, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__52); - __Pyx_GIVEREF(__pyx_tuple__52); - __pyx_codeobj__25 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 3, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__52, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx, __pyx_n_s_set_global, 135, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__25)) __PYX_ERR(0, 135, __pyx_L1_error) - - /* "rednose/helpers/ekf_sym_pyx.pyx":138 - * self.ekf.set_global(global_var.encode('utf8'), val) - * - * def reset_rewind(self): # <<<<<<<<<<<<<< - * self.ekf.reset_rewind() - * - */ - __pyx_codeobj__26 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__50, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx, __pyx_n_s_reset_rewind, 138, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__26)) __PYX_ERR(0, 138, __pyx_L1_error) - - /* "rednose/helpers/ekf_sym_pyx.pyx":141 - * self.ekf.reset_rewind() - * - * def predict(self, double t): # <<<<<<<<<<<<<< - * self.ekf.predict(t) - * - */ - __pyx_codeobj__27 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__51, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx, __pyx_n_s_predict, 141, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__27)) __PYX_ERR(0, 141, __pyx_L1_error) - - /* "rednose/helpers/ekf_sym_pyx.pyx":144 - * self.ekf.predict(t) - * - * def predict_and_update_batch(self, double t, int kind, z, R, extra_args=[[]], bool augment=False): # <<<<<<<<<<<<<< - * cdef vector[MapVectorXd] z_map - * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] zi_b - */ - __pyx_tuple__53 = PyTuple_Pack(20, __pyx_n_s_self, __pyx_n_s_t, __pyx_n_s_kind, __pyx_n_s_z, __pyx_n_s_R, __pyx_n_s_extra_args, __pyx_n_s_augment, __pyx_n_s_z_map, __pyx_n_s_zi_b, __pyx_n_s_zi, __pyx_n_s_R_map, __pyx_n_s_Ri_b, __pyx_n_s_Ri, __pyx_n_s_extra_args_map, __pyx_n_s_args_map, __pyx_n_s_args, __pyx_n_s_a, __pyx_n_s_res, __pyx_n_s_tmpvec, __pyx_n_s_tmpvec); if (unlikely(!__pyx_tuple__53)) __PYX_ERR(0, 144, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__53); - __Pyx_GIVEREF(__pyx_tuple__53); - __pyx_codeobj__29 = (PyObject*)__Pyx_PyCode_New(7, 0, 0, 20, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__53, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx, __pyx_n_s_predict_and_update_batch, 144, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__29)) __PYX_ERR(0, 144, __pyx_L1_error) - - /* "rednose/helpers/ekf_sym_pyx.pyx":182 - * ) - * - * def augment(self): # <<<<<<<<<<<<<< - * raise NotImplementedError() # TODO - * - */ - __pyx_codeobj__30 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__50, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx, __pyx_n_s_augment, 182, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__30)) __PYX_ERR(0, 182, __pyx_L1_error) - - /* "rednose/helpers/ekf_sym_pyx.pyx":185 - * raise NotImplementedError() # TODO - * - * def get_augment_times(self): # <<<<<<<<<<<<<< - * raise NotImplementedError() # TODO - * - */ - __pyx_codeobj__31 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__50, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx, __pyx_n_s_get_augment_times, 185, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__31)) __PYX_ERR(0, 185, __pyx_L1_error) - - /* "rednose/helpers/ekf_sym_pyx.pyx":188 - * raise NotImplementedError() # TODO - * - * def rts_smooth(self, estimates, norm_quats=False): # <<<<<<<<<<<<<< - * raise NotImplementedError() # TODO - * - */ - __pyx_tuple__54 = PyTuple_Pack(3, __pyx_n_s_self, __pyx_n_s_estimates, __pyx_n_s_norm_quats); if (unlikely(!__pyx_tuple__54)) __PYX_ERR(0, 188, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__54); - __Pyx_GIVEREF(__pyx_tuple__54); - __pyx_codeobj__32 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 3, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__54, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx, __pyx_n_s_rts_smooth, 188, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__32)) __PYX_ERR(0, 188, __pyx_L1_error) - __pyx_tuple__55 = PyTuple_Pack(1, Py_False); if (unlikely(!__pyx_tuple__55)) __PYX_ERR(0, 188, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__55); - __Pyx_GIVEREF(__pyx_tuple__55); - - /* "rednose/helpers/ekf_sym_pyx.pyx":191 - * raise NotImplementedError() # TODO - * - * def maha_test(self, x, P, kind, z, R, extra_args=[], maha_thresh=0.95): # <<<<<<<<<<<<<< - * raise NotImplementedError() # TODO - * - */ - __pyx_tuple__56 = PyTuple_Pack(8, __pyx_n_s_self, __pyx_n_s_x, __pyx_n_s_P, __pyx_n_s_kind, __pyx_n_s_z, __pyx_n_s_R, __pyx_n_s_extra_args, __pyx_n_s_maha_thresh); if (unlikely(!__pyx_tuple__56)) __PYX_ERR(0, 191, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__56); - __Pyx_GIVEREF(__pyx_tuple__56); - __pyx_codeobj__34 = (PyObject*)__Pyx_PyCode_New(8, 0, 0, 8, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__56, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx, __pyx_n_s_maha_test, 191, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__34)) __PYX_ERR(0, 191, __pyx_L1_error) - - /* "(tree fragment)":1 - * def __reduce_cython__(self): # <<<<<<<<<<<<<< - * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" - * def __setstate_cython__(self, __pyx_state): - */ - __pyx_codeobj__35 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__50, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__35)) __PYX_ERR(1, 1, __pyx_L1_error) - - /* "(tree fragment)":3 - * def __reduce_cython__(self): - * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" - * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< - * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" - */ - __pyx_tuple__57 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_pyx_state); if (unlikely(!__pyx_tuple__57)) __PYX_ERR(1, 3, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__57); - __Pyx_GIVEREF(__pyx_tuple__57); - __pyx_codeobj__36 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__57, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 3, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__36)) __PYX_ERR(1, 3, __pyx_L1_error) - __Pyx_RefNannyFinishContext(); - return 0; - __pyx_L1_error:; - __Pyx_RefNannyFinishContext(); - return -1; -} -/* #### Code section: init_constants ### */ - -static CYTHON_SMALL_CODE int __Pyx_InitConstants(void) { - if (__Pyx_CreateStringTabAndInitStrings() < 0) __PYX_ERR(0, 1, __pyx_L1_error); - __pyx_float_0_95 = PyFloat_FromDouble(0.95); if (unlikely(!__pyx_float_0_95)) __PYX_ERR(0, 1, __pyx_L1_error) - __pyx_int_0 = PyInt_FromLong(0); if (unlikely(!__pyx_int_0)) __PYX_ERR(0, 1, __pyx_L1_error) - __pyx_int_1 = PyInt_FromLong(1); if (unlikely(!__pyx_int_1)) __PYX_ERR(0, 1, __pyx_L1_error) - __pyx_int_3 = PyInt_FromLong(3); if (unlikely(!__pyx_int_3)) __PYX_ERR(0, 1, __pyx_L1_error) - __pyx_int_112105877 = PyInt_FromLong(112105877L); if (unlikely(!__pyx_int_112105877)) __PYX_ERR(0, 1, __pyx_L1_error) - __pyx_int_136983863 = PyInt_FromLong(136983863L); if (unlikely(!__pyx_int_136983863)) __PYX_ERR(0, 1, __pyx_L1_error) - __pyx_int_184977713 = PyInt_FromLong(184977713L); if (unlikely(!__pyx_int_184977713)) __PYX_ERR(0, 1, __pyx_L1_error) - __pyx_int_neg_1 = PyInt_FromLong(-1); if (unlikely(!__pyx_int_neg_1)) __PYX_ERR(0, 1, __pyx_L1_error) - return 0; - __pyx_L1_error:; - return -1; -} -/* #### Code section: init_globals ### */ - -static CYTHON_SMALL_CODE int __Pyx_InitGlobals(void) { - /* AssertionsEnabled.init */ - if (likely(__Pyx_init_assertions_enabled() == 0)); else - -if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 1, __pyx_L1_error) - - /* NumpyImportArray.init */ - /* - * Cython has automatically inserted a call to _import_array since - * you didn't include one when you cimported numpy. To disable this - * add the line - * numpy._import_array - */ -#ifdef NPY_FEATURE_VERSION -#ifndef NO_IMPORT_ARRAY -if (unlikely(_import_array() == -1)) { - PyErr_SetString(PyExc_ImportError, "numpy.core.multiarray failed to import " - "(auto-generated because you didn't call 'numpy.import_array()' after cimporting numpy; " - "use 'numpy._import_array' to disable if you are certain you don't need it)."); -} -#endif -#endif - -if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 1, __pyx_L1_error) - - return 0; - __pyx_L1_error:; - return -1; -} -/* #### Code section: init_module ### */ - -static CYTHON_SMALL_CODE int __Pyx_modinit_global_init_code(void); /*proto*/ -static CYTHON_SMALL_CODE int __Pyx_modinit_variable_export_code(void); /*proto*/ -static CYTHON_SMALL_CODE int __Pyx_modinit_function_export_code(void); /*proto*/ -static CYTHON_SMALL_CODE int __Pyx_modinit_type_init_code(void); /*proto*/ -static CYTHON_SMALL_CODE int __Pyx_modinit_type_import_code(void); /*proto*/ -static CYTHON_SMALL_CODE int __Pyx_modinit_variable_import_code(void); /*proto*/ -static CYTHON_SMALL_CODE int __Pyx_modinit_function_import_code(void); /*proto*/ - -static int __Pyx_modinit_global_init_code(void) { - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("__Pyx_modinit_global_init_code", 0); - /*--- Global init code ---*/ - __pyx_collections_abc_Sequence = Py_None; Py_INCREF(Py_None); - generic = Py_None; Py_INCREF(Py_None); - strided = Py_None; Py_INCREF(Py_None); - indirect = Py_None; Py_INCREF(Py_None); - contiguous = Py_None; Py_INCREF(Py_None); - indirect_contiguous = Py_None; Py_INCREF(Py_None); - __Pyx_RefNannyFinishContext(); - return 0; -} - -static int __Pyx_modinit_variable_export_code(void) { - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("__Pyx_modinit_variable_export_code", 0); - /*--- Variable export code ---*/ - __Pyx_RefNannyFinishContext(); - return 0; -} - -static int __Pyx_modinit_function_export_code(void) { - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("__Pyx_modinit_function_export_code", 0); - /*--- Function export code ---*/ - __Pyx_RefNannyFinishContext(); - return 0; -} - -static int __Pyx_modinit_type_init_code(void) { - __Pyx_RefNannyDeclarations - PyObject *__pyx_t_1 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("__Pyx_modinit_type_init_code", 0); - /*--- Type init code ---*/ - #if CYTHON_USE_TYPE_SPECS - __pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx_spec, NULL); if (unlikely(!__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx)) __PYX_ERR(0, 85, __pyx_L1_error) - if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx_spec, __pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx) < 0) __PYX_ERR(0, 85, __pyx_L1_error) - #else - __pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx = &__pyx_type_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx; - #endif - #if !CYTHON_COMPILING_IN_LIMITED_API - #endif - #if !CYTHON_USE_TYPE_SPECS - if (__Pyx_PyType_Ready(__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx) < 0) __PYX_ERR(0, 85, __pyx_L1_error) - #endif - #if PY_MAJOR_VERSION < 3 - __pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx->tp_print = 0; - #endif - #if !CYTHON_COMPILING_IN_LIMITED_API - if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx->tp_dictoffset && __pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx->tp_getattro == PyObject_GenericGetAttr)) { - __pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx->tp_getattro = __Pyx_PyObject_GenericGetAttr; - } - #endif - if (PyObject_SetAttr(__pyx_m, __pyx_n_s_EKF_sym_pyx, (PyObject *) __pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx) < 0) __PYX_ERR(0, 85, __pyx_L1_error) - #if !CYTHON_COMPILING_IN_LIMITED_API - if (__Pyx_setup_reduce((PyObject *) __pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx) < 0) __PYX_ERR(0, 85, __pyx_L1_error) - #endif - __pyx_vtabptr_array = &__pyx_vtable_array; - __pyx_vtable_array.get_memview = (PyObject *(*)(struct __pyx_array_obj *))__pyx_array_get_memview; - #if CYTHON_USE_TYPE_SPECS - __pyx_array_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_array_spec, NULL); if (unlikely(!__pyx_array_type)) __PYX_ERR(1, 114, __pyx_L1_error) - #if !CYTHON_COMPILING_IN_LIMITED_API - __pyx_array_type->tp_as_buffer = &__pyx_tp_as_buffer_array; - if (!__pyx_array_type->tp_as_buffer->bf_releasebuffer && __pyx_array_type->tp_base->tp_as_buffer && __pyx_array_type->tp_base->tp_as_buffer->bf_releasebuffer) { - __pyx_array_type->tp_as_buffer->bf_releasebuffer = __pyx_array_type->tp_base->tp_as_buffer->bf_releasebuffer; - } - #elif defined(Py_bf_getbuffer) && defined(Py_bf_releasebuffer) - /* PY_VERSION_HEX >= 0x03090000 || Py_LIMITED_API >= 0x030B0000 */ - #elif defined(_MSC_VER) - #pragma message ("The buffer protocol is not supported in the Limited C-API < 3.11.") - #else - #warning "The buffer protocol is not supported in the Limited C-API < 3.11." - #endif - if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_array_spec, __pyx_array_type) < 0) __PYX_ERR(1, 114, __pyx_L1_error) - #else - __pyx_array_type = &__pyx_type___pyx_array; - #endif - #if !CYTHON_COMPILING_IN_LIMITED_API - #endif - #if !CYTHON_USE_TYPE_SPECS - if (__Pyx_PyType_Ready(__pyx_array_type) < 0) __PYX_ERR(1, 114, __pyx_L1_error) - #endif - #if PY_MAJOR_VERSION < 3 - __pyx_array_type->tp_print = 0; - #endif - if (__Pyx_SetVtable(__pyx_array_type, __pyx_vtabptr_array) < 0) __PYX_ERR(1, 114, __pyx_L1_error) - #if !CYTHON_COMPILING_IN_LIMITED_API - if (__Pyx_MergeVtables(__pyx_array_type) < 0) __PYX_ERR(1, 114, __pyx_L1_error) - #endif - #if !CYTHON_COMPILING_IN_LIMITED_API - if (__Pyx_setup_reduce((PyObject *) __pyx_array_type) < 0) __PYX_ERR(1, 114, __pyx_L1_error) - #endif - #if CYTHON_USE_TYPE_SPECS - __pyx_MemviewEnum_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_MemviewEnum_spec, NULL); if (unlikely(!__pyx_MemviewEnum_type)) __PYX_ERR(1, 302, __pyx_L1_error) - if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_MemviewEnum_spec, __pyx_MemviewEnum_type) < 0) __PYX_ERR(1, 302, __pyx_L1_error) - #else - __pyx_MemviewEnum_type = &__pyx_type___pyx_MemviewEnum; - #endif - #if !CYTHON_COMPILING_IN_LIMITED_API - #endif - #if !CYTHON_USE_TYPE_SPECS - if (__Pyx_PyType_Ready(__pyx_MemviewEnum_type) < 0) __PYX_ERR(1, 302, __pyx_L1_error) - #endif - #if PY_MAJOR_VERSION < 3 - __pyx_MemviewEnum_type->tp_print = 0; - #endif - #if !CYTHON_COMPILING_IN_LIMITED_API - if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_MemviewEnum_type->tp_dictoffset && __pyx_MemviewEnum_type->tp_getattro == PyObject_GenericGetAttr)) { - __pyx_MemviewEnum_type->tp_getattro = __Pyx_PyObject_GenericGetAttr; - } - #endif - #if !CYTHON_COMPILING_IN_LIMITED_API - if (__Pyx_setup_reduce((PyObject *) __pyx_MemviewEnum_type) < 0) __PYX_ERR(1, 302, __pyx_L1_error) - #endif - __pyx_vtabptr_memoryview = &__pyx_vtable_memoryview; - __pyx_vtable_memoryview.get_item_pointer = (char *(*)(struct __pyx_memoryview_obj *, PyObject *))__pyx_memoryview_get_item_pointer; - __pyx_vtable_memoryview.is_slice = (PyObject *(*)(struct __pyx_memoryview_obj *, PyObject *))__pyx_memoryview_is_slice; - __pyx_vtable_memoryview.setitem_slice_assignment = (PyObject *(*)(struct __pyx_memoryview_obj *, PyObject *, PyObject *))__pyx_memoryview_setitem_slice_assignment; - __pyx_vtable_memoryview.setitem_slice_assign_scalar = (PyObject *(*)(struct __pyx_memoryview_obj *, struct __pyx_memoryview_obj *, PyObject *))__pyx_memoryview_setitem_slice_assign_scalar; - __pyx_vtable_memoryview.setitem_indexed = (PyObject *(*)(struct __pyx_memoryview_obj *, PyObject *, PyObject *))__pyx_memoryview_setitem_indexed; - __pyx_vtable_memoryview.convert_item_to_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *))__pyx_memoryview_convert_item_to_object; - __pyx_vtable_memoryview.assign_item_from_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *, PyObject *))__pyx_memoryview_assign_item_from_object; - __pyx_vtable_memoryview._get_base = (PyObject *(*)(struct __pyx_memoryview_obj *))__pyx_memoryview__get_base; - #if CYTHON_USE_TYPE_SPECS - __pyx_memoryview_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_memoryview_spec, NULL); if (unlikely(!__pyx_memoryview_type)) __PYX_ERR(1, 337, __pyx_L1_error) - #if !CYTHON_COMPILING_IN_LIMITED_API - __pyx_memoryview_type->tp_as_buffer = &__pyx_tp_as_buffer_memoryview; - if (!__pyx_memoryview_type->tp_as_buffer->bf_releasebuffer && __pyx_memoryview_type->tp_base->tp_as_buffer && __pyx_memoryview_type->tp_base->tp_as_buffer->bf_releasebuffer) { - __pyx_memoryview_type->tp_as_buffer->bf_releasebuffer = __pyx_memoryview_type->tp_base->tp_as_buffer->bf_releasebuffer; - } - #elif defined(Py_bf_getbuffer) && defined(Py_bf_releasebuffer) - /* PY_VERSION_HEX >= 0x03090000 || Py_LIMITED_API >= 0x030B0000 */ - #elif defined(_MSC_VER) - #pragma message ("The buffer protocol is not supported in the Limited C-API < 3.11.") - #else - #warning "The buffer protocol is not supported in the Limited C-API < 3.11." - #endif - if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_memoryview_spec, __pyx_memoryview_type) < 0) __PYX_ERR(1, 337, __pyx_L1_error) - #else - __pyx_memoryview_type = &__pyx_type___pyx_memoryview; - #endif - #if !CYTHON_COMPILING_IN_LIMITED_API - #endif - #if !CYTHON_USE_TYPE_SPECS - if (__Pyx_PyType_Ready(__pyx_memoryview_type) < 0) __PYX_ERR(1, 337, __pyx_L1_error) - #endif - #if PY_MAJOR_VERSION < 3 - __pyx_memoryview_type->tp_print = 0; - #endif - #if !CYTHON_COMPILING_IN_LIMITED_API - if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_memoryview_type->tp_dictoffset && __pyx_memoryview_type->tp_getattro == PyObject_GenericGetAttr)) { - __pyx_memoryview_type->tp_getattro = __Pyx_PyObject_GenericGetAttr; - } - #endif - if (__Pyx_SetVtable(__pyx_memoryview_type, __pyx_vtabptr_memoryview) < 0) __PYX_ERR(1, 337, __pyx_L1_error) - #if !CYTHON_COMPILING_IN_LIMITED_API - if (__Pyx_MergeVtables(__pyx_memoryview_type) < 0) __PYX_ERR(1, 337, __pyx_L1_error) - #endif - #if !CYTHON_COMPILING_IN_LIMITED_API - if (__Pyx_setup_reduce((PyObject *) __pyx_memoryview_type) < 0) __PYX_ERR(1, 337, __pyx_L1_error) - #endif - __pyx_vtabptr__memoryviewslice = &__pyx_vtable__memoryviewslice; - __pyx_vtable__memoryviewslice.__pyx_base = *__pyx_vtabptr_memoryview; - __pyx_vtable__memoryviewslice.__pyx_base.convert_item_to_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *))__pyx_memoryviewslice_convert_item_to_object; - __pyx_vtable__memoryviewslice.__pyx_base.assign_item_from_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *, PyObject *))__pyx_memoryviewslice_assign_item_from_object; - __pyx_vtable__memoryviewslice.__pyx_base._get_base = (PyObject *(*)(struct __pyx_memoryview_obj *))__pyx_memoryviewslice__get_base; - #if CYTHON_USE_TYPE_SPECS - __pyx_t_1 = PyTuple_Pack(1, (PyObject *)__pyx_memoryview_type); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 952, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_memoryviewslice_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_memoryviewslice_spec, __pyx_t_1); - __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; - if (unlikely(!__pyx_memoryviewslice_type)) __PYX_ERR(1, 952, __pyx_L1_error) - if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_memoryviewslice_spec, __pyx_memoryviewslice_type) < 0) __PYX_ERR(1, 952, __pyx_L1_error) - #else - __pyx_memoryviewslice_type = &__pyx_type___pyx_memoryviewslice; - #endif - #if !CYTHON_COMPILING_IN_LIMITED_API - __pyx_memoryviewslice_type->tp_base = __pyx_memoryview_type; - #endif - #if !CYTHON_USE_TYPE_SPECS - if (__Pyx_PyType_Ready(__pyx_memoryviewslice_type) < 0) __PYX_ERR(1, 952, __pyx_L1_error) - #endif - #if PY_MAJOR_VERSION < 3 - __pyx_memoryviewslice_type->tp_print = 0; - #endif - #if !CYTHON_COMPILING_IN_LIMITED_API - if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_memoryviewslice_type->tp_dictoffset && __pyx_memoryviewslice_type->tp_getattro == PyObject_GenericGetAttr)) { - __pyx_memoryviewslice_type->tp_getattro = __Pyx_PyObject_GenericGetAttr; - } - #endif - if (__Pyx_SetVtable(__pyx_memoryviewslice_type, __pyx_vtabptr__memoryviewslice) < 0) __PYX_ERR(1, 952, __pyx_L1_error) - #if !CYTHON_COMPILING_IN_LIMITED_API - if (__Pyx_MergeVtables(__pyx_memoryviewslice_type) < 0) __PYX_ERR(1, 952, __pyx_L1_error) - #endif - #if !CYTHON_COMPILING_IN_LIMITED_API - if (__Pyx_setup_reduce((PyObject *) __pyx_memoryviewslice_type) < 0) __PYX_ERR(1, 952, __pyx_L1_error) - #endif - __Pyx_RefNannyFinishContext(); - return 0; - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_1); - __Pyx_RefNannyFinishContext(); - return -1; -} - -static int __Pyx_modinit_type_import_code(void) { - __Pyx_RefNannyDeclarations - PyObject *__pyx_t_1 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("__Pyx_modinit_type_import_code", 0); - /*--- Type import code ---*/ - __pyx_t_1 = PyImport_ImportModule(__Pyx_BUILTIN_MODULE_NAME); if (unlikely(!__pyx_t_1)) __PYX_ERR(3, 9, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_ptype_7cpython_4type_type = __Pyx_ImportType_3_0_8(__pyx_t_1, __Pyx_BUILTIN_MODULE_NAME, "type", - #if defined(PYPY_VERSION_NUM) && PYPY_VERSION_NUM < 0x050B0000 - sizeof(PyTypeObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyTypeObject), - #elif CYTHON_COMPILING_IN_LIMITED_API - sizeof(PyTypeObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyTypeObject), - #else - sizeof(PyHeapTypeObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyHeapTypeObject), - #endif - __Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_7cpython_4type_type) __PYX_ERR(3, 9, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_t_1 = PyImport_ImportModule("numpy"); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 202, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_ptype_5numpy_dtype = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "dtype", sizeof(PyArray_Descr), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyArray_Descr),__Pyx_ImportType_CheckSize_Ignore_3_0_8); if (!__pyx_ptype_5numpy_dtype) __PYX_ERR(2, 202, __pyx_L1_error) - __pyx_ptype_5numpy_flatiter = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "flatiter", sizeof(PyArrayIterObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyArrayIterObject),__Pyx_ImportType_CheckSize_Ignore_3_0_8); if (!__pyx_ptype_5numpy_flatiter) __PYX_ERR(2, 225, __pyx_L1_error) - __pyx_ptype_5numpy_broadcast = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "broadcast", sizeof(PyArrayMultiIterObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyArrayMultiIterObject),__Pyx_ImportType_CheckSize_Ignore_3_0_8); if (!__pyx_ptype_5numpy_broadcast) __PYX_ERR(2, 229, __pyx_L1_error) - __pyx_ptype_5numpy_ndarray = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "ndarray", sizeof(PyArrayObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyArrayObject),__Pyx_ImportType_CheckSize_Ignore_3_0_8); if (!__pyx_ptype_5numpy_ndarray) __PYX_ERR(2, 238, __pyx_L1_error) - __pyx_ptype_5numpy_generic = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "generic", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_generic) __PYX_ERR(2, 809, __pyx_L1_error) - __pyx_ptype_5numpy_number = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "number", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_number) __PYX_ERR(2, 811, __pyx_L1_error) - __pyx_ptype_5numpy_integer = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "integer", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_integer) __PYX_ERR(2, 813, __pyx_L1_error) - __pyx_ptype_5numpy_signedinteger = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "signedinteger", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_signedinteger) __PYX_ERR(2, 815, __pyx_L1_error) - __pyx_ptype_5numpy_unsignedinteger = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "unsignedinteger", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_unsignedinteger) __PYX_ERR(2, 817, __pyx_L1_error) - __pyx_ptype_5numpy_inexact = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "inexact", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_inexact) __PYX_ERR(2, 819, __pyx_L1_error) - __pyx_ptype_5numpy_floating = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "floating", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_floating) __PYX_ERR(2, 821, __pyx_L1_error) - __pyx_ptype_5numpy_complexfloating = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "complexfloating", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_complexfloating) __PYX_ERR(2, 823, __pyx_L1_error) - __pyx_ptype_5numpy_flexible = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "flexible", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_flexible) __PYX_ERR(2, 825, __pyx_L1_error) - __pyx_ptype_5numpy_character = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "character", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_character) __PYX_ERR(2, 827, __pyx_L1_error) - __pyx_ptype_5numpy_ufunc = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "ufunc", sizeof(PyUFuncObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyUFuncObject),__Pyx_ImportType_CheckSize_Ignore_3_0_8); if (!__pyx_ptype_5numpy_ufunc) __PYX_ERR(2, 866, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __Pyx_RefNannyFinishContext(); - return 0; - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_1); - __Pyx_RefNannyFinishContext(); - return -1; -} - -static int __Pyx_modinit_variable_import_code(void) { - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("__Pyx_modinit_variable_import_code", 0); - /*--- Variable import code ---*/ - __Pyx_RefNannyFinishContext(); - return 0; -} - -static int __Pyx_modinit_function_import_code(void) { - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("__Pyx_modinit_function_import_code", 0); - /*--- Function import code ---*/ - __Pyx_RefNannyFinishContext(); - return 0; -} - - -#if PY_MAJOR_VERSION >= 3 -#if CYTHON_PEP489_MULTI_PHASE_INIT -static PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def); /*proto*/ -static int __pyx_pymod_exec_ekf_sym_pyx(PyObject* module); /*proto*/ -static PyModuleDef_Slot __pyx_moduledef_slots[] = { - {Py_mod_create, (void*)__pyx_pymod_create}, - {Py_mod_exec, (void*)__pyx_pymod_exec_ekf_sym_pyx}, - {0, NULL} -}; -#endif - -#ifdef __cplusplus -namespace { - struct PyModuleDef __pyx_moduledef = - #else - static struct PyModuleDef __pyx_moduledef = - #endif - { - PyModuleDef_HEAD_INIT, - "ekf_sym_pyx", - 0, /* m_doc */ - #if CYTHON_PEP489_MULTI_PHASE_INIT - 0, /* m_size */ - #elif CYTHON_USE_MODULE_STATE - sizeof(__pyx_mstate), /* m_size */ - #else - -1, /* m_size */ - #endif - __pyx_methods /* m_methods */, - #if CYTHON_PEP489_MULTI_PHASE_INIT - __pyx_moduledef_slots, /* m_slots */ - #else - NULL, /* m_reload */ - #endif - #if CYTHON_USE_MODULE_STATE - __pyx_m_traverse, /* m_traverse */ - __pyx_m_clear, /* m_clear */ - NULL /* m_free */ - #else - NULL, /* m_traverse */ - NULL, /* m_clear */ - NULL /* m_free */ - #endif - }; - #ifdef __cplusplus -} /* anonymous namespace */ -#endif -#endif - -#ifndef CYTHON_NO_PYINIT_EXPORT -#define __Pyx_PyMODINIT_FUNC PyMODINIT_FUNC -#elif PY_MAJOR_VERSION < 3 -#ifdef __cplusplus -#define __Pyx_PyMODINIT_FUNC extern "C" void -#else -#define __Pyx_PyMODINIT_FUNC void -#endif -#else -#ifdef __cplusplus -#define __Pyx_PyMODINIT_FUNC extern "C" PyObject * -#else -#define __Pyx_PyMODINIT_FUNC PyObject * -#endif -#endif - - -#if PY_MAJOR_VERSION < 3 -__Pyx_PyMODINIT_FUNC initekf_sym_pyx(void) CYTHON_SMALL_CODE; /*proto*/ -__Pyx_PyMODINIT_FUNC initekf_sym_pyx(void) -#else -__Pyx_PyMODINIT_FUNC PyInit_ekf_sym_pyx(void) CYTHON_SMALL_CODE; /*proto*/ -__Pyx_PyMODINIT_FUNC PyInit_ekf_sym_pyx(void) -#if CYTHON_PEP489_MULTI_PHASE_INIT -{ - return PyModuleDef_Init(&__pyx_moduledef); -} -static CYTHON_SMALL_CODE int __Pyx_check_single_interpreter(void) { - #if PY_VERSION_HEX >= 0x030700A1 - static PY_INT64_T main_interpreter_id = -1; - PY_INT64_T current_id = PyInterpreterState_GetID(PyThreadState_Get()->interp); - if (main_interpreter_id == -1) { - main_interpreter_id = current_id; - return (unlikely(current_id == -1)) ? -1 : 0; - } else if (unlikely(main_interpreter_id != current_id)) - #else - static PyInterpreterState *main_interpreter = NULL; - PyInterpreterState *current_interpreter = PyThreadState_Get()->interp; - if (!main_interpreter) { - main_interpreter = current_interpreter; - } else if (unlikely(main_interpreter != current_interpreter)) - #endif - { - PyErr_SetString( - PyExc_ImportError, - "Interpreter change detected - this module can only be loaded into one interpreter per process."); - return -1; - } - return 0; -} -#if CYTHON_COMPILING_IN_LIMITED_API -static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *module, const char* from_name, const char* to_name, int allow_none) -#else -static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *moddict, const char* from_name, const char* to_name, int allow_none) -#endif -{ - PyObject *value = PyObject_GetAttrString(spec, from_name); - int result = 0; - if (likely(value)) { - if (allow_none || value != Py_None) { -#if CYTHON_COMPILING_IN_LIMITED_API - result = PyModule_AddObject(module, to_name, value); -#else - result = PyDict_SetItemString(moddict, to_name, value); -#endif - } - Py_DECREF(value); - } else if (PyErr_ExceptionMatches(PyExc_AttributeError)) { - PyErr_Clear(); - } else { - result = -1; - } - return result; -} -static CYTHON_SMALL_CODE PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def) { - PyObject *module = NULL, *moddict, *modname; - CYTHON_UNUSED_VAR(def); - if (__Pyx_check_single_interpreter()) - return NULL; - if (__pyx_m) - return __Pyx_NewRef(__pyx_m); - modname = PyObject_GetAttrString(spec, "name"); - if (unlikely(!modname)) goto bad; - module = PyModule_NewObject(modname); - Py_DECREF(modname); - if (unlikely(!module)) goto bad; -#if CYTHON_COMPILING_IN_LIMITED_API - moddict = module; -#else - moddict = PyModule_GetDict(module); - if (unlikely(!moddict)) goto bad; -#endif - if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "loader", "__loader__", 1) < 0)) goto bad; - if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "origin", "__file__", 1) < 0)) goto bad; - if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "parent", "__package__", 1) < 0)) goto bad; - if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "submodule_search_locations", "__path__", 0) < 0)) goto bad; - return module; -bad: - Py_XDECREF(module); - return NULL; -} - - -static CYTHON_SMALL_CODE int __pyx_pymod_exec_ekf_sym_pyx(PyObject *__pyx_pyinit_module) -#endif -#endif -{ - int stringtab_initialized = 0; - #if CYTHON_USE_MODULE_STATE - int pystate_addmodule_run = 0; - #endif - __Pyx_TraceDeclarations - PyObject *__pyx_t_1 = NULL; - PyObject *__pyx_t_2 = NULL; - PyObject *__pyx_t_3 = NULL; - PyObject *__pyx_t_4 = NULL; - PyObject *__pyx_t_5 = NULL; - int __pyx_t_6; - PyObject *__pyx_t_7 = NULL; - static PyThread_type_lock __pyx_t_8[8]; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannyDeclarations - #if CYTHON_PEP489_MULTI_PHASE_INIT - if (__pyx_m) { - if (__pyx_m == __pyx_pyinit_module) return 0; - PyErr_SetString(PyExc_RuntimeError, "Module 'ekf_sym_pyx' has already been imported. Re-initialisation is not supported."); - return -1; - } - #elif PY_MAJOR_VERSION >= 3 - if (__pyx_m) return __Pyx_NewRef(__pyx_m); - #endif - /*--- Module creation code ---*/ - #if CYTHON_PEP489_MULTI_PHASE_INIT - __pyx_m = __pyx_pyinit_module; - Py_INCREF(__pyx_m); - #else - #if PY_MAJOR_VERSION < 3 - __pyx_m = Py_InitModule4("ekf_sym_pyx", __pyx_methods, 0, 0, PYTHON_API_VERSION); Py_XINCREF(__pyx_m); - if (unlikely(!__pyx_m)) __PYX_ERR(0, 1, __pyx_L1_error) - #elif CYTHON_USE_MODULE_STATE - __pyx_t_1 = PyModule_Create(&__pyx_moduledef); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 1, __pyx_L1_error) - { - int add_module_result = PyState_AddModule(__pyx_t_1, &__pyx_moduledef); - __pyx_t_1 = 0; /* transfer ownership from __pyx_t_1 to "ekf_sym_pyx" pseudovariable */ - if (unlikely((add_module_result < 0))) __PYX_ERR(0, 1, __pyx_L1_error) - pystate_addmodule_run = 1; - } - #else - __pyx_m = PyModule_Create(&__pyx_moduledef); - if (unlikely(!__pyx_m)) __PYX_ERR(0, 1, __pyx_L1_error) - #endif - #endif - CYTHON_UNUSED_VAR(__pyx_t_1); - __pyx_d = PyModule_GetDict(__pyx_m); if (unlikely(!__pyx_d)) __PYX_ERR(0, 1, __pyx_L1_error) - Py_INCREF(__pyx_d); - __pyx_b = __Pyx_PyImport_AddModuleRef(__Pyx_BUILTIN_MODULE_NAME); if (unlikely(!__pyx_b)) __PYX_ERR(0, 1, __pyx_L1_error) - __pyx_cython_runtime = __Pyx_PyImport_AddModuleRef((const char *) "cython_runtime"); if (unlikely(!__pyx_cython_runtime)) __PYX_ERR(0, 1, __pyx_L1_error) - if (PyObject_SetAttrString(__pyx_m, "__builtins__", __pyx_b) < 0) __PYX_ERR(0, 1, __pyx_L1_error) - #if CYTHON_REFNANNY -__Pyx_RefNanny = __Pyx_RefNannyImportAPI("refnanny"); -if (!__Pyx_RefNanny) { - PyErr_Clear(); - __Pyx_RefNanny = __Pyx_RefNannyImportAPI("Cython.Runtime.refnanny"); - if (!__Pyx_RefNanny) - Py_FatalError("failed to import 'refnanny' module"); -} -#endif - __Pyx_RefNannySetupContext("__Pyx_PyMODINIT_FUNC PyInit_ekf_sym_pyx(void)", 0); - if (__Pyx_check_binary_version(__PYX_LIMITED_VERSION_HEX, __Pyx_get_runtime_version(), CYTHON_COMPILING_IN_LIMITED_API) < 0) __PYX_ERR(0, 1, __pyx_L1_error) - #ifdef __Pxy_PyFrame_Initialize_Offsets - __Pxy_PyFrame_Initialize_Offsets(); - #endif - __pyx_empty_tuple = PyTuple_New(0); if (unlikely(!__pyx_empty_tuple)) __PYX_ERR(0, 1, __pyx_L1_error) - __pyx_empty_bytes = PyBytes_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_bytes)) __PYX_ERR(0, 1, __pyx_L1_error) - __pyx_empty_unicode = PyUnicode_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_unicode)) __PYX_ERR(0, 1, __pyx_L1_error) - #ifdef __Pyx_CyFunction_USED - if (__pyx_CyFunction_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) - #endif - #ifdef __Pyx_FusedFunction_USED - if (__pyx_FusedFunction_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) - #endif - #ifdef __Pyx_Coroutine_USED - if (__pyx_Coroutine_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) - #endif - #ifdef __Pyx_Generator_USED - if (__pyx_Generator_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) - #endif - #ifdef __Pyx_AsyncGen_USED - if (__pyx_AsyncGen_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) - #endif - #ifdef __Pyx_StopAsyncIteration_USED - if (__pyx_StopAsyncIteration_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) - #endif - /*--- Library function declarations ---*/ - /*--- Threads initialization code ---*/ - #if defined(WITH_THREAD) && PY_VERSION_HEX < 0x030700F0 && defined(__PYX_FORCE_INIT_THREADS) && __PYX_FORCE_INIT_THREADS - PyEval_InitThreads(); - #endif - /*--- Initialize various global constants etc. ---*/ - if (__Pyx_InitConstants() < 0) __PYX_ERR(0, 1, __pyx_L1_error) - stringtab_initialized = 1; - if (__Pyx_InitGlobals() < 0) __PYX_ERR(0, 1, __pyx_L1_error) - #if PY_MAJOR_VERSION < 3 && (__PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT) - if (__Pyx_init_sys_getdefaultencoding_params() < 0) __PYX_ERR(0, 1, __pyx_L1_error) - #endif - if (__pyx_module_is_main_rednose__helpers__ekf_sym_pyx) { - if (PyObject_SetAttr(__pyx_m, __pyx_n_s_name_2, __pyx_n_s_main) < 0) __PYX_ERR(0, 1, __pyx_L1_error) - } - #if PY_MAJOR_VERSION >= 3 - { - PyObject *modules = PyImport_GetModuleDict(); if (unlikely(!modules)) __PYX_ERR(0, 1, __pyx_L1_error) - if (!PyDict_GetItemString(modules, "rednose.helpers.ekf_sym_pyx")) { - if (unlikely((PyDict_SetItemString(modules, "rednose.helpers.ekf_sym_pyx", __pyx_m) < 0))) __PYX_ERR(0, 1, __pyx_L1_error) - } - } - #endif - /*--- Builtin init code ---*/ - if (__Pyx_InitCachedBuiltins() < 0) __PYX_ERR(0, 1, __pyx_L1_error) - /*--- Constants init code ---*/ - if (__Pyx_InitCachedConstants() < 0) __PYX_ERR(0, 1, __pyx_L1_error) - /*--- Global type/function init code ---*/ - (void)__Pyx_modinit_global_init_code(); - (void)__Pyx_modinit_variable_export_code(); - (void)__Pyx_modinit_function_export_code(); - if (unlikely((__Pyx_modinit_type_init_code() < 0))) __PYX_ERR(0, 1, __pyx_L1_error) - if (unlikely((__Pyx_modinit_type_import_code() < 0))) __PYX_ERR(0, 1, __pyx_L1_error) - (void)__Pyx_modinit_variable_import_code(); - (void)__Pyx_modinit_function_import_code(); - /*--- Execution code ---*/ - #if defined(__Pyx_Generator_USED) || defined(__Pyx_Coroutine_USED) - if (__Pyx_patch_abc() < 0) __PYX_ERR(0, 1, __pyx_L1_error) - #endif - __Pyx_TraceCall("__Pyx_PyMODINIT_FUNC PyInit_ekf_sym_pyx(void)", __pyx_f[0], 1, 0, __PYX_ERR(0, 1, __pyx_L1_error)); - - /* "View.MemoryView":99 - * - * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" - * try: # <<<<<<<<<<<<<< - * if __import__("sys").version_info >= (3, 3): - * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence - */ - { - __Pyx_PyThreadState_declare - __Pyx_PyThreadState_assign - __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); - __Pyx_XGOTREF(__pyx_t_1); - __Pyx_XGOTREF(__pyx_t_2); - __Pyx_XGOTREF(__pyx_t_3); - /*try:*/ { - - /* "View.MemoryView":100 - * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" - * try: - * if __import__("sys").version_info >= (3, 3): # <<<<<<<<<<<<<< - * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence - * else: - */ - __pyx_t_4 = __Pyx_PyObject_Call(__pyx_builtin___import__, __pyx_tuple__37, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 100, __pyx_L2_error) - __Pyx_GOTREF(__pyx_t_4); - __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_version_info); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 100, __pyx_L2_error) - __Pyx_GOTREF(__pyx_t_5); - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __pyx_t_4 = PyObject_RichCompare(__pyx_t_5, __pyx_tuple__38, Py_GE); __Pyx_XGOTREF(__pyx_t_4); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 100, __pyx_L2_error) - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __pyx_t_6 = __Pyx_PyObject_IsTrue(__pyx_t_4); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(1, 100, __pyx_L2_error) - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - if (__pyx_t_6) { - - /* "View.MemoryView":101 - * try: - * if __import__("sys").version_info >= (3, 3): - * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence # <<<<<<<<<<<<<< - * else: - * __pyx_collections_abc_Sequence = __import__("collections").Sequence - */ - __pyx_t_4 = __Pyx_PyObject_Call(__pyx_builtin___import__, __pyx_tuple__39, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 101, __pyx_L2_error) - __Pyx_GOTREF(__pyx_t_4); - __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_abc); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 101, __pyx_L2_error) - __Pyx_GOTREF(__pyx_t_5); - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_Sequence); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 101, __pyx_L2_error) - __Pyx_GOTREF(__pyx_t_4); - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __Pyx_XGOTREF(__pyx_collections_abc_Sequence); - __Pyx_DECREF_SET(__pyx_collections_abc_Sequence, __pyx_t_4); - __Pyx_GIVEREF(__pyx_t_4); - __pyx_t_4 = 0; - - /* "View.MemoryView":100 - * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" - * try: - * if __import__("sys").version_info >= (3, 3): # <<<<<<<<<<<<<< - * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence - * else: - */ - goto __pyx_L8; - } - - /* "View.MemoryView":103 - * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence - * else: - * __pyx_collections_abc_Sequence = __import__("collections").Sequence # <<<<<<<<<<<<<< - * except: - * - */ - /*else*/ { - __pyx_t_4 = __Pyx_PyObject_Call(__pyx_builtin___import__, __pyx_tuple__40, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 103, __pyx_L2_error) - __Pyx_GOTREF(__pyx_t_4); - __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_Sequence); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 103, __pyx_L2_error) - __Pyx_GOTREF(__pyx_t_5); - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __Pyx_XGOTREF(__pyx_collections_abc_Sequence); - __Pyx_DECREF_SET(__pyx_collections_abc_Sequence, __pyx_t_5); - __Pyx_GIVEREF(__pyx_t_5); - __pyx_t_5 = 0; - } - __pyx_L8:; - - /* "View.MemoryView":99 - * - * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" - * try: # <<<<<<<<<<<<<< - * if __import__("sys").version_info >= (3, 3): - * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence - */ - } - __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; - __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; - __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; - goto __pyx_L7_try_end; - __pyx_L2_error:; - __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; - __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; - - /* "View.MemoryView":104 - * else: - * __pyx_collections_abc_Sequence = __import__("collections").Sequence - * except: # <<<<<<<<<<<<<< - * - * __pyx_collections_abc_Sequence = None - */ - /*except:*/ { - __Pyx_AddTraceback("View.MemoryView", __pyx_clineno, __pyx_lineno, __pyx_filename); - if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_4, &__pyx_t_7) < 0) __PYX_ERR(1, 104, __pyx_L4_except_error) - __Pyx_XGOTREF(__pyx_t_5); - __Pyx_XGOTREF(__pyx_t_4); - __Pyx_XGOTREF(__pyx_t_7); - - /* "View.MemoryView":106 - * except: - * - * __pyx_collections_abc_Sequence = None # <<<<<<<<<<<<<< - * - * - */ - __Pyx_INCREF(Py_None); - __Pyx_XGOTREF(__pyx_collections_abc_Sequence); - __Pyx_DECREF_SET(__pyx_collections_abc_Sequence, Py_None); - __Pyx_GIVEREF(Py_None); - __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; - __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; - __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; - goto __pyx_L3_exception_handled; - } - - /* "View.MemoryView":99 - * - * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" - * try: # <<<<<<<<<<<<<< - * if __import__("sys").version_info >= (3, 3): - * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence - */ - __pyx_L4_except_error:; - __Pyx_XGIVEREF(__pyx_t_1); - __Pyx_XGIVEREF(__pyx_t_2); - __Pyx_XGIVEREF(__pyx_t_3); - __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); - goto __pyx_L1_error; - __pyx_L3_exception_handled:; - __Pyx_XGIVEREF(__pyx_t_1); - __Pyx_XGIVEREF(__pyx_t_2); - __Pyx_XGIVEREF(__pyx_t_3); - __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); - __pyx_L7_try_end:; - } - - /* "View.MemoryView":241 - * - * - * try: # <<<<<<<<<<<<<< - * count = __pyx_collections_abc_Sequence.count - * index = __pyx_collections_abc_Sequence.index - */ - { - __Pyx_PyThreadState_declare - __Pyx_PyThreadState_assign - __Pyx_ExceptionSave(&__pyx_t_3, &__pyx_t_2, &__pyx_t_1); - __Pyx_XGOTREF(__pyx_t_3); - __Pyx_XGOTREF(__pyx_t_2); - __Pyx_XGOTREF(__pyx_t_1); - /*try:*/ { - - /* "View.MemoryView":242 - * - * try: - * count = __pyx_collections_abc_Sequence.count # <<<<<<<<<<<<<< - * index = __pyx_collections_abc_Sequence.index - * except: - */ - __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_count); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 242, __pyx_L11_error) - __Pyx_GOTREF(__pyx_t_7); - if (__Pyx_SetItemOnTypeDict(__pyx_array_type, __pyx_n_s_count, __pyx_t_7) < 0) __PYX_ERR(1, 242, __pyx_L11_error) - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - PyType_Modified(__pyx_array_type); - - /* "View.MemoryView":243 - * try: - * count = __pyx_collections_abc_Sequence.count - * index = __pyx_collections_abc_Sequence.index # <<<<<<<<<<<<<< - * except: - * pass - */ - __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_index); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 243, __pyx_L11_error) - __Pyx_GOTREF(__pyx_t_7); - if (__Pyx_SetItemOnTypeDict(__pyx_array_type, __pyx_n_s_index, __pyx_t_7) < 0) __PYX_ERR(1, 243, __pyx_L11_error) - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - PyType_Modified(__pyx_array_type); - - /* "View.MemoryView":241 - * - * - * try: # <<<<<<<<<<<<<< - * count = __pyx_collections_abc_Sequence.count - * index = __pyx_collections_abc_Sequence.index - */ - } - __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; - __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; - __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; - goto __pyx_L16_try_end; - __pyx_L11_error:; - __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; - __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; - __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; - - /* "View.MemoryView":244 - * count = __pyx_collections_abc_Sequence.count - * index = __pyx_collections_abc_Sequence.index - * except: # <<<<<<<<<<<<<< - * pass - * - */ - /*except:*/ { - __Pyx_ErrRestore(0,0,0); - goto __pyx_L12_exception_handled; - } - __pyx_L12_exception_handled:; - __Pyx_XGIVEREF(__pyx_t_3); - __Pyx_XGIVEREF(__pyx_t_2); - __Pyx_XGIVEREF(__pyx_t_1); - __Pyx_ExceptionReset(__pyx_t_3, __pyx_t_2, __pyx_t_1); - __pyx_L16_try_end:; - } - - /* "View.MemoryView":309 - * return self.name - * - * cdef generic = Enum("") # <<<<<<<<<<<<<< - * cdef strided = Enum("") # default - * cdef indirect = Enum("") - */ - __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__41, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 309, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __Pyx_XGOTREF(generic); - __Pyx_DECREF_SET(generic, __pyx_t_7); - __Pyx_GIVEREF(__pyx_t_7); - __pyx_t_7 = 0; - - /* "View.MemoryView":310 - * - * cdef generic = Enum("") - * cdef strided = Enum("") # default # <<<<<<<<<<<<<< - * cdef indirect = Enum("") - * - */ - __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__42, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 310, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __Pyx_XGOTREF(strided); - __Pyx_DECREF_SET(strided, __pyx_t_7); - __Pyx_GIVEREF(__pyx_t_7); - __pyx_t_7 = 0; - - /* "View.MemoryView":311 - * cdef generic = Enum("") - * cdef strided = Enum("") # default - * cdef indirect = Enum("") # <<<<<<<<<<<<<< - * - * - */ - __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__43, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 311, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __Pyx_XGOTREF(indirect); - __Pyx_DECREF_SET(indirect, __pyx_t_7); - __Pyx_GIVEREF(__pyx_t_7); - __pyx_t_7 = 0; - - /* "View.MemoryView":314 - * - * - * cdef contiguous = Enum("") # <<<<<<<<<<<<<< - * cdef indirect_contiguous = Enum("") - * - */ - __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__44, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 314, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __Pyx_XGOTREF(contiguous); - __Pyx_DECREF_SET(contiguous, __pyx_t_7); - __Pyx_GIVEREF(__pyx_t_7); - __pyx_t_7 = 0; - - /* "View.MemoryView":315 - * - * cdef contiguous = Enum("") - * cdef indirect_contiguous = Enum("") # <<<<<<<<<<<<<< - * - * - */ - __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__45, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 315, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __Pyx_XGOTREF(indirect_contiguous); - __Pyx_DECREF_SET(indirect_contiguous, __pyx_t_7); - __Pyx_GIVEREF(__pyx_t_7); - __pyx_t_7 = 0; - - /* "View.MemoryView":323 - * - * - * cdef int __pyx_memoryview_thread_locks_used = 0 # <<<<<<<<<<<<<< - * cdef PyThread_type_lock[8] __pyx_memoryview_thread_locks = [ - * PyThread_allocate_lock(), - */ - __pyx_memoryview_thread_locks_used = 0; - - /* "View.MemoryView":324 - * - * cdef int __pyx_memoryview_thread_locks_used = 0 - * cdef PyThread_type_lock[8] __pyx_memoryview_thread_locks = [ # <<<<<<<<<<<<<< - * PyThread_allocate_lock(), - * PyThread_allocate_lock(), - */ - __pyx_t_8[0] = PyThread_allocate_lock(); - __pyx_t_8[1] = PyThread_allocate_lock(); - __pyx_t_8[2] = PyThread_allocate_lock(); - __pyx_t_8[3] = PyThread_allocate_lock(); - __pyx_t_8[4] = PyThread_allocate_lock(); - __pyx_t_8[5] = PyThread_allocate_lock(); - __pyx_t_8[6] = PyThread_allocate_lock(); - __pyx_t_8[7] = PyThread_allocate_lock(); - memcpy(&(__pyx_memoryview_thread_locks[0]), __pyx_t_8, sizeof(__pyx_memoryview_thread_locks[0]) * (8)); - - /* "View.MemoryView":982 - * - * - * try: # <<<<<<<<<<<<<< - * count = __pyx_collections_abc_Sequence.count - * index = __pyx_collections_abc_Sequence.index - */ - { - __Pyx_PyThreadState_declare - __Pyx_PyThreadState_assign - __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); - __Pyx_XGOTREF(__pyx_t_1); - __Pyx_XGOTREF(__pyx_t_2); - __Pyx_XGOTREF(__pyx_t_3); - /*try:*/ { - - /* "View.MemoryView":983 - * - * try: - * count = __pyx_collections_abc_Sequence.count # <<<<<<<<<<<<<< - * index = __pyx_collections_abc_Sequence.index - * except: - */ - __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_count); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 983, __pyx_L17_error) - __Pyx_GOTREF(__pyx_t_7); - if (__Pyx_SetItemOnTypeDict(__pyx_memoryviewslice_type, __pyx_n_s_count, __pyx_t_7) < 0) __PYX_ERR(1, 983, __pyx_L17_error) - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - PyType_Modified(__pyx_memoryviewslice_type); - - /* "View.MemoryView":984 - * try: - * count = __pyx_collections_abc_Sequence.count - * index = __pyx_collections_abc_Sequence.index # <<<<<<<<<<<<<< - * except: - * pass - */ - __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_index); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 984, __pyx_L17_error) - __Pyx_GOTREF(__pyx_t_7); - if (__Pyx_SetItemOnTypeDict(__pyx_memoryviewslice_type, __pyx_n_s_index, __pyx_t_7) < 0) __PYX_ERR(1, 984, __pyx_L17_error) - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - PyType_Modified(__pyx_memoryviewslice_type); - - /* "View.MemoryView":982 - * - * - * try: # <<<<<<<<<<<<<< - * count = __pyx_collections_abc_Sequence.count - * index = __pyx_collections_abc_Sequence.index - */ - } - __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; - __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; - __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; - goto __pyx_L22_try_end; - __pyx_L17_error:; - __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; - __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; - __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; - - /* "View.MemoryView":985 - * count = __pyx_collections_abc_Sequence.count - * index = __pyx_collections_abc_Sequence.index - * except: # <<<<<<<<<<<<<< - * pass - * - */ - /*except:*/ { - __Pyx_ErrRestore(0,0,0); - goto __pyx_L18_exception_handled; - } - __pyx_L18_exception_handled:; - __Pyx_XGIVEREF(__pyx_t_1); - __Pyx_XGIVEREF(__pyx_t_2); - __Pyx_XGIVEREF(__pyx_t_3); - __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); - __pyx_L22_try_end:; - } - - /* "View.MemoryView":988 - * pass - * - * try: # <<<<<<<<<<<<<< - * if __pyx_collections_abc_Sequence: - * - */ - { - __Pyx_PyThreadState_declare - __Pyx_PyThreadState_assign - __Pyx_ExceptionSave(&__pyx_t_3, &__pyx_t_2, &__pyx_t_1); - __Pyx_XGOTREF(__pyx_t_3); - __Pyx_XGOTREF(__pyx_t_2); - __Pyx_XGOTREF(__pyx_t_1); - /*try:*/ { - - /* "View.MemoryView":989 - * - * try: - * if __pyx_collections_abc_Sequence: # <<<<<<<<<<<<<< - * - * - */ - __pyx_t_6 = __Pyx_PyObject_IsTrue(__pyx_collections_abc_Sequence); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(1, 989, __pyx_L23_error) - if (__pyx_t_6) { - - /* "View.MemoryView":993 - * - * - * __pyx_collections_abc_Sequence.register(_memoryviewslice) # <<<<<<<<<<<<<< - * __pyx_collections_abc_Sequence.register(array) - * except: - */ - __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_register); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 993, __pyx_L23_error) - __Pyx_GOTREF(__pyx_t_7); - __pyx_t_4 = __Pyx_PyObject_CallOneArg(__pyx_t_7, ((PyObject *)__pyx_memoryviewslice_type)); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 993, __pyx_L23_error) - __Pyx_GOTREF(__pyx_t_4); - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - - /* "View.MemoryView":994 - * - * __pyx_collections_abc_Sequence.register(_memoryviewslice) - * __pyx_collections_abc_Sequence.register(array) # <<<<<<<<<<<<<< - * except: - * pass # ignore failure, it's a minor issue - */ - __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_register); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 994, __pyx_L23_error) - __Pyx_GOTREF(__pyx_t_4); - __pyx_t_7 = __Pyx_PyObject_CallOneArg(__pyx_t_4, ((PyObject *)__pyx_array_type)); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 994, __pyx_L23_error) - __Pyx_GOTREF(__pyx_t_7); - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - - /* "View.MemoryView":989 - * - * try: - * if __pyx_collections_abc_Sequence: # <<<<<<<<<<<<<< - * - * - */ - } - - /* "View.MemoryView":988 - * pass - * - * try: # <<<<<<<<<<<<<< - * if __pyx_collections_abc_Sequence: - * - */ - } - __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; - __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; - __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; - goto __pyx_L28_try_end; - __pyx_L23_error:; - __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; - __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; - __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; - - /* "View.MemoryView":995 - * __pyx_collections_abc_Sequence.register(_memoryviewslice) - * __pyx_collections_abc_Sequence.register(array) - * except: # <<<<<<<<<<<<<< - * pass # ignore failure, it's a minor issue - * - */ - /*except:*/ { - __Pyx_ErrRestore(0,0,0); - goto __pyx_L24_exception_handled; - } - __pyx_L24_exception_handled:; - __Pyx_XGIVEREF(__pyx_t_3); - __Pyx_XGIVEREF(__pyx_t_2); - __Pyx_XGIVEREF(__pyx_t_1); - __Pyx_ExceptionReset(__pyx_t_3, __pyx_t_2, __pyx_t_1); - __pyx_L28_try_end:; - } - - /* "(tree fragment)":1 - * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< - * cdef object __pyx_PickleError - * cdef object __pyx_result - */ - __pyx_t_7 = PyCFunction_NewEx(&__pyx_mdef_15View_dot_MemoryView_1__pyx_unpickle_Enum, NULL, __pyx_n_s_View_MemoryView); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 1, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - if (PyDict_SetItem(__pyx_d, __pyx_n_s_pyx_unpickle_Enum, __pyx_t_7) < 0) __PYX_ERR(1, 1, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - - /* "rednose/helpers/ekf_sym_pyx.pyx":12 - * cimport numpy as np - * - * import numpy as np # <<<<<<<<<<<<<< - * - * - */ - __pyx_t_7 = __Pyx_ImportDottedModule(__pyx_n_s_numpy, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 12, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - if (PyDict_SetItem(__pyx_d, __pyx_n_s_np, __pyx_t_7) < 0) __PYX_ERR(0, 12, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - - /* "rednose/helpers/ekf_sym_pyx.pyx":89 - * def __cinit__(self, str gen_dir, str name, np.ndarray[np.float64_t, ndim=2] Q, - * np.ndarray[np.float64_t, ndim=1] x_initial, np.ndarray[np.float64_t, ndim=2] P_initial, int dim_main, - * int dim_main_err, int N=0, int dim_augment=0, int dim_augment_err=0, list maha_test_kinds=[], # <<<<<<<<<<<<<< - * list quaternion_idxs=[], list global_vars=[], double max_rewind_age=1.0, logger=None): - * # TODO logger - */ - __pyx_t_7 = PyList_New(0); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 89, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __pyx_k__17 = ((PyObject*)__pyx_t_7); - __Pyx_GIVEREF(__pyx_t_7); - __pyx_t_7 = 0; - - /* "rednose/helpers/ekf_sym_pyx.pyx":90 - * np.ndarray[np.float64_t, ndim=1] x_initial, np.ndarray[np.float64_t, ndim=2] P_initial, int dim_main, - * int dim_main_err, int N=0, int dim_augment=0, int dim_augment_err=0, list maha_test_kinds=[], - * list quaternion_idxs=[], list global_vars=[], double max_rewind_age=1.0, logger=None): # <<<<<<<<<<<<<< - * # TODO logger - * ekf_load_and_register(gen_dir.encode('utf8'), name.encode('utf8')) - */ - __pyx_t_7 = PyList_New(0); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 90, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __pyx_k__18 = ((PyObject*)__pyx_t_7); - __Pyx_GIVEREF(__pyx_t_7); - __pyx_t_7 = 0; - __pyx_t_7 = PyList_New(0); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 90, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __pyx_k__19 = ((PyObject*)__pyx_t_7); - __Pyx_GIVEREF(__pyx_t_7); - __pyx_t_7 = 0; - - /* "rednose/helpers/ekf_sym_pyx.pyx":113 - * ) - * - * def init_state(self, np.ndarray[np.float64_t, ndim=1] state, np.ndarray[np.float64_t, ndim=2] covs, filter_time): # <<<<<<<<<<<<<< - * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] state_b = np.ascontiguousarray(state, dtype=np.double) - * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] covs_b = np.ascontiguousarray(covs, dtype=np.double) - */ - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_3init_state, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_EKF_sym_pyx_init_state, NULL, __pyx_n_s_rednose_helpers_ekf_sym_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__20)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 113, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx, __pyx_n_s_init_state, __pyx_t_7) < 0) __PYX_ERR(0, 113, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - PyType_Modified(__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx); - - /* "rednose/helpers/ekf_sym_pyx.pyx":122 - * ) - * - * def state(self): # <<<<<<<<<<<<<< - * cdef np.ndarray res = vector_to_numpy(self.ekf.state()) - * return res - */ - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_5state, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_EKF_sym_pyx_state, NULL, __pyx_n_s_rednose_helpers_ekf_sym_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__21)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 122, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx, __pyx_n_s_state, __pyx_t_7) < 0) __PYX_ERR(0, 122, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - PyType_Modified(__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx); - - /* "rednose/helpers/ekf_sym_pyx.pyx":126 - * return res - * - * def covs(self): # <<<<<<<<<<<<<< - * return matrix_to_numpy(self.ekf.covs()) - * - */ - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_7covs, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_EKF_sym_pyx_covs, NULL, __pyx_n_s_rednose_helpers_ekf_sym_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__22)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 126, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx, __pyx_n_s_covs, __pyx_t_7) < 0) __PYX_ERR(0, 126, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - PyType_Modified(__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx); - - /* "rednose/helpers/ekf_sym_pyx.pyx":129 - * return matrix_to_numpy(self.ekf.covs()) - * - * def set_filter_time(self, double t): # <<<<<<<<<<<<<< - * self.ekf.set_filter_time(t) - * - */ - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_9set_filter_time, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_EKF_sym_pyx_set_filter_time, NULL, __pyx_n_s_rednose_helpers_ekf_sym_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__23)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 129, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx, __pyx_n_s_set_filter_time, __pyx_t_7) < 0) __PYX_ERR(0, 129, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - PyType_Modified(__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx); - - /* "rednose/helpers/ekf_sym_pyx.pyx":132 - * self.ekf.set_filter_time(t) - * - * def get_filter_time(self): # <<<<<<<<<<<<<< - * return self.ekf.get_filter_time() - * - */ - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_11get_filter_time, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_EKF_sym_pyx_get_filter_time, NULL, __pyx_n_s_rednose_helpers_ekf_sym_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__24)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 132, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx, __pyx_n_s_get_filter_time, __pyx_t_7) < 0) __PYX_ERR(0, 132, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - PyType_Modified(__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx); - - /* "rednose/helpers/ekf_sym_pyx.pyx":135 - * return self.ekf.get_filter_time() - * - * def set_global(self, str global_var, double val): # <<<<<<<<<<<<<< - * self.ekf.set_global(global_var.encode('utf8'), val) - * - */ - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_13set_global, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_EKF_sym_pyx_set_global, NULL, __pyx_n_s_rednose_helpers_ekf_sym_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__25)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 135, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx, __pyx_n_s_set_global, __pyx_t_7) < 0) __PYX_ERR(0, 135, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - PyType_Modified(__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx); - - /* "rednose/helpers/ekf_sym_pyx.pyx":138 - * self.ekf.set_global(global_var.encode('utf8'), val) - * - * def reset_rewind(self): # <<<<<<<<<<<<<< - * self.ekf.reset_rewind() - * - */ - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_15reset_rewind, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_EKF_sym_pyx_reset_rewind, NULL, __pyx_n_s_rednose_helpers_ekf_sym_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__26)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 138, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx, __pyx_n_s_reset_rewind, __pyx_t_7) < 0) __PYX_ERR(0, 138, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - PyType_Modified(__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx); - - /* "rednose/helpers/ekf_sym_pyx.pyx":141 - * self.ekf.reset_rewind() - * - * def predict(self, double t): # <<<<<<<<<<<<<< - * self.ekf.predict(t) - * - */ - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_17predict, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_EKF_sym_pyx_predict, NULL, __pyx_n_s_rednose_helpers_ekf_sym_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__27)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 141, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx, __pyx_n_s_predict, __pyx_t_7) < 0) __PYX_ERR(0, 141, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - PyType_Modified(__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx); - - /* "rednose/helpers/ekf_sym_pyx.pyx":144 - * self.ekf.predict(t) - * - * def predict_and_update_batch(self, double t, int kind, z, R, extra_args=[[]], bool augment=False): # <<<<<<<<<<<<<< - * cdef vector[MapVectorXd] z_map - * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] zi_b - */ - __pyx_t_7 = PyList_New(0); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 144, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __pyx_t_4 = PyList_New(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 144, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __Pyx_GIVEREF(__pyx_t_7); - if (__Pyx_PyList_SET_ITEM(__pyx_t_4, 0, __pyx_t_7)) __PYX_ERR(0, 144, __pyx_L1_error); - __pyx_t_7 = 0; - __pyx_k__28 = __pyx_t_4; - __Pyx_GIVEREF(__pyx_t_4); - __pyx_t_4 = 0; - __pyx_t_4 = PyList_New(0); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 144, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __pyx_t_7 = PyList_New(1); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 144, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __Pyx_GIVEREF(__pyx_t_4); - if (__Pyx_PyList_SET_ITEM(__pyx_t_7, 0, __pyx_t_4)) __PYX_ERR(0, 144, __pyx_L1_error); - __pyx_t_4 = 0; - __pyx_t_4 = PyTuple_New(2); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 144, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __Pyx_GIVEREF(__pyx_t_7); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_7)) __PYX_ERR(0, 144, __pyx_L1_error); - __Pyx_INCREF(Py_False); - __Pyx_GIVEREF(Py_False); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 1, Py_False)) __PYX_ERR(0, 144, __pyx_L1_error); - __pyx_t_7 = 0; - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_19predict_and_update_batch, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_EKF_sym_pyx_predict_and_update_b, NULL, __pyx_n_s_rednose_helpers_ekf_sym_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__29)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 144, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_7, __pyx_t_4); - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx, __pyx_n_s_predict_and_update_batch, __pyx_t_7) < 0) __PYX_ERR(0, 144, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - PyType_Modified(__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx); - - /* "rednose/helpers/ekf_sym_pyx.pyx":182 - * ) - * - * def augment(self): # <<<<<<<<<<<<<< - * raise NotImplementedError() # TODO - * - */ - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_21augment, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_EKF_sym_pyx_augment, NULL, __pyx_n_s_rednose_helpers_ekf_sym_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__30)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 182, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx, __pyx_n_s_augment, __pyx_t_7) < 0) __PYX_ERR(0, 182, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - PyType_Modified(__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx); - - /* "rednose/helpers/ekf_sym_pyx.pyx":185 - * raise NotImplementedError() # TODO - * - * def get_augment_times(self): # <<<<<<<<<<<<<< - * raise NotImplementedError() # TODO - * - */ - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_23get_augment_times, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_EKF_sym_pyx_get_augment_times, NULL, __pyx_n_s_rednose_helpers_ekf_sym_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__31)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 185, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx, __pyx_n_s_get_augment_times, __pyx_t_7) < 0) __PYX_ERR(0, 185, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - PyType_Modified(__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx); - - /* "rednose/helpers/ekf_sym_pyx.pyx":188 - * raise NotImplementedError() # TODO - * - * def rts_smooth(self, estimates, norm_quats=False): # <<<<<<<<<<<<<< - * raise NotImplementedError() # TODO - * - */ - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_25rts_smooth, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_EKF_sym_pyx_rts_smooth, NULL, __pyx_n_s_rednose_helpers_ekf_sym_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__32)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 188, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_7, __pyx_tuple__55); - if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx, __pyx_n_s_rts_smooth, __pyx_t_7) < 0) __PYX_ERR(0, 188, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - PyType_Modified(__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx); - - /* "rednose/helpers/ekf_sym_pyx.pyx":191 - * raise NotImplementedError() # TODO - * - * def maha_test(self, x, P, kind, z, R, extra_args=[], maha_thresh=0.95): # <<<<<<<<<<<<<< - * raise NotImplementedError() # TODO - * - */ - __pyx_t_7 = PyList_New(0); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 191, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __pyx_k__33 = __pyx_t_7; - __Pyx_GIVEREF(__pyx_t_7); - __pyx_t_7 = 0; - __pyx_t_7 = PyList_New(0); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 191, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __pyx_t_4 = PyTuple_New(2); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 191, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __Pyx_GIVEREF(__pyx_t_7); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_7)) __PYX_ERR(0, 191, __pyx_L1_error); - __Pyx_INCREF(__pyx_float_0_95); - __Pyx_GIVEREF(__pyx_float_0_95); - if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 1, __pyx_float_0_95)) __PYX_ERR(0, 191, __pyx_L1_error); - __pyx_t_7 = 0; - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_27maha_test, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_EKF_sym_pyx_maha_test, NULL, __pyx_n_s_rednose_helpers_ekf_sym_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__34)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 191, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_7, __pyx_t_4); - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx, __pyx_n_s_maha_test, __pyx_t_7) < 0) __PYX_ERR(0, 191, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - PyType_Modified(__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx); - - /* "(tree fragment)":1 - * def __reduce_cython__(self): # <<<<<<<<<<<<<< - * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" - * def __setstate_cython__(self, __pyx_state): - */ - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_31__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_EKF_sym_pyx___reduce_cython, NULL, __pyx_n_s_rednose_helpers_ekf_sym_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__35)); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 1, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - if (PyDict_SetItem(__pyx_d, __pyx_n_s_reduce_cython, __pyx_t_7) < 0) __PYX_ERR(1, 1, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - - /* "(tree fragment)":3 - * def __reduce_cython__(self): - * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" - * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< - * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" - */ - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_33__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_EKF_sym_pyx___setstate_cython, NULL, __pyx_n_s_rednose_helpers_ekf_sym_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__36)); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 3, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - if (PyDict_SetItem(__pyx_d, __pyx_n_s_setstate_cython, __pyx_t_7) < 0) __PYX_ERR(1, 3, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - - /* "rednose/helpers/ekf_sym_pyx.pyx":1 - * # cython: language_level=3 # <<<<<<<<<<<<<< - * # cython: profile=True - * # distutils: language = c++ - */ - __pyx_t_7 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 1, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - if (PyDict_SetItem(__pyx_d, __pyx_n_s_test, __pyx_t_7) < 0) __PYX_ERR(0, 1, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - __Pyx_TraceReturn(Py_None, 0); - - /*--- Wrapped vars code ---*/ - - goto __pyx_L0; - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_4); - __Pyx_XDECREF(__pyx_t_5); - __Pyx_XDECREF(__pyx_t_7); - if (__pyx_m) { - if (__pyx_d && stringtab_initialized) { - __Pyx_AddTraceback("init rednose.helpers.ekf_sym_pyx", __pyx_clineno, __pyx_lineno, __pyx_filename); - } - #if !CYTHON_USE_MODULE_STATE - Py_CLEAR(__pyx_m); - #else - Py_DECREF(__pyx_m); - if (pystate_addmodule_run) { - PyObject *tp, *value, *tb; - PyErr_Fetch(&tp, &value, &tb); - PyState_RemoveModule(&__pyx_moduledef); - PyErr_Restore(tp, value, tb); - } - #endif - } else if (!PyErr_Occurred()) { - PyErr_SetString(PyExc_ImportError, "init rednose.helpers.ekf_sym_pyx"); - } - __pyx_L0:; - __Pyx_RefNannyFinishContext(); - #if CYTHON_PEP489_MULTI_PHASE_INIT - return (__pyx_m != NULL) ? 0 : -1; - #elif PY_MAJOR_VERSION >= 3 - return __pyx_m; - #else - return; - #endif -} -/* #### Code section: cleanup_globals ### */ -/* #### Code section: cleanup_module ### */ -/* #### Code section: main_method ### */ -/* #### Code section: utility_code_pragmas ### */ -#ifdef _MSC_VER -#pragma warning( push ) -/* Warning 4127: conditional expression is constant - * Cython uses constant conditional expressions to allow in inline functions to be optimized at - * compile-time, so this warning is not useful - */ -#pragma warning( disable : 4127 ) -#endif - - - -/* #### Code section: utility_code_def ### */ - -/* --- Runtime support code --- */ -/* Refnanny */ -#if CYTHON_REFNANNY -static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname) { - PyObject *m = NULL, *p = NULL; - void *r = NULL; - m = PyImport_ImportModule(modname); - if (!m) goto end; - p = PyObject_GetAttrString(m, "RefNannyAPI"); - if (!p) goto end; - r = PyLong_AsVoidPtr(p); -end: - Py_XDECREF(p); - Py_XDECREF(m); - return (__Pyx_RefNannyAPIStruct *)r; -} -#endif - -/* PyErrExceptionMatches */ -#if CYTHON_FAST_THREAD_STATE -static int __Pyx_PyErr_ExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { - Py_ssize_t i, n; - n = PyTuple_GET_SIZE(tuple); -#if PY_MAJOR_VERSION >= 3 - for (i=0; i= 0x030C00A6 - PyObject *current_exception = tstate->current_exception; - if (unlikely(!current_exception)) return 0; - exc_type = (PyObject*) Py_TYPE(current_exception); - if (exc_type == err) return 1; -#else - exc_type = tstate->curexc_type; - if (exc_type == err) return 1; - if (unlikely(!exc_type)) return 0; -#endif - #if CYTHON_AVOID_BORROWED_REFS - Py_INCREF(exc_type); - #endif - if (unlikely(PyTuple_Check(err))) { - result = __Pyx_PyErr_ExceptionMatchesTuple(exc_type, err); - } else { - result = __Pyx_PyErr_GivenExceptionMatches(exc_type, err); - } - #if CYTHON_AVOID_BORROWED_REFS - Py_DECREF(exc_type); - #endif - return result; -} -#endif - -/* PyErrFetchRestore */ -#if CYTHON_FAST_THREAD_STATE -static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb) { -#if PY_VERSION_HEX >= 0x030C00A6 - PyObject *tmp_value; - assert(type == NULL || (value != NULL && type == (PyObject*) Py_TYPE(value))); - if (value) { - #if CYTHON_COMPILING_IN_CPYTHON - if (unlikely(((PyBaseExceptionObject*) value)->traceback != tb)) - #endif - PyException_SetTraceback(value, tb); - } - tmp_value = tstate->current_exception; - tstate->current_exception = value; - Py_XDECREF(tmp_value); - Py_XDECREF(type); - Py_XDECREF(tb); -#else - PyObject *tmp_type, *tmp_value, *tmp_tb; - tmp_type = tstate->curexc_type; - tmp_value = tstate->curexc_value; - tmp_tb = tstate->curexc_traceback; - tstate->curexc_type = type; - tstate->curexc_value = value; - tstate->curexc_traceback = tb; - Py_XDECREF(tmp_type); - Py_XDECREF(tmp_value); - Py_XDECREF(tmp_tb); -#endif -} -static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { -#if PY_VERSION_HEX >= 0x030C00A6 - PyObject* exc_value; - exc_value = tstate->current_exception; - tstate->current_exception = 0; - *value = exc_value; - *type = NULL; - *tb = NULL; - if (exc_value) { - *type = (PyObject*) Py_TYPE(exc_value); - Py_INCREF(*type); - #if CYTHON_COMPILING_IN_CPYTHON - *tb = ((PyBaseExceptionObject*) exc_value)->traceback; - Py_XINCREF(*tb); - #else - *tb = PyException_GetTraceback(exc_value); - #endif - } -#else - *type = tstate->curexc_type; - *value = tstate->curexc_value; - *tb = tstate->curexc_traceback; - tstate->curexc_type = 0; - tstate->curexc_value = 0; - tstate->curexc_traceback = 0; -#endif -} -#endif - -/* PyObjectGetAttrStr */ -#if CYTHON_USE_TYPE_SLOTS -static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name) { - PyTypeObject* tp = Py_TYPE(obj); - if (likely(tp->tp_getattro)) - return tp->tp_getattro(obj, attr_name); -#if PY_MAJOR_VERSION < 3 - if (likely(tp->tp_getattr)) - return tp->tp_getattr(obj, PyString_AS_STRING(attr_name)); -#endif - return PyObject_GetAttr(obj, attr_name); -} -#endif - -/* PyObjectGetAttrStrNoError */ -#if __PYX_LIMITED_VERSION_HEX < 0x030d00A1 -static void __Pyx_PyObject_GetAttrStr_ClearAttributeError(void) { - __Pyx_PyThreadState_declare - __Pyx_PyThreadState_assign - if (likely(__Pyx_PyErr_ExceptionMatches(PyExc_AttributeError))) - __Pyx_PyErr_Clear(); -} -#endif -static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name) { - PyObject *result; -#if __PYX_LIMITED_VERSION_HEX >= 0x030d00A1 - (void) PyObject_GetOptionalAttr(obj, attr_name, &result); - return result; -#else -#if CYTHON_COMPILING_IN_CPYTHON && CYTHON_USE_TYPE_SLOTS && PY_VERSION_HEX >= 0x030700B1 - PyTypeObject* tp = Py_TYPE(obj); - if (likely(tp->tp_getattro == PyObject_GenericGetAttr)) { - return _PyObject_GenericGetAttrWithDict(obj, attr_name, NULL, 1); - } -#endif - result = __Pyx_PyObject_GetAttrStr(obj, attr_name); - if (unlikely(!result)) { - __Pyx_PyObject_GetAttrStr_ClearAttributeError(); - } - return result; -#endif -} - -/* GetBuiltinName */ -static PyObject *__Pyx_GetBuiltinName(PyObject *name) { - PyObject* result = __Pyx_PyObject_GetAttrStrNoError(__pyx_b, name); - if (unlikely(!result) && !PyErr_Occurred()) { - PyErr_Format(PyExc_NameError, -#if PY_MAJOR_VERSION >= 3 - "name '%U' is not defined", name); -#else - "name '%.200s' is not defined", PyString_AS_STRING(name)); -#endif - } - return result; -} - -/* TupleAndListFromArray */ -#if CYTHON_COMPILING_IN_CPYTHON -static CYTHON_INLINE void __Pyx_copy_object_array(PyObject *const *CYTHON_RESTRICT src, PyObject** CYTHON_RESTRICT dest, Py_ssize_t length) { - PyObject *v; - Py_ssize_t i; - for (i = 0; i < length; i++) { - v = dest[i] = src[i]; - Py_INCREF(v); - } -} -static CYTHON_INLINE PyObject * -__Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n) -{ - PyObject *res; - if (n <= 0) { - Py_INCREF(__pyx_empty_tuple); - return __pyx_empty_tuple; - } - res = PyTuple_New(n); - if (unlikely(res == NULL)) return NULL; - __Pyx_copy_object_array(src, ((PyTupleObject*)res)->ob_item, n); - return res; -} -static CYTHON_INLINE PyObject * -__Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n) -{ - PyObject *res; - if (n <= 0) { - return PyList_New(0); - } - res = PyList_New(n); - if (unlikely(res == NULL)) return NULL; - __Pyx_copy_object_array(src, ((PyListObject*)res)->ob_item, n); - return res; -} -#endif - -/* BytesEquals */ -static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals) { -#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API - return PyObject_RichCompareBool(s1, s2, equals); -#else - if (s1 == s2) { - return (equals == Py_EQ); - } else if (PyBytes_CheckExact(s1) & PyBytes_CheckExact(s2)) { - const char *ps1, *ps2; - Py_ssize_t length = PyBytes_GET_SIZE(s1); - if (length != PyBytes_GET_SIZE(s2)) - return (equals == Py_NE); - ps1 = PyBytes_AS_STRING(s1); - ps2 = PyBytes_AS_STRING(s2); - if (ps1[0] != ps2[0]) { - return (equals == Py_NE); - } else if (length == 1) { - return (equals == Py_EQ); - } else { - int result; -#if CYTHON_USE_UNICODE_INTERNALS && (PY_VERSION_HEX < 0x030B0000) - Py_hash_t hash1, hash2; - hash1 = ((PyBytesObject*)s1)->ob_shash; - hash2 = ((PyBytesObject*)s2)->ob_shash; - if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { - return (equals == Py_NE); - } -#endif - result = memcmp(ps1, ps2, (size_t)length); - return (equals == Py_EQ) ? (result == 0) : (result != 0); - } - } else if ((s1 == Py_None) & PyBytes_CheckExact(s2)) { - return (equals == Py_NE); - } else if ((s2 == Py_None) & PyBytes_CheckExact(s1)) { - return (equals == Py_NE); - } else { - int result; - PyObject* py_result = PyObject_RichCompare(s1, s2, equals); - if (!py_result) - return -1; - result = __Pyx_PyObject_IsTrue(py_result); - Py_DECREF(py_result); - return result; - } -#endif -} - -/* UnicodeEquals */ -static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals) { -#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API - return PyObject_RichCompareBool(s1, s2, equals); -#else -#if PY_MAJOR_VERSION < 3 - PyObject* owned_ref = NULL; -#endif - int s1_is_unicode, s2_is_unicode; - if (s1 == s2) { - goto return_eq; - } - s1_is_unicode = PyUnicode_CheckExact(s1); - s2_is_unicode = PyUnicode_CheckExact(s2); -#if PY_MAJOR_VERSION < 3 - if ((s1_is_unicode & (!s2_is_unicode)) && PyString_CheckExact(s2)) { - owned_ref = PyUnicode_FromObject(s2); - if (unlikely(!owned_ref)) - return -1; - s2 = owned_ref; - s2_is_unicode = 1; - } else if ((s2_is_unicode & (!s1_is_unicode)) && PyString_CheckExact(s1)) { - owned_ref = PyUnicode_FromObject(s1); - if (unlikely(!owned_ref)) - return -1; - s1 = owned_ref; - s1_is_unicode = 1; - } else if (((!s2_is_unicode) & (!s1_is_unicode))) { - return __Pyx_PyBytes_Equals(s1, s2, equals); - } -#endif - if (s1_is_unicode & s2_is_unicode) { - Py_ssize_t length; - int kind; - void *data1, *data2; - if (unlikely(__Pyx_PyUnicode_READY(s1) < 0) || unlikely(__Pyx_PyUnicode_READY(s2) < 0)) - return -1; - length = __Pyx_PyUnicode_GET_LENGTH(s1); - if (length != __Pyx_PyUnicode_GET_LENGTH(s2)) { - goto return_ne; - } -#if CYTHON_USE_UNICODE_INTERNALS - { - Py_hash_t hash1, hash2; - #if CYTHON_PEP393_ENABLED - hash1 = ((PyASCIIObject*)s1)->hash; - hash2 = ((PyASCIIObject*)s2)->hash; - #else - hash1 = ((PyUnicodeObject*)s1)->hash; - hash2 = ((PyUnicodeObject*)s2)->hash; - #endif - if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { - goto return_ne; - } - } -#endif - kind = __Pyx_PyUnicode_KIND(s1); - if (kind != __Pyx_PyUnicode_KIND(s2)) { - goto return_ne; - } - data1 = __Pyx_PyUnicode_DATA(s1); - data2 = __Pyx_PyUnicode_DATA(s2); - if (__Pyx_PyUnicode_READ(kind, data1, 0) != __Pyx_PyUnicode_READ(kind, data2, 0)) { - goto return_ne; - } else if (length == 1) { - goto return_eq; - } else { - int result = memcmp(data1, data2, (size_t)(length * kind)); - #if PY_MAJOR_VERSION < 3 - Py_XDECREF(owned_ref); - #endif - return (equals == Py_EQ) ? (result == 0) : (result != 0); - } - } else if ((s1 == Py_None) & s2_is_unicode) { - goto return_ne; - } else if ((s2 == Py_None) & s1_is_unicode) { - goto return_ne; - } else { - int result; - PyObject* py_result = PyObject_RichCompare(s1, s2, equals); - #if PY_MAJOR_VERSION < 3 - Py_XDECREF(owned_ref); - #endif - if (!py_result) - return -1; - result = __Pyx_PyObject_IsTrue(py_result); - Py_DECREF(py_result); - return result; - } -return_eq: - #if PY_MAJOR_VERSION < 3 - Py_XDECREF(owned_ref); - #endif - return (equals == Py_EQ); -return_ne: - #if PY_MAJOR_VERSION < 3 - Py_XDECREF(owned_ref); - #endif - return (equals == Py_NE); -#endif -} - -/* fastcall */ -#if CYTHON_METH_FASTCALL -static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s) -{ - Py_ssize_t i, n = PyTuple_GET_SIZE(kwnames); - for (i = 0; i < n; i++) - { - if (s == PyTuple_GET_ITEM(kwnames, i)) return kwvalues[i]; - } - for (i = 0; i < n; i++) - { - int eq = __Pyx_PyUnicode_Equals(s, PyTuple_GET_ITEM(kwnames, i), Py_EQ); - if (unlikely(eq != 0)) { - if (unlikely(eq < 0)) return NULL; - return kwvalues[i]; - } - } - return NULL; -} -#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030d0000 -CYTHON_UNUSED static PyObject *__Pyx_KwargsAsDict_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues) { - Py_ssize_t i, nkwargs = PyTuple_GET_SIZE(kwnames); - PyObject *dict; - dict = PyDict_New(); - if (unlikely(!dict)) - return NULL; - for (i=0; i= 3 - "%s() got multiple values for keyword argument '%U'", func_name, kw_name); - #else - "%s() got multiple values for keyword argument '%s'", func_name, - PyString_AsString(kw_name)); - #endif -} - -/* ParseKeywords */ -static int __Pyx_ParseOptionalKeywords( - PyObject *kwds, - PyObject *const *kwvalues, - PyObject **argnames[], - PyObject *kwds2, - PyObject *values[], - Py_ssize_t num_pos_args, - const char* function_name) -{ - PyObject *key = 0, *value = 0; - Py_ssize_t pos = 0; - PyObject*** name; - PyObject*** first_kw_arg = argnames + num_pos_args; - int kwds_is_tuple = CYTHON_METH_FASTCALL && likely(PyTuple_Check(kwds)); - while (1) { - Py_XDECREF(key); key = NULL; - Py_XDECREF(value); value = NULL; - if (kwds_is_tuple) { - Py_ssize_t size; -#if CYTHON_ASSUME_SAFE_MACROS - size = PyTuple_GET_SIZE(kwds); -#else - size = PyTuple_Size(kwds); - if (size < 0) goto bad; -#endif - if (pos >= size) break; -#if CYTHON_AVOID_BORROWED_REFS - key = __Pyx_PySequence_ITEM(kwds, pos); - if (!key) goto bad; -#elif CYTHON_ASSUME_SAFE_MACROS - key = PyTuple_GET_ITEM(kwds, pos); -#else - key = PyTuple_GetItem(kwds, pos); - if (!key) goto bad; -#endif - value = kwvalues[pos]; - pos++; - } - else - { - if (!PyDict_Next(kwds, &pos, &key, &value)) break; -#if CYTHON_AVOID_BORROWED_REFS - Py_INCREF(key); -#endif - } - name = first_kw_arg; - while (*name && (**name != key)) name++; - if (*name) { - values[name-argnames] = value; -#if CYTHON_AVOID_BORROWED_REFS - Py_INCREF(value); - Py_DECREF(key); -#endif - key = NULL; - value = NULL; - continue; - } -#if !CYTHON_AVOID_BORROWED_REFS - Py_INCREF(key); -#endif - Py_INCREF(value); - name = first_kw_arg; - #if PY_MAJOR_VERSION < 3 - if (likely(PyString_Check(key))) { - while (*name) { - if ((CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**name) == PyString_GET_SIZE(key)) - && _PyString_Eq(**name, key)) { - values[name-argnames] = value; -#if CYTHON_AVOID_BORROWED_REFS - value = NULL; -#endif - break; - } - name++; - } - if (*name) continue; - else { - PyObject*** argname = argnames; - while (argname != first_kw_arg) { - if ((**argname == key) || ( - (CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**argname) == PyString_GET_SIZE(key)) - && _PyString_Eq(**argname, key))) { - goto arg_passed_twice; - } - argname++; - } - } - } else - #endif - if (likely(PyUnicode_Check(key))) { - while (*name) { - int cmp = ( - #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 - (__Pyx_PyUnicode_GET_LENGTH(**name) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : - #endif - PyUnicode_Compare(**name, key) - ); - if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; - if (cmp == 0) { - values[name-argnames] = value; -#if CYTHON_AVOID_BORROWED_REFS - value = NULL; -#endif - break; - } - name++; - } - if (*name) continue; - else { - PyObject*** argname = argnames; - while (argname != first_kw_arg) { - int cmp = (**argname == key) ? 0 : - #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 - (__Pyx_PyUnicode_GET_LENGTH(**argname) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : - #endif - PyUnicode_Compare(**argname, key); - if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; - if (cmp == 0) goto arg_passed_twice; - argname++; - } - } - } else - goto invalid_keyword_type; - if (kwds2) { - if (unlikely(PyDict_SetItem(kwds2, key, value))) goto bad; - } else { - goto invalid_keyword; - } - } - Py_XDECREF(key); - Py_XDECREF(value); - return 0; -arg_passed_twice: - __Pyx_RaiseDoubleKeywordsError(function_name, key); - goto bad; -invalid_keyword_type: - PyErr_Format(PyExc_TypeError, - "%.200s() keywords must be strings", function_name); - goto bad; -invalid_keyword: - #if PY_MAJOR_VERSION < 3 - PyErr_Format(PyExc_TypeError, - "%.200s() got an unexpected keyword argument '%.200s'", - function_name, PyString_AsString(key)); - #else - PyErr_Format(PyExc_TypeError, - "%s() got an unexpected keyword argument '%U'", - function_name, key); - #endif -bad: - Py_XDECREF(key); - Py_XDECREF(value); - return -1; -} - -/* ArgTypeTest */ -static int __Pyx__ArgTypeTest(PyObject *obj, PyTypeObject *type, const char *name, int exact) -{ - __Pyx_TypeName type_name; - __Pyx_TypeName obj_type_name; - if (unlikely(!type)) { - PyErr_SetString(PyExc_SystemError, "Missing type object"); - return 0; - } - else if (exact) { - #if PY_MAJOR_VERSION == 2 - if ((type == &PyBaseString_Type) && likely(__Pyx_PyBaseString_CheckExact(obj))) return 1; - #endif - } - else { - if (likely(__Pyx_TypeCheck(obj, type))) return 1; - } - type_name = __Pyx_PyType_GetName(type); - obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); - PyErr_Format(PyExc_TypeError, - "Argument '%.200s' has incorrect type (expected " __Pyx_FMT_TYPENAME - ", got " __Pyx_FMT_TYPENAME ")", name, type_name, obj_type_name); - __Pyx_DECREF_TypeName(type_name); - __Pyx_DECREF_TypeName(obj_type_name); - return 0; -} - -/* RaiseException */ -#if PY_MAJOR_VERSION < 3 -static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause) { - __Pyx_PyThreadState_declare - CYTHON_UNUSED_VAR(cause); - Py_XINCREF(type); - if (!value || value == Py_None) - value = NULL; - else - Py_INCREF(value); - if (!tb || tb == Py_None) - tb = NULL; - else { - Py_INCREF(tb); - if (!PyTraceBack_Check(tb)) { - PyErr_SetString(PyExc_TypeError, - "raise: arg 3 must be a traceback or None"); - goto raise_error; - } - } - if (PyType_Check(type)) { -#if CYTHON_COMPILING_IN_PYPY - if (!value) { - Py_INCREF(Py_None); - value = Py_None; - } -#endif - PyErr_NormalizeException(&type, &value, &tb); - } else { - if (value) { - PyErr_SetString(PyExc_TypeError, - "instance exception may not have a separate value"); - goto raise_error; - } - value = type; - type = (PyObject*) Py_TYPE(type); - Py_INCREF(type); - if (!PyType_IsSubtype((PyTypeObject *)type, (PyTypeObject *)PyExc_BaseException)) { - PyErr_SetString(PyExc_TypeError, - "raise: exception class must be a subclass of BaseException"); - goto raise_error; - } - } - __Pyx_PyThreadState_assign - __Pyx_ErrRestore(type, value, tb); - return; -raise_error: - Py_XDECREF(value); - Py_XDECREF(type); - Py_XDECREF(tb); - return; -} -#else -static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause) { - PyObject* owned_instance = NULL; - if (tb == Py_None) { - tb = 0; - } else if (tb && !PyTraceBack_Check(tb)) { - PyErr_SetString(PyExc_TypeError, - "raise: arg 3 must be a traceback or None"); - goto bad; - } - if (value == Py_None) - value = 0; - if (PyExceptionInstance_Check(type)) { - if (value) { - PyErr_SetString(PyExc_TypeError, - "instance exception may not have a separate value"); - goto bad; - } - value = type; - type = (PyObject*) Py_TYPE(value); - } else if (PyExceptionClass_Check(type)) { - PyObject *instance_class = NULL; - if (value && PyExceptionInstance_Check(value)) { - instance_class = (PyObject*) Py_TYPE(value); - if (instance_class != type) { - int is_subclass = PyObject_IsSubclass(instance_class, type); - if (!is_subclass) { - instance_class = NULL; - } else if (unlikely(is_subclass == -1)) { - goto bad; - } else { - type = instance_class; - } - } - } - if (!instance_class) { - PyObject *args; - if (!value) - args = PyTuple_New(0); - else if (PyTuple_Check(value)) { - Py_INCREF(value); - args = value; - } else - args = PyTuple_Pack(1, value); - if (!args) - goto bad; - owned_instance = PyObject_Call(type, args, NULL); - Py_DECREF(args); - if (!owned_instance) - goto bad; - value = owned_instance; - if (!PyExceptionInstance_Check(value)) { - PyErr_Format(PyExc_TypeError, - "calling %R should have returned an instance of " - "BaseException, not %R", - type, Py_TYPE(value)); - goto bad; - } - } - } else { - PyErr_SetString(PyExc_TypeError, - "raise: exception class must be a subclass of BaseException"); - goto bad; - } - if (cause) { - PyObject *fixed_cause; - if (cause == Py_None) { - fixed_cause = NULL; - } else if (PyExceptionClass_Check(cause)) { - fixed_cause = PyObject_CallObject(cause, NULL); - if (fixed_cause == NULL) - goto bad; - } else if (PyExceptionInstance_Check(cause)) { - fixed_cause = cause; - Py_INCREF(fixed_cause); - } else { - PyErr_SetString(PyExc_TypeError, - "exception causes must derive from " - "BaseException"); - goto bad; - } - PyException_SetCause(value, fixed_cause); - } - PyErr_SetObject(type, value); - if (tb) { - #if PY_VERSION_HEX >= 0x030C00A6 - PyException_SetTraceback(value, tb); - #elif CYTHON_FAST_THREAD_STATE - PyThreadState *tstate = __Pyx_PyThreadState_Current; - PyObject* tmp_tb = tstate->curexc_traceback; - if (tb != tmp_tb) { - Py_INCREF(tb); - tstate->curexc_traceback = tb; - Py_XDECREF(tmp_tb); - } -#else - PyObject *tmp_type, *tmp_value, *tmp_tb; - PyErr_Fetch(&tmp_type, &tmp_value, &tmp_tb); - Py_INCREF(tb); - PyErr_Restore(tmp_type, tmp_value, tb); - Py_XDECREF(tmp_tb); -#endif - } -bad: - Py_XDECREF(owned_instance); - return; -} -#endif - -/* PyFunctionFastCall */ -#if CYTHON_FAST_PYCALL && !CYTHON_VECTORCALL -static PyObject* __Pyx_PyFunction_FastCallNoKw(PyCodeObject *co, PyObject **args, Py_ssize_t na, - PyObject *globals) { - PyFrameObject *f; - PyThreadState *tstate = __Pyx_PyThreadState_Current; - PyObject **fastlocals; - Py_ssize_t i; - PyObject *result; - assert(globals != NULL); - /* XXX Perhaps we should create a specialized - PyFrame_New() that doesn't take locals, but does - take builtins without sanity checking them. - */ - assert(tstate != NULL); - f = PyFrame_New(tstate, co, globals, NULL); - if (f == NULL) { - return NULL; - } - fastlocals = __Pyx_PyFrame_GetLocalsplus(f); - for (i = 0; i < na; i++) { - Py_INCREF(*args); - fastlocals[i] = *args++; - } - result = PyEval_EvalFrameEx(f,0); - ++tstate->recursion_depth; - Py_DECREF(f); - --tstate->recursion_depth; - return result; -} -static PyObject *__Pyx_PyFunction_FastCallDict(PyObject *func, PyObject **args, Py_ssize_t nargs, PyObject *kwargs) { - PyCodeObject *co = (PyCodeObject *)PyFunction_GET_CODE(func); - PyObject *globals = PyFunction_GET_GLOBALS(func); - PyObject *argdefs = PyFunction_GET_DEFAULTS(func); - PyObject *closure; -#if PY_MAJOR_VERSION >= 3 - PyObject *kwdefs; -#endif - PyObject *kwtuple, **k; - PyObject **d; - Py_ssize_t nd; - Py_ssize_t nk; - PyObject *result; - assert(kwargs == NULL || PyDict_Check(kwargs)); - nk = kwargs ? PyDict_Size(kwargs) : 0; - #if PY_MAJOR_VERSION < 3 - if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) { - return NULL; - } - #else - if (unlikely(Py_EnterRecursiveCall(" while calling a Python object"))) { - return NULL; - } - #endif - if ( -#if PY_MAJOR_VERSION >= 3 - co->co_kwonlyargcount == 0 && -#endif - likely(kwargs == NULL || nk == 0) && - co->co_flags == (CO_OPTIMIZED | CO_NEWLOCALS | CO_NOFREE)) { - if (argdefs == NULL && co->co_argcount == nargs) { - result = __Pyx_PyFunction_FastCallNoKw(co, args, nargs, globals); - goto done; - } - else if (nargs == 0 && argdefs != NULL - && co->co_argcount == Py_SIZE(argdefs)) { - /* function called with no arguments, but all parameters have - a default value: use default values as arguments .*/ - args = &PyTuple_GET_ITEM(argdefs, 0); - result =__Pyx_PyFunction_FastCallNoKw(co, args, Py_SIZE(argdefs), globals); - goto done; - } - } - if (kwargs != NULL) { - Py_ssize_t pos, i; - kwtuple = PyTuple_New(2 * nk); - if (kwtuple == NULL) { - result = NULL; - goto done; - } - k = &PyTuple_GET_ITEM(kwtuple, 0); - pos = i = 0; - while (PyDict_Next(kwargs, &pos, &k[i], &k[i+1])) { - Py_INCREF(k[i]); - Py_INCREF(k[i+1]); - i += 2; - } - nk = i / 2; - } - else { - kwtuple = NULL; - k = NULL; - } - closure = PyFunction_GET_CLOSURE(func); -#if PY_MAJOR_VERSION >= 3 - kwdefs = PyFunction_GET_KW_DEFAULTS(func); -#endif - if (argdefs != NULL) { - d = &PyTuple_GET_ITEM(argdefs, 0); - nd = Py_SIZE(argdefs); - } - else { - d = NULL; - nd = 0; - } -#if PY_MAJOR_VERSION >= 3 - result = PyEval_EvalCodeEx((PyObject*)co, globals, (PyObject *)NULL, - args, (int)nargs, - k, (int)nk, - d, (int)nd, kwdefs, closure); -#else - result = PyEval_EvalCodeEx(co, globals, (PyObject *)NULL, - args, (int)nargs, - k, (int)nk, - d, (int)nd, closure); -#endif - Py_XDECREF(kwtuple); -done: - Py_LeaveRecursiveCall(); - return result; -} -#endif - -/* PyObjectCall */ -#if CYTHON_COMPILING_IN_CPYTHON -static CYTHON_INLINE PyObject* __Pyx_PyObject_Call(PyObject *func, PyObject *arg, PyObject *kw) { - PyObject *result; - ternaryfunc call = Py_TYPE(func)->tp_call; - if (unlikely(!call)) - return PyObject_Call(func, arg, kw); - #if PY_MAJOR_VERSION < 3 - if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) - return NULL; - #else - if (unlikely(Py_EnterRecursiveCall(" while calling a Python object"))) - return NULL; - #endif - result = (*call)(func, arg, kw); - Py_LeaveRecursiveCall(); - if (unlikely(!result) && unlikely(!PyErr_Occurred())) { - PyErr_SetString( - PyExc_SystemError, - "NULL result without error in PyObject_Call"); - } - return result; -} -#endif - -/* PyObjectCallMethO */ -#if CYTHON_COMPILING_IN_CPYTHON -static CYTHON_INLINE PyObject* __Pyx_PyObject_CallMethO(PyObject *func, PyObject *arg) { - PyObject *self, *result; - PyCFunction cfunc; - cfunc = __Pyx_CyOrPyCFunction_GET_FUNCTION(func); - self = __Pyx_CyOrPyCFunction_GET_SELF(func); - #if PY_MAJOR_VERSION < 3 - if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) - return NULL; - #else - if (unlikely(Py_EnterRecursiveCall(" while calling a Python object"))) - return NULL; - #endif - result = cfunc(self, arg); - Py_LeaveRecursiveCall(); - if (unlikely(!result) && unlikely(!PyErr_Occurred())) { - PyErr_SetString( - PyExc_SystemError, - "NULL result without error in PyObject_Call"); - } - return result; -} -#endif - -/* PyObjectFastCall */ -#if PY_VERSION_HEX < 0x03090000 || CYTHON_COMPILING_IN_LIMITED_API -static PyObject* __Pyx_PyObject_FastCall_fallback(PyObject *func, PyObject **args, size_t nargs, PyObject *kwargs) { - PyObject *argstuple; - PyObject *result = 0; - size_t i; - argstuple = PyTuple_New((Py_ssize_t)nargs); - if (unlikely(!argstuple)) return NULL; - for (i = 0; i < nargs; i++) { - Py_INCREF(args[i]); - if (__Pyx_PyTuple_SET_ITEM(argstuple, (Py_ssize_t)i, args[i]) < 0) goto bad; - } - result = __Pyx_PyObject_Call(func, argstuple, kwargs); - bad: - Py_DECREF(argstuple); - return result; -} -#endif -static CYTHON_INLINE PyObject* __Pyx_PyObject_FastCallDict(PyObject *func, PyObject **args, size_t _nargs, PyObject *kwargs) { - Py_ssize_t nargs = __Pyx_PyVectorcall_NARGS(_nargs); -#if CYTHON_COMPILING_IN_CPYTHON - if (nargs == 0 && kwargs == NULL) { - if (__Pyx_CyOrPyCFunction_Check(func) && likely( __Pyx_CyOrPyCFunction_GET_FLAGS(func) & METH_NOARGS)) - return __Pyx_PyObject_CallMethO(func, NULL); - } - else if (nargs == 1 && kwargs == NULL) { - if (__Pyx_CyOrPyCFunction_Check(func) && likely( __Pyx_CyOrPyCFunction_GET_FLAGS(func) & METH_O)) - return __Pyx_PyObject_CallMethO(func, args[0]); - } -#endif - #if PY_VERSION_HEX < 0x030800B1 - #if CYTHON_FAST_PYCCALL - if (PyCFunction_Check(func)) { - if (kwargs) { - return _PyCFunction_FastCallDict(func, args, nargs, kwargs); - } else { - return _PyCFunction_FastCallKeywords(func, args, nargs, NULL); - } - } - #if PY_VERSION_HEX >= 0x030700A1 - if (!kwargs && __Pyx_IS_TYPE(func, &PyMethodDescr_Type)) { - return _PyMethodDescr_FastCallKeywords(func, args, nargs, NULL); - } - #endif - #endif - #if CYTHON_FAST_PYCALL - if (PyFunction_Check(func)) { - return __Pyx_PyFunction_FastCallDict(func, args, nargs, kwargs); - } - #endif - #endif - if (kwargs == NULL) { - #if CYTHON_VECTORCALL - #if PY_VERSION_HEX < 0x03090000 - vectorcallfunc f = _PyVectorcall_Function(func); - #else - vectorcallfunc f = PyVectorcall_Function(func); - #endif - if (f) { - return f(func, args, (size_t)nargs, NULL); - } - #elif defined(__Pyx_CyFunction_USED) && CYTHON_BACKPORT_VECTORCALL - if (__Pyx_CyFunction_CheckExact(func)) { - __pyx_vectorcallfunc f = __Pyx_CyFunction_func_vectorcall(func); - if (f) return f(func, args, (size_t)nargs, NULL); - } - #endif - } - if (nargs == 0) { - return __Pyx_PyObject_Call(func, __pyx_empty_tuple, kwargs); - } - #if PY_VERSION_HEX >= 0x03090000 && !CYTHON_COMPILING_IN_LIMITED_API - return PyObject_VectorcallDict(func, args, (size_t)nargs, kwargs); - #else - return __Pyx_PyObject_FastCall_fallback(func, args, (size_t)nargs, kwargs); - #endif -} - -/* RaiseUnexpectedTypeError */ -static int -__Pyx_RaiseUnexpectedTypeError(const char *expected, PyObject *obj) -{ - __Pyx_TypeName obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); - PyErr_Format(PyExc_TypeError, "Expected %s, got " __Pyx_FMT_TYPENAME, - expected, obj_type_name); - __Pyx_DECREF_TypeName(obj_type_name); - return 0; -} - -/* CIntToDigits */ -static const char DIGIT_PAIRS_10[2*10*10+1] = { - "00010203040506070809" - "10111213141516171819" - "20212223242526272829" - "30313233343536373839" - "40414243444546474849" - "50515253545556575859" - "60616263646566676869" - "70717273747576777879" - "80818283848586878889" - "90919293949596979899" -}; -static const char DIGIT_PAIRS_8[2*8*8+1] = { - "0001020304050607" - "1011121314151617" - "2021222324252627" - "3031323334353637" - "4041424344454647" - "5051525354555657" - "6061626364656667" - "7071727374757677" -}; -static const char DIGITS_HEX[2*16+1] = { - "0123456789abcdef" - "0123456789ABCDEF" -}; - -/* BuildPyUnicode */ -static PyObject* __Pyx_PyUnicode_BuildFromAscii(Py_ssize_t ulength, char* chars, int clength, - int prepend_sign, char padding_char) { - PyObject *uval; - Py_ssize_t uoffset = ulength - clength; -#if CYTHON_USE_UNICODE_INTERNALS - Py_ssize_t i; -#if CYTHON_PEP393_ENABLED - void *udata; - uval = PyUnicode_New(ulength, 127); - if (unlikely(!uval)) return NULL; - udata = PyUnicode_DATA(uval); -#else - Py_UNICODE *udata; - uval = PyUnicode_FromUnicode(NULL, ulength); - if (unlikely(!uval)) return NULL; - udata = PyUnicode_AS_UNICODE(uval); -#endif - if (uoffset > 0) { - i = 0; - if (prepend_sign) { - __Pyx_PyUnicode_WRITE(PyUnicode_1BYTE_KIND, udata, 0, '-'); - i++; - } - for (; i < uoffset; i++) { - __Pyx_PyUnicode_WRITE(PyUnicode_1BYTE_KIND, udata, i, padding_char); - } - } - for (i=0; i < clength; i++) { - __Pyx_PyUnicode_WRITE(PyUnicode_1BYTE_KIND, udata, uoffset+i, chars[i]); - } -#else - { - PyObject *sign = NULL, *padding = NULL; - uval = NULL; - if (uoffset > 0) { - prepend_sign = !!prepend_sign; - if (uoffset > prepend_sign) { - padding = PyUnicode_FromOrdinal(padding_char); - if (likely(padding) && uoffset > prepend_sign + 1) { - PyObject *tmp; - PyObject *repeat = PyInt_FromSsize_t(uoffset - prepend_sign); - if (unlikely(!repeat)) goto done_or_error; - tmp = PyNumber_Multiply(padding, repeat); - Py_DECREF(repeat); - Py_DECREF(padding); - padding = tmp; - } - if (unlikely(!padding)) goto done_or_error; - } - if (prepend_sign) { - sign = PyUnicode_FromOrdinal('-'); - if (unlikely(!sign)) goto done_or_error; - } - } - uval = PyUnicode_DecodeASCII(chars, clength, NULL); - if (likely(uval) && padding) { - PyObject *tmp = PyNumber_Add(padding, uval); - Py_DECREF(uval); - uval = tmp; - } - if (likely(uval) && sign) { - PyObject *tmp = PyNumber_Add(sign, uval); - Py_DECREF(uval); - uval = tmp; - } -done_or_error: - Py_XDECREF(padding); - Py_XDECREF(sign); - } -#endif - return uval; -} - -/* CIntToPyUnicode */ -static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_int(int value, Py_ssize_t width, char padding_char, char format_char) { - char digits[sizeof(int)*3+2]; - char *dpos, *end = digits + sizeof(int)*3+2; - const char *hex_digits = DIGITS_HEX; - Py_ssize_t length, ulength; - int prepend_sign, last_one_off; - int remaining; -#ifdef __Pyx_HAS_GCC_DIAGNOSTIC -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wconversion" -#endif - const int neg_one = (int) -1, const_zero = (int) 0; -#ifdef __Pyx_HAS_GCC_DIAGNOSTIC -#pragma GCC diagnostic pop -#endif - const int is_unsigned = neg_one > const_zero; - if (format_char == 'X') { - hex_digits += 16; - format_char = 'x'; - } - remaining = value; - last_one_off = 0; - dpos = end; - do { - int digit_pos; - switch (format_char) { - case 'o': - digit_pos = abs((int)(remaining % (8*8))); - remaining = (int) (remaining / (8*8)); - dpos -= 2; - memcpy(dpos, DIGIT_PAIRS_8 + digit_pos * 2, 2); - last_one_off = (digit_pos < 8); - break; - case 'd': - digit_pos = abs((int)(remaining % (10*10))); - remaining = (int) (remaining / (10*10)); - dpos -= 2; - memcpy(dpos, DIGIT_PAIRS_10 + digit_pos * 2, 2); - last_one_off = (digit_pos < 10); - break; - case 'x': - *(--dpos) = hex_digits[abs((int)(remaining % 16))]; - remaining = (int) (remaining / 16); - break; - default: - assert(0); - break; - } - } while (unlikely(remaining != 0)); - assert(!last_one_off || *dpos == '0'); - dpos += last_one_off; - length = end - dpos; - ulength = length; - prepend_sign = 0; - if (!is_unsigned && value <= neg_one) { - if (padding_char == ' ' || width <= length + 1) { - *(--dpos) = '-'; - ++length; - } else { - prepend_sign = 1; - } - ++ulength; - } - if (width > ulength) { - ulength = width; - } - if (ulength == 1) { - return PyUnicode_FromOrdinal(*dpos); - } - return __Pyx_PyUnicode_BuildFromAscii(ulength, dpos, (int) length, prepend_sign, padding_char); -} - -/* CIntToPyUnicode */ -static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_Py_ssize_t(Py_ssize_t value, Py_ssize_t width, char padding_char, char format_char) { - char digits[sizeof(Py_ssize_t)*3+2]; - char *dpos, *end = digits + sizeof(Py_ssize_t)*3+2; - const char *hex_digits = DIGITS_HEX; - Py_ssize_t length, ulength; - int prepend_sign, last_one_off; - Py_ssize_t remaining; -#ifdef __Pyx_HAS_GCC_DIAGNOSTIC -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wconversion" -#endif - const Py_ssize_t neg_one = (Py_ssize_t) -1, const_zero = (Py_ssize_t) 0; -#ifdef __Pyx_HAS_GCC_DIAGNOSTIC -#pragma GCC diagnostic pop -#endif - const int is_unsigned = neg_one > const_zero; - if (format_char == 'X') { - hex_digits += 16; - format_char = 'x'; - } - remaining = value; - last_one_off = 0; - dpos = end; - do { - int digit_pos; - switch (format_char) { - case 'o': - digit_pos = abs((int)(remaining % (8*8))); - remaining = (Py_ssize_t) (remaining / (8*8)); - dpos -= 2; - memcpy(dpos, DIGIT_PAIRS_8 + digit_pos * 2, 2); - last_one_off = (digit_pos < 8); - break; - case 'd': - digit_pos = abs((int)(remaining % (10*10))); - remaining = (Py_ssize_t) (remaining / (10*10)); - dpos -= 2; - memcpy(dpos, DIGIT_PAIRS_10 + digit_pos * 2, 2); - last_one_off = (digit_pos < 10); - break; - case 'x': - *(--dpos) = hex_digits[abs((int)(remaining % 16))]; - remaining = (Py_ssize_t) (remaining / 16); - break; - default: - assert(0); - break; - } - } while (unlikely(remaining != 0)); - assert(!last_one_off || *dpos == '0'); - dpos += last_one_off; - length = end - dpos; - ulength = length; - prepend_sign = 0; - if (!is_unsigned && value <= neg_one) { - if (padding_char == ' ' || width <= length + 1) { - *(--dpos) = '-'; - ++length; - } else { - prepend_sign = 1; - } - ++ulength; - } - if (width > ulength) { - ulength = width; - } - if (ulength == 1) { - return PyUnicode_FromOrdinal(*dpos); - } - return __Pyx_PyUnicode_BuildFromAscii(ulength, dpos, (int) length, prepend_sign, padding_char); -} - -/* JoinPyUnicode */ -static PyObject* __Pyx_PyUnicode_Join(PyObject* value_tuple, Py_ssize_t value_count, Py_ssize_t result_ulength, - Py_UCS4 max_char) { -#if CYTHON_USE_UNICODE_INTERNALS && CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS - PyObject *result_uval; - int result_ukind, kind_shift; - Py_ssize_t i, char_pos; - void *result_udata; - CYTHON_MAYBE_UNUSED_VAR(max_char); -#if CYTHON_PEP393_ENABLED - result_uval = PyUnicode_New(result_ulength, max_char); - if (unlikely(!result_uval)) return NULL; - result_ukind = (max_char <= 255) ? PyUnicode_1BYTE_KIND : (max_char <= 65535) ? PyUnicode_2BYTE_KIND : PyUnicode_4BYTE_KIND; - kind_shift = (result_ukind == PyUnicode_4BYTE_KIND) ? 2 : result_ukind - 1; - result_udata = PyUnicode_DATA(result_uval); -#else - result_uval = PyUnicode_FromUnicode(NULL, result_ulength); - if (unlikely(!result_uval)) return NULL; - result_ukind = sizeof(Py_UNICODE); - kind_shift = (result_ukind == 4) ? 2 : result_ukind - 1; - result_udata = PyUnicode_AS_UNICODE(result_uval); -#endif - assert(kind_shift == 2 || kind_shift == 1 || kind_shift == 0); - char_pos = 0; - for (i=0; i < value_count; i++) { - int ukind; - Py_ssize_t ulength; - void *udata; - PyObject *uval = PyTuple_GET_ITEM(value_tuple, i); - if (unlikely(__Pyx_PyUnicode_READY(uval))) - goto bad; - ulength = __Pyx_PyUnicode_GET_LENGTH(uval); - if (unlikely(!ulength)) - continue; - if (unlikely((PY_SSIZE_T_MAX >> kind_shift) - ulength < char_pos)) - goto overflow; - ukind = __Pyx_PyUnicode_KIND(uval); - udata = __Pyx_PyUnicode_DATA(uval); - if (!CYTHON_PEP393_ENABLED || ukind == result_ukind) { - memcpy((char *)result_udata + (char_pos << kind_shift), udata, (size_t) (ulength << kind_shift)); - } else { - #if PY_VERSION_HEX >= 0x030d0000 - if (unlikely(PyUnicode_CopyCharacters(result_uval, char_pos, uval, 0, ulength) < 0)) goto bad; - #elif CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030300F0 || defined(_PyUnicode_FastCopyCharacters) - _PyUnicode_FastCopyCharacters(result_uval, char_pos, uval, 0, ulength); - #else - Py_ssize_t j; - for (j=0; j < ulength; j++) { - Py_UCS4 uchar = __Pyx_PyUnicode_READ(ukind, udata, j); - __Pyx_PyUnicode_WRITE(result_ukind, result_udata, char_pos+j, uchar); - } - #endif - } - char_pos += ulength; - } - return result_uval; -overflow: - PyErr_SetString(PyExc_OverflowError, "join() result is too long for a Python string"); -bad: - Py_DECREF(result_uval); - return NULL; -#else - CYTHON_UNUSED_VAR(max_char); - CYTHON_UNUSED_VAR(result_ulength); - CYTHON_UNUSED_VAR(value_count); - return PyUnicode_Join(__pyx_empty_unicode, value_tuple); -#endif -} - -/* GetAttr */ -static CYTHON_INLINE PyObject *__Pyx_GetAttr(PyObject *o, PyObject *n) { -#if CYTHON_USE_TYPE_SLOTS -#if PY_MAJOR_VERSION >= 3 - if (likely(PyUnicode_Check(n))) -#else - if (likely(PyString_Check(n))) -#endif - return __Pyx_PyObject_GetAttrStr(o, n); -#endif - return PyObject_GetAttr(o, n); -} - -/* GetItemInt */ -static PyObject *__Pyx_GetItemInt_Generic(PyObject *o, PyObject* j) { - PyObject *r; - if (unlikely(!j)) return NULL; - r = PyObject_GetItem(o, j); - Py_DECREF(j); - return r; -} -static CYTHON_INLINE PyObject *__Pyx_GetItemInt_List_Fast(PyObject *o, Py_ssize_t i, - CYTHON_NCP_UNUSED int wraparound, - CYTHON_NCP_UNUSED int boundscheck) { -#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS - Py_ssize_t wrapped_i = i; - if (wraparound & unlikely(i < 0)) { - wrapped_i += PyList_GET_SIZE(o); - } - if ((!boundscheck) || likely(__Pyx_is_valid_index(wrapped_i, PyList_GET_SIZE(o)))) { - PyObject *r = PyList_GET_ITEM(o, wrapped_i); - Py_INCREF(r); - return r; - } - return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); -#else - return PySequence_GetItem(o, i); -#endif -} -static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Tuple_Fast(PyObject *o, Py_ssize_t i, - CYTHON_NCP_UNUSED int wraparound, - CYTHON_NCP_UNUSED int boundscheck) { -#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS - Py_ssize_t wrapped_i = i; - if (wraparound & unlikely(i < 0)) { - wrapped_i += PyTuple_GET_SIZE(o); - } - if ((!boundscheck) || likely(__Pyx_is_valid_index(wrapped_i, PyTuple_GET_SIZE(o)))) { - PyObject *r = PyTuple_GET_ITEM(o, wrapped_i); - Py_INCREF(r); - return r; - } - return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); -#else - return PySequence_GetItem(o, i); -#endif -} -static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Fast(PyObject *o, Py_ssize_t i, int is_list, - CYTHON_NCP_UNUSED int wraparound, - CYTHON_NCP_UNUSED int boundscheck) { -#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS && CYTHON_USE_TYPE_SLOTS - if (is_list || PyList_CheckExact(o)) { - Py_ssize_t n = ((!wraparound) | likely(i >= 0)) ? i : i + PyList_GET_SIZE(o); - if ((!boundscheck) || (likely(__Pyx_is_valid_index(n, PyList_GET_SIZE(o))))) { - PyObject *r = PyList_GET_ITEM(o, n); - Py_INCREF(r); - return r; - } - } - else if (PyTuple_CheckExact(o)) { - Py_ssize_t n = ((!wraparound) | likely(i >= 0)) ? i : i + PyTuple_GET_SIZE(o); - if ((!boundscheck) || likely(__Pyx_is_valid_index(n, PyTuple_GET_SIZE(o)))) { - PyObject *r = PyTuple_GET_ITEM(o, n); - Py_INCREF(r); - return r; - } - } else { - PyMappingMethods *mm = Py_TYPE(o)->tp_as_mapping; - PySequenceMethods *sm = Py_TYPE(o)->tp_as_sequence; - if (mm && mm->mp_subscript) { - PyObject *r, *key = PyInt_FromSsize_t(i); - if (unlikely(!key)) return NULL; - r = mm->mp_subscript(o, key); - Py_DECREF(key); - return r; - } - if (likely(sm && sm->sq_item)) { - if (wraparound && unlikely(i < 0) && likely(sm->sq_length)) { - Py_ssize_t l = sm->sq_length(o); - if (likely(l >= 0)) { - i += l; - } else { - if (!PyErr_ExceptionMatches(PyExc_OverflowError)) - return NULL; - PyErr_Clear(); - } - } - return sm->sq_item(o, i); - } - } -#else - if (is_list || !PyMapping_Check(o)) { - return PySequence_GetItem(o, i); - } -#endif - return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); -} - -/* PyObjectCallOneArg */ -static CYTHON_INLINE PyObject* __Pyx_PyObject_CallOneArg(PyObject *func, PyObject *arg) { - PyObject *args[2] = {NULL, arg}; - return __Pyx_PyObject_FastCall(func, args+1, 1 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); -} - -/* ObjectGetItem */ -#if CYTHON_USE_TYPE_SLOTS -static PyObject *__Pyx_PyObject_GetIndex(PyObject *obj, PyObject *index) { - PyObject *runerr = NULL; - Py_ssize_t key_value; - key_value = __Pyx_PyIndex_AsSsize_t(index); - if (likely(key_value != -1 || !(runerr = PyErr_Occurred()))) { - return __Pyx_GetItemInt_Fast(obj, key_value, 0, 1, 1); - } - if (PyErr_GivenExceptionMatches(runerr, PyExc_OverflowError)) { - __Pyx_TypeName index_type_name = __Pyx_PyType_GetName(Py_TYPE(index)); - PyErr_Clear(); - PyErr_Format(PyExc_IndexError, - "cannot fit '" __Pyx_FMT_TYPENAME "' into an index-sized integer", index_type_name); - __Pyx_DECREF_TypeName(index_type_name); - } - return NULL; -} -static PyObject *__Pyx_PyObject_GetItem_Slow(PyObject *obj, PyObject *key) { - __Pyx_TypeName obj_type_name; - if (likely(PyType_Check(obj))) { - PyObject *meth = __Pyx_PyObject_GetAttrStrNoError(obj, __pyx_n_s_class_getitem); - if (!meth) { - PyErr_Clear(); - } else { - PyObject *result = __Pyx_PyObject_CallOneArg(meth, key); - Py_DECREF(meth); - return result; - } - } - obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); - PyErr_Format(PyExc_TypeError, - "'" __Pyx_FMT_TYPENAME "' object is not subscriptable", obj_type_name); - __Pyx_DECREF_TypeName(obj_type_name); - return NULL; -} -static PyObject *__Pyx_PyObject_GetItem(PyObject *obj, PyObject *key) { - PyTypeObject *tp = Py_TYPE(obj); - PyMappingMethods *mm = tp->tp_as_mapping; - PySequenceMethods *sm = tp->tp_as_sequence; - if (likely(mm && mm->mp_subscript)) { - return mm->mp_subscript(obj, key); - } - if (likely(sm && sm->sq_item)) { - return __Pyx_PyObject_GetIndex(obj, key); - } - return __Pyx_PyObject_GetItem_Slow(obj, key); -} -#endif - -/* KeywordStringCheck */ -static int __Pyx_CheckKeywordStrings( - PyObject *kw, - const char* function_name, - int kw_allowed) -{ - PyObject* key = 0; - Py_ssize_t pos = 0; -#if CYTHON_COMPILING_IN_PYPY - if (!kw_allowed && PyDict_Next(kw, &pos, &key, 0)) - goto invalid_keyword; - return 1; -#else - if (CYTHON_METH_FASTCALL && likely(PyTuple_Check(kw))) { - Py_ssize_t kwsize; -#if CYTHON_ASSUME_SAFE_MACROS - kwsize = PyTuple_GET_SIZE(kw); -#else - kwsize = PyTuple_Size(kw); - if (kwsize < 0) return 0; -#endif - if (unlikely(kwsize == 0)) - return 1; - if (!kw_allowed) { -#if CYTHON_ASSUME_SAFE_MACROS - key = PyTuple_GET_ITEM(kw, 0); -#else - key = PyTuple_GetItem(kw, pos); - if (!key) return 0; -#endif - goto invalid_keyword; - } -#if PY_VERSION_HEX < 0x03090000 - for (pos = 0; pos < kwsize; pos++) { -#if CYTHON_ASSUME_SAFE_MACROS - key = PyTuple_GET_ITEM(kw, pos); -#else - key = PyTuple_GetItem(kw, pos); - if (!key) return 0; -#endif - if (unlikely(!PyUnicode_Check(key))) - goto invalid_keyword_type; - } -#endif - return 1; - } - while (PyDict_Next(kw, &pos, &key, 0)) { - #if PY_MAJOR_VERSION < 3 - if (unlikely(!PyString_Check(key))) - #endif - if (unlikely(!PyUnicode_Check(key))) - goto invalid_keyword_type; - } - if (!kw_allowed && unlikely(key)) - goto invalid_keyword; - return 1; -invalid_keyword_type: - PyErr_Format(PyExc_TypeError, - "%.200s() keywords must be strings", function_name); - return 0; -#endif -invalid_keyword: - #if PY_MAJOR_VERSION < 3 - PyErr_Format(PyExc_TypeError, - "%.200s() got an unexpected keyword argument '%.200s'", - function_name, PyString_AsString(key)); - #else - PyErr_Format(PyExc_TypeError, - "%s() got an unexpected keyword argument '%U'", - function_name, key); - #endif - return 0; -} - -/* DivInt[Py_ssize_t] */ -static CYTHON_INLINE Py_ssize_t __Pyx_div_Py_ssize_t(Py_ssize_t a, Py_ssize_t b) { - Py_ssize_t q = a / b; - Py_ssize_t r = a - q*b; - q -= ((r != 0) & ((r ^ b) < 0)); - return q; -} - -/* GetAttr3 */ -#if __PYX_LIMITED_VERSION_HEX < 0x030d00A1 -static PyObject *__Pyx_GetAttr3Default(PyObject *d) { - __Pyx_PyThreadState_declare - __Pyx_PyThreadState_assign - if (unlikely(!__Pyx_PyErr_ExceptionMatches(PyExc_AttributeError))) - return NULL; - __Pyx_PyErr_Clear(); - Py_INCREF(d); - return d; -} -#endif -static CYTHON_INLINE PyObject *__Pyx_GetAttr3(PyObject *o, PyObject *n, PyObject *d) { - PyObject *r; -#if __PYX_LIMITED_VERSION_HEX >= 0x030d00A1 - int res = PyObject_GetOptionalAttr(o, n, &r); - return (res != 0) ? r : __Pyx_NewRef(d); -#else - #if CYTHON_USE_TYPE_SLOTS - if (likely(PyString_Check(n))) { - r = __Pyx_PyObject_GetAttrStrNoError(o, n); - if (unlikely(!r) && likely(!PyErr_Occurred())) { - r = __Pyx_NewRef(d); - } - return r; - } - #endif - r = PyObject_GetAttr(o, n); - return (likely(r)) ? r : __Pyx_GetAttr3Default(d); -#endif -} - -/* PyDictVersioning */ -#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS -static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj) { - PyObject *dict = Py_TYPE(obj)->tp_dict; - return likely(dict) ? __PYX_GET_DICT_VERSION(dict) : 0; -} -static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj) { - PyObject **dictptr = NULL; - Py_ssize_t offset = Py_TYPE(obj)->tp_dictoffset; - if (offset) { -#if CYTHON_COMPILING_IN_CPYTHON - dictptr = (likely(offset > 0)) ? (PyObject **) ((char *)obj + offset) : _PyObject_GetDictPtr(obj); -#else - dictptr = _PyObject_GetDictPtr(obj); -#endif - } - return (dictptr && *dictptr) ? __PYX_GET_DICT_VERSION(*dictptr) : 0; -} -static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version) { - PyObject *dict = Py_TYPE(obj)->tp_dict; - if (unlikely(!dict) || unlikely(tp_dict_version != __PYX_GET_DICT_VERSION(dict))) - return 0; - return obj_dict_version == __Pyx_get_object_dict_version(obj); -} -#endif - -/* GetModuleGlobalName */ -#if CYTHON_USE_DICT_VERSIONS -static PyObject *__Pyx__GetModuleGlobalName(PyObject *name, PY_UINT64_T *dict_version, PyObject **dict_cached_value) -#else -static CYTHON_INLINE PyObject *__Pyx__GetModuleGlobalName(PyObject *name) -#endif -{ - PyObject *result; -#if !CYTHON_AVOID_BORROWED_REFS -#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030500A1 && PY_VERSION_HEX < 0x030d0000 - result = _PyDict_GetItem_KnownHash(__pyx_d, name, ((PyASCIIObject *) name)->hash); - __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) - if (likely(result)) { - return __Pyx_NewRef(result); - } else if (unlikely(PyErr_Occurred())) { - return NULL; - } -#elif CYTHON_COMPILING_IN_LIMITED_API - if (unlikely(!__pyx_m)) { - return NULL; - } - result = PyObject_GetAttr(__pyx_m, name); - if (likely(result)) { - return result; - } -#else - result = PyDict_GetItem(__pyx_d, name); - __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) - if (likely(result)) { - return __Pyx_NewRef(result); - } -#endif -#else - result = PyObject_GetItem(__pyx_d, name); - __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) - if (likely(result)) { - return __Pyx_NewRef(result); - } - PyErr_Clear(); -#endif - return __Pyx_GetBuiltinName(name); -} - -/* RaiseTooManyValuesToUnpack */ -static CYTHON_INLINE void __Pyx_RaiseTooManyValuesError(Py_ssize_t expected) { - PyErr_Format(PyExc_ValueError, - "too many values to unpack (expected %" CYTHON_FORMAT_SSIZE_T "d)", expected); -} - -/* RaiseNeedMoreValuesToUnpack */ -static CYTHON_INLINE void __Pyx_RaiseNeedMoreValuesError(Py_ssize_t index) { - PyErr_Format(PyExc_ValueError, - "need more than %" CYTHON_FORMAT_SSIZE_T "d value%.1s to unpack", - index, (index == 1) ? "" : "s"); -} - -/* RaiseNoneIterError */ -static CYTHON_INLINE void __Pyx_RaiseNoneNotIterableError(void) { - PyErr_SetString(PyExc_TypeError, "'NoneType' object is not iterable"); -} - -/* ExtTypeTest */ -static CYTHON_INLINE int __Pyx_TypeTest(PyObject *obj, PyTypeObject *type) { - __Pyx_TypeName obj_type_name; - __Pyx_TypeName type_name; - if (unlikely(!type)) { - PyErr_SetString(PyExc_SystemError, "Missing type object"); - return 0; - } - if (likely(__Pyx_TypeCheck(obj, type))) - return 1; - obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); - type_name = __Pyx_PyType_GetName(type); - PyErr_Format(PyExc_TypeError, - "Cannot convert " __Pyx_FMT_TYPENAME " to " __Pyx_FMT_TYPENAME, - obj_type_name, type_name); - __Pyx_DECREF_TypeName(obj_type_name); - __Pyx_DECREF_TypeName(type_name); - return 0; -} - -/* GetTopmostException */ -#if CYTHON_USE_EXC_INFO_STACK && CYTHON_FAST_THREAD_STATE -static _PyErr_StackItem * -__Pyx_PyErr_GetTopmostException(PyThreadState *tstate) -{ - _PyErr_StackItem *exc_info = tstate->exc_info; - while ((exc_info->exc_value == NULL || exc_info->exc_value == Py_None) && - exc_info->previous_item != NULL) - { - exc_info = exc_info->previous_item; - } - return exc_info; -} -#endif - -/* SaveResetException */ -#if CYTHON_FAST_THREAD_STATE -static CYTHON_INLINE void __Pyx__ExceptionSave(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { - #if CYTHON_USE_EXC_INFO_STACK && PY_VERSION_HEX >= 0x030B00a4 - _PyErr_StackItem *exc_info = __Pyx_PyErr_GetTopmostException(tstate); - PyObject *exc_value = exc_info->exc_value; - if (exc_value == NULL || exc_value == Py_None) { - *value = NULL; - *type = NULL; - *tb = NULL; - } else { - *value = exc_value; - Py_INCREF(*value); - *type = (PyObject*) Py_TYPE(exc_value); - Py_INCREF(*type); - *tb = PyException_GetTraceback(exc_value); - } - #elif CYTHON_USE_EXC_INFO_STACK - _PyErr_StackItem *exc_info = __Pyx_PyErr_GetTopmostException(tstate); - *type = exc_info->exc_type; - *value = exc_info->exc_value; - *tb = exc_info->exc_traceback; - Py_XINCREF(*type); - Py_XINCREF(*value); - Py_XINCREF(*tb); - #else - *type = tstate->exc_type; - *value = tstate->exc_value; - *tb = tstate->exc_traceback; - Py_XINCREF(*type); - Py_XINCREF(*value); - Py_XINCREF(*tb); - #endif -} -static CYTHON_INLINE void __Pyx__ExceptionReset(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb) { - #if CYTHON_USE_EXC_INFO_STACK && PY_VERSION_HEX >= 0x030B00a4 - _PyErr_StackItem *exc_info = tstate->exc_info; - PyObject *tmp_value = exc_info->exc_value; - exc_info->exc_value = value; - Py_XDECREF(tmp_value); - Py_XDECREF(type); - Py_XDECREF(tb); - #else - PyObject *tmp_type, *tmp_value, *tmp_tb; - #if CYTHON_USE_EXC_INFO_STACK - _PyErr_StackItem *exc_info = tstate->exc_info; - tmp_type = exc_info->exc_type; - tmp_value = exc_info->exc_value; - tmp_tb = exc_info->exc_traceback; - exc_info->exc_type = type; - exc_info->exc_value = value; - exc_info->exc_traceback = tb; - #else - tmp_type = tstate->exc_type; - tmp_value = tstate->exc_value; - tmp_tb = tstate->exc_traceback; - tstate->exc_type = type; - tstate->exc_value = value; - tstate->exc_traceback = tb; - #endif - Py_XDECREF(tmp_type); - Py_XDECREF(tmp_value); - Py_XDECREF(tmp_tb); - #endif -} -#endif - -/* GetException */ -#if CYTHON_FAST_THREAD_STATE -static int __Pyx__GetException(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) -#else -static int __Pyx_GetException(PyObject **type, PyObject **value, PyObject **tb) -#endif -{ - PyObject *local_type = NULL, *local_value, *local_tb = NULL; -#if CYTHON_FAST_THREAD_STATE - PyObject *tmp_type, *tmp_value, *tmp_tb; - #if PY_VERSION_HEX >= 0x030C00A6 - local_value = tstate->current_exception; - tstate->current_exception = 0; - if (likely(local_value)) { - local_type = (PyObject*) Py_TYPE(local_value); - Py_INCREF(local_type); - local_tb = PyException_GetTraceback(local_value); - } - #else - local_type = tstate->curexc_type; - local_value = tstate->curexc_value; - local_tb = tstate->curexc_traceback; - tstate->curexc_type = 0; - tstate->curexc_value = 0; - tstate->curexc_traceback = 0; - #endif -#else - PyErr_Fetch(&local_type, &local_value, &local_tb); -#endif - PyErr_NormalizeException(&local_type, &local_value, &local_tb); -#if CYTHON_FAST_THREAD_STATE && PY_VERSION_HEX >= 0x030C00A6 - if (unlikely(tstate->current_exception)) -#elif CYTHON_FAST_THREAD_STATE - if (unlikely(tstate->curexc_type)) -#else - if (unlikely(PyErr_Occurred())) -#endif - goto bad; - #if PY_MAJOR_VERSION >= 3 - if (local_tb) { - if (unlikely(PyException_SetTraceback(local_value, local_tb) < 0)) - goto bad; - } - #endif - Py_XINCREF(local_tb); - Py_XINCREF(local_type); - Py_XINCREF(local_value); - *type = local_type; - *value = local_value; - *tb = local_tb; -#if CYTHON_FAST_THREAD_STATE - #if CYTHON_USE_EXC_INFO_STACK - { - _PyErr_StackItem *exc_info = tstate->exc_info; - #if PY_VERSION_HEX >= 0x030B00a4 - tmp_value = exc_info->exc_value; - exc_info->exc_value = local_value; - tmp_type = NULL; - tmp_tb = NULL; - Py_XDECREF(local_type); - Py_XDECREF(local_tb); - #else - tmp_type = exc_info->exc_type; - tmp_value = exc_info->exc_value; - tmp_tb = exc_info->exc_traceback; - exc_info->exc_type = local_type; - exc_info->exc_value = local_value; - exc_info->exc_traceback = local_tb; - #endif - } - #else - tmp_type = tstate->exc_type; - tmp_value = tstate->exc_value; - tmp_tb = tstate->exc_traceback; - tstate->exc_type = local_type; - tstate->exc_value = local_value; - tstate->exc_traceback = local_tb; - #endif - Py_XDECREF(tmp_type); - Py_XDECREF(tmp_value); - Py_XDECREF(tmp_tb); -#else - PyErr_SetExcInfo(local_type, local_value, local_tb); -#endif - return 0; -bad: - *type = 0; - *value = 0; - *tb = 0; - Py_XDECREF(local_type); - Py_XDECREF(local_value); - Py_XDECREF(local_tb); - return -1; -} - -/* SwapException */ -#if CYTHON_FAST_THREAD_STATE -static CYTHON_INLINE void __Pyx__ExceptionSwap(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { - PyObject *tmp_type, *tmp_value, *tmp_tb; - #if CYTHON_USE_EXC_INFO_STACK && PY_VERSION_HEX >= 0x030B00a4 - _PyErr_StackItem *exc_info = tstate->exc_info; - tmp_value = exc_info->exc_value; - exc_info->exc_value = *value; - if (tmp_value == NULL || tmp_value == Py_None) { - Py_XDECREF(tmp_value); - tmp_value = NULL; - tmp_type = NULL; - tmp_tb = NULL; - } else { - tmp_type = (PyObject*) Py_TYPE(tmp_value); - Py_INCREF(tmp_type); - #if CYTHON_COMPILING_IN_CPYTHON - tmp_tb = ((PyBaseExceptionObject*) tmp_value)->traceback; - Py_XINCREF(tmp_tb); - #else - tmp_tb = PyException_GetTraceback(tmp_value); - #endif - } - #elif CYTHON_USE_EXC_INFO_STACK - _PyErr_StackItem *exc_info = tstate->exc_info; - tmp_type = exc_info->exc_type; - tmp_value = exc_info->exc_value; - tmp_tb = exc_info->exc_traceback; - exc_info->exc_type = *type; - exc_info->exc_value = *value; - exc_info->exc_traceback = *tb; - #else - tmp_type = tstate->exc_type; - tmp_value = tstate->exc_value; - tmp_tb = tstate->exc_traceback; - tstate->exc_type = *type; - tstate->exc_value = *value; - tstate->exc_traceback = *tb; - #endif - *type = tmp_type; - *value = tmp_value; - *tb = tmp_tb; -} -#else -static CYTHON_INLINE void __Pyx_ExceptionSwap(PyObject **type, PyObject **value, PyObject **tb) { - PyObject *tmp_type, *tmp_value, *tmp_tb; - PyErr_GetExcInfo(&tmp_type, &tmp_value, &tmp_tb); - PyErr_SetExcInfo(*type, *value, *tb); - *type = tmp_type; - *value = tmp_value; - *tb = tmp_tb; -} -#endif - -/* Import */ -static PyObject *__Pyx_Import(PyObject *name, PyObject *from_list, int level) { - PyObject *module = 0; - PyObject *empty_dict = 0; - PyObject *empty_list = 0; - #if PY_MAJOR_VERSION < 3 - PyObject *py_import; - py_import = __Pyx_PyObject_GetAttrStr(__pyx_b, __pyx_n_s_import); - if (unlikely(!py_import)) - goto bad; - if (!from_list) { - empty_list = PyList_New(0); - if (unlikely(!empty_list)) - goto bad; - from_list = empty_list; - } - #endif - empty_dict = PyDict_New(); - if (unlikely(!empty_dict)) - goto bad; - { - #if PY_MAJOR_VERSION >= 3 - if (level == -1) { - if (strchr(__Pyx_MODULE_NAME, '.') != NULL) { - module = PyImport_ImportModuleLevelObject( - name, __pyx_d, empty_dict, from_list, 1); - if (unlikely(!module)) { - if (unlikely(!PyErr_ExceptionMatches(PyExc_ImportError))) - goto bad; - PyErr_Clear(); - } - } - level = 0; - } - #endif - if (!module) { - #if PY_MAJOR_VERSION < 3 - PyObject *py_level = PyInt_FromLong(level); - if (unlikely(!py_level)) - goto bad; - module = PyObject_CallFunctionObjArgs(py_import, - name, __pyx_d, empty_dict, from_list, py_level, (PyObject *)NULL); - Py_DECREF(py_level); - #else - module = PyImport_ImportModuleLevelObject( - name, __pyx_d, empty_dict, from_list, level); - #endif - } - } -bad: - Py_XDECREF(empty_dict); - Py_XDECREF(empty_list); - #if PY_MAJOR_VERSION < 3 - Py_XDECREF(py_import); - #endif - return module; -} - -/* ImportDottedModule */ -#if PY_MAJOR_VERSION >= 3 -static PyObject *__Pyx__ImportDottedModule_Error(PyObject *name, PyObject *parts_tuple, Py_ssize_t count) { - PyObject *partial_name = NULL, *slice = NULL, *sep = NULL; - if (unlikely(PyErr_Occurred())) { - PyErr_Clear(); - } - if (likely(PyTuple_GET_SIZE(parts_tuple) == count)) { - partial_name = name; - } else { - slice = PySequence_GetSlice(parts_tuple, 0, count); - if (unlikely(!slice)) - goto bad; - sep = PyUnicode_FromStringAndSize(".", 1); - if (unlikely(!sep)) - goto bad; - partial_name = PyUnicode_Join(sep, slice); - } - PyErr_Format( -#if PY_MAJOR_VERSION < 3 - PyExc_ImportError, - "No module named '%s'", PyString_AS_STRING(partial_name)); -#else -#if PY_VERSION_HEX >= 0x030600B1 - PyExc_ModuleNotFoundError, -#else - PyExc_ImportError, -#endif - "No module named '%U'", partial_name); -#endif -bad: - Py_XDECREF(sep); - Py_XDECREF(slice); - Py_XDECREF(partial_name); - return NULL; -} -#endif -#if PY_MAJOR_VERSION >= 3 -static PyObject *__Pyx__ImportDottedModule_Lookup(PyObject *name) { - PyObject *imported_module; -#if PY_VERSION_HEX < 0x030700A1 || (CYTHON_COMPILING_IN_PYPY && PYPY_VERSION_NUM < 0x07030400) - PyObject *modules = PyImport_GetModuleDict(); - if (unlikely(!modules)) - return NULL; - imported_module = __Pyx_PyDict_GetItemStr(modules, name); - Py_XINCREF(imported_module); -#else - imported_module = PyImport_GetModule(name); -#endif - return imported_module; -} -#endif -#if PY_MAJOR_VERSION >= 3 -static PyObject *__Pyx_ImportDottedModule_WalkParts(PyObject *module, PyObject *name, PyObject *parts_tuple) { - Py_ssize_t i, nparts; - nparts = PyTuple_GET_SIZE(parts_tuple); - for (i=1; i < nparts && module; i++) { - PyObject *part, *submodule; -#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS - part = PyTuple_GET_ITEM(parts_tuple, i); -#else - part = PySequence_ITEM(parts_tuple, i); -#endif - submodule = __Pyx_PyObject_GetAttrStrNoError(module, part); -#if !(CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS) - Py_DECREF(part); -#endif - Py_DECREF(module); - module = submodule; - } - if (unlikely(!module)) { - return __Pyx__ImportDottedModule_Error(name, parts_tuple, i); - } - return module; -} -#endif -static PyObject *__Pyx__ImportDottedModule(PyObject *name, PyObject *parts_tuple) { -#if PY_MAJOR_VERSION < 3 - PyObject *module, *from_list, *star = __pyx_n_s__3; - CYTHON_UNUSED_VAR(parts_tuple); - from_list = PyList_New(1); - if (unlikely(!from_list)) - return NULL; - Py_INCREF(star); - PyList_SET_ITEM(from_list, 0, star); - module = __Pyx_Import(name, from_list, 0); - Py_DECREF(from_list); - return module; -#else - PyObject *imported_module; - PyObject *module = __Pyx_Import(name, NULL, 0); - if (!parts_tuple || unlikely(!module)) - return module; - imported_module = __Pyx__ImportDottedModule_Lookup(name); - if (likely(imported_module)) { - Py_DECREF(module); - return imported_module; - } - PyErr_Clear(); - return __Pyx_ImportDottedModule_WalkParts(module, name, parts_tuple); -#endif -} -static PyObject *__Pyx_ImportDottedModule(PyObject *name, PyObject *parts_tuple) { -#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030400B1 - PyObject *module = __Pyx__ImportDottedModule_Lookup(name); - if (likely(module)) { - PyObject *spec = __Pyx_PyObject_GetAttrStrNoError(module, __pyx_n_s_spec); - if (likely(spec)) { - PyObject *unsafe = __Pyx_PyObject_GetAttrStrNoError(spec, __pyx_n_s_initializing); - if (likely(!unsafe || !__Pyx_PyObject_IsTrue(unsafe))) { - Py_DECREF(spec); - spec = NULL; - } - Py_XDECREF(unsafe); - } - if (likely(!spec)) { - PyErr_Clear(); - return module; - } - Py_DECREF(spec); - Py_DECREF(module); - } else if (PyErr_Occurred()) { - PyErr_Clear(); - } -#endif - return __Pyx__ImportDottedModule(name, parts_tuple); -} - -/* FastTypeChecks */ -#if CYTHON_COMPILING_IN_CPYTHON -static int __Pyx_InBases(PyTypeObject *a, PyTypeObject *b) { - while (a) { - a = __Pyx_PyType_GetSlot(a, tp_base, PyTypeObject*); - if (a == b) - return 1; - } - return b == &PyBaseObject_Type; -} -static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b) { - PyObject *mro; - if (a == b) return 1; - mro = a->tp_mro; - if (likely(mro)) { - Py_ssize_t i, n; - n = PyTuple_GET_SIZE(mro); - for (i = 0; i < n; i++) { - if (PyTuple_GET_ITEM(mro, i) == (PyObject *)b) - return 1; - } - return 0; - } - return __Pyx_InBases(a, b); -} -static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b) { - PyObject *mro; - if (cls == a || cls == b) return 1; - mro = cls->tp_mro; - if (likely(mro)) { - Py_ssize_t i, n; - n = PyTuple_GET_SIZE(mro); - for (i = 0; i < n; i++) { - PyObject *base = PyTuple_GET_ITEM(mro, i); - if (base == (PyObject *)a || base == (PyObject *)b) - return 1; - } - return 0; - } - return __Pyx_InBases(cls, a) || __Pyx_InBases(cls, b); -} -#if PY_MAJOR_VERSION == 2 -static int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject* exc_type2) { - PyObject *exception, *value, *tb; - int res; - __Pyx_PyThreadState_declare - __Pyx_PyThreadState_assign - __Pyx_ErrFetch(&exception, &value, &tb); - res = exc_type1 ? PyObject_IsSubclass(err, exc_type1) : 0; - if (unlikely(res == -1)) { - PyErr_WriteUnraisable(err); - res = 0; - } - if (!res) { - res = PyObject_IsSubclass(err, exc_type2); - if (unlikely(res == -1)) { - PyErr_WriteUnraisable(err); - res = 0; - } - } - __Pyx_ErrRestore(exception, value, tb); - return res; -} -#else -static CYTHON_INLINE int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject *exc_type2) { - if (exc_type1) { - return __Pyx_IsAnySubtype2((PyTypeObject*)err, (PyTypeObject*)exc_type1, (PyTypeObject*)exc_type2); - } else { - return __Pyx_IsSubtype((PyTypeObject*)err, (PyTypeObject*)exc_type2); - } -} -#endif -static int __Pyx_PyErr_GivenExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { - Py_ssize_t i, n; - assert(PyExceptionClass_Check(exc_type)); - n = PyTuple_GET_SIZE(tuple); -#if PY_MAJOR_VERSION >= 3 - for (i=0; itp_as_sequence && type->tp_as_sequence->sq_repeat)) { - return type->tp_as_sequence->sq_repeat(seq, mul); - } else -#endif - { - return __Pyx_PySequence_Multiply_Generic(seq, mul); - } -} - -/* SetItemInt */ -static int __Pyx_SetItemInt_Generic(PyObject *o, PyObject *j, PyObject *v) { - int r; - if (unlikely(!j)) return -1; - r = PyObject_SetItem(o, j, v); - Py_DECREF(j); - return r; -} -static CYTHON_INLINE int __Pyx_SetItemInt_Fast(PyObject *o, Py_ssize_t i, PyObject *v, int is_list, - CYTHON_NCP_UNUSED int wraparound, CYTHON_NCP_UNUSED int boundscheck) { -#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS && CYTHON_USE_TYPE_SLOTS - if (is_list || PyList_CheckExact(o)) { - Py_ssize_t n = (!wraparound) ? i : ((likely(i >= 0)) ? i : i + PyList_GET_SIZE(o)); - if ((!boundscheck) || likely(__Pyx_is_valid_index(n, PyList_GET_SIZE(o)))) { - PyObject* old = PyList_GET_ITEM(o, n); - Py_INCREF(v); - PyList_SET_ITEM(o, n, v); - Py_DECREF(old); - return 1; - } - } else { - PyMappingMethods *mm = Py_TYPE(o)->tp_as_mapping; - PySequenceMethods *sm = Py_TYPE(o)->tp_as_sequence; - if (mm && mm->mp_ass_subscript) { - int r; - PyObject *key = PyInt_FromSsize_t(i); - if (unlikely(!key)) return -1; - r = mm->mp_ass_subscript(o, key, v); - Py_DECREF(key); - return r; - } - if (likely(sm && sm->sq_ass_item)) { - if (wraparound && unlikely(i < 0) && likely(sm->sq_length)) { - Py_ssize_t l = sm->sq_length(o); - if (likely(l >= 0)) { - i += l; - } else { - if (!PyErr_ExceptionMatches(PyExc_OverflowError)) - return -1; - PyErr_Clear(); - } - } - return sm->sq_ass_item(o, i, v); - } - } -#else - if (is_list || !PyMapping_Check(o)) - { - return PySequence_SetItem(o, i, v); - } -#endif - return __Pyx_SetItemInt_Generic(o, PyInt_FromSsize_t(i), v); -} - -/* RaiseUnboundLocalError */ -static CYTHON_INLINE void __Pyx_RaiseUnboundLocalError(const char *varname) { - PyErr_Format(PyExc_UnboundLocalError, "local variable '%s' referenced before assignment", varname); -} - -/* DivInt[long] */ -static CYTHON_INLINE long __Pyx_div_long(long a, long b) { - long q = a / b; - long r = a - q*b; - q -= ((r != 0) & ((r ^ b) < 0)); - return q; -} - -/* ImportFrom */ -static PyObject* __Pyx_ImportFrom(PyObject* module, PyObject* name) { - PyObject* value = __Pyx_PyObject_GetAttrStr(module, name); - if (unlikely(!value) && PyErr_ExceptionMatches(PyExc_AttributeError)) { - const char* module_name_str = 0; - PyObject* module_name = 0; - PyObject* module_dot = 0; - PyObject* full_name = 0; - PyErr_Clear(); - module_name_str = PyModule_GetName(module); - if (unlikely(!module_name_str)) { goto modbad; } - module_name = PyUnicode_FromString(module_name_str); - if (unlikely(!module_name)) { goto modbad; } - module_dot = PyUnicode_Concat(module_name, __pyx_kp_u__2); - if (unlikely(!module_dot)) { goto modbad; } - full_name = PyUnicode_Concat(module_dot, name); - if (unlikely(!full_name)) { goto modbad; } - #if PY_VERSION_HEX < 0x030700A1 || (CYTHON_COMPILING_IN_PYPY && PYPY_VERSION_NUM < 0x07030400) - { - PyObject *modules = PyImport_GetModuleDict(); - if (unlikely(!modules)) - goto modbad; - value = PyObject_GetItem(modules, full_name); - } - #else - value = PyImport_GetModule(full_name); - #endif - modbad: - Py_XDECREF(full_name); - Py_XDECREF(module_dot); - Py_XDECREF(module_name); - } - if (unlikely(!value)) { - PyErr_Format(PyExc_ImportError, - #if PY_MAJOR_VERSION < 3 - "cannot import name %.230s", PyString_AS_STRING(name)); - #else - "cannot import name %S", name); - #endif - } - return value; -} - -/* HasAttr */ -#if __PYX_LIMITED_VERSION_HEX < 0x030d00A1 -static CYTHON_INLINE int __Pyx_HasAttr(PyObject *o, PyObject *n) { - PyObject *r; - if (unlikely(!__Pyx_PyBaseString_Check(n))) { - PyErr_SetString(PyExc_TypeError, - "hasattr(): attribute name must be string"); - return -1; - } - r = __Pyx_GetAttr(o, n); - if (!r) { - PyErr_Clear(); - return 0; - } else { - Py_DECREF(r); - return 1; - } -} -#endif - -/* PyObjectCall2Args */ -static CYTHON_INLINE PyObject* __Pyx_PyObject_Call2Args(PyObject* function, PyObject* arg1, PyObject* arg2) { - PyObject *args[3] = {NULL, arg1, arg2}; - return __Pyx_PyObject_FastCall(function, args+1, 2 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); -} - -/* PyObjectGetMethod */ -static int __Pyx_PyObject_GetMethod(PyObject *obj, PyObject *name, PyObject **method) { - PyObject *attr; -#if CYTHON_UNPACK_METHODS && CYTHON_COMPILING_IN_CPYTHON && CYTHON_USE_PYTYPE_LOOKUP - __Pyx_TypeName type_name; - PyTypeObject *tp = Py_TYPE(obj); - PyObject *descr; - descrgetfunc f = NULL; - PyObject **dictptr, *dict; - int meth_found = 0; - assert (*method == NULL); - if (unlikely(tp->tp_getattro != PyObject_GenericGetAttr)) { - attr = __Pyx_PyObject_GetAttrStr(obj, name); - goto try_unpack; - } - if (unlikely(tp->tp_dict == NULL) && unlikely(PyType_Ready(tp) < 0)) { - return 0; - } - descr = _PyType_Lookup(tp, name); - if (likely(descr != NULL)) { - Py_INCREF(descr); -#if defined(Py_TPFLAGS_METHOD_DESCRIPTOR) && Py_TPFLAGS_METHOD_DESCRIPTOR - if (__Pyx_PyType_HasFeature(Py_TYPE(descr), Py_TPFLAGS_METHOD_DESCRIPTOR)) -#elif PY_MAJOR_VERSION >= 3 - #ifdef __Pyx_CyFunction_USED - if (likely(PyFunction_Check(descr) || __Pyx_IS_TYPE(descr, &PyMethodDescr_Type) || __Pyx_CyFunction_Check(descr))) - #else - if (likely(PyFunction_Check(descr) || __Pyx_IS_TYPE(descr, &PyMethodDescr_Type))) - #endif -#else - #ifdef __Pyx_CyFunction_USED - if (likely(PyFunction_Check(descr) || __Pyx_CyFunction_Check(descr))) - #else - if (likely(PyFunction_Check(descr))) - #endif -#endif - { - meth_found = 1; - } else { - f = Py_TYPE(descr)->tp_descr_get; - if (f != NULL && PyDescr_IsData(descr)) { - attr = f(descr, obj, (PyObject *)Py_TYPE(obj)); - Py_DECREF(descr); - goto try_unpack; - } - } - } - dictptr = _PyObject_GetDictPtr(obj); - if (dictptr != NULL && (dict = *dictptr) != NULL) { - Py_INCREF(dict); - attr = __Pyx_PyDict_GetItemStr(dict, name); - if (attr != NULL) { - Py_INCREF(attr); - Py_DECREF(dict); - Py_XDECREF(descr); - goto try_unpack; - } - Py_DECREF(dict); - } - if (meth_found) { - *method = descr; - return 1; - } - if (f != NULL) { - attr = f(descr, obj, (PyObject *)Py_TYPE(obj)); - Py_DECREF(descr); - goto try_unpack; - } - if (likely(descr != NULL)) { - *method = descr; - return 0; - } - type_name = __Pyx_PyType_GetName(tp); - PyErr_Format(PyExc_AttributeError, -#if PY_MAJOR_VERSION >= 3 - "'" __Pyx_FMT_TYPENAME "' object has no attribute '%U'", - type_name, name); -#else - "'" __Pyx_FMT_TYPENAME "' object has no attribute '%.400s'", - type_name, PyString_AS_STRING(name)); -#endif - __Pyx_DECREF_TypeName(type_name); - return 0; -#else - attr = __Pyx_PyObject_GetAttrStr(obj, name); - goto try_unpack; -#endif -try_unpack: -#if CYTHON_UNPACK_METHODS - if (likely(attr) && PyMethod_Check(attr) && likely(PyMethod_GET_SELF(attr) == obj)) { - PyObject *function = PyMethod_GET_FUNCTION(attr); - Py_INCREF(function); - Py_DECREF(attr); - *method = function; - return 1; - } -#endif - *method = attr; - return 0; -} - -/* PyObjectCallMethod1 */ -#if !(CYTHON_VECTORCALL && __PYX_LIMITED_VERSION_HEX >= 0x030C00A2) -static PyObject* __Pyx__PyObject_CallMethod1(PyObject* method, PyObject* arg) { - PyObject *result = __Pyx_PyObject_CallOneArg(method, arg); - Py_DECREF(method); - return result; -} -#endif -static PyObject* __Pyx_PyObject_CallMethod1(PyObject* obj, PyObject* method_name, PyObject* arg) { -#if CYTHON_VECTORCALL && __PYX_LIMITED_VERSION_HEX >= 0x030C00A2 - PyObject *args[2] = {obj, arg}; - (void) __Pyx_PyObject_GetMethod; - (void) __Pyx_PyObject_CallOneArg; - (void) __Pyx_PyObject_Call2Args; - return PyObject_VectorcallMethod(method_name, args, 2 | PY_VECTORCALL_ARGUMENTS_OFFSET, NULL); -#else - PyObject *method = NULL, *result; - int is_method = __Pyx_PyObject_GetMethod(obj, method_name, &method); - if (likely(is_method)) { - result = __Pyx_PyObject_Call2Args(method, obj, arg); - Py_DECREF(method); - return result; - } - if (unlikely(!method)) return NULL; - return __Pyx__PyObject_CallMethod1(method, arg); -#endif -} - -/* StringJoin */ -static CYTHON_INLINE PyObject* __Pyx_PyBytes_Join(PyObject* sep, PyObject* values) { - (void) __Pyx_PyObject_CallMethod1; -#if CYTHON_COMPILING_IN_CPYTHON && PY_MAJOR_VERSION < 3 - return _PyString_Join(sep, values); -#elif CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030d0000 - return _PyBytes_Join(sep, values); -#else - return __Pyx_PyObject_CallMethod1(sep, __pyx_n_s_join, values); -#endif -} - -/* CIntToPyUnicode */ -static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_size_t(size_t value, Py_ssize_t width, char padding_char, char format_char) { - char digits[sizeof(size_t)*3+2]; - char *dpos, *end = digits + sizeof(size_t)*3+2; - const char *hex_digits = DIGITS_HEX; - Py_ssize_t length, ulength; - int prepend_sign, last_one_off; - size_t remaining; -#ifdef __Pyx_HAS_GCC_DIAGNOSTIC -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wconversion" -#endif - const size_t neg_one = (size_t) -1, const_zero = (size_t) 0; -#ifdef __Pyx_HAS_GCC_DIAGNOSTIC -#pragma GCC diagnostic pop -#endif - const int is_unsigned = neg_one > const_zero; - if (format_char == 'X') { - hex_digits += 16; - format_char = 'x'; - } - remaining = value; - last_one_off = 0; - dpos = end; - do { - int digit_pos; - switch (format_char) { - case 'o': - digit_pos = abs((int)(remaining % (8*8))); - remaining = (size_t) (remaining / (8*8)); - dpos -= 2; - memcpy(dpos, DIGIT_PAIRS_8 + digit_pos * 2, 2); - last_one_off = (digit_pos < 8); - break; - case 'd': - digit_pos = abs((int)(remaining % (10*10))); - remaining = (size_t) (remaining / (10*10)); - dpos -= 2; - memcpy(dpos, DIGIT_PAIRS_10 + digit_pos * 2, 2); - last_one_off = (digit_pos < 10); - break; - case 'x': - *(--dpos) = hex_digits[abs((int)(remaining % 16))]; - remaining = (size_t) (remaining / 16); - break; - default: - assert(0); - break; - } - } while (unlikely(remaining != 0)); - assert(!last_one_off || *dpos == '0'); - dpos += last_one_off; - length = end - dpos; - ulength = length; - prepend_sign = 0; - if (!is_unsigned && value <= neg_one) { - if (padding_char == ' ' || width <= length + 1) { - *(--dpos) = '-'; - ++length; - } else { - prepend_sign = 1; - } - ++ulength; - } - if (width > ulength) { - ulength = width; - } - if (ulength == 1) { - return PyUnicode_FromOrdinal(*dpos); - } - return __Pyx_PyUnicode_BuildFromAscii(ulength, dpos, (int) length, prepend_sign, padding_char); -} - -/* Profile */ -#if CYTHON_PROFILE -static int __Pyx_TraceSetupAndCall(PyCodeObject** code, - PyFrameObject** frame, - PyThreadState* tstate, - const char *funcname, - const char *srcfile, - int firstlineno) { - PyObject *type, *value, *traceback; - int retval; - if (*frame == NULL || !CYTHON_PROFILE_REUSE_FRAME) { - if (*code == NULL) { - *code = __Pyx_createFrameCodeObject(funcname, srcfile, firstlineno); - if (*code == NULL) return 0; - } - *frame = PyFrame_New( - tstate, /*PyThreadState *tstate*/ - *code, /*PyCodeObject *code*/ - __pyx_d, /*PyObject *globals*/ - 0 /*PyObject *locals*/ - ); - if (*frame == NULL) return 0; - if (CYTHON_TRACE && (*frame)->f_trace == NULL) { - Py_INCREF(Py_None); - (*frame)->f_trace = Py_None; - } -#if PY_VERSION_HEX < 0x030400B1 - } else { - (*frame)->f_tstate = tstate; -#endif - } - __Pyx_PyFrame_SetLineNumber(*frame, firstlineno); - retval = 1; - __Pyx_EnterTracing(tstate); - __Pyx_ErrFetchInState(tstate, &type, &value, &traceback); - #if CYTHON_TRACE - if (tstate->c_tracefunc) - retval = tstate->c_tracefunc(tstate->c_traceobj, *frame, PyTrace_CALL, NULL) == 0; - if (retval && tstate->c_profilefunc) - #endif - retval = tstate->c_profilefunc(tstate->c_profileobj, *frame, PyTrace_CALL, NULL) == 0; - __Pyx_LeaveTracing(tstate); - if (retval) { - __Pyx_ErrRestoreInState(tstate, type, value, traceback); - return __Pyx_IsTracing(tstate, 0, 0) && retval; - } else { - Py_XDECREF(type); - Py_XDECREF(value); - Py_XDECREF(traceback); - return -1; - } -} -static PyCodeObject *__Pyx_createFrameCodeObject(const char *funcname, const char *srcfile, int firstlineno) { - PyCodeObject *py_code = 0; -#if PY_MAJOR_VERSION >= 3 - py_code = PyCode_NewEmpty(srcfile, funcname, firstlineno); - if (likely(py_code)) { - py_code->co_flags |= CO_OPTIMIZED | CO_NEWLOCALS; - } -#else - PyObject *py_srcfile = 0; - PyObject *py_funcname = 0; - py_funcname = PyString_FromString(funcname); - if (unlikely(!py_funcname)) goto bad; - py_srcfile = PyString_FromString(srcfile); - if (unlikely(!py_srcfile)) goto bad; - py_code = PyCode_New( - 0, - 0, - 0, - CO_OPTIMIZED | CO_NEWLOCALS, - __pyx_empty_bytes, /*PyObject *code,*/ - __pyx_empty_tuple, /*PyObject *consts,*/ - __pyx_empty_tuple, /*PyObject *names,*/ - __pyx_empty_tuple, /*PyObject *varnames,*/ - __pyx_empty_tuple, /*PyObject *freevars,*/ - __pyx_empty_tuple, /*PyObject *cellvars,*/ - py_srcfile, /*PyObject *filename,*/ - py_funcname, /*PyObject *name,*/ - firstlineno, - __pyx_empty_bytes /*PyObject *lnotab*/ - ); -bad: - Py_XDECREF(py_srcfile); - Py_XDECREF(py_funcname); -#endif - return py_code; -} -#endif - -/* IsLittleEndian */ -static CYTHON_INLINE int __Pyx_Is_Little_Endian(void) -{ - union { - uint32_t u32; - uint8_t u8[4]; - } S; - S.u32 = 0x01020304; - return S.u8[0] == 4; -} - -/* BufferFormatCheck */ -static void __Pyx_BufFmt_Init(__Pyx_BufFmt_Context* ctx, - __Pyx_BufFmt_StackElem* stack, - __Pyx_TypeInfo* type) { - stack[0].field = &ctx->root; - stack[0].parent_offset = 0; - ctx->root.type = type; - ctx->root.name = "buffer dtype"; - ctx->root.offset = 0; - ctx->head = stack; - ctx->head->field = &ctx->root; - ctx->fmt_offset = 0; - ctx->head->parent_offset = 0; - ctx->new_packmode = '@'; - ctx->enc_packmode = '@'; - ctx->new_count = 1; - ctx->enc_count = 0; - ctx->enc_type = 0; - ctx->is_complex = 0; - ctx->is_valid_array = 0; - ctx->struct_alignment = 0; - while (type->typegroup == 'S') { - ++ctx->head; - ctx->head->field = type->fields; - ctx->head->parent_offset = 0; - type = type->fields->type; - } -} -static int __Pyx_BufFmt_ParseNumber(const char** ts) { - int count; - const char* t = *ts; - if (*t < '0' || *t > '9') { - return -1; - } else { - count = *t++ - '0'; - while (*t >= '0' && *t <= '9') { - count *= 10; - count += *t++ - '0'; - } - } - *ts = t; - return count; -} -static int __Pyx_BufFmt_ExpectNumber(const char **ts) { - int number = __Pyx_BufFmt_ParseNumber(ts); - if (number == -1) - PyErr_Format(PyExc_ValueError,\ - "Does not understand character buffer dtype format string ('%c')", **ts); - return number; -} -static void __Pyx_BufFmt_RaiseUnexpectedChar(char ch) { - PyErr_Format(PyExc_ValueError, - "Unexpected format string character: '%c'", ch); -} -static const char* __Pyx_BufFmt_DescribeTypeChar(char ch, int is_complex) { - switch (ch) { - case '?': return "'bool'"; - case 'c': return "'char'"; - case 'b': return "'signed char'"; - case 'B': return "'unsigned char'"; - case 'h': return "'short'"; - case 'H': return "'unsigned short'"; - case 'i': return "'int'"; - case 'I': return "'unsigned int'"; - case 'l': return "'long'"; - case 'L': return "'unsigned long'"; - case 'q': return "'long long'"; - case 'Q': return "'unsigned long long'"; - case 'f': return (is_complex ? "'complex float'" : "'float'"); - case 'd': return (is_complex ? "'complex double'" : "'double'"); - case 'g': return (is_complex ? "'complex long double'" : "'long double'"); - case 'T': return "a struct"; - case 'O': return "Python object"; - case 'P': return "a pointer"; - case 's': case 'p': return "a string"; - case 0: return "end"; - default: return "unparsable format string"; - } -} -static size_t __Pyx_BufFmt_TypeCharToStandardSize(char ch, int is_complex) { - switch (ch) { - case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; - case 'h': case 'H': return 2; - case 'i': case 'I': case 'l': case 'L': return 4; - case 'q': case 'Q': return 8; - case 'f': return (is_complex ? 8 : 4); - case 'd': return (is_complex ? 16 : 8); - case 'g': { - PyErr_SetString(PyExc_ValueError, "Python does not define a standard format string size for long double ('g').."); - return 0; - } - case 'O': case 'P': return sizeof(void*); - default: - __Pyx_BufFmt_RaiseUnexpectedChar(ch); - return 0; - } -} -static size_t __Pyx_BufFmt_TypeCharToNativeSize(char ch, int is_complex) { - switch (ch) { - case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; - case 'h': case 'H': return sizeof(short); - case 'i': case 'I': return sizeof(int); - case 'l': case 'L': return sizeof(long); - #ifdef HAVE_LONG_LONG - case 'q': case 'Q': return sizeof(PY_LONG_LONG); - #endif - case 'f': return sizeof(float) * (is_complex ? 2 : 1); - case 'd': return sizeof(double) * (is_complex ? 2 : 1); - case 'g': return sizeof(long double) * (is_complex ? 2 : 1); - case 'O': case 'P': return sizeof(void*); - default: { - __Pyx_BufFmt_RaiseUnexpectedChar(ch); - return 0; - } - } -} -typedef struct { char c; short x; } __Pyx_st_short; -typedef struct { char c; int x; } __Pyx_st_int; -typedef struct { char c; long x; } __Pyx_st_long; -typedef struct { char c; float x; } __Pyx_st_float; -typedef struct { char c; double x; } __Pyx_st_double; -typedef struct { char c; long double x; } __Pyx_st_longdouble; -typedef struct { char c; void *x; } __Pyx_st_void_p; -#ifdef HAVE_LONG_LONG -typedef struct { char c; PY_LONG_LONG x; } __Pyx_st_longlong; -#endif -static size_t __Pyx_BufFmt_TypeCharToAlignment(char ch, int is_complex) { - CYTHON_UNUSED_VAR(is_complex); - switch (ch) { - case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; - case 'h': case 'H': return sizeof(__Pyx_st_short) - sizeof(short); - case 'i': case 'I': return sizeof(__Pyx_st_int) - sizeof(int); - case 'l': case 'L': return sizeof(__Pyx_st_long) - sizeof(long); -#ifdef HAVE_LONG_LONG - case 'q': case 'Q': return sizeof(__Pyx_st_longlong) - sizeof(PY_LONG_LONG); -#endif - case 'f': return sizeof(__Pyx_st_float) - sizeof(float); - case 'd': return sizeof(__Pyx_st_double) - sizeof(double); - case 'g': return sizeof(__Pyx_st_longdouble) - sizeof(long double); - case 'P': case 'O': return sizeof(__Pyx_st_void_p) - sizeof(void*); - default: - __Pyx_BufFmt_RaiseUnexpectedChar(ch); - return 0; - } -} -/* These are for computing the padding at the end of the struct to align - on the first member of the struct. This will probably the same as above, - but we don't have any guarantees. - */ -typedef struct { short x; char c; } __Pyx_pad_short; -typedef struct { int x; char c; } __Pyx_pad_int; -typedef struct { long x; char c; } __Pyx_pad_long; -typedef struct { float x; char c; } __Pyx_pad_float; -typedef struct { double x; char c; } __Pyx_pad_double; -typedef struct { long double x; char c; } __Pyx_pad_longdouble; -typedef struct { void *x; char c; } __Pyx_pad_void_p; -#ifdef HAVE_LONG_LONG -typedef struct { PY_LONG_LONG x; char c; } __Pyx_pad_longlong; -#endif -static size_t __Pyx_BufFmt_TypeCharToPadding(char ch, int is_complex) { - CYTHON_UNUSED_VAR(is_complex); - switch (ch) { - case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; - case 'h': case 'H': return sizeof(__Pyx_pad_short) - sizeof(short); - case 'i': case 'I': return sizeof(__Pyx_pad_int) - sizeof(int); - case 'l': case 'L': return sizeof(__Pyx_pad_long) - sizeof(long); -#ifdef HAVE_LONG_LONG - case 'q': case 'Q': return sizeof(__Pyx_pad_longlong) - sizeof(PY_LONG_LONG); -#endif - case 'f': return sizeof(__Pyx_pad_float) - sizeof(float); - case 'd': return sizeof(__Pyx_pad_double) - sizeof(double); - case 'g': return sizeof(__Pyx_pad_longdouble) - sizeof(long double); - case 'P': case 'O': return sizeof(__Pyx_pad_void_p) - sizeof(void*); - default: - __Pyx_BufFmt_RaiseUnexpectedChar(ch); - return 0; - } -} -static char __Pyx_BufFmt_TypeCharToGroup(char ch, int is_complex) { - switch (ch) { - case 'c': - return 'H'; - case 'b': case 'h': case 'i': - case 'l': case 'q': case 's': case 'p': - return 'I'; - case '?': case 'B': case 'H': case 'I': case 'L': case 'Q': - return 'U'; - case 'f': case 'd': case 'g': - return (is_complex ? 'C' : 'R'); - case 'O': - return 'O'; - case 'P': - return 'P'; - default: { - __Pyx_BufFmt_RaiseUnexpectedChar(ch); - return 0; - } - } -} -static void __Pyx_BufFmt_RaiseExpected(__Pyx_BufFmt_Context* ctx) { - if (ctx->head == NULL || ctx->head->field == &ctx->root) { - const char* expected; - const char* quote; - if (ctx->head == NULL) { - expected = "end"; - quote = ""; - } else { - expected = ctx->head->field->type->name; - quote = "'"; - } - PyErr_Format(PyExc_ValueError, - "Buffer dtype mismatch, expected %s%s%s but got %s", - quote, expected, quote, - __Pyx_BufFmt_DescribeTypeChar(ctx->enc_type, ctx->is_complex)); - } else { - __Pyx_StructField* field = ctx->head->field; - __Pyx_StructField* parent = (ctx->head - 1)->field; - PyErr_Format(PyExc_ValueError, - "Buffer dtype mismatch, expected '%s' but got %s in '%s.%s'", - field->type->name, __Pyx_BufFmt_DescribeTypeChar(ctx->enc_type, ctx->is_complex), - parent->type->name, field->name); - } -} -static int __Pyx_BufFmt_ProcessTypeChunk(__Pyx_BufFmt_Context* ctx) { - char group; - size_t size, offset, arraysize = 1; - if (ctx->enc_type == 0) return 0; - if (ctx->head->field->type->arraysize[0]) { - int i, ndim = 0; - if (ctx->enc_type == 's' || ctx->enc_type == 'p') { - ctx->is_valid_array = ctx->head->field->type->ndim == 1; - ndim = 1; - if (ctx->enc_count != ctx->head->field->type->arraysize[0]) { - PyErr_Format(PyExc_ValueError, - "Expected a dimension of size %zu, got %zu", - ctx->head->field->type->arraysize[0], ctx->enc_count); - return -1; - } - } - if (!ctx->is_valid_array) { - PyErr_Format(PyExc_ValueError, "Expected %d dimensions, got %d", - ctx->head->field->type->ndim, ndim); - return -1; - } - for (i = 0; i < ctx->head->field->type->ndim; i++) { - arraysize *= ctx->head->field->type->arraysize[i]; - } - ctx->is_valid_array = 0; - ctx->enc_count = 1; - } - group = __Pyx_BufFmt_TypeCharToGroup(ctx->enc_type, ctx->is_complex); - do { - __Pyx_StructField* field = ctx->head->field; - __Pyx_TypeInfo* type = field->type; - if (ctx->enc_packmode == '@' || ctx->enc_packmode == '^') { - size = __Pyx_BufFmt_TypeCharToNativeSize(ctx->enc_type, ctx->is_complex); - } else { - size = __Pyx_BufFmt_TypeCharToStandardSize(ctx->enc_type, ctx->is_complex); - } - if (ctx->enc_packmode == '@') { - size_t align_at = __Pyx_BufFmt_TypeCharToAlignment(ctx->enc_type, ctx->is_complex); - size_t align_mod_offset; - if (align_at == 0) return -1; - align_mod_offset = ctx->fmt_offset % align_at; - if (align_mod_offset > 0) ctx->fmt_offset += align_at - align_mod_offset; - if (ctx->struct_alignment == 0) - ctx->struct_alignment = __Pyx_BufFmt_TypeCharToPadding(ctx->enc_type, - ctx->is_complex); - } - if (type->size != size || type->typegroup != group) { - if (type->typegroup == 'C' && type->fields != NULL) { - size_t parent_offset = ctx->head->parent_offset + field->offset; - ++ctx->head; - ctx->head->field = type->fields; - ctx->head->parent_offset = parent_offset; - continue; - } - if ((type->typegroup == 'H' || group == 'H') && type->size == size) { - } else { - __Pyx_BufFmt_RaiseExpected(ctx); - return -1; - } - } - offset = ctx->head->parent_offset + field->offset; - if (ctx->fmt_offset != offset) { - PyErr_Format(PyExc_ValueError, - "Buffer dtype mismatch; next field is at offset %" CYTHON_FORMAT_SSIZE_T "d but %" CYTHON_FORMAT_SSIZE_T "d expected", - (Py_ssize_t)ctx->fmt_offset, (Py_ssize_t)offset); - return -1; - } - ctx->fmt_offset += size; - if (arraysize) - ctx->fmt_offset += (arraysize - 1) * size; - --ctx->enc_count; - while (1) { - if (field == &ctx->root) { - ctx->head = NULL; - if (ctx->enc_count != 0) { - __Pyx_BufFmt_RaiseExpected(ctx); - return -1; - } - break; - } - ctx->head->field = ++field; - if (field->type == NULL) { - --ctx->head; - field = ctx->head->field; - continue; - } else if (field->type->typegroup == 'S') { - size_t parent_offset = ctx->head->parent_offset + field->offset; - if (field->type->fields->type == NULL) continue; - field = field->type->fields; - ++ctx->head; - ctx->head->field = field; - ctx->head->parent_offset = parent_offset; - break; - } else { - break; - } - } - } while (ctx->enc_count); - ctx->enc_type = 0; - ctx->is_complex = 0; - return 0; -} -static int -__pyx_buffmt_parse_array(__Pyx_BufFmt_Context* ctx, const char** tsp) -{ - const char *ts = *tsp; - int i = 0, number, ndim; - ++ts; - if (ctx->new_count != 1) { - PyErr_SetString(PyExc_ValueError, - "Cannot handle repeated arrays in format string"); - return -1; - } - if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return -1; - ndim = ctx->head->field->type->ndim; - while (*ts && *ts != ')') { - switch (*ts) { - case ' ': case '\f': case '\r': case '\n': case '\t': case '\v': continue; - default: break; - } - number = __Pyx_BufFmt_ExpectNumber(&ts); - if (number == -1) return -1; - if (i < ndim && (size_t) number != ctx->head->field->type->arraysize[i]) { - PyErr_Format(PyExc_ValueError, - "Expected a dimension of size %zu, got %d", - ctx->head->field->type->arraysize[i], number); - return -1; - } - if (*ts != ',' && *ts != ')') { - PyErr_Format(PyExc_ValueError, - "Expected a comma in format string, got '%c'", *ts); - return -1; - } - if (*ts == ',') ts++; - i++; - } - if (i != ndim) { - PyErr_Format(PyExc_ValueError, "Expected %d dimension(s), got %d", - ctx->head->field->type->ndim, i); - return -1; - } - if (!*ts) { - PyErr_SetString(PyExc_ValueError, - "Unexpected end of format string, expected ')'"); - return -1; - } - ctx->is_valid_array = 1; - ctx->new_count = 1; - *tsp = ++ts; - return 0; -} -static const char* __Pyx_BufFmt_CheckString(__Pyx_BufFmt_Context* ctx, const char* ts) { - int got_Z = 0; - while (1) { - switch(*ts) { - case 0: - if (ctx->enc_type != 0 && ctx->head == NULL) { - __Pyx_BufFmt_RaiseExpected(ctx); - return NULL; - } - if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; - if (ctx->head != NULL) { - __Pyx_BufFmt_RaiseExpected(ctx); - return NULL; - } - return ts; - case ' ': - case '\r': - case '\n': - ++ts; - break; - case '<': - if (!__Pyx_Is_Little_Endian()) { - PyErr_SetString(PyExc_ValueError, "Little-endian buffer not supported on big-endian compiler"); - return NULL; - } - ctx->new_packmode = '='; - ++ts; - break; - case '>': - case '!': - if (__Pyx_Is_Little_Endian()) { - PyErr_SetString(PyExc_ValueError, "Big-endian buffer not supported on little-endian compiler"); - return NULL; - } - ctx->new_packmode = '='; - ++ts; - break; - case '=': - case '@': - case '^': - ctx->new_packmode = *ts++; - break; - case 'T': - { - const char* ts_after_sub; - size_t i, struct_count = ctx->new_count; - size_t struct_alignment = ctx->struct_alignment; - ctx->new_count = 1; - ++ts; - if (*ts != '{') { - PyErr_SetString(PyExc_ValueError, "Buffer acquisition: Expected '{' after 'T'"); - return NULL; - } - if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; - ctx->enc_type = 0; - ctx->enc_count = 0; - ctx->struct_alignment = 0; - ++ts; - ts_after_sub = ts; - for (i = 0; i != struct_count; ++i) { - ts_after_sub = __Pyx_BufFmt_CheckString(ctx, ts); - if (!ts_after_sub) return NULL; - } - ts = ts_after_sub; - if (struct_alignment) ctx->struct_alignment = struct_alignment; - } - break; - case '}': - { - size_t alignment = ctx->struct_alignment; - ++ts; - if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; - ctx->enc_type = 0; - if (alignment && ctx->fmt_offset % alignment) { - ctx->fmt_offset += alignment - (ctx->fmt_offset % alignment); - } - } - return ts; - case 'x': - if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; - ctx->fmt_offset += ctx->new_count; - ctx->new_count = 1; - ctx->enc_count = 0; - ctx->enc_type = 0; - ctx->enc_packmode = ctx->new_packmode; - ++ts; - break; - case 'Z': - got_Z = 1; - ++ts; - if (*ts != 'f' && *ts != 'd' && *ts != 'g') { - __Pyx_BufFmt_RaiseUnexpectedChar('Z'); - return NULL; - } - CYTHON_FALLTHROUGH; - case '?': case 'c': case 'b': case 'B': case 'h': case 'H': case 'i': case 'I': - case 'l': case 'L': case 'q': case 'Q': - case 'f': case 'd': case 'g': - case 'O': case 'p': - if ((ctx->enc_type == *ts) && (got_Z == ctx->is_complex) && - (ctx->enc_packmode == ctx->new_packmode) && (!ctx->is_valid_array)) { - ctx->enc_count += ctx->new_count; - ctx->new_count = 1; - got_Z = 0; - ++ts; - break; - } - CYTHON_FALLTHROUGH; - case 's': - if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; - ctx->enc_count = ctx->new_count; - ctx->enc_packmode = ctx->new_packmode; - ctx->enc_type = *ts; - ctx->is_complex = got_Z; - ++ts; - ctx->new_count = 1; - got_Z = 0; - break; - case ':': - ++ts; - while(*ts != ':') ++ts; - ++ts; - break; - case '(': - if (__pyx_buffmt_parse_array(ctx, &ts) < 0) return NULL; - break; - default: - { - int number = __Pyx_BufFmt_ExpectNumber(&ts); - if (number == -1) return NULL; - ctx->new_count = (size_t)number; - } - } - } -} - -/* BufferGetAndValidate */ - static CYTHON_INLINE void __Pyx_SafeReleaseBuffer(Py_buffer* info) { - if (unlikely(info->buf == NULL)) return; - if (info->suboffsets == __Pyx_minusones) info->suboffsets = NULL; - __Pyx_ReleaseBuffer(info); -} -static void __Pyx_ZeroBuffer(Py_buffer* buf) { - buf->buf = NULL; - buf->obj = NULL; - buf->strides = __Pyx_zeros; - buf->shape = __Pyx_zeros; - buf->suboffsets = __Pyx_minusones; -} -static int __Pyx__GetBufferAndValidate( - Py_buffer* buf, PyObject* obj, __Pyx_TypeInfo* dtype, int flags, - int nd, int cast, __Pyx_BufFmt_StackElem* stack) -{ - buf->buf = NULL; - if (unlikely(__Pyx_GetBuffer(obj, buf, flags) == -1)) { - __Pyx_ZeroBuffer(buf); - return -1; - } - if (unlikely(buf->ndim != nd)) { - PyErr_Format(PyExc_ValueError, - "Buffer has wrong number of dimensions (expected %d, got %d)", - nd, buf->ndim); - goto fail; - } - if (!cast) { - __Pyx_BufFmt_Context ctx; - __Pyx_BufFmt_Init(&ctx, stack, dtype); - if (!__Pyx_BufFmt_CheckString(&ctx, buf->format)) goto fail; - } - if (unlikely((size_t)buf->itemsize != dtype->size)) { - PyErr_Format(PyExc_ValueError, - "Item size of buffer (%" CYTHON_FORMAT_SSIZE_T "d byte%s) does not match size of '%s' (%" CYTHON_FORMAT_SSIZE_T "d byte%s)", - buf->itemsize, (buf->itemsize > 1) ? "s" : "", - dtype->name, (Py_ssize_t)dtype->size, (dtype->size > 1) ? "s" : ""); - goto fail; - } - if (buf->suboffsets == NULL) buf->suboffsets = __Pyx_minusones; - return 0; -fail:; - __Pyx_SafeReleaseBuffer(buf); - return -1; -} - -/* BufferFallbackError */ - static void __Pyx_RaiseBufferFallbackError(void) { - PyErr_SetString(PyExc_ValueError, - "Buffer acquisition failed on assignment; and then reacquiring the old buffer failed too!"); -} - -/* PyObjectCallNoArg */ - static CYTHON_INLINE PyObject* __Pyx_PyObject_CallNoArg(PyObject *func) { - PyObject *arg[2] = {NULL, NULL}; - return __Pyx_PyObject_FastCall(func, arg + 1, 0 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); -} - -/* WriteUnraisableException */ - static void __Pyx_WriteUnraisable(const char *name, int clineno, - int lineno, const char *filename, - int full_traceback, int nogil) { - PyObject *old_exc, *old_val, *old_tb; - PyObject *ctx; - __Pyx_PyThreadState_declare -#ifdef WITH_THREAD - PyGILState_STATE state; - if (nogil) - state = PyGILState_Ensure(); - else state = (PyGILState_STATE)0; -#endif - CYTHON_UNUSED_VAR(clineno); - CYTHON_UNUSED_VAR(lineno); - CYTHON_UNUSED_VAR(filename); - CYTHON_MAYBE_UNUSED_VAR(nogil); - __Pyx_PyThreadState_assign - __Pyx_ErrFetch(&old_exc, &old_val, &old_tb); - if (full_traceback) { - Py_XINCREF(old_exc); - Py_XINCREF(old_val); - Py_XINCREF(old_tb); - __Pyx_ErrRestore(old_exc, old_val, old_tb); - PyErr_PrintEx(1); - } - #if PY_MAJOR_VERSION < 3 - ctx = PyString_FromString(name); - #else - ctx = PyUnicode_FromString(name); - #endif - __Pyx_ErrRestore(old_exc, old_val, old_tb); - if (!ctx) { - PyErr_WriteUnraisable(Py_None); - } else { - PyErr_WriteUnraisable(ctx); - Py_DECREF(ctx); - } -#ifdef WITH_THREAD - if (nogil) - PyGILState_Release(state); -#endif -} - -/* PyObject_GenericGetAttrNoDict */ - #if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 -static PyObject *__Pyx_RaiseGenericGetAttributeError(PyTypeObject *tp, PyObject *attr_name) { - __Pyx_TypeName type_name = __Pyx_PyType_GetName(tp); - PyErr_Format(PyExc_AttributeError, -#if PY_MAJOR_VERSION >= 3 - "'" __Pyx_FMT_TYPENAME "' object has no attribute '%U'", - type_name, attr_name); -#else - "'" __Pyx_FMT_TYPENAME "' object has no attribute '%.400s'", - type_name, PyString_AS_STRING(attr_name)); -#endif - __Pyx_DECREF_TypeName(type_name); - return NULL; -} -static CYTHON_INLINE PyObject* __Pyx_PyObject_GenericGetAttrNoDict(PyObject* obj, PyObject* attr_name) { - PyObject *descr; - PyTypeObject *tp = Py_TYPE(obj); - if (unlikely(!PyString_Check(attr_name))) { - return PyObject_GenericGetAttr(obj, attr_name); - } - assert(!tp->tp_dictoffset); - descr = _PyType_Lookup(tp, attr_name); - if (unlikely(!descr)) { - return __Pyx_RaiseGenericGetAttributeError(tp, attr_name); - } - Py_INCREF(descr); - #if PY_MAJOR_VERSION < 3 - if (likely(PyType_HasFeature(Py_TYPE(descr), Py_TPFLAGS_HAVE_CLASS))) - #endif - { - descrgetfunc f = Py_TYPE(descr)->tp_descr_get; - if (unlikely(f)) { - PyObject *res = f(descr, obj, (PyObject *)tp); - Py_DECREF(descr); - return res; - } - } - return descr; -} -#endif - -/* PyObject_GenericGetAttr */ - #if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 -static PyObject* __Pyx_PyObject_GenericGetAttr(PyObject* obj, PyObject* attr_name) { - if (unlikely(Py_TYPE(obj)->tp_dictoffset)) { - return PyObject_GenericGetAttr(obj, attr_name); - } - return __Pyx_PyObject_GenericGetAttrNoDict(obj, attr_name); -} -#endif - -/* FixUpExtensionType */ - #if CYTHON_USE_TYPE_SPECS -static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type) { -#if PY_VERSION_HEX > 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API - CYTHON_UNUSED_VAR(spec); - CYTHON_UNUSED_VAR(type); -#else - const PyType_Slot *slot = spec->slots; - while (slot && slot->slot && slot->slot != Py_tp_members) - slot++; - if (slot && slot->slot == Py_tp_members) { - int changed = 0; -#if !(PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON) - const -#endif - PyMemberDef *memb = (PyMemberDef*) slot->pfunc; - while (memb && memb->name) { - if (memb->name[0] == '_' && memb->name[1] == '_') { -#if PY_VERSION_HEX < 0x030900b1 - if (strcmp(memb->name, "__weaklistoffset__") == 0) { - assert(memb->type == T_PYSSIZET); - assert(memb->flags == READONLY); - type->tp_weaklistoffset = memb->offset; - changed = 1; - } - else if (strcmp(memb->name, "__dictoffset__") == 0) { - assert(memb->type == T_PYSSIZET); - assert(memb->flags == READONLY); - type->tp_dictoffset = memb->offset; - changed = 1; - } -#if CYTHON_METH_FASTCALL - else if (strcmp(memb->name, "__vectorcalloffset__") == 0) { - assert(memb->type == T_PYSSIZET); - assert(memb->flags == READONLY); -#if PY_VERSION_HEX >= 0x030800b4 - type->tp_vectorcall_offset = memb->offset; -#else - type->tp_print = (printfunc) memb->offset; -#endif - changed = 1; - } -#endif -#else - if ((0)); -#endif -#if PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON - else if (strcmp(memb->name, "__module__") == 0) { - PyObject *descr; - assert(memb->type == T_OBJECT); - assert(memb->flags == 0 || memb->flags == READONLY); - descr = PyDescr_NewMember(type, memb); - if (unlikely(!descr)) - return -1; - if (unlikely(PyDict_SetItem(type->tp_dict, PyDescr_NAME(descr), descr) < 0)) { - Py_DECREF(descr); - return -1; - } - Py_DECREF(descr); - changed = 1; - } -#endif - } - memb++; - } - if (changed) - PyType_Modified(type); - } -#endif - return 0; -} -#endif - -/* PyObjectCallMethod0 */ - static PyObject* __Pyx_PyObject_CallMethod0(PyObject* obj, PyObject* method_name) { - PyObject *method = NULL, *result = NULL; - int is_method = __Pyx_PyObject_GetMethod(obj, method_name, &method); - if (likely(is_method)) { - result = __Pyx_PyObject_CallOneArg(method, obj); - Py_DECREF(method); - return result; - } - if (unlikely(!method)) goto bad; - result = __Pyx_PyObject_CallNoArg(method); - Py_DECREF(method); -bad: - return result; -} - -/* ValidateBasesTuple */ - #if CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API || CYTHON_USE_TYPE_SPECS -static int __Pyx_validate_bases_tuple(const char *type_name, Py_ssize_t dictoffset, PyObject *bases) { - Py_ssize_t i, n; -#if CYTHON_ASSUME_SAFE_MACROS - n = PyTuple_GET_SIZE(bases); -#else - n = PyTuple_Size(bases); - if (n < 0) return -1; -#endif - for (i = 1; i < n; i++) - { -#if CYTHON_AVOID_BORROWED_REFS - PyObject *b0 = PySequence_GetItem(bases, i); - if (!b0) return -1; -#elif CYTHON_ASSUME_SAFE_MACROS - PyObject *b0 = PyTuple_GET_ITEM(bases, i); -#else - PyObject *b0 = PyTuple_GetItem(bases, i); - if (!b0) return -1; -#endif - PyTypeObject *b; -#if PY_MAJOR_VERSION < 3 - if (PyClass_Check(b0)) - { - PyErr_Format(PyExc_TypeError, "base class '%.200s' is an old-style class", - PyString_AS_STRING(((PyClassObject*)b0)->cl_name)); -#if CYTHON_AVOID_BORROWED_REFS - Py_DECREF(b0); -#endif - return -1; - } -#endif - b = (PyTypeObject*) b0; - if (!__Pyx_PyType_HasFeature(b, Py_TPFLAGS_HEAPTYPE)) - { - __Pyx_TypeName b_name = __Pyx_PyType_GetName(b); - PyErr_Format(PyExc_TypeError, - "base class '" __Pyx_FMT_TYPENAME "' is not a heap type", b_name); - __Pyx_DECREF_TypeName(b_name); -#if CYTHON_AVOID_BORROWED_REFS - Py_DECREF(b0); -#endif - return -1; - } - if (dictoffset == 0) - { - Py_ssize_t b_dictoffset = 0; -#if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY - b_dictoffset = b->tp_dictoffset; -#else - PyObject *py_b_dictoffset = PyObject_GetAttrString((PyObject*)b, "__dictoffset__"); - if (!py_b_dictoffset) goto dictoffset_return; - b_dictoffset = PyLong_AsSsize_t(py_b_dictoffset); - Py_DECREF(py_b_dictoffset); - if (b_dictoffset == -1 && PyErr_Occurred()) goto dictoffset_return; -#endif - if (b_dictoffset) { - { - __Pyx_TypeName b_name = __Pyx_PyType_GetName(b); - PyErr_Format(PyExc_TypeError, - "extension type '%.200s' has no __dict__ slot, " - "but base type '" __Pyx_FMT_TYPENAME "' has: " - "either add 'cdef dict __dict__' to the extension type " - "or add '__slots__ = [...]' to the base type", - type_name, b_name); - __Pyx_DECREF_TypeName(b_name); - } -#if !(CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY) - dictoffset_return: -#endif -#if CYTHON_AVOID_BORROWED_REFS - Py_DECREF(b0); -#endif - return -1; - } - } -#if CYTHON_AVOID_BORROWED_REFS - Py_DECREF(b0); -#endif - } - return 0; -} -#endif - -/* PyType_Ready */ - static int __Pyx_PyType_Ready(PyTypeObject *t) { -#if CYTHON_USE_TYPE_SPECS || !(CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API) || defined(PYSTON_MAJOR_VERSION) - (void)__Pyx_PyObject_CallMethod0; -#if CYTHON_USE_TYPE_SPECS - (void)__Pyx_validate_bases_tuple; -#endif - return PyType_Ready(t); -#else - int r; - PyObject *bases = __Pyx_PyType_GetSlot(t, tp_bases, PyObject*); - if (bases && unlikely(__Pyx_validate_bases_tuple(t->tp_name, t->tp_dictoffset, bases) == -1)) - return -1; -#if PY_VERSION_HEX >= 0x03050000 && !defined(PYSTON_MAJOR_VERSION) - { - int gc_was_enabled; - #if PY_VERSION_HEX >= 0x030A00b1 - gc_was_enabled = PyGC_Disable(); - (void)__Pyx_PyObject_CallMethod0; - #else - PyObject *ret, *py_status; - PyObject *gc = NULL; - #if PY_VERSION_HEX >= 0x030700a1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM+0 >= 0x07030400) - gc = PyImport_GetModule(__pyx_kp_u_gc); - #endif - if (unlikely(!gc)) gc = PyImport_Import(__pyx_kp_u_gc); - if (unlikely(!gc)) return -1; - py_status = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_isenabled); - if (unlikely(!py_status)) { - Py_DECREF(gc); - return -1; - } - gc_was_enabled = __Pyx_PyObject_IsTrue(py_status); - Py_DECREF(py_status); - if (gc_was_enabled > 0) { - ret = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_disable); - if (unlikely(!ret)) { - Py_DECREF(gc); - return -1; - } - Py_DECREF(ret); - } else if (unlikely(gc_was_enabled == -1)) { - Py_DECREF(gc); - return -1; - } - #endif - t->tp_flags |= Py_TPFLAGS_HEAPTYPE; -#if PY_VERSION_HEX >= 0x030A0000 - t->tp_flags |= Py_TPFLAGS_IMMUTABLETYPE; -#endif -#else - (void)__Pyx_PyObject_CallMethod0; -#endif - r = PyType_Ready(t); -#if PY_VERSION_HEX >= 0x03050000 && !defined(PYSTON_MAJOR_VERSION) - t->tp_flags &= ~Py_TPFLAGS_HEAPTYPE; - #if PY_VERSION_HEX >= 0x030A00b1 - if (gc_was_enabled) - PyGC_Enable(); - #else - if (gc_was_enabled) { - PyObject *tp, *v, *tb; - PyErr_Fetch(&tp, &v, &tb); - ret = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_enable); - if (likely(ret || r == -1)) { - Py_XDECREF(ret); - PyErr_Restore(tp, v, tb); - } else { - Py_XDECREF(tp); - Py_XDECREF(v); - Py_XDECREF(tb); - r = -1; - } - } - Py_DECREF(gc); - #endif - } -#endif - return r; -#endif -} - -/* SetupReduce */ - #if !CYTHON_COMPILING_IN_LIMITED_API -static int __Pyx_setup_reduce_is_named(PyObject* meth, PyObject* name) { - int ret; - PyObject *name_attr; - name_attr = __Pyx_PyObject_GetAttrStrNoError(meth, __pyx_n_s_name_2); - if (likely(name_attr)) { - ret = PyObject_RichCompareBool(name_attr, name, Py_EQ); - } else { - ret = -1; - } - if (unlikely(ret < 0)) { - PyErr_Clear(); - ret = 0; - } - Py_XDECREF(name_attr); - return ret; -} -static int __Pyx_setup_reduce(PyObject* type_obj) { - int ret = 0; - PyObject *object_reduce = NULL; - PyObject *object_getstate = NULL; - PyObject *object_reduce_ex = NULL; - PyObject *reduce = NULL; - PyObject *reduce_ex = NULL; - PyObject *reduce_cython = NULL; - PyObject *setstate = NULL; - PyObject *setstate_cython = NULL; - PyObject *getstate = NULL; -#if CYTHON_USE_PYTYPE_LOOKUP - getstate = _PyType_Lookup((PyTypeObject*)type_obj, __pyx_n_s_getstate); -#else - getstate = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_getstate); - if (!getstate && PyErr_Occurred()) { - goto __PYX_BAD; - } -#endif - if (getstate) { -#if CYTHON_USE_PYTYPE_LOOKUP - object_getstate = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_getstate); -#else - object_getstate = __Pyx_PyObject_GetAttrStrNoError((PyObject*)&PyBaseObject_Type, __pyx_n_s_getstate); - if (!object_getstate && PyErr_Occurred()) { - goto __PYX_BAD; - } -#endif - if (object_getstate != getstate) { - goto __PYX_GOOD; - } - } -#if CYTHON_USE_PYTYPE_LOOKUP - object_reduce_ex = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_reduce_ex); if (!object_reduce_ex) goto __PYX_BAD; -#else - object_reduce_ex = __Pyx_PyObject_GetAttrStr((PyObject*)&PyBaseObject_Type, __pyx_n_s_reduce_ex); if (!object_reduce_ex) goto __PYX_BAD; -#endif - reduce_ex = __Pyx_PyObject_GetAttrStr(type_obj, __pyx_n_s_reduce_ex); if (unlikely(!reduce_ex)) goto __PYX_BAD; - if (reduce_ex == object_reduce_ex) { -#if CYTHON_USE_PYTYPE_LOOKUP - object_reduce = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_reduce); if (!object_reduce) goto __PYX_BAD; -#else - object_reduce = __Pyx_PyObject_GetAttrStr((PyObject*)&PyBaseObject_Type, __pyx_n_s_reduce); if (!object_reduce) goto __PYX_BAD; -#endif - reduce = __Pyx_PyObject_GetAttrStr(type_obj, __pyx_n_s_reduce); if (unlikely(!reduce)) goto __PYX_BAD; - if (reduce == object_reduce || __Pyx_setup_reduce_is_named(reduce, __pyx_n_s_reduce_cython)) { - reduce_cython = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_reduce_cython); - if (likely(reduce_cython)) { - ret = PyDict_SetItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_reduce, reduce_cython); if (unlikely(ret < 0)) goto __PYX_BAD; - ret = PyDict_DelItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_reduce_cython); if (unlikely(ret < 0)) goto __PYX_BAD; - } else if (reduce == object_reduce || PyErr_Occurred()) { - goto __PYX_BAD; - } - setstate = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_setstate); - if (!setstate) PyErr_Clear(); - if (!setstate || __Pyx_setup_reduce_is_named(setstate, __pyx_n_s_setstate_cython)) { - setstate_cython = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_setstate_cython); - if (likely(setstate_cython)) { - ret = PyDict_SetItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_setstate, setstate_cython); if (unlikely(ret < 0)) goto __PYX_BAD; - ret = PyDict_DelItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_setstate_cython); if (unlikely(ret < 0)) goto __PYX_BAD; - } else if (!setstate || PyErr_Occurred()) { - goto __PYX_BAD; - } - } - PyType_Modified((PyTypeObject*)type_obj); - } - } - goto __PYX_GOOD; -__PYX_BAD: - if (!PyErr_Occurred()) { - __Pyx_TypeName type_obj_name = - __Pyx_PyType_GetName((PyTypeObject*)type_obj); - PyErr_Format(PyExc_RuntimeError, - "Unable to initialize pickling for " __Pyx_FMT_TYPENAME, type_obj_name); - __Pyx_DECREF_TypeName(type_obj_name); - } - ret = -1; -__PYX_GOOD: -#if !CYTHON_USE_PYTYPE_LOOKUP - Py_XDECREF(object_reduce); - Py_XDECREF(object_reduce_ex); - Py_XDECREF(object_getstate); - Py_XDECREF(getstate); -#endif - Py_XDECREF(reduce); - Py_XDECREF(reduce_ex); - Py_XDECREF(reduce_cython); - Py_XDECREF(setstate); - Py_XDECREF(setstate_cython); - return ret; -} -#endif - -/* SetVTable */ - static int __Pyx_SetVtable(PyTypeObject *type, void *vtable) { - PyObject *ob = PyCapsule_New(vtable, 0, 0); - if (unlikely(!ob)) - goto bad; -#if CYTHON_COMPILING_IN_LIMITED_API - if (unlikely(PyObject_SetAttr((PyObject *) type, __pyx_n_s_pyx_vtable, ob) < 0)) -#else - if (unlikely(PyDict_SetItem(type->tp_dict, __pyx_n_s_pyx_vtable, ob) < 0)) -#endif - goto bad; - Py_DECREF(ob); - return 0; -bad: - Py_XDECREF(ob); - return -1; -} - -/* GetVTable */ - static void* __Pyx_GetVtable(PyTypeObject *type) { - void* ptr; -#if CYTHON_COMPILING_IN_LIMITED_API - PyObject *ob = PyObject_GetAttr((PyObject *)type, __pyx_n_s_pyx_vtable); -#else - PyObject *ob = PyObject_GetItem(type->tp_dict, __pyx_n_s_pyx_vtable); -#endif - if (!ob) - goto bad; - ptr = PyCapsule_GetPointer(ob, 0); - if (!ptr && !PyErr_Occurred()) - PyErr_SetString(PyExc_RuntimeError, "invalid vtable found for imported type"); - Py_DECREF(ob); - return ptr; -bad: - Py_XDECREF(ob); - return NULL; -} - -/* MergeVTables */ - #if !CYTHON_COMPILING_IN_LIMITED_API -static int __Pyx_MergeVtables(PyTypeObject *type) { - int i; - void** base_vtables; - __Pyx_TypeName tp_base_name; - __Pyx_TypeName base_name; - void* unknown = (void*)-1; - PyObject* bases = type->tp_bases; - int base_depth = 0; - { - PyTypeObject* base = type->tp_base; - while (base) { - base_depth += 1; - base = base->tp_base; - } - } - base_vtables = (void**) malloc(sizeof(void*) * (size_t)(base_depth + 1)); - base_vtables[0] = unknown; - for (i = 1; i < PyTuple_GET_SIZE(bases); i++) { - void* base_vtable = __Pyx_GetVtable(((PyTypeObject*)PyTuple_GET_ITEM(bases, i))); - if (base_vtable != NULL) { - int j; - PyTypeObject* base = type->tp_base; - for (j = 0; j < base_depth; j++) { - if (base_vtables[j] == unknown) { - base_vtables[j] = __Pyx_GetVtable(base); - base_vtables[j + 1] = unknown; - } - if (base_vtables[j] == base_vtable) { - break; - } else if (base_vtables[j] == NULL) { - goto bad; - } - base = base->tp_base; - } - } - } - PyErr_Clear(); - free(base_vtables); - return 0; -bad: - tp_base_name = __Pyx_PyType_GetName(type->tp_base); - base_name = __Pyx_PyType_GetName((PyTypeObject*)PyTuple_GET_ITEM(bases, i)); - PyErr_Format(PyExc_TypeError, - "multiple bases have vtable conflict: '" __Pyx_FMT_TYPENAME "' and '" __Pyx_FMT_TYPENAME "'", tp_base_name, base_name); - __Pyx_DECREF_TypeName(tp_base_name); - __Pyx_DECREF_TypeName(base_name); - free(base_vtables); - return -1; -} -#endif - -/* TypeImport */ - #ifndef __PYX_HAVE_RT_ImportType_3_0_8 -#define __PYX_HAVE_RT_ImportType_3_0_8 -static PyTypeObject *__Pyx_ImportType_3_0_8(PyObject *module, const char *module_name, const char *class_name, - size_t size, size_t alignment, enum __Pyx_ImportType_CheckSize_3_0_8 check_size) -{ - PyObject *result = 0; - char warning[200]; - Py_ssize_t basicsize; - Py_ssize_t itemsize; -#if CYTHON_COMPILING_IN_LIMITED_API - PyObject *py_basicsize; - PyObject *py_itemsize; -#endif - result = PyObject_GetAttrString(module, class_name); - if (!result) - goto bad; - if (!PyType_Check(result)) { - PyErr_Format(PyExc_TypeError, - "%.200s.%.200s is not a type object", - module_name, class_name); - goto bad; - } -#if !CYTHON_COMPILING_IN_LIMITED_API - basicsize = ((PyTypeObject *)result)->tp_basicsize; - itemsize = ((PyTypeObject *)result)->tp_itemsize; -#else - py_basicsize = PyObject_GetAttrString(result, "__basicsize__"); - if (!py_basicsize) - goto bad; - basicsize = PyLong_AsSsize_t(py_basicsize); - Py_DECREF(py_basicsize); - py_basicsize = 0; - if (basicsize == (Py_ssize_t)-1 && PyErr_Occurred()) - goto bad; - py_itemsize = PyObject_GetAttrString(result, "__itemsize__"); - if (!py_itemsize) - goto bad; - itemsize = PyLong_AsSsize_t(py_itemsize); - Py_DECREF(py_itemsize); - py_itemsize = 0; - if (itemsize == (Py_ssize_t)-1 && PyErr_Occurred()) - goto bad; -#endif - if (itemsize) { - if (size % alignment) { - alignment = size % alignment; - } - if (itemsize < (Py_ssize_t)alignment) - itemsize = (Py_ssize_t)alignment; - } - if ((size_t)(basicsize + itemsize) < size) { - PyErr_Format(PyExc_ValueError, - "%.200s.%.200s size changed, may indicate binary incompatibility. " - "Expected %zd from C header, got %zd from PyObject", - module_name, class_name, size, basicsize+itemsize); - goto bad; - } - if (check_size == __Pyx_ImportType_CheckSize_Error_3_0_8 && - ((size_t)basicsize > size || (size_t)(basicsize + itemsize) < size)) { - PyErr_Format(PyExc_ValueError, - "%.200s.%.200s size changed, may indicate binary incompatibility. " - "Expected %zd from C header, got %zd-%zd from PyObject", - module_name, class_name, size, basicsize, basicsize+itemsize); - goto bad; - } - else if (check_size == __Pyx_ImportType_CheckSize_Warn_3_0_8 && (size_t)basicsize > size) { - PyOS_snprintf(warning, sizeof(warning), - "%s.%s size changed, may indicate binary incompatibility. " - "Expected %zd from C header, got %zd from PyObject", - module_name, class_name, size, basicsize); - if (PyErr_WarnEx(NULL, warning, 0) < 0) goto bad; - } - return (PyTypeObject *)result; -bad: - Py_XDECREF(result); - return NULL; -} -#endif - -/* FetchSharedCythonModule */ - static PyObject *__Pyx_FetchSharedCythonABIModule(void) { - return __Pyx_PyImport_AddModuleRef((char*) __PYX_ABI_MODULE_NAME); -} - -/* FetchCommonType */ - static int __Pyx_VerifyCachedType(PyObject *cached_type, - const char *name, - Py_ssize_t basicsize, - Py_ssize_t expected_basicsize) { - if (!PyType_Check(cached_type)) { - PyErr_Format(PyExc_TypeError, - "Shared Cython type %.200s is not a type object", name); - return -1; - } - if (basicsize != expected_basicsize) { - PyErr_Format(PyExc_TypeError, - "Shared Cython type %.200s has the wrong size, try recompiling", - name); - return -1; - } - return 0; -} -#if !CYTHON_USE_TYPE_SPECS -static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type) { - PyObject* abi_module; - const char* object_name; - PyTypeObject *cached_type = NULL; - abi_module = __Pyx_FetchSharedCythonABIModule(); - if (!abi_module) return NULL; - object_name = strrchr(type->tp_name, '.'); - object_name = object_name ? object_name+1 : type->tp_name; - cached_type = (PyTypeObject*) PyObject_GetAttrString(abi_module, object_name); - if (cached_type) { - if (__Pyx_VerifyCachedType( - (PyObject *)cached_type, - object_name, - cached_type->tp_basicsize, - type->tp_basicsize) < 0) { - goto bad; - } - goto done; - } - if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; - PyErr_Clear(); - if (PyType_Ready(type) < 0) goto bad; - if (PyObject_SetAttrString(abi_module, object_name, (PyObject *)type) < 0) - goto bad; - Py_INCREF(type); - cached_type = type; -done: - Py_DECREF(abi_module); - return cached_type; -bad: - Py_XDECREF(cached_type); - cached_type = NULL; - goto done; -} -#else -static PyTypeObject *__Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases) { - PyObject *abi_module, *cached_type = NULL; - const char* object_name = strrchr(spec->name, '.'); - object_name = object_name ? object_name+1 : spec->name; - abi_module = __Pyx_FetchSharedCythonABIModule(); - if (!abi_module) return NULL; - cached_type = PyObject_GetAttrString(abi_module, object_name); - if (cached_type) { - Py_ssize_t basicsize; -#if CYTHON_COMPILING_IN_LIMITED_API - PyObject *py_basicsize; - py_basicsize = PyObject_GetAttrString(cached_type, "__basicsize__"); - if (unlikely(!py_basicsize)) goto bad; - basicsize = PyLong_AsSsize_t(py_basicsize); - Py_DECREF(py_basicsize); - py_basicsize = 0; - if (unlikely(basicsize == (Py_ssize_t)-1) && PyErr_Occurred()) goto bad; -#else - basicsize = likely(PyType_Check(cached_type)) ? ((PyTypeObject*) cached_type)->tp_basicsize : -1; -#endif - if (__Pyx_VerifyCachedType( - cached_type, - object_name, - basicsize, - spec->basicsize) < 0) { - goto bad; - } - goto done; - } - if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; - PyErr_Clear(); - CYTHON_UNUSED_VAR(module); - cached_type = __Pyx_PyType_FromModuleAndSpec(abi_module, spec, bases); - if (unlikely(!cached_type)) goto bad; - if (unlikely(__Pyx_fix_up_extension_type_from_spec(spec, (PyTypeObject *) cached_type) < 0)) goto bad; - if (PyObject_SetAttrString(abi_module, object_name, cached_type) < 0) goto bad; -done: - Py_DECREF(abi_module); - assert(cached_type == NULL || PyType_Check(cached_type)); - return (PyTypeObject *) cached_type; -bad: - Py_XDECREF(cached_type); - cached_type = NULL; - goto done; -} -#endif - -/* PyVectorcallFastCallDict */ - #if CYTHON_METH_FASTCALL -static PyObject *__Pyx_PyVectorcall_FastCallDict_kw(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) -{ - PyObject *res = NULL; - PyObject *kwnames; - PyObject **newargs; - PyObject **kwvalues; - Py_ssize_t i, pos; - size_t j; - PyObject *key, *value; - unsigned long keys_are_strings; - Py_ssize_t nkw = PyDict_GET_SIZE(kw); - newargs = (PyObject **)PyMem_Malloc((nargs + (size_t)nkw) * sizeof(args[0])); - if (unlikely(newargs == NULL)) { - PyErr_NoMemory(); - return NULL; - } - for (j = 0; j < nargs; j++) newargs[j] = args[j]; - kwnames = PyTuple_New(nkw); - if (unlikely(kwnames == NULL)) { - PyMem_Free(newargs); - return NULL; - } - kwvalues = newargs + nargs; - pos = i = 0; - keys_are_strings = Py_TPFLAGS_UNICODE_SUBCLASS; - while (PyDict_Next(kw, &pos, &key, &value)) { - keys_are_strings &= Py_TYPE(key)->tp_flags; - Py_INCREF(key); - Py_INCREF(value); - PyTuple_SET_ITEM(kwnames, i, key); - kwvalues[i] = value; - i++; - } - if (unlikely(!keys_are_strings)) { - PyErr_SetString(PyExc_TypeError, "keywords must be strings"); - goto cleanup; - } - res = vc(func, newargs, nargs, kwnames); -cleanup: - Py_DECREF(kwnames); - for (i = 0; i < nkw; i++) - Py_DECREF(kwvalues[i]); - PyMem_Free(newargs); - return res; -} -static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) -{ - if (likely(kw == NULL) || PyDict_GET_SIZE(kw) == 0) { - return vc(func, args, nargs, NULL); - } - return __Pyx_PyVectorcall_FastCallDict_kw(func, vc, args, nargs, kw); -} -#endif - -/* CythonFunctionShared */ - #if CYTHON_COMPILING_IN_LIMITED_API -static CYTHON_INLINE int __Pyx__IsSameCyOrCFunction(PyObject *func, void *cfunc) { - if (__Pyx_CyFunction_Check(func)) { - return PyCFunction_GetFunction(((__pyx_CyFunctionObject*)func)->func) == (PyCFunction) cfunc; - } else if (PyCFunction_Check(func)) { - return PyCFunction_GetFunction(func) == (PyCFunction) cfunc; - } - return 0; -} -#else -static CYTHON_INLINE int __Pyx__IsSameCyOrCFunction(PyObject *func, void *cfunc) { - return __Pyx_CyOrPyCFunction_Check(func) && __Pyx_CyOrPyCFunction_GET_FUNCTION(func) == (PyCFunction) cfunc; -} -#endif -static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj) { -#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API - __Pyx_Py_XDECREF_SET( - __Pyx_CyFunction_GetClassObj(f), - ((classobj) ? __Pyx_NewRef(classobj) : NULL)); -#else - __Pyx_Py_XDECREF_SET( - ((PyCMethodObject *) (f))->mm_class, - (PyTypeObject*)((classobj) ? __Pyx_NewRef(classobj) : NULL)); -#endif -} -static PyObject * -__Pyx_CyFunction_get_doc(__pyx_CyFunctionObject *op, void *closure) -{ - CYTHON_UNUSED_VAR(closure); - if (unlikely(op->func_doc == NULL)) { -#if CYTHON_COMPILING_IN_LIMITED_API - op->func_doc = PyObject_GetAttrString(op->func, "__doc__"); - if (unlikely(!op->func_doc)) return NULL; -#else - if (((PyCFunctionObject*)op)->m_ml->ml_doc) { -#if PY_MAJOR_VERSION >= 3 - op->func_doc = PyUnicode_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); -#else - op->func_doc = PyString_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); -#endif - if (unlikely(op->func_doc == NULL)) - return NULL; - } else { - Py_INCREF(Py_None); - return Py_None; - } -#endif - } - Py_INCREF(op->func_doc); - return op->func_doc; -} -static int -__Pyx_CyFunction_set_doc(__pyx_CyFunctionObject *op, PyObject *value, void *context) -{ - CYTHON_UNUSED_VAR(context); - if (value == NULL) { - value = Py_None; - } - Py_INCREF(value); - __Pyx_Py_XDECREF_SET(op->func_doc, value); - return 0; -} -static PyObject * -__Pyx_CyFunction_get_name(__pyx_CyFunctionObject *op, void *context) -{ - CYTHON_UNUSED_VAR(context); - if (unlikely(op->func_name == NULL)) { -#if CYTHON_COMPILING_IN_LIMITED_API - op->func_name = PyObject_GetAttrString(op->func, "__name__"); -#elif PY_MAJOR_VERSION >= 3 - op->func_name = PyUnicode_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); -#else - op->func_name = PyString_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); -#endif - if (unlikely(op->func_name == NULL)) - return NULL; - } - Py_INCREF(op->func_name); - return op->func_name; -} -static int -__Pyx_CyFunction_set_name(__pyx_CyFunctionObject *op, PyObject *value, void *context) -{ - CYTHON_UNUSED_VAR(context); -#if PY_MAJOR_VERSION >= 3 - if (unlikely(value == NULL || !PyUnicode_Check(value))) -#else - if (unlikely(value == NULL || !PyString_Check(value))) -#endif - { - PyErr_SetString(PyExc_TypeError, - "__name__ must be set to a string object"); - return -1; - } - Py_INCREF(value); - __Pyx_Py_XDECREF_SET(op->func_name, value); - return 0; -} -static PyObject * -__Pyx_CyFunction_get_qualname(__pyx_CyFunctionObject *op, void *context) -{ - CYTHON_UNUSED_VAR(context); - Py_INCREF(op->func_qualname); - return op->func_qualname; -} -static int -__Pyx_CyFunction_set_qualname(__pyx_CyFunctionObject *op, PyObject *value, void *context) -{ - CYTHON_UNUSED_VAR(context); -#if PY_MAJOR_VERSION >= 3 - if (unlikely(value == NULL || !PyUnicode_Check(value))) -#else - if (unlikely(value == NULL || !PyString_Check(value))) -#endif - { - PyErr_SetString(PyExc_TypeError, - "__qualname__ must be set to a string object"); - return -1; - } - Py_INCREF(value); - __Pyx_Py_XDECREF_SET(op->func_qualname, value); - return 0; -} -static PyObject * -__Pyx_CyFunction_get_dict(__pyx_CyFunctionObject *op, void *context) -{ - CYTHON_UNUSED_VAR(context); - if (unlikely(op->func_dict == NULL)) { - op->func_dict = PyDict_New(); - if (unlikely(op->func_dict == NULL)) - return NULL; - } - Py_INCREF(op->func_dict); - return op->func_dict; -} -static int -__Pyx_CyFunction_set_dict(__pyx_CyFunctionObject *op, PyObject *value, void *context) -{ - CYTHON_UNUSED_VAR(context); - if (unlikely(value == NULL)) { - PyErr_SetString(PyExc_TypeError, - "function's dictionary may not be deleted"); - return -1; - } - if (unlikely(!PyDict_Check(value))) { - PyErr_SetString(PyExc_TypeError, - "setting function's dictionary to a non-dict"); - return -1; - } - Py_INCREF(value); - __Pyx_Py_XDECREF_SET(op->func_dict, value); - return 0; -} -static PyObject * -__Pyx_CyFunction_get_globals(__pyx_CyFunctionObject *op, void *context) -{ - CYTHON_UNUSED_VAR(context); - Py_INCREF(op->func_globals); - return op->func_globals; -} -static PyObject * -__Pyx_CyFunction_get_closure(__pyx_CyFunctionObject *op, void *context) -{ - CYTHON_UNUSED_VAR(op); - CYTHON_UNUSED_VAR(context); - Py_INCREF(Py_None); - return Py_None; -} -static PyObject * -__Pyx_CyFunction_get_code(__pyx_CyFunctionObject *op, void *context) -{ - PyObject* result = (op->func_code) ? op->func_code : Py_None; - CYTHON_UNUSED_VAR(context); - Py_INCREF(result); - return result; -} -static int -__Pyx_CyFunction_init_defaults(__pyx_CyFunctionObject *op) { - int result = 0; - PyObject *res = op->defaults_getter((PyObject *) op); - if (unlikely(!res)) - return -1; - #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS - op->defaults_tuple = PyTuple_GET_ITEM(res, 0); - Py_INCREF(op->defaults_tuple); - op->defaults_kwdict = PyTuple_GET_ITEM(res, 1); - Py_INCREF(op->defaults_kwdict); - #else - op->defaults_tuple = __Pyx_PySequence_ITEM(res, 0); - if (unlikely(!op->defaults_tuple)) result = -1; - else { - op->defaults_kwdict = __Pyx_PySequence_ITEM(res, 1); - if (unlikely(!op->defaults_kwdict)) result = -1; - } - #endif - Py_DECREF(res); - return result; -} -static int -__Pyx_CyFunction_set_defaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { - CYTHON_UNUSED_VAR(context); - if (!value) { - value = Py_None; - } else if (unlikely(value != Py_None && !PyTuple_Check(value))) { - PyErr_SetString(PyExc_TypeError, - "__defaults__ must be set to a tuple object"); - return -1; - } - PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__defaults__ will not " - "currently affect the values used in function calls", 1); - Py_INCREF(value); - __Pyx_Py_XDECREF_SET(op->defaults_tuple, value); - return 0; -} -static PyObject * -__Pyx_CyFunction_get_defaults(__pyx_CyFunctionObject *op, void *context) { - PyObject* result = op->defaults_tuple; - CYTHON_UNUSED_VAR(context); - if (unlikely(!result)) { - if (op->defaults_getter) { - if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; - result = op->defaults_tuple; - } else { - result = Py_None; - } - } - Py_INCREF(result); - return result; -} -static int -__Pyx_CyFunction_set_kwdefaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { - CYTHON_UNUSED_VAR(context); - if (!value) { - value = Py_None; - } else if (unlikely(value != Py_None && !PyDict_Check(value))) { - PyErr_SetString(PyExc_TypeError, - "__kwdefaults__ must be set to a dict object"); - return -1; - } - PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__kwdefaults__ will not " - "currently affect the values used in function calls", 1); - Py_INCREF(value); - __Pyx_Py_XDECREF_SET(op->defaults_kwdict, value); - return 0; -} -static PyObject * -__Pyx_CyFunction_get_kwdefaults(__pyx_CyFunctionObject *op, void *context) { - PyObject* result = op->defaults_kwdict; - CYTHON_UNUSED_VAR(context); - if (unlikely(!result)) { - if (op->defaults_getter) { - if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; - result = op->defaults_kwdict; - } else { - result = Py_None; - } - } - Py_INCREF(result); - return result; -} -static int -__Pyx_CyFunction_set_annotations(__pyx_CyFunctionObject *op, PyObject* value, void *context) { - CYTHON_UNUSED_VAR(context); - if (!value || value == Py_None) { - value = NULL; - } else if (unlikely(!PyDict_Check(value))) { - PyErr_SetString(PyExc_TypeError, - "__annotations__ must be set to a dict object"); - return -1; - } - Py_XINCREF(value); - __Pyx_Py_XDECREF_SET(op->func_annotations, value); - return 0; -} -static PyObject * -__Pyx_CyFunction_get_annotations(__pyx_CyFunctionObject *op, void *context) { - PyObject* result = op->func_annotations; - CYTHON_UNUSED_VAR(context); - if (unlikely(!result)) { - result = PyDict_New(); - if (unlikely(!result)) return NULL; - op->func_annotations = result; - } - Py_INCREF(result); - return result; -} -static PyObject * -__Pyx_CyFunction_get_is_coroutine(__pyx_CyFunctionObject *op, void *context) { - int is_coroutine; - CYTHON_UNUSED_VAR(context); - if (op->func_is_coroutine) { - return __Pyx_NewRef(op->func_is_coroutine); - } - is_coroutine = op->flags & __Pyx_CYFUNCTION_COROUTINE; -#if PY_VERSION_HEX >= 0x03050000 - if (is_coroutine) { - PyObject *module, *fromlist, *marker = __pyx_n_s_is_coroutine; - fromlist = PyList_New(1); - if (unlikely(!fromlist)) return NULL; - Py_INCREF(marker); -#if CYTHON_ASSUME_SAFE_MACROS - PyList_SET_ITEM(fromlist, 0, marker); -#else - if (unlikely(PyList_SetItem(fromlist, 0, marker) < 0)) { - Py_DECREF(marker); - Py_DECREF(fromlist); - return NULL; - } -#endif - module = PyImport_ImportModuleLevelObject(__pyx_n_s_asyncio_coroutines, NULL, NULL, fromlist, 0); - Py_DECREF(fromlist); - if (unlikely(!module)) goto ignore; - op->func_is_coroutine = __Pyx_PyObject_GetAttrStr(module, marker); - Py_DECREF(module); - if (likely(op->func_is_coroutine)) { - return __Pyx_NewRef(op->func_is_coroutine); - } -ignore: - PyErr_Clear(); - } -#endif - op->func_is_coroutine = __Pyx_PyBool_FromLong(is_coroutine); - return __Pyx_NewRef(op->func_is_coroutine); -} -#if CYTHON_COMPILING_IN_LIMITED_API -static PyObject * -__Pyx_CyFunction_get_module(__pyx_CyFunctionObject *op, void *context) { - CYTHON_UNUSED_VAR(context); - return PyObject_GetAttrString(op->func, "__module__"); -} -static int -__Pyx_CyFunction_set_module(__pyx_CyFunctionObject *op, PyObject* value, void *context) { - CYTHON_UNUSED_VAR(context); - return PyObject_SetAttrString(op->func, "__module__", value); -} -#endif -static PyGetSetDef __pyx_CyFunction_getsets[] = { - {(char *) "func_doc", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, - {(char *) "__doc__", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, - {(char *) "func_name", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, - {(char *) "__name__", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, - {(char *) "__qualname__", (getter)__Pyx_CyFunction_get_qualname, (setter)__Pyx_CyFunction_set_qualname, 0, 0}, - {(char *) "func_dict", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, - {(char *) "__dict__", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, - {(char *) "func_globals", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, - {(char *) "__globals__", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, - {(char *) "func_closure", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, - {(char *) "__closure__", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, - {(char *) "func_code", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, - {(char *) "__code__", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, - {(char *) "func_defaults", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, - {(char *) "__defaults__", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, - {(char *) "__kwdefaults__", (getter)__Pyx_CyFunction_get_kwdefaults, (setter)__Pyx_CyFunction_set_kwdefaults, 0, 0}, - {(char *) "__annotations__", (getter)__Pyx_CyFunction_get_annotations, (setter)__Pyx_CyFunction_set_annotations, 0, 0}, - {(char *) "_is_coroutine", (getter)__Pyx_CyFunction_get_is_coroutine, 0, 0, 0}, -#if CYTHON_COMPILING_IN_LIMITED_API - {"__module__", (getter)__Pyx_CyFunction_get_module, (setter)__Pyx_CyFunction_set_module, 0, 0}, -#endif - {0, 0, 0, 0, 0} -}; -static PyMemberDef __pyx_CyFunction_members[] = { -#if !CYTHON_COMPILING_IN_LIMITED_API - {(char *) "__module__", T_OBJECT, offsetof(PyCFunctionObject, m_module), 0, 0}, -#endif -#if CYTHON_USE_TYPE_SPECS - {(char *) "__dictoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_dict), READONLY, 0}, -#if CYTHON_METH_FASTCALL -#if CYTHON_BACKPORT_VECTORCALL - {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_vectorcall), READONLY, 0}, -#else -#if !CYTHON_COMPILING_IN_LIMITED_API - {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(PyCFunctionObject, vectorcall), READONLY, 0}, -#endif -#endif -#endif -#if PY_VERSION_HEX < 0x030500A0 || CYTHON_COMPILING_IN_LIMITED_API - {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_weakreflist), READONLY, 0}, -#else - {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(PyCFunctionObject, m_weakreflist), READONLY, 0}, -#endif -#endif - {0, 0, 0, 0, 0} -}; -static PyObject * -__Pyx_CyFunction_reduce(__pyx_CyFunctionObject *m, PyObject *args) -{ - CYTHON_UNUSED_VAR(args); -#if PY_MAJOR_VERSION >= 3 - Py_INCREF(m->func_qualname); - return m->func_qualname; -#else - return PyString_FromString(((PyCFunctionObject*)m)->m_ml->ml_name); -#endif -} -static PyMethodDef __pyx_CyFunction_methods[] = { - {"__reduce__", (PyCFunction)__Pyx_CyFunction_reduce, METH_VARARGS, 0}, - {0, 0, 0, 0} -}; -#if PY_VERSION_HEX < 0x030500A0 || CYTHON_COMPILING_IN_LIMITED_API -#define __Pyx_CyFunction_weakreflist(cyfunc) ((cyfunc)->func_weakreflist) -#else -#define __Pyx_CyFunction_weakreflist(cyfunc) (((PyCFunctionObject*)cyfunc)->m_weakreflist) -#endif -static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject *op, PyMethodDef *ml, int flags, PyObject* qualname, - PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { -#if !CYTHON_COMPILING_IN_LIMITED_API - PyCFunctionObject *cf = (PyCFunctionObject*) op; -#endif - if (unlikely(op == NULL)) - return NULL; -#if CYTHON_COMPILING_IN_LIMITED_API - op->func = PyCFunction_NewEx(ml, (PyObject*)op, module); - if (unlikely(!op->func)) return NULL; -#endif - op->flags = flags; - __Pyx_CyFunction_weakreflist(op) = NULL; -#if !CYTHON_COMPILING_IN_LIMITED_API - cf->m_ml = ml; - cf->m_self = (PyObject *) op; -#endif - Py_XINCREF(closure); - op->func_closure = closure; -#if !CYTHON_COMPILING_IN_LIMITED_API - Py_XINCREF(module); - cf->m_module = module; -#endif - op->func_dict = NULL; - op->func_name = NULL; - Py_INCREF(qualname); - op->func_qualname = qualname; - op->func_doc = NULL; -#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API - op->func_classobj = NULL; -#else - ((PyCMethodObject*)op)->mm_class = NULL; -#endif - op->func_globals = globals; - Py_INCREF(op->func_globals); - Py_XINCREF(code); - op->func_code = code; - op->defaults_pyobjects = 0; - op->defaults_size = 0; - op->defaults = NULL; - op->defaults_tuple = NULL; - op->defaults_kwdict = NULL; - op->defaults_getter = NULL; - op->func_annotations = NULL; - op->func_is_coroutine = NULL; -#if CYTHON_METH_FASTCALL - switch (ml->ml_flags & (METH_VARARGS | METH_FASTCALL | METH_NOARGS | METH_O | METH_KEYWORDS | METH_METHOD)) { - case METH_NOARGS: - __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_NOARGS; - break; - case METH_O: - __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_O; - break; - case METH_METHOD | METH_FASTCALL | METH_KEYWORDS: - __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD; - break; - case METH_FASTCALL | METH_KEYWORDS: - __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS; - break; - case METH_VARARGS | METH_KEYWORDS: - __Pyx_CyFunction_func_vectorcall(op) = NULL; - break; - default: - PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); - Py_DECREF(op); - return NULL; - } -#endif - return (PyObject *) op; -} -static int -__Pyx_CyFunction_clear(__pyx_CyFunctionObject *m) -{ - Py_CLEAR(m->func_closure); -#if CYTHON_COMPILING_IN_LIMITED_API - Py_CLEAR(m->func); -#else - Py_CLEAR(((PyCFunctionObject*)m)->m_module); -#endif - Py_CLEAR(m->func_dict); - Py_CLEAR(m->func_name); - Py_CLEAR(m->func_qualname); - Py_CLEAR(m->func_doc); - Py_CLEAR(m->func_globals); - Py_CLEAR(m->func_code); -#if !CYTHON_COMPILING_IN_LIMITED_API -#if PY_VERSION_HEX < 0x030900B1 - Py_CLEAR(__Pyx_CyFunction_GetClassObj(m)); -#else - { - PyObject *cls = (PyObject*) ((PyCMethodObject *) (m))->mm_class; - ((PyCMethodObject *) (m))->mm_class = NULL; - Py_XDECREF(cls); - } -#endif -#endif - Py_CLEAR(m->defaults_tuple); - Py_CLEAR(m->defaults_kwdict); - Py_CLEAR(m->func_annotations); - Py_CLEAR(m->func_is_coroutine); - if (m->defaults) { - PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); - int i; - for (i = 0; i < m->defaults_pyobjects; i++) - Py_XDECREF(pydefaults[i]); - PyObject_Free(m->defaults); - m->defaults = NULL; - } - return 0; -} -static void __Pyx__CyFunction_dealloc(__pyx_CyFunctionObject *m) -{ - if (__Pyx_CyFunction_weakreflist(m) != NULL) - PyObject_ClearWeakRefs((PyObject *) m); - __Pyx_CyFunction_clear(m); - __Pyx_PyHeapTypeObject_GC_Del(m); -} -static void __Pyx_CyFunction_dealloc(__pyx_CyFunctionObject *m) -{ - PyObject_GC_UnTrack(m); - __Pyx__CyFunction_dealloc(m); -} -static int __Pyx_CyFunction_traverse(__pyx_CyFunctionObject *m, visitproc visit, void *arg) -{ - Py_VISIT(m->func_closure); -#if CYTHON_COMPILING_IN_LIMITED_API - Py_VISIT(m->func); -#else - Py_VISIT(((PyCFunctionObject*)m)->m_module); -#endif - Py_VISIT(m->func_dict); - Py_VISIT(m->func_name); - Py_VISIT(m->func_qualname); - Py_VISIT(m->func_doc); - Py_VISIT(m->func_globals); - Py_VISIT(m->func_code); -#if !CYTHON_COMPILING_IN_LIMITED_API - Py_VISIT(__Pyx_CyFunction_GetClassObj(m)); -#endif - Py_VISIT(m->defaults_tuple); - Py_VISIT(m->defaults_kwdict); - Py_VISIT(m->func_is_coroutine); - if (m->defaults) { - PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); - int i; - for (i = 0; i < m->defaults_pyobjects; i++) - Py_VISIT(pydefaults[i]); - } - return 0; -} -static PyObject* -__Pyx_CyFunction_repr(__pyx_CyFunctionObject *op) -{ -#if PY_MAJOR_VERSION >= 3 - return PyUnicode_FromFormat("", - op->func_qualname, (void *)op); -#else - return PyString_FromFormat("", - PyString_AsString(op->func_qualname), (void *)op); -#endif -} -static PyObject * __Pyx_CyFunction_CallMethod(PyObject *func, PyObject *self, PyObject *arg, PyObject *kw) { -#if CYTHON_COMPILING_IN_LIMITED_API - PyObject *f = ((__pyx_CyFunctionObject*)func)->func; - PyObject *py_name = NULL; - PyCFunction meth; - int flags; - meth = PyCFunction_GetFunction(f); - if (unlikely(!meth)) return NULL; - flags = PyCFunction_GetFlags(f); - if (unlikely(flags < 0)) return NULL; -#else - PyCFunctionObject* f = (PyCFunctionObject*)func; - PyCFunction meth = f->m_ml->ml_meth; - int flags = f->m_ml->ml_flags; -#endif - Py_ssize_t size; - switch (flags & (METH_VARARGS | METH_KEYWORDS | METH_NOARGS | METH_O)) { - case METH_VARARGS: - if (likely(kw == NULL || PyDict_Size(kw) == 0)) - return (*meth)(self, arg); - break; - case METH_VARARGS | METH_KEYWORDS: - return (*(PyCFunctionWithKeywords)(void*)meth)(self, arg, kw); - case METH_NOARGS: - if (likely(kw == NULL || PyDict_Size(kw) == 0)) { -#if CYTHON_ASSUME_SAFE_MACROS - size = PyTuple_GET_SIZE(arg); -#else - size = PyTuple_Size(arg); - if (unlikely(size < 0)) return NULL; -#endif - if (likely(size == 0)) - return (*meth)(self, NULL); -#if CYTHON_COMPILING_IN_LIMITED_API - py_name = __Pyx_CyFunction_get_name((__pyx_CyFunctionObject*)func, NULL); - if (!py_name) return NULL; - PyErr_Format(PyExc_TypeError, - "%.200S() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", - py_name, size); - Py_DECREF(py_name); -#else - PyErr_Format(PyExc_TypeError, - "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", - f->m_ml->ml_name, size); -#endif - return NULL; - } - break; - case METH_O: - if (likely(kw == NULL || PyDict_Size(kw) == 0)) { -#if CYTHON_ASSUME_SAFE_MACROS - size = PyTuple_GET_SIZE(arg); -#else - size = PyTuple_Size(arg); - if (unlikely(size < 0)) return NULL; -#endif - if (likely(size == 1)) { - PyObject *result, *arg0; - #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS - arg0 = PyTuple_GET_ITEM(arg, 0); - #else - arg0 = __Pyx_PySequence_ITEM(arg, 0); if (unlikely(!arg0)) return NULL; - #endif - result = (*meth)(self, arg0); - #if !(CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS) - Py_DECREF(arg0); - #endif - return result; - } -#if CYTHON_COMPILING_IN_LIMITED_API - py_name = __Pyx_CyFunction_get_name((__pyx_CyFunctionObject*)func, NULL); - if (!py_name) return NULL; - PyErr_Format(PyExc_TypeError, - "%.200S() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", - py_name, size); - Py_DECREF(py_name); -#else - PyErr_Format(PyExc_TypeError, - "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", - f->m_ml->ml_name, size); -#endif - return NULL; - } - break; - default: - PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); - return NULL; - } -#if CYTHON_COMPILING_IN_LIMITED_API - py_name = __Pyx_CyFunction_get_name((__pyx_CyFunctionObject*)func, NULL); - if (!py_name) return NULL; - PyErr_Format(PyExc_TypeError, "%.200S() takes no keyword arguments", - py_name); - Py_DECREF(py_name); -#else - PyErr_Format(PyExc_TypeError, "%.200s() takes no keyword arguments", - f->m_ml->ml_name); -#endif - return NULL; -} -static CYTHON_INLINE PyObject *__Pyx_CyFunction_Call(PyObject *func, PyObject *arg, PyObject *kw) { - PyObject *self, *result; -#if CYTHON_COMPILING_IN_LIMITED_API - self = PyCFunction_GetSelf(((__pyx_CyFunctionObject*)func)->func); - if (unlikely(!self) && PyErr_Occurred()) return NULL; -#else - self = ((PyCFunctionObject*)func)->m_self; -#endif - result = __Pyx_CyFunction_CallMethod(func, self, arg, kw); - return result; -} -static PyObject *__Pyx_CyFunction_CallAsMethod(PyObject *func, PyObject *args, PyObject *kw) { - PyObject *result; - __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *) func; -#if CYTHON_METH_FASTCALL - __pyx_vectorcallfunc vc = __Pyx_CyFunction_func_vectorcall(cyfunc); - if (vc) { -#if CYTHON_ASSUME_SAFE_MACROS - return __Pyx_PyVectorcall_FastCallDict(func, vc, &PyTuple_GET_ITEM(args, 0), (size_t)PyTuple_GET_SIZE(args), kw); -#else - (void) &__Pyx_PyVectorcall_FastCallDict; - return PyVectorcall_Call(func, args, kw); -#endif - } -#endif - if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { - Py_ssize_t argc; - PyObject *new_args; - PyObject *self; -#if CYTHON_ASSUME_SAFE_MACROS - argc = PyTuple_GET_SIZE(args); -#else - argc = PyTuple_Size(args); - if (unlikely(!argc) < 0) return NULL; -#endif - new_args = PyTuple_GetSlice(args, 1, argc); - if (unlikely(!new_args)) - return NULL; - self = PyTuple_GetItem(args, 0); - if (unlikely(!self)) { - Py_DECREF(new_args); -#if PY_MAJOR_VERSION > 2 - PyErr_Format(PyExc_TypeError, - "unbound method %.200S() needs an argument", - cyfunc->func_qualname); -#else - PyErr_SetString(PyExc_TypeError, - "unbound method needs an argument"); -#endif - return NULL; - } - result = __Pyx_CyFunction_CallMethod(func, self, new_args, kw); - Py_DECREF(new_args); - } else { - result = __Pyx_CyFunction_Call(func, args, kw); - } - return result; -} -#if CYTHON_METH_FASTCALL -static CYTHON_INLINE int __Pyx_CyFunction_Vectorcall_CheckArgs(__pyx_CyFunctionObject *cyfunc, Py_ssize_t nargs, PyObject *kwnames) -{ - int ret = 0; - if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { - if (unlikely(nargs < 1)) { - PyErr_Format(PyExc_TypeError, "%.200s() needs an argument", - ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); - return -1; - } - ret = 1; - } - if (unlikely(kwnames) && unlikely(PyTuple_GET_SIZE(kwnames))) { - PyErr_Format(PyExc_TypeError, - "%.200s() takes no keyword arguments", ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); - return -1; - } - return ret; -} -static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) -{ - __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; - PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; -#if CYTHON_BACKPORT_VECTORCALL - Py_ssize_t nargs = (Py_ssize_t)nargsf; -#else - Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); -#endif - PyObject *self; - switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { - case 1: - self = args[0]; - args += 1; - nargs -= 1; - break; - case 0: - self = ((PyCFunctionObject*)cyfunc)->m_self; - break; - default: - return NULL; - } - if (unlikely(nargs != 0)) { - PyErr_Format(PyExc_TypeError, - "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", - def->ml_name, nargs); - return NULL; - } - return def->ml_meth(self, NULL); -} -static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) -{ - __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; - PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; -#if CYTHON_BACKPORT_VECTORCALL - Py_ssize_t nargs = (Py_ssize_t)nargsf; -#else - Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); -#endif - PyObject *self; - switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { - case 1: - self = args[0]; - args += 1; - nargs -= 1; - break; - case 0: - self = ((PyCFunctionObject*)cyfunc)->m_self; - break; - default: - return NULL; - } - if (unlikely(nargs != 1)) { - PyErr_Format(PyExc_TypeError, - "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", - def->ml_name, nargs); - return NULL; - } - return def->ml_meth(self, args[0]); -} -static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) -{ - __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; - PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; -#if CYTHON_BACKPORT_VECTORCALL - Py_ssize_t nargs = (Py_ssize_t)nargsf; -#else - Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); -#endif - PyObject *self; - switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { - case 1: - self = args[0]; - args += 1; - nargs -= 1; - break; - case 0: - self = ((PyCFunctionObject*)cyfunc)->m_self; - break; - default: - return NULL; - } - return ((_PyCFunctionFastWithKeywords)(void(*)(void))def->ml_meth)(self, args, nargs, kwnames); -} -static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) -{ - __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; - PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; - PyTypeObject *cls = (PyTypeObject *) __Pyx_CyFunction_GetClassObj(cyfunc); -#if CYTHON_BACKPORT_VECTORCALL - Py_ssize_t nargs = (Py_ssize_t)nargsf; -#else - Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); -#endif - PyObject *self; - switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { - case 1: - self = args[0]; - args += 1; - nargs -= 1; - break; - case 0: - self = ((PyCFunctionObject*)cyfunc)->m_self; - break; - default: - return NULL; - } - return ((__Pyx_PyCMethod)(void(*)(void))def->ml_meth)(self, cls, args, (size_t)nargs, kwnames); -} -#endif -#if CYTHON_USE_TYPE_SPECS -static PyType_Slot __pyx_CyFunctionType_slots[] = { - {Py_tp_dealloc, (void *)__Pyx_CyFunction_dealloc}, - {Py_tp_repr, (void *)__Pyx_CyFunction_repr}, - {Py_tp_call, (void *)__Pyx_CyFunction_CallAsMethod}, - {Py_tp_traverse, (void *)__Pyx_CyFunction_traverse}, - {Py_tp_clear, (void *)__Pyx_CyFunction_clear}, - {Py_tp_methods, (void *)__pyx_CyFunction_methods}, - {Py_tp_members, (void *)__pyx_CyFunction_members}, - {Py_tp_getset, (void *)__pyx_CyFunction_getsets}, - {Py_tp_descr_get, (void *)__Pyx_PyMethod_New}, - {0, 0}, -}; -static PyType_Spec __pyx_CyFunctionType_spec = { - __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", - sizeof(__pyx_CyFunctionObject), - 0, -#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR - Py_TPFLAGS_METHOD_DESCRIPTOR | -#endif -#if (defined(_Py_TPFLAGS_HAVE_VECTORCALL) && CYTHON_METH_FASTCALL) - _Py_TPFLAGS_HAVE_VECTORCALL | -#endif - Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, - __pyx_CyFunctionType_slots -}; -#else -static PyTypeObject __pyx_CyFunctionType_type = { - PyVarObject_HEAD_INIT(0, 0) - __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", - sizeof(__pyx_CyFunctionObject), - 0, - (destructor) __Pyx_CyFunction_dealloc, -#if !CYTHON_METH_FASTCALL - 0, -#elif CYTHON_BACKPORT_VECTORCALL - (printfunc)offsetof(__pyx_CyFunctionObject, func_vectorcall), -#else - offsetof(PyCFunctionObject, vectorcall), -#endif - 0, - 0, -#if PY_MAJOR_VERSION < 3 - 0, -#else - 0, -#endif - (reprfunc) __Pyx_CyFunction_repr, - 0, - 0, - 0, - 0, - __Pyx_CyFunction_CallAsMethod, - 0, - 0, - 0, - 0, -#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR - Py_TPFLAGS_METHOD_DESCRIPTOR | -#endif -#if defined(_Py_TPFLAGS_HAVE_VECTORCALL) && CYTHON_METH_FASTCALL - _Py_TPFLAGS_HAVE_VECTORCALL | -#endif - Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, - 0, - (traverseproc) __Pyx_CyFunction_traverse, - (inquiry) __Pyx_CyFunction_clear, - 0, -#if PY_VERSION_HEX < 0x030500A0 - offsetof(__pyx_CyFunctionObject, func_weakreflist), -#else - offsetof(PyCFunctionObject, m_weakreflist), -#endif - 0, - 0, - __pyx_CyFunction_methods, - __pyx_CyFunction_members, - __pyx_CyFunction_getsets, - 0, - 0, - __Pyx_PyMethod_New, - 0, - offsetof(__pyx_CyFunctionObject, func_dict), - 0, - 0, - 0, - 0, - 0, - 0, - 0, - 0, - 0, - 0, - 0, - 0, -#if PY_VERSION_HEX >= 0x030400a1 - 0, -#endif -#if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) - 0, -#endif -#if __PYX_NEED_TP_PRINT_SLOT - 0, -#endif -#if PY_VERSION_HEX >= 0x030C0000 - 0, -#endif -#if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 - 0, -#endif -}; -#endif -static int __pyx_CyFunction_init(PyObject *module) { -#if CYTHON_USE_TYPE_SPECS - __pyx_CyFunctionType = __Pyx_FetchCommonTypeFromSpec(module, &__pyx_CyFunctionType_spec, NULL); -#else - CYTHON_UNUSED_VAR(module); - __pyx_CyFunctionType = __Pyx_FetchCommonType(&__pyx_CyFunctionType_type); -#endif - if (unlikely(__pyx_CyFunctionType == NULL)) { - return -1; - } - return 0; -} -static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *func, size_t size, int pyobjects) { - __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; - m->defaults = PyObject_Malloc(size); - if (unlikely(!m->defaults)) - return PyErr_NoMemory(); - memset(m->defaults, 0, size); - m->defaults_pyobjects = pyobjects; - m->defaults_size = size; - return m->defaults; -} -static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *func, PyObject *tuple) { - __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; - m->defaults_tuple = tuple; - Py_INCREF(tuple); -} -static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *func, PyObject *dict) { - __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; - m->defaults_kwdict = dict; - Py_INCREF(dict); -} -static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *func, PyObject *dict) { - __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; - m->func_annotations = dict; - Py_INCREF(dict); -} - -/* CythonFunction */ - static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, int flags, PyObject* qualname, - PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { - PyObject *op = __Pyx_CyFunction_Init( - PyObject_GC_New(__pyx_CyFunctionObject, __pyx_CyFunctionType), - ml, flags, qualname, closure, module, globals, code - ); - if (likely(op)) { - PyObject_GC_Track(op); - } - return op; -} - -/* CLineInTraceback */ - #ifndef CYTHON_CLINE_IN_TRACEBACK -static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line) { - PyObject *use_cline; - PyObject *ptype, *pvalue, *ptraceback; -#if CYTHON_COMPILING_IN_CPYTHON - PyObject **cython_runtime_dict; -#endif - CYTHON_MAYBE_UNUSED_VAR(tstate); - if (unlikely(!__pyx_cython_runtime)) { - return c_line; - } - __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); -#if CYTHON_COMPILING_IN_CPYTHON - cython_runtime_dict = _PyObject_GetDictPtr(__pyx_cython_runtime); - if (likely(cython_runtime_dict)) { - __PYX_PY_DICT_LOOKUP_IF_MODIFIED( - use_cline, *cython_runtime_dict, - __Pyx_PyDict_GetItemStr(*cython_runtime_dict, __pyx_n_s_cline_in_traceback)) - } else -#endif - { - PyObject *use_cline_obj = __Pyx_PyObject_GetAttrStrNoError(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback); - if (use_cline_obj) { - use_cline = PyObject_Not(use_cline_obj) ? Py_False : Py_True; - Py_DECREF(use_cline_obj); - } else { - PyErr_Clear(); - use_cline = NULL; - } - } - if (!use_cline) { - c_line = 0; - (void) PyObject_SetAttr(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback, Py_False); - } - else if (use_cline == Py_False || (use_cline != Py_True && PyObject_Not(use_cline) != 0)) { - c_line = 0; - } - __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); - return c_line; -} -#endif - -/* CodeObjectCache */ - #if !CYTHON_COMPILING_IN_LIMITED_API -static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line) { - int start = 0, mid = 0, end = count - 1; - if (end >= 0 && code_line > entries[end].code_line) { - return count; - } - while (start < end) { - mid = start + (end - start) / 2; - if (code_line < entries[mid].code_line) { - end = mid; - } else if (code_line > entries[mid].code_line) { - start = mid + 1; - } else { - return mid; - } - } - if (code_line <= entries[mid].code_line) { - return mid; - } else { - return mid + 1; - } -} -static PyCodeObject *__pyx_find_code_object(int code_line) { - PyCodeObject* code_object; - int pos; - if (unlikely(!code_line) || unlikely(!__pyx_code_cache.entries)) { - return NULL; - } - pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); - if (unlikely(pos >= __pyx_code_cache.count) || unlikely(__pyx_code_cache.entries[pos].code_line != code_line)) { - return NULL; - } - code_object = __pyx_code_cache.entries[pos].code_object; - Py_INCREF(code_object); - return code_object; -} -static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object) { - int pos, i; - __Pyx_CodeObjectCacheEntry* entries = __pyx_code_cache.entries; - if (unlikely(!code_line)) { - return; - } - if (unlikely(!entries)) { - entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Malloc(64*sizeof(__Pyx_CodeObjectCacheEntry)); - if (likely(entries)) { - __pyx_code_cache.entries = entries; - __pyx_code_cache.max_count = 64; - __pyx_code_cache.count = 1; - entries[0].code_line = code_line; - entries[0].code_object = code_object; - Py_INCREF(code_object); - } - return; - } - pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); - if ((pos < __pyx_code_cache.count) && unlikely(__pyx_code_cache.entries[pos].code_line == code_line)) { - PyCodeObject* tmp = entries[pos].code_object; - entries[pos].code_object = code_object; - Py_DECREF(tmp); - return; - } - if (__pyx_code_cache.count == __pyx_code_cache.max_count) { - int new_max = __pyx_code_cache.max_count + 64; - entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Realloc( - __pyx_code_cache.entries, ((size_t)new_max) * sizeof(__Pyx_CodeObjectCacheEntry)); - if (unlikely(!entries)) { - return; - } - __pyx_code_cache.entries = entries; - __pyx_code_cache.max_count = new_max; - } - for (i=__pyx_code_cache.count; i>pos; i--) { - entries[i] = entries[i-1]; - } - entries[pos].code_line = code_line; - entries[pos].code_object = code_object; - __pyx_code_cache.count++; - Py_INCREF(code_object); -} -#endif - -/* AddTraceback */ - #include "compile.h" -#include "frameobject.h" -#include "traceback.h" -#if PY_VERSION_HEX >= 0x030b00a6 && !CYTHON_COMPILING_IN_LIMITED_API - #ifndef Py_BUILD_CORE - #define Py_BUILD_CORE 1 - #endif - #include "internal/pycore_frame.h" -#endif -#if CYTHON_COMPILING_IN_LIMITED_API -static PyObject *__Pyx_PyCode_Replace_For_AddTraceback(PyObject *code, PyObject *scratch_dict, - PyObject *firstlineno, PyObject *name) { - PyObject *replace = NULL; - if (unlikely(PyDict_SetItemString(scratch_dict, "co_firstlineno", firstlineno))) return NULL; - if (unlikely(PyDict_SetItemString(scratch_dict, "co_name", name))) return NULL; - replace = PyObject_GetAttrString(code, "replace"); - if (likely(replace)) { - PyObject *result; - result = PyObject_Call(replace, __pyx_empty_tuple, scratch_dict); - Py_DECREF(replace); - return result; - } - PyErr_Clear(); - #if __PYX_LIMITED_VERSION_HEX < 0x030780000 - { - PyObject *compiled = NULL, *result = NULL; - if (unlikely(PyDict_SetItemString(scratch_dict, "code", code))) return NULL; - if (unlikely(PyDict_SetItemString(scratch_dict, "type", (PyObject*)(&PyType_Type)))) return NULL; - compiled = Py_CompileString( - "out = type(code)(\n" - " code.co_argcount, code.co_kwonlyargcount, code.co_nlocals, code.co_stacksize,\n" - " code.co_flags, code.co_code, code.co_consts, code.co_names,\n" - " code.co_varnames, code.co_filename, co_name, co_firstlineno,\n" - " code.co_lnotab)\n", "", Py_file_input); - if (!compiled) return NULL; - result = PyEval_EvalCode(compiled, scratch_dict, scratch_dict); - Py_DECREF(compiled); - if (!result) PyErr_Print(); - Py_DECREF(result); - result = PyDict_GetItemString(scratch_dict, "out"); - if (result) Py_INCREF(result); - return result; - } - #else - return NULL; - #endif -} -static void __Pyx_AddTraceback(const char *funcname, int c_line, - int py_line, const char *filename) { - PyObject *code_object = NULL, *py_py_line = NULL, *py_funcname = NULL, *dict = NULL; - PyObject *replace = NULL, *getframe = NULL, *frame = NULL; - PyObject *exc_type, *exc_value, *exc_traceback; - int success = 0; - if (c_line) { - (void) __pyx_cfilenm; - (void) __Pyx_CLineForTraceback(__Pyx_PyThreadState_Current, c_line); - } - PyErr_Fetch(&exc_type, &exc_value, &exc_traceback); - code_object = Py_CompileString("_getframe()", filename, Py_eval_input); - if (unlikely(!code_object)) goto bad; - py_py_line = PyLong_FromLong(py_line); - if (unlikely(!py_py_line)) goto bad; - py_funcname = PyUnicode_FromString(funcname); - if (unlikely(!py_funcname)) goto bad; - dict = PyDict_New(); - if (unlikely(!dict)) goto bad; - { - PyObject *old_code_object = code_object; - code_object = __Pyx_PyCode_Replace_For_AddTraceback(code_object, dict, py_py_line, py_funcname); - Py_DECREF(old_code_object); - } - if (unlikely(!code_object)) goto bad; - getframe = PySys_GetObject("_getframe"); - if (unlikely(!getframe)) goto bad; - if (unlikely(PyDict_SetItemString(dict, "_getframe", getframe))) goto bad; - frame = PyEval_EvalCode(code_object, dict, dict); - if (unlikely(!frame) || frame == Py_None) goto bad; - success = 1; - bad: - PyErr_Restore(exc_type, exc_value, exc_traceback); - Py_XDECREF(code_object); - Py_XDECREF(py_py_line); - Py_XDECREF(py_funcname); - Py_XDECREF(dict); - Py_XDECREF(replace); - if (success) { - PyTraceBack_Here( - (struct _frame*)frame); - } - Py_XDECREF(frame); -} -#else -static PyCodeObject* __Pyx_CreateCodeObjectForTraceback( - const char *funcname, int c_line, - int py_line, const char *filename) { - PyCodeObject *py_code = NULL; - PyObject *py_funcname = NULL; - #if PY_MAJOR_VERSION < 3 - PyObject *py_srcfile = NULL; - py_srcfile = PyString_FromString(filename); - if (!py_srcfile) goto bad; - #endif - if (c_line) { - #if PY_MAJOR_VERSION < 3 - py_funcname = PyString_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); - if (!py_funcname) goto bad; - #else - py_funcname = PyUnicode_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); - if (!py_funcname) goto bad; - funcname = PyUnicode_AsUTF8(py_funcname); - if (!funcname) goto bad; - #endif - } - else { - #if PY_MAJOR_VERSION < 3 - py_funcname = PyString_FromString(funcname); - if (!py_funcname) goto bad; - #endif - } - #if PY_MAJOR_VERSION < 3 - py_code = __Pyx_PyCode_New( - 0, - 0, - 0, - 0, - 0, - 0, - __pyx_empty_bytes, /*PyObject *code,*/ - __pyx_empty_tuple, /*PyObject *consts,*/ - __pyx_empty_tuple, /*PyObject *names,*/ - __pyx_empty_tuple, /*PyObject *varnames,*/ - __pyx_empty_tuple, /*PyObject *freevars,*/ - __pyx_empty_tuple, /*PyObject *cellvars,*/ - py_srcfile, /*PyObject *filename,*/ - py_funcname, /*PyObject *name,*/ - py_line, - __pyx_empty_bytes /*PyObject *lnotab*/ - ); - Py_DECREF(py_srcfile); - #else - py_code = PyCode_NewEmpty(filename, funcname, py_line); - #endif - Py_XDECREF(py_funcname); - return py_code; -bad: - Py_XDECREF(py_funcname); - #if PY_MAJOR_VERSION < 3 - Py_XDECREF(py_srcfile); - #endif - return NULL; -} -static void __Pyx_AddTraceback(const char *funcname, int c_line, - int py_line, const char *filename) { - PyCodeObject *py_code = 0; - PyFrameObject *py_frame = 0; - PyThreadState *tstate = __Pyx_PyThreadState_Current; - PyObject *ptype, *pvalue, *ptraceback; - if (c_line) { - c_line = __Pyx_CLineForTraceback(tstate, c_line); - } - py_code = __pyx_find_code_object(c_line ? -c_line : py_line); - if (!py_code) { - __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); - py_code = __Pyx_CreateCodeObjectForTraceback( - funcname, c_line, py_line, filename); - if (!py_code) { - /* If the code object creation fails, then we should clear the - fetched exception references and propagate the new exception */ - Py_XDECREF(ptype); - Py_XDECREF(pvalue); - Py_XDECREF(ptraceback); - goto bad; - } - __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); - __pyx_insert_code_object(c_line ? -c_line : py_line, py_code); - } - py_frame = PyFrame_New( - tstate, /*PyThreadState *tstate,*/ - py_code, /*PyCodeObject *code,*/ - __pyx_d, /*PyObject *globals,*/ - 0 /*PyObject *locals*/ - ); - if (!py_frame) goto bad; - __Pyx_PyFrame_SetLineNumber(py_frame, py_line); - PyTraceBack_Here(py_frame); -bad: - Py_XDECREF(py_code); - Py_XDECREF(py_frame); -} -#endif - -#if PY_MAJOR_VERSION < 3 -static int __Pyx_GetBuffer(PyObject *obj, Py_buffer *view, int flags) { - __Pyx_TypeName obj_type_name; - if (PyObject_CheckBuffer(obj)) return PyObject_GetBuffer(obj, view, flags); - if (__Pyx_TypeCheck(obj, __pyx_array_type)) return __pyx_array_getbuffer(obj, view, flags); - if (__Pyx_TypeCheck(obj, __pyx_memoryview_type)) return __pyx_memoryview_getbuffer(obj, view, flags); - obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); - PyErr_Format(PyExc_TypeError, - "'" __Pyx_FMT_TYPENAME "' does not have the buffer interface", - obj_type_name); - __Pyx_DECREF_TypeName(obj_type_name); - return -1; -} -static void __Pyx_ReleaseBuffer(Py_buffer *view) { - PyObject *obj = view->obj; - if (!obj) return; - if (PyObject_CheckBuffer(obj)) { - PyBuffer_Release(view); - return; - } - if ((0)) {} - view->obj = NULL; - Py_DECREF(obj); -} -#endif - - - /* MemviewSliceIsContig */ - static int -__pyx_memviewslice_is_contig(const __Pyx_memviewslice mvs, char order, int ndim) -{ - int i, index, step, start; - Py_ssize_t itemsize = mvs.memview->view.itemsize; - if (order == 'F') { - step = 1; - start = 0; - } else { - step = -1; - start = ndim - 1; - } - for (i = 0; i < ndim; i++) { - index = start + step * i; - if (mvs.suboffsets[index] >= 0 || mvs.strides[index] != itemsize) - return 0; - itemsize *= mvs.shape[index]; - } - return 1; -} - -/* OverlappingSlices */ - static void -__pyx_get_array_memory_extents(__Pyx_memviewslice *slice, - void **out_start, void **out_end, - int ndim, size_t itemsize) -{ - char *start, *end; - int i; - start = end = slice->data; - for (i = 0; i < ndim; i++) { - Py_ssize_t stride = slice->strides[i]; - Py_ssize_t extent = slice->shape[i]; - if (extent == 0) { - *out_start = *out_end = start; - return; - } else { - if (stride > 0) - end += stride * (extent - 1); - else - start += stride * (extent - 1); - } - } - *out_start = start; - *out_end = end + itemsize; -} -static int -__pyx_slices_overlap(__Pyx_memviewslice *slice1, - __Pyx_memviewslice *slice2, - int ndim, size_t itemsize) -{ - void *start1, *end1, *start2, *end2; - __pyx_get_array_memory_extents(slice1, &start1, &end1, ndim, itemsize); - __pyx_get_array_memory_extents(slice2, &start2, &end2, ndim, itemsize); - return (start1 < end2) && (start2 < end1); -} - -/* CIntFromPyVerify */ - #define __PYX_VERIFY_RETURN_INT(target_type, func_type, func_value)\ - __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 0) -#define __PYX_VERIFY_RETURN_INT_EXC(target_type, func_type, func_value)\ - __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 1) -#define __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, exc)\ - {\ - func_type value = func_value;\ - if (sizeof(target_type) < sizeof(func_type)) {\ - if (unlikely(value != (func_type) (target_type) value)) {\ - func_type zero = 0;\ - if (exc && unlikely(value == (func_type)-1 && PyErr_Occurred()))\ - return (target_type) -1;\ - if (is_unsigned && unlikely(value < zero))\ - goto raise_neg_overflow;\ - else\ - goto raise_overflow;\ - }\ - }\ - return (target_type) value;\ - } - -/* TypeInfoCompare */ - static int -__pyx_typeinfo_cmp(__Pyx_TypeInfo *a, __Pyx_TypeInfo *b) -{ - int i; - if (!a || !b) - return 0; - if (a == b) - return 1; - if (a->size != b->size || a->typegroup != b->typegroup || - a->is_unsigned != b->is_unsigned || a->ndim != b->ndim) { - if (a->typegroup == 'H' || b->typegroup == 'H') { - return a->size == b->size; - } else { - return 0; - } - } - if (a->ndim) { - for (i = 0; i < a->ndim; i++) - if (a->arraysize[i] != b->arraysize[i]) - return 0; - } - if (a->typegroup == 'S') { - if (a->flags != b->flags) - return 0; - if (a->fields || b->fields) { - if (!(a->fields && b->fields)) - return 0; - for (i = 0; a->fields[i].type && b->fields[i].type; i++) { - __Pyx_StructField *field_a = a->fields + i; - __Pyx_StructField *field_b = b->fields + i; - if (field_a->offset != field_b->offset || - !__pyx_typeinfo_cmp(field_a->type, field_b->type)) - return 0; - } - return !a->fields[i].type && !b->fields[i].type; - } - } - return 1; -} - -/* MemviewSliceValidateAndInit */ - static int -__pyx_check_strides(Py_buffer *buf, int dim, int ndim, int spec) -{ - if (buf->shape[dim] <= 1) - return 1; - if (buf->strides) { - if (spec & __Pyx_MEMVIEW_CONTIG) { - if (spec & (__Pyx_MEMVIEW_PTR|__Pyx_MEMVIEW_FULL)) { - if (unlikely(buf->strides[dim] != sizeof(void *))) { - PyErr_Format(PyExc_ValueError, - "Buffer is not indirectly contiguous " - "in dimension %d.", dim); - goto fail; - } - } else if (unlikely(buf->strides[dim] != buf->itemsize)) { - PyErr_SetString(PyExc_ValueError, - "Buffer and memoryview are not contiguous " - "in the same dimension."); - goto fail; - } - } - if (spec & __Pyx_MEMVIEW_FOLLOW) { - Py_ssize_t stride = buf->strides[dim]; - if (stride < 0) - stride = -stride; - if (unlikely(stride < buf->itemsize)) { - PyErr_SetString(PyExc_ValueError, - "Buffer and memoryview are not contiguous " - "in the same dimension."); - goto fail; - } - } - } else { - if (unlikely(spec & __Pyx_MEMVIEW_CONTIG && dim != ndim - 1)) { - PyErr_Format(PyExc_ValueError, - "C-contiguous buffer is not contiguous in " - "dimension %d", dim); - goto fail; - } else if (unlikely(spec & (__Pyx_MEMVIEW_PTR))) { - PyErr_Format(PyExc_ValueError, - "C-contiguous buffer is not indirect in " - "dimension %d", dim); - goto fail; - } else if (unlikely(buf->suboffsets)) { - PyErr_SetString(PyExc_ValueError, - "Buffer exposes suboffsets but no strides"); - goto fail; - } - } - return 1; -fail: - return 0; -} -static int -__pyx_check_suboffsets(Py_buffer *buf, int dim, int ndim, int spec) -{ - CYTHON_UNUSED_VAR(ndim); - if (spec & __Pyx_MEMVIEW_DIRECT) { - if (unlikely(buf->suboffsets && buf->suboffsets[dim] >= 0)) { - PyErr_Format(PyExc_ValueError, - "Buffer not compatible with direct access " - "in dimension %d.", dim); - goto fail; - } - } - if (spec & __Pyx_MEMVIEW_PTR) { - if (unlikely(!buf->suboffsets || (buf->suboffsets[dim] < 0))) { - PyErr_Format(PyExc_ValueError, - "Buffer is not indirectly accessible " - "in dimension %d.", dim); - goto fail; - } - } - return 1; -fail: - return 0; -} -static int -__pyx_verify_contig(Py_buffer *buf, int ndim, int c_or_f_flag) -{ - int i; - if (c_or_f_flag & __Pyx_IS_F_CONTIG) { - Py_ssize_t stride = 1; - for (i = 0; i < ndim; i++) { - if (unlikely(stride * buf->itemsize != buf->strides[i] && buf->shape[i] > 1)) { - PyErr_SetString(PyExc_ValueError, - "Buffer not fortran contiguous."); - goto fail; - } - stride = stride * buf->shape[i]; - } - } else if (c_or_f_flag & __Pyx_IS_C_CONTIG) { - Py_ssize_t stride = 1; - for (i = ndim - 1; i >- 1; i--) { - if (unlikely(stride * buf->itemsize != buf->strides[i] && buf->shape[i] > 1)) { - PyErr_SetString(PyExc_ValueError, - "Buffer not C contiguous."); - goto fail; - } - stride = stride * buf->shape[i]; - } - } - return 1; -fail: - return 0; -} -static int __Pyx_ValidateAndInit_memviewslice( - int *axes_specs, - int c_or_f_flag, - int buf_flags, - int ndim, - __Pyx_TypeInfo *dtype, - __Pyx_BufFmt_StackElem stack[], - __Pyx_memviewslice *memviewslice, - PyObject *original_obj) -{ - struct __pyx_memoryview_obj *memview, *new_memview; - __Pyx_RefNannyDeclarations - Py_buffer *buf; - int i, spec = 0, retval = -1; - __Pyx_BufFmt_Context ctx; - int from_memoryview = __pyx_memoryview_check(original_obj); - __Pyx_RefNannySetupContext("ValidateAndInit_memviewslice", 0); - if (from_memoryview && __pyx_typeinfo_cmp(dtype, ((struct __pyx_memoryview_obj *) - original_obj)->typeinfo)) { - memview = (struct __pyx_memoryview_obj *) original_obj; - new_memview = NULL; - } else { - memview = (struct __pyx_memoryview_obj *) __pyx_memoryview_new( - original_obj, buf_flags, 0, dtype); - new_memview = memview; - if (unlikely(!memview)) - goto fail; - } - buf = &memview->view; - if (unlikely(buf->ndim != ndim)) { - PyErr_Format(PyExc_ValueError, - "Buffer has wrong number of dimensions (expected %d, got %d)", - ndim, buf->ndim); - goto fail; - } - if (new_memview) { - __Pyx_BufFmt_Init(&ctx, stack, dtype); - if (unlikely(!__Pyx_BufFmt_CheckString(&ctx, buf->format))) goto fail; - } - if (unlikely((unsigned) buf->itemsize != dtype->size)) { - PyErr_Format(PyExc_ValueError, - "Item size of buffer (%" CYTHON_FORMAT_SSIZE_T "u byte%s) " - "does not match size of '%s' (%" CYTHON_FORMAT_SSIZE_T "u byte%s)", - buf->itemsize, - (buf->itemsize > 1) ? "s" : "", - dtype->name, - dtype->size, - (dtype->size > 1) ? "s" : ""); - goto fail; - } - if (buf->len > 0) { - for (i = 0; i < ndim; i++) { - spec = axes_specs[i]; - if (unlikely(!__pyx_check_strides(buf, i, ndim, spec))) - goto fail; - if (unlikely(!__pyx_check_suboffsets(buf, i, ndim, spec))) - goto fail; - } - if (unlikely(buf->strides && !__pyx_verify_contig(buf, ndim, c_or_f_flag))) - goto fail; - } - if (unlikely(__Pyx_init_memviewslice(memview, ndim, memviewslice, - new_memview != NULL) == -1)) { - goto fail; - } - retval = 0; - goto no_fail; -fail: - Py_XDECREF(new_memview); - retval = -1; -no_fail: - __Pyx_RefNannyFinishContext(); - return retval; -} - -/* ObjectToMemviewSlice */ - static CYTHON_INLINE __Pyx_memviewslice __Pyx_PyObject_to_MemoryviewSlice_dsds_double(PyObject *obj, int writable_flag) { - __Pyx_memviewslice result = { 0, 0, { 0 }, { 0 }, { 0 } }; - __Pyx_BufFmt_StackElem stack[1]; - int axes_specs[] = { (__Pyx_MEMVIEW_DIRECT | __Pyx_MEMVIEW_STRIDED), (__Pyx_MEMVIEW_DIRECT | __Pyx_MEMVIEW_STRIDED) }; - int retcode; - if (obj == Py_None) { - result.memview = (struct __pyx_memoryview_obj *) Py_None; - return result; - } - retcode = __Pyx_ValidateAndInit_memviewslice(axes_specs, 0, - PyBUF_RECORDS_RO | writable_flag, 2, - &__Pyx_TypeInfo_double, stack, - &result, obj); - if (unlikely(retcode == -1)) - goto __pyx_fail; - return result; -__pyx_fail: - result.memview = NULL; - result.data = NULL; - return result; -} - -/* MemviewDtypeToObject */ - static CYTHON_INLINE PyObject *__pyx_memview_get_double(const char *itemp) { - return (PyObject *) PyFloat_FromDouble(*(double *) itemp); -} -static CYTHON_INLINE int __pyx_memview_set_double(const char *itemp, PyObject *obj) { - double value = __pyx_PyFloat_AsDouble(obj); - if (unlikely((value == (double)-1) && PyErr_Occurred())) - return 0; - *(double *) itemp = value; - return 1; -} - -/* ObjectToMemviewSlice */ - static CYTHON_INLINE __Pyx_memviewslice __Pyx_PyObject_to_MemoryviewSlice_ds_double(PyObject *obj, int writable_flag) { - __Pyx_memviewslice result = { 0, 0, { 0 }, { 0 }, { 0 } }; - __Pyx_BufFmt_StackElem stack[1]; - int axes_specs[] = { (__Pyx_MEMVIEW_DIRECT | __Pyx_MEMVIEW_STRIDED) }; - int retcode; - if (obj == Py_None) { - result.memview = (struct __pyx_memoryview_obj *) Py_None; - return result; - } - retcode = __Pyx_ValidateAndInit_memviewslice(axes_specs, 0, - PyBUF_RECORDS_RO | writable_flag, 1, - &__Pyx_TypeInfo_double, stack, - &result, obj); - if (unlikely(retcode == -1)) - goto __pyx_fail; - return result; -__pyx_fail: - result.memview = NULL; - result.data = NULL; - return result; -} - -/* Declarations */ - #if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) - #ifdef __cplusplus - static CYTHON_INLINE __pyx_t_float_complex __pyx_t_float_complex_from_parts(float x, float y) { - return ::std::complex< float >(x, y); - } - #else - static CYTHON_INLINE __pyx_t_float_complex __pyx_t_float_complex_from_parts(float x, float y) { - return x + y*(__pyx_t_float_complex)_Complex_I; - } - #endif -#else - static CYTHON_INLINE __pyx_t_float_complex __pyx_t_float_complex_from_parts(float x, float y) { - __pyx_t_float_complex z; - z.real = x; - z.imag = y; - return z; - } -#endif - -/* Arithmetic */ - #if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) -#else - static CYTHON_INLINE int __Pyx_c_eq_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { - return (a.real == b.real) && (a.imag == b.imag); - } - static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_sum_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { - __pyx_t_float_complex z; - z.real = a.real + b.real; - z.imag = a.imag + b.imag; - return z; - } - static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_diff_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { - __pyx_t_float_complex z; - z.real = a.real - b.real; - z.imag = a.imag - b.imag; - return z; - } - static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_prod_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { - __pyx_t_float_complex z; - z.real = a.real * b.real - a.imag * b.imag; - z.imag = a.real * b.imag + a.imag * b.real; - return z; - } - #if 1 - static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_quot_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { - if (b.imag == 0) { - return __pyx_t_float_complex_from_parts(a.real / b.real, a.imag / b.real); - } else if (fabsf(b.real) >= fabsf(b.imag)) { - if (b.real == 0 && b.imag == 0) { - return __pyx_t_float_complex_from_parts(a.real / b.real, a.imag / b.imag); - } else { - float r = b.imag / b.real; - float s = (float)(1.0) / (b.real + b.imag * r); - return __pyx_t_float_complex_from_parts( - (a.real + a.imag * r) * s, (a.imag - a.real * r) * s); - } - } else { - float r = b.real / b.imag; - float s = (float)(1.0) / (b.imag + b.real * r); - return __pyx_t_float_complex_from_parts( - (a.real * r + a.imag) * s, (a.imag * r - a.real) * s); - } - } - #else - static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_quot_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { - if (b.imag == 0) { - return __pyx_t_float_complex_from_parts(a.real / b.real, a.imag / b.real); - } else { - float denom = b.real * b.real + b.imag * b.imag; - return __pyx_t_float_complex_from_parts( - (a.real * b.real + a.imag * b.imag) / denom, - (a.imag * b.real - a.real * b.imag) / denom); - } - } - #endif - static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_neg_float(__pyx_t_float_complex a) { - __pyx_t_float_complex z; - z.real = -a.real; - z.imag = -a.imag; - return z; - } - static CYTHON_INLINE int __Pyx_c_is_zero_float(__pyx_t_float_complex a) { - return (a.real == 0) && (a.imag == 0); - } - static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_conj_float(__pyx_t_float_complex a) { - __pyx_t_float_complex z; - z.real = a.real; - z.imag = -a.imag; - return z; - } - #if 1 - static CYTHON_INLINE float __Pyx_c_abs_float(__pyx_t_float_complex z) { - #if !defined(HAVE_HYPOT) || defined(_MSC_VER) - return sqrtf(z.real*z.real + z.imag*z.imag); - #else - return hypotf(z.real, z.imag); - #endif - } - static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_pow_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { - __pyx_t_float_complex z; - float r, lnr, theta, z_r, z_theta; - if (b.imag == 0 && b.real == (int)b.real) { - if (b.real < 0) { - float denom = a.real * a.real + a.imag * a.imag; - a.real = a.real / denom; - a.imag = -a.imag / denom; - b.real = -b.real; - } - switch ((int)b.real) { - case 0: - z.real = 1; - z.imag = 0; - return z; - case 1: - return a; - case 2: - return __Pyx_c_prod_float(a, a); - case 3: - z = __Pyx_c_prod_float(a, a); - return __Pyx_c_prod_float(z, a); - case 4: - z = __Pyx_c_prod_float(a, a); - return __Pyx_c_prod_float(z, z); - } - } - if (a.imag == 0) { - if (a.real == 0) { - return a; - } else if ((b.imag == 0) && (a.real >= 0)) { - z.real = powf(a.real, b.real); - z.imag = 0; - return z; - } else if (a.real > 0) { - r = a.real; - theta = 0; - } else { - r = -a.real; - theta = atan2f(0.0, -1.0); - } - } else { - r = __Pyx_c_abs_float(a); - theta = atan2f(a.imag, a.real); - } - lnr = logf(r); - z_r = expf(lnr * b.real - theta * b.imag); - z_theta = theta * b.real + lnr * b.imag; - z.real = z_r * cosf(z_theta); - z.imag = z_r * sinf(z_theta); - return z; - } - #endif -#endif - -/* Declarations */ - #if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) - #ifdef __cplusplus - static CYTHON_INLINE __pyx_t_double_complex __pyx_t_double_complex_from_parts(double x, double y) { - return ::std::complex< double >(x, y); - } - #else - static CYTHON_INLINE __pyx_t_double_complex __pyx_t_double_complex_from_parts(double x, double y) { - return x + y*(__pyx_t_double_complex)_Complex_I; - } - #endif -#else - static CYTHON_INLINE __pyx_t_double_complex __pyx_t_double_complex_from_parts(double x, double y) { - __pyx_t_double_complex z; - z.real = x; - z.imag = y; - return z; - } -#endif - -/* Arithmetic */ - #if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) -#else - static CYTHON_INLINE int __Pyx_c_eq_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { - return (a.real == b.real) && (a.imag == b.imag); - } - static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_sum_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { - __pyx_t_double_complex z; - z.real = a.real + b.real; - z.imag = a.imag + b.imag; - return z; - } - static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_diff_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { - __pyx_t_double_complex z; - z.real = a.real - b.real; - z.imag = a.imag - b.imag; - return z; - } - static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_prod_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { - __pyx_t_double_complex z; - z.real = a.real * b.real - a.imag * b.imag; - z.imag = a.real * b.imag + a.imag * b.real; - return z; - } - #if 1 - static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_quot_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { - if (b.imag == 0) { - return __pyx_t_double_complex_from_parts(a.real / b.real, a.imag / b.real); - } else if (fabs(b.real) >= fabs(b.imag)) { - if (b.real == 0 && b.imag == 0) { - return __pyx_t_double_complex_from_parts(a.real / b.real, a.imag / b.imag); - } else { - double r = b.imag / b.real; - double s = (double)(1.0) / (b.real + b.imag * r); - return __pyx_t_double_complex_from_parts( - (a.real + a.imag * r) * s, (a.imag - a.real * r) * s); - } - } else { - double r = b.real / b.imag; - double s = (double)(1.0) / (b.imag + b.real * r); - return __pyx_t_double_complex_from_parts( - (a.real * r + a.imag) * s, (a.imag * r - a.real) * s); - } - } - #else - static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_quot_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { - if (b.imag == 0) { - return __pyx_t_double_complex_from_parts(a.real / b.real, a.imag / b.real); - } else { - double denom = b.real * b.real + b.imag * b.imag; - return __pyx_t_double_complex_from_parts( - (a.real * b.real + a.imag * b.imag) / denom, - (a.imag * b.real - a.real * b.imag) / denom); - } - } - #endif - static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_neg_double(__pyx_t_double_complex a) { - __pyx_t_double_complex z; - z.real = -a.real; - z.imag = -a.imag; - return z; - } - static CYTHON_INLINE int __Pyx_c_is_zero_double(__pyx_t_double_complex a) { - return (a.real == 0) && (a.imag == 0); - } - static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_conj_double(__pyx_t_double_complex a) { - __pyx_t_double_complex z; - z.real = a.real; - z.imag = -a.imag; - return z; - } - #if 1 - static CYTHON_INLINE double __Pyx_c_abs_double(__pyx_t_double_complex z) { - #if !defined(HAVE_HYPOT) || defined(_MSC_VER) - return sqrt(z.real*z.real + z.imag*z.imag); - #else - return hypot(z.real, z.imag); - #endif - } - static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_pow_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { - __pyx_t_double_complex z; - double r, lnr, theta, z_r, z_theta; - if (b.imag == 0 && b.real == (int)b.real) { - if (b.real < 0) { - double denom = a.real * a.real + a.imag * a.imag; - a.real = a.real / denom; - a.imag = -a.imag / denom; - b.real = -b.real; - } - switch ((int)b.real) { - case 0: - z.real = 1; - z.imag = 0; - return z; - case 1: - return a; - case 2: - return __Pyx_c_prod_double(a, a); - case 3: - z = __Pyx_c_prod_double(a, a); - return __Pyx_c_prod_double(z, a); - case 4: - z = __Pyx_c_prod_double(a, a); - return __Pyx_c_prod_double(z, z); - } - } - if (a.imag == 0) { - if (a.real == 0) { - return a; - } else if ((b.imag == 0) && (a.real >= 0)) { - z.real = pow(a.real, b.real); - z.imag = 0; - return z; - } else if (a.real > 0) { - r = a.real; - theta = 0; - } else { - r = -a.real; - theta = atan2(0.0, -1.0); - } - } else { - r = __Pyx_c_abs_double(a); - theta = atan2(a.imag, a.real); - } - lnr = log(r); - z_r = exp(lnr * b.real - theta * b.imag); - z_theta = theta * b.real + lnr * b.imag; - z.real = z_r * cos(z_theta); - z.imag = z_r * sin(z_theta); - return z; - } - #endif -#endif - -/* MemviewSliceCopyTemplate */ - static __Pyx_memviewslice -__pyx_memoryview_copy_new_contig(const __Pyx_memviewslice *from_mvs, - const char *mode, int ndim, - size_t sizeof_dtype, int contig_flag, - int dtype_is_object) -{ - __Pyx_RefNannyDeclarations - int i; - __Pyx_memviewslice new_mvs = { 0, 0, { 0 }, { 0 }, { 0 } }; - struct __pyx_memoryview_obj *from_memview = from_mvs->memview; - Py_buffer *buf = &from_memview->view; - PyObject *shape_tuple = NULL; - PyObject *temp_int = NULL; - struct __pyx_array_obj *array_obj = NULL; - struct __pyx_memoryview_obj *memview_obj = NULL; - __Pyx_RefNannySetupContext("__pyx_memoryview_copy_new_contig", 0); - for (i = 0; i < ndim; i++) { - if (unlikely(from_mvs->suboffsets[i] >= 0)) { - PyErr_Format(PyExc_ValueError, "Cannot copy memoryview slice with " - "indirect dimensions (axis %d)", i); - goto fail; - } - } - shape_tuple = PyTuple_New(ndim); - if (unlikely(!shape_tuple)) { - goto fail; - } - __Pyx_GOTREF(shape_tuple); - for(i = 0; i < ndim; i++) { - temp_int = PyInt_FromSsize_t(from_mvs->shape[i]); - if(unlikely(!temp_int)) { - goto fail; - } else { - PyTuple_SET_ITEM(shape_tuple, i, temp_int); - temp_int = NULL; - } - } - array_obj = __pyx_array_new(shape_tuple, sizeof_dtype, buf->format, (char *) mode, NULL); - if (unlikely(!array_obj)) { - goto fail; - } - __Pyx_GOTREF(array_obj); - memview_obj = (struct __pyx_memoryview_obj *) __pyx_memoryview_new( - (PyObject *) array_obj, contig_flag, - dtype_is_object, - from_mvs->memview->typeinfo); - if (unlikely(!memview_obj)) - goto fail; - if (unlikely(__Pyx_init_memviewslice(memview_obj, ndim, &new_mvs, 1) < 0)) - goto fail; - if (unlikely(__pyx_memoryview_copy_contents(*from_mvs, new_mvs, ndim, ndim, - dtype_is_object) < 0)) - goto fail; - goto no_fail; -fail: - __Pyx_XDECREF(new_mvs.memview); - new_mvs.memview = NULL; - new_mvs.data = NULL; -no_fail: - __Pyx_XDECREF(shape_tuple); - __Pyx_XDECREF(temp_int); - __Pyx_XDECREF(array_obj); - __Pyx_RefNannyFinishContext(); - return new_mvs; -} - -/* MemviewSliceInit */ - static int -__Pyx_init_memviewslice(struct __pyx_memoryview_obj *memview, - int ndim, - __Pyx_memviewslice *memviewslice, - int memview_is_new_reference) -{ - __Pyx_RefNannyDeclarations - int i, retval=-1; - Py_buffer *buf = &memview->view; - __Pyx_RefNannySetupContext("init_memviewslice", 0); - if (unlikely(memviewslice->memview || memviewslice->data)) { - PyErr_SetString(PyExc_ValueError, - "memviewslice is already initialized!"); - goto fail; - } - if (buf->strides) { - for (i = 0; i < ndim; i++) { - memviewslice->strides[i] = buf->strides[i]; - } - } else { - Py_ssize_t stride = buf->itemsize; - for (i = ndim - 1; i >= 0; i--) { - memviewslice->strides[i] = stride; - stride *= buf->shape[i]; - } - } - for (i = 0; i < ndim; i++) { - memviewslice->shape[i] = buf->shape[i]; - if (buf->suboffsets) { - memviewslice->suboffsets[i] = buf->suboffsets[i]; - } else { - memviewslice->suboffsets[i] = -1; - } - } - memviewslice->memview = memview; - memviewslice->data = (char *)buf->buf; - if (__pyx_add_acquisition_count(memview) == 0 && !memview_is_new_reference) { - Py_INCREF(memview); - } - retval = 0; - goto no_fail; -fail: - memviewslice->memview = 0; - memviewslice->data = 0; - retval = -1; -no_fail: - __Pyx_RefNannyFinishContext(); - return retval; -} -#ifndef Py_NO_RETURN -#define Py_NO_RETURN -#endif -static void __pyx_fatalerror(const char *fmt, ...) Py_NO_RETURN { - va_list vargs; - char msg[200]; -#if PY_VERSION_HEX >= 0x030A0000 || defined(HAVE_STDARG_PROTOTYPES) - va_start(vargs, fmt); -#else - va_start(vargs); -#endif - vsnprintf(msg, 200, fmt, vargs); - va_end(vargs); - Py_FatalError(msg); -} -static CYTHON_INLINE int -__pyx_add_acquisition_count_locked(__pyx_atomic_int_type *acquisition_count, - PyThread_type_lock lock) -{ - int result; - PyThread_acquire_lock(lock, 1); - result = (*acquisition_count)++; - PyThread_release_lock(lock); - return result; -} -static CYTHON_INLINE int -__pyx_sub_acquisition_count_locked(__pyx_atomic_int_type *acquisition_count, - PyThread_type_lock lock) -{ - int result; - PyThread_acquire_lock(lock, 1); - result = (*acquisition_count)--; - PyThread_release_lock(lock); - return result; -} -static CYTHON_INLINE void -__Pyx_INC_MEMVIEW(__Pyx_memviewslice *memslice, int have_gil, int lineno) -{ - __pyx_nonatomic_int_type old_acquisition_count; - struct __pyx_memoryview_obj *memview = memslice->memview; - if (unlikely(!memview || (PyObject *) memview == Py_None)) { - return; - } - old_acquisition_count = __pyx_add_acquisition_count(memview); - if (unlikely(old_acquisition_count <= 0)) { - if (likely(old_acquisition_count == 0)) { - if (have_gil) { - Py_INCREF((PyObject *) memview); - } else { - PyGILState_STATE _gilstate = PyGILState_Ensure(); - Py_INCREF((PyObject *) memview); - PyGILState_Release(_gilstate); - } - } else { - __pyx_fatalerror("Acquisition count is %d (line %d)", - old_acquisition_count+1, lineno); - } - } -} -static CYTHON_INLINE void __Pyx_XCLEAR_MEMVIEW(__Pyx_memviewslice *memslice, - int have_gil, int lineno) { - __pyx_nonatomic_int_type old_acquisition_count; - struct __pyx_memoryview_obj *memview = memslice->memview; - if (unlikely(!memview || (PyObject *) memview == Py_None)) { - memslice->memview = NULL; - return; - } - old_acquisition_count = __pyx_sub_acquisition_count(memview); - memslice->data = NULL; - if (likely(old_acquisition_count > 1)) { - memslice->memview = NULL; - } else if (likely(old_acquisition_count == 1)) { - if (have_gil) { - Py_CLEAR(memslice->memview); - } else { - PyGILState_STATE _gilstate = PyGILState_Ensure(); - Py_CLEAR(memslice->memview); - PyGILState_Release(_gilstate); - } - } else { - __pyx_fatalerror("Acquisition count is %d (line %d)", - old_acquisition_count-1, lineno); - } -} - -/* TypeInfoToFormat */ - static struct __pyx_typeinfo_string __Pyx_TypeInfoToFormat(__Pyx_TypeInfo *type) { - struct __pyx_typeinfo_string result = { {0} }; - char *buf = (char *) result.string; - size_t size = type->size; - switch (type->typegroup) { - case 'H': - *buf = 'c'; - break; - case 'I': - case 'U': - if (size == 1) - *buf = (type->is_unsigned) ? 'B' : 'b'; - else if (size == 2) - *buf = (type->is_unsigned) ? 'H' : 'h'; - else if (size == 4) - *buf = (type->is_unsigned) ? 'I' : 'i'; - else if (size == 8) - *buf = (type->is_unsigned) ? 'Q' : 'q'; - break; - case 'P': - *buf = 'P'; - break; - case 'C': - { - __Pyx_TypeInfo complex_type = *type; - complex_type.typegroup = 'R'; - complex_type.size /= 2; - *buf++ = 'Z'; - *buf = __Pyx_TypeInfoToFormat(&complex_type).string[0]; - break; - } - case 'R': - if (size == 4) - *buf = 'f'; - else if (size == 8) - *buf = 'd'; - else - *buf = 'g'; - break; - } - return result; -} - -/* CIntFromPy */ - static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *x) { -#ifdef __Pyx_HAS_GCC_DIAGNOSTIC -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wconversion" -#endif - const int neg_one = (int) -1, const_zero = (int) 0; -#ifdef __Pyx_HAS_GCC_DIAGNOSTIC -#pragma GCC diagnostic pop -#endif - const int is_unsigned = neg_one > const_zero; -#if PY_MAJOR_VERSION < 3 - if (likely(PyInt_Check(x))) { - if ((sizeof(int) < sizeof(long))) { - __PYX_VERIFY_RETURN_INT(int, long, PyInt_AS_LONG(x)) - } else { - long val = PyInt_AS_LONG(x); - if (is_unsigned && unlikely(val < 0)) { - goto raise_neg_overflow; - } - return (int) val; - } - } else -#endif - if (likely(PyLong_Check(x))) { - if (is_unsigned) { -#if CYTHON_USE_PYLONG_INTERNALS - if (unlikely(__Pyx_PyLong_IsNeg(x))) { - goto raise_neg_overflow; - } else if (__Pyx_PyLong_IsCompact(x)) { - __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) - } else { - const digit* digits = __Pyx_PyLong_Digits(x); - assert(__Pyx_PyLong_DigitCount(x) > 1); - switch (__Pyx_PyLong_DigitCount(x)) { - case 2: - if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { - if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { - __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) - } else if ((8 * sizeof(int) >= 2 * PyLong_SHIFT)) { - return (int) (((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); - } - } - break; - case 3: - if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { - if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { - __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) - } else if ((8 * sizeof(int) >= 3 * PyLong_SHIFT)) { - return (int) (((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); - } - } - break; - case 4: - if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { - if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { - __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) - } else if ((8 * sizeof(int) >= 4 * PyLong_SHIFT)) { - return (int) (((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); - } - } - break; - } - } -#endif -#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 - if (unlikely(Py_SIZE(x) < 0)) { - goto raise_neg_overflow; - } -#else - { - int result = PyObject_RichCompareBool(x, Py_False, Py_LT); - if (unlikely(result < 0)) - return (int) -1; - if (unlikely(result == 1)) - goto raise_neg_overflow; - } -#endif - if ((sizeof(int) <= sizeof(unsigned long))) { - __PYX_VERIFY_RETURN_INT_EXC(int, unsigned long, PyLong_AsUnsignedLong(x)) -#ifdef HAVE_LONG_LONG - } else if ((sizeof(int) <= sizeof(unsigned PY_LONG_LONG))) { - __PYX_VERIFY_RETURN_INT_EXC(int, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) -#endif - } - } else { -#if CYTHON_USE_PYLONG_INTERNALS - if (__Pyx_PyLong_IsCompact(x)) { - __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) - } else { - const digit* digits = __Pyx_PyLong_Digits(x); - assert(__Pyx_PyLong_DigitCount(x) > 1); - switch (__Pyx_PyLong_SignedDigitCount(x)) { - case -2: - if ((8 * sizeof(int) - 1 > 1 * PyLong_SHIFT)) { - if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { - __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) - } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { - return (int) (((int)-1)*(((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); - } - } - break; - case 2: - if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { - if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { - __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) - } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { - return (int) ((((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); - } - } - break; - case -3: - if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { - if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { - __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) - } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { - return (int) (((int)-1)*(((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); - } - } - break; - case 3: - if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { - if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { - __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) - } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { - return (int) ((((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); - } - } - break; - case -4: - if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { - if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { - __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) - } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { - return (int) (((int)-1)*(((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); - } - } - break; - case 4: - if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { - if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { - __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) - } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { - return (int) ((((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); - } - } - break; - } - } -#endif - if ((sizeof(int) <= sizeof(long))) { - __PYX_VERIFY_RETURN_INT_EXC(int, long, PyLong_AsLong(x)) -#ifdef HAVE_LONG_LONG - } else if ((sizeof(int) <= sizeof(PY_LONG_LONG))) { - __PYX_VERIFY_RETURN_INT_EXC(int, PY_LONG_LONG, PyLong_AsLongLong(x)) -#endif - } - } - { - int val; - PyObject *v = __Pyx_PyNumber_IntOrLong(x); -#if PY_MAJOR_VERSION < 3 - if (likely(v) && !PyLong_Check(v)) { - PyObject *tmp = v; - v = PyNumber_Long(tmp); - Py_DECREF(tmp); - } -#endif - if (likely(v)) { - int ret = -1; -#if PY_VERSION_HEX < 0x030d0000 && !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) - int one = 1; int is_little = (int)*(unsigned char *)&one; - unsigned char *bytes = (unsigned char *)&val; - ret = _PyLong_AsByteArray((PyLongObject *)v, - bytes, sizeof(val), - is_little, !is_unsigned); -#else - PyObject *stepval = NULL, *mask = NULL, *shift = NULL; - int bits, remaining_bits, is_negative = 0; - long idigit; - int chunk_size = (sizeof(long) < 8) ? 30 : 62; - if (unlikely(!PyLong_CheckExact(v))) { - PyObject *tmp = v; - v = PyNumber_Long(v); - assert(PyLong_CheckExact(v)); - Py_DECREF(tmp); - if (unlikely(!v)) return (int) -1; - } -#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 - if (Py_SIZE(x) == 0) - return (int) 0; - is_negative = Py_SIZE(x) < 0; -#else - { - int result = PyObject_RichCompareBool(x, Py_False, Py_LT); - if (unlikely(result < 0)) - return (int) -1; - is_negative = result == 1; - } -#endif - if (is_unsigned && unlikely(is_negative)) { - goto raise_neg_overflow; - } else if (is_negative) { - stepval = PyNumber_Invert(v); - if (unlikely(!stepval)) - return (int) -1; - } else { - stepval = __Pyx_NewRef(v); - } - val = (int) 0; - mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; - shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; - for (bits = 0; bits < (int) sizeof(int) * 8 - chunk_size; bits += chunk_size) { - PyObject *tmp, *digit; - digit = PyNumber_And(stepval, mask); - if (unlikely(!digit)) goto done; - idigit = PyLong_AsLong(digit); - Py_DECREF(digit); - if (unlikely(idigit < 0)) goto done; - tmp = PyNumber_Rshift(stepval, shift); - if (unlikely(!tmp)) goto done; - Py_DECREF(stepval); stepval = tmp; - val |= ((int) idigit) << bits; - #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 - if (Py_SIZE(stepval) == 0) - goto unpacking_done; - #endif - } - idigit = PyLong_AsLong(stepval); - if (unlikely(idigit < 0)) goto done; - remaining_bits = ((int) sizeof(int) * 8) - bits - (is_unsigned ? 0 : 1); - if (unlikely(idigit >= (1L << remaining_bits))) - goto raise_overflow; - val |= ((int) idigit) << bits; - #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 - unpacking_done: - #endif - if (!is_unsigned) { - if (unlikely(val & (((int) 1) << (sizeof(int) * 8 - 1)))) - goto raise_overflow; - if (is_negative) - val = ~val; - } - ret = 0; - done: - Py_XDECREF(shift); - Py_XDECREF(mask); - Py_XDECREF(stepval); -#endif - Py_DECREF(v); - if (likely(!ret)) - return val; - } - return (int) -1; - } - } else { - int val; - PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); - if (!tmp) return (int) -1; - val = __Pyx_PyInt_As_int(tmp); - Py_DECREF(tmp); - return val; - } -raise_overflow: - PyErr_SetString(PyExc_OverflowError, - "value too large to convert to int"); - return (int) -1; -raise_neg_overflow: - PyErr_SetString(PyExc_OverflowError, - "can't convert negative value to int"); - return (int) -1; -} - -/* CIntToPy */ - static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value) { -#ifdef __Pyx_HAS_GCC_DIAGNOSTIC -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wconversion" -#endif - const long neg_one = (long) -1, const_zero = (long) 0; -#ifdef __Pyx_HAS_GCC_DIAGNOSTIC -#pragma GCC diagnostic pop -#endif - const int is_unsigned = neg_one > const_zero; - if (is_unsigned) { - if (sizeof(long) < sizeof(long)) { - return PyInt_FromLong((long) value); - } else if (sizeof(long) <= sizeof(unsigned long)) { - return PyLong_FromUnsignedLong((unsigned long) value); -#ifdef HAVE_LONG_LONG - } else if (sizeof(long) <= sizeof(unsigned PY_LONG_LONG)) { - return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); -#endif - } - } else { - if (sizeof(long) <= sizeof(long)) { - return PyInt_FromLong((long) value); -#ifdef HAVE_LONG_LONG - } else if (sizeof(long) <= sizeof(PY_LONG_LONG)) { - return PyLong_FromLongLong((PY_LONG_LONG) value); -#endif - } - } - { - int one = 1; int little = (int)*(unsigned char *)&one; - unsigned char *bytes = (unsigned char *)&value; -#if !CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030d0000 - return _PyLong_FromByteArray(bytes, sizeof(long), - little, !is_unsigned); -#else - PyObject *from_bytes, *result = NULL; - PyObject *py_bytes = NULL, *arg_tuple = NULL, *kwds = NULL, *order_str = NULL; - from_bytes = PyObject_GetAttrString((PyObject*)&PyLong_Type, "from_bytes"); - if (!from_bytes) return NULL; - py_bytes = PyBytes_FromStringAndSize((char*)bytes, sizeof(long)); - if (!py_bytes) goto limited_bad; - order_str = PyUnicode_FromString(little ? "little" : "big"); - if (!order_str) goto limited_bad; - arg_tuple = PyTuple_Pack(2, py_bytes, order_str); - if (!arg_tuple) goto limited_bad; - if (!is_unsigned) { - kwds = PyDict_New(); - if (!kwds) goto limited_bad; - if (PyDict_SetItemString(kwds, "signed", __Pyx_NewRef(Py_True))) goto limited_bad; - } - result = PyObject_Call(from_bytes, arg_tuple, kwds); - limited_bad: - Py_XDECREF(kwds); - Py_XDECREF(arg_tuple); - Py_XDECREF(order_str); - Py_XDECREF(py_bytes); - Py_XDECREF(from_bytes); - return result; -#endif - } -} - -/* CIntToPy */ - static CYTHON_INLINE PyObject* __Pyx_PyInt_From_int(int value) { -#ifdef __Pyx_HAS_GCC_DIAGNOSTIC -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wconversion" -#endif - const int neg_one = (int) -1, const_zero = (int) 0; -#ifdef __Pyx_HAS_GCC_DIAGNOSTIC -#pragma GCC diagnostic pop -#endif - const int is_unsigned = neg_one > const_zero; - if (is_unsigned) { - if (sizeof(int) < sizeof(long)) { - return PyInt_FromLong((long) value); - } else if (sizeof(int) <= sizeof(unsigned long)) { - return PyLong_FromUnsignedLong((unsigned long) value); -#ifdef HAVE_LONG_LONG - } else if (sizeof(int) <= sizeof(unsigned PY_LONG_LONG)) { - return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); -#endif - } - } else { - if (sizeof(int) <= sizeof(long)) { - return PyInt_FromLong((long) value); -#ifdef HAVE_LONG_LONG - } else if (sizeof(int) <= sizeof(PY_LONG_LONG)) { - return PyLong_FromLongLong((PY_LONG_LONG) value); -#endif - } - } - { - int one = 1; int little = (int)*(unsigned char *)&one; - unsigned char *bytes = (unsigned char *)&value; -#if !CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030d0000 - return _PyLong_FromByteArray(bytes, sizeof(int), - little, !is_unsigned); -#else - PyObject *from_bytes, *result = NULL; - PyObject *py_bytes = NULL, *arg_tuple = NULL, *kwds = NULL, *order_str = NULL; - from_bytes = PyObject_GetAttrString((PyObject*)&PyLong_Type, "from_bytes"); - if (!from_bytes) return NULL; - py_bytes = PyBytes_FromStringAndSize((char*)bytes, sizeof(int)); - if (!py_bytes) goto limited_bad; - order_str = PyUnicode_FromString(little ? "little" : "big"); - if (!order_str) goto limited_bad; - arg_tuple = PyTuple_Pack(2, py_bytes, order_str); - if (!arg_tuple) goto limited_bad; - if (!is_unsigned) { - kwds = PyDict_New(); - if (!kwds) goto limited_bad; - if (PyDict_SetItemString(kwds, "signed", __Pyx_NewRef(Py_True))) goto limited_bad; - } - result = PyObject_Call(from_bytes, arg_tuple, kwds); - limited_bad: - Py_XDECREF(kwds); - Py_XDECREF(arg_tuple); - Py_XDECREF(order_str); - Py_XDECREF(py_bytes); - Py_XDECREF(from_bytes); - return result; -#endif - } -} - -/* CIntFromPy */ - static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *x) { -#ifdef __Pyx_HAS_GCC_DIAGNOSTIC -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wconversion" -#endif - const long neg_one = (long) -1, const_zero = (long) 0; -#ifdef __Pyx_HAS_GCC_DIAGNOSTIC -#pragma GCC diagnostic pop -#endif - const int is_unsigned = neg_one > const_zero; -#if PY_MAJOR_VERSION < 3 - if (likely(PyInt_Check(x))) { - if ((sizeof(long) < sizeof(long))) { - __PYX_VERIFY_RETURN_INT(long, long, PyInt_AS_LONG(x)) - } else { - long val = PyInt_AS_LONG(x); - if (is_unsigned && unlikely(val < 0)) { - goto raise_neg_overflow; - } - return (long) val; - } - } else -#endif - if (likely(PyLong_Check(x))) { - if (is_unsigned) { -#if CYTHON_USE_PYLONG_INTERNALS - if (unlikely(__Pyx_PyLong_IsNeg(x))) { - goto raise_neg_overflow; - } else if (__Pyx_PyLong_IsCompact(x)) { - __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) - } else { - const digit* digits = __Pyx_PyLong_Digits(x); - assert(__Pyx_PyLong_DigitCount(x) > 1); - switch (__Pyx_PyLong_DigitCount(x)) { - case 2: - if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { - if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { - __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) - } else if ((8 * sizeof(long) >= 2 * PyLong_SHIFT)) { - return (long) (((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); - } - } - break; - case 3: - if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { - if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { - __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) - } else if ((8 * sizeof(long) >= 3 * PyLong_SHIFT)) { - return (long) (((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); - } - } - break; - case 4: - if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { - if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { - __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) - } else if ((8 * sizeof(long) >= 4 * PyLong_SHIFT)) { - return (long) (((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); - } - } - break; - } - } -#endif -#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 - if (unlikely(Py_SIZE(x) < 0)) { - goto raise_neg_overflow; - } -#else - { - int result = PyObject_RichCompareBool(x, Py_False, Py_LT); - if (unlikely(result < 0)) - return (long) -1; - if (unlikely(result == 1)) - goto raise_neg_overflow; - } -#endif - if ((sizeof(long) <= sizeof(unsigned long))) { - __PYX_VERIFY_RETURN_INT_EXC(long, unsigned long, PyLong_AsUnsignedLong(x)) -#ifdef HAVE_LONG_LONG - } else if ((sizeof(long) <= sizeof(unsigned PY_LONG_LONG))) { - __PYX_VERIFY_RETURN_INT_EXC(long, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) -#endif - } - } else { -#if CYTHON_USE_PYLONG_INTERNALS - if (__Pyx_PyLong_IsCompact(x)) { - __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) - } else { - const digit* digits = __Pyx_PyLong_Digits(x); - assert(__Pyx_PyLong_DigitCount(x) > 1); - switch (__Pyx_PyLong_SignedDigitCount(x)) { - case -2: - if ((8 * sizeof(long) - 1 > 1 * PyLong_SHIFT)) { - if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { - __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) - } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { - return (long) (((long)-1)*(((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); - } - } - break; - case 2: - if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { - if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { - __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) - } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { - return (long) ((((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); - } - } - break; - case -3: - if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { - if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { - __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) - } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { - return (long) (((long)-1)*(((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); - } - } - break; - case 3: - if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { - if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { - __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) - } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { - return (long) ((((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); - } - } - break; - case -4: - if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { - if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { - __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) - } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { - return (long) (((long)-1)*(((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); - } - } - break; - case 4: - if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { - if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { - __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) - } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { - return (long) ((((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); - } - } - break; - } - } -#endif - if ((sizeof(long) <= sizeof(long))) { - __PYX_VERIFY_RETURN_INT_EXC(long, long, PyLong_AsLong(x)) -#ifdef HAVE_LONG_LONG - } else if ((sizeof(long) <= sizeof(PY_LONG_LONG))) { - __PYX_VERIFY_RETURN_INT_EXC(long, PY_LONG_LONG, PyLong_AsLongLong(x)) -#endif - } - } - { - long val; - PyObject *v = __Pyx_PyNumber_IntOrLong(x); -#if PY_MAJOR_VERSION < 3 - if (likely(v) && !PyLong_Check(v)) { - PyObject *tmp = v; - v = PyNumber_Long(tmp); - Py_DECREF(tmp); - } -#endif - if (likely(v)) { - int ret = -1; -#if PY_VERSION_HEX < 0x030d0000 && !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) - int one = 1; int is_little = (int)*(unsigned char *)&one; - unsigned char *bytes = (unsigned char *)&val; - ret = _PyLong_AsByteArray((PyLongObject *)v, - bytes, sizeof(val), - is_little, !is_unsigned); -#else - PyObject *stepval = NULL, *mask = NULL, *shift = NULL; - int bits, remaining_bits, is_negative = 0; - long idigit; - int chunk_size = (sizeof(long) < 8) ? 30 : 62; - if (unlikely(!PyLong_CheckExact(v))) { - PyObject *tmp = v; - v = PyNumber_Long(v); - assert(PyLong_CheckExact(v)); - Py_DECREF(tmp); - if (unlikely(!v)) return (long) -1; - } -#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 - if (Py_SIZE(x) == 0) - return (long) 0; - is_negative = Py_SIZE(x) < 0; -#else - { - int result = PyObject_RichCompareBool(x, Py_False, Py_LT); - if (unlikely(result < 0)) - return (long) -1; - is_negative = result == 1; - } -#endif - if (is_unsigned && unlikely(is_negative)) { - goto raise_neg_overflow; - } else if (is_negative) { - stepval = PyNumber_Invert(v); - if (unlikely(!stepval)) - return (long) -1; - } else { - stepval = __Pyx_NewRef(v); - } - val = (long) 0; - mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; - shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; - for (bits = 0; bits < (int) sizeof(long) * 8 - chunk_size; bits += chunk_size) { - PyObject *tmp, *digit; - digit = PyNumber_And(stepval, mask); - if (unlikely(!digit)) goto done; - idigit = PyLong_AsLong(digit); - Py_DECREF(digit); - if (unlikely(idigit < 0)) goto done; - tmp = PyNumber_Rshift(stepval, shift); - if (unlikely(!tmp)) goto done; - Py_DECREF(stepval); stepval = tmp; - val |= ((long) idigit) << bits; - #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 - if (Py_SIZE(stepval) == 0) - goto unpacking_done; - #endif - } - idigit = PyLong_AsLong(stepval); - if (unlikely(idigit < 0)) goto done; - remaining_bits = ((int) sizeof(long) * 8) - bits - (is_unsigned ? 0 : 1); - if (unlikely(idigit >= (1L << remaining_bits))) - goto raise_overflow; - val |= ((long) idigit) << bits; - #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 - unpacking_done: - #endif - if (!is_unsigned) { - if (unlikely(val & (((long) 1) << (sizeof(long) * 8 - 1)))) - goto raise_overflow; - if (is_negative) - val = ~val; - } - ret = 0; - done: - Py_XDECREF(shift); - Py_XDECREF(mask); - Py_XDECREF(stepval); -#endif - Py_DECREF(v); - if (likely(!ret)) - return val; - } - return (long) -1; - } - } else { - long val; - PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); - if (!tmp) return (long) -1; - val = __Pyx_PyInt_As_long(tmp); - Py_DECREF(tmp); - return val; - } -raise_overflow: - PyErr_SetString(PyExc_OverflowError, - "value too large to convert to long"); - return (long) -1; -raise_neg_overflow: - PyErr_SetString(PyExc_OverflowError, - "can't convert negative value to long"); - return (long) -1; -} - -/* CIntFromPy */ - static CYTHON_INLINE char __Pyx_PyInt_As_char(PyObject *x) { -#ifdef __Pyx_HAS_GCC_DIAGNOSTIC -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wconversion" -#endif - const char neg_one = (char) -1, const_zero = (char) 0; -#ifdef __Pyx_HAS_GCC_DIAGNOSTIC -#pragma GCC diagnostic pop -#endif - const int is_unsigned = neg_one > const_zero; -#if PY_MAJOR_VERSION < 3 - if (likely(PyInt_Check(x))) { - if ((sizeof(char) < sizeof(long))) { - __PYX_VERIFY_RETURN_INT(char, long, PyInt_AS_LONG(x)) - } else { - long val = PyInt_AS_LONG(x); - if (is_unsigned && unlikely(val < 0)) { - goto raise_neg_overflow; - } - return (char) val; - } - } else -#endif - if (likely(PyLong_Check(x))) { - if (is_unsigned) { -#if CYTHON_USE_PYLONG_INTERNALS - if (unlikely(__Pyx_PyLong_IsNeg(x))) { - goto raise_neg_overflow; - } else if (__Pyx_PyLong_IsCompact(x)) { - __PYX_VERIFY_RETURN_INT(char, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) - } else { - const digit* digits = __Pyx_PyLong_Digits(x); - assert(__Pyx_PyLong_DigitCount(x) > 1); - switch (__Pyx_PyLong_DigitCount(x)) { - case 2: - if ((8 * sizeof(char) > 1 * PyLong_SHIFT)) { - if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { - __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) - } else if ((8 * sizeof(char) >= 2 * PyLong_SHIFT)) { - return (char) (((((char)digits[1]) << PyLong_SHIFT) | (char)digits[0])); - } - } - break; - case 3: - if ((8 * sizeof(char) > 2 * PyLong_SHIFT)) { - if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { - __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) - } else if ((8 * sizeof(char) >= 3 * PyLong_SHIFT)) { - return (char) (((((((char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0])); - } - } - break; - case 4: - if ((8 * sizeof(char) > 3 * PyLong_SHIFT)) { - if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { - __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) - } else if ((8 * sizeof(char) >= 4 * PyLong_SHIFT)) { - return (char) (((((((((char)digits[3]) << PyLong_SHIFT) | (char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0])); - } - } - break; - } - } -#endif -#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 - if (unlikely(Py_SIZE(x) < 0)) { - goto raise_neg_overflow; - } -#else - { - int result = PyObject_RichCompareBool(x, Py_False, Py_LT); - if (unlikely(result < 0)) - return (char) -1; - if (unlikely(result == 1)) - goto raise_neg_overflow; - } -#endif - if ((sizeof(char) <= sizeof(unsigned long))) { - __PYX_VERIFY_RETURN_INT_EXC(char, unsigned long, PyLong_AsUnsignedLong(x)) -#ifdef HAVE_LONG_LONG - } else if ((sizeof(char) <= sizeof(unsigned PY_LONG_LONG))) { - __PYX_VERIFY_RETURN_INT_EXC(char, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) -#endif - } - } else { -#if CYTHON_USE_PYLONG_INTERNALS - if (__Pyx_PyLong_IsCompact(x)) { - __PYX_VERIFY_RETURN_INT(char, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) - } else { - const digit* digits = __Pyx_PyLong_Digits(x); - assert(__Pyx_PyLong_DigitCount(x) > 1); - switch (__Pyx_PyLong_SignedDigitCount(x)) { - case -2: - if ((8 * sizeof(char) - 1 > 1 * PyLong_SHIFT)) { - if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { - __PYX_VERIFY_RETURN_INT(char, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) - } else if ((8 * sizeof(char) - 1 > 2 * PyLong_SHIFT)) { - return (char) (((char)-1)*(((((char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); - } - } - break; - case 2: - if ((8 * sizeof(char) > 1 * PyLong_SHIFT)) { - if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { - __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) - } else if ((8 * sizeof(char) - 1 > 2 * PyLong_SHIFT)) { - return (char) ((((((char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); - } - } - break; - case -3: - if ((8 * sizeof(char) - 1 > 2 * PyLong_SHIFT)) { - if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { - __PYX_VERIFY_RETURN_INT(char, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) - } else if ((8 * sizeof(char) - 1 > 3 * PyLong_SHIFT)) { - return (char) (((char)-1)*(((((((char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); - } - } - break; - case 3: - if ((8 * sizeof(char) > 2 * PyLong_SHIFT)) { - if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { - __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) - } else if ((8 * sizeof(char) - 1 > 3 * PyLong_SHIFT)) { - return (char) ((((((((char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); - } - } - break; - case -4: - if ((8 * sizeof(char) - 1 > 3 * PyLong_SHIFT)) { - if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { - __PYX_VERIFY_RETURN_INT(char, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) - } else if ((8 * sizeof(char) - 1 > 4 * PyLong_SHIFT)) { - return (char) (((char)-1)*(((((((((char)digits[3]) << PyLong_SHIFT) | (char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); - } - } - break; - case 4: - if ((8 * sizeof(char) > 3 * PyLong_SHIFT)) { - if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { - __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) - } else if ((8 * sizeof(char) - 1 > 4 * PyLong_SHIFT)) { - return (char) ((((((((((char)digits[3]) << PyLong_SHIFT) | (char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); - } - } - break; - } - } -#endif - if ((sizeof(char) <= sizeof(long))) { - __PYX_VERIFY_RETURN_INT_EXC(char, long, PyLong_AsLong(x)) -#ifdef HAVE_LONG_LONG - } else if ((sizeof(char) <= sizeof(PY_LONG_LONG))) { - __PYX_VERIFY_RETURN_INT_EXC(char, PY_LONG_LONG, PyLong_AsLongLong(x)) -#endif - } - } - { - char val; - PyObject *v = __Pyx_PyNumber_IntOrLong(x); -#if PY_MAJOR_VERSION < 3 - if (likely(v) && !PyLong_Check(v)) { - PyObject *tmp = v; - v = PyNumber_Long(tmp); - Py_DECREF(tmp); - } -#endif - if (likely(v)) { - int ret = -1; -#if PY_VERSION_HEX < 0x030d0000 && !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) - int one = 1; int is_little = (int)*(unsigned char *)&one; - unsigned char *bytes = (unsigned char *)&val; - ret = _PyLong_AsByteArray((PyLongObject *)v, - bytes, sizeof(val), - is_little, !is_unsigned); -#else - PyObject *stepval = NULL, *mask = NULL, *shift = NULL; - int bits, remaining_bits, is_negative = 0; - long idigit; - int chunk_size = (sizeof(long) < 8) ? 30 : 62; - if (unlikely(!PyLong_CheckExact(v))) { - PyObject *tmp = v; - v = PyNumber_Long(v); - assert(PyLong_CheckExact(v)); - Py_DECREF(tmp); - if (unlikely(!v)) return (char) -1; - } -#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 - if (Py_SIZE(x) == 0) - return (char) 0; - is_negative = Py_SIZE(x) < 0; -#else - { - int result = PyObject_RichCompareBool(x, Py_False, Py_LT); - if (unlikely(result < 0)) - return (char) -1; - is_negative = result == 1; - } -#endif - if (is_unsigned && unlikely(is_negative)) { - goto raise_neg_overflow; - } else if (is_negative) { - stepval = PyNumber_Invert(v); - if (unlikely(!stepval)) - return (char) -1; - } else { - stepval = __Pyx_NewRef(v); - } - val = (char) 0; - mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; - shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; - for (bits = 0; bits < (int) sizeof(char) * 8 - chunk_size; bits += chunk_size) { - PyObject *tmp, *digit; - digit = PyNumber_And(stepval, mask); - if (unlikely(!digit)) goto done; - idigit = PyLong_AsLong(digit); - Py_DECREF(digit); - if (unlikely(idigit < 0)) goto done; - tmp = PyNumber_Rshift(stepval, shift); - if (unlikely(!tmp)) goto done; - Py_DECREF(stepval); stepval = tmp; - val |= ((char) idigit) << bits; - #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 - if (Py_SIZE(stepval) == 0) - goto unpacking_done; - #endif - } - idigit = PyLong_AsLong(stepval); - if (unlikely(idigit < 0)) goto done; - remaining_bits = ((int) sizeof(char) * 8) - bits - (is_unsigned ? 0 : 1); - if (unlikely(idigit >= (1L << remaining_bits))) - goto raise_overflow; - val |= ((char) idigit) << bits; - #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 - unpacking_done: - #endif - if (!is_unsigned) { - if (unlikely(val & (((char) 1) << (sizeof(char) * 8 - 1)))) - goto raise_overflow; - if (is_negative) - val = ~val; - } - ret = 0; - done: - Py_XDECREF(shift); - Py_XDECREF(mask); - Py_XDECREF(stepval); -#endif - Py_DECREF(v); - if (likely(!ret)) - return val; - } - return (char) -1; - } - } else { - char val; - PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); - if (!tmp) return (char) -1; - val = __Pyx_PyInt_As_char(tmp); - Py_DECREF(tmp); - return val; - } -raise_overflow: - PyErr_SetString(PyExc_OverflowError, - "value too large to convert to char"); - return (char) -1; -raise_neg_overflow: - PyErr_SetString(PyExc_OverflowError, - "can't convert negative value to char"); - return (char) -1; -} - -/* FormatTypeName */ - #if CYTHON_COMPILING_IN_LIMITED_API -static __Pyx_TypeName -__Pyx_PyType_GetName(PyTypeObject* tp) -{ - PyObject *name = __Pyx_PyObject_GetAttrStr((PyObject *)tp, - __pyx_n_s_name_2); - if (unlikely(name == NULL) || unlikely(!PyUnicode_Check(name))) { - PyErr_Clear(); - Py_XDECREF(name); - name = __Pyx_NewRef(__pyx_n_s__58); - } - return name; -} -#endif - -/* CheckBinaryVersion */ - static unsigned long __Pyx_get_runtime_version(void) { -#if __PYX_LIMITED_VERSION_HEX >= 0x030B00A4 - return Py_Version & ~0xFFUL; -#else - const char* rt_version = Py_GetVersion(); - unsigned long version = 0; - unsigned long factor = 0x01000000UL; - unsigned int digit = 0; - int i = 0; - while (factor) { - while ('0' <= rt_version[i] && rt_version[i] <= '9') { - digit = digit * 10 + (unsigned int) (rt_version[i] - '0'); - ++i; - } - version += factor * digit; - if (rt_version[i] != '.') - break; - digit = 0; - factor >>= 8; - ++i; - } - return version; -#endif -} -static int __Pyx_check_binary_version(unsigned long ct_version, unsigned long rt_version, int allow_newer) { - const unsigned long MAJOR_MINOR = 0xFFFF0000UL; - if ((rt_version & MAJOR_MINOR) == (ct_version & MAJOR_MINOR)) - return 0; - if (likely(allow_newer && (rt_version & MAJOR_MINOR) > (ct_version & MAJOR_MINOR))) - return 1; - { - char message[200]; - PyOS_snprintf(message, sizeof(message), - "compile time Python version %d.%d " - "of module '%.100s' " - "%s " - "runtime version %d.%d", - (int) (ct_version >> 24), (int) ((ct_version >> 16) & 0xFF), - __Pyx_MODULE_NAME, - (allow_newer) ? "was newer than" : "does not match", - (int) (rt_version >> 24), (int) ((rt_version >> 16) & 0xFF) - ); - return PyErr_WarnEx(NULL, message, 1); - } -} - -/* InitStrings */ - #if PY_MAJOR_VERSION >= 3 -static int __Pyx_InitString(__Pyx_StringTabEntry t, PyObject **str) { - if (t.is_unicode | t.is_str) { - if (t.intern) { - *str = PyUnicode_InternFromString(t.s); - } else if (t.encoding) { - *str = PyUnicode_Decode(t.s, t.n - 1, t.encoding, NULL); - } else { - *str = PyUnicode_FromStringAndSize(t.s, t.n - 1); - } - } else { - *str = PyBytes_FromStringAndSize(t.s, t.n - 1); - } - if (!*str) - return -1; - if (PyObject_Hash(*str) == -1) - return -1; - return 0; -} -#endif -static int __Pyx_InitStrings(__Pyx_StringTabEntry *t) { - while (t->p) { - #if PY_MAJOR_VERSION >= 3 - __Pyx_InitString(*t, t->p); - #else - if (t->is_unicode) { - *t->p = PyUnicode_DecodeUTF8(t->s, t->n - 1, NULL); - } else if (t->intern) { - *t->p = PyString_InternFromString(t->s); - } else { - *t->p = PyString_FromStringAndSize(t->s, t->n - 1); - } - if (!*t->p) - return -1; - if (PyObject_Hash(*t->p) == -1) - return -1; - #endif - ++t; - } - return 0; -} - -#include -static CYTHON_INLINE Py_ssize_t __Pyx_ssize_strlen(const char *s) { - size_t len = strlen(s); - if (unlikely(len > (size_t) PY_SSIZE_T_MAX)) { - PyErr_SetString(PyExc_OverflowError, "byte string is too long"); - return -1; - } - return (Py_ssize_t) len; -} -static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char* c_str) { - Py_ssize_t len = __Pyx_ssize_strlen(c_str); - if (unlikely(len < 0)) return NULL; - return __Pyx_PyUnicode_FromStringAndSize(c_str, len); -} -static CYTHON_INLINE PyObject* __Pyx_PyByteArray_FromString(const char* c_str) { - Py_ssize_t len = __Pyx_ssize_strlen(c_str); - if (unlikely(len < 0)) return NULL; - return PyByteArray_FromStringAndSize(c_str, len); -} -static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject* o) { - Py_ssize_t ignore; - return __Pyx_PyObject_AsStringAndSize(o, &ignore); -} -#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT -#if !CYTHON_PEP393_ENABLED -static const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { - char* defenc_c; - PyObject* defenc = _PyUnicode_AsDefaultEncodedString(o, NULL); - if (!defenc) return NULL; - defenc_c = PyBytes_AS_STRING(defenc); -#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII - { - char* end = defenc_c + PyBytes_GET_SIZE(defenc); - char* c; - for (c = defenc_c; c < end; c++) { - if ((unsigned char) (*c) >= 128) { - PyUnicode_AsASCIIString(o); - return NULL; - } - } - } -#endif - *length = PyBytes_GET_SIZE(defenc); - return defenc_c; -} -#else -static CYTHON_INLINE const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { - if (unlikely(__Pyx_PyUnicode_READY(o) == -1)) return NULL; -#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII - if (likely(PyUnicode_IS_ASCII(o))) { - *length = PyUnicode_GET_LENGTH(o); - return PyUnicode_AsUTF8(o); - } else { - PyUnicode_AsASCIIString(o); - return NULL; - } -#else - return PyUnicode_AsUTF8AndSize(o, length); -#endif -} -#endif -#endif -static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject* o, Py_ssize_t *length) { -#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT - if ( -#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII - __Pyx_sys_getdefaultencoding_not_ascii && -#endif - PyUnicode_Check(o)) { - return __Pyx_PyUnicode_AsStringAndSize(o, length); - } else -#endif -#if (!CYTHON_COMPILING_IN_PYPY && !CYTHON_COMPILING_IN_LIMITED_API) || (defined(PyByteArray_AS_STRING) && defined(PyByteArray_GET_SIZE)) - if (PyByteArray_Check(o)) { - *length = PyByteArray_GET_SIZE(o); - return PyByteArray_AS_STRING(o); - } else -#endif - { - char* result; - int r = PyBytes_AsStringAndSize(o, &result, length); - if (unlikely(r < 0)) { - return NULL; - } else { - return result; - } - } -} -static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject* x) { - int is_true = x == Py_True; - if (is_true | (x == Py_False) | (x == Py_None)) return is_true; - else return PyObject_IsTrue(x); -} -static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject* x) { - int retval; - if (unlikely(!x)) return -1; - retval = __Pyx_PyObject_IsTrue(x); - Py_DECREF(x); - return retval; -} -static PyObject* __Pyx_PyNumber_IntOrLongWrongResultType(PyObject* result, const char* type_name) { - __Pyx_TypeName result_type_name = __Pyx_PyType_GetName(Py_TYPE(result)); -#if PY_MAJOR_VERSION >= 3 - if (PyLong_Check(result)) { - if (PyErr_WarnFormat(PyExc_DeprecationWarning, 1, - "__int__ returned non-int (type " __Pyx_FMT_TYPENAME "). " - "The ability to return an instance of a strict subclass of int is deprecated, " - "and may be removed in a future version of Python.", - result_type_name)) { - __Pyx_DECREF_TypeName(result_type_name); - Py_DECREF(result); - return NULL; - } - __Pyx_DECREF_TypeName(result_type_name); - return result; - } -#endif - PyErr_Format(PyExc_TypeError, - "__%.4s__ returned non-%.4s (type " __Pyx_FMT_TYPENAME ")", - type_name, type_name, result_type_name); - __Pyx_DECREF_TypeName(result_type_name); - Py_DECREF(result); - return NULL; -} -static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x) { -#if CYTHON_USE_TYPE_SLOTS - PyNumberMethods *m; -#endif - const char *name = NULL; - PyObject *res = NULL; -#if PY_MAJOR_VERSION < 3 - if (likely(PyInt_Check(x) || PyLong_Check(x))) -#else - if (likely(PyLong_Check(x))) -#endif - return __Pyx_NewRef(x); -#if CYTHON_USE_TYPE_SLOTS - m = Py_TYPE(x)->tp_as_number; - #if PY_MAJOR_VERSION < 3 - if (m && m->nb_int) { - name = "int"; - res = m->nb_int(x); - } - else if (m && m->nb_long) { - name = "long"; - res = m->nb_long(x); - } - #else - if (likely(m && m->nb_int)) { - name = "int"; - res = m->nb_int(x); - } - #endif -#else - if (!PyBytes_CheckExact(x) && !PyUnicode_CheckExact(x)) { - res = PyNumber_Int(x); - } -#endif - if (likely(res)) { -#if PY_MAJOR_VERSION < 3 - if (unlikely(!PyInt_Check(res) && !PyLong_Check(res))) { -#else - if (unlikely(!PyLong_CheckExact(res))) { -#endif - return __Pyx_PyNumber_IntOrLongWrongResultType(res, name); - } - } - else if (!PyErr_Occurred()) { - PyErr_SetString(PyExc_TypeError, - "an integer is required"); - } - return res; -} -static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject* b) { - Py_ssize_t ival; - PyObject *x; -#if PY_MAJOR_VERSION < 3 - if (likely(PyInt_CheckExact(b))) { - if (sizeof(Py_ssize_t) >= sizeof(long)) - return PyInt_AS_LONG(b); - else - return PyInt_AsSsize_t(b); - } -#endif - if (likely(PyLong_CheckExact(b))) { - #if CYTHON_USE_PYLONG_INTERNALS - if (likely(__Pyx_PyLong_IsCompact(b))) { - return __Pyx_PyLong_CompactValue(b); - } else { - const digit* digits = __Pyx_PyLong_Digits(b); - const Py_ssize_t size = __Pyx_PyLong_SignedDigitCount(b); - switch (size) { - case 2: - if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { - return (Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); - } - break; - case -2: - if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { - return -(Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); - } - break; - case 3: - if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { - return (Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); - } - break; - case -3: - if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { - return -(Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); - } - break; - case 4: - if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { - return (Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); - } - break; - case -4: - if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { - return -(Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); - } - break; - } - } - #endif - return PyLong_AsSsize_t(b); - } - x = PyNumber_Index(b); - if (!x) return -1; - ival = PyInt_AsSsize_t(x); - Py_DECREF(x); - return ival; -} -static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject* o) { - if (sizeof(Py_hash_t) == sizeof(Py_ssize_t)) { - return (Py_hash_t) __Pyx_PyIndex_AsSsize_t(o); -#if PY_MAJOR_VERSION < 3 - } else if (likely(PyInt_CheckExact(o))) { - return PyInt_AS_LONG(o); -#endif - } else { - Py_ssize_t ival; - PyObject *x; - x = PyNumber_Index(o); - if (!x) return -1; - ival = PyInt_AsLong(x); - Py_DECREF(x); - return ival; - } -} -static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b) { - return b ? __Pyx_NewRef(Py_True) : __Pyx_NewRef(Py_False); -} -static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t ival) { - return PyInt_FromSize_t(ival); -} - - -/* #### Code section: utility_code_pragmas_end ### */ -#ifdef _MSC_VER -#pragma warning( pop ) -#endif - - - -/* #### Code section: end ### */ -#endif /* Py_PYTHON_H */ diff --git a/rednose/helpers/ekf_sym_pyx.so b/rednose/helpers/ekf_sym_pyx.so deleted file mode 100755 index 63737dcf899b750a7426a4e6930e0c066bbbdaa9..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 4898664 zcmeFa30xdS`v2cTOvqs*rx=e+Fh-1;41_CDBO!r6&Ji$TJO&1aFbT&9Lqg&;5{>A3 z5KlHax)Jfh8_$iatB9_P$12{$HRk`Ru4?8pooNG@`1}6;uit2A=JW2S zpQ?JQy1J^mXSg73QF_>Z`)S52Tzga#%AO@zirUfi$O6MeOVN_GA^7(QEn2tTzjx2> z9~KQ6tV82n(~pq4Z^$F+Eh`^?~|3C@h)t|%keK?q4?a;AWLa}e|e;CrWx_lihj2o9Ko z&4$mzv0d~`x^~!vg!sV)EmK#(2X8-S&{J7c7Ps8fn&Al7YN7|{wd6R4?Ki3BHd};k=;Y*?!v=Nu zM@(5e_cYtY7mm9qJZ?}}%w-pM9J!zEsd15W*H6;4_$O+|HQF@P&rt26)V7rQ?U5tH z>KcxT9QCq$e4YKpu$)b{14azns6|eWxT3cCuZ0mKr|;)Gx&7ix9dS|iBXWu(YwRf( zeSC3P{GfSZ`;AU*8C=t1uNgFJ%tM!VEUcM#WXk9o|D=@lS4Zp@zAm@5(;m~}7?Cm~ z>aw9fN zDmL*t4e!gbosR7c#m>aL6I&j(d~5~Sim(~475MDIwoRs?3@Og*Qzuu`R`Byd3KD$?81|?>Xx8GQ6LP?KEu5 z6%)sufzM}R%fptB&4ta4tq5B&HV-!AwF;lhl&-}4YV~;y-m9^#Ra)4eOP?>mXFs+J zvDIL^7~2MH;&ln$FU58RwyUsh#3o)>pN!VKJwJBM}0NNb8f-Cx4pFHpU*t} zX7=*)TR!Uf?!wPMKkTFn|Mai-uMPYD=1r|k+WFnF zF+2a8u;9@DUikJ^myPI&FPk=hW^GX>w*6jv<=fNWeKK`zimmvqXFt4lDOl3Y0q5?A6R_O3->N_Zo6R4 zw$IAnT{w37HwhJW+kV_~%%I6LYQMYm#M+|EusxA=-7ycGJ^%Cz8ZV#p>nn->z3$gf zd;aD9EcJvNTdzIl?H`}K5;jvN{!h=-IbS?{=9A|Rd8yQOM^#1f^P_T~fBwHe)%kD2 z{`H0D939_q=imRGe#)+*2WrAj44?Jru_tH0`To#V7oIw7lz-z5ajOR3oO$Esj<-I0 zV#F_#zIbuY(|>xsHtmBu%Ko*Y_^VkHZ*M(o&A-M>$@`?}wKa>@Uo|oN^{cMErf7Q2 z-(UH5%Bxqrev0pjj9J=A^QW)>pVObnNqQvq+9qrEItqH$u_%iFkmRIVAKA3pe$Js*`#D2a1c~>0m zz5DC%lV|3=dFav6vzrdT$g}Rs#m)Iu(eG5J-a7ak``tAUdk%2@{6JXKm_NP!=O2fy z`)ur)W8NFPBz^z4?_V{gC4SJZb5EOgqw~GSCytvL({)~3!NW)T*SzxdgX^AX9W`hD zow*qgUO9K@8z;Qo_U{{Ccx7KWd85WWmiXwlsYflduT8sc<_-7ejhS8d>Xr4^9Q@#x z!m*#Oc>du_D;{+npA@lZ-0|!74?m@}CujXt@3vg?#puB$o1^nieEQUsao^qZp95!H zKYw=E=MP1^cF641Md7z?yQ|^j5-x>GhRduDcOU^HverLk+^Ghn%-v7+sE`9yByH6h;9XYx4os(vt_x7(3eA0GP z!oo{#-f-_<=Wk7X`Msal7qv}z&T~rCvr&!pg}$r)cG9@lUp*wcx#O;vj(+O+seeAH zHd#vcHI~=KDy(( z6MQj~);xb?&za9;*2UlZ?GHD;v-(d-9}a#qsp89=QG*V<#INtY>!)cunkyTg|M=U_vTprl!us&{x4r7W^`Kc#**rDd zGsb;)?Z}eN^R6rRmcQ_qM%Sq6xu?w@bI;(bMvZ>z)&KnM)L+WSHBPPl?w1#8i~NNh z#W#+f`BL~bwx8DS@0jj-^z)d1?YzJ4vy+Cre%7d=C;v0*+vp$9o_TQoow21K{BXeA zFT8)V`O`0J^6rfOQ{#xgEJ+-3-sbxXoA91__p!%6`|8zi-IV0na`6X^ z+ur#mF6ojbJsd;Mtuw`iJNOl@9i-WgmGcQ>&tynrY;G{| zJ{tqqP~3Tlrj24l^?9g;{Q(%bhw^j(VHhKX@bmt#(Du(_dJ@Xd_ZIvf4E{se|8r<) zehelvq3l0g7&@PK93Ps0WD(EQ<3iiJQB9%J{n#RI<1PGuk{;Us&Jm&g7pI1{Ps9W( zRDOQ8h}+;fq5Z^Qd=bje5R3Y~)1tgf(cVI}lcP_-I5I^0c`q%r{j(PB?Hr5vbXnB< zV;1dg)#0Jj{nnzs4zsBD9<-}a<#J(pB2*l%01tIOj-G|V3hKj@M z7WH_7MSnZgBHd~W|LNe-A^PpVTGZDG7WF08fI{Uz(V{&xTl9M+7VYX&^uwXfqj@Pvn}%9c46qa zO`ab*Ki^o?*IJ9X6KBYD0e>>O4Kb;`-QT zQLYw?{^4DV>xEcv40XQv4+)*0E(=~_kx#L99LoPP3x2JIpAL)sA7oK4msqs7zgx8D z!!6FozgXChwCFb;wD9wUMZJG)k7n_0i+Fx-ah-Bog%PsnuM=aw1wMBc&wP;skQ$xq0YC&i|-oj5B&eKr+*vl6ATyJ5YZxR2OE#kSx z6*`~o7U$#77T3WWEZWZx7Tj-ct}l%i?dk@L zbPuo?5BM#{=R+;Zm1mLehl!!jizbWu{j){6{KG?+cY(!q+Nq^TpuS}@GC6( zrDrViUt@6{+-6aaUJL(UT9kL0MSO0zsF#~9>K)B3WIK7qqQ1`F5W1aQYf;`~E&S(L z^fTglqEPjFi^X~R@`BLqWR*pJ4n%xH&3CSy6Pgbh9y&j3EXFN87WsMJ!q03AeyK&h z*ITr=zgWaG)1q9j>F4QiEwTv>5-*4Tucm!fDb`(wYjyGHF!5?r{53pODR|2;X&;Yz z60g*?BK~8v;?W2!UPj%Wwp`jf4wHVwGnwM`fnJZpwRUmC7q2e;Urn1nM%w#_2K)bf ziKv(1n*DjnTa^8===Vf^ns?!Z#VcO%SWJQh_lHaS_Z7cTmCJ9J`MC+#OYu4*Mf$fr zD(&q$)wJf)iq9*D@yU3vz7ly=|>)g=fY-4-Xazr@p?}4|l-6}pt{NFfT+BZ*;`84d) z$4T!0MaJ!A<>%7_m7n8fezqzekAR5yH#{x5QC}H~x3@}OsO&!~QT`7Nj!%7_F7@;X$NTDnMPO|p90lBBUPM@db}QS8-?dj{PSczN^f{}@_5-!9=KkntCH0=tMj5kofi#8x<|@< zcF&g{{E8>7lDy+c>BsPYE+*uny|t_U%7}l)5z5b5(y~MOSusobxlZy(m7zOT|6|ji zvd43;%KowO(!TC%8Q?n<|0GHB$a?ALA=MAm9w6I;c97&Y`KFD)JV@j-uTBD^pE(rw z8TEc|f5|Ub`I&x_^wYjY@?TWCuN6squUNpxOS#vsyI8jK?PFy8jdmVgBe~;X$^H6K zxL&wbx+XvOITarx{i7M^uM2H5Kg}^R#X)kn){rIb8^%ds^yljx(%#(v+@QF*|9L-G z`I#jBJR_6UEI3_*4!ZNGnAjVRlj6Y{rNqLM;xX6 z&y)7&Dt^#~vfbv~B>kh?(O)m0FZuh58xLyTt;%KY-+DaKzozw@<44 zo6q+xD4^)y>YkN;E|PAvn`g>&+c!ymg7SZb@^2d}+gp^fzXbCpQI9EWq`gs(CHd07 zzfE%E{B4~p?em_L{3ccJWvC!=-ML6Suz?rCqQBOlqZZ|AQSIMIH&%@Y+D-X6O_kTC z`n^TU&w@Oeu2=P+k&54hdLM;!-@QSmJ67?>Qe^(^56gTS^}F&^$@5gX3_lJeB;wGa z&X*IEpXFZ3{f9{Z#fm?o+Id~HL1d$oQl;NPA>Mf4xv4{kKdF z_OlQTTjVECop;9hTW7>gjc1H_rj$y1uj%^r-3rO;j+6ckKgX%|sa+%Ud5_9ZC;DyC zt~678+&En4IkLh>DEr6O%j;>E`ks|v@gXYC4KGXoXa@Rg#i23|r}<@mjQnTk%6xXK zI2-M4vAT}<)pgC_CKmGyQehi87zvO)}kiirZ9vyry#9qvr?hQ{_KK*=MPG z(Ts`+pP-M#QJ3S*Cl2;+s`H`c*qI;?{h)^rMZE_C`M$cAhNP zP*twUDnAdZ>xCvBM8wOl|Ep<*$gtjS&y;>fsC461Ki2M)TvPlM)oxRwWd3_p|FFR= z{nV-Jj*-t>)%Y!PqO>>ic^T?moYxL@{u=o?Bu@IttCHy=y!z{S)t}o`f8MV6NSBOT z$BWY5XeaMs+@i;GrQ{C{l?S}4#?_kYho4b?N~g+n8%~qb*zV*Qx7;U0pAX_!seUHUG;Zlcx?;RtXX^jYTq@Hwk8f8klf3R* znQoqZ(>@rZ;{0D3un3j^BhgMoKD!r6!zjf+I!ESn>jZhe82wCvDzEwavO(p?d_6tF zsnS*Bt_W4$U)8v`&eY$&rQ+sS?ca!78OEO?pUvOM{I@ATS?YY>q|SHax-b-h71z__ zOguvMlaVT2BR@wRB>mep8HZZse?^&!kLrJl6~A4z6Pu}>e6HdjY2v@AakyWNa|}OU z=BxTr_C|iz=E!tyrt8=7IKf4~(PU~5@2h;an69Vw2#AQAO_euA<^L;Oxb=GfkBn!x z;{T12JTF(q!I%%eqViLxuJ1-ZwbP}&*K~bpQRAx)(>O#d$cTO^aWq-elPjj~PW6VPrs_RjAq~s{3{(4-c+pW?yt|MQbE&aEvaf>l- z+`2}^!L-h^3*{2+x#=d^{}^$2XPvZ9HrZdQ&fjFy_;9CcKV7Er&*h_4c~$$*RsF!E zk+Qz>Y_eQ-RjxIO(%yfSYT9?|{E8eR$@|LxkW6VG`B%w}@%B`8 zUVp9DVJ0j87f+M+4eO-+J?PiO>o#@$%3ChE(Qc1W?bfT#3!~kRQRDe8Q+)oV`Z066 zJ+e}!+iV(VrbSEc&5-FD*O7LwI!5x2QzWUA z#nsAZ%X+bi2aWLZs&UA@D$ag&VN{nT?RGSH(S8nB@tmRjM5^{2xmfx!t_#amd?HnR zjQ0G}X)-@~YCXq@=ZOiDr)-pdjP@}02+7-1B=1n^UV`h6xL)UG$?J;>gSMYK-y<8O zeZ8{JzCh-G%q=o*=+^YtRk_l?X6nzg=1E>BZgAk$uK%lP2d7EySK}F@ofjMDooW7f zq8k7B)p`Zo>aPt^(oc7U^k1v^e=e5iqu8@QZ{j?t_ zf_>r1F^{WV+FucrFXWW@`|%KY2HWE_lkb;(82kEZ+>_NSr&2>+UDCw}E8 z3@4^O&QbCFUhxSwRbOgd)S>vD>b$dEEz>p5yZ@dk{p5|6@tmwqu(MDR!oPQcwC_-U z&UC4M-ZYO`rq<;e)VQ=*+25_=pVuV)T%>r9>L0wSzVZ~mVu|$MZCZCdT=}v8B{)Cf zWip@brt!>d)y{3>Ww{Pj?f(c|fA#tG2FM5cgA^?sCcuf9{-I7EaDKU=3n!apPSV6w@zKS z7AgKop0szUb!&<+ogNWrp99t>i2Jqc6G7phli_vX^gU;G+X-5Q~g+r zYCrL+J$qGqR?9|OM2&2>k!t+!SAOnOezZGeKE-nb;uWR(fs|45d>JdTwo;Y1TV2O} ziod>I^-JnHn5_77YMj=wRr*JFs=uDhm-%m2=S7|3@2-?_?l#@mxBwS!(cWyTeKsij zdNt08bV&bR6^A5s-9K5y&4}kxoTsAwbmvI>Pn4h14AoBlCb=;_zxO=ZZa1mxuTieA z5Kqw$`%UXYx1S;XitSS6-Jtw;A0zA6IPaoV`*iG-_I?%59u!|4&f-O?Cci>U!O#_%nIZ-mk_X5sHsVk>#y>NTyq;cmhsvk)H-r|M2L6 z(!O1-QyJxIM?WUokKO7rvtn}|)Ciy+e{y!?79bd`#+@W|5 z8n##u|BsqK8smh@k||V%dX<~ zk+Qd&>^G=#b*SsRJPPxV6zRV~t+REgbgzh${`0D(r7`K)Q&)nSa! zP5cCP{yNnB*RRq&LdC5?^-D%O)SS*0rR8PLN?(43&*{{hnK_G{h3*RX3QwiaU6HeR zZb^BWJ15^&;+FeD?{OAX=R1o$W%(tZb#BeEHZ{M}z0|eRUEp)(to7=os;J0a;mmTE zxUo-|to6C)R8-`z?X>`?bk3>F_EmVwR?I0Y%vQd1o?cO2D)*>kE1dykHdblQO|L2| z@Oe-?11xs?ipvX~OWbSVWp2K=vZ}=GobUEI$~|Q$F2P_EUVh)azR-jFmps z<12QQS1v6pSv#jSMLfu+5gXCK-IFiceZa zg>x>VDsnGAr&SlYy`t2M^L+)yZjl>-)7?R&d4(^Cloh(G8OT^MS(0BGl=_l#AN-WKOWkO0g>1QW zwY#FIqp#(N|~#?s;qEPc|m>& z^JV!ZRY8W!-4*5YJgYsGh!7ddMkdaloQnJcw=2J3l}uahKt=P8^pf&?A5QOiO~#ukb#t}5|)yd|Qq>NQ3k1mx}p zS?REdgKHoc8XY4nVNomrlO;<@Fe z-hBOxRu%+P%gZTV=xBnAs(`shVe;x1-icy)he^yXIHt)3f#`Q`Hg@XgndsVZ@`*Z^ zM>vbnc6yQMcvI0NoEaFh2^-N(h|^3Jv{&mH?KO~@mpdJ@MM+_l1eXf5LDZs8j@|@! z;+*vqdGw3CuF(|~inHyMGEadR2+gUSlRY;xvp4Jkeo9Vya*&|_yV(V5+&B`|fD1Dn zInOOpBG7wg8Hb3|G9+ADQ7BGbK9+}+e7wwAU{Go7)4S|4z2DTwsN`z_29P9WfQ{o+ zR0GY;X$(wp2(DacDp_s}peivEQ$3DTZxg%Gr5M!cHG*sutp0SXREKOh0+CN1bQrenj>O1obFltgD|cY@m1R4si z6zby>rx^U^2rKlR@`@xrr{|Ycx>0>qxO7YHQ-d23aUCtee1DjTdOI?-jiq-mnZC+g3>fSwxV)xq8Si47z7%(ft z=ygd#nrDT(Y{uezZ|0KhSZ5*z_7$G$%)&*Uve>jm9J!6$_pL0b?xeIX}NEmka7+2vIJ}cZJ_#r}( zumXFFJSAurPJKAMd$baS12)+$mAH5ewF-2q;IJj_7B-6}wj>*-Ap*AqVMD}b27(o`iOUepb9%%pP=_7_ z%Y$HLIc{(Ozr0A}|6(u$a4Oon{ zJw^I8dyTsgncpo2yA=WFU?D1XbykiuYhjKZ|13cQGcjuNtSED0Mwb)o%!xyFi`rg@ zer2W$9Z|VHwa+hc<`)#WD=XvI6zBV7&5NGLIZupW(6B4rnIXCwyYzW1ih8L!8~|timMR_ZBH-a#4fvu>duWl2C;5>OUYd3I`WS@v1>0)a3M5cb@o;H(sVH~Naj zftj2bd+6QS9(yhvjKP9DtK*!d=z!*`G7mH-xPWCXgiqNDdc6#!`$5^ni5HuMvSG?A zR)?IJEW0awnG5tiX{+~CK$xLL;zHzInzI+PG~jTn?1)Y@K@WHOUd)vYy>S8>q0bH) z*NLlg$bh2K#J)a+G}ehBMaYnFDCabhmHpXO6 zd8IyPi5JU-7=!8~)@)xepV!Ov5rp3Ch`Ej19_pk;hlsrSiYv<3z&B=aqL~WE*nx3_ z+)+}#0&_RFxM|>6i1{IQimSWY=`LI0D>m&7@@X23N$)c;{wT##gU>B=4#t9kf+Q8? zdrGiQotmIe9>vfu2MZ>#c9BCLCdVEzbJ0<3MSj@|w@lq&afRh#!O{fFt9;J#BByR| zSjOY(qTf#lwoSl-e<+^lDO-)<7NS(K0(0Lo%${W~LJii`zGRW-0?gc%4%CVPdaFc$ zY!UYmBUrI-*^*d99U;kgc~-}Y8mRO*^#w#dDCk^@%Jo<+`z$)N2xx(z5bOx6@hdE)n+5pt}UFf>N(07W_2a zb`xvxrS8%K?^^LDh7aN$GhYouff9F_c&jKVuFzKZu46lw$J*r*hFEbK*t!Km7^|;? zh-o--Az~UEC%hW#A&!MJuxbH}mTq)zl8LdYxC#cYqXX$K^7VTmX*fYef06C;mRK*d zSP$oNoMOZ#x>EFB$xg>Ybo8pyR#fFzpy?N!UFE?ls;p+oD%9=j!jf{_kI@S8CmKW^ zV(kSbD<-x=a|F07<*nNR#Zk$L`&K>o=y^B2h;+R+5drr&3lrd;oNT2ov znJ35zj+kmziZ$pokEb_5!)21FC3iIzpPUuw7d&O?W(TxfW%e8w8%X`^Dx5dCQ(9gY zV$tC@R$6v1<8CV%iE0^Ww*{O;xn`5*>FeBJPgB!CTU9d|bBR%H)~(5Uo$vpmwGg?G z5u1QpYMwH=`YRsX=+o*&8fr?cdZgh78CrcmT!mUD*sIRw#)%T>%cbaj#Nww|jtQ~O zB)S6ZnmNyn!K+^K9CQzX;+RMIyXRb<+HypNC7NU>CT6&CRD!WmzE>^73}l3@mSGlR zPU}ct?I_e|_M$h%s-Wm7(A}VCD)7Zt`Y`iL#+(t8PG7mc&V|`fF>c4{pM`C*xN### z2TrjAcLjtGTxD^CHXk=l<-S6Fr`m%DIB@U1!Y%Bb-g5LdYxQ)KoZ@DIPuzSr7PuF= zu(E~K8S##lWASesmZY-K$BIbqyQruI(bWIjB7z}IpV#Ryr(f)p!(}XQVbY)G5VLvx z(j_jp{qQ6vYk_4oj6S?+YWN-OWS>o@LzV^eE@S=VkIF`01EDSpp|V|wiI!;G<_a(l zu}(saZTI!^=I-4T`UqoSX1P{3zy(f6z_qa=7;;gr56e!miD;tUD)czwSt7BjmARmI z_Dc%|eQ_mfKzCJCfm`{%-LUEV9Wvuo36bBdh3MKt<<~goH@q9oysx7~V}=rP=|!Kr^kLyet<_P02bv8z zp4e@XPL8hjJRH$)w}=VXA6uMI9gdp$g)Y$UOJC?02ewYC7QMv6U97%vXRHkyRj_+n zGEYViZfz%*%glDF5z<N5|68}WLjnU zv^Z_i()rGu%*AQhIdc{}vb7~ko#|O~7N99#R)q=HOPtQt`OXqNa44>3v2hug2d}|HS2>;nPqLUvmf_(%W35U|{9%*5CLg!| zSLly9&A^8==@RvTyA1=LY6km74TVU}SVf3;~;foqgl zckJ(KOPby);!AL2Ia4gpi{7z!DuO#~c5xvIk*0n%H048|!JC-AUSVQ-MbnMkI4r-G zJFBsng^9|53W29>axiW3II!STigljkpq8FiirYu}O3gyfNqk{dsaLGR^gn1KAP9PY zgB_3WOBCv>T523V;93i60vPM53KVzBxB`uP95}nsWnszJxW`_hcLDn360K(@PUGI& zwtrNfjC1>UwB3G2!BdUfu3`yL4CCcf4+HAGf|E^?7Z+nrvp4-_X3fF8e_=tEiV-re zH|^ls7LNePsW@(|EyWqI_X~)O#Q!hJM*{MJIPCiZCyD|)3if?MNg^T7zE39^=@jn! zWM=AdLy!9hB^4@i{q2}>mWkPmSA5YRtrS-f{k{WwiDYM%3(H<^u|nGK?q2lE`m-1rQ?GsP5XD$$3HJ<5P;5v;dXV)@i~T;TtB#fkg= zlu4>PJ*TL=-;DSFo|0f89CyR>E8SM73oeytSG@tpT0TxTaW`C?UI8o?V)eCsv%ROR zFZMG-GAz2Vs5j_y;iL-YnUx!-3@gu9<$cu3`)P{jJwc=c`3e6SuMYR5{#i0GCBs{V+dIFrkTX=h$!VT3f2WA+kMyf1DpnyxEe2wQN3PYhyb@LKEc8_T?i?kF z?+_H=d&#kbIfZWMZGzu1(ATiq+)lqnD-j- zcPuOpR6#PzrY`^uuwcDO>nlm3NODm}&ttNvz!Fc{s^9B;COV3}(a13fiN(?b9@xbL zVd8Ygmv)lyl#bqm=xY?PNGK4`XkiZqTZ?gK6}rpN{1AM@px;ByII#%e#8)N7BV2*S zfB`HgBvk0@339B;$0x`#$urGWRb>6}%naD58x@{-Q9)^r0{!lOwg(N*y=p~Ti5{iQ z@=Dx)cCSJM5tWR+K6gpU3Uz3?7%-^EK}&IqJ-b{z;aOgS+m~<<$dEg~)FMNAcL&=U zfeNv*3@jbQ8of%Pdo`Yq5w{7%nXK{!XR6Z)?A9x9VCSt~aBpeH_>=m0#6Zw zi}Hqwei{}9e>)RcT~*&A6XSdl|E0LH;aM`b%tqXdQan87#`4j2Wo)wkPi$QLj2UqWGt$xudP^M_kI{V*zK?@qb5-)6z=yuiuDo-o)DRedGL6{fR@>{06-GCDvw46F8dv>2sO1 zparNz44(2!+=1s=``?qGwf9b)(n|Gv-|b-LiqlUIX9vv_7Zh`AW|+8{_xiy>=j44|>L+1p|D| z(A?g{HxKvDqliOiwGqe7jQ9XRKP0KDQGy@Cto! zudOK6rvw$6K5NxV^`Vy-nhFPAIlcA@t$8ajt<}WfP3$s8*;*xLZ-tmu`;5s=fatsM zOnQZe-6}owYh_{@k9S{rp?oXRuq+{dECT^B)-Pl2;-04b{T|~xoa(Nc+$EnX4Y?~@ zzr$zV6)PNy-}i9mmznnI_fKPEah1j@VX64FmpzP{tiFn$RhoszpzsXjOp%yF_|w}d z-w#aClNo3NdvuQr!#w+WJEWt& zB^ehgMsa)T{yF^o(XrN(G?o;8E7ozwY6rJSeMG{2R$qU4Vz(O5zmM<-KO`X2>|5b? zf1Dsr{#1b}9J@bGpq?9HJ7apNSc3lZA(@MC_Uq?dy!c6yv>AB1x&L=`(o7xH-t`?^ zme9WAX^l!e7mSlv|FU48GG=*jUs6s$$^)MsA*;sp2sf-nwtJ^X_(r>4guVs$56DJv zG?K(6BeTqBig1#69?DZtiIY@c3sSAkz@|o+ESxNV$d$1A26Pj;mdt& zT$%iRHY|2jsinP8cKYK9=+BJHtzHWK@)F8AQU59f)`|LPKU1tPSmr>EK4Rm_<*&J6 z3BR<`SnHHab}H~ZSi!t};8(ifGRYXn#$gzRVWrGx==6EmgKvXk{1d8Fas;%8-Ld)l zud3>Wm5tHJlsx=5>P;E!FDV2h>Xm{mrIQ^ zijM5t#S*0YE{dvcJzG{SN8jl_TjVLY@#{PGO5-p*>1!lGl~W?_teDab-Sg{TYKpas zP6VwCzju|E_In>;Q_<;rdg3|3-#kt zZjeA<*x zJx^iSc#i|~fbnleO3&e58S(}a?2T#v7hIC?9VRTxiW_?vCChKgVdl{LWZv(-wPwta z^#Qv6kZI6eHvQ?+;K%L7)3@@A9Dy4#_<1)mufb2d;D#)I!XJxGG%3d~5{Rel)R*ex z((sJ|)687XTJ=>C-0IVxj~(zzi}=Y=S(@GjmwBcImwDos4fTg=)3Pw@$E|r3+AG%$ zjB@z$S7c%>K);V?{C?E$EheTd;-?72;*TumK&E-f_aBsLy#?!QGnD1PIyMCw1;ULl z@#rA^I4-fht{frYZ)Zd^#nlnPDk>K%-TNkCW7%yVc~@(9efLg%#6E2V{ZD6L zji6uY?9E2dpM?A02>Ru{-;IEJ(0$qn`k&6g8bQC(*_(}^KMD805%kM@e;NTV8t>EV z!9Wx0cQY73LVKwl^grc(HG~1U??+28rbzp;5ey`a{?>m#)7U#z-@iorQ|tZo+>Z+H zy@9wdYkWY7^ta0Uo5weU_X$rEBuK5E?rN8yw?^O0q#rHSa{?vTG zefL(q@mNgo`h)Q_N9Z5(LG9x`vPAL6}P&33#@-tJMdl7IIJAWZ-DX-204pLeRwKE z{ALNBxxtr2OYlv@g7Os=`QBm=9>_%A^<^=q2VbuifAu19B_1zPzc-VH>ZeAM;KVnY zD)F0knc_PlV!>PgcC@ULB=HluSi8Wl0)eeo94uD%i9~P0El3^D%0q9=s=L=oYjq^o@!Tcjkk05&AH3 zuefh^_~SNx$cDH_+84V4-mdG5YpYvQeK~gD-^mEhMekTGD71l#c@U0k$TO;^GTy!Sl+lHovVBHlC!Cx#2tONG_xP7s%r?S*n*Zo=U=%?%cOrrbl zI_TV1*V{f-(w-yI+o1NY+dzxlyMC!j_t|l_WshsxLp`o(5B0c#Jwdf1DzkT2=&sYM z$KAtWy*=(8?NpDu2fN-LcMo>Ir^nrc>)-5g_i*eV)Z_N%qW1&|s^LKU4#Lztcjti~ zSNxHQe)hQHkb(5L`roq}A1wsLwX-p*}mX zC#dd3L+#xay3hVSo!}l^|7It+hhzVsPOvu@z3nn6WPxTCgsD~R&I6qw{zy(=&*T2~ zKK*dr-`=MmuKU~j^v!ip3-0?_*Oy@T*7DwU8)znb*DtlRzB<-_3m;$I+3j+OA40%i z?M+*qhLs2X>Ztz|l^1^l%emT9;ltmp5Wj+rxw&&vGo7*1X3$6Eno{7;)8b;a>EbUmP8VOz^?FLmebar#9{jB#JjLW&J3YT3 zzp%V=dPzS1Y*S+VbQEIN^s35=>H2R$2&vI4O#d8CMAO2xLD2gvCM<+D{uS?owJ=x- zOAVjIYcOcQQqzX$Oza8vEr{3~u0_a?I4(TMMx-9_u8j0F#pi%Gk*6WxA|*{5s{gBL z!_>Rr!?9Ps0!IbXm3yRxv0vn61a=5IsP|~`Sy;%;@F|WrjuW3m4ulr_!&C|IQN4^~ zg(tBMLBx#MNfQ}$@mYEm`H(M>6Tw7`#Y-G5-}SfN&j;wA24laplTj2<yzaBZa6rN6>-&tb|=?w5On7nyJALr|Fync{&eT_ZmGY5(uP{}+M( zKS$u!4Vo5-v%rS!hK<+bbU#pg9ZbALxi`~($CS0hHJoSf)BbahGanxjbo`@qy!1af zX#exO?GLB@L$x}!U*yNza|1ev1GG;RE7tW0?K`Dc>w35rc8Sc>r579x`(fHBrStXu zL$!%Yzj^;ETt0?q)0D1y{eF~he{H7HzN4>3_diHWSNd%I_%JOCTD+=94bk7jW#^=I zXYZ$LzlqzkB(F7bui|wk-mG}NiFYgBVB$?GUE8t2`7yM^#4k#hSIuG*ub(H6_nLT} z()A`DnIp^9Wa1smByThE_vguU+f6*OL-xsCCcbK}wC^_Yj>E-uLenCS3oh?!Wgltc z-AU3u#>CH6_I49*nJMivO#DJ+?=W%y@zTE7#5XE?uZcI$miDzKew(tdGjT_Xv~M!; zdz5{%i8rT9`!*AQOxd@acuIz}?=tbHlzq2}dlyRkh-ty`|A(@VG;w>jw2v|IPGxU5 zaqSdopJC$PD|?5Dw=a|S#U{Q>*?UdAW4W}iHSwXUeb$+{zd+hInfM{fzS+bh-O|3p z#Ea+4_S|FQkSG?H7?@{sbnz-So+Qbb%btXPq<)_}n9dD>O zo48l;ttLKE`DronZe`zQ;`TSC{|*y>Se2{G#0@{)CT{qNhzqXAqg8$)O}s^=Yd7&k zWuI)~hJCJyrz-nA6Yo&|{U*Lt+1Hx5Vc%rprz`tr6W897acehmx3b@E;)Z>XiI*vR zZANh1?8<+HiED4mbZsVnuJRLO;)Wl)i5q@0O#D*i$6?~lD&1TY_rD|a<2CVm<)_-j z?SGf{eiQd9UT@;tR6A@iac#Twqs0fuZLLH04^bxW9Vz?sb`$S7ULJ2t2=>z+Dedb` ze4|(TZ#HplnHv9?c=v4Sx7);1PLez_F*x0nQ>7o9iRUW&ViPY`yxPRO6yIv%+7?+Z zds1+^-&V+SWte!2OXkOG;&}y^od+Sv`P28sJi%mRbleG7mc#Goo zCT>@Ln#?>^=BLZVn_rOin>Wi;-t%O9s?GdenV%jLKU3Lj>ijUS@7{k%`v?<{d{1(_ ziMPy^`S6>#P36-#{|x`ee4)!^Z_F386N1ZS%oid|+?X%eOx&0+#F)4-Uq~@=W4@4K z;>LU-&%}-SLa~V(^98?&8}o%)6F24y4JK~P7n)4mm@l-LxG`U7GjU_S&|%`ne4)$4 zjroFhVsQM8`9g$=8}kL5i5v5U7!x<<3n?aU%oj3D+?X%qnYb}uC^m6pzTh`;W4=&p z;>LWT!NiUELX(O2&KFGl^IUn})vD`&(avY6d53X*FnC_BI=@u^ZE&yR#&yHshJA*~ zzC+nNOuX(i>EF1X7=HX`N^V?F41UGgGXGwapN2D}eXWTb@vJj(uT$DLnYam@_xRL)n6VFrj)h2G_-*4hArP9A~ zJu%X4xKZ+Uv%TWRb;fKTsjdSCx8EfFM45Qq{gNBkAH&|ZO>*OUVsIlq$tFK7PfB}- ziNCW}#xvK%+m*f7#CIzDY7@_UO8T!e@w-+1)|+^DtF&)6@%z`w{A@MxmS?1WyNMh1 zyWPYao|E?7CT`SkkBR%Am-cpb9X8@Q`g)n4WE1zkBJFcce5)#No{6`-Chh$uK1LRDK*Lp7M_L?=|t4l>cfI&-=TyH^w7IK8^O!X0mTr@=L;Fd#;O!Q?%YrA53+=z%f_GW) z@1gupqx@@h{xXlS;E@(QiukSMzsZ89P<+_lPw@%j z6d&gH@qu>8yxD^LDL!m(r*_WVM*07d%GGSaGpJl_UrXf*;#4l?$&`QQTP=7km5c3@ zsa(usDF63U``>E89aJv1ucLA?PoaD=Z?WKY)Xv$yj@o$;r}8pSq4F}fQ@PHk^0rv; zTq-Zy*Hd|eIMpNb3@R`4HVa-)abWv;iUacuDlhY7D%U;KZu6*I%p0g&L7d9P+(G$g z-fqDgs9bE{K;;VJRKLs}R9@yORNj-Rev7HR%$umZL7d9VJeSJFe7gm2qVlqR6O}iJ zQ+b)^QhAwYP93G{Z=Y3^I|F&^DYa%mCDQZTdBN3oXX3*n99pMm&$cFoxd$qt{_h33gVQ{ zAWr#Yo=52}p>&IhS0M7n_&<{J!`w^ugQ$J_iJwlqmbiLkM6cgSia+x@viDIwqsX3l zJ=w3LbZunMyn*a5A^RAzXWmBkrDWeu{Bq)5#8ZiT$v^XMvcH_lt5N@U7x4(}$zC^JcQYnEbR6Paxhw{6OMe#4jV>O?)Ep9^zw( zYjnPQh({3LLgk7gzL9tg@dL<@o%m72Q;64*pA6zRGpGJAh*N(U#Hl|F;?!?5Z=-&j zc@)iyndeeI521495r2&GUrc-&*?Wn1lYKSupNY2-_YmJs{7CZOO}vVD5AoZ{PXxtT z-HMj|Ht`3@K8pBq;x^)65RW0Q9v##D+lf0VpDD!W5zi&QnEdAvSGVeQ|HZ`BBNsaN z5>F#P)x>is-8$lH$i9tu6WMPkeh~3);wKXCAwGh5HT5Uz(JMXwJ;bjj`v^KO{!ICd zB>oZcDB>3qw-LXHcnt9uh}(&0QGQa0A4fcwxRdRZBdQ_)6kY#CK3WZNyI{`xxSP5VsTm zmi(j;FDCn3;_A^8y&dKek0JYF;-`~;FY%SctBIdOe*DDmB>P(8*OGl3arKC;p3m*X zpCLcp#AlJ89^%bpA3@iVd&oYL_-e9`B7Onc+lXI7_A$iOBTah#?Zj^>nrl7UC}AUh>1d zjqGowa&0I675V8VejD)~;`frD2uhcEHStwsUrYSoSzn}}aY zyqWlum;)jua1Mwq?HxYl9 z{4^7fA^WYwk0#zm{21cx#4E}FcH;L@d^(69L%fUlJo4X7Jd=12@dd=S!vpt&vWQ0z zUr+grBz`K{M-jh<@@XT!fOrh?Gsusf_?g6$iMxoW5O)*LAij4zKM7Z<+GW11KDpS zekbu3;vJN38}YlzzMc5}#J3ZFgm?$>Cy5u+eNyIKWdA(bcN1?T-b4H~;u_s2eVup& z@i&P_5`UX`6!Cu&w-N6m9z*;Fil?1;7V%`_ZNyWE???5UK^$Kh?0q?ihY`;ueg^S8 z;_53#y02p5HDvE4K8AQT@o~ic#N#RdwZso6`#R#2h}RR3Cf-1N1Nm#5Yhr{lpLK^{#2P#Ep9(Vs{O@nqtYiKh^sLOg@`QN$g@qbLr!#HW&d z9`R#|7ZWchKVIUu5U*xVarP6(*XVm+wZy0OQnY{K;pD%b_;j*wApQ-d+eF+>_RYlq zL-t#V$C7;u@i^jb#Agt1Cw>$8-%dQ9>^q1j5bq+MNW7c)42n+=@g%a>q66(enRo>8 znZzTB&mta0{CMIv;+2%27~&_8y`A`p#FL57CZ0n4B;pywQ;0i=&mo>mJe7DJ@wvo{ ziKh|w5}!}Jns^3rKk>*P{pXT>1o0E7-9{2$ zPWDm67m$A&@zcpZhWP7bZzmo!PbYpB`AH$}B%VP$kGO+)KJi@QnN;39;+rU+#l#E9 zkC%8M@oM5l#Qnrq5U(X(OuUZxm6V@);vTYZAik1#6Y*8Vn~9eY-%7lccnk3|;%&ss ziMJE?65mezY~mfnPowg75nn~Tn|LMp=^^eTu1yZK|0?1U#G|P_L=wM|cogx~0c z#QnrCBwkCrhIk$E=P91`#MhI31M!Q9HxX|jKh4B1Ci|_#r&1hRh_4~uM*KbU-%dP& z?6(u&KE*OPrU@hxQU zCw?^XTHx$1~tPrRP^4U}#J@p|G-#Q#jZnfM~g&sO52h_?{mM1I5HOAlbJN{~zLQ#2+HwPW)lw+leou zbUTRKDE?i<)lZx0-nxlDO8$F@ZzZlB6=?sjQMwVtA0zun;*S%LBK}w6HsZr5|1rd$ zAbUIUzY$L+zKwVa@yX;rgLn(sJBU9`<;^8tN<5EvEBPrV{xoqf@qdz^YU0n3y`T8A z#A}H^N4$>s3&iV*zev1+_*;~pCgSH4Zzlc{`PoYRW#TQwmy(}0;;)c>JMmYEZzp~( z`RO438rgRduO|C$;_YPLL;MZmT1=q*zePNPcrvxCNaF91eH8KS#BIdiB_2b34EeVc zPo;7t6aNSKNg@6o@eJbXr|a~+4&v{VeJ=6CDL;9{KOp;J;vW+C67L{hP5dL`e&U_P zYl(kMypH%r%4a?CGKyOR@lVK46Y+l$ZzldJ@vX%FO}vHpXT;lxe@?ue_=S}J?Zn@q z{C5!l6Y(zM|03Q^{0mCAhxnJowW9;=|3Abdh<`;qlK9ueqllkO`LPkdk$4R8e2Rme zcsKb^CjJfa6yo0!&mjICaR>1mDBWD*-;;eF@gIm66aSI8m-smHUrqccviB43Azn*- z3Hhlb{wc+?p7?mOZy>&d{5KJ=B|pu?e8R9;{3cpH}U-_KRv`-h-*^=?LVA&1aZD!97+5`vX3IZKXDuJA;e>dJBZtfzd}5j z_2X#B+%cC!R-q1o2|x2N3rXA4$BL_<_Xz#3PB<5+6mpj`;o* zhkD|75pN(qn*1~opHIA*_;})5i62C~g?JS4HsZ4>KkdZNA^Yvb4<_D0d;;+<;)f9L zCVnXK9^w_0AMKbx`=3bm5yWl8BZ>bH@hIX)5VsLOn9_|QKAG(8#E&GNOnf@|Ng+Ok z>@$cTMchF=hIlUVsl@Y$A49yDxSjIjC4L>*R}(*$xS#lO#A}I9BVI>*I`Mkq7g2s1 zh{uwB6Y)6W&BV78-%8v~{#%I8Ap17ro5;SM_(HPZPCS8l2k}JWUBr`!cN0%0-a~vQ zaZUZMxOo2O1mY3IPb3~m{3PO0#8ZgxJm<;HJHxe&xr4Q9cb@Z9Q%ks0pEh)ZcZX^1 zqkf&gBeL_Pjkd6f?@Y9Xzin*T*F7pMWk+O~rtj1BVCZPl!=O`1kA!xS9t~YXdOUO^ z=?T!Sqz{MgBpnSMwqGFqDbUfRr$VQao(AnA9S2=QIuW{&^epIB(zBsENvA@Gg$2@2 zhmIz_06LZQ5@;9cEa)22%b*)cFNba=eHL^lX%}=@cp&{E=xEX_p;JkhLAyv-K-Z97 z4c$n39ds+{^PxLQ*Fc923Z%aQI-2xl(5a-agm#g>8oGw`_0Wx^H$k_Oz6H9IbR%@w z{(Cd54Nq+_HBK<9N4e1}D8%h5R-Aejb z=uXmMbC7;SApOD6(WHk#r;;8C?IJxIx`y<4=tj~Lpj$~F4&6yQ8aixfApI%O(WIwB zr;?rq?IIlqT|+t%x{>rO=vLCRp*u;ZLWd0tq@NBQO?m-zD(NNAF49@hHKdn8Hw~{^|x|4JbblBKH`Wv95NnZw?O8QD@7wM~^Ye-)Y-AH;9 zbSvpwpgT!7LWhkDq<E)? zN0WXLI+gUR&@R$%K-Z9d2fC5;KcHJle*oP{x)VC=pg{VcLPwMS96FWsSI{of-$K`r z{t>#7^v}?(q<@9(Bpo&v=|=_99}FE$dKh#n>5GPpG zN!LJ!9U4e~19UX$%b-(9UkU9ZeKm9q>Fc2zNpFH~C4CEYC+SA$u)_lB-vu2_dJA+a z>HDBvq#uN?A^iw+Bk9MXTS;$&?j+p`9d>vi{pX;gNxul4O8Ql37wI>kYe>HX-AMW$ z(5<9DfbJyS2^}^ukp8F8(WF0zP9^;nw2Sn&&^4rggl;7LGjuEIU!glmhs{I!wm|xW zp`%F;gH9zq652(2G;|H=@z9N=CqTE7J{-D}bTo9>q(J&pprc7og-#_s4cbLI4!VYP zB6K6^S=tk1(pj%0w58X++20CnVApH%{(WEbfP9=RMw2SoB z&^4s5hi)Xj3A&Z^Ezq5$8==FF45WV-bTsKL(5a;FgLaXA5W0r+BhZbcABS!wy$!mP zbSre<B8=K}VB*5jvIhtI#geZ$Q_Oeh0dd^gp0mNq+#{NxBm{?5IHcpF&5I{v0}$ z^jFX>(%(YYkp2<6k@U~dt)zd2?j#+ShV)|s=?{jECOr%~mGnqx7wOT^HKfNwHBkASPt)$O_?j-Gk4m&20ei3vu>6Or_q|2aPq${9nNUw%& zB)ty0mGt@0ouq4^!;Ur5ZyvP)I-2xl(5a-agm#g>8oGw`_0Wx^H$k_Oz6H9IbR%@w zae?&jf{rG=1v-`Veb6q_4?@?FegwLa^yAR2q_;tLl5T|#n-)m_Ip}E8FG8o1eihn9 z`VHtB((gbwlKuyDE9noQJ4ts!hfNQp|0#4d>Cd54Nq+_HBK<9N4e1}D8%h5R-Aejb z=uXmM=}6xmNPjSNH0fc`sia3jyQJQE&bH0p4cB&vdk^2?UP5K+=#3rWW46@%y6c9H zFs)AOp1Bnp6GujXTe2Z5p|A*FoYQ1Rp;pT&t_Zx}i9}Vh_jv`isT! zsYCVSU3)nGtKQ?~eG@$MSf{m&+js|#`wX9t{w96LL{0mqYsjq=aQ|+maZg1r)Asp0 zQZ((M(p|d_68Bj|Il#L$+vtrS;e8U`Ptvq6S~M*Ox^B`F^LOOKzB_!sEgJ5>h-1w5 zlQiw6=wB{)bIynh|Fmn!g%6VB8B*>C#- zzVn!^!k+P%f=Uq2+A)TT5={ru^UwZ&~$ie-p zFY@pXUKjDo{2khUDLX#e4{^C;+{Vjs9G-6qEt1 zDLW$e*ESZ1X*({59gb_Cq#cPm9lK@6j$JpjL~0NHfb`?wrwO*-;WO;NX@WgsoYN6L zZp$i^_kRvV`O%JIkiWc<@)$i2DPwhCpTd`InD)?*I9}&x2tIC0XZZLnm*AK-`2Hze zn<{*__4*#aB?rEL8s3wnA5$xRy$N3p5#;NRfG^)~_?iP>Hw;z2+N7@*k*^`->yv=5 z{NM034Zf0wC|_g8>1DiE*Hc^ZCLPOo?`S%MuQRcB*7Qi>+D!y_u z_J{C^Q)^{Cd{c|E=OL~M`}ZWGjgA%dFa~KoJg6t}FlgQP&UC$wj|11jwfGzHz7_3< z_e}w_g=z8E;{6%ZKG8nWZsM=Nd%J006d2Nv-+=cBq*tu+Roq)AW43&aynh!yaf_($ z@0ZTq{Nt&qXtSb?KclyCZr?l4d3^IP<@@R9&d)2tHupHgVLu4%djHM4hNrx~YkkD) zzuAAXhCl;HB6jiD^qPtrigxv62WCFs3j?>#Z$` z)SA7K8YNMwZAs*`f}GY+ytK7FBm^ZSD2ZH>71aHH##(EWotWTx&-*;Te|~@D*;#XZ z*O+6DIp&ySjycy_T3pEzhvCvJ8%ADZBYn^%zG1J!s5`3H1k)NB6WWi5tIjTS47Dc@ z(rO~OHx2ub;9l)d4#UJeFHYzb5`~MBih$p3Gk{ZOo@GDO=C~BA50TWIwFeAb*1v zcd2TE_HlrA&|#E7<2kj4+5{Qf@jjv7gzq))ecxed*1hdo%_#LUZSNGG*s?1~w_vN| zmd`eQKz%4OVw>&ACw}{hu##uR9-1g?6WuwvH^gJecz1a{yXS=2W97ssm0{X-Qu++~ z?;N(Dgx;lHH_a^1(}%<}zK`AW*WT^3ewPjY=W=-U5JhjC_Bd0q!)+`GkPkB{$T zr*$FPK{U77nVn^*g=`9x$DS{&J)-O` zJ+iD7%)A-nR8)$l+QvtFBeOO2DP=ov8mC%cAL8}7O7dF$F2%=ls6 z$Wj~oLaH+DX?hy>#Cant?eZyHXC`_-rM`QR^}qOwN-oK3UpKlyTR-P2b^3tQeIM8nj*`5#NsiS#6V|Y1*L3AC4smxgb`}>8QODNCdbOk4-EHd} zt4~LTy4wypR{M8^x=)XFu0B0K%-y!axw^|A?>)J8xOd4W&Fw1)QEhvjtJ|HUy$#6F z>5TDdx~|&SUgT|uf6S}t%EalRsx3BTb>rTPz188^Jv8mt<7rotHzq~5FqNUIJxVvO zLiUg0(;llEG1Z)~`ZuqmnIYU<`J*v5@OT$&;Y~83xajB;Hx}n$W z>XQXv7J^wAx;hR_OeJ;PrWk>mWq_kh5 znpWsWWkH1MSfv{`qJRGyu%|4n)gpAM0`~l{5FHh4O=}KewBKpI`Wim znEhLKr8@GQZj2H9Ht;D9<=+l=tBtJ$yTitYOi)K&29xbj?YrRlI=E&VmmQ^!?6GkV zg4+wOz@ff+8{7eKlftdKo4_5iaVNli$p2FJN8k>FTW8}+2dU;`y0I5p^GV%sRyx$t zHr+7oul*|JKLz%XjZKMG&F6HZ8T}LzyEXg4*NcyK82)gF(Kgm))m;y6h{M>9Z8ax4 z3}+KOV;vUHmWj$g3hW9STQFEPk9Al)*H2W<K^n3T|QK>U*(^?J2|5(dTU0ADpC)ZgUvlLsv()!?)h4{4avt9=Uq0VC%uY zOnDPJ*=6gbXo~veb$GrB?v%~5AXXjSYxA5sSsi`bVXTjU=K=23LzMqru(?qdPd!c@ z{gCpM5cTm#HqU>#)!D=FYzDVA%967ZT$|1Fi7D#nN&Ejn8LIu1!>G=VSN=}$%@$v0 zb_h1%Fmk2e!=30cL>+ZHt$zP|rt(KQvCl!)xNVA8&9P3=dv)Ox8LBzaY3yZgZ63va zrO2D)G)}Lxv84&vg^j&FQ#FqVQyHR;OmG_hN#G9IxRgZIJk7>cfy)9{AEG|V1vi_z z$3~m}pt>I10%-WRqYF*>s@K0XRkhyYG<*famH#%dE22#~W12!#d!bW&M|I4ssj7Xc z)A+Xdj$(M;4Q_9=<=6BPs(BSWQ{cJA<~hi%POb&F4qWWu)r-XUR)QL$Jv(buuc% z@DB;WE@P~E^^4WfL})2t>f=!%GXASya9yKLCV?9ZZmW%}1UKH~SH1oy^-ka(=9LqZ zz-5AKwsF}>>S&gY`vP1pxPmbC`D}3W!A%-!)!PJaVTkc-=IxJf2{A%T!_?8+z$^i? z&c>7`tB;r3GL61QeOwH#GK~2G+zN1qY+Oo;`gjdEY@~B-h>=)NTh@Wu0A}nks~_r9 zROjXptB?M8jq2PQV!U23Mt%NNh_R$Ye5RYDJ=~MRJ$u2%#;*2*HEqH%U9}#t@hhjP z)^|e;U*%YJ_7HqO1X~zu>LfBdT(usyahonxteQVKmh)M`s5^+kmmzS2vT-ydR}91?1^w-U@K8{-9&1SaJ&<&OL05ZqQ9M{LnrY~%KWyBl03xE0`5g<@~+drquzB1mVBk)UbO4|2leg% zSDLO)z6@>`xI;Fs65N~6QpT$@dqRyTvE!3_1A2q@uFc~(JPv`YAFupxqqh&?^AU2b zNVMc?0^4k3JHQ?TTX4BL(+2J&xV<(`k5H|h(DW-*=ebbJj_;bT3_mz$81^>Y;+Fz0 zD$MHpZ0v4G7<#)xorn!H{E1=2gu|_NW`j$zao+(q7F_m~>gYIdxsnff-3G*!@(PLCoH;xOtfBeh$2THFH0>?clcBxD;?Z zY~0&1s{7?IXrQnW1E1j&)wVC`H)?{j`<0QCK;11ciN^s|Fey`6^ zoz8IdH$`>(?XpSNDt~x5er~j-^SL*Bsyez98H&N} zy2x5f6o6Y{;;Lh=$x`jBz%@-(C)R*l3(k45g)0TO0a~eBb(T>-WAf-`Fk8Vav@w-n zp0j!7!D}1%6y}5N;9dl`-Nw~}dl_2&HL81;E&t&x)$}^JH^H5gk{wNndFWI)mL8?2}h5gM?=Mr6Fvkhx*(eV4=l3e(_ zJu_;!) z_23q`jFC-))VYOry-#V%xCPv8F5`f%t$r^;b9Wbl(WBM5r8Z{%P}Nxs=5Ckq-i_Mo z!(K3}z_127x5mco(p2YKFzet`37@&TySofbHki#e<|9otZw2!dm<}+P!MN7EFp0{e-!@$AifRGaep=Cj1J$NoR!uUvh_H5|$BaHXzp>GOzcQ1^v?Bal~x^DqnI#_*v8<-_v zhK8&@oaSWE!!{<$p}L#F6bwm6sNNgtzJ%JfzWA=hc0#lFdW5J9AGcg=J4R&`=urVjWOajw1M4iY4GYw2Bn1~_n z?pz!5GX8fq7(GUvoeyRKn1f)vU~aK7;ZD_k8<>;Y3B!x|jS+hAUS&$3u| z_q#Tx6U-qnO<+C*^AQ+568*%vyPE^@gfI_-(eXWPU`~R$5sVj1r;YJrv**C1urBk1 zaYkWBVCKfVyQ8A4K0S=B4T(ZOLzNL5MXUv;1I%$SNj7F2b&Um6FjRdq4$OEk*-?zM z1b6o&8*>YoOfaQGiL=0Dfl*-665ZXiZOj@l^TAXORmT>9SqP>H%ziMp*_h4P^%5}k zLse@bn5AGQ4njY}-Q9PanCiu^!)FDUCdsdWSp%jNOvDIx_c{}^WwG;8;w&&aIgv6j zo536e;|24SjoF25JO_pxOVc(m+rgwnqo0xP?j3er2dL|1FxkV@nO$IB2eTZ^aWH#q zOeZq$1yev>Z-Y4irXI|uQSRn9%waG?2cw_S?(SnY<{X%|DB}V0 zo!uwFRt_Vl2CiT*HZ{wzYa2?=|gIi+b#)hk|Lg?h4&Mbvj zF?D6fprd4W*9sdm3Ct=mrLn|FVAg_BVA4|DT^nr7d@yBTD#>AO2D24R6PW#Ap0hDa zz-$9kA4_}$=0z|QhoYY`?yi?@%(20$YZsWNSk}Z~-UL$$CSt6+Yp;z7$0xo$$e2pp z*mVFbxiJ5`;0}WGg8R_Mt)ae;pr^#Cj>GV329q)jJG#W()n;S%f;kB$J5C)t1*Q|s zaxlli_-%|Ij58V?#i{o2Xkwyh>UL#uKyI6rg+uV3FaJ_QZNx$xI3JK zEk4(R2_I|>)f3d2sKLZPgRvbjUNDI^=2hZ}QDE3JZBGI-7EDSay1CNbG2X`fZHVfa z046&@ot*?G6U=fj$H8RTm~T;6E|`J@b#ykE`C#h7Y?|QiSZHIysOuImr3uQo4a^cS zLx-cEtK1z+ZOkKJiosM;*WF-NfGGg8AIusXa|d;;1yhgA>%eRP^9q<{6Wtw~ZOmQh zc`KNv1l9NynCHOgBhb&)?vCv?rWMSKVDv;+Q^X6__+#{nDjbL4p!Om?DbIt1oJFdblygE?$teg~!*OaXNr1Jed3dnEdq?Cv;a zWBwVfIy%9Wf;k7q4@QAWo8s;WA7b_C-^dvZ8Dd0MCaR7oyX>w=@=rssBe46YxLZdJ zvGN!llB)n)kL+WI5DS5sI0`*wxLYUKn9xY_6kwXbWP+InrW8y>rn@!Q#*6?ndx+s9 zpU^rVtWMr}0l0&sSZjd0Wr&r>TLLX*xazpgmg{rmDg>7@8lOGY-C7Ji8~WWQeapmo zm#HHwsB;yVuK$G4)?u?=9#z|@1;sg6Q!Cy1oIIX{bKYq-QC&@hMaoGF&o2kg`I6+PJ+1+j2BENm=rMQY|OQT)W?1> z&KT_JV)Qe^-5M2Ryd(M0*ckK#c1VoX=N}AWUlLpgxZ~iGpcg2#te=o2LUDvi~^IEr@^N*k(hR%9)GV9TnV=;y+ZGB#q?ka0-Lq{i}pMuU>bTVsEP1klNkpn+{ zi^rH8qSfqT@1654aeAnB@a_)(Qze{D@Njp<~Wh_kDTnb4_3Rt9PlN^9a@2Ps5DHzsk9%tuoHuRBM~a74q9T zhO;v7Xf<*UPR=x3YGbtWFr(rxT1`G>$$>IO**>kN;_9t=b?;Z)Gcr*ABz3$^9lv=b z&l6gCPh6ny!Xld0sK*0tzoBj-K>=i4@-U+a8ZoNpKSQxRIte%|X)6vla>e{jZ6 zk7OwT^bn}k%dSa6L0lcoDf8-pW*hc)k^1NyMa_(h|oO==7)M1;_ zMmZCR?Hk$X;M?$PoZmlfuFz(CjEX+@$=NG8uT|&JYSwV>&9yhj;Ebtd55FJ5S*iGR z&g-N%)ArFrv?l~h-_~qfa{g?YS${oeeXgR8LFnL0eg#*;_&7(OHELSz*V+m1%W0>a zZR0#!M`P@^#hiIl2GsS+V;S)rjhr!dgX1Vn172*T_vn%t| zux#^;a3l6!lb}5z_Eu4&)ts7_ZPeWnexA0|rg>_i-GTmo&_nwTG?A-OXnEO&_EYxz zsY7^f3-Cm)Qx16E*>m610iLfz8wSt2dT0t-@=o*oWc8`R*zfXiL-+~bN1=IMvS|-s zZ!3Ff>ujFMQXlVnsC%G?=Yuw_PH4AN-$OmLl{PJ3WZ@kTbr1K@?y_mx8_;+^MBO7j zw58A*U$kV=Hia7j|5l0KMJL)H@Ih5tP1WZqprC_qzW-h5j?npgteqKiQ;vsQU=#sedo@9O|#M z>33Yx>;4*{&vO|06*fJmH~l4{=Rw~V;6Jg~{l6CaZ>j%R0sg(|zYzLs(0^&upYKh7 zLg=qT|3!d*@A@AT`eN#TE^vQu`uYI<*}(l*sPCiy!bh^b73ko5ksj|F!Q^n(>gQSw z^WB!=g$ZiZ-ML1>Egmmtn0+J8VP|sI)INu~4!h_E*Z8PbBXi9eXNWfyUfcPTKE?0j zf0EK$rfIv6^80fX+eH18I8$vh=zvc)fM44S7R7~ePD z7H*tTw(O2eRl(wHUK72-RX zj}`@F|7noygG=&Cg5=)I{{zW>?j*7wvt%#0fb9Q-c2iQg5&xJi`yCTh!C>s3wtC=y zvB*1^vu|Ys$h$Dtls7dXZ%L25bA}LS1j(EGKa_XM1?2s$$U8RNc=8dgM*4Q~-U%w( z*)tA5|CF<&;f%v)`jBv1GR?Ds-?4VLpTyaux2 zTSc$q!;SaRhsYBcM)SDNO zXEO4fxiZ|iX;r`eItHhTE2>v8YF$D&+aUvN5|)XI(&^JtEIF*w}-CK21{j#0CYCIY#5UQ12Z# z=NN_f&F}GEj-?NI%(JaUkLDPh+c%ayo@3m}`#6s8(7ekR<4>>jc<G1ye+8ewl_d2~NPhcM-orY(1k9~{^^0gzIEnjP3M>6Mo3VPb_ z8dj3Gj@(FNkc|vvAKh&|^F-JM+P@as%4=yqW2aYt1dp-p*~a_GV~(-gd*s=d@V~Q< zBk&q%%-<&ck%N6OE(VlmT8{CGEliafK>PqA$uJUd))G4m*M zkvZml9^(P&)2kgu#hpEUIwGh~W5-)#em(Vw-%P%>N9K*l{J$CV>H;!HBJ)l2!;L9F z&}!Zz27Ti3*=9^AYbtpr<6FpU#+F0F4efh&yBtZXU}TPQ2llM7_A8`)-@7y0`2Npx zj34lP!%|}Rq6e}~yT4Z2o8dH)3$>cW+dSTL66XZBcY|fabL{qNH(Jktoh8<3p}oRC z;NzV9A8fMa`zy4Y7la$HVVfdP-+4mf zvDn01;}Tn*#_N0Jk=QFaXgu|uC%z^Rv6q276E7f-Pvlt`Ze(DaX57y6t_9cj#4n$< zp}*UiBfb-)KV%HZ9h+s@OBZ^Un6l#L9(jw9)e|IdF8}{e^cQ*oc^`t7a7(yxGxhAl zUR=g3qm_E+Y;qXKoi3j|zvLRBDUn5dzzP1^_!CS7=eUnQ?l3kz=`iO0(jjYULu`xn zOuJSwL@j%U=ZP+I8fRizvn{foiE><&Yy6XX=4|m8i(i~=RIxstGsnZacx0Qb>le?l zc$jP4f?Oj{>@Cl_SL5FFIM!S@vUa5&smoO`UCDE!MURIY=^D?vaK1FXJiJE^joed; z(|8XVlD}>7$!APR%$1OmYY=byo@C5;7HBmRe@Q%D_lUax~8G%FMqk*KnZ& zX}>F|{Ud3A2bj8f7B3fPjnZgW8u@kF*FG;hR7Ip|-tqijoPDv-+S9VHQc;)cUXxy* zrRMS((X>*BioDd}6+O-8x|n=s(QDy`Nz|_&n)$4!UbA#3dYg^jO0Ki)GkF8g8KV=?+iq+;SZCVI9-SRQpLOuR z1btQHc4f-{wbbk3|7GwdPiOUO{R~z0&v4`Np&p(Y@a#074bC2+OnH-ehXBvsrD2=% zXxlu_x>;>>tH>*yUbC!pii#-Fj6rD*uTBni5p^VcES)A?k!u*(_P)ohHtw6()5d?! zqmTdD)5gKHG5=btjbaypHkR~hW8?ImHhO7e@`PNY4I3z-T>gJh>gWGP@-Xu3VFMWL z8arRZwfRg;O_XvjFUh-vaV>WE@>cDMeKMB*%`<(Ol6P3XZo zu#+6t)xp@p0QL;)`YU^|X4_6Xdtq-4U=4iK6@9Sld&_V`0Q)8L{P;fD2YX|40$80m zFTD@;_r0;10c@z#XiV*c?dpxaJb;aG8YScUVE@${n-aiAGf!XE2Rqu`OAiSF>`dNs;7^&0Ct4a(8ly{yN4M=WALG_(fC*0<1YG_HpRb6 z+ug*NYs}IN^6Xn&)5(=FC&e??_c*kUUk{txT{%Wuz@_ecW_?dER02vvOTaPPw?-pJ>v^EeP%JHf;%Oce&=h~dHzL=$1RfQui%+~$@QCKZR)jZT7W-mR=K~<=I56+BiDQbDegS}U)QP$;N^Kz zktv?%SZ4LcELmj6XAk%Mpg^{TtfzLxhFWYJHWZsxnUxMrNs>u*V!tSNH- zzVY<0@OdzZUxZ!f5@OU6%B3Akh~It^_@CJ60UJMMetF)PoYuPZ8|oQq*K?ShbpiK| z_y&Av08bwKCh%vN3kH3|JzcF$^02! zyJVkXfoAg2m(4PY*h_THB^IGv_Ge@dt&v!(g6kIaX73$z@SP8%)ZG7b`L@7E_P<0H z{opL)d35E6=UM7*ii1Uq5wl{}ze)<^2>T>}#3V_0~1^x+qDDGvB9j zTH=g%iD%g-lzT(bYcTdy;;utXk?;T?&|f~+1L@CW>rdnod31fI zA@3;=KCVBqZ!CQPP2>N8^fy>L%KVK9gBD1?wDt#GbFqcL`XjYl5Y>_L1xz z2e&_Ve^2{&imvzf-~J5v{BB=R`;l90(6k@QgWE6r=mWK1v)g}Oc4Qk!_A|$kowl80 zKh+)^9WpMgwvFJGi(9S~JXUDGS+P*KrcNp3yv^6l#OD>`BT;GKL0&{&} zp7&!%k?65%anG2w`I}=_>i9Oi8^KB6YV?iS$G`09D6xl8!-u8IEmKNaA~`cmrH%=JLJd<S!bneTE!N-#T1<>)316 z5gSy;R_e%qtp9e5=Kh=PI!wEMlD3fN>08fd*zbLITlO)Jt$f?o7kiw6wyYL?l}SAb zz4Rq>s)Krd4)!c-q-&*J-bHv7nR|@|D{NF9`l-!B%|2F^gUA-E+ zogLCfYyL^}-2m;3tGDkfuzjEB0=_Sc`!3}BGKGEt-!}oe$fn&k%R3U^mxS+28o>8m z0(KzZbP=?H{9*z$*EjgRXfOlmCJfps^j2igzeVTu7VGn)`!MX!D>lkHTjDF3e-rSH zhgoa?Cu{BC`B&E1G6#3r_P6h5%l_zhqw2iPz- z%?%W9JqmpwJ6i{>OXhg|wamXRXJ8Bs_dN(r+T|EAQ_dr8(UN&z3;ir-Lcf$)QS{1w zBtEfWg(E=~gh}pPV_oAhW_*IL%jrLc`GL(>E5FVh$Fst%_Iqf5;QoSla*WI2(MW!_ zzc}b7c*xmOY4=0&Kfkh9ZT7$zj5Q5dM_0n2xt=kLfhT0TZzo>1yfA47xqM+*N}ZT=NO{C_ahm~ZpX z=d4CA`T5RF1N+f7Z$#cL@_BVy6@K_*yz;ALe_Tm_`ZdZfu-N=|Mc!#}J#;-Z19%6k*-o_f& zy#IiDHZm7&vh|c)WceKN?Vjr`-&#a&Nc`6k#NUqWadkNLYh(M@;Z@ud7$a%? zU+~*NA5HD)qlaf2cLw_C`+fR|v$7|TGS?;d&wqFj|DnR4Z>w4D3gZ9BOe4?cUw20z z{(QUWL-?0m+&_QuUjg|I+F9_ofc)+r`5&EWTx0Vu$%jARH*ldhd(KpnkLqQ2d~fA< z)LAjA|2mtgC)n;jlK#c+B9O(jIri{PdTo#2cGxrxn%KrW@Hg#|>wrCOjJ9oJ5OFBq zkO-E~6~i3&R*;SS%%0yW+@^gv?Dpk^?8yTGUMvmn8{@dy0o`7zj=l_D= z1ax~%k8U5IX*7r0{(-Xq=jXyPxyCYh=U>)8@5hCoFJKE6Ke2Pu{(nBx_-laYEkQiz zoB-2UdGySTSym1noy@7na$tppchZnjGFCP7Tlk=+?%=tkN2$xs;a0EU z*{w6><#|updj{l_t0kYja&vj!6Pz8n(=Jct9BP2}{u8_-lzkxKA?G~<ynO~IW{VPx}XVn7b zPyVVr?*qGB&aef_r&O@VWS7g?uJh$Dl;^!;m&+NeK>7Q>DbM>)yIjsX1E}f$}N7^1L_fayfSsC_l5aJnvP?gLBjFW^1h|<0^l?zgG4KT$g)xi%o7E>z^_w znOw+Ne@%b~eu(X{ShZLBErjPL*6}_=V(d%Nx#*qm$3D@>K3-jlKjRE}dD&;GAx`n+ zYBl0tV{a_adzL+EzULb!`R-8aH}lYYk zIT!IA75DmUrS7WB?6zV%?-!Tnt>WG%rEZT_BlH^RVyi;?wyX_7J(63TpxaK2Jy>ZW$`Nt z;`jbN^d0=JgI}Gyhu^(mgoZts^=@R(<_UOxO81eovt6rkBg}wo|qd z{F~TCaE|{e%47{{&iUE?T0YqucbT*$)3Td|3(NCv_9p7;m`(Jw-1Fj$Ib~PFbA`K{#xGF1*Ue3-;4`otye`Hl(NOYNcOZI z;vM{{=z{l!_w*Njbqapf_mw{}#nzwpsK53P?2XBoJjGa?gbsW4Z*_Uzz4SM4#xeP% zM%jH2ui7o;WXbFOzOz4nXF?av$US(x@XKfS&Ro%w5vwvl)C z!4n_2rEtz=l4Ic6jgjd;)A4=uO;fHz9Vv7u-sP$;a&oSUcf`{N4Uz*nf3A*LRbpLY zo@&X_MX-0|>a*Vexh+qBvTPO_vFt#$xIyT49-+Vc*FtYWR&(y2LC%l7&p^5Ld%=D* z(cf$TCwrpU(k8gSZHs*7uD}7m4ZyP@I zN_k$HU1rb!rX5X@`QP4CHhmE``uMM-l^7HZemw5_aC>h_S|ol$20dg+vWD$ zZoAe`uH6bH9l{v#mVuAm#SFZ}Fj7r}M#eev6w|G6)KspVSe(k9Uld+*ia&l)qns(rJ=YHRTQwZAUU`>idb9dB6j z5N}l3<#xPbmQNwxc-}6z;|;U?eQ$Z*FYIzV-mv)WD9`(OKjl+iD$mj%4XXL;UF?Q#<@a~<=@(BQtOY$g8aU-YLr&h}g9QOxr>Pb8@S!iJjo_DO%VKS47F zp#2eA*Z@3VhZZ{ktr}YL05mVOE1*dq1=?SW-Tu3?fBAk1-ZKC%@eg~U;gj06nPyDg zp0d%5skan9ou!`V9m2KvKlz?W*Anad3xV&6oZ&e>9e;D$8Jd2|>F||umdA`QoFVMf zIN8^VOTV3Yq%M;A$EZC;L<&Y+*irETk@vFUg>hrGUSctdlm!bv~R@! z59BN6K|9TSxDlQ*?`=dLYo8#_mkUkfdl45ghVt*2pLTI*eGy6a0*if^{{kz&K!pt0fgXG`k+QYT%-#v@H)rD$Pu0)5@ z|E_G#S2J(uf5KbJ~A}PJ(2eZ6CM@P@z6^5?*@AuuvVqinPe2I;U`O*_cyy#M^wFq62h+dZKXN#+IS}rE;No4E~Pk#gb*73a`vCluz4;9gz zZRUT8H|6>N>*>oD_)CAvxNM=06zXr}{{KL4VYFGW!cXuXyYDlw>yq1Nd7ng%=k5$c zp8osndU*T;eRGDRVIaSe3ud4(J005e!P;a`Y_`!jjJ}V}*&RV&&6mDvNITzGoE1!O zqb$kpuQt2Cw&_vD$DM=B{z})Q&iB_!`YW-tcA?Soq{Im~>6-xaw% zvAWSU(y=>Ik1xIg9eW@0Y>lFyPdL+jkA`TOt*iwQyFZ~-^5`S5Otnxkz8oT>3^z|Co_Prfq^A*%xL)pflxub-#3%#R3 zeBw^pb1&~xk#mf~e<1w!Mt`DKQj+%v@O9mO>ed<}`2I@72*>VJVgczlY0qevwmU)7 zjCbHyMc+g)K3zr2x)O@gy6oJhc^0s;OMIuxR}R0oz{)%l`19xL2ftk7@P4^YQ)h4C z+hGeryv*T7)w-lE*JO{;5~UfgsWSIF*wfWHKh5{JayhpzX!v-6=Su7 zr%Z~8S98WLT&rygmuE82Wt7MG8G5XfZ~9Qi{%K7r^9=o?Qjx!E-IA`2lm+Kw zk8{r^%F>xL=7CG653A7qCjJWe+jlMJ0ij85xq|yEz`87+=DET~`lFG$`j$)I5li*j z=gt-^@x*oLCmdVLBR~FY>`JWtg`soETc@IY}b90Ut-6{D-8|Tf9ZTzj} zPh_dx{suaY^LHKxqj=KsvQ9`qpB8o$iP)oJD&AJJA~ z&S?q0pWv^Z=tnT-K09aItL!lV4OD87g zyL$L2@l`F%-?FCIhwfxuA7A zv7*m-PexZaVYgLw8>DaQ%`p`3yBt0;hSK?sXKw2|kJN$dPfynPu)duaSR0HuEbR~a zz9;RJ_@*cU|BFl_?^RsO??aMr;y3VZ$-gqkh&}76)_H|GiPtjb>Ut)#*?rTG9tak9&4|=@-*hvAY6dkO1G7kuez#_%=F+ z`%=KP{fl)kaiokvDUtBz9i1~C;C=o z49F(3_LWWiy}V~ca7U<1cwPvC>e0@n*R4Kou{4&4J56$UH8>)3gg=&VYR8#e=BQC~!~n&f*lUV@$bcXHK-X zGfmf(Cp2s4JbqJ<-Orq3#W8Wdh5u#@;!ow=SS9VkA7-(#bgw1(7IZn3;$r= z*XSc3O@;PHspCuklxKO@-cjxodyqI%Y@2lsF{Jezhs$Z{NPN3xXTyEt(ZjYdtz!rM z^*%DnI_?RsYsYA;k+nq?qF2qnPhr<5D&CPiiLGSN-wK6Yj_-e^5oyL!p;Jf53TnW#@z zDu(e+ji9nR7iD95m$9aqQgK=DvXXGhu)pAYIlnrk;>zA-Ow`FfKoYvTyY+t8-G8*SjoP$~Y?(d~bR4|{eev5q`I|I7JZnNK^z z#GaGV{cokV5&tf#dtg;pzTbadH}IMw_gU)+iA{6O@2bl8RRg&ri5Jfh!^^jb1M#Bh zx(78i|SX=?9b7nBI7k7yV)Kx~w-% zc-?99DiU7cOkVVr$t%4#-sDA}nY^y-O%qfRGkIYbrd)Zw@g}duHm}9K zX(HFfHm}jb3!KRddopETnGCGhK|2+P>mT7I@yGl4Ac-eWFUawVU7o=|24eNI_#eSN@rA#( zi+hsnHD)$C^Al6p@=45S$Q&A=_qERm7iYzW5~D_I!>?=S4)7N$ep$L*{djp7g<9>T4wa{xx%gP8|8`A?PSf-oqg4{CM9bv_BZr zg>MuL)aQ>iVneUaoO{15%M~i%PQrW{^W7$X8PllH6Qek znRBVS0Zi+KFfEs=nP8g0RLH&o^Mc8rd0{)(h4#Gg;z#5&?f%w?CkN_l!Ssz+wad{% z&$u$}BM_rX8>L+uIb0cgwa6mxGOWPw$Xr-K`{jLzlE)0x|K%F%d-1Gax5ydwEWS0I zrk6e&oJVMp`G$HUuD}+1>NfKR*z2NP>Jj@6d{aKayI=V)`5(wnzl=dg`S`&)WDg!6 z0eQ)3)TD->JK_(QBRM10n*YuGh>JS(OIW)gYj9qt09hrklh{YzV7oB;t0G+`U_+8e z=-Z}m?k`K97nF}a*HZ_U?<8#x*5}vc^Nd%Y(T4uy`-87bU(wB+;bLz_;#pY_C(GP`UCNj--$m+($&m4w|1HjUBBS}PQha&@ z?_XKQoEALJf^D_b+`n=8ekkKW=E9)yD{-mmUuIrm`4{3+)4y!FLLK?r=Df}S?C~#R z52qJc`L7!E@I?14b1m1z*vR4;WcnfWP`ukC+LzU!}4)9wD2n5;JnGP5uArAAR(XT=&w3 z#(sSAeu;II&ZynbTp;HRly8 zPa5#qsX;#FIJTF{m~c^7#H|DS6|dc(%C z+wUxh_Z5m<#I_px4sL_QK*9OpR3&;N=38B4)Bw)!UC7YS{kT&EKnW6k$hbhwK6%TI2i zj5R^g9hy2$ej^gUvP6$>t0PY?{>8RY;<&Gq)|54aTPSK(Q5?j2${#yB4aWlB0NSG@|%0N1)7>e zyOMOht&zEk+*-P{Z60mQrfqVbYmTEKBaQWm+#|Ug$-kxNlRH{n)U{UE+LFHDlFB(j{`Bp~F zKEXgMVm{nQyU8_l?4V!%O1s~s-F`i~E%}Tof5%_#{`{DFKf^As{K8-J*HYGH$jfHW2Cd=(Yl7#ocdP$;=N}@ftlX;?Uyy3cRK?mTRb-0LI(TQ`qC4<8=<#4$siy9H z++)a^ReVGmay6p&@yPqb7joR!J6##`7*jt~9%B$bTl7}Q+*mJpucB*JU~MG!BtQplyCcB&zh<20`z39R zW3FLc$h_3Ej+1rEg>-Y9ts6@}zw@4pvhp+COC99ao%pyAVw_MfhgI4u2VZCIOk=)i0m^Ym~w5S-}6JdGNnwgh1df!r`Pd3`J3Ed z5I)Pi|0mop=ThqM6PApLzH6T2>=)(c*(mtR86qWJg)@-iTas=1yd@+B?E0Z7HO^$zS@-_6l~K-QJQf{LCeBz76n|{G#-&$R>R) za`iV)lz^4Bz@dI(venSeQr=(x+yku>T8rIxE$90#(N_#@pmS5-GwU19c(T5CagJO| z;F}kL?_Ee69{vFPYh`~Pxn)nmhd+|?2Pqf3%Rk|-eL?&tw%3TwU5u{zc1*3bc^&0q zKf&#GU!Yg>dw}0=n@@0mo+0ngJb6AB5%7P( z`}H#4SH$wZLVQa;d-fZ#zfJtf`8nBdH)Y4R-nmQ8d}+%kv%cGC>CjxG#L>5n*r%;? z^9)uXW|J{q6%mth-v_!En`*c>K{Mjgat#@y@!9x2?yHk|mv>M7iuy~)XN%6v=gw(o z1^IS~L&nj*d%+gjeOGk8?_zylNd4T?Hx?_sbzPp=Xq9~r_1ke^yzeCU*lp;w-*%jG z{X6UOhH_u997*({$f1!-l)ciIkyVpiWT6acAeY%;(I^IMII2tQ}dT9|M1WXU~4<7k4|^x9q(i z+Jf8?JB{$-5A+cBo=P5X31?l#oR!M;;&AqOk~Ou7d20&oazS@#nvrVnnKm*PxCS#H zvhOq*JCJiYZ_t-AUIoKGkrhJ?0>juy(&O5qqd0@f{+4U?y+ddD(-nBjV z_p&E!vLTQw{VqJP)h*inGbHwHu=n7q3x6GHTuAroOm41bYi5 zMhGKD2q#8xdBu0cCreDlnv->l%*AQE=S}vAg_g$q=R$_g?XJI0TV#(PzLT2d!+)9Y zP5K3xU+kD|$onzH*R3LkmoaBB#^2A@YOdiN*E0Oaqu^4Bspr8vOOI^R$;r>TVPA&i zXXQLlI{eMPi%uwuL&qOrryH%lH2u~<{=S9wihoMdN4KSfawZUd{~*rEqAw+;;rA6e z7r1dGXHlK3HD1`bcm!t@rMwh+6}B}3n@Ap|)w-5?c2{wZHe&p2Z_%lr97>P2i{zeX_+Q?$Ci9!eY56|ZEVabTajrQH=i4^#TG}=^p-j%% ziJyA$ePS`jLL=k)1U4)4Z=;M~&58kBnr7(O;VZQ51MbO+(q7SM8^0ad{B9bPo9154 zJF`Vz)<~`ioY&y|0x|h3GFL^6_ZaEX`<|Wqg6p{~$@A&1ciK1`zU<4nkMgay10wrw zt?RX@Y3yCorq%k09qR|d-x<;N4);&F#q}IxLA7@HU$3GM;`PWf&O|1fe2uk-m{&Sl zSywFia&Bv#?2D%YwfnlJerR$T1mSrrpkJf^N9cE-Ou#1i}gsV zj?cpOWPKq%CN(Q2qjjOCikhDNTT$F^Kd+iy|9Q&;r$6@&){O5g)70WLU2Wp|Dj(~I zdCz31;nELJaEMN2sv)>baO+44zMp@$(KNUo6$U`&_A+ z|GLa$aF(?8&)jGFiyO~BH?k$=a;Lf$AMwHD4S7d?T#|PU`V@Vop|8fPzFA*YQ~tl# zSM;O{>#K<~#G+@EmXtgo4v1RhqjQwwMhGUGbc=z``-_2*JSXlHKmr_+DLwVWLhUsb_5lIJ;7BIj1bFBTx%Xxbw=y;f(0k7qYB z#$$g{e=%)N*GH6<6{qv-c{Pncxrg{;(ebgo$4HNuf7~&;Y)*aZfqC3BkGdrXKJO3O z!TB9are4lj9an_*N?AwJ)cKcsrk3fNJDc_L*^$I-_&Kqy)KqNiVUN2db!tYHUAFO3 z*5&xV*M@15dum9_p2?ad-dBJfIi8U-K-M|fX6%)-0EU;??%5cDIj%4(fB)S`^>A8A-ZuDb9Q!}Fl^x*!|7Lwamw zUxH;T8xwnMB{lB<-d1K|D|O5<1KCPgA6vO+09*NjzIpAs4S6}(3UN%ewlC&<%#Dqu z|DEp_zJ`wwUolW#Qv9uX@9^IDaxOQ0ANR|ePU4S|rY*+$o&w)U9zpC-);J@V^A0ku z6PO1ZcpmTO`5W@af_*{aG>Hd^Rb1G-&X{TMCXS2HCf`o`ifr32I&b^2zJ2f>C^o5= zdd>5FbBMQQ6L-xb{<@BDFUncPT+V-6@!rkztg-WZ=EsGW-x-DL^JE)^AE38{_omNusUw%;qXP84_n&sDF_-ZDqX50{{VzqRBV$VP z)<8eMp8JOQde7P{@9#O2A@Q|;2UuZ}v#8w=PCol)lr7z29N%&LyvD z=9sUD$(S2q<%^@pTh1$xbB3HH;+|yY*Fb)`fcfD{Z1*{QwY*8%?f(I-fg|! zuNTN8Nk2zoM;Cg(-qW;I*3z!6CA(e5+Q%cvJ!pD_?_0#C6|5~w@Cn$T`TSnQQ=Z+# z`3=OJ%jc1cxK;L+$!p0o^b*fVtmkrS#v9J0uFwC**gzkwS8MEXrDR+M;y{UsQ!k6j zn8f$BrY35})96Zc=^{=Zne8#IAs1=dCAo+-$kI4SauITNcLZlBlgxNr)-n=*{GB?a z&QxTPag~Y;*0>ts`#bHEez9ff2p-!9q3z+mf%ZW5Lmw!A^%k_rtYJ6WV;LRE*&4=j zobOF&qW82?`d0d%F;2`}%X+IJjl8|Y3#A=?^0Bc#(O*Dsr)b|mKJhp3l=h!qaA98~ zI=p|!dcJv~#m%wxG3UHKM*5zBk6mZS9{N}M%hJ_wUpcg{o$K>NCvn^#tnarDnmJKl z1++TyWRi2gk$y=|Ab(4l)Z3r_?}z8DFR#y&KB!`x=-;1hG+xbmj{OXL@uGa}E7e{b zaIPxzF$3Sv^Qid$E!xbX;up;KBD|F$-+LOKK8J6bR_1C4kC6Y^&Y50`MLuLs$miLi zB3qa8j7<^ka%q-5xEPDs)O8cGR5+J(neFaF`xdlD&Ur~&`rbDin#kY6`87@VFz)(4 z7c>LhK(>?tZJ_TXB9r(E9XGAhywllJ+D6PAMLgWH1OI}b zIPM(ni$a#Q62G#KBfcWA&(tzzw8>GtdUo!DrA0dN%5q(C9bDQDDFK{JD!p zXwq-}(f$FguN{dEvEE33jc=Qh-}POBz8Sj>f!rTsxIKm3-{0sH_Kp(KNw0YFUcx?0 zvYg-Nn@0QC2iwmYK>P^#*hS-adJOEK=1%%e&Z0*q$7I~e9I}M|mpP=Ee*YnMu?@V2 zy~r8=;uLHD)y`!#(8h+8hOuf)G<|R9wRmB|Q;w-6d6V8+&o_R|HEgg>8d6RSQQ{xu z%!90ne3CCIrC#c(WPXx7n9L3HO#c?yR!QEV$r;W0och9vKq9voSnwr?x(a>s+oAxlZ7ECfC<-J%a1uJM&o=iazj_HC|gEb?8X+ zF`u%4J|0aRSRWqr_dnIgVDvEteQe#kUgFp-+Iu~|NZ!$M8TKRl3ae?i=xrf-lQSiK zY{}GH7JB>if2cRfPgdqS@oVwEo#-tY|0sGR$6KwhVIQkFNOzkD?`+%<-J`qBF_XBqV_#NkBA-)@p%3 z6l4-mf_SM@)Ou+N(8~mBTZ%VOn}lEu37%#YYeicUIkuUx>4~RA#o8LQ+9+)e^;X-S znt-+m)C$TaBhY!jzqR+COhTf^_x-$o%xCY}>-MZ?J?puxXRQ_a_jGF$zMgoUFH&bE z{*l4ze4lyJReeo!S9MBr=REFLs{3MdXI*M@=PPYr!*c5cuEvC!}@?6PpSaWA;fZy=u&WEUD8g+QDAYW2*=h)Bl z^OEN>)kmJo`FWbx|G>Zff55kJp!n#Z-FKt2$p6QDB|d&Wa~WHj{hhr_6hr@liSrVj z`~o_;g)tU>_q<}S6S7|3x{S0Bf3rUDEt57b@>eIV^RS(^`i1oY?jOo9`FQ^-@6&k7 zpZyD-gW+o{_)`As$UBh#B=V=1I>dj5J`W=HeCjUkL6lD`=Cz_-$W+Nw?M;lutneuC z!5QRc-&ET<$n0Uh1IyttTWDW?JlR@p)T4kGQejM8B4Vm;< zY=-<7!jIytedD$MnrX)nX7=an7H4j&9_rlo($^}t6Hl>fCv=%SD!DG@E`M+Bh~6ip zLv4lc9Qm4m`=5aAufTwxVfqiC%?C@Y(B=|P=q+fDyC4eeHl;UCATBARKygVwzFPa; zvI_P?&y|$<0c9SfjJ-!^ypu08@-DD$`Kq<)Vd~yQzTZ%%=-OV7(taL0@9F5j8%&+! z3jRW!qM4T%>q>Z{Vvv2dzG32*!8^2MuV1=rm&d-PxWN|Yb5uGRm=AJ_LVWNVskL}l$Jx9Lzi)VY9oDu zW?Kf*Y+_tx*Zb=O&&{q3XdNi`!1};$-r+<0t(?qIwR{JxuYTF-_Xi2E3g%d~)~kkv zk9$3=R}IHsauU3B1bUH=^{Qm8OV`VuwB{&o*Asa*c42tYe%nTsJ=#DVN-^spqM;q& zP&~-kseG4S{}p7d)?Ki*THHI|49&APG;HjN=g^B@WiO}D7a#Y&y0%!m!~bOiwZqr` zKwIK@g3oj9#b(W1@~@OLK7?1{Q}@ouKC<}cpXrajN12A|Nxhxy-4r}Q=GQUuri&NiZzNgIj>iT-ph;K3^vLcgWZ@dD`iV*Gy> z!OQ1|p>?y~D>RCR~nRb#eHaug?unDDp?2W*oEcWS@JH zvBm2>Z_SU>aXU1cNXJJ;SlcVjH^nn$MSgM!|0rXH-dMmK=|_hZPFvQE7l+5MIw?G! zwkFWVU^dxJ;owDh|G4*O}F5o{gs%gS^KKQN?KXH7p zwv9MGv=G{V(tB6nm*my>sN6NFcLlEJzj))!;dcf8!u$V*rq7{&L(%k^qzy&WIiw9` zH;-4^5O(varrehYwW(8;CVrlPTjK7JXITZ^+_RZeLebljmI~XhR^h#`#JjOADm;%Fd8!w9A zZ)e*v_Wl#;HZxN@X5Mm!wXG6)Sq~4=`JLjovU_CbxcoNvOl$Fcx^BDc-y=-Jrc!7^o=vDP3qH7=e=#C z9*5WWyL;y6eBU$~UE1MKiEaOsH1(&3{%B9nmZao;Wv3D+z_NP5<_)FU1unfIWdvw^4F6_`HKYW*6tDqr!q%)0^)&aDi5hyRkV zkN?hI3!i!D&BDW3HhyPOhx+G7X61m7+ZcQKVRKFcr{dlCB$}p-E=&U#f=^?p7!&F1 zjT4E_PT=>hfAK!*&^R?vr_Yf=8WS7$nUSy4rc(S|%g&UYBHS4TUswcUw0-sMl{+PKQ&jBxTzLxVP zE~&CYiuvDw&nd!x`GxX%*E;+@Z$acNPio!S!~Gxl$v;$ryVMd4@`>q1MM zvrV42&x_L79m-}dLL=XYkLv&H6YdI#W)wdvx}eIx zKKZV|;eW+i?;x+{{#E3YUs-wnKpyF6dzddKMtD!GRc$HXA@XIBZ^lGulsuWdC(fr| z@3i?q8*)H+22U-nFVV=ygX2S0(BUS&YY*O4Q|}7A1w7XS$2{7DHt{RibD@ohjONkm*V^MI^?Gf(#F3?qrQ4)J+kjy3MWSMZul7K9oFxL+3SUA!)2#+ zET4T+=n>X9D@b?kDQhG=%;KlDEDIfmSbaB5Pj|nU?-^`L=3gf^igbUA{%#Z`9) zo}(Vc#O4#$Es52XsGE0xasU_0-4XBla=!-Cd7Q zet|PKhgq!+=whx<;E(7SL0i^^g3P67kr(GNmhPPodBh$=9|bqVcUlde$3?zs=FYgt zH9XT!wq`ixcd5K|pxt--!!^)l5SbwP1pSMCni9M^K)@^z#28?@+d( z=Fd>NX(efk4V|V%-eUY}>@hWbvkP7>{qR=uXuS}cH2d*iA>Ug1?v8c)f!OqQq%~p- z>wb^1?;&r&ujnu49kHwXG3)s8+tb6x=MBeakb#Yr$vBROe@;M;%nJLON{XaE%3t7{ zn={k*L-{+h&74vHE6>M=&e>-T-XG3xsJ^gSYkUpWbDA5fXE&R%MrY|>Il2)3vfo!V zDYO=vORh=|rF4x9^_(?4oZMxFI0KXSlfuc3yyuSKeMC69nCBE9=_iq{Z^_~0+>w+! zh4&QRQ$i_Ksw0&=siB^Vk(5sl<#^iWpgWlJ2Ymli5^eHM>J1Af?~i7WXKiQ6T+TJU zPBCp($I9HS(C<9f=o`z|&f1tf%EYxvpHXa@=BoM$FOMAK=gNYA@m}f4enY&y6g;b6 z9?wPQEL`c<`o30l;?3;sJkyF=-0`ydBx{%CM`^aTi!PXkXN77L&eQNy zZ}4Jta^MY?@WdVq;>S}Tg3wn}^=Z99^zbGxPyAR-)f0Pz_-C8EJfZrg>a5#}*_iPqPC{N$dZu+AiF@{aFq!gmuqRrxY|yQlDuzTORtO~Cpl@aezccfXCM zf9jLz-A@0etNi~X?7=exXIAfu$^K}hdO~mcB>AyZB4O`@ z-rxkmmc*DON1Cd~_kNQ;$={>1&yH{o!_Vp8z`hCApVMczKYwLzEF^wazNES5q0fv( zzhWFNS(+89VH_5fm(TKXu8GAsm_ENZ&y1_;8E(dOd~XBwbr#d-5!Nn~XVt~=Jja-e z4Zx;*N2GJd^Ss+v&xguGfBfA2A>BTnr`0}BS#9k#^-Sn(E3~$$kMTU)`|@;|dKm9% zHY}@Id)`SLvVmz=UwdzoPdw=;{Ivo4s30FSxA=O-OZJB4w^~h^=DxaLcFL&T258GI zb2(+sq741B%RJs!=2wYjpi8$*F=ZxE#y`g?b5$Q5wIr5-rrk24r7@K0yuc~*`@S+; z6U#6k+%jiUW*BAQM>cHZ`pWzuu?%y`Eu(dmBaCZKkyB=AUzrVwWtfL<8J&f>mojZL zoidm8mAQj5e)iJYc*{0rQlPO;;t9qO1Bf0NU$c8lb)1ge_FmtcLYnrnxod=fB+ak1 z>g#*k@FORYuC*4WE0(>%dqZy--;WU|2z~T@ufCzz;`?E~Z^brb?wT}o#>KxAm{Z?|n? zKQXz#L0&7bd}-F`Z%!J=bF12!Vzp+`j;WuR{%+*WkNDm>*=n7r@3e(3(E2XlEua6m zZ}fL3SvkQ;jnJj+Rn=*o)^xd_eFgW>ZZmdy*O}-5yw9~p?ei5c&{}g_Bn9q;-+jgDw(F8ny5AF{K|ZJ()Ey+RgUb|GS7Q zQ+pf8vxPi9_FgDoF5~$&|JBY*q?z{l_N?5KEd;&=t7SkJSDW7^KiF%lXi)JNN&A@@AP+LS>yKLoAZ9L*YLpVFZMpQdTm&| zziG*uu;jtDjKR`x)S5el)L$Pl28{Lo+~1eLd)f2zBS+7J54E+$*p?8>aBT5<=&C+< z_UO>*qx{iz@`Ze5OehEq43XYZVoeQ|kzP8*+Gb)cPVb8?c)4Kc*aG$d4i;N*V*BgI zgi2L^j#EEAA2)X4tI~{ul#4?ZoRpedzkz-uqwHzimuNw%`!> z+h6k6F(J*hA=4+GD!Xdv^czTbVp5u4LVtxe|BL*3R;{iLlyC>oPx#;U?b<*R?^}8I ztf~!6=DmUUpTXa(iH7gR&$Ti%aByS@Usy{Cbck+Vzr22A2)e9)w0m6W9rWiH`Gsh2 z$5(0t_fXGf)idGK)$$}^_=?Y>$#YE{KDaqT62flLe(?+ z)7Ntb^_(Ldez`VK06dLftu=R;Reh~Ca0dUEe!bSjHx>uMA^&sBYXdnvJu7MhlX!OV z)c%bfD{BLipJxIG_}NzcrCQ_TUy_Y}%e{X+v~&97HJh8D17GXNP?%?aXk=&#-wdB| z=x`wYxODS(_}4JOc~fm*cZ#v6TdZ%NFMGOUIX2&E+&Na0U=J;YAB%5Jql|nXKga)K z+UfIY)GN+v8Zt}tu65zvBj&S?og9(8i6A!~N)o*wA)DV{sZY6IGPSp|J; zQ##|TebbfliEwsY6;H*IgTMIMahdIXz8TqrJyW*dc>H$ze5YgIN?=+REg5MYh*b;=H&t8^=I-Qe-RPu7$KIY5T8XW7 zY5D3|E0ago9pwBz*UplSrS%Qh#wtVq)>$7tw4wObPR2;`Yo_IAEkioLFLDGKR)ehd z>8z1ocNA{MuADJ)Y+Xf)bs&c}E7*4?UFi#Bt=2CpzLU5Y=wW~QX&19@ksYa7W`&a1 z+}b21`hc9mcLc%7#r{?N$x znPvX)k>$g}MZg{f_B;9R=j?+gIXhJFW?+A+>__MVg1h~xjzYx`jK>$cFU9!0I|>`; zvyU`8vVrys*4)N*KXg{Wb&NbHLZY8K-l-nfn^lPufs^ z7rt4*5u^Rt_+T_wySCQ`u4NBdP`Z&b4-I|5$C2Y5B|jTw)5&WiLw7+h;^SXoKK~sX zA{(0N`gLt!A?5wUduKki_O{+$#wJr|8PP6#taqtz$5@YQf86e07X4c})#+c)e8$l2 z-x|}uN^nAi`G&^0d)?MK6@MBdCbJUW)B|peu9)lUnPZLK={eml<2!AE!I|!fLx+;S-I3Qd zB03L#CSMMFgZJC&qhesDa$==yU=w7}M zY#TE+g4e+MuLV)<9nrnm243j%mJb(1pO_k7KQews1M80Y(RK&cCh8GyiO06^zul2% z?Z9Bmv-C&>aI%KfvExPUNgPYOM^@w#V9rU2$K>~m7g$aH8sv@E?QTN9Zb0s8-OdC3 z=Rh~IMHM5cSS797$rn;fnJn_wIO~HoUbp>;5zU{$@OLfWgTQ-mc~U4&o6PfI9QLu1 z&zn5Z680PGub~RX!r6SdLpE9WWNTYFuxehE!5^ekKL#G+I`#L5)~T_5POu4Rd%xjh z1LChg0AHeU(fX5rs0~~Pt^bL+taUo~`!{K8c?a2{K2Mc;>Sci(K=8g;ky;U(qn zq4ARQKPTE6alG`|Y8@qi8f9#a?(aDD-;_}Q`l0J@`1Aj={{5rkw#L2SLoo}kPe1R^ zwokwNt=Km4ol5B2vgX>l9kK_%evAD2x}Wo1>}B2eD*p%P;S_4TuK8_kKx6qW#!7SJ zjimI@t1p*Cb#|4`Q<=bAHFF8OwC3+444<%iMnucLsryi@$ouF~;u9Ue!S~L)#zVBA zI^nB^CXVc^4QO4jhWdTE>7lVNl$dx*)gSn$9j|8nHP-rd=)__Vt{J;I_WGHj!Rf?j zlJ^Vr-Q}^OyC9I3n6vZr^S2Kc>&=k^AVg=6nONyR?5Rw9oo%ysugDzGg)-=<8wfTYrwV zp8c_X&5C5wSK%=c?wQnGK;4Oa=X(wemB66m^G)` z|Ghx+ZNDqms?bv&hTl&l{>PCMA;}2?GjdHbM=)~wOa!Y^5UU9S&+v-C|1eY2_h%e^|ErWhSs@ri$dPMW+|*?AZrlgE2) zUmn(h{z#tg3i?bv(vg*?dyDilyPnt$~Y6gNsv08!EogN7_Ig!Hxx-Q1C8y=p4dNAvrNF&uYC0nZR5#dihN}rJFZR znH5(2$20W#M~u7T=cJQvLLT0iAP=u*j@O6=kPA(R9eEf=J&pUdrBQHcx5A3Q9Xbl;7PLPdtdmZ`mR;;xFe*1B{vfK*4W5cbf!$c zRq`#1Zx4|tjsFd&S*_w}bG`6Y>{InS582|bJC)%p&>F{7aO|7daCshhLw2=DZv9aG zChvnh4?_>G?AnoLEiNSX{}$ro+ihOx+GH)Bn=gvnWO?j!aBVUp3;FNlKhPeR0qKzm zv@N(~ce-$O0;_b&81qGN>5PfIRR8g0t!?F&PujtH*MhyZQvK= zYfAASx5#%G*sa{MNs>dm$XkZLxoHsI{Sj>-gE}OGy750)jDh(0;jJUWd3n801}Ve- z*ZS3yi$b!mj%*zs?wQG5cJTW=4`*MIN9$`{dpx1t_y^vgKTbQLCi*EJEFLZX(@hzh z2ak>O;7-PC4KRogn{>l}opgAS{0*x}7Y|mt&3oCK${2``i~p7@{R>X|YVlpWdeZ)4LWa?qF=B^qtrP?=zp&zAI-lUauu)Z(QVA@3>yg zIpOQ@Z)2_VnOje5Oy8&tT*#Q}J>$(=N#Kh*~0htvBtywBhr-LRz=`vRu9+Dn;WQT2kMCy0IPVCYqJO!w>oY1a0ZO} zbSr%l&A2f5fFa2E4dg>#pnv{ju?%-?#g9_(6DR84vyS#p-^>2y#PsQ;ANFPy_~=6p z`ytg=i+;*B+t+R5<|unut#8FzWAMG9`$>NIuxn#oM?YkrsjSZ5);hualrMWQme2un zRr0GM+Z5-%@WgR7aQzST5+H4>+8`#jZ%jDP(ZN^cYq3`8&+H?K<7+p3E3y7%;Jp(2 z-&wOT=ieCriF5wVK4^bn`d0Z@oOskdc6x{P`O|HG@cPqjzrw7kp>=7Mfxo!v-^lNu zo_2O9DZMiAD(PAa(J$uh+h1|;3U7D`d#?)c#VhV@4|f)+kG|Xm(P!B!6oeNchdS~; z!@b<#!sRD<+;7IbDX2savhE)GE%oEO3f+UfsCqiV@5_8!%p4Feqn=jTwpGyOhuooN z#{#%#T-q_rhAtex{oh%CG5E86_bu}4fUl0_w(q{ftidv0&!ax+4gUncLC3$@J)FDt zSgUA{#YlXHjA3J&eeyX*}vmOQ$W420elFCFo#e$1JOo~D;<-iVQ4;HuV{!gD`Q+!( zH&4Ph$vee=nso*ICPB`8Lr04ij!dgNINY2SdZ3o|I_ZE~D{yr{t@Bg>uk^np>R`{X z(d(qsHIjA%ebD+_@vyqUa?%Zq`3s`j;~eK7H(JpbnX4}D@ud#Uv<{cCFNe7> za2@Vx(u>VHTt=iRm3{r_RoSe=LGz1+p8@M|9hSWgXU@1WbnL9d-N~5x@zJ%hb|$=A z=)m2q8|f~Do!otZf3M}yVJG7=HD?b&$GWRT_nf3fHm6vdEMM=;2Ie#85@cw6lO0^{ zNUAe?ITPnpKYmD^3G=D`(X^?d)3Ig#PQCvGrX7q0@?^jDl-cWOc+uq1m4V?7Eq9~C zi+>E%AILtZ-oa#mRL6!SD`w zG>2>H^HOhJKb>=`ih_ZjF9 ze8%Z-l@&cBk^U0+-7xC^B|n`vqj~mPoWI%nbnJQSllj~He&Z3BPaCLLeNB{4?XG-s z`5R@$-~IzTGzVTbkiWGj>=iKltW_?~Au_X3Z?txX-fJ@9NXXTtplLJQDtpyk>2$;wb#sxH@Bfu6Kf2$5;Ax z(sOTLYu539sCjJo$Ao>I*zsyl`Q3GV`7U#aDLA}#ZLeTGJPg~DJW(fJBJYe2!-o}5 z@EB+Kp>NgC`s&374x5jyg^y*L7!B3SxwvsSo&k<314m}$7T~Bf@dOk0m5n+P4l~DW zK31>u6U`iR_}C)GPyD)vIU-)3n_Cz725`fF;(N4=EVlKr`jYjA-dh}ftVR0Re24%1 zj=CC8uM6Cue(UTG`mM3*aMxqJHozB&c1>MIX{_Tk>wUqS;2i ziQdgQ7)5zwtQnl~P@uXk{NVDR{FwP6dg>$=x*Oi3Z@oO5*uUF_4ns9CWMwN77E>SH}idi?)ijX{j{?i|HCroQUkDwXLd24@+^Om&$5c-r<2_3 z1up3h_x%b#2KlvDBTW9e<$1G^8Bv{S$5}8%@_A&_SL$7C!Q-w6{&rh#?`lVGW8b%e zUv&QT$a>%tzS0>7;YBk4FzpC8n$re14nD-II+NPwv?W!}k$*ZjGvnK#o;#?| zZlAeH`A+`VI64F49DQB)Hq%bFm0{BVr1sBpA-v<9%LD_q;LXC~5pe~R`f7PDu?y@|N%{V_x@k;e2rDH=|aK& zjvi2B>jCw-l$9Q^aTNOKAa)MjEX@TSp$j^q&sz^AUqplOXpmgf7|`W6BRXw!eZ;d`kPJ-k1CT-F`Viu3Q2B zhmtF2)BiGLLDjst{Zj8M>Sw>S@7_DhS^>C78oaOcgVnm1l6 zbQSe$-Z=J4hn3KNRVg|&`L;PQ$bM<0pN{=9;zL&B>FR>>urTnH@`N=8Vb?!BL_j8C%&P$WL z=S<|$JSm%p?_Tmh4_})0YUZJHYpiu=?jD6^@AERq$M1BR$`H2b6Mi=*Uo`hgX)U|V1 zYu$1xvC^zt36=)rjQU>%OauFuGmJf@-XG7-;jGLI_LK^5Qz-ug`WQNniE(}t-Bo>6 zjI-Kub@rxn5_EPu#<_mhLfdvo)Y%)b2R=?`-#~xLT%8>oWMF^(iClb^_Px%$%DuWS z@D$(F$98nT4g9npp$2=QIRuus99zCNY8<9J}+3AWcK^(iBvPi=$r zX|4K1`yu*N$^O4j+b6|e-a?-mzgTD1+Zy8I#2#wKNn@19+*-*z*Z#LA%}x3E#*a3( zRY^7wtYkW z%J15^C1%Vf^gLCU&F7>}&ik6dhh`_r_tqe1wxh#}SIKTTU-UA@YCT`}Jo8;R&|DUb zd1LzUuoL>kR@^`9#uM?7gC02$4^LoY@1Q;5;YZ*>vQ~J&7h~E;#6zWYC2Z`a^wqJk z>z6w=_IG|sAAr3Hn0?%_B>1DODU0U{{uJQvIaSH5j!k)I0jja|^9hNoYU2J37iOSc>y-$^~*z`Y>22NV1GM2K{q`Nz3 zS~_<-XGE5sZf)wmz<>PU6_+9FE=A@oLiSyP9kvi1yOi_qY&)#@%XNY8%D#XvDPDCc z|JO?1f;*!xKu5dLbGPCPluuRu)QgA1SJ)T&r1wj`k1H>u-Ap1JUa zuk$Rvq0XG0yW=|aKK|41{aT+hW5=E%=r6vf$jjKdGJLT0mKDsODcoxY4)<#xZ-VVn zpZ6#>H9C!}JCueEeRRJL)f!V~ro&&8)d2HD?gaR;aNyJ{`%^fYTzjcu14 zsKLHnYUm&>@^fHXy3?62H_V97m))%Q)p3W}hpf@*-e}F60qZpJx#`$1ee*Nu%un<( zcYex#xrVlM9(B-JV~g7^y|HZuUzC&W@+EvwokwCbc9YljA2;>dc1w`F&h1OhrcE@d&?8unE+A-N( zFV~rUWFI%C|M9dvrk^;T7Y!KCuob<}%t7WcHq$4K=Rx+4B#vhb<2%@Ro)3;aZ#v^S zu`oWKB^ktA{NIje&EVs?hrWO8cv4Q|*^~Ug7*D@5o|JLNb1E=vJgWwdXF|W0zRr38 z`8vtt9b!Cx^cQPBS*EPC&AB@+Mrwku-6LlKhp8g$?zYo|Jq4&6bC>_U{HuPbF^aWs+ zoGiTSq7(PF0f%77_VmGQ@7=Ruesvi70{mwQFt-8EK$t5(Mou%jNH*x z7szz_n1^gZ$F0vt*B#bs^j^kpWXSvYhRtRi9eo#lxZc+@E`%M@kw0!~Xev4~I&dGK z>o_H(eSf*oO!2$UoEtVXKIhg!m*+#5pQT;t8^W99wQ%Oj>q)@JnUk$CaJbhQU*AG} z%+OGfywbJunpv}DUc0=i23@}&?`MwaJZP8q_YkAN7{_`4qwtQwc*SRdyK3Kwa6bav zBY}Gw?daYY@qXPib##i(jI-~WI-YRPl*^-oM{ORRchuq0WzL)iPwt$)i@J3l)kf|W z5|745CErqum4LUd9@d=5w~st0C&;`e?s(N%O*(s_>CfB?f_(4*e+N$^&uPcV^Ldiz zeS09T^n#B=vBKg#bpZ~}&S>0S7r3A2$MN+{=*N}SdZJUXUWl#jO$r@dB!1A}*4DiA zc^q4NX<8_yG0p7%?U{nDUCbFwXUW#qc}_mwlfub6bS{%Oocwx8)b}X+y)MAZcIHXo zI;r`2#;#&g+}`f+jh`3_8+&`TvA4xjjIEu?dKBeklXersD4V-`8c%HQ?$7eX=4K7e z>=V`=VeuNBZ(-&swpegZM<1`jzV)4JZ0?TyqKWp|OKVogZEnr+l`j9e(Ow_#$A8d= zHJ69tKb?$0j)2OeSZ)WXoM&F*|$KY3nFLlj3VNbE_?SXrWH^WPdojt|P^hNfz_7sb;EnY{2Y7R?Eg2s$l3p&$bb6rnq$V^uGbow zc+N2B)8pM3c!PRnZ#S{mSYsUTGv`hjzY0DE@nY?xe$3^?_!tK6qn2&@aee-_`t0nZ zE_22&vCpgnrD-qmUief_!N=Hc^kbmy_MhNG_Vz1J!H=SKfyTr>LB9k0)PxV=gg)Uz z__Tex;1l}vGxdq~Tj`UXWHbF3~fle#Kh+JoKNz^zy^MMHar(e3N$?Qno%8|GtLjhGVf^YFa4gh#u?|`) zp6tkSV_(?*gN_nt(AZ`8e2m;+PKgG;$L}2aR(#yZ#Cog4$nqAm4vIWlz`bK%qK$#F zT)bDd_gS=C$@wLw|MVr^|5N+=|CsGJ=qSAQM12VU__6)}KK<{+Z=n8{;WrrAea|Y2tI*k44 zmHpYLgR~QelBk2MC+==A9pq%;J9(ql9Q)xriE}IWao41+gIwn5AeV-ZE|Lyn+xv;O z{$M%?INEPj8Xcr#Ib)6vV)o9y>*ydWsXsvn>DPYah>d~Wwc;q2>6(jE65zOK)Nq~|LRbDr0>71{G* zY{f3lX~~mqNV>~Mx*a|u+wcp-nJGRn6+QqD>v;4VqwV-W`kJWw-fO`#tlq+^(>Dh2 z`4}6|gYM(jZQ!`7Z=KT2_3fM|pFkgZ+<`e5eSDueZtz%H6sM1+XKf6u1CP3ocQyCh zPD;RKx6h5c%#J*TZa)urGU&rTmnZ(}M7=~jaiCsepFeY(v1>13UUk9~V@aIv;_$>o zy`)V3xFL9AHe+S!3^;Tr;kg~$cjFrsUKbsSE#@++42@4Kd{25@*OZMWp0ac(xxyG2 zo@>*0OW%6r*vJoQt81#m=MwO>3|u`9u5>SxZD+Ahd#rez;@XK9s2&hU`JqkkH6J?k z-saFdZM*cYHOQ}0?=*+r{U12=p3v^nf{g*SeJ^=r6M?58`OE9AitCa;gxKP0i?v2C z{?=jmU57){CqdIA!aCDavHsVN9L7=MoY{bEo`8+(>{M@2@{JnItwSaHzN#+i8^j=_I#Q&B2U&R0X;rQHXH+ghU zA#Jd4k#kakZ8Egv$3I{5eSdE$`jSN%pW_ehK83uM{-UPQvkDc{FaL{Kci?*--@8wl zRp`T})A>*8L)Y=x;wMC#$73^fHnd`^Hh9x^wy((Vt)UO4iqoQ=pD?~kTj)vSZl3Ij z(uH5)XbWkt14ruzcf!uCw2zqge&oic$yTU!GIw?||0K7)z$ut2xIeX$dFJx!(v+OS zAh7vTXBE2eHYMBe22*C4JrpjyOMzE>d;>7I9gEHEJQka=l{!zDPdTTAv@VeNUHObG z`G(>M#zuYvO%8ScNR%|u&|viS0cjTJY#zK~0knHDG<*@X%>8=ba`%zgcjpXM_im?d z>))|{vFr?@xT_g&JD-~KE5YoA}HcxT;%YjKX}LU>sUbfz<`74x_R zy3#mm&A{?3{HPM%d^LG=PlIT#n{^uH*~?S+HuUhU;JJ^dVjWj_Qc@zLteNbkObPO| zWzpD33A`o-ZRL!%wi%qTMuaSmWLumuhD}hB#C^r+%z{U2MHSpN0v&?Wv611FQ_Nc) zG?52SX&TvCxM7{YC=AV&@*d>fH)>X)D<_*$a|-Jw`?sg^E$GgFzHxT)_7x+^2OlWs zr~c$>jf}HVxa;q6=wqKrE+%g`%ga4Rm`Y;6jUPK=>j`LIwSu~FM_l`^RL(udro2K_$^9SJN zsnpOT+zEd!>HYk3Mm`NUvEqlY0VR_}U%JPjg7MJ)$AicrVpR%y{+qJw)h+{P%g^v{ zudv3g^f1nhTZ^x1ru@D8^Oue_etrCRq1daQ@CMEyO7_(Re5;C!vM=+j>Unk8ZSo7} z%-Jy~HrG=Wi+RJbFAVGLtX?;pIU29aha9Lm+0(n_Bunc&(PYZcrM#azKXj(oQqJn` zqz%9HG~|R}&{;jhSx;SJ4c}J`{|!#YSBESVPdShA($m12TNDaTw&Q>KZ_YnJe{0F- zdj;?YCws%?q@PZiQl&p`$A=moLR_fs3H%Ot6b-xSD=0tzz{OGe)*_#`YzfJzAUKgP z+`D7L=4bhKQq_jdrk+`+hL%!?Xg^PD!N3X(^@2h3s~CE#00xc!H1fH;_s}$d^!V); z5i@J^Tl+o-TVFm3UIy-8qWu=Dc*mTBjHkwRT$>fTnzJ-#Lc>pS&deI@$D-8}(FH2! zh~_tO2H~=FPtm$0=>DK*RUUjS7>kY0U%8BP%#-Vg87i=dB?_L(czTjn7HiB({M(m! zeJi_wIXI!Xs61V1$t%&D7Y8R57X?qXrmG)C=$xV-KQY}pKR!6YiU!FWoZu;{N%zkR zp6V%DTVid$HJyG#=Yr*LJWJcGE3>CstAgp);&qe!vljAyF8@nu+jnPrmd`Ue)wjdC zGM<)it(pg&FkjDWW1qh7PXB$Bjqao_wX1oo{riH6;8*(&S;c5UKYNh#bvlQUu^Y*6 z-L;k5gRCRq7F*D%x5`?@n)~8*;tR7MHKHuNy~>> zp}#oz5#F+UtW`UJM|V-)#@GpO^}OFsUxiEfdr|g#o>gl(`+f)hCG{Ksr|EYmb9qw= z=cs}EXQBNpXi@3J4n$b5e?W7K7>fhg)@G0Db??Wvt)0XEBd}9uFB+OCnnHd}U19QggHKiZ!KC7d~KCt)e z+cCw?-brW~J~3V6-);EC*vNml_(Av5_x9s4gO|_qUAoH6;8Oit@Ai-Tvjva(a`Um+ zHr*SLoc#Lc{Kjz)^{}qv^Ng$Wd6IXk&lF$yfzTc4+`t4xf zpPCfXnaesy_k=Rv$PLZ^MeKp62P?NfH}ng>qepb)!|!sSefU&IE^tXMp78yd9QdHG z;9TmHo_s=EnMzL~_9VIBO!EAQJd!&D^(h}~F752w8%KN3CRyg(RJW~k&ywCI_@l?~ z-)@aAE}BN3G=8rzXWRL{2YzN?+&?b#DEf-VL;HD$ktYL~?}PWPK4)0yCV1SY^r<1) z5vq^>Et`HlIy9DiF5GS#g5yc*f7h)$ZydZ)XB)ClnEDm#k|^)@|99Wru6F;1zP~w% zK0N2OrmN55#mTgl&u=>OeKCHFC2gKn(w~<6&a=wHd?~mVzRH|h&OH^<8!N1|eJhv` zjigOsj$OjNif*2>;M2<6iT~r$;nuD#rxBw_zO%@uy+D$E-(-DdI{)FzX)EB%@VbJO ze`6OX%%91$X>i(`721xxm)t=|Igyq=pT+p5MOvIZ*En@Apzd>MW5+1p<>wT8LQ^I- zUOt&$^(5crIXv$(i4$53=sCmiDikn;rT-@O_8(z~6I1qtOxW;QirW=7y{!XomOP(K(@E+`nb~X6sK2 zWkS2<$osi#Jgd^Nn?<|aF}JD_xx5UXT1p?Y>0?m5AGnckqZh3V&Qd&b9&P#QUn$S? zfjcpOH|1B5e<%6R4h9WAlL-#pR%Zmr)up7$kAo^PxI*|zt`n^YKgrY~{;OEyVLTV| zlp@(vw)SczX7~OMI&VF3szXp7Usk;{3EACvl&!KMN zPW=|{#4m+o;mXC~G4S`)PmH*<;`X^4JxXwb^FR=Nq21VxS^Hl4PH|C= z=bE)`(EZ#|-~rfPhIiwS+$MW654}GXAH+)Zggo}F1y8o31)uSR%i)33s4q6zvuf{% zEfePEVoUI(&nfvQSu+(o+lB2ItSt^FQ%4GQ%mW|j68pNKmGX-553Qh%ElJja9`A3NonMn;KcdSwg+Kix9X|mMb2?il!1% zu@isBH?U2%V4FY(=x6@uH=x0dd{5zh6nz+(;g8-(UA3N+y3~A6xEtP=|Mys{d^Ht( zXKajaQS@({-)fx2ucb>=pbvlC-SZkN+U>}_X=3O{oRt#)&%9sA*olAdcVw^RQ}RUX z)VaS$ucsf~_y*wZ9oAntRxP`#Bi$Q=M;L9dG2m`Szak?V<_n6}497cxpDQPX_jl33cyJc%PpDON0F`Ji5Qw^Zob3 zYc0>`_#fpPl0T>>$zI1SMaEY{<9kN1<|~=ox5nC$>-gvX+9I1j+xQgv?R#_T40>`3 zyS$tOi|s3)g6x&=Q)UnT*-m8nJnr7fVIFJDPiVvOp*>H2`Pe>5Ux`(Z+NC`(>cg|u zW4Q0^!sZ4q_po_q^SglG`TUBSJF8FSH-_J6ey8v|nct}9e0Zjw|AuT- z>5WhGU46}iUp)q8?G(W=FXR@DK%U)apKZ!Np4ujKoj=B7gE=9%FMU>j zOBZnN9Z$E@B=$$0|p z^l5A{XCTp@nWLNoU%@P!UI zdd=Cn(bC$0Y)$vS&bcdE$ho=9^TGP_5cPiuOhKn^@E_+(n@BrET4KBQ*p7?bBe;g> z%lAk-LR$AAc&$)5`ZLsdy0?;kjIuR@(8sq)i;uN*fsvmJ&BMoOpSLx>U^i#0FXA3C z^?f=z-4^jucm4s_msB|aFP_rH^GE6}|zVIA@1vxYt! z*}~qt1Uax0T9JQCcVLx5SLjnMxdYDoKMeij?>FbK8a~at#`UdB?Qxyc?(XT14 z4Kz{TL`R1Dke}^`iK(c*k~7Q3MxJ;j_JHo<@qo|9srFi|uszY+7 zXr3)+fNVQ1g@`Ij*NOGQuMxT%nHkk7ZGo#So3`Azgz@fc6DS+9z;{lVNBcml4AF0KuH zR&5*p)c^eab+6g?+P85Q;RDipSs&6^x@YN{F?G(*uLfq(u;xJYBJTZyZ)t8`O5L|p z_wB&GIsx`9@lXf$_6x13e;((tr`fPy=fM8QpPBKC_0H!%U+7L zmVW}=R{{6HF?o=>1$!@WB(_mi&G6T{4Kfrdrk3gVgx~X@iYZCjC{}O8Wbm zPw4M>`kM&*wbc7x)T@4q=3*5mho9iA&_sE&9#~xdB)L-wOuA$23H0u(IRmHN=7*tQ zV2`#lSAx!eV2w68ys|0If5%0p14ABi{Sb4`t(Ws$Pnbi(;kEFB`vo8Ll7rv8AMEh| zO43S2lP}qKIvASd4uL7)xQDdC&QVr>@$lE=t)?q4^yCHJqRYsc?j&t{&I zUhl-!^_@rMoR^s~NIK=?=T)6T`sB~o23E1(A~sL^14cM|@qO_9WcYsyav+uXn2}-M zw~LD;vpZSa()yu?GnxzzTd^fP{_RbdS<}mx`L{EE^}ep0PzpXr>0$VLzT@-MZkCTV zG2TQzt9`VuxSO`iC37j4JU?oDvH0tfJ?!(BUV-cgU+XLEkxzne-K-sGP12%#&SyAl z8Tw0KYK739>+iUELtq;}+3juLEAIV>n3bHfIkR8uC&k)lYDGRmo*MoKk1qAP@_j<& zVPI*TEZuB;-<_F*TGKteti7 zcCsQ{sl%^2;AyJg)Ded%D{?D&yO|$7_?IMC-@~twf4ulUtxMj+`$Ed)gR6y<*$b{D zXD|7@uW&E8x^7LLIm4K>o2dL7iZK%0|4o~+i*hcs%jY?Gs5&fJH6d~xZED}B`Z*1q zy1_f?Hs2kef3>07+SN2=(yWt6H!#zNU~bP5PO>8(VM`0%vJ(1pUFCM+MC(x6L*IFd z6k;7EPCf7816uLakN=o**JB?fA1`@z@0EZ0ATsIQ5AyGP`Jol)4VOGv7&@Ep z8%9(uNW)~dvHYKI(to--3+MYAFOaO-mJdA@tM*CX`>y}KxyQ9{Lw+Xl>&%G!yhmRt4(t7T-uL~Y#Jtxgr7o)7QBYUwO{u#) zX>46-(wMqS==pcE@+pxpmzhKZL}GR$xz> z`TIFv;R@imZcTo#=5{&sBfg+Ko`2YLbQR;Q`wS%WHK%_CU0LT?GgRLp$qe{znZBLr z#46?Y=c~!kpZKcg=u6W$Cz$yOFW+x{W`4Abwu>ac&amlJex9aj#P#LC+ouzIlzi?? zAF)K5+YRjV$WF$8r{@@J)zazK;yuToJ+&14OXgPa)E)`xlsZGp3*0&I3$^8$I^WEJ zWxy#oEPV%lx35bXOYx&Z%8;ml+Uc$5SZ~)W#B{legX6)9;~*5;8}De+|EF z!~8OG_8DVibtsO!%R3PpYh1xcKBGOXxX+5CwcWvZFp2JbLe_sCtdh1O~7|?COA?*Ec}G@UAXgE zRn|=#vvS$xoaVdJvBJ`b0(0dkQ@0MckE(oI&8NaybMSG%k zPQ^2;Hw0RrWKE8F=6;`z&ha|mZsprCZyK>p4lTvuAU=V%r0a|RRF}%C%x2Dt(0L5; zx^A)Sx9Vm zUr>+gmM>tivA)9@Yhtx!uf)e@=@4TxgRyz$tI!8`VVya%lJD%D@5A{j@8)#k6nl2iotR^WWo^AK1PVPu%6E53K*v3qp^~ ztPH&6rrWWXeeIJzxu`O*i}d5S|1um!wjO5mOmXi5D7 z_;_060_tuU(L2-7O71-7@puz2vygKL+D^84u3#3g&WrQU@sTe9V~xYJYT`UAEpiRt zU&miASeuY*Q=(i0!YjBefm@)hUiv(kj5uBJ z4k05>Bkdq*YEQUH#6db~X09y0Q2td%_K!pMrx$$4oksEly^6k`3LF}P6!Hs3AF*aZ zr@mkur(+|Wu7S+qj=n4ALv!<>LG6{%*_tmH|El_M)l=1hJpb;c`@nTp zfckqs{ncJBy&vLz2k(XC8TX6oz-zqAFLM>|Dt|vur77M_&#PLixyCJ)@o{s|$9QJv zB(AUa?FSp|{_tz0qglkZm^gdR`(=MhDc__w_=uHPO#BwsdS|oNTZ0VOI*s(y!(LAT zI1lMefJ4lo8tC$I=1~rJ#dh2H3w49PeskoE(S@c2;jm*(~JE#$9G3QOO! z=|4MiGiTe&md`;4H)Y{a!&9OrEQ#@ z!@K#vTmSEwZQdsj=lwtI_howjzIm_sTY5MV<|U`3^yUqs=Tw1Pi`Yv)vA)*b{^q3b z7dMxD-_z{B+iJG%F5&+?{(JeK#Q*vHzli_C`9G{#v|Wn6s&j)a?3t7dZ8~u`)0{kU&-{8zO;{z#sns1DiXx(SoI@=AvwB~6ms``^J zBi0Wat}MwDO2VI3ez_HW3cB?nt8V$4wS5D3O$Wa`tY2SM&KDvUy~M(YV@1FIe>rWG^G$V^^G$Z{bWlcDaF++}j(L4M-{${e+E})Z^HzR;w>iIm9q+lX z+)eBmy3N6p(qL+rEn} zXxfBdwAlX>$I!J=?xioZU+=VU_7oH6hCE0s_?835H10t9rc>8d+wKl5uCVJ4v(Gcp zznMuMKQhJ9gZlPGJO10Bg5O-`_2ggN9q^4Lo*{uBTbBR$6-|9Huid9iI(Gc1#rZB) zNH%RgyfF_uUwp6s*?FGGW%R*4J1;Nc9uxJkfN^AuOzaACvM00;O((W5 zU#SI78Ov?&fN$GJEImiIWeIq)_cLf;Ql*vs##O{we_WoTux$?+I%8db19Qahtk23e zt7I*IHgK2H*RD zjxi|5->ET>j-q+!!hRXBw=q{-90_jG@te#CbS;BB7q9MKFZI_C?5d|1c-*qWz4A)u zRNlWm8p{x^B&_|^YrW+^8NUORqmF*_(dc~6{bbMoq)#UrNdKB|(oxKO!&fzzvm%q( zTXxV}wK?Cje`Yy**n>Z3AFub^nWlYW&W!DI=?oLszZls2eZOg%@mVGI^LFO@L1^tm zVpj+DPkoF1B$lxa+PWWlXris4=iI_)lg1i7L4FSHAv+ZuGCtF_2Jj)@I+IiqhR{(EEc zsJb3-T}h1YLgG?Qe&YG_kmr|ZjUjw`zgThQEhBI8O~hiOgDq5SIO`8Hz*kaQ+Z^Ay z=wa)No4bfv@^a?Wuo{2!p0QT5&b%ts+V5&lk@h+7_IjFq$BSR>gqL^2V|THB<+~yC z3%=8CyLTabN~9ABmU8MA@6&rSyNco z<#}o*DBeVV>>l=)mrwR@?}49`pTT+=`p81;UDiMjFiwlF2L6}Wd%l8ws4LlrI+wMS za@Hi3PkDCYzfQLH-z!~_xbTA6Q`^)9cvlbl|!vR;Uqu zO>y+nQ6H2n;w%9dUf%=G2Dow?>~!_Aot4b>Mm`|$6}_o6$WT>8pu7+qK@ zy`^e$=n3g5U86!NOGnt}?0JT>?&RaHyJ2D9RA~DwZ&>HizXl(DoAcP(@5RoB7x`W~ zJ+uM7l~R6-*;|kUACf;J9lJ$!dq!Ps?xB^>M&C;%2Uvgg*X#Z~D{_SWC+X17+b3HG za+ou3bGEv8tlDV&K5Mt^V`vi0#O|y8h7`_?ul~{OO!nNgBEws$>tf35UG?k#5$I6u z{U6@mJwB@H>f=6>;WA0MX|7x}2~?c~FI6!}MVWv|1Y2s1cPl|`4WeyrwcgE5Yam`2 zZ>ZRkNUbwtX`>RAY9E3=ZKKr3P-@k-PfbAW1ZoQcGQ-7rzrTIXNhUYsdEV!J|CrA? zbM|fRwbx#It+m%)+q8e?Y}3Bd3e|SqQL*Y8+jqxpyKfsI&P^)j{wwT%n>y9bqBFyt zPQ4!zi_{XVz})JgJ z&`)&-eN&}Xo&%qMk2PO;DyWy|^PNB9j4ZlXg0m6Q#d6Ta^u31kvuU&SW~(I!y>{)S zyTV!*8odi*__Nt^12&dCi`azdIwl@9_>fHE#;va4|5o~Be4@u&>zGgFCsAidmDS?o zY=U^aA6~2VUgZ@hAxb{c=z3zZiWW?LZ`*Mc3a&u!QhzFW-yEJh^<3~-unB+SbJ>r$#}w>_k!;;e@dBOKIgxW_cn)zwRQ8b>_|RyU;X_Y zUW#8&dsiL%?5E9&7vh6h@OA%2`K-!Lw~tttzdc~@rwz6@HIlk6zq;G*xih()VWibN z?bmm=pBb_EF8^}jumbv1--HWyKeLr_)ZT)h?}qpF>}NK+`2@Whl!BTM|>zTzb$qw`v>J&^jo`_s`xjjA_ zOWz&2#r3tE1CrhLl4cYXs&B;H5dC^9h4dCK0 z)!0*Xz8JaS56orxX!Nybl;GPMq)wfSUw}OW9#PKI_=3DSaaQ5iuwUq`yxwKY*oQ4c z@ljO&%TArhb2%Z0CWI&3wvZLMoq9|0F_X?BdEIl<+40x^g)Q`g*wkvytD-kHhi>b= zmoK|eDr3m}+lfuX)U}v;lu!1u%2NXCv{ye_GA=S~<f*_<^u@=VP5<7eBuFT5Fx>gIRIKZdneU1kSbBI`K*5qjEp< zUbboZ8wn2cpY>b+nNQ{F`(un5{KwoMP{6k>;_+8nE!i&5OseB^cxLjrRzn*<`mVL^ zJ?;w7c}LZk0$%j(X2$a-)-~~Wi(G+3<^Jb`$FlzGvSbpm@W1oU6``oc1Yw92T3}vgpq6`RpZ*;H>cd)Vb#1 ztj)iIRz79?{zcwu@R2{-_l;k9MsFNrc{rbHt@*DKEBNnJ>v=21v&O=|$4Z&8W=u*- zumHMR!vUMvrGro@a#dOK@wm`MV~V5Tqigl@vc+dcelTX56?}{Fm=L#u51>oUM~3}3 zer4BI6|S6juxj(%gWrDm>z?%V$fu*mFF@a$d*QOnwqJVfE!REhIRZIv)2gxF8ydDw zFn(tHy(5cCpTc_XJ zWXnDTjrF8dHO*c)gZI%Cb#Bds;^r;@*q zc&79n`4Y%qmopT_lRaZh`%A!Ck!Nf}`jR4^ffow-sSNa4-ZhE!$&)&-i}p)5_&3g_ zjQrgszs&uOwP_yyTgO9ljNkL}FLaUS%BK4@aAy~P@OZReAJyf*WfpGD?u_-xy4yFc5GjQJom z_DyJP%#+2z>+YPp5?{K8`wyP;@GlRZ*YJlmqsK3~-xFK~o!xigeV0{@_3j*b*>$&! zJlVQcw6>jd*7!r0NAO`>uz~m=qOY@&(V(yNXX>B40~kbCXLu%T{IwN(X#%(n;R~QO zuzr>2^jo02JjPu#SM3c<`&*+;a~FVPH%IJEWw zvpPz_v^UoAZ5$UlNPf}X670S% z-MuM#dgF|SLhrbSB5!Vk=&bhCx%<3)7fsEB2A6?*(bhkqkHFBXHTU7SICJFdzqkrI zs(_xBKwBDDm!5Kx=;>AHsbR@t=x1ER{%?ZmO8zl^_f zH~ma;=;yQ~`Z)#uBl=-4{9Nd#@Z_`cMdNM=c(UK?Yk-!GUs%ewiO?o&U8Ps zpLJuhEq@vwz*^AOEmvemzRlbfJz9(9+mjR7v~S>ZUY8p_nHRZbcWv3!OnmL(x5?|7 zE2o@KzQ=x%SlgB)S9^XTU!&~ET++V9SpfA{d(3{VkJygYp8{;vvJv`zV(&*vZ?5<; z=da;KqOs!`=hnv)+&N)Iu4A1PuXp=XPk)+LsEy3X$+Yq71Bo2nQ>yxrkJ}5JdrD`b z3(t&>>At6Q8+Aq*R|AK0&e!Ds=8T}pYaJ2nB+rKf<@wu;;L)rpQ@QUhcT;WIar8^? zm+<}--b)>v>gjoAR{VDG`m*xATU$1vZ+gk>_zy|Xk-YwXZCNJi>dUdrGo#-;k!ZP@ zv`hY0TQ-ukKJe}+xWx+Yr{7cP?<4H7zf9iP*4nZZ^2!GudtA|fffLp7{@-iMigzVi z_VeGsc>Ns1k31Ki6E6dX6|4cdUA1MqNLRU5o-Z@rx$)YvfAKz*`(;k|)s=1MUGj5l zuGP{9o_5`31^#x-M20YPn^@Gy6z0zFtD#xN4sQUjo(;8Swcs|9hOA6%1)e)S#7|0P zuWu^y@z-gi7mVlQD*%k1Rdr<(^KF~v!r#`G-9R06z`}W-|1m7b0!t;ZY*=4gw!j_d z^OI~{$9sc61GgJi*Ofg@oA9n3R_PG+Yq@+qZ{<#^72xFkw7RmN18;a=)n>_HiXAxP z;Dy@)FCwRi&XetDuXuwGQfJA}z$5b@CyTNDqPFZY$`_J1#5&^M(OjbY%Ivvh^d^Ik z-^hO_D{?e?qI~v{3)lLY|E^u#&)m1?V`}7j`ew?Q`JEN{Al}%Ww-)!lmM@^tUkGks2;Q%N-8 z(!wY3gjC`F_qAnL(Uw^kY(3TBb|Sc~bofYRH_yt5oKBe@8{?tx$r3F|*V>D&wRXSe zRc_=8=B;=~GygZdUR&157<595+E;dPy))F^URGoR?TPL$f$mQLH<#?JEnAQ5`}k+I zWxwGmet5}_+OpSpe}7kP*(*FZwAPkwq`n&HiZdoTvh7HJtv?C<4INIl3yoLxPR_!C z_gB1iW!cm%JG1`B_%FZAXQ>OkG&}pi&5Dl=?KQjcv5$dA7@Fi9kg)}D4v6#}i>40? zK8<{K6zQTVcb|75@|phx{3C#=Z@r6Dud}~A+OD_Vu?zRC(~ezuxSMXt#s9VAE5;TK!}n@9{(io&$}cst^N@(Ia2E5+i@#|K z{(K(xBrIaY;BU^D7Oi3J#nyH%dZ_js-sGO6bJ?Sw!CEW5cJ4x3#;YQKBl3at@wo-| zdDbz^ufiJp3{NYv4f~}nj8}6Z>!M^25BWR4!FeWZJy!nLf}4nC#$22t`qzHUB)%`= zdlP;)vhTBo7UdHgOY5g-+~O|wt=~}`$jl`h;H?)B57$o_U%}TjUz>Zyg2cBlmDm`4 zV?mN{`Czdi-MVz{$~W2*Lr&}$3o?ced#7R+OtON%*>3b$W3P*1V>(8$_yhj!o$U2@ zVXqL*HnNAd6#pG!{FQGbj)CNY?f6h=&u=Di^{PB6$oy9M*KfTlww^O1f4J?cS0;n! zPl-z~65G&-l-%N9lD2AS-VZ9k--qa@ddl~H24w@_`FL!Ke;DqY`svI-{Ogn{A?-uP zr-pj}VEK#JsBZZ9nhWp$%X+?VM3-UjuUPr7hZidSdT;Ed`}U76{wLqADN`*HMgRh+vlw^vB70Uu)CR96s@$&UTTrX){b|pBj_woKJ>QNO z9A%CO?`^5p+9rN^9?y3CDauoszeVi(O21TG(+<}2CU|EN`@?)&BL9`Nn@XllW={{rk-_)?UoGyjjTu!7gqp9lD@_lz=eke0v$?&Bwakpgs$ z8H!H?9i%P{tShQe46(E&P0(E`bE^nG|UJB8oU+6A#|`Kd1j=s+FdY<&XTA$FvC&O$EaSIRh|Keza($87_fVWwg@bueH2 z^gECDYNLPU6{V1t&-%Z6zRv&K_anGG_2BKVh4-=tA%COKFUJ38zSqQ1&%Yz^@Gd)6 zdXeP6R{Uy28yf#^KhPBGhSTr^)jBL5TR|JH&G;0?umb<-C~5i@WsR1;DZ7UB0)IO9 z%l*Y8zP7*ubKHs_iPneN(9#~x1=rhc z?5yvW12QAyNE2LY`^9fqoJF?cgXuw|$t$~^?w9=h;+fz>F=7AH`0%pTjkRbX__t9EPvFx8S`zD^WjdMva z#b%>Ae41+uJ;C&v1+jTGd9gy)j`X1=v3Wy1v4zaPQQ%K7rEAWeuJeJOBKZXPj%Qsj zur`^tn5&hGkB=Qsd-ZqvR$ixhOPM9itMmYSu#~xWW=haU`4Q}Ed`et0@y}l}M+sIF z6bxGbzkv<2mAN#E@89s`#?o2$|HWBT#i6c%9(?)u!3^WsfsF_s-Xiv#((bfla`-*o zqDo`{>1SFKQ^B!pRLs}7eP@ZU$eoi#H{AKq5^Ss^YOu{JHX61L;MiGV+49^FVDbdxlP!Gcdt^H8)ytP$J|@we0ru((Z1~xu=f3bc zaqZJre#c|>=x_Z_O4!F)Prnx$JC=R=#986>bv^f6h6*^xfQ`oVzvS3pYR#}rn)AZH_M9!w z(~U>!E=McEeIuLFDVtoU>Tv5F>eM3`Sd(?1$xeKw%1ym*_SAbS^%8@bJ@Y)th&!)k zUP}&Q4l5Q|_Z`eZVSxSX=H&hBQz@6c7gNQ5*#q3Y81$+lcmG;@ zF%EwW)-%^Cz>AML1Yhs=d0z!zHG7@d_;12LeFOMCmoX6!D`Z`fY+gV=7p8bjj5nS4 zT(;8QL&vwWT>CTi$dy_6lvX19La)OoeX#u|Hr;P8Q4!KV0;w?b2X_Gq-e zh{i7bB4_H49<$c@4K3QS6zbU}{6PfAgdg{tM(V><(A1t|8GFcRS@cw)! z@2R=$>mm#0KeO~Qcrx+=Iw4PeOTDoEFEc1}KXNALvyEQF^Z6#(#`A4kNvhRcR_O6< zEIe4TxeMPkDlKZtT{pCsEZ_VGXeHpDw z?wZ71wU6j*fOJ%BBfV@q%G=0(f&9n*gZ?*SEAIBaoiIi=j^&Omp?%TgV}i9?mzRB{ zd6%ru6OY2ZpGx?W4+;G!_Sthh$eaTf-9N-VJ@~ErPG-)rZuv@(OW@JwJPgl5%{$5$ zhHYKE0@!3%mJfhr&iWMY0?}IM(3Y_oKXrs)Y%U08a!*=HL}fxy~q{V6NhNxkRw8J~l<4<3K}|7|?Wo4}>wS)QSBf#)i2ls_q+Tq>SrHEH7a8tYOgo~7Yyed1Z(xYL%w^U3eC z`FF2)mLsUI(vkHmS#K6HM@8Sm`0m8B{G&gm^)tn^luw)DS{^c{CG`FDB0HvK34Bj6 zE$6e(WBj+0Vpbx zP)tjFR)}?Zz8%x@BIcD7)AAy|4;a((GWcqrn3nW$$Nwg#<+H%2n3ifw=fm2rWL}NH zKZ13=Nii)K^^a+3+WKF_w7ieD+?bYI5{YKTwB$@v^I$P8HKtz{({eR5*Bz&l{7c}q zlGg@`Y59G|ygM&_R)0&c3B)hu>Gru(F)f$$k7;T8{J)54IiEh8vPm&5#{uJDF)e2~ z`TNGS97&nJF)htJMUQ`rxvqJBsF;@LQ}19gEsrHF>deb%_q@!B!cr`Y`uev`fglI zh`dUgJJx3WiB}CTZcmPB`55;(Nf!IRj%oQ6ZM!ioMbrOZ#I&T|<%UQ1iD_9v+p^1O zU&!!jo{9;$Zkj!=ePdd-IWaBkiD`Ko;~t=1t2)KrGrA==_!V%L9MiIsd#j{3^f+Xe`~BmS#+yn3n(bgiXVm10S4X$F$VkJP+8R?Hzq%T7C!E zD;?O|t|X@AqW&>0j{xyaV);my4OO3%ac!6SC&ZJ-YePUWpga23CI9cwVYcw=TOv~>whq_1`ET$z!{^fmR zS{BlVVp0V46;vOL4X!FBtn)e+dZI52nSk>V73@WxMtV!Oe5$e{ zt6nPS?BQ;=-ZR`i}630cDuiskzdlb^y4V;ak?m@wxhJ202XW? z(>i$1=*&|s;TLY#~$P2!n!hOl4Pv@6|jpQPDVB16Z zaq;~l>J`07o|PSQ`z-4b{ZEGb6X?4FnJmxBG5y%We~oX5GOjH^&t!YjX{2F4TAOU2 zxrMp73;TH0DVDkWB^P*n%y(bvoOp%@I+qbz*TjkT_)WvgKcE6 zGT)%gZ7Ne_m-&M6GwmFrObKP!f6v7JZeZK#mO;-Qteq*8sZg1TcA1Y3qs(!Xxj=KW#bvz+(kybCVnxu5sZ&igXn zM>y~I@}BCv-_5)Dh4R<%uKA<)yLi|9@8Frkd~)Z=w$Zrev~-X6HlDP zZ!*70{POr6$8S8p98bKGIf<^h!(W5U3jSo%Qp|eE++?4{+x=lmc-Ki*9G|AbM);oc7dq$kN^WGY$kyS4iOa3H&$#*PfmWOl9?nYMrUw8$|5^%Z}}oC zyn7KbOBWG)g#DiAwJD3i8B0LBjw&!n{Y0k>|?&-1d6yOWR`0dDC%6)~|=$uY{ z>ObGxJ>Ndt;8EudL&T96AC+BLbdyg^YA63r<+t_q%*c_nC!Yu(^F_Ql|Lfg)a4UctUn8sjQiQTckod4CU_CHTbx&yL(+AbxsQw|&vv=VIW*HsfQ>i(O-x zvymbEz2xKAeKv9)|FQM>EPhG*TmJw?Q{LET6bmjp^1`FchuPd8V&h_GTX)~GBY!1- zCGcmJ@MCY#tYO$-7Q>6Ib9>@(Y#}aBBfb>UNj{^@pE*}m>C{)*U0+7z_oNMk!wrIq zby~3cy)JHvC&YIjc+mduhdP6WznI{cE*_LggQfLm*TKq>8#6{02iSJqv!1sx{ba{zz)|`C*a^iAN zyyN0Pd^5D`OQsLWv3&n%>rmqHW=CqdM_KoAp3sTBb4F|`_l}zT&7|AhQ~BYR|9nakB@8QtHUr;lo`!#nDcx3$mh`ukeg zuigDw`D&g?>?ZMmR=$Uvc@pZLCs~n$nv=|_L`*VS&p!F@X|HiQ?F}$jc2MTjv*J^4 zA(q-I@3`%qn-k?-7obObQ#UFmao4}^w9h=99w1~UMcmjw1TlZ|3z6$;xAkLlEh8pHw2WeU>0@Qn| z<~wzS?((g?BgNOS>jEqOJ#wMzCQv&O+YWn-)SQA1hcRMx-etaa}C76qQYvq+!Hci`&azpoE3 zeS|i4lQs}PyPved=;z0z4Hnm}inOTsHgw;`(@)+)G*N|ROzZDsx89O8Bnr~kmPa5k}N^1e#{uPHI{1tkwy@XF}D1I)*J zJ@FmPY0cYG%~@m#lXsB0`!RW|uRJIG*hRy_kKyb4@Ymphz}6SXX8_k=cI7Fg4Tgsk zNb7tqu+FSkfr-H_HwV@kosD~a(zqiufvggRzZg6lKGO%!e49WW=$&>Rp8dvxZyCxn z$H~L9Umm`tDbG|V56^yi_~s$cU^ei5!t1F{d7k~s^KGZ{TujWFeAeWglK9E|-<4Mq z-#w`$UX_x$eGhYN?~H(OTwXD(BvwfJD&jyjG5?hB^Lgwgi_V#&Wx&$GnwL+WkoSty z>+v~jT}4*&!2;j~}&nCw9*~HkMh3~}7@V4QlCa&BMkvRopqhN+dRwoi`CsW5h zc)*L^D`PJnNVLe8qW&i4uQS&*&t3bS=5~TP?#^v|?Q%jtY%uXpeK+i1^O4QiFx`$CN>idy%+)RmgG`$X`8cbw>AEJ@Z3o znKiHD)RH*9EhjG|Un?}!mp4p-K08h-8IW(BptQ*YryWb0fyLP)H)}`fF+o3Y%lD}- z&IemJ{0=^)d%E~j*=`&<<7~!Q>x=S(R~PTnhcup7gR4^RCi4gFdĨSl8{HN>_v z4H>Qdo8{WS8OnGyO|pVFa6eP)gNfq$#r8P*_%6NB&=qTDg0)L}TB0gF{1CA$jJ*V1 z(uW@D`;fcJhND-)4;t38hS9z&4+-afjqO7Ce2+}TorAVa)Cs<~fY+Lb4u5^Ezs06I zqw`AlMF&2HHeGs20I%fQTi`7ni=;#1ySRjPRkG9#fp`?0)?a6>Rs7bAIV<&JWCZy7 zS~G_C%popqAiimx_Q5kEfiJ8nXEDC2LwcvXHtzx-^~hIE@Di=%ZriKXCTFu!)o1zq zIQp}Aj=s4%^M-GspW5qxFaeC(`|w#-JQe?bgY%4@aqj|NY~GP`IaAqj5;jTc%g{(M zvd}L0?6g$Uuc56P{BbC^oB0)e2f6^R%51A83OvZe?ehOm){#rHk)xt*#Y&eQF2Nj{ zdkx><)r>2;MNR{8lY&{ihisWL7^2UE$tYLTcgfX`p4{$xv`7EcnIS(gjD3PQvgpZv zFZDbAiF|LCp6rK)jI4`(Dp}RlJsa_daq{=l+4s^olCOe%z2N*w51fuZ-=5LL`URYoPQNSZw}DeW43115HTpaZ%-MLAnB%=VehMTbrqExk53@`Xbi$uLO=^8dtvsma#ouW(>$?MQ|xH*%H( zlge}elh44E5eWg4XyP&l4}vSVTc6I2e3f!46F|4$ZS?6LdRpU@H8f4EVSEIoQ@6W1 zbrW}INsiw&2c9DN+?L^&_tL46;X95C#J_;feU$BlPGonP!QK|MT&^_f)zYbFF^@0# zZ)`xvCh63qJ36(!e$=5;R~en!UO%XRFrBCbx)to%@HJ$|mXYAD!*AnFaq2?O91dZF zk{&IZ(!Or~1pU{YM|tK9+jx;`bNDB1=e$_T`tK-ahRea?)&ohXm8z7QX0W7j`!e_=m(()_P(BPPzl z*+$n7Wv_bD=gE35?ci;jrQa_=|KG;hL|4C0txh~N1s#7a?No2OeRBhFChPZ=*;&Ni z86O$T8kWs^)g)<|m{2$Bzar{r?{}KEzxD0+}7;KM9Dh9qV}G~x805loE3TV z!NdyA^k8Smiu{iE2HqVzLwg@PL%Z&umHcoCmq^bJ=Alxz^Kw`H_aM7le=vxR=NM)hO%^cZ-{5# zd`3>8Udf+22VUBzUDegeca<~p^H2KdA5L3tJt{B1W49f*|1SKlou%!*hO$aWMpho> zcV%j~pT7GW%A{*3rh{9b^d`4X7pH1FMBef*sV_<%$@1c31L-LzKodb=??5*(Itsc9 zH(std75lF#1K*R5(x~$)4&ReK*5!R;|K{i@$imW5n#ebhj*H9_g%>7qDgIKnYPZNEtkir zO|@hC3SL!rR5l9cwP1LM`jhht)~(_(lA+%0?vFX!>Gt_rXi9vj^g3tkWD`JdG;Lf! zy|bVL>5|l+sNzf=ZB&v+-|8vj=G8c;@0#0*DjOdfFTrDM2dWErL~E+&IqJy(2gnwh zbIm?Sm%H*M`Q>Fs8h>g{*+}1|A9X>8yRpUkJ&d3Bh&;}{b$nMpP9|S;lF{RueM9@{ zam}tC*NMKghkS{2n+Js)eIbMl9nv1>aGqPOO=)B9Iyx0wr>}&&pnzYv*aOXI57bZG z52NFWm#5qE)F;d{-G}-#Wwpn#6PzAE|5Q3LQ(MBwFUVuf$@*Lkdwi9*wH1fhOPGO8 zJi`4f(cxOl_>COfFpWLW4Bjgp7%PEsFdN}c=1Az-JHnFbS@X(6#M(sd)0=<%ILM|d1~uc@UaUTyP5IPUSbD2i|*wJaGvF6`rC!x8RHI( z)O)N08jro4BbN-Pe)iK{;g7x_qPvnV-POeWWY5m;RbR(9OrW18?wJ15e!Z7ZkVqm!<~}>c3>bo8kNU$5}0*L!a@ch>AS>=y@G3((~#BJ!2m+lx?Ub4P;=yc?zSAf;pb?4?8 z(4qFVv>&2*`Y!j?uEK9B%)J@U85kwAXCSMhPm*`-L@VgpO?Lx(*L-x+QMnDm>z+k{ z_)D9ohlSgV_i#rG{LKGdbf+X7rXgGTM~`o4Cav`P_HJ653%*55x^qM}-2&?73`IOp zVe>%g896ru;wu&s|B|~7Wm}11N3J9PiQotx*lSMS+G3ZlzRsHR33UlJ<#+d(_c9L^ z-;1&9K1+EX`PQz!D=eJmb5Ch_^&R0=$aSkYM{I%nj03YCZUrZmU)-^|^bV_K2l;SW27JMoAbwN2l}b27;n9Uq8yv6r@(J+w^dTKimy zSFL!WDmxrtPWym2SvU_wGex2k}E=YS>m?I+Z?^!z6K7g2 zGZOJ-W;8^9MH`gusLKqm2L|SG`J1)Yrc`3|HKw$lDL&-$S!_*JpBbvPIEQToRXz&; zol#@$d;=YD8|7UYJ=MwU%IL(9Kn5pnMlN;ufS356*n!JCo?}mW_+4SYWo>u&9ku6p zDtnHJmB63K2s0k#UEn8d@RPbddXwg}FS3L_$p1y<1&e$W4bIZQ*=p9~^o;N@#)E-0{Wwi&fd!^X}HhSMszI8ln?_s9s z{YCpdL7Qd|g_s*Jddp%L;HO*p#hsh$zi+kt=(9Vy&mlW93izc%;$yXQ5$&uR75J>_ zI_|RgKCwya&c_E+u_|;w+>zlQ-e>zsiT-@>KO7wi~`wNbh;3&4pir;b) zwmbHQ+A7tr3t|^=Zc_bfyRN5S?=wI9_N(*TR{50c)vvOoejO1$lYYrR%gAz7M}#|O z4G9KlS94bF-buS!i#8u`w_EycYf8)f8^br>m9_F_+K$q8bcxln+u$@avd-bd2?wVi zf>X~`-1~5y+P;9cb$3E$flAa&;FS(AfTw@8X+{PMTk7-W9JX?IhqZ zI3!JcK;MppCOLZ_X?5~rU!M|UUU+Ia)4tVbVxx)1eBe##duQrCGvdS}7wmy1_Y=Rg5x=ej%$ttYzTg(-nPN?z0=!-0ORzt3 z{|I}PMb9jKat3FT=fX&Ofyd3K9nMs) zo$DFZpx7h#6F)Z1lh)8UG(e2nk~IP6PIARI+2$P`v4ESq!sjWT$z)G@!+oiN&pLot zeZfW&ypMJCfhE_+MlC+U#3-raj+sU9YsKltRo(7gZyf>)zmO^l8zg^42mJWxINpxJ;?6-#*qH$!cF`oGQKimwbwRn1+0# z`_ZqR<||Gc9f)7<+>f4`PCvk(@|0{(lMMM!}t*b5fG;#v&8G z%6^;5xq7$sIM;R~US0ajhO%PjfBmoQ_UegYsQmrb8~B9sUxWRvt=Y~SIz(QrO;?cD z_kx|bZGgOruT%P>ogVFzuJYnd^QfbKt)0gQzY>p+w%Gs0zmj29{u$&~U)x@>^Hfr= zzE9)3@?Hb2qp!+7(0$emoqc(-eV`2dCf94$lsb4C;1q zt2We6*A`GIn;&cW$JA%w>(TekSsUg59&;caU0*ceTWQM%q8GPL(aS*aN?v&N^WL@v zSC(+)h*IiPzE82IsLs+pG^jZgp^mn@9QSeAA@Vq9i0}vMK0|aq>8AWI zjt!Ra?tjRJF`5LUa4TAPiMI4z@0H{;_$RFwtc~24dO$k_M0ISN$W)ntcsIFwM>JW6Vd=CTD*BDFLq)u^oj=n!Z`HsbhDsS7m>L@>( z@|8C@^G~)Y2Y-TF@b{&=WINj>w8=Owx2`Mfjlay}gDK4S_m=gH^ZUHJ_D#{f_6ao~ zliTap7UOK_75wboW8>#4`etD_?pv-euS}lv+3+DVUz7XBIA|_)=c5gsaZtVI(ndb( zp*v6YZJ@a?8Y^{ZGkKpuecK4UhQ`k}=jhBG@X!|VRO~z8mxB-KxnC^RT&XUr;J+Df zVl&DPhMX7oF#ahzpZ5JZ@tG6m#22aW_bjr`Ne*G#_B6}{)Ti&u?zGCYDs^L!oapuyeM$BC|*3(hOD`OBEe z!HLYv66$USZ@=RAOMV)k9rgC}U(WNN&U2gdj5^OxcnXI@2Ed`}>5KDW4$fn=(|3FZ z%D)euuloOanEC(Z%+ke|GY>9cKQwocymHX8!+h@@qT}2R|>6U;9a? zX-@L1OGS38)?5- z?J!sV%c)oEN;+xD^=WBaN65J{x<9>hQ|)j549`UBM#gjk^d*aeb;H$Ba&5BzxHO`cj?V8-Kbr6j9nPy z$2$W&?v@^oel2=wMMtd0e|H++MJG+76Vh*V=wy*-0e$CW();@EzE59V-`z{exAtP$ zX0uGJ>D|b*+RH~5ZjnDe@gs=;l@ZASzts+Xo=2Hv`do_-?v1+Z8~U8Bc2%DLGxbg# z7Vk6kPCY}Zr|-h}>}xAt%)4~YE!YnhbB5;BTPtG|sN+W9sOP_*X9;(wkbYV% z{{@G8zp(C`4On@9R(onk?Wry80TD0Mv{yf@-Lz3idw$;4w)SwY!VXe7Dzza4{k)R? z7@e2CsQ&(U+ANy^vTS<`>3R9ycimrf^w$Jo_ z*w6Eh3}zHi?sm%E%+EcextaHO_&v*SHNW}%=6N{hIVHT;-YZ!yTdeF~6^z}_CV4j5 zG?^2r#l|mxsS$so|J<>>kn~X9GNU*9H3t@AV`fhz`Ud@458T=lm%r`r`9CWy`1yKk zT{bXj|8W<5fXjA>8%hCS`s{$OfPXP$O!?rE>|?qy|8Y;e=whiY#L^XNRQG^qG}B5o2{qq^zxK>T!I<3_PLLQ^Rh*Lv^_^x7}6Xv-%W!{>H9JGrEiFHfL$6v&!hh z_<`vhmBD##Ycmz809A!?uNPhA4h94Wg z8;e4BUF26Rf)H?Ub|S`Et7(nA=K)IqJ|1H}NT*5e&wS>rbprMUubJ~^-?NjvI@_td z>bLR>pEpuIitZ@7>-Zl1!B4OHc&of`oy880Do*H)qd*dlgr5%RGP)lh$Ng4(+wC@f zBH%6{9C?#*R6V^Od<=*q%6}P-X1X{^U=t(%p>Xu80dO=79AUdYEF4W9pnL~BrIWFi zzQbB$&IxB>dkekZ<5%2y4Exo5%l&O2{yunf#v|y%rYJg<|FaMKqx_$v>N!x>L&09f;x$De^Ov;P7dQD-fPvKE;3u|tL`jwsH7zxN$?=^w_=nsUAR`BqOq zYfiBHIpJ;Wg!mxW+jM94-%UU9pRRZMS$~T9IiVjNs-IeSDoA(A@2m$;Hr@8m|2x(y zQ+M|nPOWBYaHWodW+#`VklfckeB z^Y?D@`JH_J?)q$alH0zGe9_hEW?hOp^Id#VvXSs8zwWjZxnmqzNV0=U|DcevfJ=+3(S;=lDJL#c2+(Ro=I(tQWo# zW5VxoC%t%mA~8Dr1AM-0|U>GuQCXW-VOl ziC?aLP0q=*y>6eAsee7O)}p-CG1Rt^aqrX+baS1P`IvR5^9^6{S?)0EU|kPvNEDY= zFDttg-QU!IkbAi4Kf3(#g0sh)ex+awnaLd$q6L?3K7hD0q7t&+$AJ^FVe1 z^+A1-+^;e#=$r4}Wo5#V`kO)j{wHnyr`n>t_PN`5Ca14yKUewZPza= zLyi|t+cWW3mpm$&xYyVK=QrRBhHf06dhwRf>ju}vc4DvoeeMaPPs!_27+Dbelk9)a z+4TPP*8jrhQ`UR^%Riy=!#Ufcv330F3{BxzCwyryR&BcTum)V503HV7tAD>cu_EH& z!nGA?3`AQRlhD#-WiL2*kPm%kw-0@Pm@ju=uGrKc=IbN}qZb`6%;msbN!!WeCYV~W zhx?ZGpCf`Tvs}?;*;cYRl<|9NYKAd&Co*vDLm@=q+b#-^MRv zfPS7rKO2e9eWGz+3%cj6?JPldw_f9wi$+=is{nIJz$Gy}w$|dZ>NcP|gv>ONqPE zw|oe^iTAa#Pu)vC`b&>|R1mQHI_|#%@h9hWum3@<|E90VN0L1x2l{8Lul?l#^;L7n zBE9r5DF4kd40OMQM|R1BAQfnhNDXg9nge~#p% zvBs8S^JQD_aQSkh;{z&OD&5sZZlaB+&bHS24?~_ghrEX~=F^1-r#>I}9!w89g?!Pi zzTWbY^wokM`KWXj@)0VR97A=m9B_g!NRT( zs=LJaB`5nitViEpNFCA5PV9(9qwLrbyGnE}w|Cr^U7q+w%KNMvlVYTu_xA(j#eO1w z9KGF*N#Vq=SUEsm^bLDURCXQbTcf^le;{_m;O_b7U{{=t zeerDUjI)R}F_Tym+=V`Tj)^rPe%q~w%s>Y@!{{OHvaJyNQ@q|j!^n6Z!@7Kw*gv*!%M3mmJt9NT0$M-Z_B%V;^*uJdU#Yg#O};<9`#s_&@sh z=R*49$lT62_LqgHfDdCodaZx?*(z_#+=Jl5u220@-%bD@w#?mMK3T>%zOOS-tUVgL zHt=#)(wI%?)}Q*rnC`&X_;P<3Cw%Fc^@ec>FuLoX#ze5x1B-mJ4keR(7x*P#<%1`! zovK6U-b7#OyVg(PA;x^OHsGh>tg&jt9q&rk+GA-)dApbo?i#J~?}?r%QwT3`c%JdI z_TLZvuusr+uf0B>PWdQh-E&rEUJW3xkAhzIgYQGg>pkbTUrUzP@r`uinZ@6><@E#b zChJTiubVgy$m{K)Ey(NhdgS$*qii{7!pDL5YsavLd*R{E85_~9k=NnXCYHm*!EJn! zl`BYh${*6k_jc{T^7?vbtU7>0vB{G0SuYrn*Zsd9Q@nHld**Aym|yyl(8a{q1d%*ER1f(w*`Y;o}H!L_4S{Rcd0&Ll)SzN7|gmpfIZU(J?9@Ud0oD& zwvN!(jv{$oed)_&5;?{$vb%*_GpnOhmB&~wkf>-oW`Y18^ajaxMd?RTb$92mS{bAhua~sCSKlUF--xz$P)v!AzJXkM~-x8K{AD*ZD>g}a8pUn?AYd|q=EaAN8ZLW?YybvO&y>w+2m0S3FT{?Lwy&pXM@kiSB6-R z$X6oDSm3)Bi%#yLZ8M()$5$zXpPBOKI{8D4pUHn*PyU1O&;WT|JYL9niB>DVYOVcz z68&VKaP55hgY2QbRKAzj9~%f8xfnaPA33ysk*_%P!@xSmcU`EC=NUX{cdYDK&nz>0 zHJ?+@pC6bL58WPEC!b3B8IET?XKdE#?73{vEyQGtVYiTM8?Eq}n9=KLa~o&arJt!V?&S9_F#6N7(9t}VYz41+3~1s+vnmB=d*1hl39%{J0F=2xhc<+y?q1s(Pps5 zyf~b*nNIx^(&bM^?2BX_z>!IPUdJAUJo(?W<;T9RbLfi~of9vZ@86h0OrIB@JtHi> zdCz;ctT0$Sr?)Bp8ZnrB1JwOH(#{2r(hR|wy8To9hLYi#3;a6Qwd@jK@m%1)!a3J< zZn|ar0sv>p9?lg5+l$ooEVdTeh2FmtpGe-t3pvMCB)>L$uVz9d4sWQKZ=I%g{>}IL zBssOo*hXy`KxKbQou^|fONQOfW7|fQ=TY*A7UW~Lo-^m`6K96u@y#!-_H0W08~XYl zcH6oMrzfh84u=wFgiGm@>*Lr+d&=wjICkc9Z?ZEUS|hYp?Lvo;ju4_g#bme%zu@t- zRr!2v8S`}A6nwMfUnYMAGw#G>C_r{(P3A28Wih``bAsm(Xqj`|uO_B(55c(8b<#sbN#P+TL)$#t2U5Oe%O;xpUQ9fSTo17eiAmw$#rVSP#U|&_?oQFJ zZ4=Ikd|mhfcG1eQpRiwBcWG>aXZ-d??0}l%5&WgLv%V<4bZc$v^e{0PbRSG>t?Pd^ z7XPbpu?*(W)AXa3@sRJ7>sv%0Pxo;LjpkSsyW*>LV`Kd1KAQ27BIrPU58-nari|@h zbSXYq;~XEXOR+hQ-!8l13gG;VwZK9)etFmJVbyany!^Gu&I_e z(x0YT_Wd~5!(T$&r_)IO5O7WhzE#|BT|=GVW13)-tyAY+wSP0zz_b9E#sSl%2BxM- zcZJ>9YW{!~^fPuQ4LohwnJBODww{UK{+SOzuZ^pTEkgSb0&64XUHGp7evRkaor$$~ zkgv4F@gZgGBAMWN)L24z*>|vcfyW=R`4%vmxuh|(X*w2RXshp)#5x;>9L&k%`DpD9bfdzr--LT z+b%CwogYwV+mpyT@OriB$}tx^deuL5=3`}l{Xk`9x6wS2e5CxpBX4P=?RTNN)XvSo zuk^o=R@tEm_x`Rv{}lkvIh%O{ zKm2`kK2!XLxGOoOPa$i9<4T^ovpMt=$B%?(UmUM+aQv|P`qO1)ieKwnwamnds;7M4 z{5L!K?KSTdI!J6_u{c!0gnRaIKy<^evU=uW+ zBYGZ$r<_hc@qnoKhGXM@mTxa^zSG2@79Gp(C!bHnY-r`bVqMGMvV#4Er^u`Qg%|6- z75gD=h<~o&+x~aH72b(_P<>Qy+0Ul!aglN4vChCQ%5(RE1>xw{VXWs?WE}i>--lM5 z^AIh2@ki8tM}qsbUWT{D+4GnL&*&g;(HsMtIL^w>~>o!vyN9;I8D%1G69Avx@qNPmy>Ke+9<*^GU=ZB=$)uV|XQX zDQ1ZHoxThArJ0!xTN;iCM_0&)UhyI`BJVTi9S<`Wi-rWdh!yhjJArjwt3BaQ)+6iX z%_-z8^g80UuTxBsZIg&yz*ufsG>rSbhXp^X8yeKwh75=Au(fW}9kOW!;<>5VFy1@g zoU3r@@e$}T`Rs=7A`?BvSQA8#yC3X{BeIKc9V_iKK0EaOto{C}-WmHmYn)lPy7;fX zRX?<&Jym#3ue0OYQ(91M+Eu`yw2I>7<}v+e&6Bu zZGN+upU7I7Rs3X^(pjwYocCPkIo5gV?84s7=X17;Gg|QWeDPMp+wD8=j)8vnGS8G& z!ra=+oYFcXy+Cr9%60G!nQ!el^15>@NAJ!Y%hY?)92=wm%<)k?1*hte93a{e-IVby zpI;t7-D4&nQJoE%$Zs}3!LEMf@XO}6m-4Rc)(FpvfiLl>uQ_Rg^$hTm{SmQ=;dQdi9U$Qk)!tK^Id1ix{k9R@$u{nlW6&PzI&XszU$>*X>-@+Z<+N{ICR%X@KXLK z(%iLEINbH`o;xAlCe2-E`bJxefB{5SO- zOss9B-beUv>OGif`6qOrsMGzRL&68W9`1r0ir>I6{0D~PN8sapQfhd8;;isK<_-L6 zxyE6AU0y5-ZRDl$<8C3HZM$sqIdNOh8@GMP5$Eo!A$GRkYh-WEFWL42zZYF?5plS% zD@dQz8Dz!bn8N)y(Z<@c__H4T6p%IP@A=?TaeuRCTd(*%iZPHAc^KWL5cp>hH%w>C zno?=wh_+&XdLS-4LlO5UAXlKnWi{lm?#mt#wdHu8)Iq&%j$Gf?Ez@U5{st|ICjb6- z6JMx1M)A+#Y57Mo7RObY7+$-es zOd#g)orA>CJMhpM#L#;cI4btuwfVb@gKRaDFJx!GB7H)`40NlUH-ZJo@@eK?`wgS%?$lnk1o`w7^-RdgvVQKAx4qTacO%t-pFl)+q z;89#Wzdhz=AJLX8$42fJeyOjCv459*gN?&&jG}ru!`4{kNGuHCx2P zcz}2HA^OwWGSw$qlwRI}o~JdYlc(00tGIE?qsEzk^jQa$xeta;Rt z3vbid4CeDRoxXMsH-1gcR_ht6zg>Fe7H@9RSneldBR@y`!D-YhAGn_#YdxYi#cT9E z3U1}!0X3#5)*cC(kD3X#^Krh6lpG zycJq0BAxN&PSk$)Ozi`I6(>6BC-zVOjCARR(r0{4c6+5 zd}FceTAb1Kw&~+zoxA4r~77i&j)|tNB7EVOjd%YYWlf* zehD=DdPwwY=8bb6<3rj84^zJGjEUrQH}Bclw>sblJG<+D75ca9k1a@HPIzf=NO+nB zFN9xg=PdDMyzlZ3DcbGz7Ad||alRG2nBOf!tn;NSDmJ94aE3r)c8{0!@%dmf5K$%k zjL3DsqWK^hS@iAVaiI1XgB=znFn4;-x( zY?aRZ`i90ZY24J_4fMnGiM6%!hPpD%S2zDm@)!J|t_*(EZv7#pd!Ao)RCQV2|{S^B6|gDd-x9cMmVsp6FI1BNUT_N z<*7M4uKd-jz!^L-I?D=rkafhLw+t_NL3F{MXZZV@Z2uAUQM4@D+Q1wZ?XCmgI(wx# zp}L#EGiyUU054Pdj~UZ?drYy}vcEyug=QXPMk17@t+4K(pUN1Bhq>cv#y4|F(6#q1 zBCqHzxqs@HnKP-@^R37R$ag!n2iD1ZVg9T_|E<2rYt(J%gEREHkEjGb$GM*=^|Ylk z{9|d?q;n^<=DcaQ+{@aL5!p&vx1Oliw{bQ9)lcF4SM*C~xUexq6iXtRK9c#X@SHpk zGzUV?91uPmc^53&gQ`r)FBT4z$7kksPwa%s9$sSBsC?4xxsegM1l;uHBf^v5yY*(9 z@7>JPvxUingT-mA&CpJD?HkjVvMyGPsyU+(+1&F2iA zUOg<>37q10qSdCHy0V$%l@3=jzOJm6cQd9_hIjL{=eeUx{q2B1_3iWT=!4)_eed)d z@AXDj&>l|_b89PmS_W2NF|gLmjvoiCrmg?%X{+EK;9*Q2p-ssL2XEit;$yixuRmd3 zpfAe{c8>^dK~A0dl`*!T{GUbyi4VN|nP^rJIViFS*t9=b3BNSHh@LUUmGH_o_)I7K zx`1*W#F|+Ad+@tIaoR`ZrH}279Ng~6!R@Xb{3`RoowJEL@pI@I{uf7{j4kjoenXI1 zh7vC!B|;zDeVr!+*N=uCtE})W<}7kch%rf04jV`S6Si!5N)+MN|azKOiP0X$i;;*tmJ%D&DRs_q)*f?K!Xuxy;S zd%*cyoDBo#&DPaEjc>DL@C}bL?%;eT<#T9rJMmFiXWEN@Guy-#TFQQ9(XF?z=a;=b zA0D2|zG0px*TglFZSD!u3vR!~#KC>wb>Q(3e%fHB(3VwH3`9q{< zv=>B=77WDg8xnl_ANQ9n0>73gHZ^qHEivJx4O~T$<%EZg#CHD=#z**!!+)7yYnvXZ zGy5ZL(7sC>)Vsr>i}sn|%+wEEfWzizGLH#V=D|NZ<3Q^s?Du z(ckA6pB;`Pf5#SReMAPYv)7M9(aFiwEq=Z$omjwL`VP(cSSKXI7=8-u;0PtSud8o}z9e6XUhC7x6i=ZY)+P4!&_Ok)7fudpK2JnuTgz{i z<{Q4Q#hj;28_pJyzzf2Xu2g4nz;W5NAR?`BQz5>pVxEp(oLo;R(=(&xgMs^ic?X zq(UDqZJG3%Ioh9SFL-;V*;n%Y#Ga%1_)|z1Om6SX>HF8={my*fcTEbqV$XVD)mTRne_@eM0Do~c-%iT|$7-+_q znqT~rr)+(!f_uzX!FOA+*Qt&7Xrp5yvSO0l;&W(QHo5u}#~6D+C;OJ=(A}%hK{feH zv2Tg~B(s!yUDBusb$T9`kBE=Ve%l9jxIfK)swydEwx)(2Itxckx9qt-^ z8)fBZwT$xaI$eK~vrc2*OJ1j|e#<)jdEzwXzl;2aXP!4g_1f#$hwx1LeGhj(DbG#h z`Q42+ZUTD~Evu1x42;+(GNB3C0jG{WC#Jq?uOYxZdl?^ncRj8@cFa`SOeGWl0vxv% zT2rQgoA>^5PIv}mJp(?l8(MSlYjm82j-FCYzxImHIrxf#FFP$Kaw};U!8_WLQ&pG&MiehNVhD~zx z62{*hOox*un%CT{dHG+=pPH9Hxl{Z9er@zb7arIahwDD+fQN^BGX;+UC(%dFXpaXo za8>{N(D%xu)59Y!^)&Ec4sphV&5lh0zHdxtUV;7s{ZEBS-5E)FZ_t+~uzg+xHqvWY zd)RfGFD-my?}@Fmuw&#GnvP7JBD^IAS{pwycsOhwV}1aiqTLYXq<@V%xFlG^nV^EH z{KE!c#Mmc$CK~%xbv?1(_Iqa@ZmWqf&%ir1b@ahKzhkfTCiV@=hJ6xPsJ`P(OH7^T zQK#B@>VuAUWLtR2GxP6`%#Y#2A8`+q_^+J)X&qN()Bmv~m`Z*#o=$S5hW5Ji8$U-{ zcQKSdCatp!AVw>f^XYS!I(;~Du&qXS0m2`M|(|dKTD+zdTJC60^hn%9QdB( ztVq@a6ch3-%DH$tCU`V23I2_5E__qk;hPd21AJAclKVPuI4yirqGRcIY`rf~@9$#T z63nI_SrSy6@{5n9zS1My$HW+P7wT%hjpkbe{x|oV?f_)oJH>V}YtGI(@oMOB9r9xa ze$Ws)d^tM%e&l{UJUzq1y6d0Y3gGQ#KfauqtQW2)eI~Rg`FA&C3;d~VA!>jJXWVaXoVO5;?dweM*e0*cfu1J_bv%8q@VH)yvh3uyjOJ5Z{&Hq&2>BF zH4nGF+~Gg#e72ymx6miGW+(rVWIztK*Zwvu0t~hs!|s~TQ?}6#be{1`89iz>``qcn&l#Ji*HYQro2|x8$THQr49> zk~P5yu(D*sF+tK;Zh__|bjt3uT5o|s9ni`p(1g~d4ZtJjNp_`|NS-U02 z<*Szs+y7VaanF`f8<)&zVZ&#-@K}oM!!Fpe_tWlmQf&Xz+IX{p(Ozq5&Wahf7{1d&;4}FiJNysZ9USomz0?&9Lsk&h4zFK*<)tDviL4} zU=g2ol~dAptvB_sc{&cpr^IF4tmvGTV&Q4 z(xM}&+wFT1bFAq*e%WEb=Lz;(lshmer`!VSgx7YdFFB9eK5!3X+zPC2=ALe~BYo)w z#;(JPxaraTYa?aPKmZb2T%1ur|6>H7Sf!)nON%`*oor7kN7?uUPf;0a(x=c*Y(51 z@DbWsd&A1$V&;YEMn2%5n1|kiY_n}h`GwM>JD6Wox9}nyYV27b%7#ymzD@nQM{bW( z&z01ZT(C0e@2brceZz0j<`L32(dOl*&D3Z!ZCZ!gYNnG`WREReL>saN+_f^omqg8e>{?BjxX-z8j~n3@WDFte@jokUnzc)|J6y$d#%taI%(iI~k{u6@k8C z<{=|1(4TU@8MfucZ>U525j2l6-*zhlHvd;=d$q$KgnZsCJ1pmdiAGm1MP?^d%MSEJ z@x8V0i(S>XyM3{7O%3?yxLc^X*qN{WXHSmA2Li2yz#$M7E!jJeP`|<4_Z$jwz_*5?9|L=3G*4MCw5BUtn_^ zw|DnrtnD;Lt@DU4m`}~U&BJ(id883|8@&DSjCQ=u{L6}W z4}1F0gpRe&`$fjLm+|>6TgJ$4FX|QFQVUF+Z|(BZf|kS&vA(j?(aYJNp_iA41+mvl zI{OpamZa|nD!SS4>l2-P5&l5Y1a@qM^QILOth>0hzBP^czN)W3tW3Uj|GYq*P4gkhf`)h>o3s>9`2v|YD)>_;`x>jjYuz)zM!>4(NX+O zo8HIq9DdWvw`V|4MgG#@tNg~4l@Gec@)hTT$Ga`>G}8`x(dr!+gbvZxA>{OP*A5N+ zF3TH!wr`)%YM#41x3pAv2DI#=4;7vvExVS@Xd&P3Hu_MpETg3l{n!pohme;CeTli% z6TIOIkrDl%>*px9IXBR{nQ}i_X0_a{x`Teo^g#ky+7wUK(n%c@KLQhC+$x~F&O?-|^6!}mAT1~5ECpXbre zVPD_qCEl;LT!Ozcb9tZzVY@r{h_&A1JtOo7&lw@stD3)5Te0qUJJzfNho%kDoZ&&| zF6>65Gfc$)HXwINPwRR2vyC|WlqU`ZOyI=oO=;Hi9>uyiW)}%)Q zYj-6kh5CczaokIn1q~#{2U-&!NnFnuZ-D0dL#r2O0ngXSJDa}idC(Uhg=U+FV>{d> zT8B3`z+(q}35GX|`zC~n;Z3c<%wuk2uFGuz@9%$;`JKDl1*iBkujGs>TlP$W9yEtY zkJB8Oy&);DYPN6p{--N~bH+yhE9o*Tyb9l8a;p`7j6EHPkeP?Rn-`8R$yq<`WXYcV zlV4wZjVB=?y0`D(86In1{!OcHYr1vr{e2$y^!LYEyEhE<%`4tFZH_zwzTxfMyC=RbLFOo5@lBz(Wy{@l?fIeAz);`yZ3EBMH?4kK_w-2?O=13v z_oRmM$8(N2cF#om5utwJIlnBlF5i<{KkZ6uxAt3??6sQzh28ivzP1a%!^TAawbfov zc-WAQ*UmjTanI}_{%fbvm%H{qye0}hhw?p>pX&aQas2Q}?j6jsn&(;H_(3MWd&dm8 zb}`R2Ja1UkfBh!@e~JGa`2`kP>#uvH-}+(RJAd#)&%0yZJ9EIb7cEL!@3HRu!S$qv z$-9?tkMsY~!%6F}SJ_9B)_aw|=PP5BzK`^Nq*w6kM_oxy9*aB;q$#fRZqfvc3wgf& zaN_!V$a4|D4FlHqL)!FP?|Sm|ZRbL}I}r|zFh z=Y;+zLi_jvE1t+d7ke4|ZBlA@{P)X)o4#Kfd=J|=fjiciV{`w9x$}ok8I$i9DdDm? z`0EvadN~zaPH%1grH$Xtbg1R6kvLIrh;|_5u^5;*ZN7 z_0qY4)(45ty@xaJ;~pqklM7AepB%sEYUp5I=r=6qfGnm8NIA0I@6_E2$ z4|r{({wB^QZA3O^oJ2<%Eg2k$gglAULN5;w6{Ckv^$iH+`_e+i$d+;N=%$PFKY4nT zRiHd~d547RcMh*F_6!Ogpx<%-cyLWIaMWF$j{&otz`J(YBh|C#elX^4-gPIY^wY|o za@h8TG;?a`@FX>SF))O4~sAE5{tK++3i_}N$G0=Qv`8wt*@8h0oYlYQ5 zS9u@z@$PM(tGti*@Q=6u5P$zLiWbK*IMVEg}*4Tgu6r+Q#Nb$zI(Fxe&Luteee0S zcOLSyRr>G@#<~$*MSX@ga-V^(|2KV)azAiB^Qp!l8a&@qKIrb(&kt2k4YXe4YuUP* z*tEM6`-C1vc5eqq8>J)01zJ}DduaCt^w0ho&YY?};bxrBVlgn*{i$ZGS+<^9`AJ*B zT=bq9(5W*=v}#|LiOoi5`62RNH26NaN#@Lf#((w+Tg|^8(|BHDxYAoX*8IOSG3?Q| zA18*rdj2yp>@#`#hAWp_=n&vc?|1ff^7VD{^)>k_mwT%l&+8Z7^cc7_`T9Be`Z@Xf zIr(}}SI_EyCInhXai{dr4D2=W=wQ}+;fpxN@C^Dwk@R->EdyLOGB-(=*L^b5etaT4@?_R>{MFre$LBm z!e$W84x$TP;Na@+-Zri-09VhcZP|O+bk*Q03a*OLk(r-w2w^i8(ieCr+%Ug%Y$1Bt zETfn8tKR<}G`ym3bs@UhETfzCM>k92eG>2JW{)THenxc;ZBKiBM5uTw&*N=dL%`$e z!~};%pi6v;qLG!zAZTRw0@^L7UE*1dP2=*TcyKOwcWs({)cUo9B5>zMr#fMa|NToZZkQ!N;tkKTTMbKBPQ(cLx( zW{2CjFZio1Inb_MIH%eoDpNUnGg#%Z?*1fZ&=}pfm;vY@?!A@x2_?Ts=7VZDc>byNK{pNLerNsXxc2cVnL-v*fcDF8pOH*=v$o z??)%gKp&e0UsTc75ahLMdkSyk(DQPzJym87vQECHbNVy02&Emgg z%R+wdQT8A7K{DnO+I#{y%_sdK>PARiu&(6r)Qo`Ij`@YDFEV_V42{ZDiLi6?H_tHi!f*^ynJ zPr14170A+X{x7ZF)0$_DJ|F!JUH_+{=8VzP&IybTai@*uwwlZAbx^Z@I~E;iap1D- zD@NzJKH9o3C*{3}&GY0LX3eZ3Zs3*ddGhVPXYaZ{+>`R$N6$^(@zIA59{q@ZwW2SC z2hAaVj5%c`>%RM$yFS2gR*fx^`|!2v^F48)X(z8*d)LYQ(5fG$56*eigFbHCBjX18 znxDZYNx0a0KsJed97XWS9PE&BjvaFM<+cqH|D*DCU!|S>*d90fhSdL@d%T8FcNKeF z=Cente1m87eV;zR3c73FfgW4x3tWcsV(gO4G^+2blu`Jxi)rdpyk(5_dj33w@>#y{6dX z2@8LsgPDvmfxfx4L)>9rsCbT{nWnj?(#&|`I7Bxs;O5OltL8djF&vtliEi+W*S2~5 z*gO-ld6<*Jx!62aedF709zQ%Q`}PiOp4Heq_hK_#%un`)Y#!Mp*DdO2Y#!MjKjSAG zNVdj%o;!bV2fEtR*eKUL(sz9p_R6)SKTf%ge0!At)z~A~@-Dk%r}AU-D18&@iKIWq zPxee-Cr>STDjl1rn6z=o!1H;A9!^+)7kMt=_w2)c)?dR@ZPoK#@2cw={wF%=i}{bw zt|0QeJalU-9FI;t;bHH3!B@795Bk}%uWiHvcw2lwA33lXUp2mXc-)TBG%?}G0rB|c zBjV}w+}`LTg7hh|~i!RT`!LyPPaqw&TS*)4B*ZYxE{|R1A6_*d?L&_@*{i&Sh>8K4-VkpQ({i) z2HCt??y-5b6@EMpuNwbrQi9g0H)r|T`>(j6uf~TL=adFtp&tL>Q~6lsY(BocOFsTR zWmr$2hXPtKrNp*l#K*-uFF%EkXI*kCAJ1L*SF)2Zdz7uVv(O*UT)&}g05?7m&{8!rlQE9M&v`hb19z4qbzw%${g12BHd%fJtUIAjB1-B2N zvscMOUn`t7=L)Skn|=OHd`Aj-41K@I*%q<%J-T;zQx@?}ZhB+yQ`0B;!~4$XzG651 zjmwo@;lyU|ntjw0_TKVX@C5wVW&KC};h|@j29LVwpDB;Mb?sxpgKm1~_MeRl?;Bbg z{5$E2^KgGBANmF7R}-(vn(W8Zy~NcMPwDIr5v^o{zan5IeX5o@6quPc$oIilCNx#2 zH8$3u@S{dc*f(uqr@RU+)j`WSF1#4FU>cB%K zaUVs_+T<$130l-T>+x4kUBjJ8ebRl)$m0ncdfa8*k|KKCC3@ThJ>Cvo9l>{?z6;Mq z)Nhwdj?OoALwoH1`gr;T#;-NhSE>^40ry5{OpE?E{ri(m3#ZhbRe`^Y`mdt?{iM77 zy`4H|k|r8+VXJ57{dazgSh=s4Zj&y}ezA4&C&#b#x0bBI$Jf-`&S&l9?l`Me_DC_l^L*_5 zgg)5qQvvik@SdC-C9mW`=e>eD$Nbyfy$x=xO>7;f z%lo4_+7Hq7e&Jhz=~3>HWuI{LaszWKdLOVB92NVP0L*Uo1=h$X_DAoanDHb>AE)0n zjHja?$^}B!$O=c!7}+Sk(!Ix$i{|be z68@naT z+L9kqq+>^RPXCh9*>`8su^T(5XOmupEZ4ZZ z+b6FyFJsF*Ztr!s_q8Oq?`xTf4@r4W7Ln)Ewvj)Hk&*U(U7MfX`A4$IGmrQu*4>Q0 zf*b?(h8`5-B;Ky&-Q;_iyEdgak*D0`vG221%s?scl4XKNIWV*3e@gTSeYM-TvQ=YK z*&^mL_0g@ru;cvCQ|6ApJ7q26FdCUN+ooF)53*Hzavx<+mfCG#9t)s@?FKjc-#!lP zhU~bcye+>YPMa}WuTC`jRtWi6W%qM;75xnKirpKY8vPAzs&DRmW#WB&&i*K5&p&~y zU{Xr#ecmqG#2;o;1ZR6q&g^HTo3qs=wx~WzrpYS#^Wk<-YXB zedvt;Rjz(!M1Ku!)Jj+6jEo&TotQuNuG!}>Z2_jIn_pvT$Hi+bPCL_#-{8H2W?VhF zGtGR1F?6PxMsOQTGs1N&JY0QaI%PAVhimA&<QJG@cN5$+VQ#xd<(ZHR){t;qBvMu&oDRH%x$g|jQ4Hn;!xv}2@e3Rd=GYn(* zhvRpx5T4Y&_7Dh94s47*R7+p{mMvd^sfpiwhjB>WE_B>a1sy6@* z3h93#{HFOLwoQ1XU_13_ZASWl@-^U}*SQt;UOfA}5SM5C#HyiN&I?h_KU({+?6Wk; z8`b<5JATog_SC;{Cv;1kvE;0gZ@^!4`bEyu_zrziTuJxmX`Ckh%GYPN_`?72WWxs; z9#2ytG34dn2y8QF8uuuIXl?v#=I_D$Fv!q+{)cj1ts3N zCeFj<$+|J?M3M`CX6`IKqh(a3-x^{4-MZJ0K3g?06dSz z4_E~kDUI*_h>5mJc-&b22CiV>f_odeE3CNkhV;la%m!3OuSb!Lv)M(pq?)zqcW7{yEgRO0? zq_rhm+qNRtZX3q>9P4T)uw^*+-`Iwnc~SE!@<3zPxpn!BMSl13_+9Gms>`c`eoMT3zi#69|dRDN43z6gESc~}2HPtf^qg~!{r)H>@xrOe~3 zWkxw)tHw*rT6WQ{_Awj?*kjm*EKz@&zd^q^cTjus@~A7Du^9UR`IgOic0dDKPy842 zmCoGQjxE`se#KkO?CTZzbLCJQ`;;R)riGlVEyb9X@ z7|KRq&#vl_KB+#`UV_gSxEMQ6=l4;@yfa7WJiki#$hGTG;A>IANW0s8MLFe-&!Ou7Rji+9x@&zJ%iw2aE^@mUzn zWPN%hFnSXh#nN6`h7F_6v?mx{MSY^Z%=0^7WZ;9WS9|v`9@#&pFAn}R{!Gqh%XVNI zJN{YZ*WSxIjsKjE@t3oAD3(Slp&3)BGycp@@7WcN zlnv;fMtV6kQh9dA`1cQUXvBfR1>L~F>IMc`q5@IN8hFmaZWANZNz5tt7GY53^K{U9ZKBzD1 zLo5IN@R{GTeJ}etH@1oT_H$N$Haz0WZ^>@SaLI4UZsh$o$??W7b4DQYx)u4|m@z4` z9~pjZn8lg9>A6=DXD#_%%bfy^!_6MQ{*vYQac;53)q01$SGeJ?Z8b}vJ$*asd@Fpv zt!As?9;TO?<3c% z?D?{}0Y0v3*LPE+&uIMTF-FtRfzh>;v);GM{VBFw#;N7LPq||moZ)Wd^}y&d$~6pT zpYK7+lK0qP>3sMzV(Wl@+S?|5wd(ls#7K}j#t}2o0B!O#@mP{&ImqlBWcIJ=o00FN zOTIT!ubZxUS8KngD?g5O)g}4QzK!~7XRMX<4Lv9t;oVKw{P3ZZ{vFZepU zWvEB*-{Sq)PnHLD&XV4r;=Sf)%Y#j^?eJ}3&GO*;PM+hur@pW}xX;OxUTDW2)V#Rd ztW&uCo6h%}URoYB>mBGh?}4}4Y;0TnZ(7$ecPDUFJ%|BlhWm!0?NdMCf)3f=M4kpJf~`4>J940!(wFtm{ERhnC!`w-4uO`p!SMmzz1 zh_~t-+O2D++qCFO`h9TEmGZ6a^0VhlFkacy_O%ugW1EXky9${ym2YOx@!3gvQ{za7 z{}ZsW^JiMbuPK&``xCL@Sf6js$L3Ld}4X&9ZU05_Y`j;PAG;$7u3k&I3f<*#-m@zoz(HeQi)QPyNCcYV-9u?fUu)B};?Hura$E``M~T zcx3+NQNZ9+((%?bTGfr9G?|S`CXJ{-&7G|RZq5p)l(SQ821KW<{?`ur4Mtbg)kBxJt z@w-m;SWlF)zwIUDz-^p|Wb^2tCcd@%*mk5LyIddJIr!M#I@QPK=o(?o^~+pwCMkkZ>ux5`=4AIyp_C?m-mC~ZTy$KRR0H5E)8CmR~pnAAKwA?Kjvxr(;-LA zJ*e9l`*%s}?%q@6-!A#rBop@%OMeQ@p+hLHTC`lqnwIbj&$OQrFw^)6(xTs?&t38L z8oo0Z=5{xits=dNe1K&uI zJqEK5p}bn7sJkR7FS(D-?y}7OqS!o@kJQB9E7*``ooj9RIWbxIK;|_;quOJR-)M90 zwyRpD$Fko6eHNcQa=Dm#o6h&=g@_fH`#`q#s)b9ig%xXIXan6#e#3@g`0t!MJ&S;A zw$@B?lkzmT$saABhxRQCckf7+K>MTc59TqZBHB@0se6`9Q8wqx;g4*Azh}_aDs=Fo zzJo%k(nph6wTpCYY099NJgpTOzjkhCsY zNS_|2Pl8`S=g)}tZkp)E&V=Kj^EmlYq1RWLyZrr#kpX9-8I8e>Mcm6==ioRDT-x_` zXAj8C^Jn7A88A9;iswtC{QbQ*g5!CtG3)H|d6mF7qd$8L@v*&ka{C#Iqfm@(JWtz> z7Jq=Bn>Y{hw&lTGrMGPeYVGsAjMAWV2hmSsGJW%-7jTZ9cr|D2q*m|OW8-%RL}xPA zT#YB)YAwY+s!RkA(1`Rd__kSeV#9qvGywbr3(bi-=jqv(c(-}0xemIp^QA@e$mjNR zD>U>%(ej}BJH?^BSX*KEY4CNn(!f`D_RkQ~jcmO>Lwc(-m&-m#%WW-@?<6Cd%(*l= z*F}2tz5;w~*Dep91)Qpct4{NC61=T^vw-XPg5|*!^1U!`xq<6(o;Od&uK=$+$XV0M z_gnFs^zE4TJy$OeZlaw(JMG^=o(YumP`-2CT~40K68%SPBCy~MQMt~-lI=$T+QF?Hg;LWHPeS(irY7KhZEQQmYYso z@hRz7e>uEq6nB8S>5~#ZlRoq^?i(dtb7trGj;gP~bDT>YxiPRU$Hx=@VFbHmIAz{ec-ZoUKJ-1d z?jkFpzRmJ9C4IVi)uGLguWPf$fAs9Mz_vr4igmO(?={ck>s00^9#81d$)BtmZf$sb zJN>$__R)3QJ>x%mo%9W)7keIESInN-yAoer_b7WObJ)*P!kHSOo~zgO`RzHOl{r@H zoRiP2S{Y}xE}^d)L)<5Ac{-DJ>N(!^aXsk&Cv98Rcg1qyOCDkPgS!yspS>cue$>Wu##_~~ols~XnhN0PS+*`+ui={M3*s*qu`*o#pUAySAGTSa_pZ`yjl6>{CCo{KdXfA{$ZuT8J2%8v|ms@!K~r6ZnBa_l@N2Ib69i_ z!KSwKyz)HK6o)gECvBFd)s8LfRXVo(65cz-@~DrJ!|Gd^=4<+|dj|drjqA?J&i4{@ zmwz|;6{Azq%QE*8#KO_w44LluPAamvPvCXU$+CrjXPspJ9LEm2VPflr+Z?%zzsZ%m zS$WHXi^mf;z#UD6%!T0fGdAaD`k?kz@4M9dy<;7?63*Iuy@`h%#C(5Ee%wASL=)z4}Mas+FCk+cbyUA*1>bbPfK=#r;P`f1!rAb8oU(zDE{hgTSl9`C)8o~o)}y@_k%5* z!FpR4_{ewg@gDbUx%l|iLFN>A>;DuVvMXGC8|4wy!+S#4&5%cRs#y z7Y~ZD{*U6}XxDgn1(y3%wJC|Muy`{ui5LHRK1sYG($HDS5`NKh)KH?9=?-x z4c~<7_m*hQBRSfTJh8fAZ5-a!7(7(Y`6%(F4qf4H;0l22c z@Klw)0nCw_TwC;ttfot@o|->*1$Rg4E| z-SXG>Z@2H0IN{vC*7kDTZppiR2cPeCgU{zLz4R1(K0DF3`~L<$;}Y0E=84M{E)8C5 z&j<^rm9!TRP80t_IORYjgHy(j%-7yKJBIYMa`G3sUE=f|VA>T<>uj7J&Z3-fy002~ zba1*i9ew=<=dPTA%Yzew4opOC`FS|arhS)J^>pvI5MFcPJ>8eXTw3Ay z6f1Oh%U51-^zp+T?Rn0oALxyBPP^{?2B(2Zh3?DgYVLT7K6Q6rj=`&QU(WXh6X(91 z)6wmruXT*^^X|*hSpQS^}!%6e8Ghc~q!^b>S)`ChED9@R&PJJsA}dC>F9ID4lIeXfkNddjTo z!4~V(%uQPV))_Z(6TRGNG^^#cJ}p}(^w4=D-lj5ibL}OKqd!NfvzD`a-^GV{V!9_M z0iIMj#aO0Jw88`N(^bx0)ROj9a6mr!_M~t5b%zsYQ+;n3b77)IY}t^e9q1ghMrmC{ zamBiuau9p+IOF|!`&{8n;*0(0mRi^HUBg<=^zk`5!+yiBm`~7M@t@$QNRAEz)`Pa= zck#E3vV6>iOMKzI^rhj;jCTck?c>sG{jBk)?uC)UF_HpUA@zsB)&W06n zoF|2j`?z#mV!T%*RHK7e&+6Nu6BqX4Y@WWhPCP4@cF>DwFTT>m5)}5DRNZi1>Dax* z4E&L`p8)sBlsk4uId;cPBiz%$UJ~uc?o5a8AuC*8!^_~(mC0={ z`>-z(x!=ndJ~H3Ll2yotRQ!fw9}4l;nz#-2AGmQFaqOAtHf{sji;de*?1gAie!4E= z8aB7bH9$Mw)zc%Hj{TB}{W3Jhe#yjs85(21WMaPzjj>-m?5pVUgw{;0@CxWn`k&w= z-Ra1D*~iy#*16Bv8+<=({V=Cp&Ut#Xr+8&)@ZyKyhb~};tf+9$JYNt4JHap(en+qC z8%f9ncFq~a4HsFF1o~B?*na7m^sPfLi8ngt@6jDuCun{g9n&A9W9B$IWj&-!nibwb-v@bvZY1Yv;yX$Bk&P^*M zF8#s7@Bp!a%t-}KpTp|&QRqc>Y;6C3L;oeyj$U^yx>zSViW$$2+m{75F{TalS9NM! zS_|#Wi?Q_7@Rbf;6g{1C{~3O2|CzRrQ+Ta(>Dl;uY@N`+>=zv{^As%$PPnQx_y~QF zpF-ygw9H_CC$!@3?^IpV-G0fq3boJj8>QPc56J#+!moNCew^p;TNeBi=dm53v2*tPks93wY$|(NBUPWqqVHGp&C*^dzG)n)qr9Eg zxDVUls$;Ka%M9tyub4Y?jx1be^aA<7=YQ+eeRi%qznb#ht!-XO8t~p_ef2`o=q_{i z#$@fYOU~8((^^B`OFxhJ(sOk-0eOi-GCt+a@+pJ&U9%mZ@+=4MUE#++1|J@Haq)B` z?H1xo_za%#y(KTR@id)hS9r>H@dUqrAw2m%A5T8|6N{(ogr{Do;%Oi4TEt6rho_Gy zBiZcksg1=GJbqZdH9bA!C$>)C()QGzvSq=2z*@eB8<%$AaS!8G8=dLkZR+n1k9$ZP zI>p#DyDaOXc3cXNo4Jolc>MDh#N%Pc>CUA#|9+O=`~iEPM7G)M%Gu7eA0S4%suSOB zoxr_k@Z6EL%Yvhx=o+6}ZngQY7Jcc9;B!^N=i~En`V))Kzc8lKxKr_Y58oPyGw6&@ z?msCIUp_(|Zv1}oFNw#8?>90&|47!FS$9>8Oc77vTrmrx?OOP_I~vgb!Uq^@C1oU= zlu!Fkr$Bq1`{45K*XYAq?h3lJVp(t}_!X^O3M`X&iszpPrd`pB=(jssnL?U(szWQ! zo=Pj{IJENnFGwq22Zpio-MXW6+XCh;!J@Kj*}luV<4f)I>G?kXWct#Zb|nux&llGD zoJ|7EPFr7(i`(nV`q8qWH=p~oxMQiKzF$U;CD`ZD=>B5EgZ`&E z+*n%*@pmP_M^?<%={z7Gqk`9UgqKe_S8>qLDn)q2qxXF^MBjG)8?Um8ZYyK z`k|Nu;Y6@^?>`NZ{txIYo4VCjC3Cyx7I@K|i=i=5#`NEB*|OJf+54{-Iqf{pnoaCD zkAXMQPj@(wd^rk!${kvWozw3$b#~l`*VVaHx+Bm>A3ydD$$jDHM%QGXzNDSj?fcTw za&@1W@Ogw7S>1!&cAE1>8hhI3jg%mBV$T~H2G7Qhtte>AxCrpkU9HlCGSMsJ_7c~5 zaz=SPYbd!V6Uv_<_Cv7@B{y5G&!A_O1lwV>Tkx;!r@Q3?kw1dZ!k6szqLP=;lRCk8 zm;>W#`XPRJ{zGUxSv$UF*6F-} zQk@}i?y2VmH0TTgU;0>Iayxo*!C z_zm(#I4)u?%J8IoE^h1Ld%>>r833{H&20NDe6@D=EN$tI*qxEp!LbIupS@pPazy@8 zJ>@U$_cKR+U7y!Z?>pA6F#gg-+%G2i6XP$f=(N^m?ib&LP3-tfE1b2q3U{q-8hz@{ zU%F8~3&&r213o_2Us@>}oA^DGP7F2r@?qD8ej2)TarAlqQjPIH9IlaHMLjF<% zU)x`bf5*OGe46)J`c|&%>FE{PZlyJ8-Zgc0`0aLO^|`#g&c71}_6YSlbA*{& zXBvNDa&!ydWnV}>AHD8+#&ccd#0b>>0>; zis%6E(RbZ%{SVrygg5u{O*}3?+x?Q~C)@I5hlj#c;((iWpH(n6dU4(Hnt+4Kx)ENx>pSB|Y@til&c15JI%@cW9`U2Ph4yBaQs#3W7>`@iDTug3HJZT>Fyv; znz`pucLa^|4KVklDE+&nXFYU3_dKRWe$@ksh+r6_RL_;?RwVUVI8`PA^-f)dg`Q5P@-nV6#*+*mM2uFquqOaTO z+l$h5*jNAWj`v)~{C(=!_@$M>gTOFzFmm9*2U|pwjqKyoSjRzMbH60}H7y!t&Gjg< z1E1he#jERR*BWls)Nog)?Av&~XBt22F2#Xb>`_;|XD#2^r!cRPy&}k-+OTQX2tSv7lA4h%^+IzZpd3H=N=PyW>*z!#GjArEim_Aj}wq&7n`zqSEr$$Rv#u;Z(dppU|2Q^0E_6y`w zrUN(i$Evo^*t(GKmB2t{1$Wm5vHOx7oomYLEWwoMABo{9ciJd#ZzILX`yJy}YVO%= zZ5}JS-z=ZpPGEcmcS}_{WijXO{ znek6y{I0Je!2gx-oZ#c$$63ZX2={@Xw6ogb8D4-qtD`-qzecCj7(0*e657tDpGO$q ze&lx!{(i6S<9yG(j}v|+&O)&H7{0G_>QLP-zOty}4dTbUs$cw5E*XJ6vYmYek}c|g zmHPj>ZKGfVn!9_IZ=>`$=k8wSo6QrPyL*3oGwY#~KMUib%#r_C;QC@RqF*v{Dx>AM z!gu<=&#zYji=Wcg-iy0vi?r8ht7G1r%KSBjd2BNC*;U*hcqKmGNfG8c$M%u$AvJpI zKKxk3s{1V){(j50QTNbJxeZT)AK^gwDF?Q;4V)5vjXbh}-x#wp_yX<$+J}Vg*lR>XuLVZt)cDdM=*C+-OCwgzuR{wT{ZZK`T05GK=@){J)(1jf`1s zXsnIxbd(-_oV09geSOdNx%4$Kx{~jH=exiC`+(>Yz8`zn>F4WqjN}ezChLtW(1FsT z3`HWcs7M^J1$)rT*kMj7`u@TjNLO~WpE#PI>WD& ze9|uz+d6{(PfS`FJWjqnM|CbjMzqM`kD~T*B}Z?iAD!!Q@sI~Sr80(M>QbEl+L)x^waE71&(Hq>dTU4&RW5A(p`Hg)_-Wn`dU%V z7dbtwJS&bh7~*P5rE4NHG?ytp(?5{dPVOkwxiuE?o3VFw>U&&4>D&09%$d9yoYzL# z0-ko+b0+5aABaO=_1DWT_497=E_+b*@EzN7XH|TG)@S_DtGB^(*vZ1@o2*U7;$=L0 zh${P8lu3?$#F*sokYCLr?oQ_c)iQQ#NRn(CqYoGu1g;2gN(~3o92mIqL-7@XZO?%J zd{08W_H#^a39OmH{*W^I9)T}7mn_!{jl~mJ`!r|r&LAedi8*>0_f6>DrMN=fhiA?6 z>MR0_bHBh-Ch}i)a=^-XtC)FMd$vNpq`YG4Px!RW$p0L4F6Hy`GyTjwFRc4zBwIg| zHsze~BKqy`A{{($&N_cwcme6L_Ic%L=;TfK6IlLwj)Q;7-J$-7&`p=#ai9df*r13mo@8kztYbn&vr64!2mtz z2^Tkd{-5^u`Y+huGdlIR@8|S)vD07t`ls~w(|#E(lW)Wa8MJw+foW9MFeBD?ZJ28^42=wx!|n{hUW~QEFa(Ub^57(Z>0VO(6F2Lapk>v zd`Dh*>bBUtjF&sX49~{mp-jAp{jNGI#fyvyy=%)u)c1+_aA=@)i*vR}Y`M<(iyhAw zrI%T!p%>)WzeO)2JJE~mpPkq`TcMX)#x8oPWo)9C+OvqE&=dHHUTQB1w2EG8b6L;S z6WNoXC$ScBdfpaj?X4$ru&18)1X@Kewco&Y)N?VXJcIk%2aywcew#bA^n488k)Bcf zJ9=(H7uWMw(6ydh1Fg+^{((IQdcGED{Xoz6xkEzFzcEMi6dh|kPqTg#OUI=#bld>$ zDjDZr$g?j%9|qe&-Oj&4u;fd8tvY9 zdjP+$1^=fTKC6YUf5`VX&gu{ksGj@GT$C359k{4EBPFyDd!Q(u{Z;t9?(Y?7jrXP1 zPoW*HaJ2JsEcmbJ1J;@Dn!QJ;W;5MxC+;Li}_{t;x6X#-1W}6ZA1H(R9n5SsP^_9SDi`R>rmoetzK63 z#a?gN+tvR!8=dxZPgy91pHsq(2-alZ=HsX zlMu%<5xpIl=)T(o;*b42Hv(JYA=72caF$BJs7^S=uiE?pIDZkGZkpYJ(=UG^oN@;2 zzlqcS;57070h}iO2XNZ=G&qg_{{g2(v$*FG8}wLTp73ww8UD~-bbH-1(sYAuV~M{N zqgV+&N;Z6-?-@Q@HW)j!e@cj0*jC9EHzvE4b#uiNn6>jIwod2H&3b;``68)BfyfkJ zYW@C051V@_GdcV1z!A^S;!aLP#^7JR>B*0BxQjG9b;G)*Bi7HJi8g%1eU;DbAH^A% z*rErY+At``(HV-&=c>u_JoMg)DeU@>;s5 zY+MtM;UiuJxwPm;|N2b!Lk~PLaqR}qHQtcG`H#q^?6yUFs@O033gz|=4Me;iPrZCb z)5)jU4y{XQ{YYyle(HLNdi?zchQ8yoTJL|{YAK@qSw^-Fh~9~8_4i8;6_K_b+1rRt zgg(u_0eqRr$V^Y|Sc|<0x$tT{yo!u$9rv&m$(aey^V8am_9v$Ee+Kv|q-?G3XXRev zI_85$`p9v9IzLHe7Meb!MsH>u3vRa}`*p4Z{mp*ZzrLLNeI)BY?<@=G z%b%o%>IE^lbZX%lTpi_@N*EAGl_+p7>pFS}12&AYx&I-Ov9F@RkAo27#Yi z=y?kG!)I4hK)*Bx3h(kQRp~qz?m*$p*VZh`gV&~8DWmgRq|2Tlzv5ixQ>RV$lh8va z;yayy?^OEe|Crd=3xR=$I;Zgb7#J5KBLh570HgWzmHwK0roZRFas0PRmyF3io9}0H4o)`m{+7VDaVLC{alFUf!Wp*N=eQHSBi7mEzn<^cQ!h6AxJ7Z1as2mJdM`7&EYHiYcjN0m zdq11TB0EI1;o*N4<8sI5VSHJP%^jbIF=jD7jWHAZR5of>AKv+8XQET`%gLl|ei~~W zzZ}LFJ7#yRskdAec^5sd^O!YOjky*&F=u%p`)&u1(vzeYxjeHHT$V2W&6tI6Pd4=w zE?zOF{3_ORuCiJ;==W*wQ|h>;i#qOC9p~1LU3lA6yN+|&qmM3JM7+xe{T_*n1mNeR z(4ORq?1^_f*%NnChwKTrU$c3)Y4gPmA zPx;tS?9X|NvAc7O>pwzX27h{;S+m*YKZpJDrJ^tC>*9$9bm6DGsiBr$f!6!cXZ>vt?e1wWpfv{c$s6byp}Z+BRf+a z*=f^fY^=KQHqpl0X8)C^;B7N_+nn{y$*mKHOm4l3aVqcVFOc`k z{A6nuLZ2x;T3!(CTlmjDrv4|O)ACOrHau4P(ZhQ#qpl6a!MJo<2EAM4p=_)8u7sz~ zHc?!myC+;@e)UIn>eH8SJZJjm~188mKUF$4>cxZ*Y~yx zMw}gpmUbh4(zoawy^|Bx z>YReNfTPx@+;-%%lN>3ekLXG@|AfyK!&DaU4-G|!qV0leyRKG$9J(%W?{1EI7djSf zT=)~H@wAQ2y!)-iR+z)^!^EXEpHE#y_+c8o{`$0jg71}UYtvj?EInF8JHop^ zHP+VptlYehJRfr(+AjKJ>~-4D?$mx(H|=W-;s?q8?dUkAT30kE>x5XKlum+B;CL1mOK&$m?>c1=1YE^yt)IX!AXY>ruz@}2_P4L8p=I*e<&w6=M=76tH z^cu#wUFVnLo2jIo!on3@6Z~9zqDuNwR$SPB@?C!w=eJezZq@q3?mhtXo*5TD zN*$SPZ6h{HS0#O%-@=x(BJlHOYxLw+*&Y*0zZ70WU)(Yo^!Xrk(%pO)+qQTGA4i_~ zw$~qy%aQLq-pIX6kymlZt(+|66EvheDFes1HsVVgi4LK4jsSD!i=R$hYwi?Ems}oz zTwc_*T(&-4GYYxkcR*-6b67Hdt7nkAwol()U-%h$li?Rv9{q|j znm+IFhhOcR9!k5WtV(-T37}-v%sQxmL)#;OhRm zx*y*3%fT&oz;2$u(;vncmnS_zHh-pc&8q_u*+*{;wf#)sv*1l+N)>ZT32+rZCd02A z`DV+AfAzPP2<1XM(7+0(T__z z+6PE{cdO`0`iu*&M;WWi{K26mjk)b*#jE?#pSRhN9=Yq$9ke$zzgSy)YN_b zv0!6j<$qQAGG44&V(m^H&)Pn|oSI=*M0O~K>J9FM^V#xm25rua4{#r+6)u2B8<$w& zWb%_9)g9Au%u!kk)?B<_?|#$-cetvTiKWVbzfv}~-+$J)prsASL6<))%l1?L;cDW?jKAo!_DMQ0 zO!ru=ska0ok|VFg2R_-z9BljW{L!t%q`iy%Ol(lW#@V8oWHV=Oq@5~a)C!q5rIUQy zvT8I}E4Dok-gy^UQpOmooVi>4rZqy@F?soRS<$y_hdIuCUd8t!creatS(A-z#2P`< z)3i%$iisnU-v11F#CPI3$r|_k0^q;dV$N-Iana~A^ep};r2Y&m-Qf3e1E-YeP4vHQ zqHlNOrPj%l5A}|mWPRhry?*?@amcTD^pXVhl0FgtkjiUy?vVJwdUV+s$xOwJ9`p6i zZSnQW{g>?s#5q&=i4E7@MnF(7)(0x8-?J;KEjeJd7A{WYtUTaHS>dc9h4|Qq%w34{_WyCipy>R-wmCbk z%N9m^(CR?8Qpd0zN|yv%X;Ozo_x+r>i}ti$ ztTpLr@b6q_jq!Br!#Vv~52k-wCzj2#5!mG?>_e7|@5g|v#!CYyk6w2*{4ota$%kL25@S9EKAaqZpN#JmUOa4#iL+(l z9X)JWxvNKb7Hd((@UKa~x}TlyPqNeBNeU0;zSY@o`WR>bUQGE-_;bGEroYqsGxZOp z{u|x&yZoO?pFsLF(iQ*R7kL!>)V;ZSFWhI#%w@KHU1Q4s!YfX0}s zPa7k+fI8%3e;QmX|2KIrWIf;t>TzQPGm&ql#xAhuqdUpt#{7v!-k_YTcNMBn@Q>xO z`}kGftLT^eev9fS2IgGqmmlbC^_O^yLG)L1LSw%nCr}n^6V$Dv)!2 z=3@IUb1RxgOs06zqJM6D$57_h`BULN>~W=)5d%_3|1@tz{`<*w+wsrkIPo63`?v|8 z(n02fQep%0iT5ZZ-a|a5c#kOeEnfq#&2acku^!K$mnOnLA9@o)+dX{^pCu3v@d5WZ zZ)ZJNd`7Iqnn$7E9KIj)5<>uA>Ri%N_>411n-{}po8Yrb_^jIDGvt=xvuC_<(+>D@ zqET;rsMz5%wW~9Cbk5WVbMIpdXHVT0h%B6i4#pZu2J5?usWbA8xGLlSG%&XPO1dlO5%|o_I};gN zzPwON4};1ujJby;2bO8J_Np9$+r)@|5^F=;oO**m@eeo0SE5?u6$dN zSGuhz*E(6i`Rhf*h%ID36ufPk7Q9oUqUm2v0p6r5Z7;EKHNdz0k-(a?2TIoHOoC$Y z!^475~Td?H%5xiy(zL~ z`W2C_GsY2Pt~oxrJ0WhS~B>qJ*}#H!Oba=`)*H- zv|ftbx~^m2)5(XfY~Syce5^ws?i@dxhP=~xk@sOM)ZuflBZlBj@Fty6I2{5X3h(Zk zLl$#&rTjRzS&=g2t77kB! zdu?m8v$nO_UEBH|b-22{o*v@l<+tB7)%G`7+15$v`EDL7J8;T-?D~t&;gelg3T+Fw zij(m?u;9g^NmhT+=ndex=-kPXC)jVBoD{Vdx_NXs%@@3Xzu>q%A zp5iOPRb8r8lgnP3sUA=6oRpSP3BWmLQDCj^94JBl*C!JPlw^&-cRcTI?rBSSJu6h` z37qu!3(vyeKCcouUrYXjzMS0E9&f_yan|nD#Pw~btmNhe@ZtI3Dw#R^cb>TV|Bt;l zkB_=K`@g@F2{4lo5Xb@nNdk&VaH*{7&pFCTdh`%v?nD@GdpK9k>zGNKcz$>C#8B&X(&VxM3K{d|*t zugRFUbp^hf#ZN9;c8;t6mL}xh3YW3-Zl0}RECoZ$M^?Cu{f{Bf)+1XU1JC#1*L9_O zW*wC=0GZXFTG~g2w<8;01Kz3oDz1AEIhBI_`!TtMX9K5lBg4qZnc!j;eQ2z&xiYrA zN8X@vKo=wX7Taz1&*)$OISwZJ1CN$~g2@YYKXe~8>YoPIQ( zeDE-jer9YKwZ)T>R-de&{kKh{{=Li8CG$r#&RSW^zGUp4kUKBB1N)`}-Q`EpMNcXX z?LhwtrB{bu{vk96avMP&u`2%cnF?jvSX8DrJ1- zCpAx=Ti?eV-w@i+`x(M9Ht*Vj#=5odr?fPX^Si!w7<<|?_pNhhJ=;+G(4>airFq!5^=fQRC>FLsO^|>cgH@U&@2XPpz30tIiHJy0fFR zc&}uxYAcNBXhtU+r#J)m1c%y{P7wmG$TPy@P)py4ySFm#UPU3fflo=!vDfey4=qzJ z#(_FCd&!gN&}nXOM-z32q(dubTDojHIUNJxIjhm-9!GDAVPh^}9;HX;rKFoV(^|XN z@Xlg#rtg6lz5;I*|ICM{+~XRsA!oX^&*@Fu;U5M$(<$Uk zx03&?TxR;~W!H|ibEe1IInxKz)up44 z^;$X8V>8g*!ATKgkI$LD1OMxG=1zXCN@%Q=x$<-EZT!iKuNv^pAoP~qXqac+l%wyM z^g`ZSWG;0Ah#3?jr(@OWq1aq%71ZWLf5ZHnF=Jwv1~_jZzcYwU5cw5;nv?vKTUozt z^!YP%oyJu^Fln)r7~yuV%NF}3Yr6GPU+3R}10USF6qhkL!o5b|(7M|5b*(F3lloL! zvFiSz$PM^etMS+Uq)$_Mdh_I1bw;Rs0_&=F)1=52qcf6Tx-M2d5IPfBDL(^ z@;4T5U`(xC8!p`Oj`Xvj`?6?ug{$RH+*7Wta@-qgFO5FP`V7`y7WEbwfl%#;s297e zu&r+(wCc2wYB@$mPcIQa!uNQJ4?Kw20iSa&rH^g|V_Pzz4qimvRP1 zjVs`7bK!Sp9(ZSt*XX=1*XW$Xvpe45*);!TANZ{1dNtSTu?vX}ue;_FV_o@z+DSfe zI`4_p(2fplW}caMDmlV>cQ5B2o@sQJ=jwfOG`Xk#+ufy|RpbpS7tse^^SGYJ^+Nbd zCGf|z{6AL|G>Q7%$h3yacMLU{3+(xh&+GF zeNohTc7~qadQ)F$JRx)Tc_mNT5@IDin^>t*|8OX3{_=Dt^m7F_k zpY&1X$f{4|Z&^9E73*is3ACZSzo%+1jy`4Q{c-;d+y3EY3@BH>f!hj_%=I$A>OIwC-yi|AFgk-nqrhbu^G=eqi%~ zyS~77KQPO8QvsgV0HfoBi81Ci7yY0+KN6h2Ognm3I9&ryoo9FH*>`U0eiodrkAD`N zI?uNAtZ;fM-SZlRH>rDcSjhjf(K!H^>c*TK(%RcWJCgg0koz-vmK>#k z54kUSe=Yh$-I#Bg&zZUb?V7p)?YUTom19cHd#${0@P86xsD!V1bT7?{@n~!dfXP3K z{*bZdJnP9fTD-s-6s+`X!un$yR{F1dbYRHS)-O=^L!;9_s?2<^f%mc+jFtyh@?5#m zqOm@t_puqx_n)xeujv=a0=~LOGee$&egQpiur4oW%ni)w-8DDbDpvRu1BtA7~U((_F)Z))Bws`#4O&-sBOyu31 zBi6_CEnNrQC%u1*%e?pO7C##j&SgzX_Fsd(<@hr69doC)M9x;cE)5@53h}yh z>p}p4^kC-k7jZ%TOKxP z!8x+)UEz5dXG9;vzQi}&IS(6nCeO~`8O8Io-rK$bU&E(j;2$8yv_Hz(Bg)DA%QUW+ zl#ldqeGAXvpAC5?Qv(BE{7U@&hHJ{UAifm&TSS-2v2xvdgY9d{3h$YUzQX+*Y+p;Y z?Q4-eL%sBH5FcjwfFDnap$oKbC!UCppcT2_x`6ZR78rcoO~BI`5pPPP)&u&6&Xkvr ze-1pcbt<|cxcCZqe)=!?8~chs4YU2Aia8E5ZI;`oA#?0|HD{rN(dHEFlA>SyblH@o zc1d2J==B8u{%gJX_h0>z{rj(dfq(yH8~2CH zi#}zosy3tQFfJV>-6N-?G?(>-U;Wmp#9LT@PjB~y_U8E3eGdJ1+2YW%&$6GZ;P;H`Vaq-L1kL~7MDOI^VBZf9?|_dl9d1mp z^qb7^4*2#{Tkq^)yFCJ3ciDNhS9IBKuZzc@tr-5f$jn*D&U28V-@s-&8=Gw=epjo` z>gUKPopYu9Y}r|@oPE56HXE?H@8MhPZ5#6HXLF6fZPW0*xN^3vLTr>b389y4IfC)8R@dk3QY{-NlZwm%s zX_z}HR7sn4*lBI^ZZr2HjVeXPy>H-q%MH(Ae2R&C(D8HVzn%TOF>)GW)hXuw(IMLZ zi43m%$L(9EryFa3$MbDGqrIUXYOU(rc{2yXof5Ki$Xs(D@O*IY0ftKAL#pMeXS6R^ z?J9>$zo)bBH$om%<3#6|aH!H;%40{W7&B=latF+q3+$Gc~eLN?QiRke{$~kPd{*M zL;SP1Irm@af580|_JqCW+<$05&-={-0t=`c{GxL|v42}X{f%?~#)S95?bICd|F|#R z^(g4T(PM}3Ti3KFN8g&iW}cJ(LI36Z()SNdUrlbf9sFyJJ;O7iC+nTdqEGRE?dx~q zYqaX;XfMYTT&u=+D1XCR*7i+i8(HCZ)dsR}Hut4J|4eHMz1jI#`Qui+&dIy?`pq2U z7SAop{jm0GNY`z^FIiQLE&U_*w_|tTjNSUQ9Ve|DWW`Cvf3~tN;$x()!T3>*!vA!s z5vpLFDn@#$FSb-?eOF9%kQ=?r$4!n}paNS?d8%sjI>u2I2Chbl->Uo@t^MS~WUq7||K#=|z&QwezY(7e`L*PsbXH>L3&)B%x6%Hwz@Xfn zIVNtf|M{+b6Fz}&qWoq0(79mfZORFdKctdt+zV8`Y?$Xes79FXU8VPa%$d%`vqID} z+cNLOb3@7ppr+cEw2VddmGgAQpl8d>jQV=&Z?w$m;m67gutA;_Z8SaUUA`WBxDDUb3Z7SNxSkri9%3Y|tmQWFvH+T! zOaBk^ExR@nhac6)aNT-~ZP(_6ec(s;Raaa&1bOLJ4nbt2uVnKO$P;uUc*A3#_*D1y;}9)!)n)c#`|(`<70z#MWt6&mB6*^m&E2 zFBxCXTt3Hd$?MhVbk5q>x3gc#%q6Jk8}I>>!P;~7DJ9$gGVWc@$hk9Xx%Pvo{b!Kb z+E46Z-D}^^Uuh!--FW)@?oBQ7eTHmQPSaZP=!<~^9^GRvIlA9!bib~>`j-NubXGrm z5g(MCeU!bT)R&?CH5H6SwE>iy@8DMX`KO+)8g&Qe?1Mkf@G^Bmb00rCVb?zX3Sd$F zn9g*oenWixL%dsihRd-boLXs}`1EeYr&q|D%e-UQ@=D~O_R*?#nra4lxMuDnMuvJB zv$OW3pFDAT&wa!-tf`w#ohmzA3qSUdH(Yn2XZcMjjF&N&KvUb$SCr#c4j*c!AH}q8 z;aSDBtbN3)rDpZ3HNAj7#fQeiYo_1vzssr9WbY@oYN!1-^P>I4YiZYPJ7GU@mbstU zYR?Ni#s%KxR*k2e@KoT>1SXC5W@2e?0mBqK=cq7AUkiHaOK@wCR2$e7~K{uWIBt^>Mmz0pE3SG0w(CJUz#zb)UDz)bB)F+*0?dj>?k+|M^*4HfDcjnf-EOM=gw`L)eJT(iKc`~e8 zBA!&@NYJ`;=JE6^-mU%Wp51qDMIXF3+wj!CJs_*T9GbCcO>u~!qd(anA#hzz zoygy)U+fR%U`n4>-$&bhSM&WeeOvtN!2L!M)@h~I>Ft}BBOkX0!EG#?y$RI0-Vtm2 zq@DcQLU23?dDEfdf0BRpqqK7{{Dae zt!CDM^fPA-#Mh*qL7(r%t%3cliE2B?`R8{3m)ZTxU$DE~T7U8VPd8lQ&3#no#Hx!R z`Md!+^AsPC@$tQ$jIGNQH$EF#QHNZ;896T5n#Z021G(Xc=Kcpb9z@nEU)e(rY%?zjWE`7 z#`+9nt&YpduHk*2?=jZdWK!wmr~xux4>~B&q{}rj5iu}9`-bJuby(g!Pbr6WUWlL>APn=W2-(EI^&uM^&B^c z7kv_>rsEWRD=E-#VXCWMe0&~jN8`8rT-IJ{?SmHV{g_|r!ih5I9Pm@g$H|vDnl_q& zL%6!rd}m0wmG2zj>c;2mi}imp;~T zl=%;`AKuXud(`6@a9};2KkzPkR$M)vX@^&jhx3q~dOR;#ZFPDw4qlJv^V8z-lf3?m zQ;S2ot>#HFfC*nhea63mAH~Zx?}t*K@qWg1DD@d%WK1sFY~_0o^We^B_OTi4vzu~9O|VA#*#=|hXx5(Y!RIFD_o3D!IfMp&(|oUfQ)AN0 z?+pDWMnVmmDR;O-%7azi;3>$X0`&SE>~IgYZyLm}OUc&)2KELFDiRFvpa$UO|IXIF zHIvrgY4x3F_pN)%S!n3nJbAsw(U;$8`i)*s&Sb*?{bv8q06*XE&{}ej_wrd!y;}9{ ztoeL!w0ZEb`kSvXm?xiUi#h&A=iJ-ZL9al>(<_4*FusFnrqjsb!sBLE4klqsL2zLO_+b#oT7p0mwJ|K z-rBKez25G6N1_MpcnD_u8^qUA1LZ#|Rl=&YR{YNc$1mTdxmo%MMj-+4U*I z%y*nQSPu^tY@TY*^3Bwg)m+FXc5K7M+NloC=Y#Xa{a1O^ig0kjnL3>X=m9H%1OB}8 zjG?~I8lWpnFWQJ+jS_;aHE$lRLy6~X<-@^6_jJ$oPb&QmSDY7^h+RXz5- zp&u;4r_{CY?M3ECa;BVl*vs>h{~vNKe!rUc7<8EYsqiJwma+Rw@2kpKSfBotX`!px z7j?~zfj3|I`ZJ$g%^K@}`CFe{)AGS5Rmb*Uu6<{U%b0mw{GYk_o;Qo13x2X=<(5wt zorqq7jad#q^BVXF(8;75IDTEx54CG&YcI!h(7b`IFiAQHxef+-i~9EB2d>H{20{*^ zlT%yHTBv-~6%y^;u5rcHBZQup7|$AkCm7>6;RSkC?t2yQ%;Stz!Q+B6$oU6IGP zPI&hi26b4Bbp>2E*B9+SxRM$He6-(SF!It5KW^mnDR4W!y?DRr((U*RXe$QKZe}gE zk{5j!&uags;*{?&x6i=uw2$Hm+P8E7BmCg(Qgi>P)-QEK)|&A@#?nlj^G4oZp}c_17GD z1dDPIJ>()N4>8NmF|3B~3ch^t^f>)lwVtFu|11Gc@!?>a2VW=k$AMR{z5`t(gY^zz z9hv~^H*8o3+j#u4;r;$0z?7G=G*Z8h3n3I$J^IkdMo(TdrmFf@|3Ll z8b0qrPm*iz;k&AUrf%Sx=sl6I&7$wM%%%2AY}M~8t@^PKv;MW_uB3mx_X6Laf6z^X zz1e%BI}iMe+QG%HOx8U0<+=sWunV9<@O0Guh8s0Y6h-7CPS+Qx7dLo-EfortM$yZaFYDgTI@v zG(w82F91Jv*dK-~WlNa*H^K+&ct(6s{4av7z7YMOY7E!sRhs;<@=>>GQ^xBGjt}|m zi3$9^a2mWmZHw@hUdXvs%E!faoB`iY^H}-0Ma0{8^z*-&W^6ZkxpdPsYOE?QUzkz1 zrHiMdmj=zTSUg?(i54<<@_qh}F=^aJANV#on+r7t7r(h?@?qfjbj9Qye{3m!|4CA2_NR-J2I9R@w@2c^aNR-v3$p0jbHA#>c^kV`>rMD{n)aH zN*jw9r-5Hq<8^4mk1j6ykbdpQj#&Y(Hn5=<4u($1Jy|iB5BAIfbYtdO^iDUAF>XhO z{U_7Ue(3v1>1QQ)6#rOF8_D>`GVXWr4-;QW=*PyRd{W8y$8RU}XQV{Esf${j&Uz3xEL|>|f!3T%y?gFB$XEj4?K?5A`Pou@@vYuh|G{!kX!}4{)1Pxvn*NgKZffXvded%j&l$4w70-Q` zoV!2c^9*iswRn)t>#Ivb>qnm&3Ra&MdW37}ti@LCvdrT5nWMp+E7<71B-+5eXU0pP zE(`6uPxb81N3NVle6o+3H}&WD$rt50&99z)oM$!1k22SPF8%yxsQ&j_UZH!jq#@KHYq!R zJ@)a`hO|KIG;9MtzXit)8;!tt>>u-)Z)68no=*-N*LA;Pfh%yKbMO1yt2J7p;G}`Q zCO13R@8|k`M$4a|Tk{=q{~mPit>)e)qosp)8u4k7Q&7BiqdTyiXTkfm!8ez^xjFUu zPbxS3_LIVmfBmH3-HIzxs7Ge-T|g}l)%0MV_M5Q1m2I9&ESo^`+^mlPjH_t(&u$~I zkv{kG|5@;NA>-Wkr!zaF3sM8h#nc||DDO3suaZ?eCyEWTCOFCnWHX=M{d4My`xxh? z?N6_JEEXF_OnrVUdPFwwdC3(r@41Y1x?TVsbka`Y?|e}+Uy9$#kGfF)_t=~|FYOe? z((1yrlgIOovOnO7g4x5~b3JR2BkBQQ!^c=?~l%I1QPcko>mx_#@+Hr&QKy`PU? zY!}ywA9vOPa|2@)Um3y}gV$33vwy?&kWhFS+J=zs=aB~yw29K)_t*@RE z%1lM?JH`l=^+Ts)>^GxRCL6mC8G15fxB40qo(QfFrLRkp^mSvJ)z^dcnXIpJawcc? zf@jqkioEFHIn%`R&DqLxvGCmfkDhpzUMfA-!L#x}oqC_?z_x~Y-(|yduz8=A3?6)g zyJ+Lvf-JS?0x7a*?68NhxSOu^A3DmuUMVIM%Ib zm}jQiW59;{!ZGx=7L(!hL2z=YIBf*xmDGh@wdwL_A7))5&ptN%-oRgg?*n-7d}v?1 z_-ygyIC}a4us2elKsrs4xJ!0do-Ns!j>wPE9=~??0;(pWDX;z%Rd>YF2*$ zoX&gKGln}kw_S3^xmKldF}`%#)b;o=p6<*~hBZH;jl?x9+DN3W3Ti4Pr7h+qk+zQE zef4{x{T<)`NT+}AVfIg~Bx(PLNZS>vo0GsxPPE}Wp6_T|Z0WIlYyAm!XAK@Ie%gBB z1$sY`ZiU}OI%!L?_T=!^IYmtq5eh>2TEpm}gvH8f` zhd9ULA5rnzE;(rNXT9&S<)GJ=gBpX!mTO*Ht|j9i%_)~hH!m<+-r8u%MIYn*Z^p0! z*}aFpHc$g+ygkmR;V*7}Uyfd(ad`S7_gJ&e zSKPR+GRKwGA^xRtX$=-j*VO*!O>z3}_XZQY8UkO*gui5=^JRyoGk>0)XX3;0l~j&3 zPFY_oy-$0TUE$_bUz2p)b?A}kx#s?)Hgv+h?$l!GxcNVEHThUq(rN39&`sD^GQG%H zQzPI0zAXH}uE0v(%Y$A_eGNQ+1z1C4t3w{&PiIfR;TPABF7hll`OWRr#^=4M!Q22k zNWeu6>N`2v|C>|jo29QDIO}lO!T)O z-Wr|ouY>P1&tbqf+J+Cg>cICl@U@Z?BK#{a-nsrd*G)Qk-lUUt?3ul~id^^}^Y$$B z#&}&R{@L%lbBccsU06DwD{uq9)#gyztW*5wTN@_pOpO@wz13Ya$(&2>|B-$i{W8ba zFDLZvp34Zj$ue}~M7g24EQg1TVGUQ>yrIhG4L{~LLic-_yryX(2`b@kNAwPrt8 z-KMU&&oSrz_pI5(xfd@=Y*)Mp9t$nxbkhPj%`=9YG;lj(d3q3JD$F|+TI9qFfJE_r~8*QhJ9cTO2g=>dBTU1~K z@@s1*6{Z@U5!Q(6(*$dWM`OqJ3AI=EC6|}_qF*K7nS7=Rhk?6n<|uKF3z%co1}#j$ z-7U0R*o)nD0Irg(lRn_;VR&FN`+d~DZruEiaqK$xLU`~6@ZvIf^7-tgoo(6in=CuN zFu`^+I9KL<=+%_Var6{{=Sg>11MJA+HzbSe!1tlb-ZpR{dAK>j7Sa2gZCm6e+ZGYM zZ?^T%mu&sB?O^(YO;0EAo@~J9--|6hiSJ+W{T!cN%%#R7o##kk*INB&VAoo$OVG^{ z`JbO>{tFyCI*~))7cz&Ev)_cb{X}Cy?)=A%C5a5WjIr!uef>w_Jb~|2fOGcE6|4T% zR|GG=rJo7Er@&_t=Sa`5`80NlVob;IeA%b{#yj)%pFY;s4`XF};gh1J=i#fr<|Dn$ z`NTH4@z)LDtO+-@#L0Jevkw&i{$=nh0& zmXFl&kIFY1oQD4rxgN6nmv6MuUETC(-f3q4@qISBPj3pE{hWh6YxU#oS8@@bt2tRP zY%pVFzxzLlE#w#ma#ne?StaIM>QiP@LWm ze$f>=sex$bf{jNW9qinZp|oi}+qe77ks5eL`2r*GBlvx?Jxa3gofx!phRB`f9A}2l zNSNQl8Q-;sFuv)BIlk7fSmV=pD&xi|zo6tAJ$vYfw{O)R`JCJH&es|dT%QA18}Bo}#mcFD zAAjgJ#-aQgavTGd#Fg*gh)%VM^Vo>*TJKqT&fhn2=nA{Y3z+~fDQ7>q>Okg`*Id`v z*ZC4{0X){V<@{};I&A76?; z2b^<~$P*H*L&7fsqkM{+fd8{U+V+`S`(~8tjGF`IJ?R(crwQYR2_9@KMbf@#Pzr=XNkY`Mg_MOTtkI9A$%} zPtik!rv>=j8f`pXtTx=nDb23vc)D1`7Mv*&yFyD{pQ;2=8bi^z(4*k z!0Yg@!&zSsFh5_!Kfcf09S;BS9Atfs<6g4$b(+>4xG0D29R6{gsc&S4PvM?3Hho+5 z_xnOWYp!EaX(b#}K&*qJQPyV4#C}&^a z(3{}D0lw%Wetr^tJlNkq+dtCid^(RDFKoJ%HyD9h)=M*RJTMZSev=Uh@LU@@oZ=Bz z2tI!6dc5uEVP8N(Q-Hbr04fmifZ2aIZ4{byoJ#H!t)*!i3jS=}e3H7Gi3 zKZ$)HSGYnyAaA%0ouh`e5IN1aj{Hu^f_1I6FH9<5P%{bpqBC-mWrK*9IPJ93_PexU zj-@;&a5>{(Kj|8a7vZzue;x397Up30gNxC$!#na_7Xs&=`;1$6k9LRJxF&cCz)j>h z)qys;;wh(~3*&QoL-8i*@dxw8_h#E9^J71K#ex1nC#H0O4$M3{v5q%b&%0Q=f-7D} z&jNSJ>~Q9$*H~9FU488(2ih6E!DZrobxt4#4fx~mzKZ{mbMBd4_~GN%6E84npy<`R zXSdfIw+i>0q1)JSS4lkXH!`k&7w#`CJ2KqQ{}5`X3zkbN`LF-!tRLa6h;w?pHf@^_NBWyT5)|xL<7?Gc-_|fcp>NAC-T*dv>s? z8}~(b-*Zs9PwgG|tG{fX^Wc;t!~Ii|i`_iuOUL~KryVBluNfNH4zA;Q&X4(Dcl_en z!NS4VUyS>4Cm%ZQk^8F)UKon3Gy=uod-D^EXHUQG ziEch~B7El6rt8Jy+rO6jY%I@J5`ovp^ZDujMx1Bo9U0E|qEq}U={;-sq2nAGyV}?{ zG%yBylOMdZEoVip@P99OtULbh+0*ao#(&X3e;2O_Cg6PsWBPZ|`Zms`OpJB*rb9?a zb#$Ab{)_ScHu)HdKGfdelAhQH-rQPCO+tQ;;dkBRi)U{>5&kj+orXE6;(z>IK4$-7OQV<%BxaEKj0`5Jm#8MRpMN1v=jpQPB_5$J70;{3xy%y`Hea$kBI zTP1dj^xLl78Fx3%CjsN9*q>hpT)XL`JBP-G3qL|IA&17n`2lbxu~#xh6PydS_cZ0! z>5R%VyUqoRB;;O{x5df^U~6tp@QIgy5Gy;8>xs`dbi~TalRV!*PKH0p_2%8NvM0G7 zwA&BaKKJI%SXoPw_M01HWrL{cm6Ry&fyOgX^XrC2swOPQ+(` zp76jirp;u^&>%Fv4ZlsIZ6aGSF%Gn0l=7&u;_||*{JUg)e2@9QRbw%pht%0H+?0Q0 zFf@)#4#OU5vL*5~VltT#K8bj^%7)>B5l03?4fT(c;bB{n{J1sruUc@4Fq~<_Fpk=A z*sq5@7ZusbVR(A*fq1x&{vS;O!?89DS;&JUfuWQ-l*#b$;D7^RxSsxh?Poa1jgXRPJ#Jqz9GPTG*aE`EQiVi?8OpZ_`=2Hksx=j2DO;@aW(H!r8nFY<3r1lGgxZ@y97d;DNO_mcTH z-SiCw@!eyOuk4=~-yMfAzKaiYd>ruIVIiyRL0tnVvMVt>NE4jUV&F) zTP`u`a;b@I)wO#-V1v4)EZC$4y=eZI5 z7vK0hv?`uq)vHeBymG~n`mmSV6DE&55Zh#wWa1~-g>7WQ(J+jBHEb>JjTaq{HHF#lDX4|1s*1@Ap2MONQxiRcVIYuRZYbnBVIxq;j})bpop`ecy}Jxyu|FZ zKVLZuK5D4sv;WVFJyu10mAG_?hrQ*k=nU#VK31~Z9P`&1EAAYPFAG@ias53%MoY1%MQAwU9V#=@O&^V5F%FYa`~DfcjNC`+;lz9b+%LU26@-y`PlVrJMqZ8%A$$Fv)Xu! zcLlS9&-K8IFK0=?jk%nGXSJ_b(*5!o@L&3C9lo5(`{e0jyi02Twx2w2!#yZmx^>C9W^wW1n5mXb-hCcb!Wd zjWd*>v%uI%MnL%|S96B>F4onm`zD4ipjJjZG#XrGv^=uBBvi4;X!=EMZnT{GFjtNA zPo8_PtLZz-QkvL19$;+*9(&)_^0!p~z5U5yX=06{ zXfy3`@1X%HrT5Ul`OaO=JIfIkE70#2>xXUSiB8 z{|mgri^V^w7XjT#AAtAj{Jk~V&`LgQY81436SVj?bbJwXycaqaO+JH8o@f_OA$L~$ zoWI69dPe8rv=aMQE=9W?=XY`;+Uywr9Qrj}hM5cT9=Q;YGmZn|@Z@W(qCKldTTb{o z;hOf8pAlqCdssKBb(Uz8Te+DB?upA`UGwgEY$HTrY&JG<9bRL{oM(M;aVLw&6pixV<^ox`ZfvS-0V%d%Nh70`k5Zv5c+58$WV z;7nBVJ(T0A+>9xl+ah@{n$U0MX5??G%gyf-o$xgCSi^gIznpen;eCUA5hFD^ev)WV zG=eSqH1{_1dm%6kiOa{)yUpDDjoyO>)n7IFAJ?d+8U5+E`YR_Fq`6;oy!Hb|Qig8v z@|^1Q2(EUX({HZLHa0BGZFWZ|*!Ai%pN6NaW@j^d35CP&gI5pZ&*7{mt+f<8XU2i! zXK`@E==*rqlHky9!O;pFes^^IX4=hj89TS7+()g(`<99JHAeN7&pYbt9M+Zk$_8i3 z+eoQ-$jm`<)?H0pU+>YrgJb+r9>xKJOcX=*hLRky;9{)Wrus)3$OF#_CoKU z@{DAIb-tCc^X8PLz`JzW$6RyxU$XjV(s?8+#RriGYaaYAwd{c@3NDn#Sq@wg@;Ixm zR9%0&#$=YS^Hj$ADK&~xYJO^tRkWpgJ!dl3a&nR8KzB2dS99E~=S@pjgm~!ZDb{At#5H)ebH8FXpLFOc%ciI8@JweOi`Ab^$Et5Bx>_HHWBnG6 z8^CcnIab1#Y<|&=;1!?iEeA|^b3XC*za=kR;irI4^JMtNFEhi>@L%*0Z~s4ioOSIQ z?hQn?==oRq)^jJZ-oN{nt^c~E?@_;Ln(A>{^4o0NX9Q#yj=NZAP#Zg6Nb`Nx#{Ol^ z*?UusoqN#XBv0E$Td@Sm({Z$`cOv*$RWIm^t! zT$&*KgIv@lMSo;3Nr4e~i8+u=Dxxl+cfYj<*YVYw*IdRrM^Dk&7%_AP>BY>|YU9^= zfhEkFgIj%@xj5w706+WY^NRn>r~0^Vomlw))YfmnORL?vlcXa~9o36LlBNb6@k31I4u8 zfqtR!>3jj_jFA2=|GE|X2hOiVe?O<-m1R0(eenl(+DR}<$Y{56ZD>mW4h@I0l|DO)A-~%UtR{HK_T*?o0{xkm0SKtxG?f$e+(Ya0h zZZb^#I_)LZ2Wtnkn0Tg!zyfeBdtw*AkEVTpN=je_@KMujd@I*vH)(HH3jOH6p1X?Y zv}Y_`ymAZto^#i!<6Q44@U5$K8{;x>_uY3BYg{!^Mc-Nzn$OF%F6=h-|3m&)Kxew9 zI#L#G?s`w1fsWwcw7tSk;7HSV&`&pf>XbNK2}cd!N_cuS0Z$F!N$m+wQ-HNMyzB-q z4d6x3wlUA~cxeDHW*gw;MB0!Y@dxJGp?!T@`S)Jos0L@=Fph>n_`pZI0>c@H?4x$@Fp1yFSBR{FKl9!X*ble&<=j9n z*Ca>I;Jql<{R6T4&i0k$4Kn8Y;0txk#&~Avx%xje961)+#h>prqW9|DT6Bz# z_c{L#UJ-8P9i3U(!84y9XZb3;*dO9M4bp?SCb`{yl4X13fFICGb;La?_o z4*BQQ=RRovW!l7G2{&MeS-JKj%v^h|sm9Sp3p5mdgy&_Cweoxf|3V48e@Z`NXAOOO z+`bazb&2R(FmC63&B?T>=OfH%J90$w!;wd?(N?(j@~Ch#hkBi@$f^$Bqn*yGjMAv= zr!af(^IYj2Y4jInA6CR&w``sZ*+aj<+M}Z(_O=e8Kkd<9z%_$+=TJ|)4S3kQI#KXQ zSBYR_t>t;?6RN?IBe;0SL%Uwy5nMrFS??Z6f9zod);wcGhmUsdg2o!S=kOW73{2EFM0_^G*J1{i_`(t}#c?K#PNz zlj(2vTraYZlj(=rGaPlh@e!urLvw{iJI|40oMre2w_0bb7IWry@m=5=*>JLITAl-) zdkp-Ctbq!2xl8&{0|i}hDDbd$il5SYK<8j_coG z4NEUitWloK|0ExR@Fcxmc7SRUYMo@cv+4zF1Gs6pB76CjDOp>j)4$JLgc-ZmM(aN~ zACLKQ@K(-vHGj&Lu=+pH=M&HG;`LMMjgr4hX^;6Y*1R-=$G^t4Z;dMxe0A5i>)Bq< z^HH4n2S>%ivom)WLeH90r;pd-`e?T2EV1UI`q6ysy9j;Pjf~;Ewpc%3OKh6aA|5Q> zu{~B}=_mZ2ag0e@Pa4qDih21HrDKR+NzZtYd!ljiGV!$0;8=W2;}O$x zOCNp<9KOf1?b5t!Khy+=M-x4__TOf-z zFVJ2S{Q4`f543k^nn0<}CQyl)&CgwO^t?avWK1$1f`JH@K+%Sj1S%(e*r)6%+HGH|B3(ENVyloVSQp z;n}(m{T5GwR`dHArxZ9e>&2&rzMuDXYCKW@!<@HT&08KcpNd`3Z6j3B#wOlt{~CPG zFy=?dw=2rX96V)^Z+<(!ITtQ%H24(VwQ~`@G+1$I% zJ%`wZr+Cjr-{71j*$kZjTWjs*v-m~N_M2&6@ctP5KmP{woWwpApOX#Y<(V6S?MBvD z1N5jduVxI=lS~~0y41R~)|0g^7xRv6POV*MUCL)Jzi$Q4ivH?Ym;HhNZO+QL0KR-7 z=Ylvk?<#o9-%R-{-AZdTJ3O2|6YbbuY*3T#J`!Jnw)E*~U%HCl0-p`oxKpu{WDDi< ztj$-8li8S&fg`)lpVZltFYvyf_w{ZTW7Rwu8%B+kt!DVH92x01)jTWG>Ay#Px2-xa ztGm9N@ToN>`73mTgJUU(_RTVFiPw~jj4X)|3%f3rBKq$l#-v(hq93Ey zUE=u(A8M?4_`48z{SEi zn{hW|5Dm!op#L`#ZO3?f=wrrjK7;KTZx3BbA9ZndW4t}|`6z46g}~1N@-ZFxSUaM{ z%q=~h{W7DCb%l@LGrR6?@_N6P@+|vjfX!7LTVa$)=9{((bF-T|aPZ@RQ9dBh#xs}D zc6@!M7lG5cKNi?N6pV;IVnX3FFTN53(edj%=+Rae!=H_PRAk@$Uq9NBaML+%vD^1CkzJVe|eA z=wq?fZg@7ot@Zv~SG+9o{15s@7de{PnI{~C?}Y%^znJ<_%mB_1HQJ6liGhbqqBkML)2e1S{F>3%K00WaB;za!=J;S41p(5Ba*&?wUH-#2?__h>_1M zc_F>)~(Xgs<6ZH*GX!#+2#=NRiC%y&07arBFXhC=^29H6`ogY?J zKC$vbU#N=stYTZw!AHFAh0Er+y&WN9JXT-g`+4ZmdEsLiYm9#7`_Q@dd4{D&3;rLId(BmV|+!Hp?3)8`cbd^^06KB7^)`GPjtmi${)GjFWnf17-U0;6% zG?na~*tAsiF{{47zBvQ1eFvhC9fdwd-o`5OHr_W%Or12wIWzQaj`a2Qy9j5yFXVq6wuWdW0u5-s>R2bzwVSCgZID|c|BvWcxY`4r6wm%W-4<~y3XRBlk@T?t-n#CSWwAk4K9Z z4g5R1?R<(Iv=M~wE1yDmc(#{(3W9RI=2LV+kMa2wQwH{#SVApZ%Xeetq`d;|%I6}R zqz1kF9oD+&G@tcR&Uo{TVdmOc1UwDE|BaiTrNe-jyEcPY>-P)OM6x>1@=ikx}W0Y=tgzK)FeZtXFEPC#dzb-+WiI3 z$HRVU0_+#ruwTG;RO^-TKMfuS|orBGn=Lqu$UJ-2nME=09d0*@4aPtSA z(0l)e{DE?Cs+fLn`2&mN;Lx1^Gx-CPp(XXzTmHcOxW3+ti*4(7vit!rb1z!>|6=~Y zc*a`(CFKu%1YYHXI9UEbuKN2o^riSi{IrkCh4{-v8fHu+sov$^YDz`f$yOg}cb$ouLjzKh_yqxFCIgR{K_PhF26Dr~&sJLed#c{zio5B`z-n&wH5 z_>AlNju4=@jqC0KC2JlWAI;(@e(-u$bEUKxvSN)XJM+b0J@O}18)%Q;0d!`H9)8!4P|9VE} z)qQ5X?7%hCs(-+3v6>o9DCi&iV=alnv-`<1HRf356@}@#x(kz32f=;z}EoJ)xfgI zl@{**l`}gR^_lrHa4iztdClI=87}Y3-d}q=y~qbI|I^-BG<(q_PhIc1g)?`fbdZ{<5QgN$2+PNy(6W&)XL7-0EoBYm#wGx5Uf0?);GdH^%qvgz>#_ zkny?V#&=JW@%_ji-<-Jdnf}Gk4b!Ikl$fmWVc?&WuQ8y$QjLLy;L&pe{-*xMek0Y` zZ_ZnV<$v-RRvfuVeuWHIv@*pAeTv_1|L5czB={mNeWCmOW>cr5FZq{lj_+&TnVmz1 z8tc0H`f2jM>gX%cPK~#RZN}rzqy_v^(*Fn8^P@R2>0!`WohBVT**!O+0s0T8HCVKe)}OdNvS2JZ z2G!))H6TaQxwZ(~AT86%F(`*G``~Mfh_j>}#ra25jgp1fvu4|U=tFenA-%W!!5eYBL7YNSoAB~bo*%O(^=t4p1+Cx1iQ(9l8-+= z$4u=?w*8kq57Ljz;^yLT=i>s_Yj5*$dXo7t*9(4f)=M}H4CXv+IIGhcpEI6v`2qaY z&egg-=PdS~kPiaB+ks!tIA;X1k0Odcp~o6J9C})K5PBMr1b&mAycRwEFmYZQZF*`s zke<^07Cnh>UPf*#O!KW1{Vc`?@-Nsh3A=Fe*?o-89n8(ycTbI`=Np}KYDPvE4=_5v zQIi*y-P%sfD$Q^O(pBT^@s!XU@<6=##yU#|^-gDwymKMH@{xC4{|6=fCwH~SePSIw z{vVz2zaZg%QP2M=$6E5$=`ZC3>wl~Js-HWuSoEeC;=%s+CZ9JO#(2q7li&FI2b|nS zhyT1N{VmolSI20+dXcMhx#zt1@zJrRI}-TTU%4i^x{x*x37+Ny;aQmgPs%~ynGy%j zD@owlWW)2FLxm?l;{g2JnE=n9M)r=M;c@T;lfbjWhNm>K6s$6iSIbq z;`vWvKGfm#kM2;czSpOCu66;3U=s}L$ArV%4MRNK^l`vg(Ce;t{EMyRbU8URF}LzP zto+SA7o{Ql(upltags)I{2F4DLOQpg;eDNjl~+to-^7*EMn1cd928v}+RwP3+`ox+ zig801!4a{gmqUv|&i7e}4x@b}jk1@AG*6CIr-r0!kzSZSc8aNlNhPc+B$%z}zJj?%X-ur&{y)3Rvzf%lP&ohUe*9^DgNL}%Y zEGzGl=Nd;_d6#EFV`jX9=aoxI9NNrNl3mZaN@kv;^2r)$Q@J?r<=XKIbf|Vazi}>b z&h4KcxGQ1*>t(D>?eok8Ch2~=(7}4-lM+L_iU@+Uf$u%F1w#-1!f0A)Hx;?u55)Zn5NaupNe?Lj@N~cGE zT~dUO@96$ogR+^V|Eq1sCcitC7zBGypre*W_+LDx97wBo8@`h2HP+dK3%TyDs+w5c zY|J;Hr>kEu&Z{mk=GU>8u0Ot`4)$fS2PdHC>Z`7vc9ltZ&#eGAh2*6(%h%Q{t zUUO){j9ZiM@D-PlS-lR}M;K+*S+4p1qxpWoHQ&c~G3PnYIhOoh?m4+v8{l)Md;*pW z!L^BFd=C!J9h{oi@j+zbli0^N#lz=jSv(TdH(>u2 zb1mDngl9B=#eCFf5jOQq>}kzm2lQ;n*TP)R3 z@-yV?-j(QIyIu1uz5;Dx!=)v{j{PcoJb3+-cZxS6`*`US61#E_;+(%d*|( z$#y#l`#+!B%IbeC-zi4tV~k~UlX8)|YidgN)!|cZt#t)rL#!IUzhfRn6Wh5aS`h5N z1oltae{=qOu{FquB~HD&UDV!9-1GcM3jG|vcy`^j-L(uu#2TG?!9n^{4awF`oN@(k4nEOcpV%3f`q8*_29oxlt+D&k zIXg~Yx6#*Awcm=~@NUn(GG`yy*FE%w9n{xKK+!T*+duHj#u!+Mo0bJ|F!jcV~(UE|kGy51|`srWm^1LQZ6 zucQiJ$voAmgVr=(kzROM2mP2l|HETV`IS$8mUx%sSn*EwrhM#*ihfulO_F7Km6jY6 z-JV1HiSxA-ScAyQuK7ZK{(Yz&|7R|G%ooq;EKJRp#v9c6OFXarE?E<;`Kp-EJzu|q zXIgq+R=9#THNQdXHH3Ii@)f;r$=uds0wx{MrrJ$KPyLf$aOme-!*87yZ=IDLWo4fWZ!Jpf&G|DRIvmo`@fcSI+eXJK;;7j>C;xBu_Wqe=K zElnL0{5pNLIy$ECYwMW8xwD2+`Zzj+mD{om9@2okade0W^&cE4CRX!2Ilm{JgJme>3{5azjJFue_;Y%#G+_0^h>V2)-|7eMq-m z{xxIVv^-=|9s71phW2<)ZIi@g>Rp>{Tj~OM&}s0z&)h?cpW;0|(@I~GXOcnH5%TWg z4dPu6zAppcjxKo~a~3@Ahnz=zYA83A`8mc2JqM36btLu|Pan%fuIDkC|%``%HG(TH2Rg*5e+0^?yVwJl_fL^gyehL!%Ag#9EibEPD)GVUL-7 z^nIw58sw!J+D1;?W|9&%U0SGPt$rd*XZ<7fxFPJ zqwtDn;0anM@oOZ+HFG_}w-eV$2wHU3hJ<;I-$ve?T7=T_9f; z#mdTnHE|79EW~fXc)HKxvuYZ@B^i-m(;t&$4OaZ5m-q2+B)*@S?EN40@;+-V@qO{D z&9>j;CEM>&QA@6yDOU9ad6ZIvz5 z>pm1)1wT$^-c8u;*#5HHH__){;LpKNZN{Axa|*H-5u4^_o;Al2r;q0`hD3e*X6RLU zHV4zk&l8=->*LI;sgFxW+I~Id>vY+J;L@}Qd%@*?;QlJlJ8R~TSqJKa)0l&~Zx!^= z2PJndfv0>K`k;J5j{Lz+x<6hgJ6UVS*2#SMT~6SCVG?|9;ksan*Oy22hEJ_~WU1un ze#T(p)6tjNYao19#Nl%Y{b^47Gq-8>ysmIT!^9FzI{sr%I&Q-jmVWXYxV-f9ZhrJ* z2e)zj$i(eeMhDISpYi-i{QAr0M^nLVywB|StR06R`H(}~`2W;JKMYl;u(uvuvnTLl z)xXm^zd`;7t{Ysx5k2^R&Q7aCXXTj#bSu>p(;jQ-O^N(XxmL-}CQ>^Qo4>W&XN~63 zPAO-es-1|{ec>?(P86RiEilS5xR=fcev^6E zMxDp{Ewjd3Ci@c{JPKa~lMld`@SBLIQt+G%Pxu@Tz!SVB^JqT1@I`2BH$uZl(q|(& zNU}bAtK)3?wQV14!7!tYT2z@jYg5;e??(hfO)vBzyd~0y@OG$lA()&w-!O!I-MqV| z_7ZE3`ZFhzN9d@Uqn8eKj>uQsjZW8n{s6WUwv>mqJhr|YOgM)?Fb5N21ulH8iL`tg z&z0~oaSXp#&UrJu{6pyY6s}Lc?bwK-K^JK0$E{-KPq27a12#(@r;rVT!#L-4PSgWut!w`azdj^o)UHgxaTTXX3T zLo0Mx!FbEYp##Z6^1RAS>5rWxZ3X{#v1+E13ww_tPN*vvS_ zx;*t)@0??fOZ$`szs9D0tE%;-acK_KUeIHla;{+O1@?D z;Lz}}=SzND{D>xeeT;E}d5SBu<92eUTA_m-?h)bXD0-|?C=5KbLc}I=v9Khj(r&OM)^3S*w-n#&KTX3u61ro zJYDZPcRK6iEY``HtQYoTe(wz8eACD&x6TK>8vM=UQ^lu}kK&llCt3Xg#e`bj+E--l zi~k>ZPMzjmcx7!r2u=%BH_7mJSh&sZf!mk4FWjz#2dxCR&F};Vw}r&pz)^|#op8HB zaSoo_0zEv&dt2DsC)@_P&H=7wI}ze;A^t0V936~q%k!Ig{w3NKUW0t2r*=hix7Z`8`=1)dTJ2Bu;?FUkq28XZ z)5Zb1igY`TpM9JM>MX3qWHRDY+DViV((N`tlXWKV%nZBmLnhW&$S3cFarTI-`&mng z&&B7WXpXJ@f)+pR#6KK=mTqgc%dFS69Uok5l~MBkNya*4X=k374>fi@slLuaud&9F zDawPDO@>b(VEf;SCq=0_x6;?s-^&^`{k_nBzWlwcAFX%Eduz|cknn8ia1VHAzl7=U zrH@|mo1Fx|TBphUzI&m!M8B`_i;h#a*~D+RpEt4!nx=Mx#&YF9Sg-sKvi4MWp$>Wr zL1)TmsfotQM0=iuy3v00vyYG~I-j=_JI6Vr*IavUYwhVg9<8Sb4pSDppr1XgwQk>s zRsUMDcyog9LwIFuCT+ZA+XV8VK`%XIv76^yd<4%;SE}yiP;+k!b#2y4CRd>QKh2nr z#0TGr55BOgR(H1#KCwozU@f%qSmZX=^)@$a(Hl(o&>L=I99f^sj>!stA6_I_#{;WL z-4A*YI4ufqJ-WS7O7gG!Sm4!aRex8!u5mncLH1IfMyXrKeVsuCFHQ4_8Tnr^85(owu2kfrwA`{#%2I#yZ$q__OV8%Y2z}-8h?>J&MyDraquR4oU~)r zXX3nI>P40G#5M6naQ*&}GeXtmO|_-_LhWOHojZtWOgB>NXSfzF6Rhp<1v92VoJ;qd z>s72j%}wi|*izLdmQ4Q^zp0DYqgIvb;H?+#k?B?~152L22wqy@2~Iq1qy8h`cbz*E zSv>>!Os&#Q7LSmub$qXz(F6Y7G=RR*MFaBhhz3*-(4m1gaOBWH{M>kKybL)Ey!cH# z2rt$?{M!@obc_D8_dxWe*t2{J1$(S>-=MwKs`Ymgv?M-e*$v%oRmHXC2j=ha-?9G^ z+tirE)4SSS*q!F}jL>fEfAd`S zY1Ur8Ds;HwKEQ|0S*koR=Gk1^(!r65L3BsWedAoq|EB(Cux^TWjyChag2*B6o4R+= zPG8jfu@N=(ar8;)o{m1g+0@G{efK7GC_n3I2W!*Oca_T&=DKvQH1za&$l@Xw`S$3R zZz8|8Bcr4PH`r_5)Pbk<)PY0r4(Ze(-qm^u*?Jmd>fC`&n@-!R$DnaJbaD4lta;uE z@=l1hO&u86W5BNUB3-RgdN9{?HigdjlYaL&F#U#g&>MeOO$F&D$cu9JLqj`n7{S6WzV)*B5qzsF_MT&6BAS)y22OU*q|fa3Hy|kPrI?>+2YIb4v5%_t?)<4xg5dBc9#t#OC98S&hzo zVNBIVN{9A-uA&Xm#$EJp@v!V(d03I=n>lIcdBqQ;m$$>qid>6K9=8x$7cXm~Evtq> zH@|rt{D|L3W-*uHweVbrFE{XBGMVG>V$~0Ic(Ll|IDYF6)`nBp1-zHlf@{sO=-*k> zx_*bQkM3T-x9Wew+ShY8a6K8{GX}v#CXasf^pF*-?>*5IXzJhc)vvETdZKa&){%eh!p9+6kRFrga(5JncZ|05ibCbwKsOO` zhgGwsZI#742GFO;JH{0UMArr64YsQusGdE^I-ADp$1Xy?%1)L&7c9k|J5GEft3x)O z??my9Zd`Aa@ANx@8av~F_fkHeL2G-lultMs@m~$Cnm|3+ z%c34vcKy@Jbz!aRehvIkHts~f%s?hM*%sZ3F&B%1|(ZZW6cPIjbkNYw;PG#v=$@SR zclg-JCia~@zd51fx3`!z8ExrvUir-6Zk*%^py@&R{NuNtje*_%yUlhI@iuUVY&)vsMp#4hdJyg1(`mDt3 zvsb-7TljP2F~!Scy_d&~pCga)ULGIy@_6UZk;hNanKb50ygV%O_&)m3hgsiS$bPLQ zz9-w-4_v)MYx=<0L{85+{Ezhcy`+;}XaaIZzU~vy70f<4I>tfS+>m=e#K%B$t?s4% zSKeKHCPbPElxg%0#<={=e0@W;A!* zDRb(PL46OoYnLwkrgXpTA5wSOR?_!}-!tg`@J|^UM^g8Pzs5Sv?00L8=IwVQ=O%q0 z`S*S9TJQ1KaE!^m`l_YSX(@7M(nxd3^OVC}(p~a4=91#snRAK7USh^vGTog^v^S{! z#ZJLmk9&X^d#~gB{0(29WWM?#^HqcDss80X%Cl_Kc3#H{`Ace!Y$ToL%ouV0e*KT$ zAs)=UFCCqryZ-E)!`1Mm?DGCPtA)8*{Fm~ngpY!H&+B^EdK6ys*V?_l-X?ykbl2MA zx0DWv|7O!eMu+U4-Z{tkZ|aV-&EiYuAYaE)n=;DMyUL>7ep$YbrS-61mgcR-yVG>m zywx)ybKdGghHBp04_&5x#Cql-=ExBKBYg$Ne1s-{COVw ze#6(<84r%?;pyyV3=t-MPh-cwGY{UY4Uw0-2j}|874Uvz^Jes&P3S!v(SJ5zpMHY% zFZbk*aqnBpHAY?{o%%<5w;3b!hx*s}gp4;d`H}8J)tn|8fA1kz54xa!9gpq|ejk0e zh;@y|$cMo5$B6V4jgcAnLi)1lL(tJ5Bh1Mup4u*YkY68tZuAB0&4#CnA2~b|KLt}Z z{4D>8zcb_dm($OEx2OC0GxT!@_J|*%gQWBm#{3TnUqf9}@{%?gdC7R1;LA&ROXKN& zgXfN?DPH?OkNogug!Wzi_G>@Y$PjG5y}k?y&7~mZa#yzUe7LH|saa7(xa5GXsq$(-%t7-%4vkolei1@7HY=6kquBdx*Jva#vaJss6&-~ z#w+_C?;h5@^!ZQj=(tn)OlzvB(A^WtSNVOqY}~@HkmpU}mG8TT$@lYF`R*g%qxV<~ z-F%n2`EK#@_3D{PBljDSK8^mPm*148@`|mr|KJC=xb5CO_2+8$b6NFMyHz)}J=kuw z_2`mp7yuuQ&{kHmJCbO?I$Aj##s@HmK1rt2JR2@}6t$ohlZJq9C{Ja;L^5)BP z599OD{k|_g$erU>_mnTsJ&fN&_tJlwd-(mp=l^Q%Vf5JU*Zy=acd>GpUeo@HZ_Hpl z*tbvr|s4h3~%G#+sgV*?2vyM_s(hCszpX zgVr0f;7=Oe65zmFa*eL(p=LSETr z)u9i&W!-;rMy`0)rEdJ)CnY}zrANn7Ja(t<=_lqMerFDxN^FU49`~M{kSqQjfjlnH zJ-m{2$Dh%jgS6+^czkB~4&X;_IJM{+lfL`0G0%Jm`S{T>p^ul0tz7!9y!>bKc>mOG z*wdQYE2jOY{Aaq*^QL_+|CuU}wkeum*LRA^m&)8uvE$)Aq7|712V{W)`5M&D7- zSF!b^>RDWNSoYTrXwr|o*I9r@#_6Z1lj^Mc2FJx$GwPTr`!;)ZbjO1`X4_3Y7cpMf zF!ok62CEs1eCM`RcUN;C-`8CmKJ%`bWA9{6mpw20euujXIERn#02AS;&f#m0o{)7` zWIDQCu58lpTz&#w#!n!P6O>8%-p-re-0XiJ(ckBnoqZDY z*Zin^4gEXG#iM!LVW{#enCmn8kvm?$K>ZZw&eQjtyn{Ss-&R;5&+=J#6L}f@p0JIt zm2{aiil?kP+UM(qKZf?&^Zg2C*_M4t{owy~z$2OM$^5>~-4`ogJ;--~7Mr_D?%{i2 z6W*wT-e1jUzkxB-MLF2WQv1W`Pjh;*!d~Pq4bj}k{hH#(y8FYu+#~cFw$X3%_Xn3PTn)7v$b#?_8pEQs3Xu zB3wR@pThU{#0=K?L-?0`i1uhtGkZ+RH#?Uvr1Ht-U*h{_hq8P`>Htz zUwntoSGo6M<@%o1Bygv29&-tQ3weG8KaeiQ!i)Kn&6xPqhpoeV_*0$rJ*_3IFFNwA zC0cK5OfTfUCr|H_PM)Fe8n5d2*Lc?YL-~CU`YFF&zPlv)Dy+lshx_dujS-(u{PwDy zx#}C_{~mO9@xSZYwK8DaM!I9UJ$UvGINK>VO6s8=vHiWe~TEvE}04ZE(LM+!^xk$Q(zaPu!!A#+2ll z_#|V@c(T%`g=te=8SA8~SN$>b)d|jI+mnxR#;h;<1g$~i$NS!Z#tion6)701hPQkG+W#$*W|H_Oz@=$v9Yv_P=GkSaFTkj{m+V9^p_3_)B$shCb>APcU z|1Ix6%{T90EfoCbF8b(MWJWP(kWAjMkvDfdu(s+f`No=5J=u>lcX;@BcUYwRUD7Fy z_6tJ41Fq85SxZgYe_r#JZ(A#;u6NVcNt{=2%;(#aqjXYQ1KG=68Fqh5{qu5RL=SJgQ93)v`){xn#=i?^(b10t4bJ5n56iRkq3rld#@#}2{P02Y`FGYDy-4>h^h#f2%-iUTp(od(KZo9^ zR2X}}(_VGYSEILgPOn}2)}J5~>s;TZlad>CE0OW&Y5qN!{v6}$5&pa8ZNDxG%Z|VG zy!U+^)gj;$sD8u;1X_uPCgEOAFrBzm_3Znr{_-Ro9gUozw=`+Y2FvTPmNF0`vcJ1 zBHv)0j%Lv}mp*3ZZuD{K1$Uv3zv$`W7V;JS*xV7Kc}Vk~dsgxuBWv4#h4t}IQnw$& zJJM^i$M9BYk{#yLY&iO8UYqp)!}ZD?p8l6jlL^o%INtiuS*3$!>yO_Ym#IJg3>om# zKX7HFPgj3@+#t?>7R-*6!I}!9tOWxSuDFk zf$r182mPI%Kl$`J^Q}tBf?W5*k2?K(bEkLD^SJ)1KW5L;qWsXnzx+*JPu+w0dAnY= z?Hvzl{nU&8@aO#HF-Eb0USD}&E^7npa31>dqo#kY!=Iv`8W|TUTO#(=uam~uSHaa- zISS5?*#kFzuVY-BnbHJhzw8KRy#U^H(HHqIe9ZyW_wa9wGcxI->^~Lb({rWzTlM$* z)_=FGy$||fKJ(YBH zyD=wU1^H=I>A#c7SK0hDCRF(q@ee%HxpL-hDW3UV<`VHwCV;lcG z?0>}heQEleHmkiB?NndWhOY$s{2KFF5a0ctGvB{ng`BXxx{dY0H1EEn zzWmCiga^I{E&stOCm$Q@rfa;@daDUN-S{$5w-EP)NS?~S=nu&6CI0+xK&QXGi2eE_ z?pTDb=9|0|8CSlY<`tf`CW}$G2L6Kd3({8MN3!Va(?@>BW=;J$?q&=jXRtFEeG@(J zH%Q~>qw(~S!22&tKHomd@l=Q^DVrq_B8Hr&r#49wYKT| zwC!f)VuFORajkD32}NShw# zP6zUx)XZMiA8(oa4+w!zV!B>;LlG_S^*y5j_&iRu8=XCR}$U&3t z);kXVj^ix)5$owXWSyb&#!MN9gG$N<7hG5W7X9SQw5O=Acp?nl=6SRe{eojf?{!)H zmP>y(bx5sms@(OBWE|_8H)*@>SNOkfeZw3w)cWRrXp*hV`*cHQoW6^A|9z0W`8oCL zmyrW?qtLI_KiT_};(v{O^?~luYS$5!+(u-h<>`iU+2D7(sv!m z;_uL}Z_=+f370+MP2P2G{Jq|Jx9@$}I{XOv_IdeAKU2OId*V|l<9p;EMP9ji-(&KA zguHvmTXzvk=HwbXd6e}Zpu5uP?C9-0|0C(t-(T?Nz_FCOJgYx$JkTU~l&>#vj1 zE$(6d$H(IIqUK7@Ip>|6f-dnEI>mkH5(spa-`MdHS5N6>-%NXZr>LjJcOqXIGvy8Le64+D%)M`PeEp^S^!*Rn zdDsW6J;?g5iS&1Sdd~NueU$Va`S`AoUgNqBHF*MMO4s3g7H?c*Zt0_*de*l!yZDZ4 zrFC<$>MR;%>#+T;+5>gJA@1|OAbuH~r*ifCT>ev&>ewG1GwGYJzp?-KHE&s*YngDX z`jhxB|ET!xS6&L`P59!(ThD*%^(C*|7a{D2>`(IDzd5p#O|YEbEP3a_mx`@P-xR;O z_g`2i?~QZXzP&vwUIEsP=~(ew=oGK8R`@%3uJ|GA z@O|`E_I{G~GPFOPYu`GL@Hbg|^rh_L_nLc{luuudJH@m=t$f7)vT?ue*|NX(Q>V5V zKO3!M{CynRyjAyU)V+>&^;1{1={0yw;X1G1JQZ_a^_CRh_b9(m`%HZ!PiZ@{(z0eV z`F)pf%zRJ!9%X$FTT{ALiY-pDirZ#Ke%g6nY;?ZqIw>s#ic|7T@ zM>H=y z$r|-e$x-E@wX2@BZq<6Vjx!}4&@jlG(0fi@R+#C3!jS#u`%1#se31{&WzU_J*0gU2 z^FzlQl;11#gT85``8<=RtDxyhY(APh&KciZUqABK>sEO3gm5_gptUGgxBb`N`{dSl zZ{GOC`n9XA33uKR4Xjx|3aYk=%h*f z&(FGZ(xf8(FXErf-=mM-H|YV}i=Xsp(WFPM@#FcQU)k94YoF-EAVLX0MsEW{qV%@@V+cM;~2eJ+L5LR%%Tyet0|_)e_wuv#hpQLrZHS zR@NA6j>p;(WwEDsMiTpWN8Y(0B)J^mnV{KO)a|; zt?g~~vB#`Pgv{IPW044tD$P7JG}R~d(3FVOx3;ymC!1Pg)-v0w+PZ4}daJ6r*=}gs z9cxK6wYDVecw4MK)tlIY zKik%njP7WTd6~F1+u7E-d)UOLvG%h~$woW5FCMdJ`?)6DqAdy2nskXS9!Z*@U@}d; zgjMZRSA?Wls=bS4t$t!ns_z5OWvPy=-hRIpd@4yXenkMwv05^ui)A zQKUWIpmywtChHqBklJE25`KObl4eFE6OqL3*4AVuzOaX?vEp_$x9*5GXXNCyp}Dy! zo@k=|yW`1ycA_y#S0~%!aLdltHru6eS+uP!y3bm_JKoxsbeVj8OMUC^cr@80zN&AG z)jyqR-<`0F!+U4#wfC5ZiUrYyixw^^wZnTCM`KHuE?uO@9pS|lOBc>Bu~*o|8l)v9 z)_M&qKU*GcMycJp)85hA-qJu;(Y^4^tOkRa&0p>~Y>%sE48`>=d!o%vjM&zOSgFmR zgBuyJv+HNuv}QI<68Fw7wRgdWDQvgZj51S_<%%G;Ld)G3$s<*1R-4V}R3jg=21m8- zc#85Kvo=|qT9Z(#IVMhwHMm)Awl-(9tF^@+^3nSGSi*0pRb$mO)j!=Fb5m`xwnTPE z0;#eG zVP!WZW4k3j+$vk|i8i-;xXY{;tYWLwDzoNT@3Km)U$>%GbVt1vZEkL@H{5FElx3u# z6>ZygIcB7^`^2bJy$GpqModSVS|W5; zeQZax{%NbewYeGUN=^r#%T%}J>EcYaTmeHDWrh0!>M?R?M@C34KvQM_Um66TBeAwN z^S(RU)RKDeLKC8>)gaNRxy7Sn%n;g&wY2Y!wLvV4ESM6I3r)LuO<1wLv?yYzmVPv} z3l86%%~8m@s~#Fb6Ia+pEW6lnt^R3f(j23Sid^6^Ge@K*GTUluAZe2suTYa_$M!M> zBD$Iw9?y}^YD&0uZLmc0MALIId-)1GJb2VU)k@=^mK4W15?Vslrma1|483P#+ex!q_= zeyVgZ$=aEn68jRC+N9}=qLaJhdt&ugdrD^bBj0vu&Xg4`%N6a4Q7K2BnjC>Nt zhn#qQjbX4-(3YNU(-VBELsRNUpbJxBv#olop|xE?!qCNH?tvjKcP5VPi6Rx4Lm4K! zVl5Fm&3d=B*B_!*P3kFCZbV}+VQE0b+FA_t8ulV2%*?L*5*GTHQUB^&Rr1^w{m)~E(iB;r26IIV3>yO0$T z^@^15c(hH57@0HBkP2e!_8o|ZcA^upXj^?FiJ4Q3Ocz?R5uEi*nQe3y|DsuF3?Vv_ z?nFMZ{fZBjHGewY8C+Y_M0kg_zaA ztg;1U=#wJqE)l#*aAJl54+R3(kw9{>kCZ>#{%RGYaY;Q4Bf26f7 zvO7jw8<^Yo`Jwi#C#9Cnia%!6?5maX8d)Wkv{>_O38L0eG3Pq6J{~8{W}~>-bKEXk zwQr4I+$v;WRbrzlu{e!a3c>v}!RHbLp3z!aYN?X8A=B3461yc9LzRVJsS>&Y!=h$i zwU(xCMW24QWKcC~_PqzDZ*8lm4v{s{L{gPenv9Adsy!T0BUl-9AC|3iN)4SO$zYTU z3(~1IUSiE_PqfX`aBQ9z-xq7yGtXnD#Jq)N^XHe9&ueO_Z*Fgh5i4F(;JkYGd7fD? zxV>N2NZt{ar_aSAN!u@G?dsad*7fgO9jJPV7o>CE-3kU`HL7v8>T>M9( zB9W(`&3H8?0auEeXtzcws|E9-6r`w`l^J&4C=J$rBwRH~QhIg*&C@(Z8MT4MM?S-Dw3`#DXX#MX)=h$%;V(29mL&zP(M;7z`Ih=f=1p0frLO4$HPD5R0rE{pK3B zQ+EY>XmDNBe7_rps!B!o>v}Z5Z{P&of&|kusl(W@c4NYd@WjF0K zg)uML^{i)Egt&#nqe&xdS>cwH1(ySn^s*shmIhX&YRi_YUyD@LtPec;Q(DcwRna)g ze$4NvG`3JSJ-K0n9cO7oOSIY%qBkQWNOn;lWN+2V^{Hvr7)Ewr05A%SKT$J9o0cj| zVGNyB&D+h&F0;+ZGW?o=aT&k%s=2flj`fW(llg z+s^>h#$+;{ST=8-+eNKyyXG~-_8=P*%pkG0dCAON=DNLX*1=_s$=%Hl)z6K_o6xB; z>mX~BRwkZ0h;+9bTc1^zCt92Lpyo*LLy4n;yX`V-O;v5xhGo8flcqdlvgPTP)@NJn z7@48|4vk3Dlk}R4SBfo$Wwozoy6bC(y%*gg`wVUO6+4Mod-kj+XZ!4eMW;5@sq6OpTdS^)O0cS->#rt2wz$>p?st<`|r2G8<*y zWq}o0rr3V^S&;(KomPlk0lqeteBxPSR*I~t+FHA+YQu&hTA0#P(pf0GCtI4#T@N?&g-#QQEQi@1n!tIcX_=Ve7X>wydtI{` zk;Tx(t=hb?rfOB~D6!41MFy^F z_qoL1DAJQPYh}}}xvoI;GnERITIotEyJFMF@+5C+*DG58OnZ~tr_1cs zDf|2L{-i&s zd;IoXdm0nFLYg^!e$3rLkD`d}P1-w~V$Ejj524VybElRg8v5!kL7%-5ImU*OvP8I3 zs#&*SQ;f1e%c#6tNe$Wn9qi)SyJnY^m03@w#Xx2%^)&0pSlcpKq&~H&iJhqdQP38P zYd2PFL3X^1RXrnlnhwKLj7>YA_oLDacSpsO8CkisGj&Me28mmoC`pkw&>BXkdMGO^ zpNRJClG#?ZZ_8o(3`1*D7THv@{c-J%zKm=j9uz6D3_mU|k0kvaUj#l1E8XQ9ebC9= zC+xWOTeWlW7&`~90l_yC#F|(gES$GmU|yoFe%>l9_wzPJ<0~;oVk0mS%a(Zo%hRvv zM}+&{cZ+Wa5(o*pxgUaGBTQ++vc;m2&nJeJD1IGwQyUM{IT7rP`n3oI}< zJl7;zwyeh0rP{o)fZDqOv4686{9U#THZ?~nzaR=f!1~eyurh2-`*y*8ci&fC*n$jFSY6^ zHFlL*Ti76D7jjvkOtTG~Qtv3VeTN&Aokd!_&PsSv(#R$Y54ZW@1>uF^^6;YY;_#Ai zMR@7_@cjAn7tCKczkL3p`HSZ-nO`w~>4NZr`3n{-Sh%2k!J-9=7c5y&v0&-K@WS~E z7c5-3upGaI#S51#tXR0TJX}7%d_nob^78UU<%`Rglvk85T@+q4f6;SyI=K1}>vf>|q zmt7uy8J>J8?OD5YzTzwuEuAOYXUw%dXQY&kE+NBHDhvDp=LT~3mU3PV0ukt*sWcQj zTq?ib(pNLmc+G>+ab!$LG`q^YyHH~wXh_Pp(L*%0^R$ncaU}G76Fh&XtP)bh7)(Jo zf$=pPl*rrkHolmW7ydS`ziInitYP|a{ili0BpwDSAToSuynzK?q?!$Hv@&*ki_sJx zv*%k3EpG=yJG;q9Rf7GC;Er8MuA${C*o-o;Ei-w#LzD)!;qisroAKx&#|Q!5B&)3y z6fjZ#2a!5eBqPdLik6C5q_;qDgRAHGlwW`v_0tN|GRN1V7isk*qgZ6af zn6MM|xY_ljvY&0#rnj$tq~-(9Dq~b8Z|)Gs$&=6|RGobx8d-&)vW8Qp0%p}R<9kxv zGJ^Vr4TI%MTKyVr?s8fQIIXG{)waPtr;5O4#?=@oCvdBg@X3>%5FU5|Hw>8KliKE?<{)U6EI**#QGTf9# z+k?J4)7!)!>~CDNZv(DqzobrSCac{2VG7CF72ZShr2u_9yKC}$*%>0 zVvvpFqh`Za)*arYm+}N`oi4KkJ`twZNMW`*Sd3u7z!?hbiP?IQ#o4&sT1JUpK7X-U zcf-BQmU+sxD@RIZ&0k!yVg>7RR?;)J?!y;vH~ZkbO}=RnXH3uVgV|K@HU`;&^PF_d z?6;cJHk%?F*$LUaDpIwx#fm{Dh!R6F(ho8yWTlsFVa19;SgG`ba$ez=uP)gb-8%>&s{mDS`HEbKsWJwY zo?XTugsd{u2vf!&M7Ipp;W2vIGsk$3Gkk}2u^ig~E|c@3wRIFG)2t%(+z7nUb$LxQ zyU&}AN0Vo4Gu`g>dRFW(cAKEN&Bmn0aG;XDMa@{pMq^}A3x+h~ePGnG(s$Avt=P-q z%sI3(UB>=s!0B_eg{7P{N8OykPNbtPE0?qB=+pWu-@%hVs+U=}AQX&iyDLP8nDaer zlcx|!#r1^l=US< z-6guK2&We4xb@&~gF2dMZe{mU`wk}KLC9F5P#IYlM;mlxg#8CrK+N}k2F3wJ(@s`_ z8lFl)&rpIC-xc=z%gV|=kV=p$4`snWiIHBP*v9QvBVHyB&$O-+CxOFou4SW4TyJ-Zf*77SV!O%CIf>wE4_<|kzv?Y8W#6zn41o!4boF_cuT4ExE#1D#WHimZN&<+ z8u0g(wYF&8finq~|KTX(>J#KURLKlBoig-1Q-{Vw)i!qCkubgfM5|Ws>a>Qxgxnaz z^zt4<)C7hNnVnp@ZqF&PQrp*Nu(;+|_vnEP4m&xTnA8@Rw>hm2;`v+rjIcJ=2(~HzLg21S@W zwa=wBGAeX@5QfROrB(6`k`9X2VFq*TR0z4LV~%DG-LA4+B#R`lB}8+Wip`;39n4@c z0bnI!&Ik{xSD@Sc{7wI2uomm_l5p zaGBEdy;sU`>O#6X!&P5{JnjnL;Jlsi4kyaO?@KCoT&A;)xB>BkoNG0EX?B^K6IJ@0qoEnVz+;}pjQu(KI4C_+mTy@+ddgSJ9cLYNk;kYQq zS)baqH5r}4IKi~VI2Wk%p>oPaonZNBj*4p`?aeH*s0B#;cDiG6U}heDcf5_R@kh|$ zu1VLJ83s_{;>&i>c8&tg9K7*qq1``D%8}r$7ry1>~1u85=TO%x&yPpQ7`*|jr>`dG-aq6*N9b#ObE5Er{karxS-dD+S34@qS_Ddr;?UqUP4zJdRr;CCg(53E*?M1MJ!ag0%?Ud!t1 z-O_c4Q~}1+?;kWTW?bW~?b>wBPL2Jr@4}rChz|qlnKpfxaui422DU=vS%F7`&ST7d zj3hbh#g#s)7W-&hmo3x3`*!=#GcTK}lw!Tbm(E~qG`7xd4Q;rH1w8EDV{G}`8vM{f zxD2>bIDPOxrgg5NYB}*_FnmaW8sNH)hb0yg+}v?sKcek$|C$JUj=f1h!*8*aIJ-{QUdedXO$VP|&TP-o|hU9`=C`oLXsxh~0B z8p}rS`U}5UQ>XVgeZX%zos??$l~zODd%sHq6G{uc+V((lj^k zXHxm!rZ17VLkcxGq)jtPYJBX#Q1i5zT69iA^GgbaE0^}h+x$sruAN5pv6y)>GtyL) z3NaZ8#mlJP)fv2uggTm0u~HRG4+it<(`^JkanEB&ZsNO;h{5D0b#Y+c^2SGw4dc|< z$q~m?=I1e5o-MUa*@n_9%!v{6ZV2YSuW#YRdQB7~ACr)&@CSxC((sGW;Fo&>C6h?G z&ZGQdbqyR}a5YrP_TrMq45PXsE?2oBGjzsZ{;BO|b&kCgTRvyVcN_J6R6Z$N*g)G0 zyJ?fjEXmSR4DGNfnON=}xq+Lu8tc3-W2-U3$5vwg@wwBCb@o&x&Hb=+Zl2VR?no@i zkl5~$$m7djgnGDq8pjCQiYpJ!lIR%JUP&^jBCC;!-IFW$1E)yv^nCs z)3>=h1-dlPU5#aE!s+h#ze3X-R_z&XqWl%rFbo6w^BVeHZvA>ttFx00tswl|g6IE& zS(YmPTTZem3jFHNv4N@vrr2Lmo~N=Y(VLs&-~KciAi&UL!M{z=vO?bDP94sTG&OA4 zyf#w1e&gz`wN)EywpyH)Wd~E2-J$d1Jy4(AYc=Z#Ej}lfE*z95Vd>yNORKqp%e=et zx53(-*kzGn4M&7(t%lf+_FdMqQEpMhAYZ+C)7lNIBkQZV1FvNlSI6Pfy_W0wHg8$K zcKs&vxN=L?rd8`O{&PgK(S&fr#>VxvGVbqgN?IGMHdU=%y@mTWR&U(A$!dtQo84lC z%a)cc#x2fVb!n~Iu)2zy)xJ=f^W9# z&9#x5Evwh8-)7C@e$IJ2o7#3$9#Y-xda!W4$Y`Yqpo_e}@cS~#h8P0{b?|F9bzUQh|uBu+WX6?H5 zk3X?t1p1xtAtJ0><>QvbLun=8W zhSluxq>lMXQ8fo(( zya(hzz}?fk+jnzi0v1@dy*Pry9p9<)X3yZNAr9&Vvrk7Z8!obR8vdxTHJTN$uTg=I(`bKjC>bZ6uCUe(bp0z$RHpq#=4iWLlRbq`UWBC)OFAN)Q zZ@1ldK7HW#h#L^N8e+(7-3!}{u|WsDB=$t_A=rXiB-l^q95@NhP8c%wSA|xy~WzzW^GSe+uLV_%l85}wq4sOO~J$b93WI1=KCDw0U8c`^(@n}=q z`X_kzDzMtxnq06jvNeufk;88>cox4FMpiT2x8846g_6uw z4cKmAApAY|tzJN@sMF$Lo|+|~$w+DDM>cZeYp+?sjD$Y8Y9r7xyqZ3lA66^a9N-L< z$gh1*RdhGEe@5`tV5dHkjP6Qn1es5xq1F8PBGyW_pJLILQPRtAOlH~<8nj^b4%32> zyU(3Ls?E)MZ?{Hf^6`?6P@(y&8%9~7B_h%KmgL*4Oe)!k6=@n}MO?~gv#4d)+pJ7R z(h(}O5Z-(H19+5eFnWZmGkAh!#E~{ymhqI1(Phg}$-95dqZe+stjk>3-T8Yzb8gJ$ zqkOF!TrD@d36PU>H~j+zyNbT#VZW0ERss(K>ww1;5A4=^dB1Z3ShR@t0DFO_OZuHU zV0T5oa{ySgtlv2WELz_0oCk(i^gDfeuj+UBqLkIUvfrry)~u#I!0wuU=P2;{d%y?A z-%tG&AEDlN)80Dh2fQBZcjCaVX7GVMz*9hbH|c=gz^lNEz?;Buob>n5z7O_0;mPFp znSQ5(5ANB&)$g1D_P#`a5MK0hztaiqeuaJ@yy!pEe%`zO3-7>-C;Od#VCV1mJEc>o z&gp(<12Fuhey15&`G?d8*!!pSKQMl--|1EOe}i84QvYw#USRKE_B-2wU4PZ@><89d zq8`BT-$G~L#ebk2p#4AS|NFoPhJkfIgucLoGELp-g2%3t)Ja;iXP$}I1|_jtOj1ceZWZqYbFgi zUBHg}2b_z74-7chf%dckr)VbS0cQex>;b15STke5X#my>)`?CIItJkqxX^l zrw`cq$bd6t7WFC}aLR%9yaA^c7zf6IMe_%oqrlz;qyt)uNC&I|7CcNlfHtsa@qkka z?5rRi@Z!<|=MXTyY`{4M3_m*HTmTj=C%xVuqu$8h_`3$23Si~>0jE*$aq27h1nmXZ zY#4CP0xtqD>wV*ZQ={>`X}}3HPOk&E0lPL+F5%t4gFw4xz&QaddN<_)dx6)0HCqOp zLdJ3L)&XZ7eA&Hiz&Qq=UVPtxa|zh{e)3WHcIp8P|2p{qiy{Ngd0-9jDzF1+!LOab z5d3V{Q6FFj9|W!g_U;&PCW)Wxp)0VrfqDYtI|rN&U`-?GA0ZrA47B<1`F3F4(*sT? z@FK7W7~T!N6yE|K^Hfb7dI}F%!+ZRh0cZa_-uI9%?;X$aAyvIUPrZ2$@2CC1N?^fU z(gUXe>wu-eZr}!B&x_C>cpZ3^^hE~;oT*{T{SU+g>yDByu;#ZZAH1St15PjRMP202 zdl=YDIYpm?ZoKz?9!Px07wG5tq&q&~EC*f$HVFPF+NtpWJm8!W{4bQNaA2R(pP--0 zcz>1j3#jKw_zPI`Me0p>{1o-&z2kSFgWmrubO82t)1QPF{Q>~uv1Ha}^;3uX3D&uVt zu!sDB_Fqsgu=iWks~oyr8gQC{J;37%2U?4H|6AGt?D{r*p?5xjYlCO=aowwoE z1&(o?smmD;;~eLp@WwmNXc>krTl#XsmcSAcc4G?Y!5_ zcAWjdI$$R-4m=L*0Gi-Tz-pjXOuKPNb|u;ZLn`t{U9`E8{9 zO3K*`y`P}`chfFl&3k|wsNZ`X=K!$teU8&DxXW?ktEkUY)MqXEwa_o554Tbe()9xC zc)t!z0%1hwAg~K~3fKee0d_y*I9K%!ya~M6Mn6@N9#{@6N{~OW2N(xlPtxx|tDSzK zoJ!zjU%9cRi)>JKah#(|Z<4qz>? z2N(xl1RenP0*?Z(15W|1{p1fU0$u`k0Ivf(fd$Z~8#o1c5m*Wgzd(C{mB8)58sJf2 z{Db5J?0Av-QU4x6-Y)|CfxW<@YRU!91X>-AQvr+vYk?iWMqm%{fZ{*oI9nd;8n$c7&% zKHzm=Kd|yQpfCIv2bKbRfR&VY@gVsDi#|rZ3AcfVfMH-4u;$~)1z;WU3h*NEn9?1B zF1+^w3)fK&@I2w+{{Ve>uLPC@yMfmT@A;38Q^R}jCy;xLzw?AudSNzD&o>A&*;U(o3RGV%o9okbjx`LP+8ihT^d#2pJX;$IAFw}J z@bb9NhD=`{BJMJA>MQ+<`RgL=Dq%GRywv4tw@Xc%=nLS6uvMsxOj^2>oJ#O@;%e{f zclN3eQ*90zs)!eg2tPfw-%(xlQ<|BC^$>Pm`Q}JdO?>>pbiI{!8)5qi+s1RSor+5; zKjLZ?x32JkqL=eOtL7=LlehxxEQXH*^ikX?;wp&S%X2WD>V2NLW5oHi6aE##PUOH> z+)d&NZR`*{XV-7i7{)Ylor(+8PvwM(J5HQmj>4)5>n2S3>Zh=6gqJ)rBkUm#+Km>H|+`Hr($o)mG&HQ7l|7x?N#FI9?IQT3&I~DF1xKZ z^_WWBP2x6W^gH9-8$)VaB{(y&a~&PTbLsJ+wl{)z?BRartndOfRof2`S6K}GGRkpF z(HJ%FyZn~sDYdJg_%p;`1CErR>RC#A_F~&R;mP2Pdj6JMPw{@O;@_Jd zBc}feDY?^s0Wb8vey2b) zAahYXNY~(8GkWxY8B--pTL8aSa{o(*$& zdfYd5{Zupm*dgTgN04Jf@tnAG?7Atc;|6f|{(DarKnGj&_GFmin~C4{AHBIWE54Zc zL&Tr|#K>i-Z_j{x;Wx3H(x%b$Z6EmCU&1cy(I>lZp$YW=vE1>hTQTuxKMOC>=efs< zD}#hv3vSov`kgMy91d5!-vRCY*pPs>cng)`t^_!|14>c>y~b%C(Z*O_A!ki}mr;~McNi0{w<9zlKz ze=73+Cbs?Sqrg{xZ2&pe79XECzNQ%Eqd^7RVbJ8?V%afbLZ|FmoXUGdTUVJ%)HeY$2{T#)^m%ffB zx|9HoV&#upurfL}L;Jp}PHbj+o5tBqⅅ|H#+2++TIHqml zuMpoDVlPGU8EXqyA67f9cObtfQdTMtS7Iq{DsfW^vGoftptGos6~rAP?t=J#h&f1k z)PYz2PWAzE=9&_te%Ij(3x)n$JMxwvybQS!L z58QGJa`1xMqWQ6tdGFjXZ4n=qg4c+x{{qkY+5A-!HuGKBtJQ`aG*5m>Jar+Ig{?7zH7X>G^0&vomO&wIe2|*DNA_`8t<%ijppX+?~UM|`ZW7^!ZqX7 z?N8PD0C5*T!yX&Y*>zSq$B8dG%HEdZhbc!ixd`rYaDz0tN>~?R%}Sp|6O~^;!t2C$ z4-r3;_>SMYUShAzWbGl{GD zJnd5)KjBvpwwskp; z?e8PslwUx9Ddly$(w}B8RRkMhp0GhV1bzj3w6#NwP4SZa7?S^;KJ>;>P%lxL7l}X4 z{;sisj8LX%XWa!oF0yZ{=V8W{notVviN9v=Icp5t#H}N)|8L+2(IKTTrFmF&Zw6<| z-!f<9sJr415r3Y&=nkH9jWhXR6n`i8I1+DMAij@yTj}{J&tAfA5SDA~i(WDeR$qqZ z;EmKrqE{IFc(5>B*}jK5Qd1Czsl8H?C%c|FF%$e&MoIsj(EfN#MkC| zb6-FfNN(*XZc09Ta5=|fdfk5Q!n=bG!p9U0F)r}A?3 z#?%^3X^ZYbo=jlBljq=gR((r}yGh(JK`rgSNte2l} zyH#21h+BRa`>;Ic8oQ0epC!IW@mX`Q@;*rX_DQ+<Q8?_Th`v-p=^N>;o2jBvzfoj%?-hsH~ScfN)7Ipu`D?BQjNDdl&Jzc{{YJ;M7! zZoG1E&hdA74|Z|ctv=!54R5EJs{T~JgeRe&F{V@bXZC+;FU1D8lzLph=aw^t^;N3g zfw_A*I5ps0yB9yHCCc+*LijZnKG2ajNV)I^$=G!=8jXG2w$zqR(ihIdZ$@>xt;8fB ziPyqlohRLmu*)-{JG^wm%rl~IKWRD^As=~8rAg_LZoi67(oy=r(|R$5H-y{~el7S@ zmU#I0dvzHCUu`}Be(@IOCtgB)SV+Q1+@&swmV=irzw z;cte@&HU&IjW!dmJz)O=zSC0|9Y5Bqq|#7pa;=fOGq?*_{Sm7{%(>!dG+ zUZJ&KTe8Nz`nwvukm@Kpy(^8Et)r_N%6It#j8}Z!Y|>@P+m{PJd;8dRG}b1n0laQ} z+s^Tvo*UA-p=fdtob8*_YgwDHV}z|s;ETm`u68S34>;wd3kipx!Y&aO4unA(tB9$N0R`HAYf~lOG`apUeRRQj`4*bM~JE-01u_PKbfLruYPj486o2Jnr zmH)BaI)d^!Mf`czPTff{ED0 zpLOMB=oPO`*?sQW;Z@&q@EiByGs<)5)m%5&%o zx!Wha<=}OIcS?Al7#goZW8)(p-bZrdsqKfr>jdwh^7Gp>MBBBGkwi91wuipx<(buX z^+7Lq+mU^}%5$=kZpK>VpPw&(H_g7?Yvzc({XP z-R+*o0%ej$`xuj;o95`yLtg&|>LA&B7Mz+R_@pb}yF8o``b%}cLAuK?0Jn_;zU@BlHyych~T^-Qb?}akmbQYsN9S@jvwBjz5=Y)HidS6&9iIgI^$-;`ase z#}4=-h_>b6UFJ-{B;onG4#P zv21qr8|8fl{Hy0UFT!)^2OfS_{}N^N`coyy^FK$2RRBN19>Qi4rg7xzdakWcaaV|2 zN8C}xnf9mSZW4EaxOG`^YQv;C@bmu|o!nF#s=>GZ(p#qtGfpG};^3YJw}$7mE}yo& z=v>)V;twc(h(1<6XTaO=-?3u~FN6E}gK^%PNp(*W7ydiWe5BH)_bAnGM~LqrUbGFa zg%sCK+!5l`PuX!7h->_Zz&b79TdH$M`-wB@NUD1D6L#~8tFNVLl}ow$vDsubb!Z%aE{+f_DWxV{7JJw781AY-Fs+?h*R#Lxk`P z=Hbm%8Vf~}&}*1O<+l`i!^0iLoU)E|$1iw##zU$xKg#gt)nopeQ}s!LdjekV=Q%Xq z!_C1f!tDZA{MaE`^DjB-9`K>Q0B-oN(I?bSzwX)dtT)Rl?|$%$;I-|_J3yE0I)}k6 z#{OS@iFK>;{()By)@^ke@`<_4^U|gptnH+!`3~#SA?u!LUp@rB4X>RL{y(JKno9<% zuMd==@6gwJ)=#{7l&}p~y)oj-?hOByGsGVwe!CK6jen)TO#IaUhdK-qf0Ot_{{$U| zh}Su>(!Shlan)1j$1V`>*I94_Vdt~LbPoMoR#=j-o~*Eggq_U_J4V=@s1evcj$rc7m{w+RV??Jq*8Rg-s%?D-b5RQ%u-~AEtFoV5m!gt zq&FDHDlkh%?kDajaYwS^O#c%%^_o{+YVF{TKEu z9EPg-+5Eeou$zQkRY=BM=So7Q>jLK-=dt|qBxOz$)~PRviIReskA zJ5E@bXZ@64!2@2k zH7o2mVZDSEs($>$b7u&kNdcU44WdBdm_+>~?*b3 zb(41LFnpr?_Jem~*~ol+9K4H8W$}> zUM)}4ShSl-SP@|)b9v3v$53cF6&jjXVO#mEK1{BqT*ZG`P7tVa0; z>>Y|r64y=KcEx4ME}j3r5y(qzK2F&6K$!A4L)bOKs&nLVi8#A5-6rAd9Qks>vhmgK zf(l6g5NAO(u1C<3RiAS3J6C4Xb{%1d0%0@3+fLX)!iJLr%I^Sp9jh|weUz~Mgyo|5 zY2q$cXO@4SunSpXR|pHO&dgWm-wO!K&R29OS7P8{%~7rxHSZ(GaR zP;}{$=w^e`4E}k}R5uKgi|%|coKA2iJ&~=Gq;(0=)tto#r)E$->G@iDO_~ntp|@Y= zIrJM-_?KUR-)vqhz$v)w;XFSW$MhpOovb(H$)ntX~bzUAb|l%s^gX%ji@- zKby?I{IY1U9Gsf}>EZk!H%=WmXMLP+4#p`a+XLVnWF1q^I12rNhm&esx(_vv=-!xP z|A;;LUU0wY;f}C>rgVLzJ2$|(NM-zy*X9w%ta#Oai1~aB=b7_K_g}npL(Ji7OAYvk z#-T41fdAVbevY;XcR#pY$d7KGQ+3MFBh&nS0^DluB~V*JuXy&evOer}n7TUftPqnKg;d9HekZ=sTNq+Q;Zb?>6-K z=3sh+!LhLMUt0`aRbQVk2K8^I&02Q^?M44GdoMmuq}rI~SJAHy-0kR070UlJ>2~I# zpXkyFe(7V-o9B=(SBBt;v*6myWrio}y}ScFq4ImdISY=l>24jqe9$c}Qp+1#QP`Q6 zM}@s#&M+tMc554QE5z(qcb#4&Z7S>(VZDCXTI=*!gzwmb(}mWhv7s}C*442^-G$bT zu^ph?7;h7DIaGL*@X!%Ty*Xhfm}e)}5`Ofyshny#eOs4m;~cBXE3fU$J2RH!&PAPL z^Sbgc3x7;4Ar}hPVc{EFaAK@=bZh|urzmi2UiVn2lWq!m9Lnbk;=(C2C(ndFH6adB zZsXxVUg+jn>rft#XYxXv?CjCwwY*U8SnGx!yYfSq##$%xdAyV#IzN_E(mWm<6FN(6 z#_)J{OsIRTbxx1h$ApfLrCvN9F9;o_E(JVZE(jeOYxNZrc93NO6ZnC#2lI}M%R4l# zP*u!-Vay8!FN}R*+zaDh2)!`jg^4fR_CnzcQ)=DHhdg+GtNVV@gMA)6;lZ9P*yX*S z@t~j1>ssh>d~DvQ$9CowbTm`>Q2*1`k%BAZ4(ztNZwvP|TgMASH=njn!w>|WzP;f1 z(|O142=RROj&u3fnyrpIFXr_&TNm%@AIICp`%dSbXtWMJFq7P_JTSGZ(K_{D0U`Yl z77~48+RP)3R^PNDp07<09e>I?JLBN^8_m{%IpMCSt($W~T~Aqu9yyv%(2=r&OHFw< z=S|}Ic=*B?lH6E$V$88d>&lWYm3(8_%+5yZ^rOnSXL-^2r}ECM2wiNljy)E-Ns@Pk zt`PpNVxG@c7945LJ73ue=`L4=PCSKnHS=hrb#Y|@&mF4@NPA#a4IR6xkbu5bGY>Ud zC#se4_3DDFjn;+Lp(~A6=i1PvM(fPlg03d3XYI_sM(gU@ZaDbJ)7LQB>xkk zvyIk~C-yUtH-x$yt)mQn1MQ5L~u5CJ00OM{6oqEc;ywxV;U~TVM zqC2)19&F4z@qxkvjd{m@y_t}{NMT1~-kG{ao)7E@_3z3%w1Z)Me8(gL&gk*tjw5+I z_cW-g=NbyA>iLEOs(PUzOn83-I7ebrcsv#3@tk?QqQ@KN@z72lkM9)1Sv_7dkJt2g zV3$IV?c(vYdHmn(eG7aPMfPr0PfyPfCYeb{V2}Xe9Ufr<1Udwe1PFq>A0lAD$or{5 z5m8WsA|eEdiW)Ua6m-Li5)}nq9|2KOP=g|(phQJQMa7j>RD}DT>Z+ceNl<^g|GoGA z?u8#yed;@3oqBdvbj=p;ijx!{n7)zhWjc^az% zQpNSdF20u&q1r|AVHXN@(xn&b_({B8tn=l%xTC^jyc2I#pjUA|e>8TIT;I+4ZjOA9 zas4=FC%C>;<0pAknpV6a%fv=0kk1ETW-id@vxWLn&KF1Vx?^@A@5`M$v0UQ^Im&We zh|4u3uhjG%8ctcz_iB8%7LgS9-hYzzc^BX0TBz@s#*pXXscg3vte(m?yMlYCV!laU zit()nj!tFO`g)XZsWAh{aU*bKDqHFyq}*HP0kk8~5+;_$@2rE!iF1NgQ`wP5he@-$ zMWL$@m)1obvFF>SET6)Twk`G|QrY$2sNb>ata5NV zkfI?O;8YIvR!?L5hk5s-9>aVGr?I2MN@05W2pxFEh(OUaUO8e8UfGWH9h=IFMo}g^ zN42b+#@1hu2zmV&FXX)!rYxPpmX1w_Tr@5f_~CJZqABe7xE(OI^&)RM%6}2okL7vZ zvMH=M590njy<`eIk>@))g)N^jpkfNEp19nFq*arAg;V&>$v!eLSx3?nlXavzIhhg^ zPAS2-ESaWPOk<_fbY!@Bn*RJWzI7UTE+IGh?{w(|KH?oOEhOd&Ai)?K541K+aRT;yH;?XNSe4_`2cG~}|}z!cCQowu8QDG50O^vI_1i^kO#fo$%mB-k}$J zalpY=7jgdT9;P&j8%w!wuXD3w<&nc^WbELno8ypipdyZ))V!5(tjg5^C*hWReE7X& ziPwi;MOJuyJL1?5ZxFw#ER9Lr3nb7_~dr3CHMMg6m*_Hd_p14eh{dQSV86WqJQ%?dT~Q(=@P9#bhz zryZ(2tVkCq*-7I~#3nCL&iM?KV=LFuH+|G~Sdg#0EOBpY!EBpSo9v=P2gllQi%m>Hj^Osoudn9p#*%&%xZjn9q;Q_;l(2 zrT0&1Lmt!8caZb+3iKxahyURaPu`ee8W<2L;A3$I7h+}OY&qB0a9$MIvZqV`oi*{_ zNOPJe^~)^P+2SG$u;qFp#8N#`6q?3YGkLRnQKKEWCH`pE!8lD|{qWrAE#qu7`fY5H zs6X&PCYI;1`a-cx&&NaoENQro9p8LZ9{YL{i^UA`C%XS=O>V}M()F=Cqvs#&7pTtk z4R1O39_GA)qe92IeuCrY82WOJ7e>yse|;SOCwqxM8dI%!gZ0>8&~5Ln<{Xbiwcn@L z@`8TJI5vAmepv$6w8Y{BR-z^2JnzloDXmENE%&p{y6;FVJE8lkV_BKocf^Osv=SXN zZ5!7c2=tLsU5-+XmE%x&gpRdY?M-hx2RvGZ_4)C3U^%zc$(NA-p z?$d*g$5zZ8*YbJu6D#Ur(n~%WkHsXgJ02&W2am*Ix;cuO@}QowJeHl*eJ5bv?W?NG zD%@*ec!xI;hotZK21{evaXgyF@||_OYhrm-9hyRq#{`RGS#e!&Q7kX1OK*So#(59N z@q=;uQNVDaFa{I*1vX=>;+`z!`c{r($*?&N;V*B+L#9h55NkrT=SM_yf|_w z{6RWwZMX9Qf#Np!&3I88w$Qu04L#A~kl}L8d$={~>aA|g@vwTbId+J?lg(JAs}l7u zG`uI8;aqIri4^v{LC8t3_jn51SjPuv_pNmZIZ@YptSKw^`HnTgb08tdZKP0)d3E?&&( zX|U9-m$@+t^$IsHcSp7crD=sHixkFEyqP>T8IvI1cMQf{Gdz-sa&=}XV$T3<4)!hA zDUU)Ob6?9fI-V4KOLclY*{I_sg%8L{7iJzRd+89~dyaRxf#o8A_chplZFJ){_Tf!R zg%-f;j7lvV1$Ox=@tVX%KiMjF`%3Zd!|;|Fyu^Bk0Yma1%JFCWxH@@(gPhHoFH(RX zz&%3uiLaVta>SDw)wzC8-${)Rpb7IB_u(zYmV?T z40ybtSuX2`d3SICuN&w1$}}`Y0N*~qB5t$wns2klE3^(yv!_dY@s8Pvl{(vume8@! z^kSacta;bye6Qv!)?s=04qD5+!^gmT& zDGwah_!>NXqB&hUrk)a)zTU-4U6H*?X|Pva&V7~9d(|`Hr+M8H?!(wzPx(_Dd0XP} z&2$VM$g#;@jK6+?Ic#(~v^Dfjt~cAakPU_rvT+7EMT|Lm)pdjiPU_fSW@ERgCF51s zUX8Yvr%QKe{26UP08R#Dsk(c$)T`MP2Aj$9jhDI*p3yV^DuqH1^Im^Er8?Nmg|AN1}o8b z!-(jo#-jtcxr_0L>ad=VHPIb_xYtdMe$?Xw<%DO3vK7;FEat{F)&@(g#VOwOh`>7h`azmV8iW&+9%QJM}~$2X)N8BK=a1$)_PZqWP*DVp2=o(GZVk<@|6%cEU)m zY{;rSr5Yl5pet&K2f8veOI2Op^9@<0FR;8JD~}B6ORPh!JrSsBf%0RrLz26YeB7T*(lYE*O8b~ zFte@Ui!q~UK8U4Skn+KPctBve#>UbP<|Lk=X_tXgS-L=q7oOJ(%kfGbZ@Q5He1D3U zmN9JlFu5)y9`#|3e#J8Z!|XShp68bG4D92#(%XY-ENz^2wuKr$5&i7(*VZyoxU<38 z7C74iXItQG3!H6%vn_D81*%qj!1&&GohV+rvzPdnOE9CWyVC~M}gPvv?SMjCGBICtT@wHL$4N>teQSsMg9LKkb zf0x{BUGcq&__wvYl`~w*#lMPfmd_4;Rv`W@jK@28{A(ma{N7Ps&ym+MsmIqT;-6Pu z|8?s0WhCO=r}$@Cg`e~gD{fd9wqF(`M#k65^3|1bdS^@jtheECl4)v{N4)F?p5Ica z#os3*$AKL`7EO? zNxeU)9-}m2E=hRa7yl0Sv+@m8TW=t4h@`REeJy=;6U$<>eu2~wdm8(Erqbt=^@{UP;`n$E)<7t`ipYhtN`kuj#%D>xROZkJ z>@V^zl03Gz_Ij%FP5q0!OC>K|*?X^cyNmxK?-t3ckai09)o!mu*?Zs87s#tBzq-CC z`wc(;QqX^NJ(HEIhg;)Zy}wtP6vRc&QwsmDUv|Co|vU~q=`($4jX@9Kbr~HTgG9xPABT?}`D}N3B-~Z3_ z%Reu#{eG#O6xnVy$}55V$$yP^rt~%Nev$V}p|oH57xT%?{^RjbBflshFeS1+RZ}D5 zQS|>fdZznj*8;0w%A#_pq@TzBg@5UHMe?@FcJb!a-aZ8-k$ja!isDE0OZL4MzfxWm z|4i3(Wk(Xy`_x{JGo_ElD_;LUbHAitYxN8Lq|5m){e#-u&&m03$SJa4CdhIXd}x&; zaNw_%r?T&V)(_EjO8GDM%h~5%xsLun`rI2mo}%MlkG1NraOF>-;{VBYq$9C<5A*L{ zyU6EzW%9pO&it{p-{%Eqz*Tw9bXE4MW%}ZAmi@vBk@>8eC)cMu3m*_=P`&>sxY*L) z5T#e|KZfVmu8*SEh^~|ETkse6DK!j40kKzE^~s)Qm8V~nUezaG>d#c4%DMkueah~$ z(nV#<)aP%r(nsqb zmHl*Vd+qv7*I4!|>6hF17oA?Ud)ceC>(w|ae64nUbh|{y6YjF|FL={RAFWsMt+F1K zZ~rkbOY#C$f6Qw(*~+(K&mZ%Gi!5H@yMN4kLFQZb-XHU}tN!>CUJIFT_P#&1w@cc~ zfB%npsvZCAs`|T1?q8zEgX-^!gI0dg`aiS(-`3N5abDlPSt+R(OuF*Y`B$cN@0igs zJ+0G~BG&1;&gmV~Gdgx|YvFA2oJ%g9p0Z%-&po)LJ9Tlk_iqlJn0pO`U5W2o3Cq_LRf!p2TK{pGyrx^K&O(J9(Gv?#Eg5>F5 z=9vqj?t41ZZ}iY_%;(_an&Y_d$mQ#)GkOvayzI0>1!b>xaZz0pumgoL# zLq~O2ko>>^qY>n1NM1YKxF7ONw20@yvBu+&=ac+!zCok84DVDukIXP00rofw>G@lM z@f+k=ti7H`7aH|(CtXaOjfF-N$imKJ%Z*l$yAbE`V&h!M=aRgs#JCXhK$4#i?FUac%-@elb02A%-N|n(ZGX42_ z&(8fuH^}dj{Cc%94D!b$?>=JO4!H~bQax`TGd4iJh2*zR#Jmcby3JF?c+6Xf(9-GI zY z{Y)M+2$2;O*`Lj0@(>Y~`d|Q$nTm+W^uysi=28_oFqX$$sUipSdCYYx^3e<)Q=}pv z7x0)8L`2sgTF7J8BJv>R^JyWEp$-$8!^?ThbBL6a=JR6CJbqO3PSo37P}d!F&lTe> z4Ve2$+1sHyCXopCrYN%*aymQm@fh$u|Xz!H^r!kX{yK9uI_c0PY<)Sj$-~=4p=jO;C9X z^){sHiNGq1DEkydnSTJng_OQr3s7lw_j)Z}d<_|Y3E=DF=OW}xrz9e?hl%{5el^m0 zmLhnC6tfcCDcsY`_y?4|F|<5=nDM5P`+AKJl-w_1e6Hl&pz%*7_fIkCycu!lotJ9F zYqA*zq#KQuJTTK}tK{>ujjoWzpc^#6$W{2@;l?n?q6|aE8sn5aG~bx4e@`Ng*g_0-kH##f%;%XyX$(I~4hAVl}F@yHb!p`Iq zF;^*h3ga=iA|fg?&C6r%R+<^O`~R*YGlRHw&POG;qw(FZ=rqGPMmBXiIv1cD1$V!y zUsh9Z4QkJ7XnGOpHGK_{?2*sv=???&R3N}|fenq-54)U#p&(AapAd6;MkZs%m zS=hO10P}PQ;X7pL-l@~;;kZetqpZYe#ACp9zpjrXmAFqtKqQz2m`VCw`qiYjE9r6= zxd)o5M0#6)Ad)1SQ-2De=S2ixgXFmm)0O8MV>4vY8jG0mB4knW#a?3<Aa0Lw=mu+XZEwAQq!oEG+H=dSi%jsR(5CL?NNlZxemqiCFIotMvVh`vZL_ zEo9>mJc_udsIEKUxy6_Q`6^PZV8(LDJ!l15iA})`0BK|H>89Td(a{>Eh`Ok8nEoK8 z+=$>Y=4Rez=zDLX(P*V#^qDt_8SY=*V!80v_Zp$MU1A~fHV7CukLQ*g3>x$pN#?xg zq!{i&h9x&@X?!%6Gn#$9$*IN>;N55%Z=7yyQgV|_V`Eddg*VMMCa#wGrVL;@wT7oZ zQrtszF!ezYtr_1%5G+I7h;zH?no_5mF&!LeKe&>my8fW?BdSXcS2vKtJYPd`H~|r_{yjuT z+gWWJgH6CwM6RRzAv!upw6aB_dVhwG`;Zv$zmr%k#1!00?oT|!k+d_3pXnEn6_IuY z`c~ZASpNaiYf$&6`jwG-yDzc+LoNGw$)kwhD zrDo(q(hZsmXqfY%nMPB{w0Y#ivW>QopP;nE2N>r;rp+lIG29plnU+*Oa;z~PGHvkq zsC>-PL^Ch|@7({F4esnTCSKuaK!4JRPHBBM6BU)1QIl z*@mDSY#Fg`H(dj~r_l*l8oIm}GX^x{VhnI>wUaJ^q6nYZUA#U$xg5j8i0c$Aum-MJ zv<_jx$3Sp5oQ~`f}ve6tIAx}y%Xl4@f zz6O zJ(YaLSmQh;FUU7WDfy}yM!u34V$%cpU9x%YLSyxZ)(q^wzR)NKF3PiHx$&&x-&kzC z0hxxPe`$&FvXWPn8G9AKsNDEU@mEzCCn3|#;D2PRVZ>QCv;S|EMiOLUf5T3rD`Zjr zN2`p1O5V8NIJQZ*@W-o-3BY3#VQ143V-IW!`N?C(eBddBZ$1(8735b*ekPU2B%;x1 zXY1dBCzj?avK3D(oe|kjRelXmEIkpKjgSA0;n>{vhvcE2{}ltl2$yp4gT`ldlM{ShQ*=t;;Xyg>%qpo{-d`tWGk8i~cTJorr@vQ?!nJotmTJz~hc<2FhAVjU5J_4vG55a~vbY>*E-E^(2 zH{E`LQExgkR!IBxrU#8Rwwz+zZ_BC1Cdkyv^`@sATOn^puhg5KVQjbMZpHzdlWBZu z%RP->Z8_WUp=_3&envxE9$=)}@?gWX<>5vjTOMtUw&k(LCAOSrTnd@mw%+u7V~H)# zFxJ>|fl+453k_;Ni(hDLw&mra4fUrlo%gCrhQqx>177Z%vSl!jb9zAoBiEAu{wh+At!qc3?MKs<3aP6X!l=$|6$`4+)y#PNE@orP;=g5Ms12?1tw z1}27me8A`qSq%GxppgTa3Z76e#TW=#4Ew}XV`6jwHm1WsBe8Lq2~kV)vCg>cpCDpNLz190P`6B8UqW~d(3!1F&<~e zM##?-W0TkDfTj>~MS$ts0QzY5)OSJh>_cE6<{y5}FG!*dfE?HIMvMs8QK*fwHS6`My%gN6oLxKG(Ug_&FxaTEVM1q;0;k|Fc+x1mBX+gP{10Ffv%yjqs@hw z)ZNy(#EvF-10`r z);V9$r-5L#qlj93nvk^vAT>%BsHk1TF90MZ5zz1lh>7teY77%-!}fw^mAD> mf) zX=ZTIW!`LtpU(v8mXSKRKW#^1T`+wQ$EOkC7}9Nx7ihweOF4V6oJ|*rfme;B!e1FRD(5q z7C_=UVl>%FI@8Kbdl!+UM&XJ*iy!{GUQ_|oZ$t{6l4*yCnL=?{=x+cto@Uue`UR07 zW(XRpl&u)5C+QS{2K1MVe4_t4gAlw$6w_++^9b--qeLJ{zXR!ld4lZpLqcI^6P>1@ z4@9)NyD~P>*J2wpSQ^0CMn2X;Ew`~PeAzA3dLD~Is#~Z9J+_r^cnh^c$F}y3ZK1XU zv2A?$E!0{co9dg&|TIvDX_sNEwrW(`Kb(M>9*eG6{OW`Y(OFzpwp>bIcw5rx35XJAgR zcW+7~Ai~ZWgGf`NoM#TAilozaPNS!V#xL3`7R&_T=@6cQS(EWV66=L;P$97<(+EzC z%8s?14|owit(M4Hr{^a+Yu#0|VhvY96*sL6Rcl4tOFeE#>-zz*)|(J=mh>_%pWs9H zB9%(qi&dbr2Ja#C5teiUgdi3pB2iZe(!T`hS0WMCBol--vDQ1JCjAjf{M_ouCV7a& z6}YGnEO;3r!S}3o?g7B!XiES$YfocH0=EP3wznI~H4~?&SjKgFkJsd3(oYsJ3qFHL z>Lc8?CvCh8xIqhniV+m-(ad1MyM#6zu;4!Mf<>C0oCUulgA;3%GWj)~r9NQu95yr! zi&g4|NEK^RA82B_gV&@zAwCD9-Q3X48Z{5slx#4q2Y79>ZIlJi2M`=!)sbKp%m>nL zzlGdLO-Vh>k}d^Ygb(!=A)>d|(cv}?$`Seq(>8+8yq+j7C1u)61T+w4L;-?T08)L9 zM$rxdX?%&e|7hK0!S9JOJG$9}rvV2;;VKG=1p`a#+nHrSqwbO zgiulc;Z7X@UHfydY@&vVehtL9aI3E&jabx0C3Mpsm^yq zqPT5-1o0PqT3s7%K*is;$h+ffD)?1RLTyd624j8AU9 ztNxx0JO|8mGa={zU7r)10@l`@4^zD3elE26aC)zQq9;xt0_y)A0=;+b_#wwudI0V{ z-YKgcJ)&ojTtE9!&d!A-iqRK>hY(89DGLb>wFIe4f-p>l^iXMcrE%7!IkX9BWNuk~ z`V&q%D4kU;oQ4YUOq6E&?p=K8e{NrVj2(epd$kgZ@62TJ*s3k-l z>?WZc%BNF;W%ZkYCYodtsvyi!g9T?=+Ek^T9@e&Xk1B-rT>Nnq)dl|Vr25=c?%(|? zM#55Lj&FS1yZ>=BxY-Tcx>w%`fkwvaJjNnN#=3mx$mscmm3Qw&vSgzlca&_)i=-_I z4}-5&yA`3_H-17|XIJh?Ty>K{C5X?;rD+NoU(XOYNpLpQJ}9o^0% zGeYFJ>EIrc%$c|20%J20(xljNA#3tHl1~>S0|d`wvRK|^{j*b8F;+o+|I&y0Z&^;79wJ<@^J3+EP|DL zm&=h>qfcoOS@6-x^GzDtW zpie()h1w!`PB*Vdo;P>+QHsCe1UN*V2@b zCQs|S0oS>t*`fusuHNf7TSl>GwV>uNhlK#?w|p?V?;3g|&tL+{of`o!Dnv2S?YWmm zz}_YJQ)i0+Ulsx154iIUfahscQmfF+><#EWf-l#o?6QEFp8`5U&2gow9u?n30n5DV zMyXunRI<#vOF7$!Pwo;YZY45zKryBfDsjJ6ECEa1BzUpBLApn3>KJ-*4L-S>w0pw^ z^nZYUpk*(2f>xh;buB1Dc!Gr9Z5ewRf*2FKAh68rE8Oe{d~%C5F5qs61cWpfzkUkT z-}{!EEr4Y8rl=`)97E9vfl)`hzkobglj{%o*r*@UMpGwdiO7#4;u=SYht{Irg|TeZ z_x8jL6Phq_efPIhVWP)l=*SLWkNS*ho;OXa7Nc(LF%n&NJr?&-N4%Pq&uwYl!ui}Q zBCZ}HpN8GAc7Q+XhBgJbbWBFF2eV*4Ef;!6%X&)tGj=(tm$uofn17FCvNq;o&K`wJ z;i!sXNN!~m?(R1CEA_LHYF3}hL9<$$C1|%(_>6jkTCui9wF^euxN}exK5B0FBh(_I zspeHMm-E$wH73~@8)Rq(AP<0dR_FNMf>voC~cTiE} z*Ci>I@zF_5zDbN_qZ_1MMfRK#amTWjPobk|(2owLEv9^zP(ZscYcqBnDzVm|g3z-0 zm2Nfj z!-}X833i)3fx|E&6HNHy1P|a>LXim?VPuLNmZ=;_uydH67oA{;NehekD8~M3QEbS#q`(#+_sq->p7xal`ojUgl;QdMlK538hbKkuH?V?P9e_CsmkaO(jz{FG`xz6v8F zDFy58c)Sf)F?;o08a?n*+U)L=<7{~`5&@^yV!g-Ba7aNTJ0^qKZ6$zoqptr;O?m@77E zVk@>^^Q&!M?x&8;+xr^kQ$7bZ%bn&*nmyZUi`5bx{mIB|>D8R| zKY{e@oTCVPZ-mX3c&N|q;>Y4{E^mbVv-O=T&vB* z;ys|xSf5B^6|wiju(9+s`)QQOB{HLk+7IB4y4gSJDs&Gy~*t-5T{YUaSHCC{*GG-2y@M?#q;l z4V(#Q&O7i)>&wqCbm6NM{5yybpL?ja!A7;gjk-%4RFUju;%43@ZstKDc$tbDdY8DN z2VaRecyxmed8~<-oj(xi-Vz)4A)g>VlHzZQ_|Wz6EiIBcQGUQ14EqNRY=UC=Em7K> zyL%7&j&dW9R3;MR&#^+pOF(>b-`0G?rXvSCu~SQln?Y$M9-&hLl9ndW80Z1I}_!Js0kTYq_Zals*-eVmeE?*pv(Y%srp^ivLue@_si%o?~ zY$8He0NsjD1e*RD5c;kwXEnFJ-b#;MiD80I7@3NglVcf7-xx)d`TPhtI(N%-D66Pu z5oE4Qpo++Yiq6vC0PHM`G*oX@ZFxL~{!gC>qpA?;R4So4%1ydaVd0!nXSa_+V|)I!$)r57+c_c+myfYK9rPT6a=1;-?AkFT6r zq14rq`dAc|g)WDRp2>5z>=9O|pbjgcmy~`-lpeqODwauiM_Co=S!kTnzaOP%p+}(l z=nI|YoZe@botfV&)Wr|jg<+ZIZJ1c*!ezDrhJRG~GH+1Iu1+P(+^z7T3SW?CzgWt; zU0TdjO7R+k7%X!Qlznhhs)*%Zwzl*wzd5$5>!j}v=*P7?yA{axop@KoZ$2|1S z!#8a(Y!{jS*4$zYbJ(zki8)T`MmSPS-9t(@DmtAce5(i-L?@O669rgKg&3=S?I?XZ zX39eZFExKujPV+|YH^oU`g&MT4in=>^OjU;BhO(&+CQLl6CJ6gu0vayEF4Dg<#FgfSKE(S28nK$ujuc zbM^uyzB8JDk*0KaMeAhZM?k3C6^ZYOCNT3yrMov;XC)q+gGHwlpPZZI69IjXHSRgw z6mmi}X8_oZPtHzZLKB;civU>j#N0>GMw#Z-Zgw|5ISZtjFkxR6?EudiiZ4t%xG%%R z%d^tQl=lb5LqCnc6Vgb$f1OG#$)XGp@~ z`L+e?Cik>}nRzq8st&DItS|1h%}CZQur-HRpM;8WsV4E{9J>NySh(gP&bl<6#aPK@ z(4SgFdQWF$unSn${Lsfrby}!|Z7Tz_^=$m44WBH=3n`gH=P_a71nCx<-Z_%S9W*w6 z5a8ALWN8*W{!T0s{yzlyXL#*5QSK-q7 z??Q@1nqOCQvmLGrNWPC(h3o0R50ur{0ltT4K8)*WlGkGIP6NsH9t9sFU}pX6@smaT zE;H*@ekh#YTnm^NBF#>I*oIwSQ4)W7GsfbULiZv!8{xW>lE3cYG4o=;2MK;70$vAr z0l~W>;4c6#B6xQM-1a8SG5BP?$>(6Zs7Cu1K)(|F7N6&U`z&MZW_+^V<_m0CP7S-1 zu8J=T>)JqM-KJpQl=UtiK}5@lmD9rZN{n@zOcXnMkx22rY)bM}VJQOI?|>{%QL&+; zZJ+1d!PYm-S);L4dwB#JH>2&C-$o)W4^_3ro1k`BUf;2{Y7@m)ttk-la>)45i537M zmxzon9BBGBAoPrx@dHnrfz;OUN!PJ25b#L{EQi(r=xE=N(NNAuBAwWBnrndXC0!T( z^My3lh3;}Hmi=6w(Z_7q0sD(i$Tf%Ge4e5)KfR=%oQBlBxp}*y^y7aQ6j3*SRtkP> zOO!r5^D10lA-O+BCuPLUeTZIY0vgDd0C22kE>Q@-F&5uSbOgcR=H0jo@*pQ!@XSL> zH$>_zxOE8i>w@IN`7&WY0DIOlLj;*gU4Vgfu)N&tkE=*AlCKPxD2jYLkz=^|q#}=Y znh%pr{6f;QHbz===*C0GGht|wvpUq-%q&&9$qpSG|B-^HSg_foGv0!djj0Zv?Du@7 zo9585@ee9^x&>!`3ZNCW(M;JbR;!rpfYCEu#w_Q!p$af_3Gh9no9)z5*+pV$;bX;` z<77FSAT0xXDtt2LIta|X8W26nWn3BozXFJ!(K0TJfRg~tBKS(Va?{9j6{~=G)IK<4 zp!st*tQ9og7CE`1M3jJ;`A|MigvDndJPYM%B3$bvScwhv#9-=;>uTyo0l%Acg$^Av z9{}_@!Am0G?*WCn177N=s%+IP;Mb6DSxwzdz+WTXZ9IJt-Kf@GI2LzdViw@#+-!mC zT#_sJy{NLJn2!UZ%}mA+C#!m@`|zcoo|w3`cEg_EMqI58ot}jLx7w0gpp?> z;MRa>>yz1u}|=a!`b+^qYS=mz(>*OxC+W|e5as@>CZoF9AoiB`G%WoaXn13u6^UM z@*1qP%K`iyH*;_m6pt1+#O@6Ld{_w)hU$| z(T!+H<^Wu7CGqwe*31&6yQhW;^AL2Y80y`3MW>U+>;k1Ayc3;R60QZ|1+viJbt<|Z zkD?wo;-2UpXP#8FA+A;M~=0+-J|_OtF6xdscG*ydT?_B5;&p)b3~ zn{HeLZIbJXXlut|?Pj7Sn0Mf^pTvc(wUO4W!h2qV$p=yD?yb!rE`qznwJXx3dya6YL>*Mbe zNQFRN5%PyZK8CPbi~k817S9EB4;;jK{MQJtM|s_Mwnaa8ZljI4V-$mAo@j%Ie0;gu zIm_}DP8*FDW#*7neASIFS3BoMzz+d#{gIn>9uxup0Qg7?+?W?cz6y+5Z_+AN1@Gl=jLPjUr0?D`uQBZ zQfq|#v*}jlY26}QFf-(d5MOG`L^enUnD$)86)KGl|m9Y9`4ON#WvhAM_t61n-prYxwJJHvG zik9E)MB`CA(eV2mXy!#g#W;z_Lw_#aDw&%BiNTj(L#;6uuc7f+&xV#E`UOFWHgpQn zVYu5nC)v&*ZRkNn#f{m}hQ0?R?(B1Hs4wnOaaT98 zp}PTzTQ}K;{s~Cjwv823bGVVi+YXE`9%|fXLlDbcLu?|`=$nPKY6Ps!w+c+Bmz!zd z3$Qa-HxjdpU|Qf^06rzKn}c}_0C@<6di)Yjo{bF2K_GOl1H1tsxq*iIgh9K!O!&io zP#+E-&CWU09y9C39T0p#LDP;1mWCLcK)*BXo{qV;>&3ivM+j8Ack!&pyN#W=7~A28 z@#%IcJqU{52R=s8DHET>B_7|3bem5T^~8gS#vxI+Ylt|p3B>a#dIS0UOdJOBDvI7L zqSrwj|B0VagNLCFIvjYJfJYLa<=wS8n==Agq(D9_BUX;0Dg zL3%6LO3^a~DDPXn5lqiUaFl|ZauD!72!`}U@Gb>|`XR{4MX-Z{By9Wg?xNsw?62~U zQ?Ly?l)PTpf8@PEL4WKU@~SDAI2^%!BN5EPLYDU>R*k$tV-WmEK^}S_ukARBQt;Av z1S>B>Ff|W>IRU|}i3lFL7{P%_2;P{2;GfeFTsj@W=otv!r{J5J2&TDA?hBKj{Gl^zuW`$=Jx(y_W)22LvNO=QLV0y)r|z-*Vc8h~Zo zC3F@)4o_c{p=*ucH$ourZ%bbAdFL?&bZmLXB4$NEwoTh>76uE=A zm*DZQ1Ez@}yO{-N{tkegS+bj}^idVcyZ~By#hKma3=DG>804&zogrLld78+}+^*oR z!j)AvseOxzP0SZqgBq9m>)g$}l4|8ug)$@AnY> zW>qrj2eQ)gLrzG{)fo(O8KvvG$#KoR_TyAW$^{b;h!cxwPXMx_f)2TC_$pFAh}7ErpA`b^mZ z7Ecpg`wM|ST|!-(SiiFCGh>@gaCAZF0j0kzO3y+DDk8e?swkD!mZ8g){<nM8X zE}r%(@^n${S!V$~;D9VE7XD~7?o>XjS$1|&J6QbZEQoa$9in12`-52zc757MJlI*! zY2xt?AZ$GPZOx;Nh~SSOJ{kt z^3q|K(ClFmMmM*;be4arymXp52seQsy>zZVth{vgIkMP>ETosttk0E~&SYWX0F})1 z3@k`5ouOYUFP)_h!Y){lUOMLwE) zX3|UNYX{*&5Tut*lW&xl&i4+&ArPdOPNSpBOXs+Qa2N#Xr4#&CdFlLO6I`bthQH~8 zm(Ggsl$VZI3~Xv|ixoQgz4FqDjZ%4jL^k*33oo4&KUiyK)=Fz8pw@IH&=?E-09Ajq zU{>YsN#VX!-%h|wC;y+yOUFS7y$19XO19mJcKs1M37E-x*@>0`wY+qksPDM)(rI9q z9OpvO24^xXOb=ZHg5{;-Af$f>Gy%IR^3oB5B7NMy!d^N83GD)6dFdoOOn-^NBfWHD zPlUa6tR&X~vAlHNMefqH=XW%r^wP=sMH1dUE(q3`cVm*1UOLzQDhY?rLGdgL)~)UF zVBwKoI_Lc+Szlxemgq{F<(Q`hY)LPj+fFJko%VJGM2AZ+oe94yFP(JKJH2#XQ>xQK zB}!lw!|Z%Yy5BI~m6ADhPA{E%6pcG*Z2W1!(o09A9zX50?WJP@Zvv2BIu?+@Fppzr z3oji3nD+sYUOHKJ#h5vl<5%a{{K8A8w*$`Axbo5o4_jtFrQkTZu8GksHVUF4P5k~U z(o07)az9vR=Izi$c?p^Na+ap;ag7vZJj&`or6<)xE?Q6LAF88W!? z(xDxUoI=fq6`by<8Z*!F;Oq?_+9!h#3*V&X4S=PW&QQ^8VknzmE4VwSTU^;5<>kst zr7`@A&jF6`(y`#Cb-D7=8SAip2(a|haaL!j zk4JjxSVlGjj_}g4;6|}L(o4sJivUM>=~%EUjz@awSnwji5nehLdCE+W<)!18)69vtpd!)6(s!nb$!n zy>#Y;)0@MRFuV$pW+$I#!>$FCB*IIlXML``bizDlt^+K+bewQZ0~FTs(s9BCfTfp? z6W#|{dg&~(%fQUP1-bIlDRjUK8sZBBJoCa!=O!C=SyMybbEK|{uL$d+ymUm%h?O(! zr6X>;u$PXA+Fm*$0lnV{d+FGad`Yhk8N&YTt&h=xaLwt5Wf1$b8#YF|=5)hwVxez< zI$d)t^n%ACU2_DQ{t{5-nv+d~QB0BPtsW1%=Gd?tPestta|2v+tZ7#eaw%)`2k4}0 zPFJjrJWc4%C!M_$hilGLn{3yd=Cc)z`LmEjx#rBTkd%HrS5QQG{cbGM$~EV)CmgOh zlo2zVJZZb;j050U!d#*d5w1Ba6nPMLkOj~Dm(mT9It#w|Dd`$BoKF&0*keN7L zbE;K}k$iHvL{Vhrnlo&(G(XyDK1?>>R)jIqnnTy?X|!Y}ZLplxv6j4tly0&^$Hvp& z@)Aj=Sg<(@fOO4qG>K*7ZKazQVWZ0ynPj>JXWk9KcFhU*zxg|G>6+shH&g*;&faRf z<~Vd>CUeyAW5t@|9C;4H@Mmq;oUj>YZUHP^bDVIK=WN#;Cww#D2-h4Md9E2Mh;Yq0 z4Q_;Mj^K(CQ37Tz{6~~)PBh^w5F%W2?A(|+^7$y&9Ea{7&_%fBkdB$nUx;$evEU-W z(lsYsRco}G-$N%|b86^DzG%DV?7{{N-^Nfb{ua0km21ukP^4?lOBXa+GV1 z1|*KOCFFprIYPQgA+z-G!D=(@hJ z-A*eGH?O$Sty$)45Tt8PuX$8?t7dahCgqy5VVCWiLk{k0P~Hi9$~EV*-453rVIlM} zAj>spgKallo3MoUddN$<=9IrF6PEf40{2X7?)FHK$es=0-(`SoTPn{c8PW(x*i))59yloIcU-~C)%1h^nIzj zr-li0D|FH|Cn}vRX3PDyYfe=Dl5iUc(lzIv`BD9`2KA7xIio+2v>~oaL38xS7#%bAqQFCZ%gm z!9m+KXIi95X?H8^O4pp8AK9)sQFfVGrgUpvQFfT=#wJ_3=F~_xQ|Vr)kuL0-Bg!u} z#9`MQF$vkOIf7yB`ju;r4MpwxJz>`zIIJ|s-d;G;99%$80Or08QI0enP=96){d<%n zjRn67IKq*}f-@hDa-^}~#{fq-(g?Wbn`LsOS%7i~N17BYhA3CVhiyli<|q+QYlBd9 zk=0KTjx?)4j!(gDJb~9rHsc#^p+z{l%9oRN|hr` z4b@dpS&lR{REMDwZU1~&#X=+QSB^AJ^hKbSBaIVn|A2C&aiEzcKy62w#&oM>)?Mpx zq_LotfUcqONRBiXq?I`wX)Nd_K*O4WMUFHU^a~){k;a0qc@R(b*e(l48VfoG$abW$ zpvxa}IMP_qXMk)+8Vee~&f!R7L3;q%jx-jOi(zCt(g>*La3fcfk4tEjHE#3!oyw7h zw*P6rB4BN%+$F(udjFVKhnlL*Zh)2}jbK_}_T9>n#=+bK(BVj9F%yxY!;!`UuLkIF zq!FN9UUtrCyeY^_u0ZfH1yk`rV)d zoItSg7X)Aair~rL5a_=nsDpRgc^^~o8eRqGJ%_ijdDr6QYThk)3!10n#a!Oo2+lc- zS8REE@j@-H7hYZE#o|R(-p3Sd!E31wx(na5YkfQP_@+5LE?Z&%jAB}kCFFidkAG z=_^I+Yjtw}WY*tR=$qbJ;H?FQdf(9oW$&BH*~MQ>!Qr)y80(rue{fy=<9<4XHM9c9 z>}=y5^!>#e3*wxiCD$<;vcIg>#0#h{Z_z15JnhPJabOW0dFeQ3h%m=FLxQrc8Ip(3 z84}nv#52>70lm_~IYSPULKi+~Nbn0OFFRnKQ*A9DfG&=6hH4>-B#v{21Vt3t%tzjI zpWEjQtq?^j1x&6J_BlfW{-bk-ELRXZXUIBn=$$n5zUYwyBw>)eh=vQ|oS{P~v^;01 z_k%b-g3cM*`W>%v(hm!r23qr+q5j|FRcj&=+UE@23dDJ|4@=({#gXR>H9Zzdl;;f1 z0DOjXhMs^bx(M=|pD?95!IP#2$L7lvh40j3wt;+&zV@?|#uNh;}_AzR5ZXDXb|84|eT%%4}3 zlFk{j6S=I@f|~sd_mErAB6QABSSj8yWG+%lI%g=Xv{D{cN;+pKI?o{|q**#=$WF=3 zM}X4=f^&wf2}J1Tq5h6@h6rQfbA|-Pnv?8vh6J{Nc;*kv^M$jN_%?-HuUDRdFvjm|$XXstU7@|ER7}R_4Gg@b#Gt~MPO`S6o zwju3bu5=?Dsip1(r5okQTj(SqW`#6-L3CnC7z2VlXK3V&;nEjirj+Ll{j3<{wfTZ! zmHwISc*BL22Imajwo=;2)512S{m+$dq9e7`WfsYF`O)blVU;3GicTyEpMW6G8FCB` z(L;1k;kO{GB;i&qn&4m+fhErwiefSI1EssYRtwB*bE~G#8LE+ZzS7-whQ!-Jkmn55 zNF0wfMdV7RegYbiMdCm|GRhGH^9vs+uuRKDC7~%*aF^q>K7+9)0 zxThY)&I5i)2W}NRfa5P<<1rHNRORVG&2Zi`3-x`GOTVP{h-0HdsApK2?U(ce2-fLA zB{yLdNy6-QwqMfpN-j?ide%WG1wr~Hy|oQz&5pri%f(raEG8lg>6f%lcZ^A-v zQHD2RLHZ@V_p-FGE_oT1!6M9n1?iWxWCxdiN&OsI%mqREC3Sj*OTVOn4#MRiNWY}d zK(I~^8tNci1%mWTy7N^oPY)X9AS?z!`Xvp0jmy)6#ySW~K#+b(o}E~>Cct-S+ytB8 znglVtBZ6O&`8t=U2hE9Mg{Hs3<>^85qEwz@WOHA>@Jo7Xmo=?st(4;qT-O51CiDwb z{V%}~sHDRUR9`y$lFr+WgJ8w!K@LJ_70^#8*>)%TAyCUN$%(dn6Myz$61Y2@=w(2y z(}Nb-C1;*0JV8spq`q%)>6hdnq~8Tp`6Y=yPp<}|P7e}DsMFhA`Xv=QOowP=It|4r zNdKye+ouOvNxJXBU?An&vzLd5(^@p4^h?^R2=5jNf^}02flcX`wCWvc;qa5T1#9B+ zY=9Z*msIav$@*fyZAP+Y!6auJ=EDG_U(y41#hBS;zwMW_&H=v$Se_mf9=6O({6NBSYL9?4 zj=GqWK!`X!i2BM^j)0j@Ko{YcQz< z=P7g90oyN$o?hf_XC6>+x}$2$3>~!nlD-s^9c94G1%Rbr(vtv`?H3f>ozpF@Y`Z_Q z{gU=LN^+xuv-uVW+xxNYm-M^?UJh8E9<l4)z^@rC(B&1Frjt?U(eP1HK5b^h^5C0UrY_PY*iefN%cP_DeeKfHOX`{gSRO z3QvmO2Qjv40ImVzbylG?0NnKFL^WTO0%T6|&qC4CjHr#~4K<(E|WrNb|Y=0w+b6#R&Q znFpbien}_7>CKr(u$w4EgY4wL+ptTc%}9h_Qo>iZUs9OI%&~x_Uy>7k0I>8+a>Abh zmVQZ2IQ47HG1wyD^dJv1R-^rC!1DAUp99YR#`a5!w_!OoysmUryna|0<(DK{My#A+ zza+7Og#D64)b>jf2_pTHY)F1Xp*C~apS^?)8Tln0#4?CCG;8n0Vd~iPs3U{c(#x69 zmq49Oi)R92~O}`qb@=Mx))Yejv{-T0$WRMNZWkN5tHVg1evZh@@c$~5} z2S6wNlHSD2U77eP(%FyL@Jo6XG%EmW*NG6$L!Db!+>6cW)Mw!x0i?H#Tf~Q+>X6to4?3X0Q1{D&%N5G|D zl4IOhx~5gK!ZD^2ngD85{`+So$S7;V%KpBZHi9=wa+{ zy5go%M+VWzbL~+& z$f0`?x(L4{(lJy28;?9P$byFemVQa$s#>GfTn(M{ORAyU1D!lFX!0F&qY88WEZl|4 zFX`fPOt4v~Km|X5B1nq)DPVbIP_+ZTVuOUA6i4mU2f@@M2BX`BZKCx zu`PL0@3;MuGB)x^za*>quL2z5mt?`u0gmuXvf$HzrC-wia5nz0Q5;`33JkxbWq5BY zj|}=vP{j1-{}oLdPZani8IN;yWKfek?ZW!Mhn03Ypy0@$Rf^)#asVq-J=qn=lWlay$QTc)%!ob_SyT~gXEI#RgxsRk>es+=W;@Z6rqbG?v>*z zM3jigSQ=27ny6F=DQWmrD3vA}m2Whc29?r0NTuKVdDgJk+2?xw|M&H}dw4(3de*r2 zUhii=dmWy@PzQyo;gLvGfn3KWHGa&~O9oYzlPI2G&PxJ4T6y}~k8Amc zO4G}skn1IbDm5S0CgOl&@@IrX5Cq2rRqLrupeMXkxFjqHvb6EeQR zGjU0gbh?=57=?GDiM7I=P|$HnEfLR<)gLWU4;`0OZ=+W0=?`EvryfV39y%^*In?x$ zLDQqw+QFKROKP}Ds}1$STe}SmPPFdnZhJn$0g;Yn_^_oTdb8v%M;77qVkXKe*62tZ<8SNLy6qhs&<>0uar|#r(mE5AGH;6_*r>MDYrsYJndY{RyawOLEcleBJOn9W-@4 zP#c$YEnO<94*>DtqXm8xRI&gw;s!b{NkKOQ+Cva6@S~ug0rfr}5XB`asLMidY=UTk z9|f%dWaE+)^cNr-m!zP9i}Zy_3;ZbP0YEk`NkIYw#4hlop#FetT#|y;0J3pO4CM|t zic6Y`@kMb-SI@yi>1a&(k~IBKR#2-HZ8KmC@;@fWF<5ghVo^x*6xLK=1wggHkE8hr zKqoFqY5oq-iAz#o2}c;bAUG2eTPlG@9}yjSo{MPljzvTS%9XWy8z9(UX>GQ?FgDWckJ)g zRExt5z!}Qn2TY^3<6IX` zJph>3q?u=|M5>kg2^zd6&B8-y$R=oMUX$h?{#jA{Y8&Txfr0N;KeMVD_W$3SG){05 zhVEY!vi9lqG0_0)&z!u19xKlJGe^aWhh7)c>(6vsPS1#oDD0{a4n^WksO$A-NT%1H zc@+uV^=C#=5LIy#WZ|wq!>C<<#u|;RKNI5IblL0AM1-M6@%6}zhDMkB=x2C!ndvuw z!}Vu4F++SSIpq2?@hYeetv@qvCACfQ@7Kii`ZMiOFE4o})h_V|gnIp%!Lzl(e|=ct zJXUblpLrPy^nk(oGi6qTr>1%$e#*64p-NQ2S$~Gi`qTmV{V8M~U4O=kmCbPdnQVd1 zaT#)?_QLuzs=-(*LnRN_pNV3$;0$5T`ZIiLf85#5{%Gd16zxXq&n!YV7-F>k43+!; zbNv}!jE2^qSwAzz*PdB_<`~Ml_~={g`(;9jDRQquK84D>ZcKw-b z+!bQ|85WjM-R$}^1cmF*@L6tuP#DL#Xif^_xDT4-X504B`Lw*uXeWykp`gP! zX7!5cFpkR{g{Dx@VH{WWj_ELtD;$MlDCjVbE6$1OFpepXLTf1KFpi0(F&)M+!%--K zf)3-D)CVK3oWeL}TLpg(4#RPaFpi)4#&j6R;)qu9h;w5)jN^`oC~+pTSvrKnIR5Fc zuJpEZ)rC&2>EBJ+6km8A+A)LIV9%YrChSWmjAJJhR2YY&P~2faOowr}=)*u&7>A42 zJ3pqwI9zlNP!-0p+?E`xMn7%CI1WHzLj_9qvZK)A(t$A>#=(Q4#m7KQ7zZQ8rGsKR zjAON9dNBr%4&zu_9M)Kv zL$rl2ue27_m76Go86C#)mC@R>%$m_!+hI$Gahy6dro%X%v=!iCp~E=h6)_#g@ifWZ zFpkTN=sy;*ZIyxi1R@>A@jNASWNsKow_#e%^FlQ-@L|9@jDz8UM_m{*VH^sW2|$N& zC}1xD9mc_c?0ZqngmJuVD<))<;W4wk%xexD9}zQQ9O1APa)N{BGcm-lvZCma({~#-rR_JQc=4brQ10rLpWV4h7!_c=7~jck@&jhk~nK z7BgWSUpltm0Ib6}-0HL+he3S>jFfpQj6)f@A8=L}hl2AjkD29VR2YYXX93O%<52M5 zfV09l6g*)(di+XcIm}aG911=FST8Trah+}NM3sA?slqr$O^BH=4(FaGKL(r?#zFRU z7)OsQVrF@nBVb5%ilpINJLGn=lS!Y)1PV z(_%J^!-4Oa9y80!)UvR?HC#4B%Miv9$|7ML+%o*+48u71vJ1mF_|%4RaDwbG4hw0A zE=71#OfKeUzjQ{6B8+1>9)p;lO{x{k3gdW%$V~AUK;1A7h4wxomi5a|jJDVW)P!-o zjnwK<(Bg#J8b%n0h4o`%9%Mud5XPZyyR5L2vX;L>ro%WEKTm_0Wgn8vPP7rmvEfKe zD%3AO&3weDiTpc|#DsB7E6^%kycMj%<;{N-8JjSUX9{Cs7zbs9`%j&i3FFuczQ;yD2134QWEGA~3~YLgPBKivay|eZ#^E%H zvhk;pU6f^`yq-=nT*0Xq0NCYa!v2>hAFG1s@yk!nxS3yTx3chG&vskRkC2hIBafM<`}Z9Fb+rdA7oi!93&HRM8jBi7>9!Y z53mm72wOlmTFD7`IG3OV*E-FhWp_iS!#JA$k1kX;m%klXp$X$Svk`8vDvZPD`>x8d z_K9i+gI|8C;=tb<_)%}Qy+H_>X&f_Q92bOFyL<((US7t9n-{714u1K`g>MC{!#G^{ zU%**m9J-}Wie-m!D0l~89ma9EEw>KiSlJ|I!Z=b-*w#q=xY>qr9NsjR9mb)IUJf`b zj6=ci1I`NLQ1Iy|$4nTkx0CYymS~xr&DyIZYNh#S~pP($aNS;oz^iO#!*>L zqWA_Quc*wZDE6~<9{`b$pL@(q=ym!Cqe!#FB6Ap5n^3N^gSExZZ^{mW04TWBw} zLd790JO%|F#xY_;R&(R~Oth~K*gTiWb#j9DPb+CX6F$O+IU6 zKjxT_$+j^Q#t})U@{mi7!b!16{#v10yO;^%Xt6O;4;m*rjAOh}%f!xOHK!glGISWn zr%=;j98qhsds@rx$T1MDqz>b_{&cN7(|;-3q}J^MyE=?xK&O}qwi`o(LL`<@E7)MUJ zxkmO(PP#CRgIj|q#9(373D8$^J!#LVKLkvJZS3|v4v0)s~ z@HC)pzIv}>!#EWDIN+=>4h5f7GnO63q2OhJv%)wS&UGA97{_3ggTpwc<6($$?W?N% z-3a4&3?=fCPnio_^;1?DM@6-m3FD|#S?+;?4&$g?;oQS?c2`HU6Y^EabQnh@F(P)V zYs0H@)7=l54&w;Z;VYrTV*{35$3B zn;pinBD)2P2Oi80aDE4Ez>9@G(IG`$w!$o%kRln2Zps90wJx=I% zn%2>!l6nb{4dYNyw*WKZ26$sa%gZR}IY4^|qA(5xb&bcuFb)N60%XHD6x2QsuNfL5 zA^lF1f}Q|0hamc$CIz)k=nIp=I27~{ARES^pvG17RZYLsq@ZPhY#4`v3NVap7zabS z!;Qi?uEO}DFpe7!m@p2a2Fbb9Dn)-7um$-alS>#J^0x`&U`++?1gOF|9L;Y3WQB1k z&2<2sFb)M4pcGCR2ZOe}qV52A3d$P67f`mBHcx_Vl-&RhQPv%E@v^m;DVJS|iEddZ zOl8YzViHI=Ag1aHH2 zSDk(|DxggrTCF9Z-+!yKmjrzJ8yyjrpa(bo7*=uPlUhML|7uuhgM${nmpBpT%I=K| z**o*eX;?OK4>oGWm_83RzTrxILWkFGm-u4zS+zu;vZ6ci`yLO5 zM17Lc=~BNw8EJI`-G;PV7sN!LOrs%?a|1r1Qc)rBAqvncYf!ZZx$^j- zcxtCcy8)kY81mfcRIgDRAX5n4>7epDAatSix!*NW@Dku^)uBAt^Qo$SiZ&&bYpO2r zepOHpKhO=@hTFH9?ip1jg~beJ)2pT{Xm>(fEXRMJW4uC=HOH|k7i;onI3n>xqn{w@ z*9e+_vf`JOD9#|og3F=ACJ$34E724MwN8wS3-I4(zFRTMPRNPCACTy_0dc2;E=0ta zkQ*W6&b!O)JeH}NzNkl+&sf1XE8?Q}N>x88wRacNb}D^Lc>yrimHB} zL5WSGeuvN$1;zL4`pwhzvsO^UCh?!H#;0T*wgsn-oPn%f2BYnVA)SBlK~IbW(&6=> zfnN|89o`I*@rSUw6sZUWZPyUpIegk^`~!_wgT5HVsXx|GOM=p0&Qibm(&0m-LV z8lWV!BtwU99JHVj(4W4qAvzpzauWqPU#@x!(mhvnTwVl2~oqD5G8U% z(;(_Zq8d4(MG%ogtV2PLXf;IS59?4bNAwItT#QDJh~EIDcS7_42=9PIt&@LGl=2KB?%2@1UUugwsa1{#hF55~vR8 zt|8SS+mJOka%n)xk^?Ah`dgsfA?G@1K~>Xv!=2nj!SR4u`C=DNmjLFLxFjei%UonG zTDliR+#%z0L=_NmhfK*4O@fF!WLA#oMu@mWZpabc2N4%zp(En)ncf5ucgS-AHKnS1 zAr(<~$m3{+1|0^*`3lK<6&><5T_NqD!5vZ_SC_*D@nk1pKB?#q$!Mq>;k42CXpM6T zRO+!BQlsSh8M;Fz#wl5{7o|V6+(f}=MtQyqr}qQqmRJ<;OP0CF zT(tDzs3>>Hk{nSIBJPlTb3{EM;tpAzBN_@3cgVvzqKOc3F`jfpYB0`+h&$xVI5nlJ zdm$B(J0$t6PTe%_|OXg-;+ctLf3bsz1L=LeO6V*w6>D9}<$2`&flGw2AIHs9J_c5_Hq|kjBJ(nO9ZN7r2`-S$Dr6csIk2wSG{og@_ zO5c5CtPFrksbrX>b<4xtsO9TI?7I{J+#P`3Y2y4-(u$h;AC3#lo9=|L}idGk;>#x zZRlkxL_T>H-lp7sh!xVY8tuVlfP!8z@1i>|Qmgs(s^-o~_6SH8v-#Ert*6k|jP?b}nKn=;XR6GMHKHOV;!Krj9z?70->bQk zimEQsj~P)bCzTRyhv<7s)g~v^pGMR+C)JT7bYAVlR3hENpq;`5BHa@x=WvFrJJO)t zUEOPeHpCUxt5>M&tLoinM18^pTJ$VLohViRoKzng(ZHNk`yo1VBx;U1BK3&V%Etj_ z(a@Y!X@~|;s*7?`RT$C5IjLqqbSI@6lap$d5sk}9^&&+3DAg4n^9nU)4j6QrLV3&- zG`iRmV~#`{TIzoUn$4lbnr|viE`Oz(6O87^ zhqNiuPZ_1J4rxxL|AA7MOHjIfhqRTPami zSzKjfJTVOay^e`xk6WG77$a|>Rfqx2^q`JtTa78K1M?)zcDV3NAAXZ{{uS_eDVAy&M6me>Eck8mDK z*G3@*;=lYs9#Q^>p8-xEH0b{n+GRJ;iyvMR6T9$VzJby7*El|PDbBZe1^|D=9k(%xcJv&w^oAYWuEysi!m> z8_hA4g~CbL88MX;=`yaGO$oc_2)RX6Hf6@7O{()BV+0SO>vXlg zp!Qp?1(>Jdlpg!#kH@AVV_jRWgRF9=mThrmTo>8M$ac9h%15O7LPkD;^1UYi0aPby zJ&_u3gmrwK87GpffgiOvPn4hJci%})cJ99X+dJar)}=K>`8}TOc#l?T>0iPs&yvOb z(>wWMEUDb*$@$A;qND=HZCxvJt${ncDdj7GuU?7vINRUsQMjvNG7UBL6k;a5tr_3(XSJzAURK9SNfU$yxAFK(h$GI?Ko$ zK&uI!mj$l_M2@NQMLb@;BsY+J4RFOn(7xS;Q{MxofVJ}bO;1oaiBz@wHNMfsb@!bN z;h$?^>jNzmvJ}uX_`b@&aLvncfQR8BU;e#M4=hI%>U(ptqCsmU*eY&^uxkj!zC^+zv`d z9uF+u6}3J+Cm-3)$ol5kmi-|s{2TTLJL!bH+`uE9Btk9#+`2kyGd@fEAp=j((tZ^% zeNIz;V=(+ua}f%;$G{7MISg}mru@}-!-4Jm_a}>h6fqV#B`)Ft`ifSPi z+sM{MWn5B`YV$yhzalJuDXxbS-NHobT;SwvE#IYaks1f+9{iWL$Io{seYBwbI2dt}lcZ5X>Oq0wbh`;z6c0ZiaLNY20cw`1+Es0sD>cJM!qlQ02i- zu{?-UBR=UT_|7a z$v>gkm|FfzrL0QMk3N|KK7?fZwCsIu*U^A(A^2ZYA$r&gxf0l3!mB2nlG7o=SdFZD zRK_=GQP2)^k(u}}KQiGw|9HkwFyF|Ib7lPGvxK~m9_FttieXSc8W(HvU%o+IbE77l z92cXRaVpEp+QaRT>i$?~Cme-4P&LeN%1bdh3x?iC=+qLL@raVyw5?BA`HbYxxTy8XY(DY- z2$6XT5!CW3!F+|}g~;L%@mWzMN^lG0iB-RN@CYVYN0krAn}yy_@-vKAFS{e(daJgRZBkkP$Bk3t)kAMN${1l*X>aIRLvYfwbeV?AX>oi$Wv zegiV0pdt;?XxC6P2Xa+gYP@Nf`cw^ZGb@8BN6Ss!RpXSmuS_(i5_VU(NVmq>1%&kT zsQtOz>Q?{?Mgd+zqCwgSDJWTLHSqUIHViMPsl^nYJLKUDe+MJq8*rVMZi-Pi6p03G z^lthTrbeS-{r^#iyTDc&jFsk54x0C4s^SpxUxHR|U zDju-g;|kBf6vDYoRY9mmK3}HzxOzN_=?xm&fBR?XZ?DxW=hqN}Zt#-#Qi;^rJay*Z zPf+n4(5ETypatu3?uuHifoRa}I<0MQkr;;&eKlkQTO{@%m*2pQ2KR`^cVh1iF1dsj zBqML-;C5co7+{M@-o7R#!^svjvJ!NkC#E+zUGxxk6aX@~b0{w)Ie8bG(!o2>03qy+ zffe<4WYV}lkEDN=|j7L~#L>OVA*;0pv zvLN##dPY^tvQQET`30I(v(WVboU#dd>T{NbIx?<{yw=Ee#T*&sBU0Z(W?3lb&&^7$ zCsJLW*Fs{Uws1l|3|zC&?OzfL;qvAG&^2VCpKaADE&X3v(e_OYZg*M%8S*T-0 zPBw67H>G?Hux6oMz6$ev6SXibwBjAhLWi@8%5w))3=56@pJkzr71`Io!+j^ETnSjS zP^S{|FTk3Gx^RzoEemyx+yhv%P#69ca25;Y!pg2YBP^8R)Kb8fh1zZssUHkZEY#w@ z>b^5}IV_aBNZt!5i-oFO{{)=HLRGHa-*Z@~wJzk{z%>hfcaP}{%`Wfn60*?mjb6jx zU)CeDTJLG-85Y{^eTRjHI`VelnuSL5kzX5G-yGXgeqdQ>m`=zW3_Q|Ff;FK5YZmHi zCqLBi^epY^fHe#K0uK{C_T_d1F9`DZ+Egvr@FRzXato@ixysvAm6B_dL%eCDuFt}xw-MCv-=mW6VKQ||+^ERIzX$C`!mamYfOuyM^o>BMhNNTan+Sr*D@YerAlU|A@m?Fki$r6_}D zp-Z5lS?FL0lNF?qj&0Ovfk!n?j$m{YP|ZT$Mrjoq&ea?i%2q53r89pVnXoLBp==gv zAy*YFl<}*=)L@|uaWh*MYPHCq zf@YzMA+s!$g`B1^XUKzvzVsM~0I|^h@YrY;dL*t0{~KbjiiOfM#jsE_^(7X1^rM!A zW+%}sbSmVAg|a!;QY`c<$TSO`M%f)l6}E0JVxecCWSWIGup0Ji<$j%lQAI42Dn^rO zVxe~~kBgr8Cl*S0$U^xtRrR78sml~BwCf{i0|+;+#yW-+#}3R5Ld4=ikx1KVZ$AD|yt!+O+%w zCyOv;`;Ttc=ke(hed-6}f#v7@t9Vc53SY@r8F>xJm6EdaSeBr!mF82tB6U?}l&>`3 zG@6Yl3x$1bu;wAQ+hC;UX7!B`kg_ZI&j_9cDc6D)RLNq@Z@7|D;*`2FlMY%VwSs*v ziR^1+XSy;jksM=WgIpQqBT{!lM(iasMrY%5<4_xj)YC?|#0WW&{1G_ayE69#$NogK z*Ah~f1%E2Wl35e1{Fz`bcK(LH1ixC#T? zHo8{iJqCWkO({14CQ_4mJvjQ8FwbqM9FdyL<-V-9U#q+uq*+Df`6g6|)MUo_at>7J z)mr8g*NR+e;IG}3@_E2SYBE1%73EXFL~1gBWx;;~rdMm3Slr28*8NM7n#^HYumnt` zCUZobI>Izk{Ro# zPJkZ0E6Xg3$9T*r9oZc?v6Rf3oP1=3k!{McEvG_8@5(YSJL#~}w}Ibwl3<1nm{>~Y zqb%*W4g9UEo!SSu7TNyCG@)v}dcYVzEKfIiPrg<<0H?QQnd1$v^fLx;VQ{5C3;2Eb z&vezeNIi&CqAr;-1IgC_(F?T9ti14&^6Ao1ohcLlXoWj-6gVH*$tbMJQBW82LZh%b zMn{rr1zub~NH<|04!Hq?m)W$sMG z)WxBCLB)MCJB(^r^;BO7C*wc!qt%~-(?<#V*+MVil-|>2>Q&LX zQ9JPf*VkR%e^`qE|Cy$T(&!KAU8EtiG{}%hJp#dBBs@Jw=%2!jrK<2n5Bz7kyBZ=@ z4vd&gre78=?*dLtCR1L8vT%xxJA#o7iOPIcoSL4`d@pmMF-lD)WC?KMdzlec=vJbP zVz~&wx8OfB#n!XUz!))k9%znTMwFS0<*b?nEq^9l#!6_|ixc*K z9}^GZDAN|Jww(wWT|t?4u_`Cfn>l(6XVS5nC(x@oJ~=Jcq5+x6bciLV(+E;$UDTO> zO$Z?@h!p&rLg;J_EheboG?<|`beTRHUP7?Q|LQD7&@x|m`7feEBWMoSDwaP1#}sap z`OA}&kd|i?e|R6EjQG(ON*hk!e)ZbiPo?|^!BcBUq)r7~%XF$}gu()Yt&0e%xB_k9 zaDzQX%F4sc8P&=XaGxpjN4o-T5Tsw(nJ17~8? z-Z52qS?8CS=z;&tg|VLw&{d?`#K*(*fnNdt=*f-Pe@n+BW3@4T(gySMp|W8g;Jsez z0L0CH!||mtCH6^E$PU0RA$($t#*3CQ?Mh7rzMf>$Od3+rTx|;kzmRaY5voK12B^e; z=30YuBHD;lHwdPX@VZ=KdL9H%l5l>E2DWMy`w>o|xd`%K#B7a%uQK?`wMl&AUd;pN zePelGy?;>50_sY|19xswFJS0xq@e=D13&uK^1$pQng<>Z+lB|SIo47cGD7n{3paNI-HdEJ9eybQJ9-^#E) zS*3IaQPqoHL@FjsYcIsPE7=Q4-5+7|;a&$Z>Mkbr#Q8Yno6=PYx<8#n^2tRKyJPRd z;bT{Zsxw>b+3)p510lbf3vuUg;gkby2$o|}-l}7%`21?IW ztoDT}@};D=H5!_Y1CeL?06tL~5Ic1S|fW*Kt(gVRuLwd5Q~=<9;a zzmYWQagflG!C0(4k|=!(L`(~+cvqS#D|-b`LG%s&GqpTb6YeKFjtZ&WeuKPlC&n+` zrr=%JjGZ@hM$vu@r{i%vbm8Y1LH^m?C!|NNf}vO2BniS^hVsxkiBc%lKwl1>gUDu# zo~tN*k0$ZnWOHz}D*U3m8BRoD4~X02hzoND4)~(`qi0ny_^>LXtQC-EK_6U?bR|6w zW#>xzj>=-MBs%kdBB*#K^wpJg0OwvZ6xl0@({kbYyPm|*9=^B;$>3e710G$s7Z_~W zd$ef_rr0`oxW9IN?5m10#0GXs`iF3RTr&Yh2wfj^>fb-Ed@BJyjm1Os)^B>LI(-n(s>{PAtZXj7j<=Gf2#`TerzHxmx zR^*!o{@P6`)A$-&yFQ#s$Oi#y*M|$&E%A-(!^vLG1x)XA;rejl1Awz!AF65Tr$(|| z9}K5H0Bl_!w)aGee!!h^a(!6bSH1cSgx2-JT_js$os2Bkhst$1VD0+20-sGdrbK?L zo}uf5R-9wKIq|z$kCJQG$C=PGu8&F3v#yU&NB#_4yFQ}%NcvR)mTk(hEw@6ZT_0gO zA=@B;h~c-LB#4{@tX&_j_7NR5{H?2+Lr-u0wp4Qnnu8;6y@M(Cd&XjK%g*)@23S2HZ6n<=Wo~+4H z;5&e7}v)ls9VU+g@EX_ zFS|ZiHLQAy$b@x$DE;dJS=WbxVtAri*9V)RwotAQmG3fWSl36T8tu;ZL)S;BL5A?V zO%PhwN4C&^fxHf>$+*<4>%(e@)RDa$*GGuU2Z3wX2W1gc!;^E9>E2p4q)J5QtKz%` z1$x!Zt`9a!O(tabb0V$}l3^uRz}ofU*waZ$t?MHyOT7h|b$x`{q)PiZt`7%)2e@^8 zIC!7Fj_bq0cL2Ap4~uKpNAG@)>w|^#K-I2~uZ@sgAEA&bbZYv!j_V^7GL25v!Q{re zK0+aDj3m>W=7f#5{D@22BAwpxj`slN>#< z@(wC$+#p9Z)H91eyf08je9cN}!>OF>25C;B&<#STQ8x%^le4Z?*aO+;%n@r@gV#*0d-JsmqB zvu+ShLn>N0u&E!qL0G8VARhs@Zjdk$r4*@(ll{;Q5)r1qgHXFcXke>WspNvFhnZXG z2D!Zkro!|({AG9)_3Q8xa1r_U;C`gtAmunTufq*3AUDXQ>N?3*FFT2LgZu@#af7fq z)>3YeX@{#R8G^EJr0m{79^u1?+#vrzL%TtWtwy1}uIZrXkv_XVRv+PsPm9#CAsujo zAjD*365+$;9xV9LP|_$>QP)=2Lne@;x_<#$xvh|F{iboTO|77VqJx7 z$hmZ0178^D($~n6oJ+r8uboSMF8%x zLL|t(b}lujr{%8{)E?IT$LfQ|BaxQTi zs;!oct?z5+QY20KD@e3+DUv8%cAO?uRXp1y+PSm?BI8`*ns7haaa2g{#?B>bAnjc0 zfw4l)r42`7nu{CA(1jf^4*ZXxArht`;aoCF82h?5?u~O2yP?z&BZizyOOfiS0vyA+ z)EfIkIhW`T#upzQ80S*6;J(J{BC1ZFhwvi06wkWwBBC>Y0zt)7aYIxW(R7@9$xvi3 zB2LTYR(_@Kn9^29GWeA?CNTha!QW7Jers&<+tBRkwZj7yQqvW`a0tKB$iEKdSIV1$ zB7}Y=I`t1DEWcyFO8iPJr|GOx3jIo%$)Le=&;w4*i`I`Q1{Yv|fB$$hxf7G#|Uulq0 zc_cWdz^2SU>$uRbv;>rM;^3(B^T}rSclX&*~=>dYrm2UuLYdtS5i&; z5#TJp62qxl|2cjo+j}C_+2G_?vbe8$buxt3uf)wI9|x4>S5mp|0j&K>Zx)&k)&8Qo zAc}n7M@UU=5g5PHAFM~owO$M88Nbr$(6fG}P)AM$uKh~UeB@dq+Z2!5mLEW-{Yqgv zArHe^Q`)Z-CK2*9z}m0mYF}dDZ=DQ8>TbZ+uf$ELTJL>>lV6GPGf`QQsvQeLzmlVW zw!z7-ar+S-%oPavvZaQWIVbJ`FF`nX;3w74FQ7DsZ{v?M7iujso8S zq#tMtn{yPxTY)?uTH3D^$w$ZsjI1aTk#R{y>L3)XUy0j*?olGuG9H9}B~{^}fO7px zd^?mYA=4o>1C9m-@_Uh$EWeV#y~g;Jc0=9zl{i<`gN^cn(67X~rY-_x{YtDFRy}n; zgx0U5^gjn={YnZtE)j%&B{o5Aq5MiJ-|5h>ex*t^K7ob}sR=d6kVti`f<`nUHQ7SH z>tt%q<OtsNvbgpuT>zmCsbL{KP_cT0-ujiwF*}O-mFN;sekDp+xnGGM$=0vLC$3-VS{hB(uS945 z+z^6aiJ@CU2!17omJ(F3_Sev_#PGcYBfJKlNaI&Jh{~Dpnul?0{7Qc#tq!kghcbG} z`zdWWm2>?{>q!*)mFP6;S7Pjc5dry?tibUrG4?DeNBl~mAmUfD0>`gpG2hA8`jtqE zC(&=#uk;dt7#By#YYd!;QG3T!<>l*uwO^@seY#9loA`LJ8o$yne^|fLI9B0&^7El$ z{7P;9bo@$ONYccG30#NQ(0Ea0(XOK{kXgSHry&(BtiIpzE3r`dl}dqIzfzcpQi{}4 z2yJ*xM3~+Kq4q1$z*enNn0rC|g~?s$S4w|}sWADK7M-V^L>s*+m{0n(sVjAO4S0$1 zD;Ziqex;gwb&{=-B-*dk4|3yIVsmU*`IYX3jHYDpD}6=T^`ow}4 zgx56{r0@sjOPWpdRdnJ2gx46-L4Kvy!L8Tfil7g|(@oHTvGmy$U`=-*cspxZvZoE2 z^+9;EVSd&J;Zt#b>QbcL;yu^^MUHGHT!9ATA)bFmQ;!>rmL=PQjOn_iWy$_97PcMQ z0$)Apu^0MgS+Ynrd`fvaAB0b)({NcbI`yX$mVZq%#p1G-C1W{%=EX|k2jQXMhR_5# zz=*|VeGtx?iztimgK);~3NiX1-0G?F*bl<3F5{}%?6PDLp}L>&f@ZWVS+>;qAe;ri zqQWY#Hui&X5(w#Eq<9>bC0h=_DVvaI8QB(B#&wZ58QCsZM)`=;H;~y6!a09#R%$(w zYCT*F>4R`vI3X7S*B^xMZb)}&E?<64ywjl@IW0?e%_Ul;r5~I?DqoVt{0(@GW0obm z>2k&Buq>HlMZRO;&TdLs2eS+PLHN0BP~|x!sfZpeOLh{ja#lIlpXB6uAymu<;T=&5 zy)2nyMb0+xa5trV4Y2+o+^K}DJy8)oEKBCX=L6Quk~!JS`vB_?!d>`Vz(n-yvSi#q zvUrlZtJr197*1UYm;wcOSu)#ABK4fX>4R{K`>Ok@U#W;5FH6SFB?ke@`XF58x)N~K z2jME$?*ZFo$*grDTjN$oyb#Nh?P+BCUw`PmU-Lp*mh1|n*D$DYq8S8QuLfQinh(M^ zK+i5qMp-KzSq-x-;)Ph2ESit(X=HtKY|90Z5dp-qWMMjd3~S(#P7)#OU!?*Iuq>IY zU18wqS=ws=>kq;|WN(*h*dGkMAoz=6)q<_3s%QgVmW*3abMh_z z0eM+6W%;OS>b*afB?~VT9(byodaD+0lX}k#r1_S8bW&K&&!grkSd@)t5*H-Ei~*0;WoLD>8sUSa=R=U z$%MQKuwIsoEX7n8(#^nEO!?I*f!RS!PuGeZ=^{9+*(4yce zD3}kz*(N<-)T6JU2=f&4L3k+ZvKuphekrtmCJyLf&L4y?m>UoFJbz^ac0FLuneMzTobI2}$-B+%!cIC2!Eye8Js@n!$X*O(%Z45Sf=`q-%)G zS4fW#SsWrhD~iN!+}n626j?`%W=rM^Za&suaPx8a1$R9*uD{@>6aRQZ8vSsAFZ4QM zj21CEaEPK&SVxS}mV}DLK9qr`vgQ5LFF`|p!CeYrvOj60kI!hdz@r)`2QfMgC=n~H zBen>oRcJW5a=zeZEA|U+I`c0i6ZQ*khIp>8Agm*1Ay*Y&a5FwOOpPzN8RBNPUvOJ3 zH+5I7N_qRrg!zJ-^hNqz)JT89P3;_(K@>E>U@>2CvvE?;wB>5Z>=)cDv5FQo6@Oj* zA!4HW>*}Wxrum{@WVaeaX`U&hhbgD|%A|QAK^Qf8WEHK!m?4(Yi>B7W(sgvV0BP#f z2GxwEpIKBHX)0c<(Jaz*FHm192Nz-o3B>l*Srgxe&oh?Jsv=tc}(lquKZDE@i zNzA8gfp3)Qz0lNaIUh>XAx*20wL_Zd)PIn${5d6+kS3P%ot2eB(i94w2u)DHLJnzS z&F3hKkTfy&YKReOvU;jKmNZ#i#v`ODBIFiP*$`>UmO7+~1%IK!DzA_MXIO$+05K4cysHDOUj2q-loUKLAYkOG}y`)q1U=XGqf( z(6gi|)REhOYtj_WN7lGc%lhWnmi-{pq$x}%IE5P(J4W!A{Znj**)3db4 z1J#|d!P5*_lP0nhQ(Z_m179`yzfjPmsd9xWYb|N2IF&5eVP6Sp zdJD>$G_kTOIY0VjlLswnQnDYpU9SRcNfTFyp29-D16-3Pr(kp_WS565X^P1BHZKY` zK*5kEwn@(yO`4iwo?=K-C{v_~9>7eR=wZ&^R>y>egRao zpgT}ng@&^whXt_}%Yx|4Uq~h_3t}jn1zE^d1q)*Q&M-At5JTL|mIYZYH#Jxg9du3N9p>SVO)psf1I5>Y zyC0=s>ToKQdci_>b;E+pdf|SpjqyV)$V_Jy3#y4?5exc(rgI?+I+=2?Ury4Q--4jxnb21( zs4dRDWGJ#Mh|_Y^D_yiA(GerGE0Tc)opCFO$v#ZQ$`Y7KwGQ@vO;<74NtMpXK9(N% zMrG{eL4#(olY>BAcGB`q%TA_a%H~Hl7r}$8*~t-ILUwW!GB)gFp0TjaizMb#w!n9! z^w-eT?Br0I4m%lztQ~ejr~ajcv4S+8_h^BT$` zWG9T>6k^0qtez^5WhYjb@d!JK2)RWdc5_4o+7dhIyu#ktL{4+Ld#CLi{w;5S+8_du4@2i zu@jZ+JAf@avDStB2e@V@8`_(`(5&O1^Fnsg;8V*^cC#Lt)p|z^2-!(j=vj6W>c~mJ zH9LvsBkwY@zCqNsd;v1ePQrBfr6vQ9bdm^pK%VotWhYS!;oU&q4=v43B3eTJVPxxavY<-@A1{C5uoJE@-KIq9 za^QB2U#@U!DIm*EST!s}YA1x2ominr<$vk06N~E$;S2~ZJ7FPJK+W-0f2@RtWhXYd zkRJfgTH}{wLe}`ovJqHjpu&;!j9E7rFC#cR8QFPV*o2 zE~h?bBH1j4<|d-#4%!+PQ$#&vSPY%`%|c{el94tcGG8I-5Lp}|J}ZjESGcKF#$sri zWLOLzYZk-DA&WVjjcXP|C;kzHG+OV@OzCTu#dLx& z*^M;Pw;Hs-qZ%jAX7nSVn#Ejz(ke8ZRXHq%tymUAXMTS&VOb1A*(}CFt}0jz<3qyK zU@;7FGg}s8wcONTF^p5*zA|B04B;YO4k3nEW0YzZLwA3}V$39!SWKOlEsM!cqFKxU$j!SP zHpg0u#oPs%W---q&GYdk2*<(rhRZu$Yc8B*zlNR zAGL2;B8mBwE%3c7Jqntd#~e!2;W1^@8ewP}o%$KV>_S~xp=m7VryDDUJSG&33Qd@$ zw6b^%YjP)sJccpu7=;m!v3jaJmd99K#v?o?BIFhcc}%v{;V~@W)qYjAERP|9kW0{{ zM351hHXDFbHvEX8k!^8hTo<{+$ac9hwc2m&F^9)+{@kq8dLng#5fYEFg%k2T;5szz zsB zob2T;z?#Rn@b7@LcnlX-9`SU9$1t2a1+e8YWoSyp22!O4Cmv&QUv=L&2rZ8xAy!5L zl*MD%yxagdi^njW+6CD17;7D~R^Xb)%CM%Fio+LqTsrg==5PRQj39_b_z@_E4eEsLxDv4N*&X&(Tr zc?_*OrpLZ4+^pdR!RrjG7CZ&8(d`6{$DkBQ_X=ka;oq#Qm;R?}HSjhh6pRk> zmgNO4tDcC+d{!u!2L;1p*d{$+G>>`5$iQPl89({L#s19VovHV*nq}**E|1}rD^*I$ zOs`~#-?m&&^B=`y_FxK>&0}b8B1$r}H9Y1hs=whebmAWyBJ+}r6otrqg(O2{aftY= z2p)4*>%ELzfjvI`MtVuF)BoCF__pMyoP<15nLl7_CjH zNYKhln#a5b4IPtq3WUiNX`~Mtw7{bpCr@Lv6}6v=Nh`w7f+{qeRXIF{tymsIXMQ&_ zVR;Ng**wNVt}1v8N3HgcLN7*$A2CF)UO(CU<$|c>G~Za449H?(iHKWmfmZPZFB-C!@hszhTBh!Blkn z=QK2;IRNX01Yy*7kzlGGn6Q-Xz@}L+^(Can%aUWryBxkO`H^aDUzX6B{~JNYe?VWo zEIEjCxXrA{zAWLi)`uVxmk#p96G%3&MYH(FZ~3C;u;RQEuy2PfhqV<6^1soS1;g6p zH3PgD9BNp*D)mpn@v!#EWjOUml8>DPN}J+khRIf}(FvX z3aLJvhGzM?BM7UcBVPOf9r5ai)DdgHMQU`!3V6Srj_5eq?Fc$k--8x^4}H}Uy#ad3 zP-HuT)7nq0L?SiB7h92x7B?CEt1ryrCNCmOTHNFEUeXU~!XW*r~-$9t%~QApvy{7B_hx za<#b0j!?c6(T3D#Slp!c&zMWo`nQ{AnnH*K+1HDkoNeT<{7UJ$kPo9cqG&cGYH^b= zWzl8>ei&8%6Ox8AY2{q2u9q-r@rzm9gws%Mwd7(*I#HT`BWcphA<>JQL=vSxhKQ!p znJV66rpkJ8lR6k0W^og)3HOs7M}^dGYUNxskY3#6w;wPDvA9Va?2pF~8oIC^#(_T= zsv=<;l2*>uNf`TQA3QH}5*1KtjiEw|n@mEg2VsL2HyKYh53zDCeMZNNo6teHxXDF- zsEg=Zm~k$mU#J-NZboPRp9B@Jg}%CoyeV`Mg(7HJv9v*)7>CBKwo+h+Pvfhb)MR=*F~=+j5_sXulH z?8@t*LPf#qOTTbgNL9&FPeDeL*wUe3Ta1$menb>F4O={|{^T_OFkJO$4Nvv+uA*vj zu49`6ri-9-rhi$eJ@#A!&-O<%%-WYuG4KukVWE*r?=|p^el3PM%geR`rl005ozGua zdr4K2A4$6|>b}T@#})yiUl1<6EvqDb47@C>Bv%=DRaQyvH}J!5Nm6eE-dYP;zMB3=KJ2OAz!*xJvMr#S z34Yw8KGz213IlKQXoSR)tZhqGNJIJnbkJTcxxHq2C5r~3y&C*j0AtsA$qi&)on5ca z{LLYR->4=9e=9-h#|w26&GFs@phT>l{?&-)IwDTh;0Ma-CY_Tln%iLN7-gIWE9*-$ zUWqKTWxNQ}1uhWV8E($F{3Fzvzk(GQ8mXamTw>1@YmE0em6$9k?Q};Yn&^l)RdyLY zx1@Mo@(QZ6zH~$$4Y;#W%+epl_~06xtS)^oFN6JU1b!#-M$Qm|26E~5qW(nSr5_}x zP@(EyK_}m;6V8i##kvhnj$e!uuk^XR71+}VDE)bL{q>Y$baDnKf0#}#(I+gK$tQfl z`mC^o&5?n)3jd||Ir@#} z0wEGu`iNt{(RQFUXhLHqXu+TSOsemwZIV`5*J<& zDCc@VOe)}9pMG*s$#>sJHq&U9bA1g^*SUUNGBD2d6@&52jcgu4X|;2G@QBd4{sA&J z&h=-Eg>7CWF`u#putBr+}FizWa8p z$n6I1?531$J7cDT_1DYK_IqZ+JXfO@#<~7!7p-!xe<`b|JRgFJajwrjBQW26J67cH z1|IIFlta3qgp}uHSw(pRuy(FHb(5(x1LItGvX}P**3NYoKH{t(+quq#l~Vy{1qm^n z`W~=#uG?-BsR7+JPR@0U`>Ol4L1>-p+(q)V9znKqUFG^9;4J65%JrzTgV4EdtqVCD zxOT38GSu{icA9@SGz=2@-sm+9@+wG=%xb+qpl3c|=+{%N2UdP^5OZ|otH8B$J(`bf z)l19z=Gc}?A=A$FFrAQjy)``2Nh0Jpz}mU)YJX(l=~>#{&Iycjy^g&Ig?z-o3xZP_ zRxMbsRILWa-+glns;;@&;N)CqoW2kjDX))O`isB&R$Vq0kan(zmkEzY)y*=|S1VMD zM-|wpTxJxG$x+~&fIPdOw$M69A-o&Nub`!!>ydnfoOG_1t;?}MmxxH!=&yJQfA`H5 zrdyauO#yD5>s;Z~9zfQ)&Z=P{Qp3(ui*}WF%!`EsUZg$)Zk_AVL<0w?HM#h^Zx&Jo zl#5#R$3M`p&UKqy$noc^RjllH-y}o08DQ;PCri2{R8wCy`MiNx7)*WlUAaPX5Z2rx zh4=FsUqlw{rQxTLL$-5$1(daOot0I|`57UPFN4pHyyg3pA-^pTq}u>n=Q>x2p29-b zELUrN;k$3AV04HdTrjfgQ5oN$@q=lD)x4_w$b@QpdcJ7q`rAeZ=elZQlJS$TkRHIq zstW00&fk4^Ovc3){Nsnf`I=KRC(;ut^>>>&_4JZAxthLjdbZr8ZGds#>v|l-2qhl;MbzG3JoV;jt`!#SRXu{`S+3u>w{+~ z+XrtUR~0^Z#@B|a;e%(0o7wu{t(Kb_K6u6{Z(o@(K6t`Kx_6Vn_~5CXmA3N1Z-vPC z;MoW%Xdiqx3?%D=XQA@J=Zs;*68+ZzlXZ$EIsi|CjwSkGBuv$#La8qz=pjMF~t%++AJ>e@K3Qsgom+2d}*qJP>u9;*DUz>STq5A(Jg2; z8NL)~OC_>yG&=J;5LCPv)mCn_vvBSuLy>i(aaw!N5Q$g?0(y`PZnO_TD&p};t&k@? z?o<%=p8x)kevR=|!Zdf(KoT zuMA1p+Buel{qE%13Mz(#T`R3nEeW&TBvS3?J0#5FzUsb5AhaZmyGRx-h>$Rq z>+OKENSMksZ=plNtaTwL0M{g};!@N9nq0NPN*naPiXxmoF?tPyxvWQKwcgp#GbHTH zMGgrIb>wrvH3^I6BbzR^BrIxM-U68>VPQHUW4Blm7A6t$Qox#ox!NBYc)C+~ta5j& zC1G7~k?656|7YL@!BB=(3pTvXAz|Ets%vgDIFT^MGjx5V4!hkUVXDif0MaBZyiEAg zP~9vG?yw{*s=!9&!$#qlcvOLJ0&?&YOTwZG;oU&~1uad&B3f9DYN;h*5gC_Mq#EDp zkT9+=-KIq97T}hIafMT{yBre6s$n5gvmmq)PF9HT$nSPYn8o#la2161OAQuMAr+NT z{n22VL&9uw1eF5Mif|&CkhSlzB#bP@R2S0Cz*kNF1Qaw0t6bsydo2lDdpTLK!@d#{ z_70Ra31ekda(?v5()%n4Q?lXQuG;`x62=vxr!b*r00t!VTWO!V!k5}Wr~E+1DHt|JBQPNGTJ-H;m+#^zW{k+9=0v?T0f%5Dl(IE#ec1r1HYrdy3dbNO+<-iJ{| zB#bIXt1J--+tfBLj=(>WFv3F;#@C&y7u85#cg=!Cg(6}9quFFg!iH0cED57Ce>6eG zTcEE<*cCYUlA*|wFiy+a(>+5Z24F;IkPIZOJ7&P~`2LBCgi%45P+gnWAxuvtOmjy` z*sK|fgwey9)66$%UPusD2?-m014vlixdA%*+_k!+&w9XibQz|V{-oKqqj6+Ay4qw# zTBxHZnj~Aj>?FFQS3_<(n$5A6>gW$4(`@@?%5ExUlGV{wQ8L}pBdkUtCg#r$3B(jcMo=40=e>fH5a~{!*&bJ)Bb~BzbmSAjUMp zYI0C%abcbqQ_L^vSwpF%?}n(>L?OnUk|Wv-(Z73Yh%xOv3N`W{AmhB@%PRdP1#|tR>ci9y7wbl??L6v3d^V3%-wwF_%^@9|t+TdKxpy zk#qhn&|o6H81kp_KW2tUfd4SJ2324^Jf>q#^wQfP{fRWL_1aH?2DexGA0UmD(t!n?bM@a~?eyjwnxcPsAT-OBa6yMHt9R(-&` z)xYy@4K05$Vcgn=ynC=8?|vG^yI+>_?zabc_xtCUkmesx^V$9#y!)%+Tmlb##b=Vg z1WDeX8nowqo1i!EWiW*ICBbF9ZyU_weY;>0?@tR>@Vf?Yzfg$GqyLGnmf%Ucr3c_YUsmeQEG0@B0MX zc;7epjQ8gTfAYS6K#QgfnRs4M%=_~LTAF9b#DT$3-VX|{-d`SU<^A~J1Kv*zzUTd<;9uTf8Pr%v`A!Lr}i^gP(anFNiIo{B8_t^Zw?b5%1>* zZFs*RIFt8_{vTsk0v$#1yl1kzIWWtNawN!MFdz{@!Xak@3E>DxvN;F@`C|ErqrNpIBm{&{b^>#MJ-x~r$B zXL_?c>wJdmWzKP2FL&m0z0$dX>s8KuT(5SX<$A628rS*GKe=A#dDfboS?ZlQWa+&CW$!zwD$(TBc2Y)wzf3EzWnie$Dw2*V~-ma=jg!7P8yn4B~p1 z^GU7?ogKN}?d;9<9_M(j_d2t=e#5z(>;2AGxGr)Qaecsf3iYIzy-qFSX%xG$Fif7N z+be_PN6^~D%&5OmPt07{X9ZP@hH;fQg{#FWt4O(IGFMAqy+cP5K&#HrZ7z$IwDDM(@MVzxd)V zC}X0K{4=Ht$;_AoX%`X*&R8s@8fbWPFak`>e5DIluMOvF`#i38Zsn@*I9IP<GZW`8!wdS6N5yry6s0I*zL|!?`*;jjMA@x%%KWu8NOxb^a1p z7rsN4mid70yPoPmy(ZUgy%pEhb?Q%AW-XltCoQwKPQ#LxSx2Vk`s_Dx zR-^m4kWZWyo`NV7XEpv}7FA9D-lL;xHjZ_``GZt-s8E@zPOc4P(%IxHwmMf`=+TlBXFc7R zt8SgSitEEw{CKVs=5m#|0aaLO5k6z-{0XIhj>lI!V9l$XM6EUHa*`Wvg_VQnTAj*Z zJK>d+!dk6P0zft?dRU5jivZ~JYdNXp(Qp@hwI&=WO}9)eG{8cR17!w-h3cssT$wE^ ze14HzKS5TFK1FQWBIHau1*`^W6mU>bQxuB5nluNMGt;ux!aD-dXOVNVg+JMA&rgJ! zJ^-APN1rm(t$sJ!2yF?uul|4=;kU3tmCTdPOhFl%2l^wu6lk+)%*cJaW(KSt_BBhB;}ANxEdP4)v$Q3hNp2gVjNc^ zXK^)Z7gwWCb2a9FT#dcYReF_|DA>3LTs@b})%fvTO<2U$#BE$nD&}hPS6pQTY$Cts zt8+E|F|KAb<0`8&S2O!^^}<-LX3gX(dkI%LTezCNkE=Onxymi!YOcPSLeHzl)%>Tp zTG)ZBMJZh6jpAx?E>}y|b9LY#R|h}h>doJ{I`q)X6zp(Qs`8SOxk?_!Rd>D`?>UL-p^H^vt0H4oU496aFwRLLNWV4$kl*Hxf;kGlqbEw;u9 zU)fvZ$+@`mp1R2?-vdb;U-lkIf>yRQo*`XM>fSD5YrGr0+!}K@wz9Uy-+&Wa<1eYX zEHvl6HLi-DiLLQ0+oCG9Pg`TWk1*gGy1sI-^(o{!bAZ0ZYvu5&UyrkX3BW-D7h0Xa zesF5-N|~mwhtLlNI7r|^tJCgB{9^?#c+)qpnC2&0P@&bS|1I(L4@XQlsOntpeeX%ZY%XmvKu!AI|NT@;*t|AuK298_p^ zs=njWcH#y4c1J;z;Gja&A|Jbs-4b3aXXtk3ZG%`r`L}(<7PZLrkna#aU1nRg?%USe zyOz`GGA9s?A|1JSa!?q`gDplagW_~`h8^Cb@~-|+4V}_3zw6+w~Ofd za`3Y29FDE5u2;Wpcl`!6HwDdkcYO^kMAzrp7FDTz?t0__^!!V_=&;cDl;};jw$@>x z`K?9v#jKx8GavIqPJJ;y2#Wb(*}e+9&&U?@L)w-_=N$1<)gtzUNGBR~CGO@^DMJ>fbMO1Re(u7gCZ?do#9*a*V9SpG7`RLEMr z11O&kcWLXo(Fck6(?VOJ;*T2fl1`r$a&SQgTD^!!msX6|x^DEQcU5{9n;i(T18E#w zkV>nU=fNAn33dzgfq3s0NaNtbYT=bsmzLhkZh=0$;oSmh99&o}WK4Bw_wicSjpj{N zdM+nB5aKS8#=!+ota?A-2Y8-YNDed;`7B@uLhL{SUj?m8VLffVOWTB(aG>Aj@piC( zvPU?~DRgPgcasBMWU8+0EF1`N3#4&y!B?Srold#5!*~e?QgREn0}0BVfff_k*rny* zwQf8OoBq#3$7jO2@pSC?Oc3Hze5Ffj2GsdQ+D+xfue-h`e9#Ew6>WzKUa38hT3k!$NW}yWp&K# zwm1*kA7*ikq+b}WmrBYzq@ z`ahKxof7TRzQqe;X9cE`$BqOZJNoaMI(9_Jv13_`9m`_uIC!KHD`HuR_@G+dSCyBTow*Gf#<(TiFr!rVw5i)mW9qT)< zTjz+x4SM@jyg{~ZgCpQ=S}8pU_%~wr?HBO4>pBFz?>#@hQ^tiI(dZgtkicJS{>x8` z?%2ttjmK-<5e{pa@d%L_j}SfJq-=yNJF8nl=58Iey2~SUl)Hvo!>zIC!us*nx7Wr4 zXx7q6>Z(nb>skS%h-)ZXcX4U!C+pOxJs=Kx#DrClUW=&ns!N-K7Yv7{V_Bff2&Lqh z2V@nbr(MFg=iOMlhqj7ABZPCP$+Us3hVt4Tor>mWQIm7INu`7QtcwItJYd}+@Zo?V z^@j77GUY7-w11s~y{KDj!J7cpx8>Jq_68|U%~Wxe?v3zY0Q9uJopsY>-alJV-ixdOrHy@! z9QYtaw-*kCcx@()g9|GE>8=}3P3oMjSEt1K zLR}N<3yVAxCy(h<#k1#}Twf@hHOU)WL&~9>us^LYbna;}UnRQm z5CrO{wdVih;w<_}deKi7t$vb^S3g6#p=xu3-8RsRw1AL}()$bPac`bqxwdL6TK z03J;_korkC8n`5tzZDVvB)#Y-i&j6$$E%-D4svN*@xpliM?Cw+Ssr%^C;Q2==qLG8 zKY23}lRep`)yi;b1^d2QO-ne(*10~zK<|D+Qu+XVu#Ko9_O>?aaTitvSqmw zxlNPHam+i}q z@zO`ne9Twdj921-1hcZQc1(~a$i#sz&v>`L_6YQ}r}t!{lk4M@bHiVkGPI%#ndYGgphbU!XvwpoIB!M#uU=ZT6-US%$C9;Z z_e_`8AFqGO`yWR}=1qjmn`Mq@4V-u0#fUuk1@1Pzr={ji_xn7mM3h}*_vu8)yjd1` z^P6JPKh46ua5m@75&73Y|0T|OC616q-W(_9=Ny;T5#zURJRgvM?qI|^L#$Y5Sfn89 zCXnd0&TL00H{Q;}I`bd#>>a#ZXULB86h781dK31ib;f!RpfndFI2X5=*q~F->GH~5 zTRDRucg+&D$a?c!+N*fc23^|P&00>U%bZx0?=?h!_M%IBWDyeB;;8ndgBHv7zKs!gFYED602-;72gQ;9XG4~q)sT?6p`%Je zN4X)b-S8!N@GxHM<~qvW5#be{J`u+cM&=B9g@0Ma90b>4EjllzEuA2IlxQ~Db7S3j z(u--!;(turcKI&t3SRcK{YN}|{>W)d7INCM%%RIq+tnLf+I75W?C7nlva!343#Hr{ zQK!Y&u{tugz@;t4>z{7)yPyB!#_H%?>tpHl|Hbjfr%8M9Btok2u&MR?* z%yG_hN3@tLxCegr6+$iGZ#>)f&?wU8<4e?4W4eJ-sHUjK5+ z{6}=_)UcupnWM{7rXQj`g&RTK?@$D5F#e^N7H!25GRG08O!QR5`P%B)s;K`snTaS{ zD*pRqCOa)Uf4@t+gBNPT`GIN}mdqpn1nM@~1S%O|iTbv}sij#yzo_YT~ znPU+ui^4Tl2Fxp-J-g*eLgB30WBJHC64Kizb94@F#lOZ22cFM9-WKpXJO8{h=g7iP z&Kz=*cgiGtFSb!{y0i^=Vdnflqg#e@=9ERZ^jh>^h*ornj}J%uuU?+#2Ib5ti(~1v zm~M!%6)(Ankp+(@3CdziP#hl?t>Z(Y*COV^9_2Z_>_v<$yyE?15hDwEd|2ktO}O7> zi`Yll__R3sugB*f`yhFIh>*vJWj<%D1MGc#)*y15V|;w*-_YvCkk(Z`BZ*MYAA9k| zLA4iO$ozlo=*`D*X1~S9ha>XU;a}pMw|wc{a-3>qan4(DBKy6I_n7daJ7o%FACi?b z2=XDZL@hG!J(pJFBy4e~EN$)K7I(^JPNzx4ow9Y2XmtjC#S3@JbP%lnr+Xi`pKhzm zvSnu-I3e?adyW0&oiYWNcghr3i+=p9OIv^!*8l%sLzbP@kdV2dqe??Z9h^nGD(76< zRJ{03S$+_Jhk);t?F_`7GEX;gr_8drQ|4fiejm8Bet6Ms8^tQS+Z$Yn`(JUVOn%~S zkJXXqi}6oEyiM^>HywlVFK(>vJ*2a*)_W`!Q>d6jMFAB%s5nH$Nfes1%{E;N{HVL8 z1)ay;qm!j~k|8anq8G7$CP5lV(w0t;s0bn$G?{dRJ8N2?o{HioNuF2~(@+F0C-%v% zfZK>Iq~Z+}K|6^!2+2uB&|!jAFd~72d!ZOhMe{fm(@DyuA|@Wi5|Z+%c!i2WDh^U{ z0)^AD9Z~*@0BjYB;v5klQjrhnWa4ikLfWE;reXjUv#8LXK{q;3fY%7R00VDA3gVy} z+5!GSMJ*!2sAxzYlgJ~2(z+CdA}AU~1hLV?E+h6axCL?J2}Gn&@eCFHs2D`Wa4N=7 zF`kMHDl(}E>D4fGURNPw|Z|HMD_g|X7qYB^T zK;1fmB4{4PWQmHII+adR25ly0KE4JMl-2^eYRw@Pk&fY8B(d%cNoQdaM1_-}lOdVR z)Y*oLz%D5jE> zL&YL0R#UNwiXAANZ&A=qX@Fl)v7d-TRJ898mWh`k1-?tgH&pl!K=C*g-@-1)u?qn_ z1aFgD9;6@++HoLY0Tn*ePy|x(AQe*wp*T!MRf5$~1a+Y(XULbEtWQKEDqbH39fc1f zHn1(}Vo*3M4u=#=Fpi2ODtc0p77CV&MHKWhK`MgQ13F(P-A{d?J4Di?ejrG4k}il? z=OrS}_kqb5ByA(9xu<4l@|O0`Gx6aE|z)? zsq2(i`)q?cv<4f~2bcM~){Yvxb!1cQ3n;eEMzL>!5;Wq6{Qmu)8siO}G*# z_+e=3_p%zN1~s22psCfIj}aF=1E8(d3fjtHjw3KLTA!FLI9?xcmfC%yv^$PyJV=vABO z{FMy%Z|(rcvJQTfj5bTp*1LeX^?;_i`wtIrgf*~;UQpt*<1e7vjX>@bg999^gi|Jz z)xSpCH7?^2;!~^H`f{i~Cc9L`$P+R0$ZlVtw8Kw6=jhv@qi-j;UxMK=VW|04*sE*D zL3OL{M=2eJ=+huuKZ`mIdATpT0vtu6`S+omt(Wvb2l1EHpZ@K0;=W7!0WbHh;WQ38 z`Xvg6uPV6jP&>jiNBwiVU5`weI9vlAAK#;Qp8t!4VyQ7W|aProaT0qaCj!x*R&l3hnTyuwxc-ZqQ47e3{1ErPx@~wQLwo*{Ol_>a%R&w>-Xr@@P za5owe8UHqvSB0`SwcTihpT}sZX_r8F`a$@Tgm)0=dkD$nA^Z+uu6|2+b%WPD-LYtk z?z2c_1t5pZ|T ztl)XHv8H_rMf`RYS4BfkYN&!E(31l8FbFN4mdA%pANQ!*|LKg@N^c0l%i1;VVv94z@3vrT{H)0^0Ze>N_=M2cy78BbmwVfg3ZB|c z@J%BSiP0$N{WtgNc>$i$&?ZCS8PinL`az(-#7z(i$RuHeU*af$QUVQzxsvz7Y&sOl zwQ+YekA&}YG;IZhL`o$JV;y(NQSjME<-^0-f2{+tp?&~&oKU3K|+MuE2)p|)#Gvl^jcj4MGO?n)ZtOh+k1 ztV)$(;9fb};n@HK`zWa_AEhU-pAbihydzZaRq*Z$-u6~m_TFrJCz5wMa&oVR*GIyO zhpPZuwyxPiwl!B@CK{?kc?<-xHy9V74WsE2!t)_rsq@L%gmbjULB6%u=+7LA66NoPyQqyx> z@_wyUK9Bg_Luz^Apl1K2UOe8Y(A=+s|5);mv{wC1+>^TZ40*&e7;5(4Ci!^kpL2$l z4xe;;(T^Xc9o@fhKiMuswR>YoHBV2_9B-bqv+|+#_6>Q|b6E0@2(>?X#P1(c!_x(7 z_Fv@17ZYDJq^jqVB? z0XWy`I#wdQ==^b?8{+UJlQ9S_zAJ2RsX>c}_<6nu-4lf80E7V~gy7wR(GZf8A!I<{ z6HYo}MrbLaH9WInZk=$6*|0greHi+v=htYQ;}qsNgqKKI0AVKyJs}(<;ZX?hlJI?$ zrd=RmaeGbsoP>kW+$3QRgkMSM4#DSj2(=+pB;hvt^)Lxh7yPE>8t$tuvR?2=Rx04AS_rqex>r1Wscz1Wuzp1Wv;Z zfz!CsL8LLQlSt!bXgH1MAaEM(AaELi5IBvG(KM&=3ItB0D%?4ZbZ9t@F3@lqyC85H zVV#vU(x|(X#xJ0iH1bG41!A#fVMp&y*a2?(6VVhEgu4tGxDS!g(oX3%gNYannMm7Z48DE1d=lz>*!&;p>J zjWqVhi8Nk-z-h!m;533Ea2j9ZHiwVKP6(VvQoKlGDm0u%ECf!Y3ItB$EA)fY*ad;p zm%^> zr%?+6r|})$D&{nbAn?)1fxu}bLEtprLKB=u4QM!xU!dVMo<(F%<01q*jqnQMXl#U5 zNh6K*NF$?{NFxRUr%@3Cr}1&BNMkbuPGc+tPNUK@A`N=umeUA;z-e6WDbm;kfzwEb zz-dH6;52ri2~NWg8cw4G8cw4VB6Au?A=qgY$TSu}tE5p(`a+~Ju#ZUNNeGk zG&Gz>?3X$*$IX@o=IG%muJ)A(zkNaGX)o>VI#a2kUk za2kyva2of~2To%Q+&PVt&~O?Xq2VAlPY`f#PVyL93(@Mf!6{qt0-V#t*|p z8V4cpxsd~b(@228X;g>6X&i+Yr*UJbNaGC%oW=_fI1LX3PNN0{PUBnjfz#*(cTQsu zG@Ql)XgH0ZAn>^{a)gpbo=l@9v`QMsNdFPiFh+|sJ{cv_co_nxkq&{=Xaj-M@P)u> zY=sx6@!?33Mgas)V>AR#qcsFh!w&+daS?ssG&;bY(^wA;r!g5CPUABOoJNl^N*bnH z9F0(Dl{BJA|25M1BVDBN4g{W5c@Q{_XCZJJk3rxxejF>(SUygqaReGZH|9g&G*TgO z8g(IX8b6_FPU9#9PNNarIgPo{a2f-k;WSP{;54G2Q_{$iX;g$(Nu!YTKOv3l6GR$? z5IBvg5IBua5IBtoA#fU3$BQ(wCWk!;I1LX3PUB$+oW}L3B8@@_oJRLdkwzvooJLm& zd^Ca}a2nUp4^Cq@1Wsc*1Ww~NB6AvDpy4!XBOs?S2Lh*|O;^$=k!hR-ZKa_lj>T=f zX&{e5BLaBSvuc5^(Vr79ckHl+*844qv>%EhySQPGS}OcBhg~0KqLa^hV6!vz!<6z|&yO9l^=c2iXVVv%Ocm#^%wJ+csyChtP z(1L`9v+zbTg!#G$Weqj|I(a&JivMZgL8%IaKfXWUN9a>X3f!^$q>YQ&LSC}AVm`bJVOwL_v$=# z)2Xe4P_LG1bocq2c!%fh5u4XoO(cGbXa!`LJED^3>p6H67z$4Wgx^Ux16S8xwCu^% zv_A6@l%s zc^&r3*c4FYd_=w^$L1K^d2Dp85*8>+aZ*VuG(FidA}jD zGP+q5`AtN=a7v`@S}f9j8iGCZBE*SckFM*qjAMjkK)`pP07Mg}6oP*E`0{`P-f!dJ|C%8QN2TB@w9RcrJD;4k9^4^JHmB~0r;oVX2&Q`sL36?s}ZSVK?&Q`sn;eAu}&Mog< zbCp-yn^o`j@J;}4=e?!8_pCDS1vsCN34RbAyKWfNq}7_XhSsH85MCkSCOlpzVIKvC zkembR6bVHTE|c&bgs&j*0#&T`sOA_~lHHq&<$F_WjaM!=1kcB?))<#35xnhvONqE0N^C26oGMi#mZ(7>+tKQwpd*8IZ@n2TD<0_;R zuJ1_0^V2$U$Mrk}zMriLf$zAUUN7#r_Cv7mxR#07e5TVK*HPG8r{G-uq9AJ^sW@|k zxO(>=Y5ynrs?sxe|B(()42-P2xL;-!^lKFQ^>l&g*991Gza~N8er*QDcY@|drC)c; z_bV7?vR^INTdN=UYdGBau3~IizoLWzFC1ghuY4FO{Ys~PO+mjlza;wg1O)Ea2e9OR z{RIv8YxpLmU%f?Sd%VWMO!lil?blmy<9=n9^=pgTuT1po7Z@r1DyDwrqF}9|FHz?!vuT1JmsSN6QF%jK1N1#QEmz?Uz9Zn%0;=rYQnxK*WIdKluOB-F3PD=ZC#W@kcaym zu9nViNDfP?XFd%0YS|SUds8z^gy*58E#rBZSwqR2n$3degLobbdnU!Bt0iBQ6R4R_ z(M<2{qM5J3b2Ei%GiS;-^Em94W}ISVxtY(=%u5u{z9`obG@YC7Z!w~mK-&vpm|$s{ z)xbJ5Ax;x8c1}^&TWx>NvN3(c3#q_5K0gemj-6 zv&(z825U`4z62Ji-lgy!t$J@R?_E&lO&8@uf={DS`vZeIc9*y)w}HSHWj_dfQT~tu z(Ply~^T5Z>aL( zG!jOfyw%|Uv(IBGpv|Uu*yERzRHm#|}f={EK_Zj8q z33yMesh42LYwAV_yrzz(z_g}Dz=qeOHiMA1+T!a!bx0k5fk?~66H zH3VK$M?>H>wEzNdbUuV&uc;AATfCKCN60AKRT7gya=&t5LYw9S~J5`Czd2Fz~ z#kqe{nXT^hQ4Y_2Ia~P_DDY)#q2cpr8tBFcMDt7^Qt4Mg5AvdGyrOvT1-;UXo~F{r zL7(!Xud4Jp(0_T+5w9x2KLs6rQ0-d2O5XrI(2KsO(!YRS;YIh}q6GKBr-a{^bmBa$ zn+er$*dHA2=eY;*y-o(FmAtdcUk-QbCi0tS?)SE>tTC7JjeAqJ?q_ysGtSpLE z9kD)xo@1GZ)L8R@>{xfo#YzP!Vs*vGIFC`R5X3qHJ%8TxM+gJJB=KiWM;%r^YZ~&J zl_T|wK5NfR2%2;G8Up8%3Bk@~yRhd=KIKyNm{%?r)#j2AuM2q2C6SI!_`?{o zAvikIpys2q3qsk^sefEKI?eEXYxeMuq^B)3JSp--vsyfj$pYcY$9FUWZ-yO@$wv@)OvXX5$0Sc}iN>VD+g@X` zOpP}N@gl*O9p6KO=Hr_VI^By7-foQo(^Elj@}ftn^lZ?Vz343}od-JLglK!Neo}CC zFvf8a(DT2w7mwzDYp48(23z*D+D-{~<2FWuB~@{dR3N{Kl=5s9O*~a-B%m=^AORg8`R$XG{xGXN&1z?nuBUcWOlWB$xw6 z%M`i%hVw*zDI|rMlae7H`CYq|y%@8I>B5KJiRvK1rvRxEH~`Wm*mD@akf`u4#GfT9y1)!M@z z;EoC^&s5t{L3b5QP{A@46iGl+|Aqtysn;(kp{GeeW}77-vr-8t(+0DI51DnBfXoUc zAhW9ykeM@E_>ftG1Z0*i0hw)=fXwbnKukoA5+GLs3UE>aGAosU0z}MKI+`T`F=r$o zA9Icpy0-)r`i2B-hF`FuzZ444TLNMVBp~LN1jK~TReYvNK%oywKxWq@pa9|Xgb$gG zQo(i!$mgO2+T&19y*2XwD^o!3Nf(~5Hm^zt5k481*Iye zu~>AJ0>r9df(i;$a7G1pRZwS%5-mXm(^RlU1s5fV#zp0x0Cedn5T7aIRlR7Lh)kD- zD-zIpAF^Cwq9h$+C3Qe=9d7UrG+7^#8RBykGFtui9jTqQhy#L3f5 zg0_gYSpte>uC~l5RvjUyP^<=JL~4Q}FOx>>y+-jCvgKVyq$Ws$66wCy_DIbTa*7-2 z=1UMpxhqyBk|3*l5|C9`zDSX}QYikhMv0sdGI!;S1Y}itz1{r4Fd?&5xCCUCp;#@D z1P#hE3COBMvAQD(vbrY$S;cNBYq7VGxy3;ev_UG%RIphE^c+`SPRMMp3J$5@gbL26 z;GzUP`~`MzQZs~X4Zj3D{EAhHBzX8GAgekXMb9Yk#g_!285X#ytd&?Hr<^;DWlAB= zsKhM^Iw5euW)X{;JSM^9Vyx5>5aWDVn2iKzpn_Nx43gk~7w}vI2`Io`2`HPZ5|G(l z3COIncmpJb%pxQpvs4MlY=Q)2mM;OB6-hv57bPIGdlHaYuy`+ok4G~J$gH;nWR@WT zMO!8TnH`dV%&tg4W_KhYvl?5(xRF^)3COIw1Z0*a0S#}i3i4HOMFqDcpnKHd*OYeB zB%pRyNkHu!lYqK&RRS`*D*>5>Y*nH~NI+((5^%32plJCLkl7gt$n35Jl$^FrnMgGx zpcEQNK+&d2K+*O}K+&#BKxTI(ATv{JZ&QfrCIK;nB$x(}D*-VD5*)ke&~8ZZbqySn zouZ@5FXL@s3HS;n!OcRL>=I@K>PSEVT1r4ZX%Y~VD*-Wu5)gAm0%G{FBdAh{!2^kC zWzzUcm>>Z$84{3Bfdtf@6DqhP0r~jvR-*BPm?$*)w3G~i1QiTZ!33;4+#NE@lYl~p zi%)WLM>|MBW@!@8Uh<3t2S3Kmrv$W@9JF7ACXl6qd=(U_;GzmjRS;67M2iqWt6uP@ zE}rn?uldoVj!K*0AyLjeJ)xVf9RlfIVm=Mgc^tBF7DZbi_f&JS?rIs}u4#linu^Ew z)H1Zt2PAmJ@DHsdL5N|7hDlJ{2o7y6!J|ebqbfN@Zjh3Oy zB}g%%LU&5g!-x$%B|%RkA@mywQjOG5pJpOjFC#6qrUcIz!$Mm~@T`#@nj}GQBO`RY z1bvLG&=nH&HF86DOVH2A3q31Anz1UhRD%9SL1^GpqR|1yme9u~7-$rRwwGX}Q4~5w zf>Fk?(D@RKHcp1VB*7S?IJ8KDvBs6q4*}9}x9?6jNG<}JlCgDWGA8?d}lMEAZm4uUxV89a+W*8xWr4l}GgaJO(LbNl*2nTE{ z;Z&m~;6Mqd8Bu`GOPFcI0&b9Sx{(0*o`f@uRKV*JW*KRKT1(N;Ok)^en1nAF>45PP z&N4Cp$4Z!OWC1RcFvrLR+#%s?BMTw$1i-%GgC2nICTh;~;QA%N8-Ty2B_wvup-5f0c< z!nH#c;Y&t3;8h7X z85w}zNx0d_0=zHb%SJ9>-3XDq& z8ySEtB|Kqd0VYWJj*$yETEcgYJiu8JzGtigTrc5CqX6)zgzp<$0Kby(lu-!yqlBl8 zB0#;J=<^xl7@#TPS>q&NZ3)jA#em@weqdYy>?C2aQ39AI;d$c*;CKly7^Q&oB>d30 z3%E|gi-zW0qVJUOlHm_{M8eC433x@qkBnfzn-X3zLID4i@M9wk5bLgWx%k8g2Yf`r zPmPv~+e!kb1RU_S}J zGl~G`OL)sT2DnPX?~RjyuSs~@CF_N;S&C41OrZy@U9U8_@acr8)1N3B>ck&2RtI- zpGHf-vl8Ajq5%IV;a^59;9Uvt8wr4ZF{00Z8>xU*CDhC`z4h1+x&aii8iC zMSyiB3^b1cHj~h8o&@YDVMVhTu&0EEc?EEagr->nxJ<$a%^QH*Bz(v$1w1BUCG#%e zMF}gLn(q?*8wsnJ{(z2-qR&-L6EIl9ATt=SiG;ys2w-~&tC?Yd!z6sz3Re-A`3^NM=UzPB2a|_@;3G17MfbUB9gjoc5 zS;7Y9F~A!VHZ)HH{wCp*W-*{|XOU4O^9o=c3B%12z<3E8n>PT*NZ75-gG;;y3OW4WG1N>3K&gLq>za)$`3jhPUhy=TsTL5cH*wriqY%Jl^W)WaV z3A>rc08=E4Gfx8cmoVNe1{^J+$Giggyo3p631E(diRKN!#S$i&rGNzzCYyHwcS+dY z)cmoEN|<8$1D=zxhiL+SE@4kI81S})sb&b^eF=M+VSp98iu9i`!vSka_^jCy@JR`K zn^AymCG2Cy0>(?&*GvHHD`7t~6>yA%X=WPWbP4;L!vJ5DaDbT(xL(46W(MF+2?v>3 zfJY=8Y~})Tc2l%;!L(NrywLe5{@_T0v?laf~f`I z##O?Jra#~{2`8B*;I9%+HiH5E@n#2axHHTUz=tJ#-V6h5AmJ10BGyU%1(N+GE|G`U61&gcw+IBmSY~2+4^3T z@#HvSMt~zN+@f|-h_Z(>`@rr3RFlXq7Ip=~?kw50tRNrGOm?MEttY#1*p&*q@5t^& z+pZGq+;O`0F4_543~-!j<>FidpsXH=Hz2I8>d|(11~Zb}fY6 zd~dtzu-gySD`b}qyCh-vy0={*?24f}M|MYG*H_q`_O`19yWgSumF!NyZkn*W<82oL zyE+~`Ssf2Tc5jDWzOZ`)N@ZLs!>%J#oycx8>Jy z#T~E<6L!BtnXNyPfVW#8M2KQg5rTRcN+tWcu#1C=XT?F-^%r)rP-g4nQF3qJ05wHW zW0+crk`q1#YO$b}Fm+6N?E|$#P;WAI4P_zq>19wS1oZ`!N}nD=!;VB{yUI{1@j_wO87iKEIk5AIw1%@il-YV3$`}f90aQgnJ?kB! z8|+?$Y9!fBf!#C0Zmzf81F(AqDxM^VVK-RVZGKEEJ3~R9pX{g-Gk~f z*H~04iEgA2W3e zC9iasK*b2^8>Xryi?#wm4Hr}uD6{o2l=rE-<3Nq>V0AYXN~OCMVAl>R9*jA#8!1Ax z<`6wmawcw2{Y8jmrUpx@BB;s2t3Oi{Q1XSS1E}W(HI}J4DEV4e1=I{dy};B;lshV; zyHA38K~PJeRJ!XzcVB~wC;xER%@KB+ImA(vr4-^gs60U(^bYX|LVN=i_riePE@AgI zhxipG5888}UKiAlOu4(``dzUdssZdb21+|N*cO+F6RH>kjF?C5&L7;vTR54T6B~=I19YK{a^{b?UK{XPS z>qn-1Q$$|XK>aGbbSSg+s*-vb)LlV6$W&cPnV|jyB-A9SWpi_iF*f>e42Cwl_(m1gsB!Nxx33iJu9dt zOeLY@?rsG&T2OIJJ%^GPpKj4z zXKEHo4mc9jZ-Sc6)M}Ig52H^DL1|Ie@m~g|(kD0ivX4>qC{TBOnr-zM}8ovLP60_ao{Ev zC10(ogL+N`{GF+ay@b~wP`!j#0F>E!C`vvJUj_A*n4z_pYLAi+%6d?X1r^CuKa@OC zMuD0r+Iohmi70uXGC_3~ZKX4{5G9Ysd{8R|mCMvCC^_YNpk5FGH!`&!CGQ(Q0yS4q zuQPQWC8t~i)DA(>Hz%_7Ur=&4dV(qxR4G#d&xn!l3hGTkIibwfYoKJW>7Yi6l!KUR zhO%x=oEtBKIxf5#L8+V@6%is{+AV_J5plkD;Sj@6@}!&y>H`sCAX76?@<}-w)LUX` zrZBY}CEu;Q1?pqrmB-W(l)St&19ewW2be0B)Kj4T64Ys?zCy`koeIh)+B(ZWW9nCw z+`~zr{ucTF$dvn8F&j33nk;(g4<+uPQSxzJ04hKPtjkmkO3te}s49YL%Tx+VK5bTk zswJodrpBSq$lv{vmD70l-!M8ptcL@Wu}gx z?2*LkLHqvREJBd9sT>szKC=qrXd4pbB2OdUkY z=g?SCodop;Q^hEG+B^ZuBdF6%eTkAsele)+;!s{?>Q9v1!xuo^5!A0tRq7{ZR2xvq zB49-*v-P?tc?@3yHB)$nFx4I<2b=|Jqo5+0dIlwTBOO$#2$;fDI!Zp2n?O|;qcM`H zg(!K>$AfAus9dHBQ1YCQ0CieWYngf-B@a|2sKKJG9Za1-$pJl}#t7;tQy)nx0n{YX z`3p?lM9GWIP*4+u*L9};M#C6{$T3CG(oikHB(T5P~xJG^2boD6x%?}7E~=L zm6f6j>|&tet?YZSTPy6^a)_}g`Aw}|pbiOY1XGJq@(Hj6)DkiC7BIC9B`*iPL47E^ zUSaAeN}fXvKz$;pgG_yZk~bI+f%;rfr2urhY-mlQI!hA3>Ee z_s6cfte{_Aq@RLwUv{-(1^rATD?V~P4H0h&qn!1aj}|x62iwbd>z^ilp>)zmT(k8F z5c%Iaf8u8{j|qM(yRMbgJy0hFwSuW4N!Ql0n!?mN zN%?{@1+|K)Ln!$lQ%CxvhfS@3`=RWp{QBmEGz_wEL)Y(u*1|C7^Wjs{#`5_YO65OR zrdNPEJ#Z96fE>NaAk1TYXWv*Bh-A%NL_5JZR_DsU$ND;HK|K%wQW5Q>KnG& zwkCC{t+uUKKz-L%+t#G!-v+}!$CQ4bgW5mA$~#B5tx1jl)$>2nFiZoGPrb)6Ow%5~ z?SRntfwKAlm{|W{qc>v4OS`GCi*0N9kAX5?fUa|if_j=bQs&Y}vwT4)8`rCle-2YmfQXMgL|u0DYA4)ircSHQb=eK2m{;854o zzSenF(Kj`;08D#2>kQxCp<5*|efxyI(@B^;=$nS0W=7n{U9(^i?5^Y+`fFT(R)Ydo zM!R+=s-WE-Z-{oQ`kI=P@~BSTkeRD9ET$(evvTNW>six%coehn1O$C_lUlyoO1#{^ zCB8Y`q5drFABor|+XuovnvIeI9K&q2eSAorZmVtUW>9C?YTKIBS+?4?ZVz>?t+uU6 zohQ^!$7MRTh>qOhhMD+z1l@nBxwv5Z(qsA)q`jMXA=_bT7Zp07EJj*VW~ z&T|jsGImZJKE|n)QZ_Y{T6@|racWbb;3v*BP(qHX8|YaJQan3^9*)&p(EJRkN0J<# zbKuJ!$uU8tLqO}uy^K!Hvii$U9(fdWlVyTVeBz8#3z?1{HG+EE%T6s4ili=7q@YOt z5vu+W_=gvx<|%O|ObGNmven5y(1>xNADWDsql^m$?D~quCuc&ieh`zM+@C-VHpT&6 zMg4%n^Em{5{#c#m&a&r^6^nlJIMdS}2g6Jmm0N=6QE7_ydcxa!cnjr~Ma?vWx)80G z%j;LD?7X^{&nwA0ue)kq6wvdk$m<0NWqB1+gUylGVd@9vH@)ju3E%QWt=Fl zd9YXVN)E`2PaI9;fgZ)OZ-D=3td^>Lz#|r%q@uY_%9Ceh|?#m5v4dtfcwDyy?`7 zuIR;!Q1g$2`~iU<=sIK#ezP9OFWI%$X+6+&90dD8vxREE=z+l(V6XJ6RBgB$8a@T@ zveVIjmX#KFI}Y?;UUY~`$Ab>XVrqHQ?*O+HG@r~#m<5+W^X~w+S?4VK9pDIIM(2(T zzXR+K((2+|JzcDY&A`Qlyyn!pB;f*^-z{)WinjVP#Jsmf!KjLRugdaEE6Ld0s znVzdJ5F8~HcYtEjFJ`22Og!7byFa`SA|vLlpF5>Q2SI(&c1vvE5Nk5J z;~tU};5k)*`3Qw4bfZ&CgOJ>5vr`*I!t)R^An@S8=YauMu#yc7MLPA!k( zk-GXzxWGZ-c?*192+0$mX$)bZuFb^nNPn>jS8CE%+U(T2LP-4T8ot0u{_&ICp0lw2 z8H(giu)7a|uO6vN>nTAsJe5Fl;|T|0GDu~E13k}!JxwvTL%0k9fAJ+~s)1cL3rv zovVikzYzGvZHFH}f@_v_v&K_I-r?~YF%hd*NBG;PtIE<4c{1$iDfD2E5^-OaG79|( z6n8Z#`Omqu?h^bw*`-~SfFJlI0G{TMdQIFBkenc{dMTTxy0jA#&{wrDN&UMzDJYW#R-{0-^~sb zLz+Tg;f|1izHn@c+l~}^CR8^G=xfrc5>T`Z3CQP+1mxos*JJ)Jvnc`jgiAm^CnX@C zI}-3$xW%H*y$+Fpz9!vW0y4WI0UZv1v50V^5h_Sf!5|69XPE^1U%>pFZ!M*G59w!Y zNBOPCU&q~sn5R1i>)P6u*p}WJcOMGnoywWmSXTx6HnAn+@IQ?{G}ZAub|@9Q_hDBb zD&BzqgbjGE*qhgdQr*1nz~*(8*!yX-^@Q_Qud*?*_0c|ce6`_tx%-yiy!OZDwZPs< z+8fLjP;ar-_6C#Gg|^zZUJG@Rt+uU6eau$d)~`W*(pKBnq%IcfrzgGVvNo@M6I=bu z=C$9yZeEA7Hm>hUm$i8vVr^EhzVEU&uY)bz_N>d=ybiK9ug%Z7tj%kGYxC;*z-4V- z`&*mWiNL&hO|v$y74QT1ym?Kx?7uqivNo?{6M6GG<$}xFypFN>CKp}S=5>_S{*X&9 zYx6qN!sca{wRs(3;k=Jr*5-A%gc=M*}g~SZc7vR4Gk?>AAmNu_-ue!8icIM6NG0G-8v9)I;^!DcU zo)VHauO~n%x5EuCSiR>vf!T=;&u`%QlEPP<4k|qdbbSm^8QtJR%bPDKb3uQEp|S4Z zXp>h;Jz4>ELaD3#=4Ay`_U5JXXG$E}yq>t@Qa7)aKe2co7Yg_TysKclmHg zX!AM%q}3dcQwha;4b41*Y|4#O0aW%lMU)?>`oDM`|3jZDc~QXM;mzaJ;AeH5%=Kt+ zTcYWy__Y|P?htsK)|+JW}YQas*k(K|i~D!mJ|c1;c= z{n||w^tvWI$M1yN@E$Zg z7T#t3x~kH9LBHfh-%;r|Kwq+H+Pnr{wg!by<^z}oQ?SvuOF3^|^Jr)eBlZ$HZakosP<9u7-1HI9cO^YnPZJy+ zi@3fxe|YnHlwj#`-a`PH|MVYF!OKo;bj5lvy(*$#}uN}W*BMMiw>;?pNUR$GK zf%Ce|ln^+t>!7Lgx;G!`Rp<2tgur>V`RcsNw|v!keHuZX*RK$K=e50g4wFe$HU&iv zoL3uB=k-NUGfk&Qwi{I{BHi#Lh&r#|dk<^sy!uagY9rQRy}pMPIIlJ;UF3G)3Bk)< zo!3R?F-V=)b$&pc*RJLfr$U_9`F=n=pL!Dz?{lenA`rQ&x$CL(I@=G3^E%%Ti1WJK z1SCmYV|vwj9cBk={D3&Gb4);-*QGun&TE|?5a)G}QEGKw7n<=@H?YR^qB^e)en6bp z0y8f9BCbt-K%B}V^9-UsVGlnbj_5EyAdYCQACNR_{eXCwoBV*J$uW0oEoY7&kTfg( zfTUUD2PDmQKOoL)u`v}|orQithGU%{kPHgU6NA#a+JU})K+=ry1LC}{F@caPdHe|W zxQ!Fjm;z>Sf{uRW7qeWbXnM;{P%zTjVeyGq&a zvkn3DsLbPYoBpPE;8H$7bS#JtTuO;92%-b_<3zU&q64->7X{G)yVpp5UKd0MY>6%j zq62n6qWcEX0b8O=P4v*8+eV$nFW7BtSNZAT+0M{e`$nA!QI?V0RW{-6w?i8Vuiab2 zvO7BT?sidUvlo``7+Sbr)cM&8Kh{3#{9%Q&J4BtokJs*-+fr`zS$9;gJ&ADV%Gl8n z4G;cV!uwa&^F9L}1@4%A-M2XuctB;0v)2+)H^~_cqquUPcXKpi%fv#7I5>z{IPzvVT6jQ@5ydiiA5>K6^pL z89uEf>Wr3f2amt_u&8s1gxh=k$|IuAL<#R#*^}dT!|xs#b#9h$SC4-(#{*_bxQiG5 zZ3vwpo!p~Rx1cAS9QC~T?jF91QwI+TznfRzZ{4WpMfdga)rqL*r61vyzdITAy!698 zJatOc^V0ix;gYJT=cOO!g|9z5>gbkwZ!i4mxlwOb;!rPq=fzRai$BB*uf9C$twQvu z)GhJmS45q;|4{#@U*%Mkc=)e( zM!i*$Bfau2ULAFsF=qM4c;P#@MV&ShKGsYB=#Hqfzl4wT^53yD>hzRwsZN@KeMKIi zY0U~qW7V!7Jgah3_pfa0rue8> zH-Pxx&}>wT?f}|M&<&ZW6uqT1>ih_hcs&!P=;r|6Cti!5PaeZe(dzggP`ST*CNt|r z$^5nqG`T2iZ}%Y3xq@DjiGC5;+x?Y_T_OIa4 ztMu01#M>+Z$*-!+b%!vQ)XSWR5O|r3tbr0Qvo)YuSrCV@T2h};+1`DIc+ZcNZv)l* z>M6Aj@94_C-M3bmWNeRY@i6&1&2aZ&?m}NOD<7lx`c99uaKvV-GGi*6x^Lg@wKNs9(xyl&cfs&|>2W5x*0;&M zroLmn`qt;=I5r`FEcHF~o~W}CpzK_PtqAI*jW_v7eaCj;^a`NXw;sXNcY0*D>A4=# zI|c7Xos-$|$)Bd?&`B;>#z`OP^3N+CT49377ktXg+DEA1ZmW%$CcYBo+M2}MCt8-GvA-iK1 za3@DdRdAURIg4xA!B0k=i$thGxLSl22vbG4b79oELxj%}<{~7&r3s~yH?C3oKuamGo_KclY> zd4@aaoe?K>1Q++Or=!k5gyf@eYT?Ws9BJ;pMeGMeq}FqB?;`XaLh=+Y^};y}&Kbl` z5Y7$4=}zc2gt8q^MVQvNz$>G182Qga#v&9f44WP+mz5N`za+ z=g6qvwNkZv5N<>$7qzJdy?1Cg_Z=cdUEEy=qB7;8GBZI%ReCM*RK*>IAnKA7b*TeY zHMyHuQ4@D1LZB-2P+Sy!km++VIdk5K#kzx5k-z>V(`L$xV%wPW_7}jYmk;aEU+9WxUm%sxxWNGT|M+IO?nv-WuWE zn!y|KaU?%ATX8tbV^-Hz`f@Q21|s$=QCIc<=wdyJbk&sU`yL&(vul!r5@zA@DanGS65ZT`%m5-PHBM zJJgctLV``mzoU{*s6l#-n~JXM*{CigEC)5q6uPKgLml!TAlbjL_Zf@YUl1jW+DSQa zw@8SxnbG-?sJB>s9)g~<@(2xnPEYxSUwwjp3bbH88O-G_cFb(5pt~6e-fjj$u$sNo zv{*VIUw1P=z1xU3sqh=ms_4Sjzp42y$&UtmCx`kQSgc0=!@#}n^Y5v$DKOZ;`c=1i zm3i(iVBH*8iJ+SUcO&S@wqEx$yGf%9#ePDmmTnHfGPiKq94eL8Jx*~)&HJBzoJ>^E zkK=?W{kVcyUG#7IXs91+{hX4-E8$+B;C)h6@F(cUyQ!Y`;};0pkDVW|`mxruH0Jl? zC}>tcE;qO?ojpm-%Sr9^qwESa8d$seDd0IitVi19Tip3iQ;Yu+t-AvK=HSY*U*JBD zphwzHoE!Ca1y&#gN7`cFS`QMkE6@_us#mGOwcte*-0?xXUL$OHF>o>jkF()tfv5Pe zciKv-{aj_!lrC1k2&RkGPcYH-q}4ivV6l3hT~k)2Q(DWooU)p4plaz{S+G8z-;L;k zbr%F(u%3e;r>&+(mKkzi$YmRAan^_~YsHh6EL`i;nom)+lm+asNUaOlgW(4Y*gj2_ zkOk~kfLbYiHd<-bSDxjr1=VMxrxE;TIXQi`-4J!?WdVCIbukOrw?^veBiUovnf0N# zUN2Oxz-f$Mj*?IO&Ko*;tjd3pr``2v=Jfzhynt(ifx8O4w6f4${#exMsIVOAn(>P@ zahLG~x$ircrJ89_sgqi&VW6I+Qad+4oVtrU*-pJMGxf9K)XT%E`?;I#)GISnw_W9z zJuPxfT@z=WA?W7HtCdZY(%f3nrB^ER-Rod$Ga2g~^UNdKJA5D7ulD-ww7s?o`ER43 z7eET^wT)^o`~hn0b^JC8ZErnO<$qAQk9*wX+{OXQE<;#|a7$z<*CN9+AH82dRX=35 zu7#vFqa*h!wHc!k0^8fiq!Rs7+xsYdYi^FQT9^L`mA{wNX`3;}hSvhG3Sd!yf~}qc zsM`HfmF@2Hyw!9Y)uyjs;x}CtpxC5VyRePa3&4Ypvr$cbRXFt^JN2)m9%QGsQBA#f zICZt1dON8%JZF_{qni3jP)l{E*r|Ub^_6yN8`abU!l`TR)W4Iuxt-cZHT4(IhRR-M zr`|#8`QSmX*{G(zBAj}yoq8v!2imD^R8zMIQcsUGnxyqI5l&*D_0#NsR*BC%aP2Nu zEdQvICDDPoPFmhA2FHs}Hd)V|SM+vQRTK9b$$*GdC%JT&%aL51q?n}|Vf_v3DOhTb zGZ=j-pGQ*@+ZSF|w6TpMiHma#7gj3JAQ+FculXhww z)zlk;)L3eniCgXTxo2d%doQ(0w^2=hBB-U$1wUDaJVxqk?bJ4^sTYM)_pwvwk$SV8 z+D0{XyO%;`kFZnkMQRs3=rM(O?bOXk-RWhkY#Y_o z<)Eh5`f!$dsY$KRV|$+wai@cy0FY>vfesjz>%I=ymH2q)o_s>dBo(t<+A-^()Bqw= z!@0!&;a+URJ!>QUIN=qZ96=M`W}@F@yT6h1uW|>MzxZ2kd~w$cdupaaR9iVA$%>uF$g~)ByP*#-}`>9`ze_{BCN+?JuR%wWNqhq z@3dU^4p_et?_Lhed7EDO9qL-E&+ff2>Na~d>NMpbazZ*Z1deLy9tRlorwvMfUIrNS z=eqxQf7-D2=UNg6{TV{(&qo1+{-lqbcr&WM#S|gdp=y2>-&lSv>g)#)@6Khr)vl^x zkt}xr=n(+!RS2aBsbRvsF_Vi6>n?zDt8g0-?i22#!aXg6D{idY@^!XmggXS`V&PuR zMgQW`htAL5RMs0lL!Syd&_?LMRM2@gum@$dVePz$lpJ(k2&MBD0|uQJ-~06@PL8RO znpIK8R2{zy1&Hs!3AfSYr;%oEd(fz$8#B?{Slj)E?6(5M4}sFm_y7p03gJGT$(1S&gYvv^uSa-8xbF$~`V6jCaS4ZzAJ)8HiT6tst`cXQvT`@K*nx zr-1P4Ux+6a*44i)@WQKqHcu<8tAG2UW#QGo>5AvL(i=u={;{n2PTaj|KbvIJBO`WrnAp|f8$UN2FwI7eBCJagHX*;+$S&^PpP40y zRS3a`QMJiOtf(w997tBW$S?)LUu2M$)@-*bvkQ0sN9rmqO>Y?46lvwj@A<8q9+_p5 zYkhxx-_&<^dc(*jB+DoDfxg?$?I$@P68%FOD zm-O zml=_dxR#ClChB}C!tDq@h_C};hX~8RjXK$HN(@2^gyb1SFOnQ(cjtTp?t5f;IYMf( zq&SGAw;;ri=d$$A^!V!TPMk<|sXaOEGMIQby1R2Ak?wMmABqq^my7e4mt2jy?CxA7 zl!K|t)j~NogQB}TLxfTVrA&mG2xkb5LZ#2!n;e@-p|W=&o$kK3h0PM_wxHu}UeNLG z{qVw_Z}ViA?mQUw03?sTE8;XrcgdF0;vYCPK}6~@F75?{u0u#}Wb>xrDYK~~S;--J^O zq(3es^gKeDgHVT1elNM#3YRUV9hCi|6no6psPiU5xhRn1Ci1;_ZN4nRdw}*l7!nX&Tm%cq*0WW-eaFRvu=Q!2Wka^cB z)r)|;aubhiBJ@HSB*HykM;#ZTd_7wxGa(O}o0r-u`zX!P-QPtR1vg8$@4#)2keo|& z9o&JPA{D8H!YPORf(Um*enW&^kXIw{hut^xS(o*?{nsq(9ia9>J!+eff56Bl?uC#7 zztl$6H+&Y<^9{Yw0(Jk$LX-z`70d0)lSC+<>6lFdaU$wqg8) zGA^BZgr|Li z_G69U$Iy>AP(AI(cM!B6TYO~owSg zKCIg?i=-9L9Kd?vkM+X z!F@lm>ov`WPXN9k1lQW|iNFu~ux`URiz)P^k!Bm_12El&nU4+7ZI~|*f^C>}c1^?E zFbxK(mPW`n%nhHKZJ1*abQ|Uc1aBK=yCL_5T=v&mvklXWhnrv<#-|iWezFa-i`2Re zGYWpN4dc^P3E76}1*l!8+c1uKLQ<3`q`N`&iDM;#|AZvlFg>hCGW{LFDC!by!_?46 z);7$^BZF<2`kkIm^pIK(9hvKHM>EsgFn#{;;I0A>8(HXn@uj^DQ?lFAsKm&oZu6fk zOV!7q^4O)8Y5=HN#gdi7Vd2zW-0^nmL}u#8!>PxFQ}=T}w^Lu3nL7Vxzie+Crp6F- z8zwo@+lEPqF1aJ~-BQ^8Hp~dq2WqbmqW!uJQ<=8cHX*+f1^pMKz+T&^_5vRT^X;{6 z!;Cli>tfzHBlmGnfuP$k&mp9@VI~-!w++)ERXvy4y6;A^6We#Wx0kEQZ!B|o*jVl%ee@P)ulzcR455&tZ;xQJR@D$!Dl7ZJ1;e)Q;YYo)WF&W zGtluffYncG`-|l#*);JWUV&w*C5)Y_o<|_2VEE`*u6Mxh@wC5W6Y?L&Uz(Yl>)DDG2!X$}#N;DY5P#`UK(z+F$kVq5 z(&AxRUV&PfdzqJi{F>=6*%WE*A=~}dPLGT>$+f;m{$~88`@H(f0Xv(Je;@Tdo7Czr z%|;0Pr7m)17%Dk~;v_|vU&J%8y%<1g*v;j>h55nHvkNuGNtv7Zv*K8COn;nqkk*o??e$owVuAxXXD(Xy(Yd&5rdTtuV} z|c1Yo|f1*wVIF&Et`v~oe5dQ>hi)o!YN1U8r}3 z>S2^h%$xXE?rQMo0o?Pb#p{yIb}l7`=KEOgd!T;_EsHwlu7I{WgC>5KdpPK)LK};) zQG~e&TM?v_%1Ku%t$8of#(gX&*Qq2TbsiV@azd9QBn!FJOGkbf$#YAI-A_0N3MZe? zVG0pz+~wKL-SNc!LPY9sF75zA zd2nV#I&hUg)sA7N;WC%R6?7kCC{#O|lOU`eHdnRdQn;!eUm#f8q078utm!PyklU6~1t?8D(ft&5+%$)FIj!hBc zR1d>5#VkIV!yDW)>|Y_O1o`fQM^yV2^)*@XPus$6#)q~O`WM)ldC@89Oeh4P6Z zueJMX@2W!gItY5}+Jq3CmbPiqUyA{~{z~>?rdOlz`Q58Jx_R3$LqxbW+`EP#B)2hf zYGuxd-Mb_&*U5hi_NNbCnhxSJ8a5aHOSxz0BTcFg)ZbdT;0ufH~R7$A!qVwEX^IYd#Df=vhaR{l2 zT;jdCl$$$++Mu3H@{jX#odH4_%0++Y5TZ=Yavz4_{mvmd9Zs#3atJAh5I>6uw>83p z2uZPp^#Y%Z4SbclsSUgtL2O`BY@qW3FzZY1%T!HmU&|Jr?Mtfd16G@NA+c)nRv@U& z>sS!jJVy2t%9~-@B4(wkdsbKX87Lb8;!kFxy|W8aFB9or17$e^Sq!+B7t5F|MES@f z$Njoxu5%H9JD9uZ)gmk+W-3B_+dW~vt`AKDEfiWS_?<*JnV5qS%332Fj*#g6HphXj zf@H1e>wR*ap~Smi73Mmph_Hy5vk(&5ndO|bk2?vl8}aTl(0hw;GBL*@#24QkuGWK} zv24`_bOV4p5&rigY}y;ch!8K!a@ z%z;&>xUE~~IunUV-N+>=C-)m<(lFn>6Z^?^#237%QF(6jwza;Hr?j;bqASC5i1GNIn zT%Q1}zZmEbEWa2?$}a}$1(vz~4pq}%3v}N%SAQ*#lwS)tOU+!LLahE$;2Q+}rND9R zc&ZSJ{3X9*5|u!f37Tp(n}?0gT--(bBSa377JZFSF2eg1dL}~I0|;Xg^fv%?!e_y@b^BcJHvmHrg5Ll%g350I zCK9Q?0eA)>_zghOORRtL8-TBfltcAys}2l+{~Le=sQw0EFtPd@fNK%#-vA`9q!u;M z(2H~2r$MI@k-D9WuKCZg2Uzq&*Zh;4!Rttc%H+8dJLWpuiEuX{?3Uzv@fN4}D@gP0 z@K5y~o|tl^TFlSx583Sc}*JfqTvY#OB$(T|};xz7GXxZ67AIz14QvhPszGO*~! zOk#D<;YbA8b4bdbLqcHDkEckj`wcBRV{`?U{e~J~y%&rjR`(iKA?RL1m;H17y#@^V z9Vo#%)0PXVn(E1`q9^Z&o-}mHbv{Oj56s}HzKj;$CBnNO-Zcni=ORo+NE}5&?2JWk zIs&GorQN#bI#nX9r7~j>$|fURj-U(ui>STm%|+03p?|;ux#@-eMo`h4=RkF#{|^Lj zp+7O1EOwdZ$gOQ|YX8*D#5swhFX5+cxoJ;pZmLbHin!GIT=XybGQ^TsRAa`wy}RW) z?-1d>M%f=B#Q)7@n8~57bd@|sOb1;6;3S)@!ZRYZYEJ6|G2}$Jw;^;yNFB^2-T-s7 z$s({U4V3gVK51FPmtBKAgszeJcRLf`H@P$B4F z{3oOtc3b2r;vFb|0L1^3iON&NheW!wpsYhc`Hs3T;>@?kM4uuK?V0PG1K{rNk?UM4 z!n+8Q5aQpXSTzJ}85hoSD_s ztp|057Cj`_IZbHYGHHKD`nml<4;9*F2>pbXlS#WJGQgb=+Cpd>5cWloKRtZZVCpA+ z74^$@YkG0_VGm3XAK9oLJ~|mRID8aBmR%h>>$V2|34O^W{8G1)!ei=?Y!W^CaXv zPl(02p8a9zxt?DTf^$6uF;4|#X-UrY+)Nh1xt=6gL6GLsE1}6L4$KWZB4$a zTB1B%dK+K*6ojxZ9pZ{FJspbr(#sISzO>C%U;1Y#>Pzo`Sf(#clRP~yvKpyXt$-Vx z?MfwE=WiecdambtLR_ipb|`wj=iolHo^DT{@3FaB)hZ}@zUMB4J)G|;F%>a0 zDBFDtUU0_8Mzs;UK!bBWeNEb6vi3ea*U`<~F$m$aJ|V6&;sGeSq5AbxsjBMB&#d2af`|7FCxlc z=F%XspX}vcK;$aIWjhc)Mo36ObL@iVd*#f_C}&5y97-B+2ye!Djiy96t#&Gb)Y)>m zgiG=eda4wx=eLpU)ZqkD1LQKC%Z$irT=g$5zSTlAP-4FFPpN9_9@C$m*4+|00$Y&h zb%4&O%dq*E0SCumZB)(?zXli_g|)#w9EG)EJqo+mF}dlZupyMAunEB6C~WdvnlO&` zVaOvy?#>jSb1 zG^T7USx*Vffjnb6=L$iwN{(m(~RA-v4IulWy zDykKzj*W`yJOLP}jt%ZXb!=Ew=Qk1ur>H|Hs?%>^rs^bUK>m%W&hdekmo%cYE z>a0Y+YP?kCZuapkh7sYq2pbWS4|7=rtg7>GViybi1Hvl;Pvp`7tVXHdpj_t`fp0>% zTVOFt1#i&bqcBRJ5-X}x_Qr|1&dmsFol1dKhdP{K=}-?dj3MjPCu3}9rpH#T(>TdW zbm$4P3UsJeV$q?qiBui>86mJvBkh8W4vo$z=RfIkj1JXHo6h4%RA8Ol!)a7tp`14} z^~k*zJkv_Gn3v-;+sji}y`9{ME^UWc1dwRtD7cM^E|s2?>--}}#O3E9HduO7B=hGX zHmtfdgT#R@g-~?qL%^^ZDxneiGts5CgDqWZYw8=Aq0yk0E>(M}%H8{kS6%uBA<(6n zz^Y3}3^BU&FN8ps>VQ?3J|tFkspH9(E;RzHE?rEl>e7f|mM#_j$LP`$;NVU-!yaPa z9?i-aOUvwnj4mzDDCeLH1G{H*X%Ts5 z=+bI(4RonN$_(A@+Do^)x3txGe}rCT5dx@4oGOP>M;x@3cU&?OsIUFtI2(xniJ zE}ah;)}?~w=+gaFhq%uGrR`FtF8u{+bV+W6rIKo1Rf&6O+)A}1Gu0$eFID` z3nz7p)IUU)JqM|26yaNhHX`ij;^QH(MnqZTq^!m4yCjGXYPiYDOK-Y!KuuZuzQ@x> z(`-ln^daKest)dl;9UXYKar=6Rvm;-|2L6t#{?dXq;- zg!m-vtIZm)Dl6Ch1auC7+bo5ffDm^wXeTt!&UTLjEf(4p2z^ADk5DSY283Y<@iD!^ z`Jd30g!`1SL;~OrMwlbQwFvVO$`&ImL5Q!&sQw9qNcb)2Y5=!Gd9JfogapDSg!n|B z4ef@Ua7lI(_eRip0PZq`MI!u+uneK>mkRs<5sn#=>#PxB5<&w)`~jWu(yvt?=!UPN}N}8Ig&M%^K+DlJ0DP z#4#CYuYuj%56FG6fb&L&Gws!{#C-rT_y(C>qP)ia96;|IWHjK`NHw)DdzPZ!Ah+ZJ z|79sn+EW{8lNwII?QvSJb1Fi7EBF+<_IGBTn%YY!XF@4NNc@f}*_5)?&En5z#69%i zNHey0t&CO{nbkJ+fMk8^p`1Ojkn;9T;wNRqJ@k2`311(wSTiD% z;dp=XH^^tU0Y@_-Pk5MD*L*;vdnXN8FTx6h?-1CPvWR6niT<7FWJx`ap>)rU>?`ym z;2wKA50nVW94?IlP0DJKYC*tBrnpwWrBR(zRRr8iVV@^h{Bo}Sn|U@#bzxFg-_&)& znFnW@aO6*we6-b~6B>La?}nlUN^VmEB_9bRQ1TE1CBG9eP;whoC0_~ZE4fz_CmzMW z+-0h)>u)bs9gy0aNcU5!ydOgR3+ioC4%?TXIObQf5)6>~gG>B{49bA3vvb|!p}Z=T zcZ4!4laig&&%GMTzlHLIQ0`>?(=SL&dTFPuzV0(no&-p}z-30{4Ot_N|G+ht?{&01 zy1^XbZibn2Kg2uLnr1}MiJ{36q zjX?TLbPtfYW~sm}D|(xf#o zV}r*NeGICRtmH8$dWQ8Fv`Auk45}l4eGD1~8axISn>@83^B7c;QO+Ida?ogT_#31t z|A$*vu#)mZk3j11m)%LRX`f#_v+-s~^nSdQBODD-0?*7w9JA~uci1b>-2kl19LbxX=jT{bZfBxD9F^1tawO71jvZsEp8bz`%F5!99$S4eJP3ih+$T=q8OAz!o5B(7|-&_RA*U=jFu~U9b$`j5rDfdRulpD@9DW5<{r|fG| z#-uGDka9e*wxtw7Q|9|A*9K+Es#&Q?spInrKEyQ?<*k}YV}{uouO;IlV@$@a5H#bj zNT7{*3c;(AWL$1%{23WvM}l<5)dp5||ALH%pKmhW7eO=rh6I}NVgxT^c@2pFLfB$y zYYwkx_!kMhWAOsdFd6p{xC!u!0W8}uBg{@#Ux8)oXZc0e_Di)vi$HbzWhefd{*3w# zX!L)xSV>`{mGancFYZ>}E+- zM?=x=m-`XI+b=d(tNI=k-G0fwbdTFFwN^z`OFo7dY`@s3Hlpce*7nOhyJE84H2_q% zU#>z3Z@;3$MKolFH15Tk%Xe#FE=5Cw_j|oHsWO{y8Y6Kkg@$D_m7%(-u*)@o4oGe zH~ao!qjLY~ex-H)m|~Jj=kDSDVZ(a=m__2?{t-gCf1CxFzJJK;RHm8i#p}=)F}w{W zc%8~jgX&=jd7a9YSK-9U`%zAqz)2nvo**W8or=vDOL9D*zD{Ky=)vn$LM$xF-xR5@ zQ~46Q!|NCHbt<#1J`+nafh>a8sf0i*$&-M=6O#=}e{KK_?#FZf-~DOB+Mk22w)!)K z(w}<+2K`A7daqNNZ;A-a!&T6N*QqQts8~of4^M&W>r}o*D5d%7*QqSB`amsN>uYko z*QpFc2)|Cn=BiRohN7=ic^+X8uTxoO^@P5CA?QFGp##&eQ?Y?PD5DK)=WU_nKp8_Q zo!8-7tMl|kL!GISdQ>t^UV{>xXs}T|(J&1(IMEP7o6umj!hY-Fwd9PDhX=d?i@bv3c-a*r3_TGM-c@CI8*?$foMxFz_*QvmhSv!(Q zz5l16$^GAZor<8$*4ChU-){yQ-1lSqrJs;xw$8rZy6=ZTX6w6v!LbV))UMqP8gy+l zlW)+qhyKfS?P!E>*A^IV(6#qM(XL&E5I%NcbG2*#hN4|tazkd<%EV5}@uFJkNO_&g z2AVGS`=q>1rCws?7Fk?l?(>%+WE``wx<@DS*_5L9`Pm5J`+Tv*)vCP!iFUrOvOI+@q87dXz@LVtQXLX6(bSMHyuEhW=1r z@5%R3VECSF^R!}mKVA(ld_UGt5=}9$xR>t(HTxz@2H2^PuL$+=1M(H2ktQIlr9O}k zu+uO%uqk;Z*V6Yu1w*#~NfV8xx(P)Q! z(x|_Avued)3QhO{>ClOOKxo_jfPBZe*1UvAzhk_`51dH`Mds}~747K6@qR!Go#O|- z{)Z(AKhO*PTxJ3?R(;Hm@l|n0`TSHa{D7$1NYD_?yS?dF$xJ&(jC~kuvklHj_Ns7&HepS~?{eUDH;|C>38`7Nk7^gAFq(Wayu~199*sFu&If&&=0iP(!}u(%&Lj;Prqt& z+M5$w8t~6FYQR4mr~&^3Ud2fVXF1Kx*%q~HZT)~CQ~ZF~wV8e(=cp_vW_EQoO`#tU zWSSq4G_(A`_I-H`lpko;j%Ou5aDjA{ANb)19w5x7N<|q*-~2r?t>`$jaH@q)^aFi6 zIL;P7Ah*pNvs|U-++VxWz!D#k!CvPFWU$&6nDG^*?C%Ez8Se)Kne7KeUDx^np%t{W zGU)3E1WEV-$zXyX5Tu9MPta*G(+>!3VJj=QHGbe|wn7G(6I&G$7-k2`?Z8MoFxn3I zrxvvn`9M;YCj;OU2GPnD+C#22jA_k8fysUUp3oeFA%`)uhXp=xIT8z&@4enL%{Gmgw0* zbikfKbZrnFuqAqa5FN0m5WOgf4%iaCG>8t^j}l!ML5`#+i(}5uR`_nhyS%V`uy5#fJz`FDgYq>z zq-V@&YlXicJlzY+&bDpunHxPcw3dae*XNC7Ae6SbR`fchOa|T-B zX9%Beg~#`bIh(z(d_}SJ;xwioG`#NgA?VF#Wx)pxCtWTPUjz{|C*39y>w}1;6aOs{ zUj`8k*FGx|8~upem*%`H5nl%pGjq1P}r^FAWDS*OSF_5EVrNB^918I$3^97mtZNB;gP>nq_OOJm+g|8{%)t%G8Ye%0~s zvaVl&cQ`5L=!f~|_tC`fz3{LzV@_{r|AsRC2w_Qe z%sENIYrSycSutmngg^JfI|)yg@K;`V-Kdx|N5bp8aNXJHq=Xy1@Rqw`-bW%gdHvCC zY0Ud5cW+6<^G5@@!BHQtG8jP-UDZN)pO57&ZUz1A0gc% zoM0;0%;-hYUVYVTR=K|Fb$X;vM{iUTv__27(#iU@l=kKNnlAZ1$Y{eTf|1{$JkOms zIu^X3YTllccTOi?V<+FAfjy+dM5F5F07PZEgMdeM-x%@?0GTgL`ud9)}hb8A2&?J)jop z#K)4uTD#1=?5I1DtgirYhagNw;FF+SH`#^k#qV=k0^g&s=y#)?&0b`)8CVqDD`l6R zx_NefH8syi*=Iz57iGR(1 zF+|?AOKoCQ;Ro<$B0P%F z79lPZr@hHW2mCCyPp^V6Gsj(kFb@IOwIA$0c6nz}$tv&uZtcCzV%8nZ5n( z+_z^%-60p4+50R)U|xKhHWl;I5>R^Ios8fa7-@2;UD*28?q*O={iG#>LTFaXoBqiI zsC%t+M(gaDyWfQ|r-X>4RIXlPb8*_&JvbDk7#KZNInTgOHJ^bHmhP3gtb>Z54&#qhjCLSm#g8CZ=} zDMsocU^P;oA_PXtr|C2kBb7hS>Hr_r-k}4I2lTW=jMNsp{TQjML46}t!ibkWLxdWs z!pkfpwcSo8Mk?=8tH=;ak;egQk)HY3X%cIF#Yk-cS0nW#LfS~>bhgZg7^y3O(?+T= z3`gCQsA1Yj6&YCDEkxiN6C?GU$8+M#v3Cw96^m#E<#|WN=-I_k@^f&ja0KMLPlzY zU0z_MM%uArq>dw1+DKK~xr>o{5?Jj);gyz=@@d+?%={~0>CE4VkTz1I?ZPl0Cy|Gz zeqyA?gwT+Ynkk(jMrsl%0wYx?v0|j2BUUT*ovD->sYZb*<>jmVQp8A&vrD0>9YD3J zWe8~_HQuISq;3KY8L0_|phl{c>3Zh`%ShR%8mW<>fsyi2?JkT|H^AVo9s-##jehk# zBQ?dY7)EL(X~RY;#K1`HhM`8P&()bm%BHH3IuD8(sksPyFjBRqbTv`~Xmve2&q&ET zhwHj|vvj%Gu%Wpno3-4h-3Vm zJ54df6oL}@@&oYR={(E8GVAhFz{S^63x(xKV6B0R1THVnb$_10A)u`j-}uA zywI+fyzBWjXjZ)nyL$E3dR0^KOj4)o)!&BC0{%}39&N*;fPeR4eb;lnRQv4mJnxg6 z2i3&9cRj!SubB6)=N}P*cRepMd8vj5?|M$kCpVofUPcJs@$A#2CKbHn`6fW^GJVH$ zy;VdwckDNj`xwx%t8WnKQ2v70j7A zCP6S~8bNg`boqB^&Wt$B%Xy5S^C{p;obD5K&Ww}cx(03SaHE+sXCvsGc>*D@N&UNf z`RRzuyNhgfdsM zYyVE8yuPGP&;5Bed^7L`KCCvWUTSd*wRn(dwMjb=^fSPTn~hCchoCm;@LMdKwA!wh z*rX?*S@r7E)2p}E>sAWBjnwISjkMw0fZqtgQ*8Kl;O#!FHmT@4sy)-UNe9j_HfiZ? z#wPuM5ZI)8lb32}*d`?;AF)Yqk%ii%8U(dT&2IH=(k7E$ZBmk))h10v2yBv1(djHU zDMf0vNlOs|o8;3}DX~dY0kzB2CN*016r1z|sM@5C6lL3_F~)cVHtC3m0-KbSm%P_V zvo5H}c6a{6A}JB-tL;3*8xcvSuR>e_sw3ikRC1=ld&pcHL+Ue}ymV?C)zsZVt<=j* zYF)27pVS?1x5}=|EISEmrCw{N9!u&ecItJRsh5UR7xeO4re$A9>aBL_LW2hF?ljXc zdwQgY0c-eu*YFg8e&+Pziu7krFRG{}_ksGEQzPqVPCZ#ab6O|;J+7jOJ5@4R&->N( z^qJE}VOD!>aY^8zp7=VucE)c2j0^sR6E?sBDg$`BoOoysy846pHLlX@=-;UPpG~C z8t7ZKK?{9-`wr9^^YI4PQIk)ow!h0tJ;BOb_00vfQqQzg%O_O-Wv8B%nfm!4HFjF& z$Xbh$e*=AR{w%9>8`aXE1GP%uWv8A(>MeF^8`abu?hd6cIy5~K^QV$J1s?R9jcV$f z(y2@4(>QWiKn=2xztZ%lUC#TUsLQz;A?$Keo)dq9u9;}nKu?}7B{F_xCL$+LuP4&|hpcWvNZl*E z#!Q}^K;0p5wk*T7;1d5&21gHhzAv1$a`~Ez{>3kOh|`KzbyRJxBQl=IK(wM~3UXT} zA{D)lNVoTWG3OD4)HA~SE|Vt}Z4}-)@OB9=#_v7i%QARc*|&u^8{P-PTgN3`;aUG@ zg>58U;Sds3_}%}haEKRFc=!KQ*yg1xeCYlEQ(@8cIi|ug4Wx(N(eMIQw^3E~`#}R$ z_fb_>RJ|TBQ1uXqsz)CPsro`wu1*tFy+3exbtS|=)h~mgsy-hftm-yZRs9Pns_J{s z$y9Y+_+FIR>Ot^=R@JUh)zX7x+cwI)T+t1Bxb%;T$Q!upE z(-6X~wyE0cSDnbfKVD1QCoQjKjY$xA zEki-oYq<`=@>*u~^Ku^J=e*b_Zt{uVN(wE{e;j{d4v(DbwS0x3UQ6-Ame;b?Jfez9 z>Ppr5&@Atu?U7!2#ezRUODajN_gDQb^k@UCSGW-PHsJJ1)i?teN$RKZ3eSARc!k{& z)GPd*1nL#uNz8=B<~PxPLaCOlRQ(5*sg-zz)%~shT}-iU7XDBFo=jBW6)rIeg8rQZ zs{OkN!Rp_U$5{OfanWW5S>I@AH)RBB{Opm6fV;8-5Y^dmr|`N+z{fN-a7(YP`ZL5!5UEFM_UARX%3C z!X*g7SIH)tjJ00k6&8b9_1a_?{4xdSKW^8n*-=)tUjZ%+!F_Ca8Sv#k?0uDNE7gA0 z_X-~a)31^p$t2OQl8r?Oyuuojm)11w6_!Xo;uW4S-*|=pke7Oew-Dofjck@lFHc5g z^-mbDFoz-nuh6IHY!|Qa15&G3cqIJ5EA(lqlz4?XfZAp171mny6t8eBsCtES5p1t; zxv?#QS9k}S6|7WM(}0aV*W($h$Ph}AqX50Ti=IPBn8aFN+2V_kwQjz> z4>7&PH`3OA;kw25!n5=ZTkq~T z1l{607$Ml=n{BdbCPOOc5O#s;7GJODLR)-`?DB#wz9n|7Z1IgEReFnWshzuQ@x2eM zyJ<%*v9|bpnraUFX0u`GzF7{e^cLSTyD&E2#)5k4CtG}VAvCnb=ln?HWQ(ts6u}l> ziNwkl-zUUsrJ6l&okOS=m{Qgg>6Ic|d@JozsA?&wR`p7R^cLT0o5mL30?^PFU%ery z(OHX)eEtRNam+^bacnYZ@Hpn9+Fd+^4gm}v$3h?zrX`>^VbtGRXIG4e&>w)q51}Cj zk7J!*G>>DaB7`5uY^pwv-3&z^$LbKmk7M52mMLBDcc0PfU*UQ8yW6<2cP;gdl+5P* zugVKjwM3S6e~B(exFxcbYq8-t@iz$#HX%{p{IAOk+{+=akyIbQOl>vQR<6TBsm9sm zY@!@Zam_1sit#}Tso5Mm#gBf?epzPMtTsp?HCt|{_=%bw^{T1air4INRtBl0oUL}M z9ez3e>+EtGgA`Iu;Q+7Cv1pAAS$ihEfa)QY>l9 zC*Ms-mw~b>nx|eT(*1}O?;w=r{U_#pj1a#rgIo1>R#s}daF2m<7eeaaTxLWb=NeCO zv2(6!lUtCgBGSDa_IU_pPas@|km!-gosg3{QmEg;7=R#uajEM(Q&+vmHudY;VY#Vm z8A4E3o13odO;Gk!*AP3X>#MM}uD>D#bq#U-x*obBUDul;tK?*DyrO83H-NV zpC4TGHb*Z(bT4?&K(9m@|FQeGbMJ?hewZ0yP$^Nq|MfLV^f=dWk;Y{&>O!k_ z`Q0k|xf7|C_Q&+d1cQl|4*!jK{R~leT^rV_*@XP=6}j#+kb*V6i6*&JT&vda9lvVc zgMWfH=l85==`Im~C0F-P1a+)RS6L7Kb4*4$zht}ZdT8bWTfe($O@pEJ7j z-B|kLWlJrZe9ovlpqC5Z$~Krh*$)36U`PtxIb55Xlzys_x*kE^F9LdAnMAKM=~SJL z1TJB4O!sXun6!WR6U1xx_4T?>JQACb--L)}E60Zruf{%Jvq5Dx1!N3k^@JE$`h*{nu1m-@DZ)<;r`v z2Gz&B_ipV5*Y|EMMbP(d-3%1GcWZ)GuDo|^Dl9WV^4_hP7Od~xdX>cb-mOLi>%Ch= zKU46DC{mXXOi$>YZkk~-dRvp|6*TkG70OI)>Xw@dZO8F3I zdqIDq#dg}N4xpca{tb}$Zzfukrxe zhnRw!V0rqglf6Vz$6K{`N0P{!>Ao?#+BX4{^h+;<6mv! zAc2MCk7?D#eQURIw*No~zL>ex&}6oYJKcjk)F_;Z;Jee(YYkSnvs`7eIBj_2&Y^PDtO}#Z7+&)N=uDjnt4|*?~V8NBqsLmLopGP9~1{_0R&p zB7~CZi-2CH>WGgtiDlxX#1WrC*6N6#hLCo|$Jm94BmN`#q#g0`VL0k`A$8gjpJ>D4 zi2vr7a@CK1DdLFN*tHQyd_Ax_;tLScj`%{GCysb`V6FABKb!o#^Y+thqB!F%fAalY zIkP^~u9rCDLx8n+)EQqSgDB^1R}d}EcuF1d$%Fz&e2&RN6iFTNrqn>}Sjze_z!JL} zffK&WE?u1POG%n`!t3mu#R*>ztp4tajg}Mc)6^Q{***?SJ=>PB(oXntyD;42t3kD; z-fxjYXvhg~kWLUM{25XNPI$pKV#NvHOsrOFzh5jTyi{OH*-E5Wia6o*b}3ZV1=Xrf zMMyj0Yit^KhL=EnCp_7RT^mR4`L|*f+kPE${vyI1h0tU_EZ!T0YJsa3Q@5vy{Y>DU z2wx+VU(cl;c+TalX?(>`<^-LFFkgiJ2ul!>1Gp6Y%16uObJ*K9a>o>SA;MS@su8Y0 zC_fLKNWha%!?q*xN?EXZzk#3jA?W;CV%fRW5e(v>O-56%Lh$C7X#O&rcO<+8z^eJ{ z5j@QoyE5JwSRL(N*q5JnS(814GTD~`n#nG|NvW}{bLvnE>H0T`rOu}!#6`Fn;dBJ= zXFzp!t&Yjs$1T`w&-&$IILkc|SO@fK1RYTAgw;0hSmx80z&c$QB6yvkzc8_R$H5!& zjZv;v2*Hy>y-hBEDX>0ROhu3f3-2$v z5BfBd!9~;ByII@0Jrm(xgU}rzF7~6**3`En?cLm+zWu0!Q%CC5+dRA6z60N0QXlp^ zPY(#G@3|zWaA_1ya~AO0z?m(aw}0aSSU69~Whs~PzFdm7L;S0$`){&{6Lu@%jS$Lc zxs2mdb_~T&K+xMsj@8inH@0&p{^8HX9Z-50v@5N>e`C~r7IZi9?q-C&+LL2zE^+y7 zlub?DN^{!&>6t@!D1w^A>ktBy*w>0o`L-EJ$3e9wIws-%in%t+c#w6fbh+vFurIA~z5 zdk+st!M?AJ>O$kmpus|;k7{FBXxz;N2_6VSAU5JzK+i_#LgPHU4J-~ zG;W8X`@RSBBp6<3w5ht#SOrBF8t+2LSZLIrc_q9@phCaZ;|J%ZTU~CU+UjFLgI4>f z-|84((CQFKt3Ny`&u(?K$ypzRX!QcphFcwC(CP*l+UnLr@-kX&Q?=DYplGWnBZON$ zJyLAcLVWkKlX#SULmp+t*|d@T>svK(Zv_pUO&e8b^CM8>((B2AwI*ZLpj$}3e4C{~ zHmZGj8)(p%KI-@72*98(Lm+**KcJ;Sn`}L&FaHD%_hpDdUzYr8H0WG}um;&w?aTY1 zXkY#pA>5bRX@w_w8l>x;i(6%@S8qpZUp>G*+UqOD%guAXE_^-ED%(AWXMJydTLxmH z4Zi?98#ovU8`aF;^%HwPU7Tf7t4_bvD&p=24`#BB>Nxaa1t1s)A630%CXWRS#vueU z4z+;RILtHU>KHN(p8$u)A;e%Dnq?cE9*7Vg2b-$na0L_{hbIv-#zBtJ%{Qf&%1oA4 zZ-5sZrCVsw9-w-ZZbnX?ca-k*CV6_4&V8Mj;5ePlm*aG&0qSwO1EB}U=|U`y)3uaL zsf)WEAvjLA+!_x#PIoI=1jp$@Ajj$I0E4lzK^?1KL4&dKQGd>Ki&|q90vW5*0IjjA zH+Ayu&kW%3ScMpj)$1_S{%k`CkCjc;u{t2vjMWH)@L19R-f_CMrUqgyV88AAFFGy+M;isERN+la92#lj&yQ@BoDv3{V{m z9iZP4!UJSewbcg=H3M`eLU@4UGMUzz()-f=+Uh&u1(Ru=LA%P}$Xizr8D=Ka-w1Lp z)jbO#m`pZbCevSJrjuzEtY9*QSWKpsuyiurE16O$J)648lr3r_lc{95HJL&nlj&^0 zV61FV$Lb!?V61%9pG@xn28J&LGFH0)t+8s%7^`0K%&`hF7^_h*bgb@12#=Lb)v;O$ zMGfCy2;s4!54_3bB)ywZFqsZjqrO_L0SweC z1fo{CWg)dHHg(dp+)s}N4x4}w1GTychN@L9LRhVAs*cr1P*km=<^QKz^))q+CkeID zN5KtjbbqVQ)J9(ns%rHJLRhUz4Odl=1G?@fP*km&R%EJ`&DE+N3q{rHa)hv2Iq}Ev z8n>7`fbgStc0PDe!2jV z!0XOGy`tD%p3k`~@sCF#1PcI#CwmiJ`VmjRy?c9eqccfa0H`6gE&!}*h9*err<&$v zEC4JLjw}F-fiqh;<#6_}0MH;r7678~bOGQmYMQYCu!7=s0YLod5vFo74EN(lU)_S) zO1yg_LfVfWX=q|%?#GXQ22}m%%?O?!Eo&X4?c7*SXj@=fnvms$F$V1_nXsG?2i4_- z>k-1s2{u)i6P7^HqfXx<=yF24z4Ow`3FA%H+Q)L#X*j4ZC)6NV%Lz3$(OXWC1%R0* zx=^ad0>F2q(iO|pK6&W{0H39^o3+X3VCe!tCs^qPfLSIprLh1o6;y9Mx{Ny8uEBbH z0YDa}itMy2cnwt#ROxZuHh)(n-P8&;Z%eyN%tn{nj^&LW~3X~ zDN^BfhPF`nKS>XX@Cw2kBHT{G)d-1mN$uBEx@_RWL)^+%sG($Ej4&BN{*t4h7yPDe zdDH#7b)IvnWb`7!wIY1nCeOJMp}aenQh0-I&vP#TJzCHM5C(~GJG2Bs@^_BdjDt3? zV`P~783i>F_%4JNA`F4o4uQYBBhsCl!rd8*xG(K%`twEv?awj!E3X#u2nX_e0SB{Fyw1{`3?2{rL*HYJW~c@cZ+g z$j?~0TCYQQM%-V)b`z6|b-HFTzk=T>YHxZJza48k|+(>8lW6Hiq;E4#e0`K55PT*4`h3+;I?H0JaBbKHk@P7%_ z0*`nF_$gvP7q~^IJZF;#V-S8u(7*V(4@aCnrY-uo);%l7{qO!fZUCenF2)PJl4#MdOi4j!EE@1BT=I*X`0v#sY z5yGt|G#a6-2f{dnc$Of6P)&mYdVX z(!8W-UeOL!FI(dhUKF2SgRL6Zr>muLNzu5O!VyiI11He5a?!LpfzYsXK`aexlxWeg zhYm0rHW(q$u%ey7qG8`qmTK6o2!Vzr1Qrd;?q)RX9E3o_YJgS4UL#gDtmr_aVOJxB zHEc?zhJAjptznN73N*~-s)k(-n%1yVLaJfS5CRPgB|^j29%O6Sql5wt3sKRqO99gw zb}XSl!)&T**j}J%4g0j%(y$O$H0%-3w1$l%q#D*AA<(c;BGIrIXj;QQrX%;HVNauP zi|BtetRTxhya#6^h)KQ8C4Lu|S+;Q!+x8%lPVx`A{=uko)hbY8m~jx2O-sw zOMDHST06OD+#o1l1EhZBqQ^o)6g00n4DVP-ayZ$PNGYOuZ}j9DO-dPqFbW~rolCXA zqIpqbj}Z7N+E6O+yfu|xY5cm=uL%1Em zvu({Ei8yObTl7g^Y+Lc6+%y5)-%9eF6GeCvA%zfs9m`_#Rr_uS-3Z{0MA$0AK?pk# z%6_A?ED{>8x8AjG35T$R)MTLLo~$vb+_uy`=?ALr$)yN^dm@>MZ`ya5msu$h3^PAr zqTYdT+TWl(Br{p^DD7>0)6Woe$zv~sz&Ew|;+uX-X6l|HLX^4SudMpg}O)o_V`=&Nk9lm)`)HnSU;s03j7-MP>EP3p8xHb6W ztorHTmxAixUx^S5zWyvX#1-H42`K8Deu)rXKeV}8)qRdIzUg3uuy3kA)16={BGWRNcgPjzin9qh%R!OwMTOxi$$zXjEw>~=UZFXJb>A+9tc0Y!hddm}>lXS+668}Skp z{ps${2z&VH?v%_%?BCaFgpFz=Mt}y5n336t+d#Du%MrrAI}UNB5j&u0BYGZ{*$A7f zji`pAjkpIPqY<)_JJVD|6h=ql9eBZ1u~D5W|9}Ql#Yg?Aa`@5KR0)Ahl?wo^sWQjv z0GTQe0f(1yLJX$Lr!aJ?1{QF>6o2)3;S9 zywZjz0dEMwjW&E8aLfL7>bAo@o2i*k1|A%OOKrFYcv1)+W5d@2FA88W$TN-o*2O|G z$koSM26?tYyV5Q-$g_?y2Dv9RHOOZW6BuNhF9x|gpc>>q5dwo8VquVXQX@6UZ^H@< za;+)bUo5o`lxLLgc;3eeKBh1T6pwCrx+ zu$F}wXxT~_s%3v6gblJyRV_QD)M(jR2w^Rw|GhQnWmd1K8JGn(SS+kFs6H0(OMZ71 zs2XHvK&C-nZn)~|i5WNyiW=ne5yA%9=4w^vK+(m*4-xiYkk?riQ8O@)r-8sA+o(3; zbI`z+HP{uCMid-xY}ttjVOzGzaMgHABd&&`w(J>%utB!D+K8{9s4Z(d=znaPy!>HH zW+R5e3mRdg+KB5xgGOx4Y{ZM8YLI_K2sffJvk^rnm`0p}5N?Fc)kaK*qK$YRVGjm* zyU9E-$lKrrQ^iJgsuZ7SO%)&Yr^*?C!Lv&UWU9;pw5E!av0bwYI6PHC45o^6l9?(; zAcUuiP1RPP4@C{~zY)Sy<^SXBO5kiN-~W5=IrrYdTr;xVYpEu~SSM3qhQyGH7(-(W zWf`(>QMN2GXd$GiR4PfOQfWm|DwQIsw4udPX;<3U|M&a6?|bfl*SrL6nZ_=Msid)wVCtu_ za#l!V_pw5>U6=~NPh(R8*Y9~;`3*=vjg=#j#!e{-%uSG#x#AGNV@t8uH}y(4_3Ih@xNZ{60~6`7coUuc&$qxZrStDnEyJL zKD~i#v;lDo?!(u(d}afZt+v&GN?WZ7$mUOZeao%*bB>e>TWr8ig5uUHcICHL2`v4u zih<<=k&*HPn?%HaP0RF3fvpeBu6*fG^5KiHD<4?U&JV2cSJ;&gOddPhU@Dah(|k=! zi;DwGHOR_R9SYW8s+Q$Q@f7G*kp5CFM`EeI2{N!$w+1@HJ+6C6#id%#0!y_WEM$*+ z8HDmnHE1eJbuCO}seTBd{8E)(Z?D+vY6Ank4zkkg&S3psTh{h^I!M3Q$-zXuL~iR?{&~rdOaT|((BC-%J*8nYI)FnC!&~Nkn3x{$RNs& zpwjYGeOy}nHoo<@-YRqJB|ozu-*OtBVa)j5tQl6J&u**G$G)&!e6Bk!;IrB)h4?() zQKRsiZCx80D}Fj`iB@fE0|{$e)w;-RrndhV^*P$*EG;hYpam? z)++Q#Z)VKMw6qG_8E6%@Gs7zMdCDsE*=rU0sOF|Nen>ITDl{8t6@E!=gH^azjvIx; zUfRO=b8^;Og_CpCD75O?(pbentg#9w=Vzn9YDB`ke`1hI@xX5VyY!!x_ zZr&C9jw9?{+U(S=+8l=YrYAT z%=nkQ2{bRL47AE7THx?R(ioNV0vDwpiQS7;_ zD4scU6(u#O47Uouk~!NdtlB=xscQ=|_Gvs}TJ{Nq(=Dhh3@Y}RSbXfEqA2@*)045zJfg|wltbK8~)tu#+F4@WX_u-CP>>g0ZJ8J4Bp}s`ab9ek+|Q61OC`kp!yri0l3g7tXhWR}u>KK@MT7TGLL46K&H=>Nm&Yc- z?wGO5qup&)tsOq^>+}O8v0rv6COKC}(Ffo{X9h}Xsu)yWzNW4Kh)<*XpWqyFY8Cgh z%AepQe9VV^>!pB?`>_APPQt$%7!B8*j01GWz8wuWHA7tsV6*V=lN^;F`zo5b9Sg4n ziz)Us*3zRrBWe^5;bPxJQ!-1i9H!u*iV^-U5)Nf zqy6xoVZGpL_#DM-cYEk91+Ju)Z2JqJjyDAW~A;Y&jfs)F3)g?mG?$v z&{TA^9D`NT77Ieg`2;q|(PovL0dS$y7o{xfSBK-{vw3>u778^LrEHLEL2WjRdXiAL zqm&KuF;FR;wb#u;J&#g0$frSN7;1}9hfv62cF7I0D(o)2+);;U7axHS0-J7~2e4T<6J>tv-)Lq6f@~oFp_+xx1gN!g;Nqm9 zyT)ZSK#vtIbZ&$w!!Z_Bc5APjUIK8Tvk7G(T`vN){aj5w0Wc6ft2h8iR_i}8jLmu4 z?tQ7^4@*VB9QRh%!AkF*Wnzr#zj&FH2RK380TL=}$`aG8;l^at3OhoQl6SYY8bW4@GOh zu?eXS!|AcHshR)1f%l2kfX6tvH@EKN;j!GA2bE_4u@A$uAYxyDQbyw?bU9(VyiBOO zEcG&|3`5;6)I*lS)5303L)|abW=p*SD#uVy3boTxuY$@m)XM;uJBLt8FJFrt6x%9O z9JPXJWG8I%jjac8q00PqjD8vFDWOi9ZYsL*a^4Ydql<9l#i;`M$Z z>o63R^#@8PE9FW@g_L*MySQ#kekOFUd5)8n1wmznA^iH)&WL;h`8LW8nksJ*Yg~!qO`!e4^|s;1yNlq1D1IgwsdtPZ1B#Bt zkzsYTU8S~{&Hn6!Q7svwcPMe&_6|a77M^;*Q;FETz@bJN4mGmi>)--NY<@IddDS2_ z<^84G9IrXPVE&;~(lSDmLR^<9>8T9fCC{@xcC358T>gr5f$tWpIM7$eAio5=j zJ~@%!u+-RY$wjRr#U(~A%8N|2a^DV->#bazAGycM{kle~q8{-b&@GZ~<%@ep9`Elc zE{>9cy(6_RaTLF)T{5_T zyHg5gGeGI_${y?}_la>RQre^7YErHG<1467;D1S%$yeE)x|<)yw%lYN;Gt~yJkFb* z5oxH=cVHSk0H^acx)iReNfRK_e7AG4n3IfdsmTb?R}RGj=+2SWw2S~%m*ed2Js<53 zXoe+Vda9!BK>oQrq)O_9y|f=a)xRVW+4G>M*IQi`c|TrVujhK$Ui#pcZ3bGXpB{Pf zrRr*IHsl6PBXcks>~hJ;`4g+7j_j4s^LA+1+d4C>)|X^NZaE1c8Y($WMQ*op!}Q3V zkY$l)W<>6>a-+Ot0F8Sm1IX$hIr)w>9YB-PWH3!8FQQv* zHU{u^=aW@owYUW?wqfxH2o*gCqr={poDy9Ik&Y$JmDd;JoH_tSy_LPIs5r;UYjQU- z`~(uBPNzi7E2Fe|H6#}C`|p4>g~jb84&DxF9i;=yAhC#3jc+El3WuhtAE1`hlb55I z&*Cu@@%PCNy$R|UWWQl?oW(CJ{$nxbW)#)eph&Qob_~Oo)G6;19dQqxh&SOc#*|5u#1mk1z%FVo^DOA1tyh#3@J75Iuz?j zJj&up7Bv^4C}!~z)z?tOA7L%S=_^gXPvQWJ&scoU;%gQ^u=tt9A1wZ5;ogJd!lm$K z7;)B;dK$4T6yE(HQd>~XVbO*~dlH>c#2e#6ajHlx${dy+!T8R(kjk!tO?TReT0}{( zL6q9e1Ixmr>WNB|GDmD!q*lEbHq5Br_uC=eOg~ZYrbNtpkkZ`eA+d;0*aqor7B7*w zcPpgbl-6#9#3D{L{u!|$kE4ydUPN(}QuilNOhXa>mu%Cgpx#S%J&Q+JJi%fsi=0g; zUZu2`#W|Z%?5A{;#rG_JXAyb{?e@Y2@zl@*P&=|n1(sTa#XV3xA-wfa8?!i{#V8in zvFHf9_zkS!QL5+C?FUG4sdU|gQ2%35LSiV3ku3HPrdv;NX;qz3Mo#>BNiv?olBz6 zI+zqtYC-987L?+Y;v_toP?_4tSu^uMnZq)EHT~X$23I z3R(P*6(Npw0J86|4-HQvz3~fM{R$t&}*eZx4bqfs4y@AE;C{#`@1b!#^=_X8?iGga> z72KtdfLllh9i8$=D`(piVf8!y4_NL9IIpIs#!YR3H*0Y~m5hPQZn$@Mi~wjI{`c;X zN*R*wws~cBNRb&*(^a9id!Y?E)pfELU`SPosF_A}uOpUw7$zs*39}scYxLI1zKL+! zjzhQzj~)(b;O2G%y?`dI-B{m{_<^Bb(EkAJ6t+oc)gSOaaMh&UQ#Pyqg!d)8>6c^Z8$ANhWYu~ATo!6@gQv@7)mxwjvTFJ> z<+ADmsDZ5dBh)}vWm}R}8^6q~+Hf;NnqG&RWYq`3+pJm(vdOByA`X*Pp9X5O>R&+p ztlIhU@>%set|dRKQgeS2$YxbBXf@z5n^o(d$Km^%hFK6*^awImFPH(9m8Mw?Z23ld5otIh#$v#M}3GgR;uo^#B!aN{Eamqx0;>o9fZ?n z{E*yO--n6WST7BjEP#p4s@-1pH`YDyce16y+$|RFiVLg4M7;|rFi}+94~gZT^}0V%U*RzTC;Kqr zv<-oYN_)efs8l=;U`;j!CTc!ROji9C{!X?unESJZJGr+?<gjIf!gN`BXZ zGZV!@H3L+K^H6@G!r@!L)minoznE2zer>aA>w6)9X-^tor!hepU^KtADR^?)xtp zc3YB-Hh^q$ZpSHp&V3!I$+_nO^>gl>UzN|f_1G~#=TdV|70BjXF=+KHuE^;l*&8n8 z;5MV-?GROzL7ALehRd|(NcIcsP`W+ouuB|v!@=a-d|V?kIkzSP(?_zp1qmgPb322# zIahP2%;en3;DR}q(J6l{bJ}$ct7-VpBUuh`GUu{=l`Yk=8?NX$-tTpy{3yLFLn252 zINqn`?i9$5k{Glq{mG8f(|8od$$p21+xb*Xv=2lxN*_QpqjZCHDE%Vo@S`{!gq0bk zFCdyxdI1i4lynOcN???}2X9A7IGUMJIt`r)juN9&b?lnLBCJ{yLE{|m-&BlBle%fH zIfuJ64OjYJ#wt>c9s+2NHr@o_vQUHDrn|xI;!UW5?P7QhH@IE=3^lM_%st5sZWnAz zwu_HrxE>t-QbL+uhnj2`n<1E^4IGQa8SwNvgAj$VJCbZP6SCPZHcj=ni@iY2cCi(x zzg@JihN=Q*c=xem{&qpleMlfX<6_Y2#T3_U7Y`J0#-F0$6A)FDL75r99-^7?PPjcP z8&c_qNrxliumx6T#%Dn^GyXgr^o;8kB$U96cc|+6GcFv>%#1$|E;!?iPWfYrb$(Y? z`CfO!kR*Fe%`Fhf_F4>DWi+zAzOxs5T|&e45LNULnlQZ{2-NiYZtGCGC+YB!I1GiA z>Ge2>rq`!7w!PLZNGO3`-v!>TbKz)a*Eu>B>@}lP{u;re+VmZQ#yanJD%bhsZ|pkH z?~8SQ-b`3GdIg|a=Y;@V7HV*Dc7HXjHMT5)r{b{Iy zzOyaq``fL#@4HSynqG&R^llt@dq(j-;xxVc3UQd;O^1c)-Su=Zdgg&Ss`)3-?fT*GeAe!}j0DB0tp0BbFrFSJA9u$W^;9%DC z=WsCVc^@3~R;*i)Py*|@83MQKSvZ=R^*kS3a6L0R<&PH55I!95Ca=3N;0gzx>p6kR z(|M}yBgAq)8s*ySF2gQj&o>cHtD5adPkG(t%F(VpL%2F%QX3{57hZSy6ei}t^F{bO z+0tNc*D(g}ghxCqY_7XJ2+o|&2VJUDgoBp{ zCW;HC!bH8w(N9hkRd*M$++7p=iK^C@jl4%Vtz%%KE}!U6)ae0}?tzK=2qtEtK83%N zEe+;&y3C)bEf`J>n~Ay)oSCSgOEp}q5V(h1$%WS-%|s<*b+;lWmDV>fQ6Iw2OjNRJ zZI|0|vOiI}e)iXJ_klALRmra!M%YYLCBMtTnTg_{nlY@yc_=?o;qdqyz+(@wDUVrl z$r76-7q>%}%$bg!H2M{w$&&2>xGdD*OO}?)lDnV=vgFyz%4NxQPy>626f_#hl59(| zBrm#$!-piK>2;_{mYfXUX32wy(`3p0h{I&bIj}HU@>8IGmP}oY-UYJcNetc3lGNO| zKsHN?L92e(*(|xDABXQW8r}s_MN=S}EIAnW1WcBE#5$DjNIJYF4q0$8S#mTSOqL8U zvRP8MAfW`Zg_+$yfSTED9WHz(kYsptUm?jXW>=C)hN{am z43#_ONk7R<>dzUzfu?CC2$eI+y}|1+G1rS$1Wbm(#O@8er~D*y8~mMYX)w2=g*&;Y zh^I9C7#dKyGr*Z76LfjP!aXXxd<)JbnPjZ)Y1mb&vWl56Z1e?9VeOm$(#gpO+6LlA& z2}~4K_g-STo6(55T~haAHu4DJwCe*CRcn(!Q5^y%w*)4tH%!dlU=#eEY-up}dJA`Q zU&C-}*z65n1!pEI=;Cbl_Xd?*I)F11m5kMW12L(zdjb)!HuiNpNPO zbp7nF;eG&TCaRKObBwT=s7ih#!I_ETpqeqP!+9t_Q7yeIUjZM;m+!+qnJ=li2L!VD zQVd$<@38surnc0(&0aG_!?FwUrvQ+^5r%-=%Y&A zf`k&tmw$n``BFHVnS6N;Iu*>9j86IaC+Cgx!>axT`kD#XZ1S23+gI6A9lPO*o-_1D zd_5BXd5xvKJ++|yT>9sXT@h9r@PEK9N&94_yzYH$UtsfKOBFVcC$B_3$vj5Y-ApXE z)7$>$k%#jVC;KJBX`dA(^Vm+9m^^k#z~md4*gRI_9e?xK4Sy$F8q6JF;ZE)sI8oBD z**xw6XEu+Z%U2feQQ75;cm2&H8LRshVp3_pA{v{=X2Q;F9?7b;UG7WZ%;up(Vt)-+ z4Wno_k4k<;;LPSx$!|3{vw3h(%^23V_(DH$(9Clf3k2V_Xeq4 z8rD0Uvp?`BD(JG%!aXXxya~?av1F|7O^8XQHAggdqT(O=6P2u5+vS#mGZUplVt)H zF`LJ($FuNGb`u)j0uk4Kr}}xUB~X*c)>wzqtx1R1#NiBBnLKtjM3cu3!$IdU-GYP? z$YYrZ+~zUiXlC-*XmG(i#^{uP9R=68hW%Q;*Kg3k?=>~|ErD#W#h_K~Uu>_-hO*Zm z(QpYw6}=Q97ayM8_ynTqb%}K-eIn_wO&pHE%Jlj>h^E)K!$J32w;-VedVLVQ?X_?; zGrewzP6d0-=x{A}s=hvi1In(A@%$ssU|t`?W8BM5!>bhekj>EDV{wezX*R4I{SD9@ z<8}w&vQUE;HuQqma^sm^@EG?YsDWeLwvD{tG43{~fn!{@CC9jYUN#*5PePhrhngJY zE&y+jalc2L98)}x(|C@5jC%tt%rS0rpyn92rT5Xv=v`nXpT^MrIi==i31sI~3|dX8 z@0qK$#g}qUb7)u!QAOhr&7A)7h)zGabNsz^D7_}>aHBZ1frFXT|KMQebW8)!%&Bfc zLJ7?25%6|Sg`=67)1l~8a84PW@<%IY79PEcwA6c84qyX%A!!^(KY+|nD_Y^pjm@D~p!swelCM6&sPiQ_bEp$^x%?b|qAI!k1I|oTGFEpVVp3_V0~58V zqd!r}sH67U!>s{l_MnygTIBl^RmpD?I5SZkR5ONkI1l9~DjZ%iR%g{- z)0tHt9BH#^pBc!i<2m$=@<#btbsA%1p$5MMG;rs*WOTW#`YqHzR-HMfTvm0_XdtVy zEy=2B_cE*Y7{`#N*P$j^H3huQs#hRRlT|Oe%Fn8`U}3Uq2~a<)x|f#Es=XMxpH->3 zMFQEZDh91qmfEcP@MsR-AR0acQAN8#G+FhU4*s4peW-CLJ(zU(QXGcC!DQ9ta4=bQ zDID~kQnw(X1hQ(CVacp29L-EtT?8(eRT-V~M=R&*c42i=d!1D|gvqQ*O=U}U?1npj zyUwa3t_p0dWGZZ|H87-sjg_ifhgj~o>HfyLcML}=gK*jhm=1e=Wxx!7V?7Zt;a`W@ ztoj8^%*NUr{#dS3`Q=yo8|zi#DGlqa`Y$-Mu?Afh&-6FeN-lL~`5S98R<~>{1O5)t z*sOXl?96#dvTALY+iJGIvFiHSU&Cz$XExSKe%EQU@k> zqNbPm6V(m=PPR0d>&^Eks)=|?!+N4_1ZO5H=yJ*ef1)b6JPgic)nu%0bKI0rX{R9? zJ5lWx`V*C`THEEm3eN2Qbp7nF;rd?fPgEtpL*UHruae(o*Z32~K{aDohx1T=qQc>v zM|4)rMYyWToQG{ztvVA~_1de^lSW$snq$=)0k|yG;9r3Tvg+9z%4OAgPy<=@d8mQw zvA;nLWL35$S(WdBiN1lP%GK(5~l-X1{CV_6*?8n^^8u{ zv9qN*|1u=3ZYm9{A=k;DlR1@FWBwCEg}(juu*%;|d67$5b>6x(tePwXuwSmMIF&Dj zXy5&A4F{hs5#IwMtInYvVYLAN{dOxoK4{y`>}Guzxs+Asn!Cd40sKe1d>YcJ{OF-= zH|cx8_&)PiSmo^vv|H(EINR>7UdeVTa=G&m_FdJK;}rX5nsKDkYCnoUHdA z{tzL`mB(#mz&YOCVD4}{{vAgAVcLttBF$R$zspJEpC){MQ%Ln+<;35inY42C$NUQu zmhmqMip0XJO6)IUGsT8_nL|0w!u$Ckiu$-Km`W+$m{N~VXd_G;>R%uTuM?%hL$En* zA5=aOA1@+yH&j2wLH9ZFF+>jojbA~DmSv9Ev+($L1o5S0_;|f{D<#2LczohJ{xC5< z)9pP?NiY^3D~w;lA>BiQQkf%7eL`I#Yy2`=&cI{S-p;Nt{EY-9k5ZhhHx`d8dwe!K zUi)&eB1zGRs`ys>mQk~ew<9PL3vc;1zzT>dv7ugu*S7&>;mw5ZO(0JxKAqCrVk!Cq zhe7kn*Z7TO8Xtjl2c^-J?xRGu%n=(F9v`fYzd(j--+P^sU@Sa7%^Clg7+0wGB_+XF zc&sq~I0r)EmP#t6GDn(9r_N~NP5(wC9WI1TBVv?1N**7yjOP&(Ns0@o(jy*I7)9PB z^QO|Sl!QnuJgV_6|6-9>!H{!LI&`u3FTOYuUqr)u@Y3KihkBVqIZn}AN9qeoEaFd6 zJt&r<)6g5%0~NnXhLT4qE>RpJMk!9o>y7Z@zYr6Ng~vaPj#rri?BwHtRXcQw8$Xq3 zDbRQ`O0+C<#GZvmFy5GB)QvQyGDpn&Q?KzWZ1|v^cT06NJD!+GEQE;9BSw=lhhOeEH;@_YUojlMso8 zM>Srj2BdIRu+?$7D|J1jGKYGZLpe^-Yewq3Dv(&j^QayX8_{X#UDyk?T||bGM=35% zk0eGZPRU!3nBp^uiNwO=U!=#E5lc9bR#Ccy(ppMn%N(&`;Sr3V!x4FrG^H{}%-^P- z8ifs?{POq+RQzxYsP+25`UkR!?kIry zNtyT)WcVzMx0RA$EIdA*5#LLU4`6uvDGA2HV})^-V{n25r7}mFa&ZSDRicqUMm&~> zmh$_-umK559wqtPM32u<#M_V%Ns6vi#qHg;447qn06~#hc>Re@AhuI%sFyjE<1D-` zES8d|6u*_yZMn1&{kv??{KN71<7CF24(T~ck5YPt64^3GY*=^%Bur(9oP6%MPlK7Q3$Ldv3_Dhz09E;XW{LI?sXwgDc+M(lRmT&z32kk zpo#cMGH*kTPoh+-8>E@y2Nu?}kyv>5+gnM7Qe0HtXpOHY##^c06O;sF;jx-BM{3+n zhK&@q~K0Rs<_>DE<<7&KbfFNEWA^Qok47w z*ibKXD92fNDJ=Ssrxd@0(vYsS5&e4H;PQBvD?XJ>m9rturPPzsBJl$YYn1*$(C{{1 z7Vg@450a-8C++d}T6`NZ-azwSqa+v$kN0%q2Z-^mjrTbv!B}`~Djw~R;$IS!${Y!z zIxhOBGS2w5cm~wV!%dNRLt>OXN^!|5ZHZBeQ}X!eY5YQBB1tiTDr<>ffcJcOypiBN zM!U;Nh{VF98b47CX;1^O%gL&fISkax9LjNu-ovEMqr@WqEY-8cQgj-6r{ji3d>ZJ`30+O7$o`NvRPfve+F_XW zjD^Qbxbak6Nl4{ITCWZz!B}{#F#gRj6s<^5Ds!Z%PShouw0kjFbEl)F{ak`(i(irZMcuL}7aW&CD>BC+s(m;&rUVnf7+dYMBx&cgc$y7xMH zO7V9o=2fitcVwP~8vl*buaumtAdxL|#D;~(i)8WoWOy0OYfMQn79Ow6 z#M=?$wHNPPN`kTQSYf;~$6z1{N@b2THJ&=7iOzKNqE9`6RgX?LJ_jNO@yE<6gMbX0zz3!Tx06h;8IQQgo5 zzHA2Pfojx+=)$iBc*#GNo}s##=`a(ePpF;*DoRnPer7!|kI}3+)F3m{DkbRl-6Qp@ zn??-?HOg!bX4*XTbO^?vsuR|o8-X#n)%J8O#$falo?1h*%PFD64 zSAVgJDAbEtMXnQb8L0AV0!lj-#T4RsPIbbXtA95xWau}ghE!V96s7KkP4DrJ*A4d3 zA{4&>Xubz81Z&>Se<4`&n^YtPZwDHN8Ed{GJ;HIIbMuvn2;cH_9sHW_&Zrjln%{h< zvkNuwOG!Jben&W z7fG}Dhxs`ELj}VfD>FQxU$QcP#kkUv#_638yqa6lvc{DUM|G z!zywnyw;LEq9UCkKSBAZiu8i~66Mb^Xx;;mqU+L>Y6mzm+S^2ZUQMOWr#{Mije6S} zN)=Hb>3sk_l}_FvN;LPrp+rOP7Zg#oz*SekdQ3{SaAJ&p*IPE`e+=IBHV!!du5U~f z>x9|GYYJ=q?$WDagF_?g+<;u_ZmEC;0Hgg;tbu>VNmv9Kss19!h^a^!aGGXRPme6J za#|vCqm|P$BHN<)S^=g%qXwqyZr1n^iY>4hTc=vM>Dc63>F^FXc`My;T$3D|l88J8 z8!oZ2wKG)oQ#eh34lmef8T}gKPH;WzMH%s{5JSzpKUsBnAugOjkJJo@Kf-UuxQqOk z-i<3#k-fm0z-CUo#fo)e2KT)W}*wRH={G4{tNXis(YgI9F_J7+!~z`QL%-QhT*-jt0I|K;&_R# zkd4iSpa0V6d65*!HBFk~1-NCAbV>T6%#ZZW+;A$c(2`jYS&pL~%yhIZid=MaLTa^e z-h_xhSQDZuQUf^0e*)&B9%QbJ2~{#8nO3gaG}6-ARLj9Z(UsT%&xcv6NJ}X3wn3bQ zmqSU4`$$moD8-+m+Hn?MlbZH0%BLRl)S$O3Y90^%}u)OSyHBS1! zQ1ncu<4V*uu6iC!&qTBq#H|oRjZ;QfLF#ZkzRNM%0`Ob(Js-a9q1Y4{ z^#8^(5VO@#Lc-bDBSW_jE@o}SnB+}JqZ-pw$Nu0ioT8l8j%)ooJD-;O3# zSCJb~6W78dY)6ma2^K9UA_riv<&4Ovm@;zH$Z;Rfi5&9fyvUc3yGT9xDq7=OY|vz(oy=;tTLV_{F>wPs6d5wP@5`qDY5NC>xk;#Q^4&aw^91- zb9yL4?~r;5-(53ZqMN1?`$?rIhe9O|5m~Qe@3;P|g|E(GEgqDbX2M&fIF z+@tG|2_mYZ(_ru)soq@WJ!O^iZe&(3y~;%{Oi?L6!YG__uM_3`O*NyFh*9eqxPO_b zN#tU;!fnk&U2${dMyIUj(5Xar3Q%zw}09{Fi{2eyK#Q(Jr{+UavJ%u}bH#dSV)YHKdbsZ-k?neE^w z_b1WvTybbuTYlO%k)N|C$WMpE6XRxk?{IzXT#;BrWSfXguf0xmxg7!YvzMSy_I-vR_&T%0dXTNQ9g z5g_1FU4Vc~Edo1y7c-3~3+ns1lvJpRpuV$9Nrj$!5;Yw4YfzyxXm-?hR-v{6_10t8$J5ttruxm19F%UA)DE{Vwm&UbttJsgQ? z8umT)cqC?P*!R~1l9*4putFuKrfW1;z9v)M^_nYRovCvrsi_0fcp^ z#Jd56{wlPe$QORQDs)HyzeyGPN&vq#mH3fB2fee>4gDTKbVG`(*Vsryi4-DTf?nwX zM0?c@AUeE;L}muUYbrn>yjB7v!wa<~aCN}tYyko;odpQEyvF$F1YF(}AmFl3fTT;} zCj#yD@unVxKLUvEj>C40jdUkbg-CwTt409PUiAWqc!gfY$>6ltB|Lp_Z~;wTm+&;u zQveB1fJ7exS;;l25|?Ns*{8%vjRZP1nTVV8GF#Uy4g0QU!@5SpzQ5U~ZX_HIR3e>7 ztk!U{5)H4{aK%cFVQo%J4^*PZ_$gYaJIP8Ysl*E!u2{(%gwLu_iM+B?CEnIt`I-#( zk><)*XSfrbWtFT`CH~ZiUz19N=&u~#UnRaefHyET4|<(Mo94-$s6>5@1iTIrX_)kK z7htPKWg7MyH1JOv_Wcd~7vWlgO5`XZ5yDqQ04FQaa8(T_E78XkClUT8uz}PS!1q?6 z(**GSRAR!iG&Sw?WVIA<^s9jxw8FlxGbWk&dlPWrbmA2%(j06 zi>BOy3q>%R9f{V2I2Gco+SS4-vtp6{kQwf*G!-d@oCAJVEe}`myjkgy(Li_xGV3H2 znFzTzSzMA+^?6FIFA?D2nI>hRud0=J2*>nuJ3514XwEdQ12OmgkRVF{EAK{>(bXu9 zKJBTpa5((q&NTJmyfY#@%omL2orUv%xbdW7UfYz&YAffaM;^3tULvx|%Iz{DuUff% z)5tz6pPdsqY~>DlksqvlPJZMsE9ZBMR6!ilR_ET4x>oMeKavGGw8~ZUx|T-TLr$f9 z{^&?&$Q-nJ-6lo4TeaA<8RY@XBWoeIrhLh&$fJ-uQXaS_vIVllFlc?`HOM?)oHux5WFKUn zsLdO)Ir1j1l1Xf(+am{nccbsH9mZg;u|1yPlR}i?8=EV8+Iqd7$=LI>%>pAII1U~XNRt=fW#k! z|I}A2?cQ|OtvwgS4Z4&tz`0@U^8R0jfSyOFR{>p&1O|+sxBYpfZhTh&pl&RvJORi7A zc_k=)er+1Moekx|D{+DY@_D6k>dY#>Nx~}e7Li`MzY>vjfn$gPxe#O#4X)J&GPIgY zTtYnL%4V3{7892e?pI;_+}5`vsAwmYkAR<_vEF$Ix9RVI++iz7nuB z(NLk9M90c%r$c41V)r^QeTM)btg5Ue2j+bLu%mv@=6RKRT3DXQ&(45 zij4ty>`CZS+P>gNqsJyOmgtpw&m_yL1P;o>j&o^_)yVV9N)G1NrvFbsvbu)XX|CQ|Gm;%tiNh`5+y$LLzrkf7K? z?orf%7-}8e473T+meNFHqHUvlfaVg-mfKxzh~`C)0=CviB;SLGW_R&9qmJl5w ztrZjP7JU|X7fXp=5aq&}K(V`svnXCD;v$MYq8;vb)om2dh&~3lTOo$pL@xsRAkj0U z*JJ1Y0MXp&XrRv$JuBK7_sljEZ5O=?=q{qIqqS=(^*YhBqbq?PBsx-B+fP)-@CDI} z@gGNTPr)jcQk>F*&I?;`q{NSc;c;g2`^a~`+EMk+#SOqvcNEvo`DVn4bjX0CVcnG_^PyO}WQancb_X zrTwBcAs&F~lIr!|!cWE*D3<;ba&a9SJMW*?V3>X&^q$ltXyR7_zv*pPBYzS3BY=ed z!y)X_{Q;-YR+xOQ^Nu)mNC9#Z(IeXNE;Q+`W4r4dTC8&(Lh1d37!vhp*IM89kc;tB zGd)y?3~=|bIY->|@e40mtHk$oJ6|^{)e}BVC7KeiqMHrGcsk+BH7wV>rGZ3i!qdpkRtQChPV?N2K zYi^kRK&_`XH3QjC-H%&j;YiSGy(2V=o1)JJ!rU%@SFBE6Os zCkJ<2NN5Ow5dmN{ z0lg-)#bg4b0~Rw0-0cJIXf&ik3yA7OuKkt}&`DSWHxtkqRRebsnBiBXLJtto2~=Bb zBrrc)iHoKC00A3Z*h3Cvaf%CIk2ijcaqANkdnMC_|Sc%TF5O`Nn(CZP@zXiwGv7S zan)YWkUA$xN!6PA8S$*-qa4_F>;|Mle-T|IX56k#heG(y+sfq?(W*rCZaP^*q6X0# z<~-4_B2ky{Qb*cjMJmyFKajGdp$avm&DG^YGG_zLN$JV*<1*Blq~`oDuS9!NwUbTg z?j$-B?yX}E$JUHt`%af9sN6f|zb8?{BhEHx z`|v;fjpO8BGOij0)&uGjz`u~H9WqqykWd?({{Wxy0_u5ISDODU9!Q2lI=_b|L@v@Y zyOlpEAdg5oclj>|(LXO0b?J5*>e(jsAc9G-T7>`M5*tB@j^G+6-SiM&#!$|L`51u5 zIS6lwYY)V)BqXB`fL?qis(x$CgJ(un!4l|=@MLFfuhG~Hz@asQr>pu)M zP=5w`6FY+XYvZs;>c0en)c*~HWc~L*llV`;1Ar3$EC_!6_M{g{uDEVO>I9MECbz6uZ`gC4C9GX75j2b z_&SGPK{R}EsER7?jK{88nwc&>fK!{+R{0UiaI2)iY>ib;g|fjaIZ*alg=XJc#jUMW zN-_G2f5l|-tU{)*Rmd!~3Yj%lA+y&iWd63wDNypw2o$%1(#Y_^-Zk@xqQ2%LOA{|1Gbpo?sJ1BAdCITKnjkvkVlI?HcA9Gmr>Lg!D?1Wog2C5^gVOZl$FwH|dMH#kS2rM?KHc+O%tIr)70+$dcdlISl)m(wZt z6SpqyD3{D(hnMO6arvBOPS&SDFPnoAIuHC9+T2^Fdm^K9ZyDQEk2!Net;GNELTR$& z27JIdyimvu&T0^wNLG;p0h6AqxQ5;V>U;c;oht`7PQJu=uEeD$qN~J}U;QN*oi}F~ zTFehqK3`-+mw?t0|HFUDp{?#R6b6&uTN50+F0bHzMfjf(Ww`YRGavtB@5nKp)8&3D z?~afz)?bE>>Ki8StF+spGDY_nB9;6 z1-rr^vEO})%3EPhQJ3EMqo;yBT5gZG1{Az0MsRx;R`1|{?BsG0=8ndaI10Sl4$R5T zQlnlHH?zWyT#(_LIXS4K4s6=sf9%nbVrY7~btJf6z$cR%H<6BJyVQ!_6OR`Hrq{si zeww~muA1m*wb9uQ{0RORH*`AksG+!_gmELPEN;lL?#Mm4M!S|4L{xF6*9PPU=Vy4G z`3h>iEz}cdHBNrsuIf}6X+BqgmDiq>lrO`rQj2q8Sebv2VdcYnVk&mKWRCo+cBT6= z*N(;ax4}v=Hs>;kJGA}z0l7y&mZY^>+w>y7TF2Q}%j|QP{IigN?h+e4fOksAkVpo= z>MB}x)pNPQxf9xUBEvM&rS~v6j}oOzbIKz}ONQ)7d4$G4ro-^jY|PAL+87Mvmw;1W z1+`+f%(6~OD`v|U`eYXj(u&zUhVR165nDN1`^$mM-Lv7}0KT2+U)vlQN;`2mAnGFR zC-gCy#8r2U#3k|86Wqjd4r3`rJ&Re_nknz%lAx1ccdsa&an-QPWbBS&YlT3ze+XtD z(e%+N#_Z84G}GZfI%POEpL{tCG;$qe0~iz6Rc(~2y7XhUk56H@5W)ATvd(L;>^GT+ zlmDW^2xujL_!n4WMn18}H|kOs$1t(}lZSAWj;p zB)ZJm2cs?%&6am1m^;a~yR&(u9`vQ18`4Els>_hx$@f zxs25=x*{;tTG2zTDD(4W}bzCtAbhaYsF?52moI zz`4T6|HA4T{EvMzzsI7FlzL?sD*I+Wmv@iD(En!T-^fLP9z*xzJc9hUT7MJzt+>eo zo%RJ;2b9{>8SQ>Q|6^SIFIWk^WFYkK<}y#63~mFrzdrD-Vs|c zaWYg^rEo6Z6|)OO;S&%(fKc=~gd=oV>MX~jWJM>?+QZQ0*!x@4S_At30RNt_Hpkve zo^sV_Q-3M>zY$FWFVVRj#6|bB;9Ko4dLBhl58!W5xC+Ai6ds3g7=j$b&oK4KG5pCB z!-Yq|K5x$eW(Rt~WBJ1PXMPks16Xc&iSiV9UkKj!UKyxcyyukn-VpRY72X?z-Ww}= zAMw3$dUzZIwH>1t3oWQpcuLkhbgoDQMaG88Mf z>DigBP($AQYK1HD-kCKZ3SWb;fx=J-n;{gHp{gAeJRo~1{0ZS81hvR%uw7TgQ=}!% z*#Kqsni^QfrNjIxh3j!HsAq4fla4=CExHZibY~rUajo2{>ygFvD;zdpb^ou$)#ocX z<)en!Z}V#w-t&c0e*q}G1VZ#v2(=;9r0~|~N}UR!=u_0xfqD~@ZsuhDJU^|l&LR8_B#5H=NAU0%g)#_b5M;|bX6$Fs{uFFk0}q=m>jnt2Wi^8! zTUK{eC0o{R2(o3p1WL9nxjMAaY!s=iD--Li7h005LrQv7${tl;5H4J9dZe%F*#5uo z_e89>(>e{-4X`b8wTks|Ydy^0LW{3?!ciMc{w;oT8~#$#DrELqg=g`NOn3DK0;@a) zX1G;a#?edDlj2pVV6Rn9f^syd)H187_#rS|&CC?Pi@kEG*{K!x24nYd#gkC=al@!< zoZcVlO?nl6oC)t%!O3P-9@xpTPmh5Y;2SVJGBf&G=yG(X^@93%1B)D?4U!|Yg8k6- zfu8vH+JK7y!%YhwXJpXCMBy=1vW-^<`ZULudb|nXVH2wt_JVH*Zo?}fbc3+O>5EeJ z>GGeeGMd6__{1tjpLTatZvcG;q3BKYqKQ=sM*_VJKw$=iSrCeDgK#Z{{uerG1q6xZ zSTL5~CsZkH3|3<4wFWkm_Uplrh4{yWlWujK5l;Ze@1@VPvL6c^^#+BZz3^sj2)zy; zO}a@BKW42kI{~7oKZJiF^nSL2S#ct@@OqHDX!SgV_aPv!bHFy6D5Sch6WSH7L}L;p z444c(V=$Z}T7>Rjk6v&;Uidr&?#l~*f*=VotB0c#;>8doAufd=32{3FKOxpKbz*7b z+!#se1Rb&BC95P1>t~fLT+t0A#GIfv6XF2yzIW@2-b>1R_Y8V7A-)jw?p@LQC*NDC z8yu(q8Z)WIUvG5OR;wJr>?q?}Ol5;nu;@1))bpH>ML!D*{vIy+cV_XVqDS3}9VOQ$ z-kHVIj)KdfkB(wk4$P8+%2NhA>JcoF*nY9^gTJ>|8=FBtIP0Xse_?zwfWplXno;O_ ziKE&;C|W%buVAI{JA?uVeYkkio5QngR+YlVu#-jOf|fZpfNN9=5^*T$8C+0@%>{UPWb*j_uW zH@_5Nlc5iyo~!jfxPE#!UJep#EAd|ITuJiE*}Fg06L77wfWZ9O#| z#j|S^zBa;S#TeeF!K_#`6bKWe>VF`rKAjmnwD$^Tg zjM$m8-NF^)0~sO6%5lfv@HGcHeb`=33%CuN-L&vLythZ%yB>nH_cjD+FOE?B_I@@U z@Y^d5wijfjy=&oX+FRu8GqG}Q7yLQSQR6rxvu59gKy+^gex`?6YF{)vT$mlKJ;+M! zuc3}WcAOFPUJUP*;Qj14+ps(o74MHOqqgz}-WA>+A(tAyshq zm5xf;i;KF?Y2RCC<`~!U(_2)%57fue%Zu+^7aFMgY#G1j4=yFugR~^M( zmeBN`E~h27>0PsH7oLyCWKZ`e1n%kja!)r8H1}`{U~&(adQ>+c`#QRQcTe{e5c@;c*XS@d@DBvd-u7KBC5Jj&-c$7ja+@6IX$2r4|y=>=? zW4(6*tGDDu&JsheMrBQ%*-58)JIs>ik6^d(2Iqsv(8VoJ#f?%^LGe&r-RNKyF0*b{k-Mf= zq0f4&&}Xw%=(EEr^s%wYj(oV8?c!^37CGK3T){J}LS~*(xbMa}9{+W~EIJdGo)b|A z@jrH42CK)3iK+TAf#b45dt_afs-EGK0LN#`<-)npXYsP5(O-dn%~!a*_v36n5Ypq} zNvVqOnX-B{=-1Hx$Ju*Y<10x{=!TRlsQ)~hw<8PsfS1#g6MEmgV{)pJTXet79)=(b zs$QO|uDuxb{VKXy<+*c~e5!lV>vhzUVw4nk#QvRKweTm@dH{s%kS)uZ3RiVg3mc;i znW<^(kge6Wfk3#i+$2KhMF>g+|us0&~vv-h{+`j;@I zTbagW?pg;G>sfp+=KE*MY=`1~rn`!{%ee<>2mgMT?30%fQDgBxwo0zy_qeNiSjjyA zqmM}oE4d)OYBFyn^r)U5R`Wl>T&ahu(}FD(O3wJAuMthn#ww$ z_M*pXhSja)k3hH=f}FNl6S;miXj-grBfKRq)q$CR1a8e37W2~)SS9n*@<7l$sp}3` zIRc*zLFcDM&KhIHmWt}s!UqWv1G@E@huc-`)`)4Tg|E~LtDgXfaV-}8~8!`)hYnxe^4Mb*Pe;qpu-df#@Ja+ul zgqejR2>vWs6Mq&m;${}Ef#A=AHM6r&1Tr}b>82fFF$-J3$}D^f!OlX4F_Kxh1~CL? zp>(mCg}LQsp`{rOxlG7es8)U!b_8dEqtYE?AYt|4EG%cOcVhInV~k|C z0Vq5H;SUNUAcT3^&<-7|LE#om_sRDBVQXOEaHlR&cqZ(n1FCrVDN1!U{F9E;cf64w zc5VZ++-SvHpsX|h>=Ut*Ie>dl_#l~zHJZlL^&Y?dj%UyKaE#WGh+f$3YX!I9t>^M! zNS0XlDnK%|x#b|dkb#`T)EvD5dZ1@+RssgdZnTt|iSj>latR=`|kdnydD&!=>t&pJZ0PJV~ z&89}~8zlQ5vQ9`Le5mU0fI+Oyv?_(Q{x-D=UF&5%YO-%>3;F^}t6m4u$Cifg#)!|J zmdcA@-veLis6X-3Yeq$z#Iyu$7HgYZ@beT7d+<{<6E#0d;XMe?LU`Iyuj1!==N*&- zO+(VxbR3$*o|zghPj z&U0qIpV#j{uUAj+wbx#2@4fcg`|R7#EfEVRdFVw>+zaLqzH`KNsRKoO+d*~%x|+Go5^!~+k2eWS;g zv}-7vX+H?|GO)e06MVu<`*l~?c>XEn%i>mG$Lwm(Iq-F0v>z+uyOf_J9f=zm8`%l3 zn@pi3=tw4@RyRt`TGi8gM%iYg*{UuZ&FL#acSqjAla1;0pFwkEX;sffYfhD0;{vw9 zJZzzu^EHFHLEJ)9Y$!R6svhTD8Eya1J-h-t*B3Q36VZ0!Q4pxgG|c2hBd|eNg{~4r zGNsOvW#ba@jCh29h4BBi?b|v=mx#v$aEbU?09hht(<~EtSsMNupIq2 zqP@>m2AXT`E>o$iS*bPfbjXm?3CVm>A-(TmZBEJ4Uckxa^v6K6VpFEQBJ?@XJYmp! z8Y{jh4kPnKLz`)wqD%li=}kOO+8TNt=!SSO2ij48=)@6xkx8Bfml%53hd5O$&e49F zI7(;{XgY|YQ|TZEXY4(W$Ajj+g$0?8(=KwpM*>H{a2i2#nSe}y(*WUn0nPzfS#tIu z7xTJ6ziF{fGLraT+rnI@OMJmthYlE?R?R6zY_GcND%X3){0gqA07`f8OAmr{tD`>Y z&XuKyg6oqW=$Focbdg^=v$FK75ovMfJmu$#Wilb%@*}e)>tx>nqPH<Cc4t+ zDoU67rTas=?KxlC`zlM{0IsjG9rsHQfb{)->9Wew`#kBKQnZ$JS_L^Df!M7C&Lv)o zuKZf*&WBDjr)SyM4`tsTWIwN%ef&`N>8U)CHjDx|KzBF9H;Ia7aa`zF)vl3L75j3f~Mh#WgH<-!RGg@%q90v>g%i+Rka&byuauUs)1c%}77G;>6 zn@FiQi9n1|x8ytmE@{po&pB+@BFEX5*gEZbnlz$}J$tf~Y(39kbNNp@r*ssYz)Js5xBxIgHsv&~I zB8*_$dML#_zO!jw61k58siP#$e1pdeUO=qbd3FlYn2zA}!iwjlRAZOGDo2*^T zNG6TC#8B}z#GA`u=}EIqi8yzeG+U05203S%G+X9OLC%*Z&6ai0Am>U(Ajo;rWC{m4 zM^eoBkz&q`3{HJn7U`$X{t5cgFuNk@36lI5v+W>Huzta$W#GTxJUDuwtFp)L$Dsco z8Tg-?onC|yC*z)C+>A%d@K%M!=JetROim6X(q=HMoS2I-dsB8!EfAeuqU#sYRu3gM z*-gM2s1zQ*9S)lGr(sRQ9-A0d#p;iLffs3l^sbFG4=*wgi|o>7ct$KkD5n6sX%KUc z35>vQDV{^hVMpLaT-FGRZMj?_bmDwCpD_yC*ku;LP2<%1d z6TaB_61#a5P2;sl8oT^yyauV;5XnuWOr%!3Qu`ullt>!;5c^AC>;#N~Ln%p`#_N$Z zV%{;w=j)Hp>e%LGz#nv@0!{e1g{Fs0fQa=$8_aXOE&0^&6WoeM-YQFGOO;>*#YM* z2zcX1{UI za>8zu+W@!Oh3FTG@h`S$q{y3Be~Lu3&jtxzv{l}&*=BD8@h<-5)G_h+ZcZJ><6Afv z>svUVBTg%M6XK|O$1TXM5<>+08iuUj2DxQ&bf#SL9^{6|(V4Pc669+XCO&%3{*ag? zQqx!*J(zC@^GbkXiW!{R;6^;|?xKKs`@&$TD}bsGMBPSz?hIjaw{d19cN=}V+vv-k ziEoAko2V%DcTu{7@3^J@C3wqBjysP_=Q*~F)7Y%}rsAXm)E#4{#N^38Z= zDUKJ}?KAme+zZEnw^ILNyMZv?n+ZS2(@M>Ri`ipy;RDOW5AHR7kPbg!RVW=@6=%8R zH43F)0!Yhwo#p@;!0Q?L-JOTy zb+eY+P9+uDH#qNr&21;Ey6?20KbmYTbpn%H8n*zLEsd=BuhGRMF_i>oT@Bl6hyW)Y zAVt7Kh}l^{^MGvy1sp`kKmg`*=NqP>GM~q0HgR?(Xg;$xAWl+KDE@S24d(|0zbMkz z*21zaK=xsw_JjINK$8n?>wAE3A;9kfE~sr=QQrVe2e?2$jYM1{B;a9yRs!l>WLuXB zcm|-SfTne9Yk+{I0D}cwc(HAb1Sqtp)O_}2*@6ZALk}eV*$cv0Hy(C z%6Wz1z8vHG-0Wf;KBR^X9=pDPE{3B-Y(jCpYO?D=7)&I zJo7YRRi8tM%XNn+U2YtJx}0n*luII;^Q$@cAqRX0vPeY-Y-AI6NZ?&QJ+<0;ls8sWrbLT~P5nSsb=OL&|@e@T#VA*8QW|vWfSXJLL z<;=MUM1o5Qr=d&8x^fpK&?g;w*GNdh_SlCpw0lQ}cZsG?>d;dAB&An_X1yw1wUur0 z4LhYLgJvIP=ujDGZV5KYmyvF0V6tu9Tm?2x%1?=xJ_|HQ)J^kcL>)?QZJSdR&FNR{ zl!m`&a>&J!OY#$)loa)!#Q>iFxY4B5iT_*&X2gF+s}geIKYPHX|C|Ld{$qMTe`5WR z*mC5E&iW^Smsp8k9TM9QW+buQel8Mg*G3b&5y0K@J)n`QBEO+!VAPcHM~HSe&qRZ* zoYzo&9W*wHK}v`NuJSWB_!wm_Ln{27ONf)TJETq`M5dpZtOWd`R9z&Geo=zw)L-(f z`q2#g7obPr)Z<4E`_tbA{hPG^A7|f-SyFmpef5hUXUlu21@@(B` z_IW>hk<0$oWhcCCa!lz`m;IZ|ZsBMD>au@#*}S8~vj1|~3;gU~T=sdFz1q)i*-*3gugfm+vxm6s|6KMyKfBOnTWm@)YL}k+ z6$EoA6U|^V%8kmGp-+Jwqcb4dwF>5Ctd&@!Kn}2vD%Xk;9HYqzuIt0?d^qUCgM4_j z56|%7r9QmQhj;n#K_9N6IfjRpXwM~mx;;J@z1Do`xyrfg^qg&HaxmqQS?sqwGP}Ao zH$(FIyGzya`TJ}21nd`Q^69+E{tTO}E*l9KYb!Cs`R|ZuN;Guka`KV>dK+yTxojH9 zNESzNhRvkbsRAZ7YIdxbl(akL4Utlf4MOouB=wBxt7H(WEUSvg4|eW5Ua4 zVb+aEd}7e7r~Fy#iL5ob)HCZ@<+TvAW+R+ty*gsn^BRGBJ6A(^9wK>WwGJD15Tnzq zyTCO=AB&sJJv0K!ovF}x_M<5CaVd9iQ?4H%NE`QNxy7?t%-#_b4^jm*ao<@LJUdT$ z#;AWmaj#e?A7G5yxPvMmV2nBnG>tmIB>psLrZymA)ETOgM$Ldx%MmGJ)CK;`TnoE2 z@8}tIh4N_B!3d{OheV9JS|iY?Lm*s$NS;xPmFpRGH@JSI9@hvkYPrH7o#{rD`5`Iy za8s@`5TsFun{uaJrsW(Sv1-*1B9FhoDCA`^A{ob(!yqk`jkG!_T*|a|Af4YOtICv2hR8NE_$D#xEdJ#KvjLW`$2d)=q=1{lOsR(Z)?W ztBt2dY&={e(8g0CoQ+7HjdPXj*?1nfejD%92q<@{LgTmzRdB5e{spF+a_xd3%RRlK z<4%v5c%Ld@Ic8RL+%jKA?D4ll@l&Gw9;5sRSNS~^mERLl?kbSn1?HigjW1UtA?wx= zQ@LU#d;C6V{#UdY80}ez$*dPt)LuaCp}Ao5Y)7H7s?0AFRUwPA$X}Grc5|#no$Ph}NSsntbOVXs^4XFm*fACE0_$<4|Z2Mjy`_MKoG2gDF)NS?B# z4nH(?xS95u4BNaU_Ib)QyQd+>I(*95C%UUPyQhr(hJ$9ad&;M>0#`d!EJ4z$4Tst6~fkZwk$-`H;` zXgbOMh?A^SjdYT?;3SVBQlwyq{5gLgIsY1Lb&})Cqm$IVTAk!@#7RzS1eWVCgwqkp zbCOfa^_*lDxPB*b)25TO_{dmTdJ=^}IHx`KaTwq$F~YB=kk3F1jqs~6LVQpQ{i|`3 zOwe?avk@mrQ;l?zzmd^<5s9VDk%!}`NZNS{&BHMU?~`ZXU*Ky~0nb5sz5LKJ zq|^zY4GC1`yeo7JbfV1Zlz!zJ^aWUBQhL7KNSKXg*HFz&W{~E9&Ql$mVJ#tLdYFZ{ zx+p;|004;eL2R#uZ`szSm zA%s{Rd=oZbg6qz1>csR#@J?tS0KhkDUjy*ogx%@Wj*F-2I!nPd>bc5!Ncn8D^^nZ( zq7R)EW`=i2&#io(8eXAK5$KIm-nXNdF4t2w1l&kkDV5XO2R73x1dz1Ce*l=*wX%l9#8^vHP}Ik!COU1h zZ0mLeIC%h51?&Qt1CSMmpFl|NZQydXb~S)m zKsB!-9npv_peB%mH zIso&Z?@KyR02kPc_{{%r0L;H!nBk8mIZS~v=I}ZIlfy-JzL;qNv>z7jQVS`^jf0Jn z{62uUDT=Sv+V}uKY9m`}B13ATLR_hlxFM!SvRND5KuK*B*j-d<7bp$S9;&sn1Hh{l zH;Pv)`H*I*z5(!R#f|3H$__9iwbDn^As1z?hZI=mfdKwmnWhmr-;rAR1`+uF7*>(Q z_Y*Y&yWJIV5*wxW+L_ChblA?`g$X0RUsr{tk&-P`f1LJ{4nEbe|F9b#?}ur04sRHaIPn*MKagfaK$ID2tX? ziGu!u1$_lG7*T5>T2F~Oix*+o!3`ggkVE6a8w^8=8sr<=vv{+J$;a%wBPK97Ep?~} z6q!gIIo!{yNzzh>3u6-{(o$~|;`zIIZ2?Zvkt|lyswpYwNsQS6j7I=A3(=CVFx$bK zvG@prR^;1K2B#j7NXg~}a$aN6iUKI%VQ_vFZtVpkWd}KstGz&$JyV|^g|i0@7ktF&O523fZUXFK-iVJ#VkE14-C= z-%wwY2wgJ{Hvx@AG9`w74>YgR+*V(T8oGEq8maKN8va_)z2!E^EmR*$%fnqLLT@&7 zy9u_%D>^qB`ft!7;cp~8-(D!hclGCfX)-_+{bCKs_!0L-9MB?3y9(^9U(@+> zEQZrygqr|VuL5u@z{LW#0W=4&IBLsl3yJ-Z7(CIo+F=-H7K5v*b~fX;>PI^ZC%L01 z*|IJcse|?7oNEy*Th>lZ0B&2q2|e7leijx2w?cT}|eeHbgz#-^e zI9c@$2B6;N0MuKqdd*9SWs;K*kpJ~lZ1WOgJpjIh_%bB;65*>O7HS3 z{~FR)fbU8Bxs<-GqV##c^f&dR&2{GfP?557YDf>MuEBlh7!~B}lLM8&F!APGm+=;k zWRG?UdHwN}OU%bG^PEfkfnjlnuZ&A_BABTJn&?GnZC#|rt>={pdaw3+zI<=4t$o_G z><@C#?4D#KJ@dI^22MMrLG~8>yS=G&NqUoLQ)!&$&d_GOGjy{(6>(NeI)#OdXgc{q zPIXdwMe8DicS@upMoLTl?tL8Wd8Dv^e2kUKxB6EXo|l$w#bh9;M(4S5BlHW9_)?_C zb)5&E9sI)(tMOzC#z>1aj9@K;*{3#%;M7yUqRW`jm3?Yk2_J7TyN;P%*;}#On9)_b z4RbT^-6p)N#Gl?(3Y^NWW17M27A7-8sq8YQ8l5>3f1<(cTJAJ@9{&Y-$TQ)25@(W; z%@=%E*Ei-w!fFKVlHlr-je&WovmuPJ4NmQdemqcv zky3d_Re%^O-huegq_Ag-7JPLLuzjCGQOqbmltbW2y^Rv^)PCfAr82!nBrjdwtuSBimPpFQo=|Qk| z3%i$JQ!m5DmjS@~N!XKYJ9reg00T&a2r`jLlnLICfHsqD`i4B>fyH5w_`eWsf?-XY z8vev`2XB&OnYp? zUN8$!4sqX~n~4!aWuV#g{%9sS3-!&%L+NYO>#vj#U4M^`4y@)Kf%)ZN1i#ShURbe%!7F?D#=>tHUEV6^hQn=-6+qzV8F&>~hfO!jh zwbnVuW%~-FonMeiQ=Y6aV&zG3a!{O3_v64C0-UFzc!GeEg}7H#fV0xJ3IM`Q3vBBF z0Ug0wD@PQY0x{Ee)KY|E~Wk2Kl= z{D%JmSx>--HCTxeu;Nk7{Q(N?tMEHotx;(A1y%Kwap#PoAWmsHxk|jb>qXA9FvA^S zIHv&a1PC{P(t81l>?Qa$1N+_IMVdsQez!R1p(p(V`!cakBLsJPN(bQofzJW>EePQN z{2>5uV1GdMNz0M*s0R^U8~bV`ns6!fHSSj1`DO#|phAGN5a2}tZ2|TRI0$`*0T$xo zq{Pnv!u2-dY_EVt0KW_P7a$5_fbg)Vakf{$a{%=PT(k*idj;GBaG3ziG_9Tj#sCZu za13BDz#=;n847=bnBzfOSqt%7B6&PAv4+!aJ6>o-fD;F>Q$RjIserct4g!P|cVO9E zKtF(!0_r}CXNG`ufb#%ZDS;TPOq5oc7;uUauNwlgs^KT81D8c+3GwU z>H69`z*_)(4REt2^Z(xf%cOA901u(aY=CP3*Z^+_U<0hbtzrYr z>;#$N-7aJU-2KD z=2i$r8emml?-#fU?38CTl`_Pm=Z`}OJ^x`%&NRR>QFsd^)`A~tfI(Hr1~?k*BOY7M zNUS?!ica>{Zn}8l59Q(shfe1-E+4X6x5r%oatmG$O3R9a$J00N= z-hj)`rT9+^Tyd)J;m=<#q|ac;XG$m8cSqvP(%oP;L+YOLAwFR$&++n>BMUf*-`}qr8;uR1p{6wC1FkC>&cZnMjt&ci(&IAxcTtfDsSG$C~>`>woA~RWi zJZDftj1IJ>a^7fy{T!DNZFw#s(R!#o8EuS9$P&~#KXK9}>f_3ob1osJPExDzM()lo zAv>b3vAKqIS~*xF&U`8gtrhoz;Xiw9&8AhX%keL8jH?*wx3`G32FNsA>DNFHHndDl z(i>u`Khj5!1U*6Mk0;6`HuNs&=|X=>eWAow_;`)b$GNT$YL^^qE%(uB}y&gPck3)bz*(I)1jGXU)Vy~lAFL;JTclKO&dcN3cFmlPjvqDgk@_u#izRs z#w^ay5ayQEE&y)VwrCscZr92{C?CZN{64X^b1lM?5RfG!qEdv)NXRKcsF(PW%G!Si zmuBa^p2sS&vzc%Yn1~541~B`?R)&m8hiLR9Dd_o$wVV))Cl$|e;&A1P8TgpW2bYzy z1Avvnhv8_ACr>F>`8QxomE(^cnCoQhU@x46OSVua?7-MjEYQkllXK(ZZTJp)wcZBw zQ1;mSl5hVWq&(p<$qF zi;s+>ytal9@>Z-je!+U~qsepPIW4c6)1Zmp)Ps~w9}@O_uxaiL0Gj(0lA*Z^>;oG6 z5Nr~95fPe6^7k-#rgqS;Zcbhu=OXMev0@ACGUZ7RA4)@bM-iUKk6>d@*wS3D682WG z`3}O;h;BCmv$`C*?{;0@~pI{P7IIskK*OQy&j$%}P{fg#T$UJa0sP(FwLL@2dk<5r#!8?=y{>{jURU3=vm zM4?YBD`x|?FY0Q#eEPI-3E7w!=o0d-lUtQJqHUdWq#ys;Jnw>7Ew#tKkEOnZ8Zc&Z zOFGg^csO#eFS#X``?|e^**S`>{7~#}jHP6`tOMhR=D&lGhTgG9m+RUYI&ZHozoi(u_q6w#3Q_ zvS(%{a%dr;Gb%XPvZnJ7a>3&x9bVVtBLx8F_((n?h0pFsHX#vCc>}|L0It<#io6^f z`4X{tK;b&X^A0Gi)6~VmW}JmWO5r5s|KZ@(d@$BJ4`JL?+fs06&+a`gB}e9K(5)?z!l zHv(R3nKc)eotCg%E#sU$P`nHQMfP6&hI0?#gB}1`L-A84kxC{va~31g9m2j2;7$Ou zER*<)NsG4MHMyFz9MZ=2Tr<5K;x8h2zZ-0E-#1Og*eb7Ud6Dzro4W7&Cn9p+w>?6* z?>hn@vhN!djWLc0;p zwbq$zz2@2Hix8Lz;R09KObt3KpQHB$aGEpVd!zR*K56!v&EE5-1~T@~^h*~&ItP4D zdQfHQ1r?>oC_f1;EU*yLFZreOe7eoFq@r{UZ5}ksB1r#;hUKO0=TchUPc!|!xnLD7 zFR&O=)!+c$(;mu&;1VI?Me8f$)3bjP{y8YE`aIDI6~;~yXg_APQJ%9 z4v85zwYZN`ECt`tvZ3=c@^7Zo;=VOB|A~_SjqpHuhsZp~g`MJOKMnS^71(|J>`h=V z^w?)`aKh~phl}z(sLsJhZ0jF6*4iAP8fIipIRq{e@G?MCfN%j=?FH-x=nB9(9<3?S zpFWrz>zo1C^QSSse9%LhedziVrSp}~c60>NIpBNJbCoN)DZQYg^lHEKhmd~BFI`+& z`X^7?$`C8K&jDKDC0OBcR1K~0AposV^<%X{cK}*p900Ab7QnMYp4KvJORR7NT(2B{ zF3S=3Nd+q`P-)swtk4a7PukC=^w^5h>-^GUg<`+7pG)ZvJZXJqmHcWvl*?5gVZ1O1 zJ%VvW>8#wr2CL`?u;=?bjD0HXRnd#!nht{%yw7i#uOVIKQ(w{iTxPB-xIXDJzw|ed z9^;qxb1D5;Md|Z?>2D!@*e~tpQabjyn|4n7?YR5o7h@Klz8UBevJg__5^{O@F(qUr z=CsR@(>G^bLI%0R&#E$6#>jIC`LNhNmymUklP>Y%$I;d~myl=;wJbRjt=%80O-A4Y zmB5zz?bt7W0RI9DdGn?na@H?(od^^XW1ziMwdJF~ zvd6Z;AbW-kwEyIzF(+baAV18+kwx1;YbnUyGmtiM_w z#)%vWD4Wqr0{(UbmXybIk%04FKyman67UZLLXSfykK4qx;$XV3}*vCEfE6{e?a+c=$W%O6Zf|=?LcNy)yuh8w`!(60G^pnsz%RD&A;}WDc?2IY6R0v zg8^u!F9D31&Z!QXDH+;nrt1JaGr3VbGo^f^W?Bs3naPdjn&~<)BW8;E)0CcEm}w8V zG}BoCznRu)M9)lTkr&rYZSce@kzyscs_6_ng}zFj*Tn#Q4dojE?=_UfzalB}HI!s< z&7gzB+kwhwLTy?_J2#>cu;1m|E@hHTTO@N%f+d-rXcSCl8A7~dMpaJcb#Q&j6#J98 z1j(F$8Z(BG*-)A`7*3YDwW{L`MpKJCc-;2HOkM@)07kX& z<*8hksNX5ZTICY5;4n~4&VF@_OGv-E$|XeRkP_(Shooq!a!y=<1ClNw9ebJ*5^ILb zkXS`7A+c7wL}`~8E2uW$t2_(*#5yI=Dd$hd{1SgHu+C+VJ#lFjt7`{zkgxWX4lI59 zh?a9@T#v|jc^M+;zw-Piv&^LNY2f9nU&;32weFkodH{Iv!dxC>vRiF&TfFI3pS>fVy=nLqfINn1{BjYH$IDE_ zW54+t0F7VmcGvhzwX8IL2E=LnIRKvV-6)>%9Y}K$^(=sAd^ehF{5fDojK5mbAs5C! z1ul)>07?0c-%j1jGyX_8ru#OF^fUuC0-7~8S77}I5Fygj$83+isX6W|!N0)X`=m*xFW3`n@uc(K`=rr5 zZ_nnL*EjByv#`%&$6k&tdlX-fc$>WWc1zhJIxxTPdq)3ayT1e+oX@6Kq^XJp10Ua4 z&1t{aT@05)TC4o*y7Ox}xnR@6%K>QN0$k!_G)q;ca=E_V{N|nT?hW4Zd<5%o`w^9g zu^Y^n!`K<=OYo^pmEj_M!}+zcuR|c#yiaMkRFu)xbpE}-U{%!uNHU?8uj$S}oB48E zqwu>ZUmg~rAufN2E1s!r@ySpj*j&-sJD+`6%)VIb);n=jch7t=Hy?qyD$oJ~f!F6( zbKZxL)~a;>9h9GQCC2hSTw=raSZk0=NYC!7K^2#1ZJ$Ny?6ITJL$8%yy2>@I;!DQH zo1t-)Yh)yx9yKoB44sw!9`v6BBJl^0kGJB}BlI@VcgaxO=#!E3u^F9zK(`;D!q7{3 z@m2#7h`UD46o;lw&~CpTGZ3;T#+yaxy4SGd9}b%1=8Fygj>+-378MCpy+-a34ebNX z#pr}_vtiunC=lEb`Ye z<-d8KKAdVA{tsWpTTgxreuHaDW<_JYm?!1uUXwo!xx=46y*l+vSnLMy&}@%>K@G@i zfQ~h(0eZ+T*VJ~pz&`B};KTxS1qh#nMXwQ%IVs-C60j2BdI625#9Oxk6xmZ40pvXb z9t2p#@Q3hQXs^d_!#hp-h4xlZLpYP-I^#T$8nMDKabe`t+KMoURMwtqllpVhZD} zodDtY07?aXSQKv^6tHx0ymd@K?)tCz)FRqqFQ@qu`}xeV|e zoGb}|8!-o_n~LQ4wpE{KXZ8L1)G_DbBs;AUd2)P3(;$An6(!u z{46xTD`51>cEiOHFgneJiwc&;1Jk-_fvqO@`y5 z|L57v5-FS<4NG|)V-b|g`3)T!kB039;L)&&VCmV+3^|g}VSc0#fp&cocr3yVWZt|p znrW`)Eq8D>eaBT~WqcnWClx)YN&)^>{f& zoG-zh;h`hmzz7!sPCWn~Vtfw@c!+TxfH}k{uF7M?PazUdF;+Q%A+8)FUI@Tr#D@WR zin0Ei@#YlcD1cVtDu)1gin0IOc+g46asZxUJPlw@F&;vW!gWAKPBC_9f=tRO#%TxD zRbK(v00quv0QA|IchqMy0O+%;0O+$n1JGx;y{A4~^^nhJb49!O?0|QDKD!j5^x2sR z^?bJTf=WJH0Zl>BkJvo0lbd)tfu68`*mPy zJ&3ob6q<~%pYH~Bd%!od3!Y3?HlMUtfqmVFZfXE5;bH)m@T?|lWl4LGHXds+Rl zwwE9P+shZnw7tv$sMKEeKpUGt@TfMNod9e&T|Ux=vjTt(ryPLCe;p`ddrA33+sk|a zwwHFFy6q(&IST)VOhnpCnPgJh%Pz!X*M8-3Z7=f>!uGNhA?)MN0Ix z;pf_3UIFm>_=Kj=F72iEXTJ85iBPtep$PTbOPLy)wJe9*ioo@?mlj2)p1k(b5-EA@ z#pQbKWeB*w_Hxcw%WN;NLOa{bF95#wlBUW0|M&6vQaEWZv&*!-3K{>ajhW0T>di{Z%sy9CAPSx>QyTw(kVo9q;-I&VU9Ap)Fc_n^HB zxEtU_fbbE3{Q`n>&|U>>2KWr1z&@)(-V~HHoOCaS+rke6`~iRwlq8bS9EprVA`c;) ziF^*gL|V?(MD73(mEpGlm`K7rlWc)K;M(5DGl2@oa2 z@h<=_04TES3mMvgZcxBcfXf72x)D8_fJ0BCXA=;;2|XJ?kv$T>h4wi7md!MlDzxte zRaf3tl}ac_nGQ*5I`qEK`D!iFMB>gGfD0rS?E&fwXu2NB3K#@%nShB;B3S|J0R{*- z1~6Dab!2%Y08++po~CSNT!A^nW~F3FBQUUct?(LTKTT#CrvL^CXozy;3K$JAM!+Kg z(*O$Xx%l1XD$Kg%saPuki%)^2z2lvJ+v2St0-QvEfdaN5uR{b(N607vsjzb%K#{!w zzu{7Z7Ypc65^v2Aa5KOPM%awsLVF*6bMsx(z2l?swO`n7#yy6YDaF~_yQa9OghGgg-DC-^TyaV=XFdSpe5Sh%MRZV6x?^51m zJ^_(^N;ax&__%5_llk+m5@U^G$-;@g^_<&aE-r2C1)wz=>{M&42H?_0^=H)@j{*3s zaTp|*HrhV-f2~n|uiqL+3_un&%!-MzhMNId3K}E}Sp|JF-8_i{C$xllhV-ok$6c~CmX6!) zd3D@40QQXwQR@HGHy%Ntc(C@dqGx2^Mxv)QntGZbJ8S@_T|MIg{*Rs)5E#*uCwius z{FK|&bMyt(^8|q8r$R$&g+Ml>p#Vm?cGQSjEZSyEuA-JCQQ1o`s+N}#}H}FW`IHw$ux`E*|e<|MTE8up3YyoQkZUD%54nLz*P@YnO zxBJC9V|T|}`y^U7fI|X`0gelZ12`q%Ff^P62!DVOYmkgvOm8hkTGzL$Gw@~Yt*ZdA zw_XOo-ntE3gMIV$0PL-w17QC>6f+g})*N8py>;@Yy531;8Hp9{~2q9rkLE%>2*rXX7GB{tGtq|26>gzY2i)zX`yz z;#?JM;pYFp*EIhJ0hs@X0BFTq0GR)d0L=eo``rBJyo3C2(6Lg^1K55k(N#B|T;J^y z@(xtKcAqAiK5F@07x%f#EumvBryjalbUDMzAJbqRTis)bARTM-$L zP{C+zE;&1f$5?Y+LKGCa#1juxvCjF4s%j}JXy+25Ak8I2L8ePcqHeWNW`WBQnRPB9 zGMimuKJ2#BCB#&9bq#@Uj&yJdG4B|4e->eZONb0!`bTBr+=mEwr0M&NvH+&#_4li|*O&dFS+7MS@6Dr8f2*WV< z`IL5&aC3V9RfD-VyXN z!}TVg=+1h{PnFKN>9YoQg3@I-=!JfEkSDNS=qH=~L2ePf&`)x2GOYN16IsF`z6R76 z60#&s#h0W}oMl{+MsaQiElJ}C<*LZW$&xhLSTaeNI8ap^oE+hPhny4`Anq3AbxGg# zqv;+r;Sn=_XL86~8JxqwLfU}D8g}%|ycYx*#GS?gW3~0WHa)Y5K;nXMH zc(6G`7mK5cJm!~8+BAu4P1+N{qx)o;ymyAF>Gnen|Kk7jeBCh8sl3>jYigQjNGhAZGx;Go^ zYZ6=|xwf+lrz;;ofb#>uT7YnK93I{x;5L941Z)F%T|ffjyf0t~zzG43aSrY~fFk=h zA+tc*7!u%e5d0R}_3(R2vr}j{16AW+lUpm}4p8T{bVbO2pmB1na~V!3-33PWJo&jF zKhA&9xkiATUfKx2$E7RDLC31JXy+iJ@o{-GqRHbjn~%zs2=*S8H8d;Ufa4Y%ZsMc9 z6M%VC0`O630q{}zHuUjPc@QDK0ml$k)EB$$qEgX3iEwY5+!dC;WuVK&1<)4c*rYcopC#0bL+D9)Ra8 zdZ-#1dIpA1NpglF8rRIY5g1f97l^ONXVr_qHVedZ33;ZnIf2auI~D=nCFFyYE6a(z zgnSkPD69wYm0wrVz82EYAiz7kGTO)Gir7g6m}3rBM(hckKh}oBfm7$?JMg8WTWTX* zW+w@cHBnUcv9?6^_$%?hIX=HxRS%bhdnZ?OzJe+qpDzL6@%fnme2HKH0FTetv7*fJ z`ThXj@%df8Tn6O${0wltGVE5a*oS4<2CgXs&zK)lKAz=RiH7u-e(57V-ITt_t{{Ed zFD=LC)4=!AF0U+owFr;EjiBFiU<#bk^Q9nY?q%`@Du(5;cp2@ zjEb_33g`#$B>)SNqfe~i8 zdd)goASF=6nt*?SvB`2mEqybZ6i1k2lR3hSjfpZB7An6BXpS%q9l9Sh=NeOzWvm|h z2{h*$lapn>5$YcsWd?wg4F5^cEY(D&7fPuTWlrvnH}t)rS<(r~;;y0Npm`zUIMO=q zTAe%uJ*)ibxNBANG!5XHx(-Uv9}1JP(-f!u485t3pZy@ZiBz!JO-N^upj^T26tnRa zDIs@8Vn$H!6O24lX|f8-Bh}%A9)Xd(l>)Y@y6oVDDm;I*lVJ_Sj{x^)a#c z)5hLYkTUK4w6S+wRW0w+ru-q$ywGu{vCo&)qRgOmhoMKsM;Wi#Zs>17)4tCbdUSQQ zXNjSk2h`qM4ZRC={W3JPEruR(L6mimj9NAu`b*Huh2CW7n`%ax!*0(Sx<)On|J|m3 zJ71{v|B|WyGSHj=ylD7#BAz)i;dsu-e|B+{8Q?!}_;njbnF0Q;WX?Z18F+y_t?Gi5 zbMPVgQ)gJ3G73&2e~U2UgU`&kD9VhlKIiyqzWulqU|LEk9!2su-|qc6a?mH`6r9}z zydW_qrmRrS8S)->4Lm31ZxH?kzQAa>Nu4PF``BTS@;-KkypQchPLjy-UiJ^j1mDZ< z4-k1TyN4=eM<(xO-v=#pJ-&lkg7G2W%YMNPw#>R6+c@K*2KcV|NFj*uvwgdhW{{{9Qmt9~VQJ#zzLT5$iG`Qm5)X9c? zOe1hG@;8K&>$?L6*{@XYT!_omHlYe`%m~;i+nh_ z)gJQaR7SNQf$N#!h;pT~q#5EHduEUg?o-OA5oJ_+75JX?X`gON=T(%B(KbeD8Pz`F zm#(T@uL_QO(xwK>{o;LLg+=}vJX=|OnCBjxQzYPNB!6_DEJ*igg02A*2PY3e<`m9) z0GU!ap8#-9!3I|>m6x4T%Slbr2Dbo!4enh4ufcWD6ubsk6I^X@GBPl?7IQ$FiQ2J8>}r8oF=vv%L9C|&B8mI1rf+?V#g%F>;{HEElf+bZpE>ElyjhJ%Pe zAFtg)eY`IKXKr@^(8o6e(8oUq@O*ros$x}(k6+l*my-?3^{j9WxIQcFR=(%s)BMt< z%JsZ-Q$^`xerfUX&-~KID@)gE<))3EKw4Om&y553r$jqblYM#jb6E$~;Hkd6cTs8P zeHo-*#xvHd{~kWwl#a&p$R|C>FTEVn4>k8m52-AD3%EY%^IA5sYhWRy`=D%I+I}w6 zzSAo?%UxHW+mtSZ^wWN6KbO)cDoS_uOBX>p!EZG`m(sn#H960@^H8*P%rad=&H}th zUG5U{zV&e1aQO0^;+$o$?oyX{_w8t_Zj{PDb32CDF7bT{u9sAsiF}_JjU}&64|fS! z`HxY{al%*ECFI_^4lW^Yf8@D@$hhMizN0ryi;p2@W&;d6@hAH2vF%$`v2yS)kTZ!x z`v2y}SzU2uluNIh7iTVe%b7G1Lg^pPkF#$4j(i!yr%$*q&N}%i=)sdnKMwvGp|2&) zyP0z}MOh0944std)IlWP&0J$aTx2{kN~2XpG#O6}M=aAhQp+?SJ1}C>1U9Q_?=syAVBQv^x;($SnLyoG z*9lCjy9L0gE3or@x=e9LvFK8srBa^N3$;AMOnKxo@w0yO4?}ql!EU@%JQ}gROU2J= zG%1fu-9{5xj1v`1_VtnNhb(e!lb)x~?@+4>^85@Nj z0fS$G7_Mc?`tq+>s}#iw%$rohc?fnmivZ^!fb};{1g$|iY5-U{Td-qStofJrxJ&U4 z+s;nYG#IJGCEDSx$9+nO#BrC=82!X~myoL-V;UJh!gR15rh>y|I(U?yU9f|#%Sgy{ z(A<4+)O>4!cN`p>z;7FEv+st;BltI_xy*IVhe^hmYuLBhTfjId%(l`>mDyHWbRYRV z{g`%FV*>|`f2sBZ8_*8yvDO869S8pcYg5?xH=@_${Bmsy=kt?Obbh%uh08%Ng64eQ z#1C1mbw2l83g`1J+UR`l*%Z#_SAgbxZl~cFx7GREHl`Q4pq63=u3Hm*moUJo-|4up|ecaG@ch>ptMw6exSLpn7i=p4V zTIZWvQ^bs+UA>~r2GcVvf9PM(+>qK~=$WaQ+>(6W#I9{V0%d^%Ld#S2?|)5QfEfg`EJ*0{?a;@)Vc$d@`t6bC)!OnjY>AGiq8 z|G9j!Oa1J+U|-hN%^M$v$Cb~zsNcG}b2Ip2^T;P7{87Z-s}MsUr*&e;L~kldidOCsZWa(xpnUg=}>suuJJftJ}3i{cn!2aH2i|K|d zo3;O4N_A%^vR$$E{ZYhh-y(*u_GhSuF33aRyOazk6I~x`zy38^`;8F7+UMwdr$0wG zw2pQL_VszYpG$AA2d-&Kls@E_z7f*jAQi8z__>tc0j^KF+%KIA>3qMmpG)bGC(X;> zmP#ew45@ojATP~4?Q*38D0K>bv!*G2)kk|^dS^RGPYSAEW!;7*Q7TF=X`SFaiQwtd zMl$Zh?+}$@#a!CDu`>@(jFn)7vjH9l;0-kXXk*&faGHS0QO#*+(?ODWNt!Q{0SB3w z<7SeJWx2{`9*4EA<2(zt@qL*nE>Jc*s9PZ206yRupvb422FP$--%K;zCk{RIdPvXq zSGb=`>Fr*HbHcQ*it%q56qPIHv?xZqogA4K&2#V#Rpq!g{MoUzZ?Ru_H7=E&7oV_ZV!RZCq$ zE<)Mh62dvF1cp{YERM?`LM?mzT^LrC$k1v8M`7t-!#*5Zjc6-Ft5Ds3I&>LHz77TM zZkwrE%+`Yvtl)8Nqp{1K$@)cdxys9xp?r@^8GkZm+>Si3j6az& zo&(J?{=_n-_Z*<3RTDon7c@_(oiSzn1vK~2el>J%x|aE@Df0%<+@1Q(l=%#3mic#I znSVBMuNF9*FMuPvOMA4_06ve-YJtUv0!cmaxPo5u zSddQ1)kb#v9(9~GVACNu`Eaec75z-PONdE>ng&dosnB@oA(*pP0!-Sg2i@in^wFff zdWhSEqC;x3RPwcIuj`TPW?FJJNC|prMh~BtZnIBdPI4CiV(%U)b=Y(BJAx%GtHk~n zj0X7FY3v$htPw`fo4|}+Bk^&ft~L0Z&dr!r{&5K8+>Mu)FMM66Ad6c zPUJ_snHZfbSxwy`fw$!zuFkyf1@*0j?3-=}`9axz(>bXdJQ7E`_f40ygXu6+;B|vn zLJpX5{t?0bCcMT852t<+gN2K?r^^Au)C(p2jp}Ka_Jq?FT+G9JS+Gj}B&l!E?~7=9Gk$y~r-@ff4snL_aNaokHpib9R{VaY@X;upDS3qs9X^gSR&V}x9 zA)+2Yu$57LMud4D)(YU0pxN~hnB7u-I?B&g_;J31_4*5_I|wr~fN%(4gn)Yh#tPU8 zaF>8@0p>AI4st2rn<2<0K$e`1S}NuHaC)p$A8gsb$dwt2lP4oEH4sgw*Cqtx<_@$3Q`WwIWvC7i*23L?i>6iW((gVTw(mqvL zdUixw&Muu(K0WgjNN)$9+aX^A$aaWR_u42+&M-OY06fPu3xL}q+X1*O@(qBTV=@P# z5)(`n=1MJn3FGa6NvSj+fJ#FER9YW^O6v_(r2_$|bT)u@II4x}A zD?KrXP+x=V8};^3enZKT?6uS#=93QkbW=JVT%Yt1zqIVN%<@YQuPptHCvEN-%J++Z z3mc#GA{5vgl-U9~3txO4iZ0F$LrNPy?Qf(@&mhnc;F~L@!}HyiM*COrwVE`!6j;-f?RXu2;rJ1r}PNk2i9oTi+1^sa5nsv~16*yWser=2u^OK1#P4L=waZdX3C~FqNGcqeN zuip?A=d1+xM&T~TPgNC_7IOVSJIeVA+=sw$>aB>fo&d<+CUL*RPYsPLcE0{bJH{D^ zDCH7&4#0VdTlI0o-CZf}kPq#E^DLsgA#r~Icwgck#}EH9J3}hLmk}vL;|HRwYY?7! zQ6*-tk#Wu-Fk47cP4V5zL|?XojiXv;_d;NH2tOJBwX4W(UuJ9;euM1e zU^q(vHVfDbunVBT_D2p6NAT+i&S>{Uj5W|#z!85&MLG5=Y$=10-3vb%R^=#@5asQa zQC6Hpsf`~e7gQ68`vG+N)v;2dUxy^tVLCWbYBhZ_Cd| zqI6;9IQK+FW#2FCHS)7j;$&2cBMD~@74}W?GY&ue%dELB#>&+M#VN()SE9U02+u4> zG(S^(VJw*cA)LN2%9qvPe7mwQ_}TP@qY(Cdp#m4a@C2BiFAVB{43zXT8LIYBlyx=e ztX>Q8VGRUczaBQP|1cUB0-TQlZWr(_;!Obi+$_MvG&`wB{0A$WYlu|91JONgYsp7o67R$*9&m6rTD-3?-$l6Xhn0F#PBfAna z`@yJcPV>j3kX`7#(#I9+Xa9g}(!op>X4A^dFB6;sFxw#YbzAAUSyG_Q<~??euREUW&zF>; zJGktQCjeCJju&WLNt$I?hbZihKLM!N9sA?541q_rJMIlosXLZON>QaUOhq)W41Old zuo+zMk+QUM8NLLUWvKgDzrWH!>eguN&dBu2|JeYnF^PLxc66 zb$+H~>_>=u&$@LgDMRu9@vQT+nX!e?>}9M17a6-2OfO?OG6r%V!a4GOV_i)vr#{+q zl1n_jA@WG1Os2~b1-ULE3P!txaPs|x>p)cC)&vuEOTWqHE0%ttLrP#@v?FG*^JONx zEL&#EI^AEEEmP9qn}$JrB!W}FD3G_Mv!^V=o$#Ma_;SWiJtKI9!RG}(ko}TOp{slb z{Gh>g1+O%?jo>vVeyZR{4IU==F@whmUTZLy9G+rE&62~D*^woO^(LIF15aej>OksD zk$pUSB&s;IK=3LP=V8GQ8N5yK!v?<~_z{EO5xm;quLT!p$JU1)E@o|DI94)*u|B-m zj+f)A&j7R)@B{!4us#LAC8zxWT#PypPD{;}INP)5z7|f;KGL+RoGS%=XR(`CS zR)bOKDh-hUC%PAEo)cA#`NcB*m_TEGpDf6?FdOGBgrHfUX`IKkmy~7+u7LT-KvG`h zBLhu|u?qAi)Rv3tVdL%KR=f@oxNdwzeE4`S?^MSSK5+eb$#$@|;2R8XAoxb&)Ruxr z7<`%Fk<^3LxkEZzh`B(f2rpoHrWPg$fpJ_yNgr?>9#I<+f7}QuLi$qBUEanLkMe5{ z$3XN#^2I`-wV=7IGoJGL<++(7mNtrlxNPecqC`DVkh`(IbMN)o??HeQbwiXjTEKMx zlL6%Z#r)a%K;cgiR3zZ_8>6gM0!nf*br-N|M3hw`VCKjuYqx-rH(?z_K)+EKA_!=A zGlmEPYTbg>Aps8noFf>GfkqKRg11Fk2?8!3gY{bh>j6>(+>sY$br$eFKv2Mp2~pNS z0T)b+vW5uQ0WeCy&y%98JOSsXL|HQc3hf2>oqVw=e4%}R1?pi?Ez~fD_7k9HxMuqD zWV98$3TE1zUCX)c4)m`G2(Je4u7vJT%V?FywtR8m3NX1?#{Hf?el8CAyaz7#d!kS> zv)_YngI{flrI#GCUPaHU}NZ@RCbth{nj0c8OZwZXI z7$5^6LBJePO;G-`n=y%K;*?*O3E#{j7G0{|+GgA|o6vh(16;qK$2tdHRgaE=n8 z?*aX-q05AR1N3i(PUs0bFdm~`xCi0~g${$RW#~Mi9|GOP(8WT34!XUe4+-58t*pDy z1@?-%#`Z1Xdf~QHu~;eL7SAG_uVZ*JG7hW`CpkmV^0<-z3c#n>ujW0lmNq<*lO5?o zFwKs%m9Yfcs@5}Vl0?n+aGWy%$*cv#`2=8#fJt{oSuY4!kC4{^!U2T5FCYkT0>J1> z@$1?FT~C5dT{Wkvt_=Xx^$A$im5LDRngT#wS(2|}w8Owo=vaQ2>iAT3WK+H~f+?Rn zL*9mACd5StSW&N>Wt6?{%H)+|POT_S@&<@x9J1W+Fa$Ps;$QTE{PlkgnMi!xn9d1=E4y@0WLeDcL9_mva;wyh6#RXO`kkT z_!qX&5r99g?25*!mMFyc8m!WGtW#I@-+h|M-l zgS=}~Ev9XHIhY}v?x|tZN#L?gUjZ;}T0vTqO^4O6X_aZyt+2{2ZPUIOx?G!@Vq{Y< zn1)R)>{$3H_OOS=rmvu^A)D4hFxxa~rr2}{fNN7fMJJo?h8){8e!AFnG=Q>cTvJv1 z+)m${AvXOJz_qCsac%lOVzW(?Am-Xsi)oww38|1x6C@wzqMZ&wRJQ4p0H#f+k=A6> z^)+mI&a~+^SY;us6@Em<6d`-=b?wRiXt?N*U?B@i;YpZ_eaPPc?2nc_B0l7Ogs^RI zKnVMgy8zgSa9Xp?w6-Iy55VTMk{^|{J_KNY@;6wV*4+r-#@)Je=8 zc#xV2z=PB_J)2Mu4)olTpLt9v_BcNxDnFN?UH91fs{Q1?jdzvf8W_Ymli1r(ICS3P zP@F+TUv3axO`_B!R+~hnNyNxt#h=0PYl8C0)C7GXVSpxxGeQ%@nQRh^Ok%wzD9#>D zbVEJGNn^|)ItH9;p8 zbo1d4k?a=^7DiQftNiz1U1OI#*(}OBgnz#2yy!}QI^eawphfUq?Owvqgvn_An7x4#mJ4Ri2taP|2O!&kuYo2P`I4*1`cG2KYP?*ls$b4 z=%z%^;e}e@bI`mZF5~!tE3>eDLi`1sexL;Ojj4EUKab-FuEqT-{EC6dpUL%Fd_G`4 z%lDi>aUbKd;B`|XqDs5ot4fSp{V2d!n&Sq1@h6gQT$+5JmKaJBwM*kAfFIDu4p&@q zp-B6B=Uk>&d00Lq94Bn0qzY%Vb-@yIc7O@FU7xHanQ z2-i2?3EovAQ2~5MM>TT(3!#L%nE9RYK{q2ux-Qvy9$cHal%eKQhF9ZCd}j=}YFc1r z(S_rFNaPanW$GfjhpC6 zGf~ZT6TPC)O%(Ipd+xxubtD1qC$;c_`Amq61H+jCFatn+fZiI9?Bl`TieR^8PL|ki z%e(}x@sxg%nR*k%zU~eq_L7>h2ZL+GK4ixBAogN2c4f`j`@>^b3%@-zIxk{hG-IC= zZX&qcr*0jf^Uht`7@l5w36C`$rDAj2VX&L53G(y@G(nssNmIFflhCfr+G+Q|hS=|4 z!OPR5hc|3`Bz`YFQ}&)aY=J!#^wa+Vo1R-J_8ewE`>AE^vRfYoiyljaV)`FKlsoUR z|2l$k@L`3get=@_vOD@cmQ4>El=Ly6?j&6>?wuYUYf{0u$4W7rc<%?X+kTgl_CEr4 z{vmq=7@RQh0x&pX;MXX^PJ0fdX50aJ+T&M=Uq?@0y}JrAHL!0T`~d{kbcFytAy5LD zEYPI0WxZ*?5E1naUKIQT0`%Nj35;fe;}_u)xDpD1O{Aj3&pxrbo?+-Iv*k z-&iO_b3D(m8+|+4V?7AL?v20mT2I|WWcQXXgq_y@h!p5Cs7hfqkZ$KQPuFPY-ifCu zQVQjhwQS4QYbx?HbT8^5xC2qKrDKgtyolesQ>u)*oY<$Jp?y6 z-qew33-b^dL&!_0aZf~P+zmgw?7t9b(=%rkXFre>?kRBG!cpAa_M!_`(z`&&EQyX+f_e70sO7TKf9zeBnM(M|Asglr+r>ug=ed1 z`4eBlHqlW0RP@AYk|b{vXU6IXYZQfc!H;ztLf3g?vu_9CWPlZTz^N{z zRC`6oJNXDDWwKcj=Iv3uR!)=WO`etU0pt=T#}t+0txn*D2V(*}zckn}hxqTq44a-kk`-uWf4A8{A8?js! z0_}03z|}~?E_oM^e9O=tzp$x2PKCnM9be`*e)u$?eVE~IFk>CQwfCv z1STRz0f8*A?gC&%Hd3n89-AYSQqE>Ym{+BEt(+raJS$@)Vjq$m-S$|2eS|d?jEu+d zbHdbz+G8rX%fWDNdkLpN2|Ng}2>_pkG=zh(2;Pn0jCPy7)&=2sVH$3azIX-V zl7~`pzvs+)HMe5fwKZNJb)@3J;A$ zDIj*+n<*o|%r+ZBKRpsn0;9%AG^GV($=w-B$+YTzu#okMVq{H@L`i%Y%KBk&+(GbK z5RDJw1X|<6kcc6)+rEfjSCdZ=t~GfZj2fD3B2CEg)zoB41e@m{rd1AUxYynz?cxMX zWtR*_5=;AgTB90Yx9`~y8Y|P6gW#IHiEA?b0%)#HMbEJ-B%vH66v){K4~3TumKJzY zP=gu8^Kd1y2++D`=^Y-tRJREp01T%ez+8ar#rVm*v4$+2@@oQ#z9jnXt2m}lQYE|K zD~%NCwBNO0K7?@RWq{cLIdKq;?WIonZGcW!f#yHfDCMl`uH*%m7I`9_W}8K$Edb#f znX;tO39Zq?5Op;QlY&OCL5elXfD~zzNgDYjUpkRV=MTRJQ)|YG<%>W9DK;32P1_=h zHF-@b##S=LNT&d#*hk6v^-bAo z=wynKPMaXbI;BI()hSF0I!%QX>l6gg-@uK zNdEK?shAEY|HEV|Oy>WYOqnwOJelGVYMx~Gl1+!&)(V9o>cvyoeTaomqbY{+X%QG{ zWr#X8mWHTL>d`nfCjwG5Pf}7ekFva4N>c3z@#}#h^dFDEter-S@{!ohbSUwoT!_D zae`(RD(JMqWXepJhu!()Ko~s5ZY~T#jmT$0|?ieOaY^YCWWL4&4p@eG9`k| z^AAJRZ*_Qxs{UEI>3N{+lE^JQM7@t{eBI7_H#B`tp94aMD5|~m??B5CMKl)pzo>+; zP`3iN?sJEzD%4=cBMWRRK?L?dfQP84gE(UghEwrT1iod1A?n}w$t}fW)e7%zV!p#g@^Dg zI+eSyw`C3TM8-HTz8Ar#`g8bHe;>=D)2_==M%pgPqBlE|(y&huc8WiX-srGyw=6#0 z+O0yJZq1=LIVva=r&@1@0o+rqS@dd2d0)w~^QY>ZZ4SLtQkt%Ey!B&szLsr~Py3dRpt0)vXcKDBxBh#dRo1*}3-9$^iVZe9YD>L!EgMl)%cr#j*nF3dnw z5x-{y&g4R~bzr)hp{P=^i6WMW0G{m3`9dnT^_Mj()|91+ z&4Vac>=^*JV#B0Rv9Vxs#qI=fE4HKLt1C7axw#b^#ze)=2Ggxr&C~|viZugu#U>dR z_=k!$*=)X_kc)f3Jd6wTy$+^pKCakgNnY#W zI$a7Ww@z~;OI@cod}Y*W7!!4R7np9HYNoa&*Qpt(>oniAT$nrME@86SavvZU*K%Q8 zSZ)cJuI0E+2T1Z-59j)$MxB~ms?)y^->uUkQ?viAQFYn?#yPWST_2NfepHaFZxCiSZ^e%_L@<#6pu;ViM&hvDPFun#6XK z*kcm=O`^giDovuwB(#@R?}A80F_CN%T}?t)Hj51v4%Q>nWIi+;)nb=4cmsDNV7}-i z?ZtWwfH&0Eij2D+IRh?lsO<#c4Yk(q=nXYfI5-D3uP%~wDJu(N}(1uzrsPGN7{gS`C9{GpOv@n_fXEV)|`RC0vUXSdQ?9_Us zQYcJxZ{epypFI%vbcjfKIz-U&cEbzBJM4|Ja@^0=vklAC{_($J!*@ErZhQ=DSlaNV z7&$-f#mouY6aC|3oo?H3sV?ZO_b|^bM-J`!~*m5{O60p8z?};HQH2 zHsCYAL*z}w-3RU)#Pz*{I>Y3UCY>w5y#loJFu3gjG8@DB_A_it6Pvr`eB}}_s}P>CsRonZSo;9nH;H=+KbaCW2Ic2B2mb>1JQ&XPZ{r9DW=GjEG)1B} zZF5AHydA%FHxwfDrmgc70KILS-4Z|irmZQNCbf}cZDjjn3f@4%~*Bzrf&n)R3o|Ukc_blDZq>uaMMtNZL%5YCZ_5UlHykL&~Ba zdmf^3MyaXhKLoQ5xdU24gfUU`)|qXT~0oAyM1&+d#s=Kxai17!CjxkvHSQRL{j5V@i3 z`6Tx@rhA;-hWP?Ea={%s`5O~4QT@nE9+I1k^|(*BsE+W>Q#OWtbC@e9Rr z`9fertl3#y*VGj|C^ST<9h7MDDBkEUv=LLt z*lmA7N%-Zl%E#k9?oQEjV1(@y?X-_0%e$|GJb6Tw_&FfUd+#+=)(KqJ=A z@SE4VwF6S2makH2M{UvD^(rdsy~LuXA7bgU_P+Xm%6cdZWu=C#q#p*7vX+43mbEE} z-FDrMMp>(%jV|kF$g@USZ@A#K{*wiHnkuNo4**%-3Wr)+HrOAgflc!a#g=CK7e%5O zL@1Kh|BK8T`oC*qtK}mkHMcGz(eh43x^pZnwcFmt1|`Bc=0l_yl*QKDKU~6>gZ@Oz zPv(Qhwm;&aOZfSOb26WBR$mlSLOuB=^3J0M!v*w=uE3kE3a9lnAc=!4N!YvdoBb=ac zIpNj{ZzJ3!kKe=IN4TlN{2p@~Rzh9tmY5g1*6pUe4U`vO#Me15^p5q7Dx5zL)KR6w z-{9<^Fn(?r*)aK17+Nrm%u($_1zmeT2@^4&~0 zIgj7--bMHZ#_|sLnY;z|dlVYgUtZ?6`^&9$UGn4(yHAKeKJOi9j*Wh%`h`(hn)-_* ze^q6#W#MeO;L1xO%-71D4@-NEj?cH{UDluTwd%D%hQrBf^J7{^=KJQxw6UAjwdng+ zzOopr%^|S=0@Dvys+@5E0#GJw9d8-8S9IWYV&-rDC=*8`kF*pZK{z27p7@cwB_|4@LKgwUWEk! zW!yLlUlxV|lgWq+a0y_uvU&uT)8u`<-3!5EiIp){bvS+pKoS0wp}5E(W9&#I=ucO8 zC~B_f-${rNy!}Y!&ULJ1N>YL~8|Pk9MOq zo(xY((NY(DG5~qeTM4NPC{p)!M<}#0jvgZFL5Mu}JfhOQlga^C0x30LdTb5kx6Xo* zU*f1GI3l1R&isP6)4s_QY5lw!@lU()n|-7;ZizFK(3lfw$r}4P1%+`y1>BwX3M8>> z6_U6P5tRz54{7a}XM@8kq%L<=5Xc2tE(Q4msZ4K!R330sDFfx6tZ^|41%~w^d$ffR) zKJaV2xqk#rdj-d*Z$$4=ugbiXOE;khuKFgz;(IREaRPylKyy3Wz!3u7zLiT;U*R`N z0@u_v-Q~6#DUmo6<&Z1l2J&%`9 zpszmb!Gtl3U{t-x}TC+|Yv4#`4R{Q67_0QLGz z)}5GnY|MaCALRO+KM_6(0nTkFBdkdTwjpE|z&!g2{08SBdVWi{ybBn&#h{i?V2CfvHZ)VurN>#s~Z1dmTI?lOs@-F4hU*uiNvjF@qWm~ZL zUCIIgewT7S0KZH5CIG+i&(#)-#^yT$doHUMdsYE(wdDY?Js18g_KZdHu04w=CfT#y zS+VDD0Iod~L|fg?3cw86vwb*M*>fI5*q(a@9xPeIq=HFEX!|v#*Uut{?yiy{0=H6u+kXcsq}JO?NK< zy{6082UJsZdM!I4(W73=o&eC+i+nx-P_JcA6Hk^5#e-KPI$s|!5WsycTZ_a}+35O! z4sAWEt33|jHVrMNo5nyeRnwr470r`;ban3qm#h0X0C``JuMbGdMlSSP_R>sG*!2Nv z;*}`{Ulgoz<*#ymz8^E=x7IAIb@G7zC1OV5jT1?xtH<%%t zo~~ij_29Bij{=xBtjhE!7;yM7oNcHf8dfK0{2|P7a|A@{S!kvfkOZT z2z>uHZVVzY!}eHX3C#C+tZ4-1c+qSK+!^VymJpa!3)iX=_^dX*8AIS)9gnq>z$qUt zOeIhqiz|i+L^kkPRRjtedaTm~UXFt&AYeCwCwL#=qaN@C1kU>52?%Vx6`p{=#h&m4 z1irovo&aE;-H*u4y**Ywfu4Qvp)`OpyA;3MJ1QqpW={ZBdab6WgF118qUPJ>uy=5M zeUuBqbhk>5y11v(T84nESj^z7s7fZ})picU1GPYa`ie~~Bz+U}Zgg^>vbs%qj=f&G z1iU2Q|5ItLMKT$b%n4!ftRjHqavMu>I7JlQMky4Ew^heW6&AysQpLcOmI< zXP(D7issx60ok|HPcD9fZ990ZVt@?KtEjLWRUUrou4Bi>IBl`payb~me1KK}I6Ogu zR(mB#+sT~r6ePofuL7_je<^bh_bh&;8}g4Z8d2z4F2N|1oNkC z8UhRk$5{ZtpR%dd)D!xY%?U#t`jkx-aua_<_Dsk{diNlkV<>D5d-lLs#%J!A0oGS{A|iK>2F zdj=q8*t1CZY|j$p*8{PYJ?TRv3r+SYuP6qlp--zBdR3Vj-;azJBX&ry3nqIE*!#oSu`-QFBrA>u z`=VxN^}Gh}T#?!jpnF`~!ebR7AXo=;i4g?41B?flZPPo}Ig$=r@A0vqbb%Kl{l>qK2qD9c~E6d4U5qeuo_>{BK4pae1rjnJvrghpuon#0wqrEu4o3!BY_0Q)L- z9Z6Jb3XbUZKTSOiLDbawi(N$|STHu$S&2}N&yHeIXO%oXab%BjR`-C!?64lt{5mBV zM}m~$A*91SpjLOY2P~v~=ArFXLr?Ajov)Q1Fd4w@0mG$SZVz|^@{%`cV9&A&fIUm|B*U}lh+M7kEZ-nk zr4^fd50&moWY-0SuHji0BgpkE^vyN;^Wz`ewLi?s<|+%fYqi*wJvF8L6Ov)URx~J~ zEb1fT)s*uR*mW_~WxIX}z@DYm^@d%WcTgF-b{z~c!>%d9XS*&#emRI8>cK-z_HwXi zX*PS71Z?T}o`DuS5X_#X;SJ(hMgXv9xd6bPC99L+Std)u+>Xh!yaO>qubpPbE0FOz z#183o$Yhs;eI$&1TG(9QE5VLUme}lBN=fbK;8|`%Fng9moyD`%y2dX|xh&7S2Dfa_Vb7&k$9 zmX%<#q1dye85)vjsf8TavvdJ4J4qwi7a*%b>^!)7Z|JfW)+ zOfFwI@CmqFAL@HlheQvKeHO7JZ#H6^T#h{=JoW`M_RolYvzfQa<=9c-vE!~WiuMa) ze~LJvykOaUC6M8SU`II@cwTtvYa5u6eh zypVz~A^1KW%-< z+g_q&;?1s~zMF9`xURWPE*tC_a1C=ONbGphg1(zkVa7JO9NW`1EOu8jHhnjvGx%=a zCYNL1g`XzrC6G4H!y_C-jL?c;4_WesykzHQM}`x8!2z`r zcfH|Nx8>E#E=OQ+uHR#=2Pm_*<2PPptco)$j5iXe-GT*R8e?cu0W|#xt#vAFTw@IV z0zvK=+VLi3ba!^XD_e%fp8<^7`SxTbNWPa-?vyEl!vI2KXc6UHkyqbo-wTZl&D$9X zz+>nZ0C#RuX%xUmtDRrn5~$CD37?zvCn(AHlpb8Fx|1P^JJy~n8tuOR@j`$A!JeyYh%tNYw(9yGg4W;$!q1DOY>OtB*u9KU=o1?w|lHd z0dhLvXAk63AFJ&Q2A7`mIL!f42|Nn1On|KOXhzi#>)FEY=TsmUdWhuA1*k{B54olQ z_{&PbLyiR8nSz|}axU-ZvFIs^b1>aw-ArIPKq`SB!Eyj{jv!(tBBVZ3+sOo%9^5#W z0h}lBd0&qeLGmv^zAix4GYFmr`JOH9T&E0ddQ#-{0@zBR0l=FCiV@)eK;|&S+9{@@ zKG1Xhwa&1B$D#)_PA7n=0Q9F8qGr|nnAga877}VUOx{>;Dzt~ZFQUK4`50{W${ECt z?WEdS04%$z@NMg7L!evWv{v z(TH7+#9cpWayj;=;Hubj>`FtgU=%u_7tdC)s44gf=i}s&1{2F=+nw(i+N%k=O)gqC zkXdZ9Cg{SUJ(?h~OPZjM1dW%?l-&1muIGSBw3pRAU8uKSa4vmovQiV1k(ecGO_ItN zoa+N)o+juclzT!_Ll0>NeT4F`CP=ZJvRvbmRcnGc9c4Q(mu|yL(*$w4Ua1;GE`671 zvL;UALFXY&Y<|OI#mLS9CmpW|N+3lO6lcFCD9!~Qt9ygL9BC{AWO}Yft0PgR}*A{3Qdr8t2IIP zNRvG@)@_j{$kb~!K?!Wv1SL?Z3F2JP1jUJwbu*_HuL;U$wk9afLQPPd)tVsAUQH0E zQWL~Ep$SSYLFN{mPkT*JoUWRnIB7!QL4Nsts=pt?e|AYVuDfhPr&2x~xdG#T`Yc?> zRv3dr8y}7=BKjB5gF^H^JL1_Pu5`~?slbOgX3xbTyuf~kh_<5^*arz*Jt~W)T}k6H z+*FRd+{qe;HEdbnk#7BL_n$kTe7@LNvyQ6n6Yj=p|TN#IsP`U6t_{>P3lLuA!xmq?aw zqC>%T6V+Td(Wk(bMCaH$B`!^A1Mh?LGMWFkk?mpbz@MNuhiEISJ&I67Iz*4E?<_}U zc0oW!AN*7s>0F(I+cCcZw*ZXb<*4Jk0IZD1@tYvVWL>lESmzb6R}ovKzK~L{jno5o z8L1~rENTOs`V-)C>hA)CQXfz=_20pk)ED9k$vu?%Wwt=yJ&q0A3+b|8B3f zgKwE6!C16j2;P{@La%|xLIqlAj(te7qIwS09WGs`o*eqjJ&RdQd$CDw_f57{Bm^AJ zw2`Vs@8S2`li+OrMGj~2M0Pm0A}v17_9UM*OP>Wg@((zmC;9ub{tf}iJ~^>DM)LFz z!F#7S(;U~j2dCslL-r|7YoBf1+Xq}lrS}GR)K>JyrzWl(5NXY_k5kl56RlFEk6K5M zQbYpE<$D_6=M3EIRqN8B{2La_*oPl2FqR@ekI3_o<$u6% z-URrXz&U^)0ni?Jn?&+%Pcb%6#3$#G9Z$@2GvHS?N{+eDL*Z0WjR*CeCZS8fqhNbU z5-0Ai^+sAR;-AmopPaXxxbyet4;z0^j9dGMPT%!pA$2nLw*H}$v1$FuxawqVpZ?gf zvU>6dk9(_dKGE7s#pM&Nw{f@}a=IS}NBMI=BlW@2bajAJj*&hf$2lLht7S;4;AXKN zhso@QsGkH*IlXNVkJG+H9`M~^4?_`fZDsvN)z4SU{j#KK8o^dze8_UO3t?v?!aT9yaJp~K(NIx+UAIkym-&SLTUrp z?pyIDm)>dl9ZdI~mVAjy?kD_y1N929!RB{b9xTKz#Wk2~(#;BHWV-L*HZa|HT6pbR zWLVEv49#AIh+4bS`f;eK_!zM3-C?W%O)jqh4^y zlr}&UG=<%xi7j}k;It-aEtn*w=EaL{YdqJUtvQt1b|K*D_dKK;dC$j$Fy===_o?M$a-H29y2476AP$gQi~XMKezC z=P~u2rVoiS?BwHw%{L*ZX@Y8Lyby5mzrc@|M8cQ9#NJGt{7cHovzuG5Tp)kR{$<0l zZ!#SFtA=CWXgKx_DlR+rmrck1iFWKCX~+Irm}5WWI`%!%Ak=u@15W)3a_nWCa(aLC z4R-88{{WgD`+Vita|elIpRXMIA<*pD=PS+Fu`gDR-H&#}C4Q25?ASBm3Vo~K*gqU5 zj=lHYhGU=IMYRp80dnjO!3;U}MJ5*&IRRX*$n^l?*qi*}wWd)ftKrx;K!Xkl2u2rs zteXhT1-OmC?*I;g{J|dU4gy;M?k3Q1h{qa3U@^c{fHJ!bzwK{Py5XoO(htTD^;pj$ zSlzagD5|kP-wn4o8tjDC*g2#daZE1x^KD?dAE<0EQQ4pW@0AWFo84E^U55J#)UI% zp>G%$`ZfU5)mOROG_eP}+vnhJm!YY!yB&g(v%6ga!0z?{0J~cYGVE?U0kFFr1`u+$ zm$Xmx0whQd{03x4O;AUkrU`Pl>oq~{wptUkLzgHfV0W9Q339jNg@7km2QQEmMYFnm za;V}7Zq4Txt;Q=x=!1?uSxBaP`Jw4vpZw5tuXlcEy4OpEt0^91nc@w}mnmLRzD(-+ z=F7W5{Kn2*ilUjn=$c5{l~lkBTo(sVa8h}K@u(U01VaA?nmxg3my1yy@OQW!vO;$YHpR6cv09=`$*;RGZS?ZIRos0nfG-liU<=wOd zzY=g&ex(H9QQiQxmazEze^h?O4YlxqZy`bhzL6ev{y#c@FnSYvvubiQ_44aGi%P_s z9fg$ph`m}2ti9P6kP3OTOTwjoPs7rBL}hO_0YJPN9k5S8?!E^3KIg459(BO}R{%Z` z{uqF9j=%j_kDTMrM4aGaknZ8@SScfqZFG+ROK@2k`q0||;U+?tK-~xAoOIKCbxxW; z0TwHEWe?XHWp029;BBJu0PaRloQP3Av`y3tOvxsz&0n|@0k8D1Z3Ze zpI`t~fWTUS0s@Ukd#t+%JO(hDz)66I2o&A#vE~4j*^BWzw!5m%GW%Ij`9jUNi;z>W z0-|dXte(rv7UklhoNr)$Bj+j@kmt5@>~i5HfEOHq@U0Y0xg_0Ux>CG$`5ve2L2*er zuob(cIRNaE-T+{ibQXYJQX+)eCG`hTE{V2b+e?PLH<+pkdS)>~6MGKfh^!{)L5WxD zDVMh2Cu@SYDm6iF?2snNSygL-+*qcVhi8r2a&T7D(UYQUp*KBkI;*GIS*b71E;k(1 zGlqkD&TvpG4F^@O!g)QqLd9ig^^EDP-qOx$mv&Zb!kpD!*I8{8#h37UbQ~Pj=j5y= zamwktU|DunLT8Q>XZ27%uSa)+<`HBrPFANbo9pn+>SoHhiZbJNmBx($OpM%Gw^vWD&YX zqX{?`fq>uufS(Aw5AX+pnVv$Qg8G`Mn!r4){YX9ve77xk)%8zuueMs8>dL+Q@|7!ql z|CfWs?f-TFZvT@3xczSc2o1@nbyGao1dsM42cBpbX@W-Kd77Z+TcHVR*m#8y3c}*l zO%jE`3+Ef&#(4GuMql;boqS2)d9?1m#CbEEv)--(=e}sP{ayveK;5f=2kH$WhW{;v zdC=y!i2D{?juch@=*^MU0N$s72XJotx2te&`+W*FK<%D9%mozYA+BFRXkbt0aJ^qs zp!aJEWH8SxFbDIoio&bqO(x=nbN@%saAXJj=|^DkPZcf)hEYDHqVGg64;iI9U3!`Q z#m(SY-XHM$uzeX)*=d*7jF zXl)=I%EoV9hGTFvq8@RrT)Y_xTT@*9Gc4?6J64e9ip8FwpEjk1PNA32648rxd^G zbeY(lWX~VSogovuA9%C~#Lbk6-3i6-x4>g@Px~fcP3(BumRQidr|Rx9(`#3--3{P( zJ#R1qcw*PSVE=6@igcnB^d^4Svr7S?3ZpvAo8moO3pA*DtFdOmba64BgU;PQ)$j{@-Xo3j9+ z7wt}qyq+Rnf?_;!ya!-T5eH)Ah%E3qi=hj@gSj7or-*|Aj49$pkm^;>OvDKepKVML zGjCPaBJKG7yjQ^0b2plaE~IRH$mYs9l1&K!XY(~g`PIZL%2WoyX8_z+6RRjDy_&cg z5!h-o=NeWUYvfE;I}WLk)h35?)f2BKh|dn+zxbF$L69VS} z`VyG9$YbRJl-YyvdrTBBv+o17U8t;0$Y>hr(YK(UlYmrdnvk&^KUIc#vtP3>cTOR5 znqF8LuOfwNlfBih?W8Qmq#X>$3-B&L=HoTRjzlvwma+X%cy+|S7j9l9j<@7<)GzDCX|dPBQ!mO)_xfF>GFKvVVzaa1+bdh z&20M?NXLoJT)RVTJU%BS5lx-X5KAdZExx(1IrVc9QI7u^Y4K|TxW$wCwHT*; zIKrs|CRyKk0AMSCYJLf3W=9%1UxKTeAC)9Aj2n@yx=dDE=st~%(a00+#6F9sAqdDK z69Gu695Qefv5`yP6*?DEwWFB}RDA_eSk-Rc3u2repplDEM5(T#36(`Zva#QWS_=QMtKcUzErRp zA}^6_+m#;cHIm(fAO7QW%K4Hz4^u@bbw1?ypmhdl?4Dp`XHdER22}{4ywegh^KKChoKCB?cOoaZ z++=r0pT2pG(oMMw_F(0vOgG$aI~+-H!+ZvS8zzrIt4+BcNXv_~xbas&&K-lo#E$6B z#N*FcGlgr=Hm`<(c>EazK;w@z@hu|AO}rSDJrY^DP2A*i6JG_c+r%|jH}Og^-6kH! zL{<8p*Hy_)e2=Lhns`sJ!<%@R1e*9bNN^Kh4-nqOO;K**MvS` zWPlxRlrRYxWd|%g#JnY#qX|C1tO*iZuL;^Y zkCur~?#C@~s9qCOo8q{ZCMeEqP0(ifUQN)RVwEQ7lR&A`y?BQ{O%ue?{(vt^J*GL7 zTC%ikKCeGQ6T~Uk1m~j(+Pm~h74WWpdreS2lTBi|5ZLjlI-=&9$MBzBvNAEs`Ud}e zBjad4GX2h9BdzOk)g9;}%oAw`CxQ1X$1p#z3Vhz78LjA3pogD@{HQpL)mEV7Jf@oT zDDJ^HY+6`>%YKVgkK!JPOCfp!XnqtoR`Fkqh_dGV7e_}*75@xq-ut|t=~-&i<%PIo zN0rvt!FdbPtK;ITQ~K* z52{T8+(9)=44TXUQ#7H~W2~79tsc{mhnn8dy03XSySB3lY*zGp08`O+uOYFOP;@pF zU3xLnN6_<2~5#N-GOH4TGBeksX%7D%`+E3HpZTSX4Z4i z`Kq#5XVKr0)@suEM}Q3gIizzY*d>ixIvEILT^~b<$X=}La3d4eH5y{9>i~$kx`v5C z*SEklb)9V_Q_{G$)5(fbx=sL4y3Vn;h!FYz;EkRrD~pu92jETs42`ejze*7rjsV{i zarK>p;J*)sGXy>E5P=A9lvM?geHuSJzt)ks8GA9mUXDoI0J9$68fi^~39=(G;Tstl zWi3X4a|O~`0g(L?ezJPuXCukf#WM01$P|#w=XR7egk(n2&jkGB{EiH(Nbq7ECmM3~ zNbYgSH6f9<^m9Faf=@%kn*n(5;jm$wWnVXSN}{4<@pl3uvEnZhP~K%*x-oi zj$|(aWY^k;Qqs!U6wUq@I_sy9vlCt+-wZBwTW2?F z#aJOHnu4@KwlZnas7RoI@xv?@+7+;DtrzTM&yj#STX~wV)NRE4l#ix+0TY zO|p^6vJ?0)0F+@*6B!+)JPoZZTwK9`AV{s%scm zuK`esjO{RJl~EtrUbKoEQCs`Sl%ox%KatLpV5kiy`brJ`altM_GD(O{HKI0{ zMwo2cV6y5+E)xJktItxA0>b zn5LO*+Fcv<)YG|8m)&FLLVIA~vZ~zyl&Um~ z*=ven4sk!YVH->PMSzzFPsBw!qhq5&3rv&Ci=yt}x{CwNWpiO;sScQKM+sx1qf~13 z)yC2xQ!y+KRwHis;vh@{i-XT0!Ha{-@X?v@MUg4Wi-T?u;l)8IK=|Syqcc2vrR2^F z%q4NyM8<0fw}Ro+0Z1p`A6G*xduK#FrxMAvB(YThR{@|y(jx1aX~h@gY-bFTao1QT zm#w%KT-S=4tF3qhOxKEGOjxl2&eAD&!%NHR8dmHBcDNP8Bw)qKkYFpm3J`8ZQl zsmt89kx}L_Cd!--rcvhY;bqPaFK-z4Z0&3=YZ+1qFRLj=WzFVt?t)x+IdeTNu||~< zn~9+&F;f%YVlBK^6SS(-{fbww=cIA+iLj2Me{Mc{&3H{v99?jZvr{-YIJN>O6k7W* zeO_lCo>|9-XVk%%myClk>(#*+UR-W84!~?M4#2#k!ui0=dh;;M0eu+eJ$)EvbJ$^+ zkK{1SqxMEwDKE5XdAu7fq&ckTo6DM{Z@^Xr9~Kk(RxEP)K*YQPJ}mY!Xg&}zuV64- zM|wxBo%m$yJXI1t?68Ps153c;rSxLv@nJDPV)>pcXz9F*4F!JK-D9iqu)DNRXx2av zyJNuQ^#ZSKCYxM5z`h?`UfHYxkd;mCt0JvZ%48KD`PF*WV>LrSFaU5Rfwcgg2sGa0 zv3d}A3?QArNr3(YiZ4v~ zdes*92&I*#N|pet1uLQNLW-u2kR?exK0>y#AkujP#^Hz11CRhegnk@=A40zazz?B+ z2jGX$9U;sQp$7pNN67T{2<@*7mmG5G)Yu|T(5bOXP0-GZE-RlJYc3k2ArD6*{+=50 zErqmcV*9y?+)@}iu6;{k=(u)Q7E-6Zx)p|wYu{Q(J0|MwJbxkWmZ-P$dZ=)2)ZG}% zQItCi<#0-2p`7qaEi_Mf4N?^LeEgzoB57AL7!7&{HR@xkQPBa$fY1H3EF92ROYo_lHib(h0B3lH zn8&rPLUmlb6rq9gopOdJq7aQ(9oMb^^3^V^?_3Eccg*|WFgoT&F)%rP>X;>v3U$n# z!lhX{9oO!GsN6AQ0HkBmAsGv~`(g@xPVQTBNM<$wAChSeV4THy9i%#olY}_I_HX0a z4iez^qAJ8JqzfNN840fJD$KE)iv<$F4Xgx*ueFXVG|rAxh`Ky?YK}6mfttK|Q3o~Q zZeAQR%1oO+m5`EbvOej6b@fo>e=SP046%+OAiEkr!75Of2;8#UV?}oaSO*YCp!FWS z_(I?zfQ|%y0Z0KTvs3Y#oUW>~%npEx7izxkM^3>ZZ^AzzSoxYXF#`LV{K7`gPO#;; zc9HNBV1nQogx^Kcl&{e(h7ao`6yh=LJK}4;hppJxG~X+}CKG^t%}fCHHQNB#*PH}U zzJ@lPPl%;>GuSJ+t5^9nL3_EAH9^O<_iBQUYj>4O;{-A_L7r=oCdfZ+)C761STPR| z&f0SD1*HBnaGzR{wmxO2=f{dcPz}*0sN^5>yDgk9l*y2W846|@NtjwE75#5@X5m8_-tS` z_T2)Xd?bElDcdgNn`3C){ZvZ)$Z8$>+Up;Re|fON@Gn}7`ZW0$8%ZhuLT3ZJN+Oy& z0$e^Dm<+%t-BtjEPP(Ovy!J;)$cp{Z$%A43sFZr}%jm%oAB#Uq17Lr&6H)lk-U5X1 zmmuB*P%ddBb;nyjF)v%uB9f<50|$muoYWPK_*^#c=xyS3Qy?1ogxa7p1@bv*EAh_KPFMnWN@rI@mC;tRoL zqrDBFocMfu8ng+%2>o1dJkN;6MLz?s6rGRQm1n3H;78T^UN5ZUbT}*?=a(S0kAzk00`N$ zoUHO5?7141!>43V0&x2r2*CDS_LbPPDUx^XS*`7vbVTfFL(a8lwNV`E*h3%{vgd_x zuCnKo5Mg_M1Q4<(Ht^Ac)Q%!eGLn%E+w*P!ZO??eVb1{cbM2X9L}PnC0j_D!9C3a; zA|8Z2hkYmZycYh8N5mljY|p0v*q)Rz+w*S#wr3~AVte9?o#YIcf~Ic~`3|vT=T=(^ z?Lc4QjQd)w{00D9`Fa4ha>Tb{<>>%qWp<;7q!heSLEgagjad600N2`DOt;?7U@B|V z%idLnDaeA$!DR~`1ke`TNEUnzdAk-&76VbDY{84*iUqL|y^%`$)d?x>m!Z-of#LfS zrEPFrN}CVBr9A-SaA`MvFQvT!3Am-LlpJ}`;G@xq$bGd51<<7}g^t0ykhfdfu34dG#-)7;TwU5Z_C^^Q6JU(Mt0!f8`L#K{Tp}s( z^zvs6dG#?S^Yn5YfIGchZe&E$%TzE`K76555yn~Hg~BFI3NoP!oq|&U_)aG^ldBZR zn@rX6H)eAAaD2RKYy-gU_6$vvaHQIK9e~^IYyfVztpT{*<^piLV5Wguf>n&iN< zvbCC^S(#V*EsKrS1RWn(t_c#W)C5iV(xmlqYNeVWvGtlDvG!7JYAUD+5}T(9nhLJf z1Z8?a6O=%b*p(BQrwN*-ZqWqAsnEoc&iH(tCWv!d6LcF;lGHb+)=v|gv1%^W1WjNM z2!X|N`?`_V^Z4gW9a!XX7t5&wX|b$!eR?rNEs%Q;3@wn;2Zk2NeFvr>vRWYDuEP1) zK$?oni{;)NE^Fjr17(ezG0GMwkxP883PN;j*crp~sP@hjRx#;un zgUfyXPXN{Dv;OXa)2ft7w}HOw`nO;awgU=YK_KEsk98G+(Ev9R_!i(+0(bp{c{+h= zfC2)KoWa5hpv)eP-zAdse7gu~2Y&@~5`wLar|>&d?8*MD|G;`qMzzO!5eyvPe=PPj zmZOhKtQI+5)D;f&I1fXP&xPSBxMV<%Cz$jL-twhr$`w>gJRZVs85rrDIxDVV3ld;g z@B;w5f-AscSC9q3u3#nrd4S+H0P+bIFWrVqqPZVo39?8N`&xQkHF@P#sX5d|+l!LC z&y=YNTCFYA1a)3r7T#y75DuE?m1v$DsEMxR_8|LAD~+!6oN7XRLC7kj>#Q}p&I?A@ zdEV$cYgAnBI;+gC^S16fFNJlT{nB+FwXIyUKRDRg6)3Aw}1$Y1Q<%-2tX+T=RB721U?3s zO<=%pXdML30+a)k+3WE;TynnRW5v935Y(an60ro%ihp{5Z{b3vW z!;g@Y{xDNA;Qp{2#o0^AtNyS@;&Fdig8tASR^g#B;dki|xd7ZB<^XVicmsg@Lp1>R zhc<{6>JKTBDEEhNty~qC`$-=T zmm%ivK{CWRgUlgjgrYERREX+cv_`w+68cDgd?42MmFg!4QAylSgueWe^ph&pPwoKC z<3^S0C;LEiKdIvQwDnTTTQ8>u^2?S5f8vcPD)@2c2VMisM)^+B_5YHsmXn-*;33fb zJmQSvzY3bST7F_@5P0Zs*=qTb9Y`P!hZp!L-)ZK{_Q_R)*5<2DHOuBr*J}oO3v>W) zpL7_M<_7Tg$xUv+e7kCdxqWhRpnA1(8bSj}I6*VyC=UPq#pUODzrVjqn&8xFd{nF?{v{2c(!{AK`NEnF6*vJK7!a90ansSkH;R3}nwG#bF2IcPC$qwZja zY!oYrXdA5tmu>VpfL<+BQ(@mg-fm%s8qv70o?32U@gn22LREc<@JxZfW4vlJy2&8( z8;koT33gUj55lG7uns$`n*ez5_5iT6I*8QSSuF=(XVn>i=kfOd@H{@N@2xm~R03nZdd@JgwQG+KO?Apej$Qj5DD_gviEGc74A`|F zK=^4&UY&_vEv<`J9{FNAo}4e&1UX(yl4qCPToW|A@2Uwp6FpQDG{;$}3G(S$KThC~ z=Fm(gS+rx0R+T;XSk0joLAelc6vpSv9%QZf7=g@pXPi7Vl} zfh?Femj(02v*4HpZU$-yNaoDc5O8BrXb9+16dD3JD$N|kONU*c zc?g&}XfP@<{pz}Sf#e9}XL5YwW6O&Mc{^eI{U8Lmc+KykK=vkoIV)GUK zEoippJVp12^{VaiGDSZPnrmUMqJIO;H8e-j!TPvp_b?QCf)x&Y0-DE^C5j)_056r% z@$jd3;0#P}=vBwVpX9+d&?HXAl*P=KF{N=);+=X3;W4FIQALps;4!61(Sc$ez+*~V zHvlV+G3KMb)r0E8GT4PeXkcn18B^A>L3vDBe}_tmyXfl}Qzl(5{_?ZNhQHKe+F!l` zDdjI|OMasyqPb0w5pT(V4Kd!m>xYog?%j5g=e-(?L937z``1zcV+<-M$F&P%kP|P% zz+wO%25JNFFz_V+dH-PDCVCjEB2Tmcr0bcJ2B=b!g6x?Ofh)rh4>(C9!FU%r1)54u zPXKUEwE#G$+nURO^ELow$y4%a6qB~4{tG!CjMp_Y47bF{nU<(AV1^7=9?n%;o;@JK zMjHnZGTK^G7DhV)E*mWt>gYjfBeV&gM}S-OOGY#_BB3KiTHMpgPX@ zHZtV+Tg#C1000j;F9Pt8a|D2goca*vA*UCB8glp%$0#IL0eiN9`{V(9C;;2DvW3_) zu9etx5rAvYOo~bNT!#p3&q)b}J?BZ^&`s?Kq(b&w6wX!lj75C5XBt4rp36;H*z*-| z*`8kmXnRhBHo<++&$VZ@5smHXgDIpbu|1EO_WTU?Om8ptYYdsdKDzJNW?!pv;Xn-ayIFCm26=l5;Jo_Du1?3qw1_IwBt*q#}Xb0)Mo5M1IXs-J?D;K3*q+UhP{^L8rY!9FFt}{bEdbh{nb0P<4EnkD+-pQ*dscyK z+H?CLqkUGvo-M8sdmir~_H5Qs?CAioJ!b&0J+}d{Jx>9I>{(7$IR<;~g_+r&mt7_H zoPrRx=Z>qzo?VcS+diwcJu?x3?b!-)u04}QTW!x7kP6weYdBZgb1OvHo<9ME?3rrH z!k#(EhV3~EK-)86H0)Ud{akx4F`}_OH-l^1bCC=tJjFZ-dp>%-*fS$Z>^TE~+vhd_ zw&y7Twr5KSvps_VY)=d>_hWGRH)x*5pW(qzJ>r0NzB8D{KZPn|D<1)1FOUVmR&ITr zSot{svN8`#aiU}_IVJK2ZLSq-&jE0)t;Mvp^T1TrrbiqJk_dBQ!JXi;1N8P46(?m|RvTZxbll~%-bY0pB+D6PpwY5OB8mv%0IF6}hv7%WBJq0$=BxU^fr z)uo+ddxxmrmxzi8+e&uE>|&21NFC^m7aS^r4?1{S2a?`{-vJeuB+!^jb3r z39H_W{}fz*k6^W$ z@d}ftO1+EfIUB*&s~Ib_nn@HnUd`MNb9@UqSc% zf|e=qVqkv5bF3!l`NlC#kXVekQWi_o1c`0e1c_B?g4RaO#a(cw^E5$XTQosp)taEx zhD!(GmDWN{kk|oD&_>n?O;Bpl(#$xY;hG@M9!=01?1Uz04HhTH%B3}!wyIibX%4Ny zwrhei)duD@*agj@HCUpwWURpwusm8zOQhZA8f-VO!PI(bkFj2Q(^xOPW2~3<8tbLE zRXDGa-Za-pU+6W`{;)ODSMC~Vny598AFre|jk1>EpKk>#kUkkrgx5$yp8(Bkq?JXy zM#||TYowJ$gVB!CKLyQeq?M`wygYf4W%c8gb~RZvAc0u`y9t~J_<+F3 zu3qbN0*3*rRf+qTCLp0OA#l}`a-(ub>_%y^&O*Wl{)Dpj6 zacGI3SsYs8JH??TeufI?Cfkp(EbH$omSugg*j(1%qbMxvWA9S!q5}WfCEuaB-j2^N z`F>GNc0cUTO;+gSTcyeVs+w#$XkOO;s+w%ep3-E0<@mI-8_zqte;4rq+h@V&!v4Yh zK;7G9)%_Qz7svt4t8Nb)ATS#=ueu|+P=RTwvg)?E@PWp?WYujkUv9}uD&8)ok^{C~ zjQ~Didu{RQVXEA+*Ly>8`@2;D&OJO}uDa_Ls{^)02o03A*MRs9DA||@wk0IB>3cOn_}K< zCmj$=X}>!rYrI3GF{n(5Sp&Y25&mT)nT^;6ezeIq&t0>EjA%ldHV1dxO)0v zWp(Y3qp=SXtJs&F0V2B)KfyInXc&PX0q!R-AkAw{A#ey_E`gr6d#xu4Yz4se=I{cq z;J4hhxgY5U+dx+xmWz$~3F#qC&|q~z6V$!qL@(~%$(o>nbh0LRSk?r2jzlRX zk9K}dkmp#U2}*jW5Z24~_wWae+4e=qmH=Wu+d=|2P7GsmUVsVTiJe5-J;S`}zApW#j+2BhvEo zmx<<$r!N!v&j)H-zWL+n8%LIxzAjX+4uV_Z`x(9~qgqF%`I<+y88NV~Dx}$ zM6zJ|=6lf~n&3=?HId4k9&;bM$Ga$l;s-tl{oho`+Y?C{ED`V>s=#L@UaS5`u{aFO zp;^ra;a(&#K*tAHfq63mGL8+z-Cd(q?kO;}Z|nF5!7oO5tq5>~cS5W#0RFOiu0Uah|262-B;S!uh}VFji+`*t zXLBm&9TV#~CHH%+4Pc=2ZXcs~e((Za5WZpQ?Sf2vtiRF)>qgXJYdGDlUI+ zs$3Hk=a?qw8-oKR3y!l~6N!T(tu30MID0ig{cx!WQG@W$_xyOO zf7{QEAT4D6;I*5G(rLYq{J92$J0@RD> z3GM^Ru1lh*S7f2bmQi26hm%j=GDdpEJ*-Bc)7bxG>|Nk&s{Z%!y=KmtGnjFU8P|-G zByz1Nmtzo_nX_lknPCbgR4O9Mr6@8)#8i?BjZ#SzMJ`QaTtaeBa{FjVB_x$frTRb5 zd#$}^pZWNFfB$*C9M4+Md%f4~z1My1jrMvVD(!(WVj{1M#1<0W_m82zj0Z;JN&6lJ zVEB$>d{)nut{Z(Q4ecN+C6#G0ha5H5+pI3_W8^ z&F~^P!YlBjlRVawqNVjo=;+aZ#Ob4vP zXDR{3eePcr_e+u((7O%Yi1ZwXUZ-hGEWTi*)}YPb>lkFpSeSuhj2IuY)sBPD&q9;9 z96n~1O(rEwKjW~Lt8?a2+J}UwA^)P~y@7U?H74yfGz4PmSz=>TRW)Oh-I?Z-V5KJS z(luEd7I`rp?R0-}Ba6d~ILjs@1o{tFO}0D}857{XrUWGt5x14IA8Bl3LWpCIalE6L zmrcfnCu5jNd>2mIhQ5u|?qrIKAbj@GXrRz4Y`2fd;PJ)#F4(d!`AlcMob z+eT}=q(*CvcM>oPV)H0^jaT#-+s9aAT> zEbw;sLb|3+UiLUnN^5GmrkH^$dy$@wcRShY4;0*t0HLd5Vs{|EZNv>@T73>xz9ZZ5 z(*i#@nKn&7hUbtTHDnjQS!UHkivRAxNYhp?#`oXZ8vWga?HuP>{kqfrZ;w1&+ewwZ z-uN`;D5K#!W)4+NyK7-!Bro8)V#7$x5344(|Pwuc+ORZ^9Ia`u$pd@aGs2GJKUZj;hUzy!xgOeqPteQ|fuf zo|@jr^^iAv^-52lrnT&m5Z9A7d`-?Mm0qLW$Jm<~ zjfA}_1sme)47~#I57Xn%%IYWjPo8TXHUW8g55eM#3?VN^&7Q6c zLh`Z<^vw<}p$Zu419(5^c!&HGanja=%4PwrNW08l06H0j{T;xS0FkEad{#4pg8(-J zgt#~01Y`*$W|vR0M}U=C^qT-Oi8? zl_;OT!Ao(6iu3$dpJ#QcO7gd+Rk5G`!e{LTVebYw3ZT{G896Ea?J%^Y{f?TJm|<)( zbZf@4BQ0dV2f7Og`&NKVfXG;YJ^)tMV5Dw0tE*gkvb}r@=JibXeE?4r)B~7J@CBw& zuL1D2nD4iL24j#YMo z!8d!s?OKQ7TN@s7S9$OZT^X$N#`W=j zx%xYtO3&g~mP;6lUso=HKfiyRH5@;cC&D)sx*8(hJb0jp`R(Q){rS!2>>cK-$}a=R zSCy^MG6<|N(TQnP8=e^Eftv6({_N+^ar{_WlpF?Ci8Y3ovzzR~lME0055z@Ddn9~B z5Tap}WJ(@HE2LMl3qcHohusT>I1C_CV>f1?1V;d-0LX(jFuyd@iM8>dJq%VJv_$}= z58A^Nm%-sT*%-dC=;Ep1Q|8XgvYsLHi7qEf3nq@NpkBCm_p>P2CkB zJrCL(Z}P5$-k-qBgLc(k=RuPOD3cjaNUvZ|LNxjT;|p&~qLQ5+uyYYilAYCKIg-s# zDe#U%577%Ab`kjg1a09n1R(MYz-Rzzna_CAlXGPqdm6-ba}}s- zVYk3@`~iS`DZK=Anj#8{}ju@wu_6aibzHnVjJVJvDTUY~x0 zeg3FvF=qfsi@6>^TFj}cjZwztH{(8Nl0Nr_bPlGZnfD4L-hebOgOKi3rBAlJS-m|y z);^Br*zJ?Otn|rAs1F@Fi#_^omc$(h)dT)+s9~N&NvOt0+)%7WYcfLhK&ao57F~^0 zHpK*!X6H`OeG$x6I=!sYd{?PtWT7{7KZM@s4ZWyr=-;A47kfkBh0xdh#}oIavZ4Ec z^%UX}Z|MFAJ<}Vyq-^L7(V?A@oOGeN2>q)!w3n5_Y=qkP#J$yw1DnuZZbRta;N4R5 zvJ(1>kDbst4`6CK+6=mK24k*J;y4~d6;w9kgPiB!NO2rwT6-O%9Y>qGxbx;XPNQ9^ z@r*WPQP9M3Fw*Xh<4%MLn$9NYAvgv(4r(hlEn3c~>iFQE<9MBEGwo6ilQY(FaH@UM zad444Xly$tyN=IV+d+Sbug0yGh-o!b9 zac_eA^HO)J%zuW|mHAcqV;HG0?0up;BMWZXvl_1Xjd06+>!G?b->Puj%(sSVejMB~ zzZ$B;zx1`4-#n<@?Y{Bp7Yh&8?!n)h`PTiCw~XrFnfcQoahvJMcXiWW)+J&lFuuz( zT@RVB{8M-POIkt($HV4mhaO$l_1o{C^mcyD*+6WoTh4w0-qQKq2p|plPe_1tE8oD! z?N-JbeQZUCk`zgU_L|r zR5#YX0B_xLvO!HZp`X6(E(rgO=>S2Oz1u4?t4c{;a21oq$fU z-T*02u?{nONhdCZ-d;Z%y_En&@25~FdM6sa`n@v`dlUQy5`l-rK!P|d%tiAY*ZXBf_55iX(#Vq)GnpDSB zr4s%{X&?E?)1-P?30>*usL&@(;w3ab9BHS5cN=6cE1}ih0r6taeG+_ z-8njRwl{PfLO^_czt?yvRF&3@jBFB*k$5zKNViGzK z$H6|MwJ8T_zPmUMisd^FHqvcOlF_V|tkbOmuF9iXomn4mGrR)LVpUnoOPewi?_B5V z*JXM4VxKW>`15!p^)2A5X}&$&>*=np-Nzs=8v;q<4qlr9E;)}&SZO!q`z={ZtdYlU z#I!fzp4A$B%{(sBrTq){3hJsQYmiv-ni((4$tiiH{aqVos^(A#1_awM$Ps8@f<#}^4YtLBpBHn7u9Wkxz zDfKmlbMppoaGKa}>5-FHXQTGWdhl)RY`h2yub)@j_8}?b;W1rJm)|+~ou(GzcXY9q zmnr2%Q`WLha8=7n_MT_WOSQ8CK8(5NKpnkv;aw9R_B4R203vUpoLc~3gAYQHs>ogk z`riW313=CxWHNkcB;Hgr%dgKVi~(>D2sJWEk%k3_+iw9W4U4>?ueF!OIfW%)W#ac0 zfIg>Sg-Q@rKO-m)OU_7quO4am83g`9TToHEjljcfp>D`4XMcyn{sM$u2c>+Bzy|mM zz{+|TWweax?v_`@K0L>76~n_G3b38v8h`@?SHFb)L4c|1{CZuYoLfeohxecGhNk$% z`0piXx)qu>!@m|h?5Z#Ot%d}-04)jT19YIQj9^nteM)Y6=K1XtpxuVU%gV!>{0c5n zaWrk^WJ5>3$!g94I9520H(}kGCY3ow?_y8LSWymlTvm7;mWf_ASsdFEM;|Y<&^YkC zro5uFkHH?E*D!`a1sn#oZ!g21!)RPyJd5YGeS0qIr#fHFd8S12Kz6fqv zy6r0I$*A^+SxWAr-GRT%(591i_lJAXPe^Z2yE|VrL!A!o#~}TBnY**-PL(0lE$!Ks zWHj^p^^$Lo_BY`4M8-b2Wy$we?H+^I56hBqckR9a_sL%nPsjHCQF$2;1^jvmIZfQD zvK-#6{Q^9hPbpd3E!QD9PnWbAUcJ|$dx7K8_Bd4a>afg}knz^y4%LiARxMm;9mf7| zWcx~X)xUjK6L{!uc$TR^88?&0um=IWPLKld9zf(6z()jEE5Ee`K*o99=j!s5l1RC` zu6;XL8Ib5{bgtp$*_?!=KLcKmFZMx42}|lFc<06Vt>f^puL3wrPz=F80V4l_Pux6! zVLrcA6(E!_Q(3ExVp*PgU~*lX-<56%!hQgtCBdrz9RNa25y&fV-{QZ_{v2!@5OzG& zrV_LR2mzQ%9%KwbMt?&mR|$Kvb|N z*RVUll!eZ^P!4^_6cozi9je%`;Wg*w%cF}(sNlDf2qFMi0N~acgd(R9?q>RThGa7U zy#jb*zOEFSQ{o(ab>q$QrXx5ApjQC-*^L8Ux!KbKHor0~3oj!8+*jpz#klYi1Zk|3 zi$3YE>e!@;H%*JRCnJ%%fz_)%%+3=X{Ptf+r1(!&c_wDgA~QOb^Xui8p&exTg=-pK zfyAK*{4j*vHhqc-&M2i#e+#URQm;?#W}M>??2tpqG{Bk)?|B_!?Nx4pGqUFNUIy>g z37$yKnObrqnFLlxBHd2BCl86s5jyM*olrK3^`b-X_LkZ^2)zcS=4Q~#N(RrkWh!wy zjg(mbk`A#`6l=ok%TSgKA@j{cp3@t)U1A(FmC8L~j9A97V@-O+vB+_x;04XA9S6_M z)iBA<*@ba$8^=)uM;EVStmEKFwb<)$8sMB&Px`He<`Kh@gyP-Wir5sXAzxk@XZ?hK ziJd2>b>8B)mT;Wcc{2Me*+%Wt4P2MW&2ZI{w^C24NypHdcb!}lTW$5RiQlKD-Gga^#9J+&p_7!YW1=X!_>aE-0A1VJbI?mK)yJERB)gLLamZ=vId?o(*m#Pj+ zcHn%$(s!@N%O825#=lf#mZ%KlEGKwP zDNg-<528OhYFq;LUF3ehEP<2B|GWbX$m(7{qml>?C<$$?13#!q6s z&e-;tGX1dB5tL)fn&7vBF0DRT{Tqb);9r_#ORsF|)tYgh;x)8?|o1JP&K>>ME`maU!vNFNFZivoR3~hjx)|m1zkw4;CehPWMYskzS>U@$ z3z&s3s#me^y~#{{UIuWdJ`bBhW~at`y{$o(PJO0$SxkL)fR(9_g~aNq59VDnEqUit zN@K+RjA}juUFd`D{ML9%*oUSXrLRpfO1}gUr4>Ml(vAS4bOeAXeG5R8 z;^opPsmPt}@qH~M92v2gk>}tJ(>+z4dtYax0kRSK>V8aK=x@p3q5!gq*Cy4l4?tc9 z7wadR!NpBa>A{6;%Jf;Hb;uBgV}mYu!HqgM>-=%xAEbyGCcfiKAf%;$Hy5-VY!j z5g&?5TSK1(@R5&*mxGUdM7$k<{)qUSDEZ3yNJVB+qWuKoSPc)G?+Doh5Z+DK<*7J_ zO)#f3W;padkDtikE~vCO0b+0QTL}bDcE`g-aCI8aFcUnTj-!(VFK3{52tt|o;2FSl zl}%^8FlwKmD1y&U6P(P&iUz@$+wp2N@#%|MFhT7*@bOoIO?TqDmdMONzDs3^@Z}KI)mKg%IOW5m^WJY`B62FAH(^;l6vl_!RikXPxNmcCTD1&zJ zutx)Q2Z;QQ;>iZkpH*AvP1biw0Ds9H_kJlS32}mb;NKSfktZg@>{<`nJjmEnZzFu>Lfy$0q|6H z(S+-VaD2yIitjCi<4Cu`ySl14?oRv_4+d|DxTDTShIL206Tq4gFUOZ%JbdB>gkItD zQ&k@i8Tk%GRYuBSUMBI+B)?r7CTP@h=XRC}DbHGBa!-3Dcsc801IW(plK`@FE7Pl! zCV-evrQ}%q<=dPhWqcP5Era8#pm%_l__FRpbScjw@AZ=_*%lsvN8usI0BXFaONO>K z_^Jf^7LcYr;1s;Op(V=R$(P$pz)LOSavT&!68hk%26C)d@fgLO$@T0;y^UQD190tn zphp?)dLc-$>jMB{*ZO3FCrRw_O57xAi`vat?n!QIcSPK!(?{z$ct4O_#U2iCY2oYk zGcEi;08Ss}oXB*KdTEpkdWFiuNaI)Wi7R`(BQk&;YVD+;80k zfW!AlN2DwKBXC+Fo|js*LKpT}jAs+44NtIVL0ZmD-31`$rhWvFb5m_cV0jf`A`=1R z+|-8va&GFWN3g6-YAt|!ZmRP0P|9;tl^#YC63w}(AbjQAR1SRIb5q48AuK{UH#G&U zc^Y_b>b&9kgvt4-`iP0=r$RhG<**W(=cuy5>T^^fo})TqLbJl|gejA9$Spd&@ zs%k5BdB}tOf1jsf=6Ig!-jQg}pvrCyAm^zR08d}p%K^;6su0i2H2Tn^eR^`W(2tOE zJSA=SD*qJ4)0>X3CFwNhgT1>O?C~caNX8~M`Y-eI}Eb!Su)c)?NTH&7%O3%OU(5!6s-sMUXMtZ^f|Q zKL)5s&~yxz&F;ElE-0jj9?@{4}#+WJprCk{g9x@2}C^8mrrDa{aVbC}_)IkveHyla~dE1_wdC&7Abv%3i$@7Sgd zUTpJ80FQ0v8^OvDO#DA>vmde{wt2-wW1BxB?_!&U0Aiaw!Rgp0yPJN-Vx&#XhlNc? zz3D*%4R5g5be{*^5auBU_%r0BZM+RWvf{fAKCt#HSjOZ(P~eq#Cf0} zon&HZ2_QKt29O+`G12K6LM9a!AjB`=b+5ufz&WE(I-S=*H=OLHhk5&~br>Ubz00AQ z$|Z)D@;{6&t5bg`wNzecXxdofQP2;A)+3DTFa{XUBsHs%Y#)Mm5FYkh0OGnsj~z$*Tx{zYlw(1QEtu5n#HSiC;aI%4g!+)(zNKVWK0&qzBB-Os5HJdIa*^31dljz`V!|H5!4HW!hYX zmQvKAYnZu^7~v3vz70m`hW4@&`WeSWb?DY6v}EPM8fKB#>nn@AGF=~R%0Q~SE-Ilt z3QVT!ZveQn-eE?J4=1NC4}moOI?aB3SuF>^OKC{O7t3BbjOFkQlT8`_?KYt#m$-Fg zCp_cOoQxM2>B?f0n#iQppJ|eo1Hh!|?4B`;L84};lU=W`WLK}$v^K)csk8$on2#Vy z@{)-lfUMLc0LY@s0VGEjRo(!QMU{>KvZyi~Ko(W>L(|W*ij-Kt|CM%P3+JI>@eDGw z>?j)NJUy~EFpC@q!<=y(ti(EInNaE~*KtrR-*HfEk>g<6PB;## z_L;{}-e8d8ILPEWj&j(}nd>;H+Ie)PMttU(k`(lF9JCh4vc(Mc8HQz;Yo6_#pHXaE z*XhE+BL3Q1xR{84i8b%m8zZs+Uh{4)fCpvqTN6Q9_|`a87QJgrfK*xVu5~vL5a3c^ z_1b=`GyWwGbS?!B^jr!Y=(!ZAvAz^|ujf+WJ?2uNTmyVat^xAm-<~~KvF9$ZzRy^C z@vpY$;$Izo@ed#G{8VRfJDN{5q#E|8(zr*pVSudjFL~Fj^KTd+>-;~%Em<}E;`hut zzjkM|TV~ezH%a)67vPp`Zydn$PG+6|z<~IjI#!u1`?hHZ8}P)v1FG9+5lVOKY@rei zEiKf(0aw`dmpcvkGzg}=j8OXr1ne6=z#UU~*bCqHTW=Fw1+Wr;y99&Q14ObBbO%BF z3cq!bp!!O`^$o!ifS(AmR{5>J36=tsLx4!*HGZo)!4Uw)K25d7@4nA;x~HksC|4R> z1v?y$QJym{SxD)}1mBfX#omAf%WGTsEqHfNAjMM}Tp^hWDe2DSI8+lai)EJ62rBCv zmm{%y`4Df!enqd5#ovLraits)M#8HxWPnqa?=ww$f-Lb#DHZHB>r78Gp~&kGE){5L=hk#!$qXNvxoe21nol9yPJ zQs179;`9u}tgP)28c%j*N}_$mTEBG^9`+!BQvl)L_!EOljVyy#MS?aTVKzwcJU~N& ziG`RA5_|~If#7?99t4jd9X$#B$WwoU41fm#rm08qYnen(QxoAD@4BYL)x;E;Sgcd? zGBVkp5^L8%6r}^v6UH#mOyOKF=uFUh7*B&9Y!plATJ-~VD$-@fXQ!S)>u#cwall&$ ze#LrIJ3kbg+F1i2wKEAoY9|aJwR6U)oqF&w;{f*L&Lby1`N09Pb`G>kqS)x2G|hnY z*AE*b6UPCsBgNz_ho89V=Q!Ag4|5#s6c;%TGOHa&2!p;RChyWX&vhK^A&ZTJsX6Bm zY|m?$;*cQej)Psr6vx46W;qTrXB-DxdMD@D)m&Df&5~`28u}4Vs2$-cwMXP+XWHom zzxBvBXp$evU>Qk-vmMEVgrXU^pIZ>vL5$lN9!}DmnWLgqa}3OD7fYB`e@Of z(X%2J=((3ZCXe4_l_BnKqfutuWAdumA0vo>N?15uaWvV!OhxH+MV?pDfrr? zDik74eJB8n&K=3Vp?j(vOzkt0x>Kn-QRD8Zs}|#A!<`}}QFVmo`>1{BL%Qdb?*wT_ zP`(qSaq10J|IkB?%0pvq9-$p30rZuAjgj&vq3S)Vs}<`}ryZbog1SKZlj=HS@*c5I zs#7*7ue~!^UU8>!s%*mVs6PD-972$Tg}WuN{NE%a<)oe3U+!IeDmqi;{>D~~ z<*vtOjpem@+pF^xd#UoSvd^kZS;_s6EgCnji-c~|I_3Ridj#VpYDcj<-Z5#0l6P~b z0m%Eq+5^b@ygLEN>ApSyPxD5}9ZB6&DK#8lG z})k-p-5a^yd`YWjGoW#UJR$TqG%c@NU`rQdwzZ!@xTRY-V@Tthlo6OIBNuGkg zFNr(+K`EH~B*vf=zviC9EMxq#36DLiS8KSXVCrG8Ua!)u`SDAAAr?+r*CT%&vHtzon#rzAgcV8IjH zU{YbIg}BS%{3S^~r)9`LHEC+-&Sa@C)I)WMcB1%msq|91?4L{JiPYe1+<62c__d#1 zp`e_`eJ+(17nHO=mnvzO3rDlXU!Qt?L1W45^BT(u*f|9#A6#p6e-36yp zO#xV)kXMP+^zkkLbq$YjEc6^p-F0k*;PlL zHc7-zjU_WXG+xW&#h+>{iT+IVnCi%_YZBVKE)u#Hx{px*EyGzK=1kNr!=<$3Ow=vI z8JRv4b<1#;oIVq!u|5;kZTMYpqj`~YP-zlYpM%O7UV08HOJg|)Ww4x~>ONd7PtHUc zEN7z9wH`SWWpv7!s2-9YeJ09aITLm3a2BFD6Lp6KwyfGruYQgzBDcRHr?u)Kx3ya8 zYH6Vz%({L{WNjg|J=76wN~>i{gufZ${Tbx#i8{QTQhIwLZ!`q07ASU21m#AC!E$3l z;~7dWH5{7QJ+f1ZfWe78Bfo{Nns zHRNhsE{X7h$#~J6*5eg3(HTEcE{S{yw{(Qsol$A7xtQ^!$YYayQ;Z~%3tOqDd9do0 ziF`{)>Mz7|1?$842aF`r(EJk}=%S?I9>hPFX;{~SMV&SgaY)e{_Yt@gQ}AzH3zlnI zrFpna!b9=Kodfq@jBQ;DIgGw&K6aY<<%q2!pV8`799E-yOA8u7#$#|xv$%I=VDM9**Tj(EdH;Clv!V-z7-xi@hJ2zLFX%aM+1o7t^lI9DuCX%IQ&7ZRlt-SL;AP8iEAhD zux|$VgWxL&`gxcm5lhWg2<`!>3m}I>3cYdWK2*b=g@7ha9P6Jqyo~j~MiKb2q^wuM zIRQDxh%dnVMzlwI+QNerDW+N^R6@&GdmZ9*S9ZOutn9XNbn2x}r&1+!96~<;-VN<# zB{X-bJ*&#Yym1E*dXG1>mzB^yB-|5vg*SA3OS7u%^_6AToCJ)!b4}UEO5AkEu?DM1 z`-}rKkb6!##5NG;9LLvqx(iHPGT2_`I5^L6>|CzX#Bb3?&!^nLlk$`=#}j^$PkCio zzDc_uS&=JYm1SusZ5iCsFjmq0Z*a?Xw5qZ^lx8o+UIC8^UnYFU3vf#Vn><;rj2(kp zuA?PszQa4FrP6M5g{zF*g+!1GqO8yz+8W;SsQMQ=t=p+*C*e@Z3}=Ffqte+!`@- zLkwc8QoK%Lt*t7>qKz`gP@%jl5U zc;#aZSRETrm^U#rx}a6)e!gWF6iLyYo6IgEDQvOz?80D~U1+Rl7q_LnkM)aGm4d+8 zBCp3deMFHSwG55pM#>EMjqrnKRs*vJQzebB6mQ1~W@|T9OJ%W(oNz7nyB$Ua&+&!OARQjdpow z39;T;0^WC}Y9s$sSq2*B1~t~xux&cC(w%*#3r)JZ z?b=_usZTVPE^M>L(!FibSPE*R#xjE4nlk7K3_Rt|)u$<(CeKj2nbPwpE*Y)wtZ#;g ze*;MGW?eBueNUNH_3@-H+ohkWczM!a#6oHj7gKMaCjI%1n_x**(DZ6|#xl4c*oz9f zW195G7vK(mgG1DJihRa~PcTFO3{&Yo(;i0Wqg#Fx13RO{0XV`s4uPcQmxZaVh88=% zds>1$6FPJY&uyyM>9LcIAA1+_5Ic@_?MU} zMWKRnkX<{1i+FJ`Rmv>&K?-%AHXq{!1bYImLi*g{eRtp;o_7b{A!{}I-GTk|y8}h_ zo%(%&a;NyNyy?h>es^GhkvH!Sd@$-t`+ zecMoWx9fWt$nss)E*1g4e*)BLm- zxLdf6x)+^Mm;b=;L3y zK{8+K9$t!(q*IiwhgE-1p<3l3o$J3FJ9LnU+YE_LmynnjBNEHi?h^fA)<9HhNX4t- ztgG=aacx4zPf2lBe~vPW6K>*H@fzTZ-QwPm(1q?^j(bx=i0-Ey_vVCLx<7W@TNC=z zea>-jOBhV|mH3jY=-Zw!lJ1_4duPIUx~Dqs-3d?AUFf*?Cd`66Rl@E|m=7$iN{Pt{ z+nzedOmo8)rjc=w$n+9@JVc(C$oCMdy~HLDamGtr@DM4-J&`vt4o05sCHi@YDPCfh zhbZ(CTRp@%FLBXBH2B&Rd2_F$i*djxFTjj8cUG3_gY6e>Jof@wzL(%xsMWpdaW0`em2yk2xU%z6a*po4~AanRv~74rWFsn4Kvrx4L-6{)o0ycegdbi_cePFV|yxR>-Lznqu6im4g^Ld;p>H{X|GHF1T z??!kQss*55$2(Tloi2U9(9grOP#ppN@9m%;cj>7@{|L`QmD~ucLAQaP=hBDxuokK` zFqdONL9KF`4H7UOo`q@{=s&Lkz2Bve3B3cJg=#zKdrAN5($+^zbXe#sufgr5#-OXg zQ-Pb8^Ka!swEA?9zYJfVcmyE_(`EAB0&E91 zmABo;80`!X{fb)F$lg+y>dT_L8r7w!qX8qz+(F@~N8ppzmI2 zn1P7?EA}_wDdK(C_;j32@8Da2eYn`DR)W+OBw|}}y|V8zU+ZxwM6}9Sfl*(&632lo z-#)}%r2KeWz4|$dlD@I;!MI$f&je;Km0I^Yzt#6>T>Xy`Jb~;sHTNBLEfd@kewR*g zvt|giIqqOTWfH$Rj)_mb3I20GR11-X)NaJ96cwlTBwnfg8R6Uyw10p4uh#w#60Z@A zEZln^^N+CRK?TxT$W~8$hPv}*BZWn3F6;M*D<*ZxQNV5Y%p3-5xa}T(JpxtuIo0Xv zTC1yzQn_o@O3lxm2|nq1l-^<_BZ-wb@&sP}ko=9$nwL)h4)sdm-_0?$$)He|xE6pm zAyV@sW4XU5D$%s8zP;5QxQD4T&|7DqNEI^eb6n|CI~b03@S~wFBgt=>YY(g;iUam7_NRy_Nfsd%A`F& z*+s76&wxZ4rT6tCWlGO?@L{%e?U44PBN6PYs9<20fO&5Sm_J;`SIj5m{RbGZdK*0C ztgRaGEHyDO6TviwU8|NZ!-voMOq~K#sV#=Zs~=T`>N=pmUPl9TyDQfP`9lMg-wxF_ zK~(}-q%v4q&q5@L?$QQ`E)#KS3FcFSX@CYJ3<@x1G?H?uuuj`kTByeqgF9`HglF3` z6(yz0uXi40PsA(`r|l8(A~p3P2seSSE)$V3&CXqTJ2)~lZ73u{uEcFXmQR5zQcsTn zbzc;vP5%GU>`05VjLBS%z`DgLn@rQ<-0>g`fvqcAA12vpajqGB=@v))FVW(NziDxZ zk@_>VqpLSKSr_wTBhlBiI7RAbn6$dpm5_S7RAZA{YV>QB)K7F{vqKu2{-`WzY*=fa z#)kf;u@R^n8w#1mh7jqEw~^j2-PCZv5^U84CG&S&H;iSvr%K}gl@_1!%Q7Gz*y!X> z1~^4(W;%T9M)?M%!V7#4jFxz|bc94lSAs(^N8-^jBGDoZuHIU8#nduypRQY5O+GkqcJ!s-76U&0#2-&i9tYU^tb zR9A9MM%@V`U#Fy;|mi+A@yF84qpY42}{qb(zRQRjE4$+^n#BT%pnmYa;!ZY?* zD-7vbmyjN)M+ca#KX<7g_P8dIn#x{)E#W7Q%suRL(SPYKTYp&E%#_#*)UUt;; zKu-r!>s|UwAXEOMsKa-^NY=Ie)@dp_?MiNUM~%^yuzxsK(9E(hH<0|b~8^&B@dtRuT^uk^P#yRR8SL#C` zWDlO06@#uqdYem^0GWbVNFBZ((T5hQ7P+`I!_MryD_Po^MHj?Q-IZL)4(p0foq{Np zb_=3eJ|vQ^e&Etw7X3{@2-F4f-(A)s$f>8@cwPXqd<>D?Sq2ct+9Q_5F27Rvsbg@b zNEO|M8P(08KXvKSo~U6=9)uwEEu?~6bNJDf;+lggq$XOZaevHzx$;nLo0DU%Jm}^% zx_o*vM3Ji971F7fkaip6FeL_FLc)|_kt)xIY_cmMjn<`_>!+y6X|APl@;29n>Mo@I z!#kjBudC~OAg5i}&lLM+LZC<$w}YxbTrnxmB4u$oqta(i*1290Ja;!PXOB|vJ|@`> zajMY5mEcsNTh=tSRkPP}u3)Bu@JaRSu-S z=5oYOt`wIeM5cUJs(-se6|P+WJtn4 zSA!YvGP8j?a62mU^3AQ8f{(!$s@VJe)@({Hb|s5l$zN_0$w$GjQ+1m`D!BJiWp%wT z_Asg{IBT3>R$GuqLg7Dz0gBY}c98Y&#PDGcR-$?jb23NNH$0AX zKcg;#SL&ZgTi2J>E(oR4oVw1`IPehsUlH6r^;u-9>#OPvqC*eO|F$cRx%HW=7|Zt^ zf+yV6f@xaN2vL;Zg`+>*k{L1_2fdT_fgTB@vzP+1164-0iAG-!Bn0NmTF7t$-Y^0I z|EG$95R;E{cFm8`I$9uS$q&Li;S|oDCyyp#v_)#xHPHKtqqp2tWfJs6iZe?n1lfVt zLb7Y~vFgBsQrWdfz}NB(mvZ|WSyM@jW64t(sY(HkmjaaMwCe;Zn;@Ulu1^X!g*M3) z8djE=j7qzmLMV;1#soy6av!QkeflBlurzv1!J(4yyzBI_kLRXk5KbJ zEq!F{e$WtY#g?zi9;XCKTfSs<(=x=EJQ3FAYxpt;6K_3=^J+ko%i(F}d0DqIX$oWjJR70*7q$!9G)YC)i~JrD%Hv6J;F zzBXP0&%STO#MqDg9k9NGhu!+0fb}y$NBH~=kUbASmA|sA7k38i1bDtr_AJ21WE0tk zlbsT)|K#IXW$`Z0;8-(N0W^w~m6ag8(N1!oT3h{mZ%+IUR-~kR(2e z@*4?{tk(D`pf8iQ8NMCiVORY(VBHE3&cRRUUHqIk)#xTI7b5)Rkv#)oJ!N-Lc0w6h zN!ogdOsDMc0JAB(06+4Vxfy#17mafEkgWX1R=mYeE``=U1B)|-!XsZ|1eH|0bpV9D z2;ggigOEQ9kU67_JdNQ^kgrqf5s1G_sc*P#;n7N?=m)7^;curx%0l&I{sz%_PleDZ z4uh;fqiBtyjUr(b6=UM9uJF&SUWV+1x65?`*#Q2b`c2U|8?`Kh;N>ybgge1AoPnRv zzbFGQ-Lyc(+HWCnb+DP=m1Vz;wI2rg3ro)V3nd`=HB1yVXQ}Z+5UUL$bS-}B7&d_{ zYrb-9ymbQz`xby8KscSUlkt<{DFZReF%Wr%vhM-BMAGRm2L)_fYo+?sD z45L_-;eKd#%P^A(>r*CS4X{Y;OjZ zNm!@y9;@?`OjrU)*Xjm&6ZYTjjhB{$y^X-G)kU#L*hrAk2^(zG;~<1Q#FfxHx(%V1 zWWtVk6E@6*q^(|}A@tIcut%WTO;{9*gr$OX6P7cww&nIKIZwe+*~BGGBga9eo#S8_ z$MhtOQ{CclidY;@w%$?HFy5luLX1^h%_g3G7ktkA1i zJ{e{*Ce6sM-0-d5q4;2C}cKUU~QEIJ(V@~c&S`vg+V zMHD-EdB92s2)&M<5~uv2rf)A*&F%|!F~#x$KBU-VWyEqng4iaoTu!ln2goP57CC+e z0DoCOW5qbg+^)wEYwC)Cm5Alha83N!&EdKVAnSd|jE79_*Vs!r^+CYmGIRJae(Y!A z`W7I2I(~{FbK7&tVXjl#ZNR(%khLE>3)XI=`RbU<>_#gC7B?WQtX|OETzi)bb2-@F zh4_X6gva71)Dk}le`=GFfmTyhF3h#%a2kFx*I~6Pik=h`=3y6To(g^#HD8AiTspQ_ zAlCT+S&Oj?u#D6_s(zT826k^y>j1LOQDwqd={Dt--t_CLUY?=FB8`B`nb?4AKWto<-mBU=P4sXH_65r`X4zneQ z&wh1nz#0ON@EH8qgW;M4ko7Z`n)4wuua&B3w}o#t%G9Gw99)e7B74^atm^@?TVj!S zH-)EGv|oj18r#vd)=_wbPvOTdfa^DatO$PcDYFK{v?1^vPnqeIxe2a00FgL=g#cM+klo!Bex3?Z zdKXy;@l00%T-5*~LjY0$O8-JV@z4!3C5w5SHFt+fwi^`%tiB-ZUq235_YrIWc!Xdk zzyyF$5`Me^`|ibSyZV5wOR;MJt|9oX5XDBY5ug)5I0HYS&*rP>(4Qc5K16;8VfO`y zeHEZFKqZ3TKMGj20Yd%D1e~`iwxYcp>%rI`LO}}JlIhn?5o!Wtce7-1Iz>n)hQz{ z5BW1-Z>Cr=Kv#la05SnG|3rCs(}M@zZde?!%2DbzfXe_v2g*qGZ5xBvkAeLTguM>n zCzk66WyM;kfc-Pr4HUa-eE`cgh;v3+v1c0Cxgh6JY8t>>0G>ZFlVzsRn$t}7!c4B* zXw2l?24f~yY|>^T*5Q>G>-ZRAVjWKdh;{r34YZC@qlgMbqv!=$F^UENVibi4M57Q} z@XCuV{DjntEffKWElhGC#(I7Vq}20T0JomKQc}-9fR%bq+3cz3C^6P^1gzBaWB|9Gqr_0p zYd}gpp8+Ua&z!NBn37@lJNG>F*4tuc?qPuFnfnPN>(1OKK}2Tms{x{C?p|3L#h-?V z%-k>E8a;ClZHCFW`>V9CntM{kh4=G;$b#r`J`i)uh~%DA@!@3@$%DvR09jn|YPoGr zd3zPe63h~1am7o@JoXe=cX1_X5+EH8=CNT}SgHGIpmbqH9+8~R_3*j|Gnf!Z15+w8 z8a(55q#K=jb6<9PtsQEZlT|E8s3HBZAI04(E)e(-oPtzlS(5$qV3!2^A%&;DVT?ilUx zo`5Bt<9fvJc8(>~#LjUo6hvexwC?9?)DYX({EI{_n_-T$R z=PJobc=jM$`-=buv2j*bb^P=L+o~!|Dg@sKq$dDeNBT#!viYDpT>!lTzW=cO{SF`= zH2y?=u~C2JmqvZwevf+VOQZfQd_}zt;HnRT7WHf3E9z?jIO_jIG~*$`)ZcXgeW?%e zZ$Lbk0c7n1TkNQB0{Uxs*w29e0U+yL{BY+$)c+3Ok4fhOY$1cxQ+*H;RR8Khquv5= z)sF`&g>yfAMg3=p$5mhKsJ|YxsGkkmQ9m7tv<_U}XeQ z1N0cuLC_OPcg0UX((L(o3m}<_e*#u3fUFBh+c_up(VzpQ3qV&P{W<8A!zT7r(8u9n-w*l>K=!-%$s~=~6Tp5< zwl&x-0QxWU7)~m8`MY$4kyTjHJ^@*tU=Ce}leO1scO5S zGLh(AD*jol+l)qPjxR|;OU><%6Gos01m>QIx69=R^zO$O0I~+&4!~Ul_lk23d_NK* zYv8Xz%3TAGl0x&J4=Gs#9||dV4g8FWn(a0Fft!&!cMUv>L_hE#NO#fCOLEa~0Z4Z> z@|;nNGQ8BHpO=&xU=08f9*Q5k4P1`_OjTaN$OG`60`E{A?BQpc z?5sd`=J!-p?Ui78WWqiP(1H>_;mn3ttkv#ncJ0|nJEcMZl>kEHFnje%b=rn`^aQYT zLD(w*76F8;GGbjT#>V1ntJu<|SgjWWR%?O`fFQw>0O5lsIX~Ml#(rctzYa z)Q5zdhA0W7;jA|eUQ*KVkv9!fVIYG{8es5N*KcBC!};)xTtEzS37X7By%D?#uma#2 zm5H%iKP=^R$bd1(_+7Df=g#=y>Rx`|Hj2*tebLa=|=how=YjRYsV(zsB3g7YD2z@VCbT z93;3E;2VHYxQw{Wi{AtLFvXGpo*?)d`kw}fya(_C03O%!_|Nydj!7Ekvq^RyQri^% z;kNj(SHaa4Aha3==oOWQ`4rf1K!kt7k6rgwtN;LnZZ9j#hB*`LQHY6(I5< zz&ik;g=ku%BH%Rm6xfeJgg?cPUAG`$eE~34c?BZ_;C&q4(l9qL*>M}@rC_CDE&*^G zX0I3<=F1kChWQo%w_)~5Ny9t_tTfC^0NjSzD<%!|S74=KuKJp3n7aZI-wNP1%uxZ^FpmW*4fA^d(l8$fa2w_*c{a?+3r)k^13(() zaRAaVKmLYkn4fslG|V3XxDB(TD!O5QAEDhw(JSIMir+xOZ4{#<&?weGoNmMHC8beJ z0~^&aw=tC*-7u#knQj`qB5oRLLc&c$lmyc7tv3x`Qqu5&Hw|o<+nF@Lc0CRAIm93h zbAz``!#p2AH_Rn?(j&d#bQ|VnY)jmRc@HSJVeaG2qT4Y07I_+GuZYtyd;N67?DZ+r zFb|B5!_zQ(8K+_P`ss$*>+@d?^Dv`4x?#Q%8IXqgegNGtdj%u&;O#cdm3N|e+=lsU zP;SFKj8t^PT%x^9!<>XxuC!sUW}4IJhWS>=T(V)#Y=&XLMNgQyKgQeD-@&#t2M=d) zhS*E?y%}44JXmaBy#zBu89`(=!~(x%)?j5eb2i?73>vz?KWyVC^G`IZUI|WM-i1UZ zO4OpnKWNmVBrth728oIn5m$GBngIIfmWj!ky!1gr+{sJ4m&D{{CP;Vk;w3qG*#Od= zyd;>AEVfIWSn$#^d1)RQQvY*LJOwkt zGcuTqjCxv;4hS0psYbA zCmc`p{mvh6w?iuOK-lE~@(K1=iMQqggcso_R1QDhKr*U&9U|9Kb{N171nmJj0Yu6H zqyr#6&dFz)_!1c35B~VDOvqOvuILH*93$sU$ip%jKMA?$$+%aJlku>eGpv1C^l39$ z?CoPz=KO*Dk9HhD4La^= zaOdXNI4O{OW_gfh6duI z$w(8Fc+>jIpV<q**N-)C9<6M7zBaEzq;`>!pg{yxOd#9~p5X!f z8H%6Kbto6FOw;dFZ1{S3hCA^m13!@|(0Uty{*&{+=_Z5K;KzNB$B{vT3Xq^pw)>v7pam?XxMn3OE=NH=oOU4>Hl%@K6%R+UPj5m`7rke zFb|7K`-)q?f@$*(HaCFpK`_q^;Ps{9cj_?G@)<1Q4K_D`86I~FKFY@}tW3nsjc}cG zzRstEtj7+B9W6pXL8ummxTmg#@axnQm$+#xVS{`%7v2W* zzit|v_&;I%+&XvT*U2o6bT(6r`g$)aCawOgNBvnPf_M?oEIdEG(Zq4fMr$j*UQ#h; z)>7oGP+2edtqevEA$vqpbs`SR( z!>U<3ge_FfXXAB&PeO_tKU%8v#@z2}q?URVQcsP86gQ`|ROyYmD(cY=qH8In0(>_6@f8w`2o!f)v=Cpfq=lw;)k60`=rlEP$3_eBB}=r(p<3d7 zNW8?CEpfw1OK@aCi=3w=euu>8yv@q36D`3PY?;(l)elj}IcO*;#N8JyBv)Sb^KpX~ zdJ;mbx2Hy+`ZUJct9$RH8|U$~1c`<6$&vNKc6MO1T^r z{gLYNRp||%&s9ELtia4TbU6b}AWjCj$+RCNZywooN^q16AarGib-bt z5R=SYMD%WEqQsb)-B2Q#*#a>)GhQ*t%qtL+%sh9A%#5oVXH7SmNimrj{SBst@V6&? z8?c@O2!+c?NoLZ)-b1m@kRL{|re(w=GszHZO|gm)3sS5?SutkjIM^hL9Yp3+D8`y` zlE!ilPQ}*dQiw@r7DCKZGojOvp6jUp=~lbK#pCe#0(G@0H8 z;AYw@C7FH!tYo?$fSYNrm}L4|u#)NDzVl={N{pFa4^}cg9Y8Y8Y&c>j(^uO)!Adq# z0GN$P>+b_rE#^n^U062X^FT|0djTZC=S~2YK;{*f;VU&JP#1X6gomHPx+nbYYNrF% zjR28ifX)D+Gbk^wc;79!o!1WXzq7)Q0w{=u6Y(=$RmX2uF^KWp@l6g?w&Ni186_71 zd;t*Y0nH@|J52EGkB5d$B5&ST(SaWU|8$cuqn5WAFt4})chfj< zURtlH{pvC7D3&W~(EQ(qook}_Z^MpaT*K~-D54F!k0 zma-YZHS8!^820TTqYe9Ww5|h<#%$AaANmak;NWl1Ku%5qM4H3rJV0n(8F4Y}%D-c2 zp7NU@|2{yt2tU)+X8dM7gr9uc7F+IHAUPHu_MecP3=kOz&Cdd4XX2-raxm=oA=aB> zCjssTurf&xGU;?0b`crth*(*?0e+4uXxQ%c?-b|y_n|+`_3yU;c>O!6jjLiTI(N`d#IK(#7D@^9~>^WIaKcS2hMn3vlqIBwc|J9rk7O7?w zV5d`7V0a4%bm6(Oz9ab(V90K01X*@vT9$K5{ocN60nRVG^{o~-T!NQ=NuZ>_^(hjn zFJA=15nD2$%%( zebJD80hcBfnI>8F!mPC?5iIQ}LH)w~@-u^}uQYJ*H%qY~^}f;0HO3RoddASzU^ zAUDN8svi8bg2r4w7r~9{oVn)N00yXrq=6}J7-yY9fREIhcm)H`22=hW#f9c-W}z8d z2q^}#Sx`gALu97}I%5JYYK6w3NZHpSYA*cisJTE8lyy7zy;3W(u#&<>el0Np5*;W} z_WiaWQBzPBn%1fkuFFu$dB5!rRcsQZ7rZyff_GvyXTh5*<2%(MtgGw04cZ-o+q>ZX z7Tj?yc(*|oyq9CayB`dQ3*JY7Wx+ci9#IS4#qfw;@ID8h=mqbTV`jm73{vDScxS>_ z7QENN*In?QtJtyN`=9vdE_g3Ao^0K@;N2<7U5J(i@9|W{1@AW1JqzB&^u>a=AD*({ z{Q!Ww;62P6ky-E_T_&E2rSX^r@9su|75~2$yuC7)TJYY4WRzL(K4a863*KuHvAf{y zCD{W$4ANcjK4(HYQ4F_{I8{D36!r`3SKR5@d+}d!QIUN2(<@;6m_E;Dg#Kbyxo7C?`8H)0*_C0P^#}G zq=uh?lxg573fXHho>%-JflkNN1*Hw#XzU@DZQ$nPx(`Ba#sv|z?h>Ik#4uD;1Ghw- zE5JJU0_^|ZSiJ#uj8srQ{C1=MkmvvsZG_NYrwLZCz7bu3e8J`>?H|YQI=0pF@->@| z8q1e(+G#9b$m#6)uxYC2!=|0IzkDI5L-hbGM1Lc*y?j8_eC}ptb@Kt7W!23me+CKd zd;sWn$JHYdUlkcG(Snn2Sx(R{G~YvzpEhTZ%cC`&Lj4{HO*}jc)fb@OI1T!5myWMR zIv<{es?BTo3>`z)fv2vLg?Kpxm}kJmd=2IXm+3*KNPXND?QuW&CS8SsD}B{1T}H=g zNSfD?@&hI2b);1T*uh$-)}MveONG^K_c3)6L7dl-%J)so>qsR$U+4VSDQGx|6zBzX zPsB{3^Ezh{NB8?3g#U`lgzi$8`TQednbpM${nizmAyvP&QwS2Rd;w&WlJ9%)^C>q_ zCIlJza_OZ%pMp05T0!&q6yi&NKBXTu&2cnc^7APSY(AetSo-;tsSLaC(qWy?rVZK^mF@(!L@qA(tD*XgPEx$yl4KWNA^~4vcQMg;9zH+5c0a?Bg zFrz{>?oGTyb|2_}T)MQ;X&Cb$gdp`Yq~2#U)}XGFYc_UZc7SO@ri0651DV%p{wB>} zdGLkmUr0{F3``AjCGThRCZn0?cWS0E)*=(2vPL0$|wq95z+@kl7u0IXw*XwMd%@fA)XMu|Kooi*S&LlyubI|@7LY` zIFIA}I?m%f&d=+*>dcN_b`$V0qs!0jR^AK~mU|p{CGH{->&r zyxO^u^Ar9BpJ^dOWZridC792fKEuyOEpr>(F_9zPCh|imV-p;XYR{5yM!U_1*L+-p z`LyZFE#xhUp{GFeTW~M67$EfTp!sRj7Y+Ze@d*w`#TS@X=)sZ%^C{CUhHiFgg8B66 z))q4Ig~~zmyK&FA7>5dkCQeLn_+7YdOmDvV_}l3%rxltS>ZeV+x13mH0>ZbR*~qE* z6NBKU7A?ImFHUflBOrVQeyS0A(Lo%KJb}>bBs7d4=NLjyLg=*!Ek;0LOLUM737ylx z%R!)YbNLI)m)wfM2)@;#v3KB-1oH*A^%D|mKNz2-nnzt6`GVUh1N!51*=;$^TuAI(ekA_12j>YlLj}VT9+bKsaC#J%jU9r9l(|9 zM=ncnK0`qG5&We61?@c5Fu|LH z&=(O<&~GT7`LgQ1YI-B@542qv;a;yv3C=|T`M*Kbmf|}H#(~>X#8v=w0Kom4O8hqm znXJ0Dp?CA-1m`W`=L75phz__i!TAngvHM>kuK*dB1@JyVQvpq;B{=N_3wlh zz+!hZe&sJ;jGGG{gqSthVzh>}5TiAm2r**~`AacQZP4_RBt3b( z!|>?|&OKmw$p8-nM4rS?{x|rkw3RLoO3#8wjmT~UI3}`99)j$)da~R&JOGh5MYd&W zg7dz}?!%AyTY^`2!YOq}@8oAU57J46zc?7@RDcmY*rJn{i)g$ZFd7p#HGPXooTE>NLXZ2O- zkP1BlO>o6=gzg;ATpZR!q+f()BO;d|f03OpA3L@Mf`7G$_g;li>~qC7mmeH%g1%}# zIE>qGh(1cQm-K_JTgG{NQ3MJwb$?t)6?Sj112e4DORdOE{Y-H6bH-EA%8QjR8VL4n z>3UazeI$7e7ig4q^=mi z*Sj4teSX2+aW7PjT~nE3=S>Bnuj{Kmh)L$j_a*qR>yx#0X!)uH|8;%$VbvCT6STgr zkMtj)?br1c-=9$Db$xFly9=~Webt7>uZMfN8}_~gyeVYfa!_y zV-tWLD6!1{y=4Gd0QoEMGf%~2tCg=Uc>~-BMC^Bfbs{#ko){+p-BCYT33y`x<_WkH z;C2A~g>S}!WscNVUf0*BBEeaO0Pi@!S^*BgCV=oT{8U1YL+iT_V&*68onT)s;9i7W z15kKblX&L<zX9MShmSOL)~K9Jt0KJ`BzfaJzx7nHWZ_p_6uE>-?<|E1sMy0mfGN&W06<}wB5y_Xj zzYXdF08I7}Wv89-84XVK{s#MQrnMTs)pgkoywe{}a5jM9l>ls}oRoi`Eq7*vCf*9L zrTh_7_NSnx1Gdai$ovhNZKBAx0p0*8xTC(<{sxhi2;*OP84NtR5llnohDRPvaPCEb z_X@zH0+s?i4G@mvCkt|%ALb(T0%5lVxKzLwk0dx(14I_#C;aQ_lO0k5-*TqjA0 zX(u;E2wqzj5o@Lq7a&B8I3jjSb1g@Ryk$~MmDX{@)*P%OLdzKRm~9!yY?+v4Oo5EC z3^CEpO^nB*rNcz4T`|o%p$wDk?rCB1Y7Bt(wgOSM0{IlY-ski?uYY8`vO1 zOQ}E^XekR^F_k1+2&R%RwvlWHif!yhBr%CEXJ0lt!D~= zSWiSOCtobbmZb$%K!g^w8$c{5LhBifJZr5-Y^ARCH2ELvK}bF8K}a3zDYW$zvz|ul zZ0i|g%fzf_AY^DgVX>ZSBrJ|?53R;Y0OecDDvchqmfeU+Cu6Lo*iPQJmXf-GYAury z)3TPywvcZv)9gU8mIo23)>`VYVJ%^C;~7%k|Fx1C7~v~5IVn9CV2#&f6%B?r2%rog zvI0N(HTc=2vRpjN{B{aN{wuN-0C7-Lq$z&#U#lm}`R#6qyeG1aHY7NE0U}@G2Y-BS zX|eWT&TY17KGxR0yvZisbYNVD!IWiJZ%kR<%s41BmWqYejOBL_+*{tnoxvq;8V0~! z?yZZkBUSqb8<{Fp$HATA4L0w9#Ti0D3ck?2R$|3-#mMNu^nyBwh428bjzGPRd^i`?8PUYg+CiSUAn(0Cmt4ltL2Ia699QjZzA zyFr5Y2Dlf2Q6PrxN0rng-!=Ar2QxNs*I{Dd?tZ&Ja2NcJxG7pDj{1iidSk(E_$XTT z1pE}dTVLX*1n*8r>_NEqI=}&d$YK2CSJV@w!5oFidXeo`p5QzyvQ_wr{S}J!mW$%? z)|)0v)M)bo>Kg5#coQjRw96qvqkR*guF=}EEW;lVq0#n$T5O|r3dDlaQ~|UVy!GZ{ zl+;+#kjGpnQ@I%^v%K}@4sgdJJaPqoyzQW70_1=DXkAghT;adqwiek=BHQ&2%)&)> zaeY~Nxxz)@J`YCZb^Lhcpxy_Fz6P)#AipQ9*Ded+dh=g!&jBM6#gEtZP81Dbp=%39 zFGBES1n2j|A|uDDEZ=&w9^7GIc%K5~0pz!+Cl=Y(psCkv8FqX`EC-+qfc_PV25Y1N z@dAvQ;2F*BMm=X)S;-49_AgIxj*B8@0tD6qZCKZ?fA6FThB?3ppV?62P$J4F}a4Ab(LkQMSZ&k^-KE9|HE32#;KgpMvyy65=AKLSmpuNwbaNPM`-J0@45VpiYqoz3ox|$dR|kCQ?;fMZHI2!Rr&UtI$NtjJL(k zkqt=vWpY&hg*U1~PovxXN8T2@;vBhAb>t~nmqkwmZEjS_8T&5x70~8JmC%I`u5+E5 z1WfjDqv~bg!V_`Qoso#qQ63=%4p-r48UiA3;w7YV4(>JFl;C^{5cyX4^YBwC{1dP{ zC1>p3Mc_Xq{EhOn1wVxY@KYl~e+D9QqVH{n%xGbk$j>zVMAtrx?N)%o|KcYj;5zqy z-pG6D8SDUq_GSSj;_M*O3P0iBF~2W{NMs47!@a?BWW{+Hx=0f6C_suVYGh8oMYYC8 zzXUU>rpQPZdtNrc8kx&4aJdvoH0qUohRApqM1d?BwrhMDc#V8%yDgTboZgbV*GPx!phfuuYPg) zVh%66gAX8we~N34>_0bGDkL_Za+c^UA+VNk#wUm`2b89=azn*jJotY+p3d*WuM%Cz zdFemvLicD#;_bFZFK;xGT(hlDqxj#5Zwa0IU*aaV_Gh#8(Aa-V03TY=TxE_d+kI?Fye0-l4@16lUn3>Hs* z3uc|&$XTG-_{+W~;Lb%jQc7b=!{++SKB;8kQt&Dzr7u#vKOp-MXfNvqY!C|Agpe%& zk?r`2o`9&;0AV>{J|Kq|^0t%PAk35Hod9yO9F~*iG#6|+Q9kiTJy9MFAScRUIZ-YK zn;XdwAe1M`2LX7J-1Vl~ljKVu!iJrsByT&JaWmW(0wNFK$NS_K>`x0Aj^NDz;nw)6 zhA^kj$p{^YfJlzWtc9=#5ZyNidl~?Rqfrv40fg~B^~Vu-73j!p{CL+uc0NGiuGLuT ziU{7NJ_8~@gO2=-A1@msiAW`U1E^w%a2`DzGV4TUv&b}s%&P$54)`e-8JRyPLuQo7 zj24-FC}ashbRX(G4Itba8CQw0yg2T0gq|kl>LcZP9Ku5ZqE{n055WH`l*6tXM3NO` zDcXofNm~Kx9wk+)X^0)lQIhA((__6p0CkV`Y*~8NOCiF8q0BF&@;kIk(0N zawnvWQ8swQb&e=kMt`gzBc~uNa=QGSfuH=!HFZTqo00tpjC>AzMGD0o(xwTe{g;IrL*+#(Ek;|s9CH7l!8&qckNqK6Pm8Ni%$OGIL=c;7hzRvGISEy@ z?6F`K%AKNWYauO;_2}i$_R9#5yn`R_eo!9)`(o`t?f^fK(Rlq0+9YhOQ;h`>QD`CtPWlr>Pw602N0_Vck{NW-E!ivM+uD4-^(3M z@v5~WAVRmx&?f$qHwR@#Q9Bzj1EhJmlo>p}h?mQQX7DjMn}f%}c=5{^sH%7gQO4hY zx`fDKT}Gb!#}jfL;$K3X{uN3hn|-DLyoC6&`xl-ycU#G9hwu2}8pV3Ym(VN@-s?py zNh*%L;+xQAs%d;`x zk>$9lO%p8k{LiCrMaoXYA8;@6CHMG2R9e>aMof-?Ap7Bev);TKjJb8wjQ>67i-mnNjB530m4k z>CnPTvq;2P$&+9?oGr$xkYnflNQ{TFzX8ahY*-Fu%Y`j(3gbbn_k=l!4a-4n6 zbK>*{+7>y&W{WS4ikx?nztgEb~8Hhw&ZjWm)F`2FzuCH3I4^^OKXH z>ew>>i5KcG^9zI@Tjn?3_K(Z_auM>E`Nfc_x6F^cXf5-rAuP-MiO7q~{Eh&1m-$W* z>B%yGAF9M<{@nmv<`)3Omib3jYh2>WGXHtx&1L>!0Bf0F8j#5azTAj^)-u1L2G?2U zcR*od%Y0u#qDTB?{>zZyF%p;gO*9dT)LG^y)#21x=8v&hv1R_xNVj&GUt){+%luPb zs=v(du42@Izsyg!1OI24FYEYiDv^eY$vVCa3D;f6+Y+*l9}S7R>-Z{7L$oUE_?I9N zJ2R=n#5(>bFk|a@o5^*2`pecj-se)ISjV3SW^5f_hlzFkA~3CW{7x+s<6<5EBG`5J z`|3zw9bW?puH!pZ)nCWkqMU7>3lXm47XtkAI=)&9zyYo9I{qd1*f;Rta>b^00Q~=2 zqQ2~2g|o2O@=zQ$2QDlLiNy{0SeJ*lV1%)jhx=>ezh~lbFi_0+igkG?@txLR<9DNb zE#9EC3;%-OwsEs+KEab)-?mxS6^|$IX|3|sgmT+1b*s}5txa1b za>55V`NzNDXMQ4|wJDZ}&+LQjfi@omU`9{5&bbJ~AD*|xV0U7dMoxeH3w9lsw+%WU z*Z~Q29VhWZxvwNRr#^$Y-Ns2_^5sf+vc{I)5bS}+30p#lH$2I1ah^$BtRvWST!Ode zb!9Jc%i(lFOCf%EIP%Lhd3*!lk*dNi~KyW7nL~jJ>1rV-=#S{zsV4FB^075@S zz+(4X{{DvFGTh#3~`y-J}NQp!TR7z2<^(ssL)W9qYqg3VH14Zu?3WMr~R zr9pq8N5I&Wg7z3pUGbjjEESOXHNtVv6hh{n4(D9j@}5uP7G-tKSf~4LI7@MbVzt*iF!QMPni5*FmJV`HW}A;KTGjA>ZLW z<`buYNLI5c>IWiI3FkI9OW_#Q)}4|MJDn-EI)*jM`v`@jy(&HY4cxyU(#+?Fo&^0d zUUe6|i1J0dD=~-ib83&?>2ePf>b(Ze%qQt&()| zkWMvXJ%a$R)z?_>0Wf;C9X)M2zGw=raTZdFeahyI;PmOq-tAzsG_L}%G@TDwrSaus zrTNuQ4qZ?#VK>n_%5)8wWF7(Jv1gmpQ}x62g55K zZ5mL@>rVXzmfsThT!X*2l@#(y-%`W-y{#DH7T1{BA8l!7AA`$e|D<&O(}gfIO^?3& zc-x@&7=*Ti5e>eL4L*P}cOQNys+@x|OjA5r$}pu1@*gE-INS8VEW~3ERQev!O{$ZH zFJ%mU2D*DQG)6AvLl3-@;P8dj=a8n6EY=*@sv|I>41f@gBrI)OC2n~nT-6l_W?L3* zJPAiI8cSMZtzX^^?!TepfxDsR8`!&4%{NfZS$ufRFtYjR^SpK(SoxsX+;#(?#cVz# zc8dw;179~YAu|xqF_?P2kyxAS(RTV6^lE9h16rO+>Z}<0S|~c3#u$0;qaJh^O1IvL zRfRmPZRk+`E_E1J8HaHTXy$k|Xvi(@}g$_zM+X^7kn0p4bS{s7UY?_$GPz*GQF zz;gf>3TXXaf^(UGTLGpE_yyo5fHJoXzeCRV9maA{#Y)j(q@92aZ%0Q@uGTJkE&#je zDu9^7II2~TbS@qp&6PeyWlc(!CjIbni-pc`1SK7`ysF!yl?eTo68>B7hE%X zv4=L%#EWuAH*!*aLb_;yPe`v^pafcK&IP8%=A-XFqLo^UYk!)rQ_uVOqXZ}Z4;Yiu zH|@pt(S#FxIyCU#xcngVuxF+(5^H}NbhoGQYW7XjpJ)vF^pBzMZxH|4=@r%uxoJ%i zVcGO%-UnbOV!0Om=CcH+m4I;v5}b|ze12z#=1a}qUDnt;bDuuHvj*UkO6=gs1YoC% zN&Ct3J6D0J%_olw?X%dym1POuN8s~WoJ16g&*Cg`r=dvEw~%=+DMfRPkAne>hpxQP zC_EME2e+5SdA%TKnsA|;qh7T$n9&Cj?*-J7TJt$HtCiEcdXvF5<#NJrL8?O3ux)yh zHx1?Z1OeV=fUg0fcO!>iB%!xZzX6&*)&CGiq-LK&9*q2Ma0NCuJ~1xI%K`TcFua)n zBLEh=MdC7WsFH!9FItIU2cz9WcZ?=HK+3)uO%OzI_-vS4wG{2K>1kd8LPsOOO8_VV zSmZXiJ$V{{Lr>?(V7hjC(3=asnl)>`SJP(gH%xCCF*Se2btBufLHHO(3zb{%K6N>! z#Yz=D^CIpf_{4kf#5tutu?vp0!Y5t=;Wtl_Oo;q!i@tB=I7fZ4nQgH&@`pbWEAR

eG+p;wCY+9O zJF$A;FX4(8NvHg}9SYGEX`d_UZ?+4u*fAU?ITY0A+3~q?oJbLmyu$Des1lPyG<~CzHZ)0QB)|0b)MBQkB3yB$L8#kfu5b z8Lp^CbHq*rjl@wX-lSk#Onb9|KoA1G<@`>@=`L!@&A}B=jF0 z_W+I^*jIc3_LV|xi<|%?YpHGN^r};fe#)|a-Y-Yode=`tb8&8`w+<#Z{pg9NKV{v|;bc7le;;#gyF z_L`4i(yJLSH+up`liPtm_@bOWkKAp&Q$1rQZQK_9|ND zHGsE{15^WS6PX`UWPYIwfJ5ACnTol^gEGIkg^A@I!2*Lb!CO+K_41~FgP~sH-jX5} z&iffOD{bWc8UEZ9&hRJH=)7`69l{u&{n|W@3G+{An-$i(_26}z?lMG0~jeF^+!A)C%^+3C*Tmkl>lY# zb@=Uku`$FlcP^-DF={cW?qdxvEbko1kg`^!qKMS^THNu{)Y|b{`YZLGFhR$l)xmp~?-U0SXpY0T#{{x#IrD{BVts4us7ztgF4WtlLG=!F1T0+s?~0yu1cKMOYbCe6XjlYC;+QB2OY!Z3!eFoaSu zh6>vlDrgK@yPL-tX2P-BGK_~U!&qY(#v`_2Y!SmK(CpG0$m}Gwdn4x}{0oj?VtI{! zQ^QbtI%pb39veIFGte}Qyi^*-fd8stYXm0WmJmK>nfEH&fMMRFAXRJLYi%yfyFH@PyuX8(G4F-$HWf;T zIfmvz;tDCkwW-IX_lGaq0fUt?T$LL1zWyu0nTi0f?caElhJZ~7nGdkoU54Li2;mO` zEOBcPC%P5n29TTw%~G96UkjcwwY%pW_vb+f$$z?}k>e|t-E0}U*>(g*s__$j4h7pM z;5&dr0{SBBBLXG?IGBKxxk>m<(roY)2)dNt5bSHWrp9@fJBg;R^+E3JYZC$3*H!_r zuT=xEuf;)_eXSpW>1&tXheTCl?09~D^v{zub1r_WeL^O4Ez|(mKQoj-FMI$!@UZm4 zYq)2oF8P|awJv!E8D~4C58ZGsrF1oD?yyZ5_aMgq z@FNqki2(BsUOFz(i*pm5=MWH`1n?Tbv#zrX|AhzOC%L)UI(7m3fjLs7wga3iphJU1 zXB@!4T<1#shgjDc>NfmW=H7|la$l+3d0AlVdz;UC%B@nkl6Cn6^*And={i2|T4cd` zbR9448%l{w)U&4Xm)xei&pS0X7aBdrH}*b2B=$F&c<1q^m(#?1j!*Cs8!CIDdr+gM zA>+_hNSh}inaqnDQ8g;Su|IQsoVNx-W}U&r8`_EY8z1j|1U~aFYKQ|5KYgsh!>KA- zBqtf^J|QO=xk|toR>KgEi!t2WUh1oscW-;CtTBfB$WTk#)ZW?Q7Hf1VqdWDiX_&>G zfhwK{5PcY6JOJ8eD*nrV`f}{pseCfzgUi}ucMw9`!H9kfPz`|nUHnc{InJ<3l;8~O zvG#FzJfnaUEZO~?qs&Yx!IYLg8aZdr7rC#$&K=Zt1==iyC5_#)D z4|oUrWkbh{ZHD%P=6T{Uws9!A5jyI9KTbLeJ zt~3T0rW3){h3N)2>)-Ltqxcsb-(FOs%{!jWoAskiug0@^O;eXp2z5*@F(xeE`*o)* zL;YTrI<_J|?>^+fsaz|@&1>8w(Tvzi7lY>1&CsIoLe(?=&Xc9Gya~$ z)I*&T6U{5qQrn9=3vC5WSJ%$)Zw(}x6NNVIx!!mlH0K8??PY!tdO4VA#`pG=*YSEp z`zo!Ij@Lz20LSZd+IOE|YCYeK*Lm$HY5>RJEb&Vn+c)!$qk0^JCnP1-PBFV{^3v;N zin$X~wPWxA<%%`S`;2-cD#zgCD7_hj@fa*}sGSsaZf_<9(-0b333*Nmy0VfB-5O1h z<8_x463uu$q&>%L45W8V#wnP}a3DPw{q85E@-P@)I&}0TK=cT}3jpkLzC63!)b?@S zXmD#6HPxCNUDMTIF9us(lZ>*y`Z&twg8yh!9c8DYd>m!h0C1Gu3&2q}2{IgIhXQbv zy&Axbvai9RP18(^gedn38Gn9g@{cD1QRzhfXA)Bg1;o?CEVxPyY!tdwPl)DWqo~(;TVM zQ_-{2o2f>{sT@|W;O>_i+k;E~3jMWI3buqDMEk5EOh3Kd^jVJ2OW6xhyDUvXn#Y}* zh6IWwk+7-VdC0ikSXi*3H)DJ#`3f%3kon@o{RHTyBjXdjMTkSEUIS3ysn?Mfr~V>@ z=+yh4Xgl=+EtXj}D?xqKb?T^i(~skw^YJfu$gcPyGZv-(4b^{RDt?;?eQPkM@`nxP z&dLu4a|flyVD6gyWH4RH&vXrDQTq$sjM=$4V#2u-^P|DbC9m&@{V}kEUUL}*z-iSJ z9rV?~-8zVA$OhWuh_+Lrwl9?+{Z6hS%tn*q`>u)!nQ!KHU<4%b38EjDBwA<^6g5P4 z^J=K0W$Cb{$PFj5s@E|%-f^egj&|Q8ZNGz6&btu}LVvCFk>={J-=^*46}M0i`Zk?Q z-e;iczuz`0qn&*~S%2xhn;iPZ8u5z<+IR47I7R*9Zve5S_nOO$Vf%jZH85-aVx`T6 zU+i+K`o%E-#xI7?ysD9t)&iM)4lB!RiO~W9(Q8^II%5QU+&a;jC}3(zqEjj$zD=St zM?mj(iOymH+fx&rl>$z0pXjU+umzw}K<5sL&NhI>?hgL$!Ec#+0KZ4BFeNW@zX7#l zqEGz{YJu`-)fKi?J00S@Cy}P{n|jc6-EjyIQel)sLMC zt`)mn`Dv1O2gJV2j=kJUn|a?Giw$}1jAn@?OzIHtJ=R0*JKSw2-W4IiV-fsHW}irwBjM#(fi=O91lYVAR_uo0g~dFD*^-#-rt1irFuN*vSBxxQO7<%Z(tLMp7;Y zUj&VTrA)He0jj-QEO=`PicV)9XPUw)}eU8}dj`sktJ6;OF?s!^v zt2_D;rBp@ej(z-G&Fm@1&h}DdI|Y$zvn^0I>ogJB_Jk6d?N^XvwxtMRwiTMK6Bhqb zCHkF;7~lIb(t2u)LIB3t3J~)fldY_zp!2~rhD~=h$1dpA9pWRkg*X&HqkJ(HzU%W{p?7UR+@~&eo`#uUV;)_-2Z?2$r=R3`pMq< z{p4=HpJV`7{baNX(xxQkzmQCAKk00DqdUOfibgb!So%qZve{3BJs<2^TNt8j_LF63 zzWXw?`Jw=9zBB+f-{%0a=JO-^{p5Q;S7R-OcDBor?P;gm*%sS{z8l#d0-OD$0)W}} z?5){efDp;nxTkW_?+PS%3HY`3D76#32MJ!^M-%J=zy!bd6MPK7B*=~@3EqzwulO;J z_%S-e)v@MF0b(_uV`U{B??N!O8J|PF?$9zKG{F$Re8&`^(d_wYRp&hkIh>13lu1!hKY@d)TD-BhXOfA_b zWZjwJ6Fi-_34bcdnwDs&7=LPV&3i*)nLoLqGJ)Tb}AIb&IGn|h*NKHbgo~e6C|L(v&q;;TK)4hhDGc?hh z5q-e;x<}L`t>8*Cv(P=F7FGcFh#I9;P4y*srjwZF;CV>-!(m5jvwhQqXF6YZFxxlf z2n{XD((RjXSYNYl67N#ep_w-eh2b>zJV?dXO&MAgdQt2ry#y)x5*}G**<4I=(-D=E z+@Bz(>n1t0Nki_zUpfT6Z*nksM}U`l7AEfkHY3D3wDAyb4s8k$C%O$}?9e7tE6s66 z4s9Bo?K?KyeVL=&bZ8;e7aSfP{n^3ain{7XTqn}o$Cdc+jS&?Dvn&?DXmU_7EYfR&nQ(LJ{`a<=(|9P@WpB^Sxo zSA|cApV;IRlE6`)5Es-!O%vU9nnHPG*qw4My6Q{PU8j$f&56AKpb&o?gBO`TQXEHK zNv?Je!w>xin%!&8$R{BmYCKZA*G(hYy=H=D_qx&WC*{EiWxr-N(+_BoT+_pJ1GO5%AsAv0eWcbh`Jdl%us7psS^?pJ*{y>1& z-%E5Fl>yuYaH4>>0NMjYn-@SA09>N3R5f#q&YRxOyAWLV?NJ4eQORmi|} z99gCxv`QANfEG`Us17Cr#B|_`iBAz7{DMSkbx@;;kP96=ji}VYQ2_OCXQ9SbQpm@U z$x)cZc?j_46~fg5L@$I)06WTF0Ctp)7idSB3=r!m6`C-; zt8|o2;IgB%z0fieU(7d>uOY?aaS+^Km0oswLWoKunFC;qWTCso$|?F47_pAB&90nu zlxM)TI*QX4wUdsr8{L8(rO_qYQEmc=b(9Q|la4Y9p?*h^Z&U2FGkAGqf>#E=#BWoy zz9_NwZhN&=4Y}L?KBP<=Ead0fV6sjo{)NgBYeWQY`&GI{?#UEO=C2{`i@-FC9&rLk z?X0(h{hH5S=r)uGJn<(^D%9m-J&$~yX|mOAf#B^}vcqj!(_DZIgr--lP-;a{--Oo^vQ zC;ey2RK*;f7;KJ91~43t8TUq%nd=02 zmzJkRT@1ck9&|d*;KOpIxwFBXWpp1ZzHp!XOn z#S2VnSmFzbHLaOhXprj>b*n_rJ;%*rZFA45t!?f(G>ZL3ptk0D49~8S@R0_ywj&H? z4MPUA=A(#_-EqXo`V_Iwp6h1ymPfVEp3CgUO5izj=bqZY$(m&0_&mtu&Sf#?UjR3n zJ9i%zr`ZF?<6Ly)+*_s1Z@;@i4AZXjD4&~ss+2E(u4(j9NXR3Wqra<=$0L%@#guik zwi<$kc}4J8Q!o~w*eXD=DZmbq88=t%reyE3@E!}#4&x5CkwKQ9fYbal#LCbt(?Tdx z#@z3g;#l`LF|>@iVs%-}(g**(+zjM- zh2%RjTQuQjl^LS8nMY=`X=#k%?Am^p&j{HoM1GXPY}x`N!>08NW}nS7GBo56v6|X# z*(k>vB=eOdl{8$mrsYT)&T=FiAcOdalZdGccDkhDEFV`lZ4KtV{Win74Z>ATiV3Hg zpE#UNUL^gz>2TT$>yT_P%iY|_x0QTPV1dlN{g%VUA7#@ov^FyI9jy#z{aYCPsQ9DQ z;gvV~x3HR-bl4Swl+kUO{|;A0I5|t*E|TRJ!=aJhK~o45Ei2~u85 zKRO3xU5+9=FU9znEZ1B--)H5w-^%Y(E58FKKU&2ncDldjz$5HMnsZJ^wYz7lMRd=m z6>vmQOe^S4E6rl7cF&ep#hSVDcIW|rg}ek+mC?xg4*!CanNME$AeI-OqtKJ7qr7#X zZ?NdN|0Fsb4UBwf3}{-}bjA<82%465HR~3N|4P@;R~h~U(A48JrXQ*TO$(fA=zG7$ z8KhXrHPk`q*Kc&qJcaS~LyyaHYRXM5I9p6U6>e@;PMmicVsqLP{vJ>KWJ&PNIZeGA z4kbFr5fD89egJPKjd9j8f*xrosU*>XzzCHV5Vrde+_(OkLS61hsS zIjQ9=E=$>*XWfeOj6gD+Ns&ET*<41?2YYsmE%U6!%H}+4CD>1b9h;?j9=Dj>eE*4%Ii)=F`vM|jIujnpZoZO=(QIv$I4G;Uox!9!cuDS9yuwQ;&^Yu%+ z-fe>dSNU>75oxDS$n@&45_lC#@tvm4rqS{WV8S3@vV6aK|g2loBWdK?6COxp!Zqya?n3m^v9stBZdtVw~?22B++577&c6LMd(4$ zjtqA>!`Qo<3m#4!`VV-g3VoL0(OS=8I-xUv#g32g&Ne(+cCO*A7oPajJj0`>$~KtZ zV}!xaaX*alUdKJE0yu%dI8<4&=Pp;sr%FowSZ>b4>D z+Fx}0(jeCNYS_xfqK}sbiKhr{0Zs4s9{F2b(`R=L;=WhhciN|`$qn5Cnls5)21#p# z-UH2=zG3K;!-)<@vnoT615IteY~tSqnp%6^&{MwGeXbpY=Ay`<3eeQZo20X;saK8c zZt$qZw+2begu4Hrdv0$V`c}}~6WeLzUk1%Rx_1oi!m@5Sj#hZr(EUKuzkD!Ae0pdS zX!_ahpgHT68GXCWB)1le8q zFM0&kUoBt|>ar2QneR@OYB>nBP-St0K2X?T`Ckf~iB9@C8Jc-{v4KColH z!_mt63q9{WaEF0imR5RAo!a|cX0%+qJ3}ZaR2zc$-kq+bwC39&Hc}#pn3oE)A3Rf zZaY?MY~H6hfF}iBhmaWtWmnR<+a%6W@^d^X(CWCdvGb!*7bEk~nSUgjw@)21dEE+{ zZ>LgvCuqLC%Ful8(@{-;iGPbH1)BevXuX}vxy#C1*k^;y_dZ<c{I2!IT6B!_Hh?<-jKyw_2w#g>1p=M`7$e|IfQbNQ?n?X? zXf_=GGnHUJyPzY=23hS%tlJp7@P|>Tl)vn{mDFeFfz7(z2;jfds#K-YM8i*k!Dlgk zq=s3HIV!;2+8=T8{vd=*F&4VZ?bxmV*4Q<*u`BG@HHbYDLVoN`cI+Gc*gw_AuCinQ zgxHm_*tD!Y%4h5T0u6i#J}rySf%w+L*JJsXP;{ku7mZkS6DA+=kz514B($DEsqb)oZ4Pjw`(_r!Rfq28IWFMj3fSB*;1mLsxyAS$y~6ajGItWFJxX!6-Z>2!F6-IUI~n=#c%cx0 zyY=@1#CGdPX;tY>^?k{V^R_dSg4UIm-)DVYu6zo*18?c&o5X^e?Q+tE{Zn(a`DW!?`~qI#5Wy}-iT6?3cE(cp$i?af+m%l<{~Lz7N7Acx29nKjWHabQ z&1Mb&vv~s`md(NX*)#^%%EnP0FdMg5ocFt=$86ZQC7bwOjlJ&8wQt`Fz{`7|1F&yT zX<_y4bWP9i+k?PV?Z_E+wWODTY@R{5@j23`x7(#i0sAYkV}07@vRAfgsgX^e_S=yj zt4%NMm3C-tuUx76kY2gX!bcUeBc^F_iligv`h;}EIX1Di3D82oUVt=!X!}+Hr@Md>fB^s~=lIE*gy1MSEF2M9kyQ2lvwM@k!jL>mQQV2(%QQO{My7*l+DCj zA@Sv4#}ZFfZY=RP>n1+HPCTWgqxXlOcv$St=>l_XgG76@F^QUs&In~mrz4a`id$yI z2n;=s0M1t18s&&dm)Heti?oi%V!;o81s^=(ApG#@J!N}9{qX6=4|BfN$M{%!!QK>7 zzdAvtSrwXknna#@5DgjVgT_p!U|#RG>Q2+^xX)9}BEOxixH~JFD?EqzNHGa2guCg6lrFgQGU`jf2A0;I?i5kf3-%ia*>2lCK;5ey- z+aVu<=JV(sjJe&F8Zd8sY;QCu%dvf$16^ubNn@`Ugy=Nb992@}lcCsg2xfEejgNaZ zmh|MKet9uDhO&=~!dG;%CdVr}iE(E&lkG0UFazKHoj6hEptisvLG*kC>Yz_KBHNGd+1VL>99?F;nWF&6A;4nR0HF&HeY* z2Jeu_EizgCPX#wOn5yVwFjdhzvsM+Sn{e)D^)TtP`llJp>Zh|n*;I8W6aJ&5-zM`~ zDFbc(RFh6)IsHn>lpQ~#(#|F>Rox|%Dx$i&8u^wY-!49w{=Z29FkelED)Mw>S7|!D%MV zTLqtN@Cv~liFFU;o=k04ub(z_Apl<PLmX2l&M5Nm*2$XF%+$V#W^#*5Y!Q^!xHo!N^Gv)-Nb4AI77C~VxJy9q^nkNk zKxGzulYoR_0q1#uGWT`-Hk2JB{FS-yf!eXrQ22~iSKQYfacaQXD{zmKtHV5(9!N6s(6PV21xGr!|{ROA6uku+2-xVuwJ&&|fX8Vo1@4E&}(XxJIT z-qWd_*L8Tn$rCo7&}o7H7i;`X5jfZ>K70w5q|>02;Ln|!dbc63=?I8M0d4|t!aqYh z6~h0kQ+qEsDBv`F9PL^(FyJHuEOO)SsJJoJpxdh(bOwrkhRB%$zUUHgvIGq59&knp z=+OhKQUTuslnD5&XTX^zAg6c0nJu7GX24k>;B$cG0>%yqI28i=qOuzVoPACJ-)@(2 za65miB`_s7;OrA{<%j@2;SR6`;D~_BN5Wp$0UQHJ60ms`HYWt+hOj~ru)P496!2ew zAp-6{50i5NV@6|gF5tE?SfL20D8>p!K>u-=M+>rl2CPaDfc>A z@GjvjtE_UDa22@hD7yg6T|y`S0J1E#?XhS^l6Mj8@nmo3`CjssTi2e!ifq)Cn3^;EHr~r6EK+@2F^N@fDz*Yh40X`M*6Tr6u`olf^2C&#| zuvmIYc8`Y6HZ4_^>O=` z1psV>_W(>IRBP&Ngyx9OMmPr`)(E~xtPxtArHybMK&%mbF~1Sc0kgId_Gv!kq7gQN z%SJc=U^l`TH9@)*X@mnPi)jRN33|2)&|^(SD>O&i|*de?CAAJB$K#IBX`P#9)A)mSe@C-yK0g~Tj*vz zWO$Ns^wnsLy-K#U3$kDj9mNX5iX$AC!{-45WZNUB(}+A75! zSi~lH1*u{rRy|ups`oV{O!e?C64WjFdw#&#g#w1<+py(Q+YeE&wg~+k0nuUr`PeKw z&>YQA3U+y?BySm*EZ7?WS}?pyd7UX$y43$U=w&~WH*butk@TDQZSGwJKgKsk|B5Q{ zjnP*Y2KdHkydkYSiuFidfUjzA1Vz3TGB)3*AahTI@2~9TC2h=9Lwm%?bVm zgB%NPZ24$&x#GJMT$3oA?olLC^RQ7|nd`0xwZ^9sK^=L-P~7*akaA6e8uv)KFyMJT zigZI}IzVhgW{(;YtyK1pRzqIvCnIRJq;mz*c@(iYf*uDjBdEOK+vx%R)V{5}-sfs_ z-7rC$>opHl z!0v+alWZz|jws_MDC@lQRq2%g+y(m$Ag1)Ab~Qxl>EK#QuatCdMmk+CP^I4jP^)Bi$}lrLO^qDSfosM@;D_U#Lo-4-iwjEhb7Y1k+ObL^~Bx`d09%^zQ*w z=@~tt^llSX>DK_%D*a%6rC)_YT1sD|8L(02L#t_H>L^{=RQg=7qduETFGkM6yP&MA zE>fkx4M3$QUu-Mgu7)W6Oo&-ZFPC&yAf4feMN3}=P^n0l}OfuLR)K>{9?U zHCv-;aB9|RvQEv;1Bgw{e397HEd2_dSu6sGP0f5UDUHmJ&jXWH;} ztO1}^VicD7@%HtmVOeLHnoXYOPtC$IQ_YZCW%Ubqi%>?+P=5p947Cv?Wnvl~2q05c zt|CThg4B}CRL4!RwKPZ4li(i^OfB67KrNkfrLU!8O@mr`aH?u)H$Y5FzDP_<6^P9z zk{UrQrX^p@*V1lC)oN+7RaVi`Kt!dMCIhIJ!lI=rDYa^8|MLqe5O7+|fV5?`2lv>o&tyVqxqcPP< z(mjyw;x^*?_41C+2soF5VP;v?ngNZkpkJKV_8M!JWpg>p`WlL4cQmmN+p)uly$Sr- z9L?r3_RV!;ch;q^F?_@h*?HSs#-0PNm3NLE`&`6+#*S@s8T>+mSdG%wDtsC3lpknL{ z#C{$8Sl&D9$G$Tb+bQb(Y9psqca4h9eA;!Abx|#Q>_fDwf(sS%38^(cArC?y^a*(_ zdP7}T@(mKBY$9D(cub(cC;GgH!v&qn7cIuw+a8~g2d>j}=8OWAWGXI_PnHz>gnV&i zvQ4b1jWYU>&yb3B)(Iis1u;trsacXvT3G#2J|Wq!Qi4)C${H!3pp+6Km8_$e;L#Rd zuDD3*o2+v+^XV{~$gzphHZj>IX4^!$Pw-PNJ|TMXC*suDUYq037RgE0Sxk|{@uxH- zw%eS8Hqj6xvHTUa#iMIGd_uI5tD{$uygp-$PsmeoB|h=+_3=(;b>Fm;O+F!=<)H%5yiDO4e(RO+x$;nc zKJyCAy(eHU7mqabko&MYe;xc>Lw~kPx5m#lbo2WI=KEkdhQ929fWt>#h8cRyg8`>h zE@fvKdgH^`6qf^-Y?HtHNWhsR{NaYa;n9Heg*=`!w72Z~hlVsW2M&lwHtrQ~&ewr}+V_!fXQeP(F@ryI#= zQ~Bf0(S^O6dVfIY9KyI2o?)}c^^W&yP))PmYXl;&u6xQS)1EIO@v(J))ywq+^z>Oxv?QSs~i>cWbc9Asq0iR3*AiR$uJpO zjBuW;ZDOC{&XFw;+=Qk-A40Klbbv;eSqI1Pm%%k-IJ&^JZ=rRs&pZ|4_E)hIQs`i# zKFz(K5rZ2tH?FsqskWFbQwM-)8asUEUR;NgRvO(W;B7~E0Rp^}HUyk80%ibA6tD}R zR6x&-=*j|?04xSr;%4>53idF_dqC#P{^D{i7q{>B%;@0tenR&dX92|a8CP1xmwm?d zU{dFw0vMeybl0d5C$u?F2AoHci+KVH`3674Awe^Qntm&NVVjj|@FTF3(a`J@`yt0Z zu?~QJVkUs}34M)>#^khbFJcZyOr1nYwVJ5=p}Kd^$n{=$TC4Q~K&)D}m{jZJXS7;{ z0BX45|DqOiqym3nYP=PUgnvV+-vhK1FdyJ#fas-gjXeOk2+h<2q)B`4oPpO^f~yun z>zua5@_48BN$@&9=c`6s+H7UhrDcNsD%iYUxfFmd?NBm*z)g?~u2lLCRPV z9qnRGmx}4zr=@oxB9l)uEw@W0>{r01nH~X%?WQcZQV}y<>L+4c(wh3Ioc6rdEqvF! zc&Ad7*}qRK@9LKW&SMCOUI6|x0O22l4V?pEcYV=~_qv1ao}dfTN-N8*K{v_!>LtHo z=7o*P{gCP)XzCdxMos+=Kuui$QEIAmtEH)w=W89STtpoPrfTX0;&)BXH_4jS*j($JNq>D&PO<#WibF1 zQ3XInoQg?AY)r1Ux~??KFObq^kuCj$c1hNwptCUs#~icGrDHxHNvmIw*vB+Bmq#1= z#6@B;9knmtrAMq-DavE4jmUEe+8`D)wO&l`0>6dy5W;T3M-clJG*K*erNw25mx62M zz0=|cA4TjcJ8zrI*hlK-eb|ou7-C;&=WTNtyK^jW-h}L~qkhp9n9Wc030a!WQvb`l zSgER1en!uCeB^BKIS(MtHlL8!{_V7hV%1<#VJg0yu0`haTE6vjo}Z?+&ShhvPsnnh z!Y2HgrYyXU_>7;ipjobc01JS$ZKgXM}AYpWJ53Yw{}g zeB|nmrZ;mtZZ}wT6VSYQWcZtLS)$6}^&^v@1nh8l2dOro+Tlf{+JL>zqcU+f0ilh^ zlM9WBtaIoW(7gRM#n1(>=|X05zX8xyXgz2yWUe6JJUKGS$o`J0)`6*U|&DZF1(?7r+9P?_; z5sZxfTrT><-{^R`k5-AhXkW>Fv{OphpP!ql*Hlj_;R3($wR%le>3cx)Q#FPTZ+ahx zy|Q_CT1k@k;dQt!f&j1iY+N7_a1+3%0MW;9z~vBt@blGpf1SMgE|ebh;%~$x5&>TJ zO#$a40XNMFI9~!pAHO-^{3zhTTLR9X0;=Z*oW_#Y%eMxc<^r;BgYytjIv-v~z@!BM zr@w%I0}L17ED1QCfE{-RoC^WU+{^Hr^0d)HnL7aWQlW_66TxsKYcq z(TtKu8!iesb0x_S0d5E232==@<8*ORdTVbQxSaSu48R#Orwg$d}1?4T( zQ;0PHJfwN^4n2kV10Z$^u>lJO`D5$IX-x9%s&$@16i9j!yb8fQq!|vtQ;1&yZTAAGjw_F7f4RSAMy!(%%G#t+~npU@x=HAl~GShG#6zo;Uz&-GJnwreGDio8k!zbi$;Fu-VS=+QIcXT6Xj1m%k zj?a)7EwpEH_E+c=a<)+F6SB*@$tNVv5t|sGt;-o>r4pPMD#l3E9;46*8HskykUHs$ z&vwn=z{`gjcFmB%EQ=$AhL5d{VBWS?&B*3$YX;|L^UKD&896t5)w-rm@Lx<-zWm(n zDUkbSJb?}9?8_vv{WB_Xo|bD~5bzmO%jPGa512T)*;Aj!jPwwbLvc2^mm}H=iMqos z_zqL>d2b_q#VokNCi%A*0ZCLMdb&)F=5{f4=dJCzT{r>Z$A{;3sr}lr5i*m7+Zn-3 zB9?aHB!ZKRB_^B`kog94Vse|ooQy2!!Z%WJqOq{ctx&r8+VY|}aR8hjZU!*l4FcfTnP2ECD}k4c z53S%zU^P|&AIeH#2J_5o{)XOUpV5UghnqlCFEgl@yzfBsqs&I$e}Zvlmk;D#`^RtV z+;$dI3lGBXkkcPdb#|Aam-8m>GRp>1CBSF_sXK6&86bKMz%&6L0?ZcB{w>^P23YJa z7xF2P6(l$CcME^F3+p1}Sq)I;9>MPztzDV>7pQqLs?o=I7$` zUDz!&C$gXKicg@_VOJ=dc|QYo@Eza3vcnfEpDRhf)bu4Qm4o)LQYenjo%$2nK0}^l zKhMk*vydV`;HC6*(ENgzq1U_9@mTqGKeY|+E$B?&NQa8_5_{2UZKRiUsO-$|z$om+ zhjD1+MHDhisnG_r6P@2ndZX!F7xb!~p zTRF}9VpQ!;sa|j9miH*C!!ED%DLVt^jq#bi#DMee0L?eXXZDhAmzVr*zkgr8Xf}AP)fwb*29Y7gKC)K_ugz|qLEH%tn?cl68M_kQ%M4;Hn6)#AV>TBvh}Xg8 z4B{w&nL&ih_BC>fC6m1WL)*K+*;sx55xl&bQRGANn83%EuRv#I3Vy8h@fj3|FQ;x!Z!GYyB-j{@ME(&-cOd{cT` z0DM#WqX77(^wj|5P3h_NW5i{pP5h+ww5p*qeH5a!5)zwNLzTb^lLMV!N_xM6wL%%h z2E!oUG7MsqR4ZOR-jOgH#1_LKwi*WUu3-?H4TIQd8pJ7W5XZeGJ zd_}X!Rzx<7RWOSI5HXuY0~Eq$(H{Vt#q$8zEItLmW)TBsHjC>3cxEwGD?d4)!&D7y z7V~t1!a!S80%q|GOrqmym_x3_h*NOD6m09>?3)w76FmL|jpm9%1GL6mR9BFJMt3vd*qslDq z`N1%YmhTldi^d>&X3^fH!Ymeo%4V?_fHI3WzK<0d4N*y2RzmbQv|u|B(kwn@2($QM z00oV|DJf18@C<<82#9=(r%*=#35834bH)ckw(64G!0{G!q_0Q~CGF97(pq$)?$ zYe`)I7_TMCxj#h-%lq<{hw0_XxoAhWmyw_(EUN9u8S4#;9tVW z<4Nc9uK5Q}7X?;79{)=HfXJJM^e1$Y>L=q#uk(&0%~$GvGM;okF9&g@%EZ5WJoHrL zy@PZ;nPzW^K2U%sB#Y54r*NOvImf$?O#`8UJ_#jTXyFVicLE;9xDuYKcb^OS!P={t%31(!F$I(8Eh zzQ@1aDWx#MIzoup$1f`ce}HcK^=R>#@d?oz{6T(j){!5YjYEnbn*9a9eQ4I}BUu!C zQg~?g5r}fP&L{$%?VZOmUzg1jNPFmkGfBqt*dH?zYr`K8X*~l@zcO1Jwes}(OQ&LyZ__@jnc|SQ% z=-)G(Kdod?d_#);b<;{?u|Z(J=Lp03TS5DsXx}ugPc+^+A7xlQBdMCRMfFJ?vdYT| zeJnevrubGl9Gq>b*f^H+OVgxiX|$fTL%xhi14Zaid{Bi60dSab5&#({TmYtmUrPjK zn6Nq;=Y|P~P<{#%eh+RwI&>TOTqnPqQ9C*L)j{+o?|vo~llL@GdGg*0zzh@4Q;cqy z@HVtTh6y{R!FE?tXoh?^dz8+zYTwVEr-&|wWoo}qV z&&zd;2WWwWdDUHLth$SgRd=zm>drG)-Gh47Jxr_a7BwaAWu+fs;{1Wgk0KESG1Ay1x+|z3P z9R+}23w{kivGw<>?NV~Q{!YjGn+DrXxt8I2o@<%Hcs1A5s7LF%s^S1Ng|&G%xIArc zXi}lg*B~ovb3Xub8ftg-8AQoc2l-)AiFyegTLM{-`7@rK6VMqzHv;AZ=tsck0EPjW zVvWY{4m||CML(xftR`{w{L!1yCRURQzbG~71c2SNi2ztlHUVHY`3V54Nk!z6YC@55 zT?NmBM^z2H7*STCP=r#n);((~!?Uam@@s~YARoCtXDG%TLowzWiZRbr zjMqppMyu*F*x?Ic_01=TFNX`un+qYcVyJZBH>DWO>wQKJ-F-;&MAy6?Z!dNs&5F^S z^V5e5BmCjQw)ObKg?Yc1lph*w#q|8QkmkuSkIT!qE~v?{y`*1*G_TQ7Zg_smMRoR} z9d{~!3(`E@=QCY>xbWe6)ptmpQXejyWFYv%g%8yWDo1yM#UCzwv|ek4z)RKe$@oh? z{NciG_2h>Ozl9d(r~Fw`^rmCQJ-EL-S?7>?_pRqdpZ`Ot_X%*hll3lBfw9US0hg!V z2TUr|`%PqJ^?nS1RPRaFX~k3-#+zT}5~g2j!jO9WY_|h_*Ki26p`lF#y8}*act=0Roji0bq(X8^77A47nxJ1Hra7s-7M7VH3f& zwiC7Ulq~*Mw$=au+gd*WY-@7?u&sRpK-wC85iqE#-~h9(uQPo(aGs{ndk{j6Ia^^% zouDbXmrB42o52DfBr9CV9;Ld{X(79#&Dj-Q)YOX{FJ>lrozjaEW(9poI+^T#E@k&q zKCW5Dc(vi*-BiulJDZ~7m8kR|s(61*V=dTUlh*=%wctR_2e2)Z=6{fxWW`@fm@7V9 z(_16HuIa52-$*<=PG2#s>Q1PoTI1A0Bd-0)FGk^C!bfH!WI|TFOIF5ayt5`v3z$}h zC_k?yPb;^>p?`{;`uZ|>|0_I1zU)q=s|ADdHnRGC<|6>xVcU6}s3zyNL7x)QTS5E+ zh=QsKLGc}cH!X1ne>&WNACV2NJv9@ePk^gEag702Hv;U$py)?H9)Mv4{0d++0sWJL zVk!aK0X#>*tVmES0RR^TzoS2q)5jER15y)r%T$N$zu*}JRd}*yQgjO{+z-TLiZdSp zP|!FO6h9I041h}n*iKLcsQ7#U$pp*-PyxUcs}_C_sCxLOl+j9L10leK)lKc_dDOrz z(KpD%E>WpcK^c;`5dgbHQvk3_v>5=qL_Y&ym#A@aP=+M#0l+TNLI9>q#BW&kq7MC7 zGd{W(RDQ#r5uRfblT9QVmciQ zDo>|t0hpVX7&WHursWPOfIizmhZnR8FhgQ3JGvH)bhp?hl{d>LK~={O=-f;LRXiUO z7s&l3is$D8yaUfc_Y+D1T^496lu!5$0hS9(Ow)zo=?lkk^cITzNL@Gk5o=V3Iib~w zpRrxkl*O}RMQzm{X4Co%>s|xPE^!XlUALAo#ni3kxtm!`kkiW566R^8ey!JF74k_~ zgIeCSat-6v3{rrpgrDq2X)0-nik_g#Dw>tagq%t$%L;fZsZ>i%C0kV6+ruubL2qCh zIZji_b#f|c23he`qSC{V=8FxllT%6JMchF|;%(POof#%cuUTZw0i*-)8~r~Rh#_{ed4f|)Swhg4VR z@wT~SBYbWP{}LL@u_{+ajg?B@k2H@}V>wnE|Geqe1bhsjF#+LnLD7nU$p8un=u$o?dJ^y>fB^(7M4=-H zI1XSe0d+Eh;zoongD*GZSogmFo6; zY`c9M;YkVpB{Y?``#2=a^Q=n$f;8K1Q)#>R{{^cg4akA*HmnMD2LiS`6MqV7)(naT z06J{F94mSe*D=`c5^#MEL_w$;qOAnX1@I#QM*v(PU{Lj-u&IdZHG(3EfZYJf0GMi3 zqvUuLU7vuR0Gblu)C!6`0`3NI3xFwBZ~U(OOk40kq<&Q?w&3a1qMEf!MxRFxw&33Z zumwkJD+^AnV_0xmmD{!8Wng0q{t|#^!L=2iYr%J+6wiY9P`zZqU9VCWoD6_1_+v1# z1mI{S#TDivufMX0UFH~ ztYyVE*tE8~$J@k`?MZtLeJ-WUyg8cJ#4@k4&I3y2*g8wA)^{fB9H|pzol|v!!YBuH zf=sogst#J;7_WIeN3VMHs%^M3y=t>7!zR|JHoGjm%np<=Z^s7IX7`1c*}Em4&9*-m zBxC=5CCp}fhlF`4?pND8F?W}QdC9#~!Uw5Ax7Rk7*^Sy%-y~E06ZAH}f~UZ2v`k1- z?NpoGAi2zTW+r5tiY#wZwzv39p_Q}SOXO7ljR{m|^WXFFSOehk+s>rW0S++6mE3;Clp!sn%rt7F4f?%@6@| z04yTldjPKzaLd)$3=z<%J~l%Hq@%>o2#C1`n;`<)060a!bO65-a1wwIwN9}T@w;lT zo+eU}%J@R2c$(NkEn0|aqU^P5nivj%r-@Gh@IwE@b;dMtS_#XYCaQtT)5NU+ylLXH z;&Z2oV<3CeglL9(X_`3DP)!q00pMw(EdZV-$~Q8mi8$2Rlj|IdbB;L+_ZL2f@g;!H$=k|w%s3!ehBhH5Tcg>yh6p*Z5$LE2v`PSI{@jD zP~GeCGVgF;l>@+YmmWZ#kJh5iUxLB)K1?e64~f}2JLk?;!_T?bA$K#--P|UXa}RTK ztNCr28d#p+j_L%>Z>?2NJJbBuO(p33^D<4Kk5BK>iPy+S(FvOPhNzaos%yhoA0va^ zZ_Xk6<;2Gm)&V(T@g#Ui!aUi1X-tA&$w`nW$HR=P;hndLxUb4X^9I>yQrspD<3)0iMP*<~cm15~ySuUNcFm8;`zvdc4G4N!I+<@`0Q zgUSw|qAC|qSxK`pnUDjNAS>Vj3f57Z>~pHQa)2Ji;H;wo%98^$7P8|3Qt7ow^8n?^ z0lF`Md7VVx76Wt=#PL8BM4JZ13;+=I^Z3&t7C+O8%c+wPEem3VxK;qDOn^TpD6#-R zxY_uFT&-oQ6aGxGdf_*?Pfo`WIGIO`O0vKkYT8Px5Bk4}WYE==L02ho*6`a6!S<4Z zWr6pUcwWMLNI9|B-d)0MLER+GmUSz`Y9J=)ffz#raS;t@aS@GZ%RK7wwoJ&SJ)eay z2c;b|!BTQmH_EaX{tX5p+!zB9l>^ZeGU9GeqSKt$z0T#gHfEhOUh7>FN1OpJ$Q ztK1kA=>&8IP!&Lj5#T#Vd>t_qEt>_!Bp?b#H4lne1iTJlApw5?c!hwjEimm8a0tM5 z0$R5Wicbmn2*6>Ht-KE+;#rg%QnEh(~thokP1GPYf1M4J3_n<<)#L!0Ze7j&S z0QYvmE~*H&Ji5g2dGO2iizoZ`RL;;kxQ`6o;mMxg09&K7@nn4;$j4nW1@v@NnEV*X z={Fg3xk=@@JRelKkjQmJb%b+|t)qP43{UXn0BKX_5Xtk%nA zUfy)Btm6fbUY0PM!3u_zx|h=5olCq*y-oT#7pK35@QqBNL!m$XqAUI-Jj*C$3Nj&0 z;W@(;X3Kmy5UfNZPd+w=84M;YATrVt1Q#Awo#PB4Y5TOk$= z1SXX#_)`$q7LjNG9j+}2myfufhatQGuGT;llxPigB;YOpy$E<0z(4{j10JactO+G?e0H#<6@LT<$_B6jkDo&+1^0P$s zoE^gV>iDC*Q3N}LlMoG)+34(7!8DZkBXYBjnv{gk>ja`(L3O>A7?qDSm^J)YP?f9n zgcWLufPA%fLGcGlV=McXr1A|)xfNK+$2Z30fHUC~+VlkQ+$OfZA*y(O<>L&fWW7OyyA9Zd~WIV{e5s$1-f&G^js4q*_abt&|{8p+;FF=~Vl`7Nx zJ<)!uPA>H7zW(SXFx7ns$##wLJESQ2s*W%m5TdsO;O~ic_$DzR7SO2HNA}oGL2(9% zg3SfcFaRCi!_OWf4{K~kM*{m9Vc+S4AR`)`Fc#REDC=V&qE~@@kbrN2`2j#dTa@=R z0UJ68#a{s0ZJmZNfoc}3;Mm8@MIQy*mmoyf060#-2>|B-v}@4UUx+{2$)6l8i_)5c z5bXdUmw@pAIs>3LGg~T2S0=-22`QHVfpx#VqVVD{>G6c<2vC)2L1g72nN_C9PBufZf6!k+v)|2KasxOvVP*z;eU86J@?c_w;o4f+A5 zQ!yLr+@voRp0@&`=4GG>iy`kE()?OwlfG0(-nCtVf$1Nv8HTd`8VAf z6kOj8TwXi+65Ke|moBI=AqOTm3We~O;ob$nUxtfAG5lq?nE?39aEAcUm*M!+aPw3N z@CJIXGT`?N_<#YQRxr97`cfM77Vhqi=<0pc-Bz-@)6iV*ZYycc$B|~y<;w2l+y>1Z z3E8)nTEPz^Rf#6BSm#E^|T-So&n(HdF!(^@}K~?73IpIZIIjI;rlVa~t2`ILG$uBzNU&52w zq|0hKcrx2NgfX27@^Ic$+1}>u>FkEcAWwYEWW3t5EzQP|>naZLkUx##{)&ctFc+3r zwkP(vU*f=zN>4a8BPZvo&wZtwP$)J9qf=yCfKAoAkFR|)hpsd(Ie9#oERRqdl6x3}9} zIv|cJ8S<&2iP;GqzXP)18#MF`0m-*xRUn`{0Dl<33;+&*DONfBUerUthx0O2rF>xM z@oayzG-~AoLx+)z4-A#MBPb8&-2{LS3_S>d4-CBmfDa6P3&1;^r>o%AzqG1>j|Fwn z33{1sv`Ro39)}_vC1nUVF_aM1nm{pD zsp@33HL*#o=!$;{o26oOg^*b>RC+totQcFQV$|!a6l052jLAsz;k+%J-#eW5Q8pjW zi@y`kW0KLM?M%;q0BKg954pVjcaY{??mPy5KmaEZZZ$&9mb($Lo_fcrhB6iEeIK&2dglO; zr%5JRWfc?6Gx-NW;KO-mvoF&i^WnU6)P`f(3DG74gYt0R5CD8QuLJ<&aNc4h<>9;x zbf_RSDCix|J76>>fez>04657}qvm#Br38eQBb!-VlZ1|Ef$aDvehPvEf+98*Kn{RX z1WX1{o`B5&Y66&IU5np=sv3DXPY(p!+Mn6D^e z81NAZQ!Z)cGJ~AjKg#ti`@>weY&L)$63=_<_qhW3*2s1V^Zt9AgxSEhO88HzYm0=F z{sR1tgn2Lio-C91`X4Z?_T|0Xs41j-8|=$FV!nv9p+2cidKpeoGPXR5%xv>8BuXNv zff{b1TAG!hURXI(u-Qa{^2!HH3eM__G9{CII@FvqposgBeHIl_a)gv(XYK4#U%|{gkLOg3cL+zNN(jPkMq+E*^iGe z-;%rfb-&1;KTOStH*@~{^261PcpLNQcSM?J#9Mhl@)zB&X2h&qbP*t-Va&{CH5X!ga_Ui%w3kcz#@zd*VCUYc+$e%I$PSBQAdpDK9Y)JcGWJ z``$6hff+Pc&Y*F8y!o!&chIvZtQ=tTXFZ^1(EcnB{t(v^C1KuG4a;?+Gtfw$N#A(T zm`OF8o=M*Wmz+uIV8b$1h^E#>MYP&QFMy3?QE&$^ok{QH=QR{RZF=e6;?byzXWo1O za^~f!HPi|!IwChATKge2wGIWqQ|mEs8dK|f;N{fX9(f8Hjxwg!vPzuPI-Xh|0aZ<{ zT+ITi=22900ffOgE*)+1u&U;DV5pjcGmpp$3I;tI6i)-g>(4pLdF|lT=vZW6sdWOM z=Uy2#lY6xmT%OeW6sC4$iJb%sODq!wc@i6F@kH66_sI7a zBO7=97^tf2>}?(RUg}K_$!2_R$!I0$Bzs#wj#Dc@#(1>?bOOLDz(fGN0&D_66Mw-u z0JIdy6>$jKkuVAJ{BVqtXVPOzo@0SwdA>7N$+Icyapk#%a*{kdBLmB`D)?M^HdL+E zdNvVUo;-63Q>8rL0t?IYJOEFgtxaCYvn#4$c}@kO<#~?eITY=4BQx=6`0bD@&w%>Z~soeY5GxfuY<^A`Xt&#K79^2D8JC*=rL#t7wCcu6@R zPv^1&0?&Z%oX`^nkK*E7JKBDXsx@u2s& z(FSAjdTv6;O-Mwaekv$-0O+`vQb|aC3!or#BEm}qbeV)235ZNajb#9|nt~b$@J~gJ z1Z;W&H4<>?NmN9@)6-Ek0qti5MOy-XcseM$5DAdpCg3nQ0Z#&$O2B>q&jAqaUO^E9)s)J?#eKPyN$-viFpKI_3HyH$FOG zmU_xx2>?Ike*pkL9XKxgF&)H$E{lVr8r3r& zKz#!K0ML|xJD1=f3Vdhl!<%4irP_iM0_;;MWgrM>fRqmPT6}7$v0G4x%1UV z#Ir<9qcoaLA>xz))5Gp=3g#m)Gj-x-JVscl6MSq_Cujq&O_=g`QVP}i6I=Xj=$lwNhiwVlJmVfLEk+3N+)98 zz$q)8h{b@P)`@sLAQWoQI#VK~6Jg{js}t0mi8?`#_}A+MwN1Myo#_q5ZYSj=hdu1K z3cQRutU*Juf1OEt*n){;fynC%k4`?^n@E9;{Ckn+;6|5;6x_&v z5or!^$n-R;N-GrBb<#8|mw@h*_^IM)RVUBqcTbFuUO+W$fc%QWWku#$a`{9jdI+Vm z`$Z+J2e#OK}xE2PxNs*8LbHIA?(?pT5a$+vNO585*NlRp@JY4T9 z6P=E?0g36Vy-`;Fd}QPZ!D6fkRF!s8{&dXN&#W=;y zR;IHe6!JA<6t(|GO>c~*U9FYVQ6|neKzMj8ZPMQuO)-ZY-)@GfInC$aiwtja2GR>v zwBYB)%b*kAlU{5eO}u#r(5kJ%OW(2rPGW83-#(gS8~c!+k?^b8_pYsIbrwc zglNGlP`WyB-rfO_2B2dV{1kkHGV1}5Pa24M^XT%?b0~?oZv9^~wr;I|M6d84sT^&E zuLY46k^=&rOe(fx^FU>N+zmi($3(m97W>6TB{bIDU85t>9JHY|2;vRP>ZmK>nBq)T zCMVXY1j${2aV&R#(^zpm{v{lda`&xLa#!gwNVD9JNVzA!uH=4XG|T-dq*?BgKmTu} zS?)hbxo=yo+#-LS=djxF?3u$|BVf595Tm{o#r1yn#Z9Mw}FKXkC!Cm^!ysRF+I1m4IZ1C~zc8 z<{+d}J_nMqq-4@ID#@sHPo!BgmXyrbNb^i!Ny#{GDalCw{FX?wWNay!w~=Pa#7M~` zzO5t?CneDgX_iC@PZA4A5+xyt$2KWR>;S-$xE=sY;vCBLBr(yHL>weB8DuSqPFqY# ze5EC^-|C84G_Q?yz{=_f>%@QAERwbm$3d&()o^qao}YmTQN#a7My#+CZcnJxZJ}Sx z14qIg2||=F7Scc|q$u?S)>4Ql{CVXbX z7G+37B_-CR1WXDNUIB3;h7w78$KqvST9=3V0}bY&r144Oi3X`nv5W?*&cQL`T!Io_ z22?;$DT2BaluFQD1eGP|UVf-(s=o}j7(JxNe4f@TwxMbKh`Vis5;retZn z;P@lm@%U^ylAhi;IBV~f4(t{74hd&h4=&id=E3%EaD1W zgCYWPC9a0IS~3Ak)H^`>+r-<|JHo7p0l45wy2d-^HYBZ>UcSV2^(^uCI<#nzFL4jx z`1OGA@g)&MOdp>W3IQRKegG+^ubX6QKb5q@#Nzx2mdUk{tG}-T5HhEv!9j>Q+d5uE z5+Acl)x)z6;Y+@BO}w~uwofFkw5U!yNUmdYE)G;O_DzW$PT11V0=s_>csDRM`F*6X znTzzh)-nrui~RTw>GHyjp{&hL#E8UsR(KsMe)t*Wde%xVcbzKX!~a|Y*PT2JoLi}` zPyQpPNNV(Ll1MyiS)l-`7Ac%OtCDt*aN+)o;6Z1FMB-9Q(l2THHfW<{lH~*-S1QM5 zLJD_=i@5xe5Q|7;b1lhPRdZ$#UE&&PTul#`t#QOBt4ifI-sF=t5ijHAFi2vXVnmjR ztfreT(#@*szef`epu?(LM@W8)6+t*3L8PQ9iEDgyQL*YR_rW=FPMx7PG@)5Btww%#7#Ea!rN)NLXXR$`#W#)7~0J;%z-&?3D zXMpZb=m!g-ou={PF+z_mR7gXhml1kuA#``3>5DmuPqV%%0XbuU?)?h5pEJ>s6^i zsxgtFK)?193b0}f(-O{ez<-SwBoae0-^24YY2k?*V6QWf=LO4IulXv*l)&sSi{*+% z_yzFoBfj}oa{xd7QXr@xqU*5EGjftH-IKX$8f~cJe?=xrFk182N-V zSfl$JS%fna=muDl5{DJyUZ>HI7UKRA=)=b#swZMDU|vzW@BFRNGh#*`)Lj*kip}Fi z)n#bO0xdx~H0?BgmBtU^A$tJ$p~U~b!V6~sP!nksPse!1#)>D0+4)&Bl<*g2;6k0| zEmR3*iZMugUZxou6l3sa1Lse0ogvkHx+s@$ZfdD$uNI|oOGRWB82;#nq1^6Q>OxbP zh`a@SC+yY}_ba@Jd;`>i6{zRhST&P+jfkY&7%#pfVvb1^kv!ltNlJH{cx4EWfH<0n zGc=I|#Y(0)4uWF?aXh0r*uI<+H^qxz2|qiQ3`4d@IM)N+X(iAf#ZpPCnKaSaQsgti zu$mY?{|^jj!ElNg4#w7mBV(vNyE`H*u!0ZFbwuKemQ%hJw1^~sR5Ht!^ZMv?0<9O( z&M4YYmg`ucXA$}@-62}+h4UuxrwAV(Fj`KaaBR35ObZsJ@dPc>I)P!#tH@kBV6K1U zYosmIv^oUm6DChlncco9pjzFT6~G4`qk@uD+fhf3^L!ivm?Hz=3v=HwCJSVSC- z^$m!jqr{Q?y2ger>T&2KV^0Gcc@Dg3)cVm+@a(MqjG)N+@3 zMS7`FwGEWXT2JBs@^W9JP%LIyU_*n;%zdN6Q{A>KqAInpjl_%OOlU+;!gR7o{@iYx zo0V1o(i|e)rV1ejNsCMY?I6+mSUw|9ape@1{CC%j7gp>9D|sun6?Y(0>_%%RmI(U} zY7}jQM3`oOa*<=7v|Mqb`;5C*P?uBD?xvrirj0-;<#WgGx->3wED+h zw64J}(q2pwbf<#Y7p&wowCqJ#P^{(KPYq%Y*RHrBACXqQVuiKa8#~oXdja-#AO6LD zXK{x|W3e~vPBw&kWJ|lt+<@w7M;nM%{<;ai-*yZ?RYqZIiHW>YboF0H1=qnaE4_$H-}gZi>Nl6F(aZr99NHH?A#D`LFkzURv+#f)TX(Slm z3_VrZ(zc_t5<$O+^swwFP^a7hQo$n4sp1zs@h>vnq)~2>*0_>iEXKb`87rMIR{;*S z3s|ZELfMtyz;E0+P&!ox=LKdwdIiQN#F%y;n7GK2vdAlN!hvrG8*_YC*+1cG8Wk?2 zsW`qv05?bAU*ugD0<{M-SnqgTT^yNHp&$u76?-5>)W}kiL6pdXP&aImZNk}Hj6^Rs z(6@sD^Fj|4KpUjUZJE^|*?h{~$ytmhy@!P>@?p$u@L94|mG>e?(zxT0cy0LmESk+! zO#Js4h3bU=j@CIjQgOXX_~r1em8{en5qB*{=OO%y?2}j?7iS@OK{pMILTO%G?o&xR6|8v4iqdg4AeOzS9}CDuy}X%!;=D~ zWA!149au3Uw>$Smu@vK9M3_1zh43Esk}L!kOxlShcqivYGz2vyOJ4pk1H}*aVZG+~L2f#-_>z;c5iTA-_*-KO#SdOX?7)m497kHk4^AM2Wf%E* z4fC7a2!{*s=t##8cB5h)KWK>^Etl}2RU|Vfxda(McnX{v%SWs^8{FQ{NOvV zsQ7_Viu0F7-(}`>(y{GV@dKk1P7cs2eqf^S09wTljOv}qK&$wHiGCI6Lh%C@kh2r$ zLh%DeM@|Fn#t+0!&eJLH-11w;dB71Q2apFIuz(a@dH`wbfDe% zfm^z8)&Z~L2Nm&1+o)ND@7(Cc5B6xjiZN}NkBU|CgHhnq@q<&~bK?gdkCTa*f{Gs$ zt;cDsX$8f~c5Vhu#SgrE!nseQ`x{w=GXrQ9KQOsp(db7DaeoA~iXZIQsrxRRV;Vgp z=0`?L3EGGSxbXv)pd6Ykji>klJp`1BA9!ZMrXh#f*`^sv_=_@d zp-%jARYI9!3_J-qeKbRZVhrAF;JgAZ6+b9ak8sXu+N;G%AQKUhYq95d;|JVfnx;gg zGw^QwfIA!+3X~f^U{p1Xk{J_O4L&$<7<;D+~NF9*7a5)}Ng2Rm; zxY>oX6Zk^$1ELAXkDb4YA5cj?IfT?xTZ+6l7*zb=$_!hQL*4$&$soEL#t@dKk_1PbT8rUe5d+_(S}IZt|V zrK{xs47$g0ftuJ`sJOrp9CWll#+b4slw3r^;z#vehLv=LJn0 z;PV78>)>*n8u%h4xAop)3|vBlJ~YV;)3FhE^;I|(@kvPXdQ;QvA|(rFsiu`TX~ZU+ zsz+76x@=IYOqQYZsHQbD^U*NKv4{kIh-I%hH4oc5o?ar|fg%SwwW~teWD$5E1bj=H zNygZ%4FwG!!}ZEbN&a?$fgS{OjaQ-Nv(1`itF~*}^V|xl>b9hnKOQS?U4wittKN{> zD%wcUeqWEOw%KQHcZW~rJD_PF*uOB%$kzy8z@lAb>Os2!N;4&t`RR2ywo6)euQN@v z9X8n-ap%7SjW&p>r%alx`nr>fcGkXui#MvC2HGKf-ZS-gqdUSm1N6-0Kwm0^ZjY~$ zOJvB=>1Ay*F=yoPL^07wWj14WD4`mXOtFVL~*$?*HHJ&>b84o;#7E%Wm!n4;g zy%)}uU5#xF?-{p!pPU7bFjlveM?Ef)RvsAI6sEuvq88#4?)c$jZE4l0lzJ&3&KcS!B>1Wp`_<4Y!nJ8Xlk`7Q65mZ_B1g}7f@CYPy{wuR6y zV&$S`Dy6-FmL~7a0iKqrlujmX9f>}(BYw!EOZnUx{jw5q7auK9N&$Ex2#Yw=Lh^Hhc@NzVtmf_Rcd4g7pEwG>r>vB2VsK^%}9Nh}yTg8Y<7cYToZv)2` z)f5&57eP%EP6Whi?}6ccmcLmC^~l&N(XR4l^B=qnFER?iiOKE|VCxB@yn9|&GCVm<#_J0PrQ?dFvqjMHS+Eb?7Wz!b2 zP^T|`u4rRT+HX5iVcOSwp(tM<-v--IBI!5$0zA_;nKbD)T-=ARX~EY^*<#Z6P$x3) zhPQW$Xy18`zb0J~A0qI2ou7cacUMKl-3x@zR z4i07WJ7YyA6-Xhhl)a)vjdqw<{cV7@LZ@OYOvn5tN|hnk(@t7?2VOBPAMk~KfbSw? zvVuxVSLO;X1s<*;+uYvBS|vaWiZ67ETpyB|P4;a6N~MJ>)R(3m`X@F#6fn7HArXkY zh@8J;eGS#sHT^;S&VW9#q7J$mx;8+rlq^*^^?_n^qrjJp=C)ozc>lj-rbWe}N?KY% z=VHT4dkOK&aKPa}Sc@?9b8NT*d~#aiL%u+`GGJQEL$LujIvP438~zK*JU%j_OA~JBQjBvA{?g1H3i&A@ zZSdIwqL$HX=Y-}eZE^)&hOqX(LziPBUto}@+=e2{poP>I`weEqkBH0$p(Blag+fFs zNU#Om+R9AC< zuF(zrZyMZvd*XIj{0m*@CqG_u|E!d}%8KbL_OJXN^iXh9W- zy8f#{vO--d`OCIfHBt+W8W(ce)4;B3WJ76fs@T(mbO5K*lpd{|-#skpLMr_ZD)TjEkSv1siMp3!RQq8MCO2 z_#+y5ZaN|7FtRSn7><9TUq^YI4{GGaK`y7;1XR2XRmFw&Ra}U_Da3I=WDqWNC{%_@ zm5Hx7VG{%C-!M$vJV>;x7=!cy(UZTv-5n&}%YMq(n#iLDiRNGXTf!RpM@1DGq;meU zyxe@?iHf01n9Aj2lO&>}L9Y#=22JuM-*%Ubw1wvT{ze5M8=)CHj^Z=np*>`vEi}&; zu8S#>XX`n>_B&t;0C~ zkLxjaUUzxIAPiFIZL3}<00q>9{UnFQh5ISjz@*|O;2|0Aiic4kwtyZWfHIyS( z$@4&`09R0Zs%u&^L%1KIi-GemdAKMke*CYKe zOPy5?mA*NWDowPV`a^O1_I+q{6?-lOiAWIaC&UpWk-+DiWS9wC{OiAmo0kkY5h954;NMtx1&I!a+{#e_BhBb6`hgNJ2U zG<3B>ld}Db!&sIc;-a-<$53mh1d{I_9V;G0BJ>n{pP|jvwjDe??kG+R{L6Z!tT`qZ zu@5WsU7*y=CTOLdI&}gX_G=(ij+}j&`c0=&ST$5=x`>sM(k@J3#3_-V#QGW3niE= zX_J7uKxoHACzqTogSDa3acy)%T(>0r+H#lc=f3HY%~k>!Th4)=W0OenGTNiW5y zEQ^dRWhqPYVSJvC9t6WDEmB(YyRnM2!k0-E)p9Gk!U(*Js_B5@|I#OIg-;i-OSY^9 zjYmiP@DolwFzNrxO0`S&d?~6FF4i>{;aB^6F4-!4=}Ng|=g>sv zuz1zHpXoyE~@SqH#8#lavl|bP<>Ae?5%aCHn;zGO|nd6|QYFU9!>Cw#n3FZxl_J?0?-LbAuK0K^1Bh zT(W9dlnj^b8)}d1l2OV&>Y?D0G3qR#lAo*?&@S0|Aebb=Q=tj;q?TN=zcq(1?jmvc zK1aT^dn(}`U*(cl6?mj?UH#cX!6hTQ;gaoS0ob4_muwRd_8!KL1Xj6Z?-TYAVGWmz ziYn@oWwwHL@5?3ap7t_T370IKi+rVW+fv0|5c>RHq&=66l5(}bjGh}0+7A(*Gi+&~ za1i<;@zYy&c4BM%_`U#FcnNCaa3_M$7XWLQZ1OV0CF7a`#P2+|+;z#Q8efP?70&%D zT$k)5qq(i=^a?9als`-=>XO|yMFs9#gY+K)_p2cQir0s!936z7HPv&;s95ciwT*f% zSqH#Za>;6T^jxyKfIXM&k3}T<=6)T7&d5Wz+#q!NlL0=V73%D710jXN)afv_oP*FE z{n7{Pj>v2UBFSVAmAuj*;dK*~$wBBoei{TH7s}&f1fje7oi)<~(j^Hd-^RmsvBwh-S3q9F9sDhMshz78YC=x0qz;ta!t|N$x82q_l%_Sf8GEXloAxt^&<;?k1ueckm;t58LC-HNWDh~J~? z!k+2>WfF9sUh3J;cTS1>)D9=`O(9GoALf>zTgmX88n=%69;~+A}>0SbL_ozvFqP z)DU|qmWqE-CL(LjTQI$yn`!Ot@)5}dp6UAc3wx%+sjq22f8cqhk5b#DXIkS!&ogB- z&*uN$Flx{A=})M&2o^>^F6^0(qqa?>CVQg@&$ReL{x2wV%s*dJtKgY#?SKY&!NMcd z9@jIalzqZO!82vlFN8{dd%x?MUI2ngBD@lspgq%$2NZ`d?lN)2?nAz`6ToWEl#44# z=y1{#o@YAdpy!!-ENSHrd7i09J`czDp(o+-E0Q|Ny4|7V`*hJ~JIO2ul= z^mG@`GyNIxl|0jr@c3CDkJt^^^GqKaN}~Typ6P||aoRIIilGS|XRW=WXZkadJkOMp zR~jV5S9`>1&y)rMPyLCN@8{qL#k^mDXF9uQTw%}DO zojuRA>VP=UGiAm;q#M#R4GoO*JX4QIMTy8?AaV?uJX7vle;)rGgW?K%rj$`Qv+hx7 z?U}N4oZAP-74}Recl99(tvyr8eHQ3Ko~h)1^InD4o+)$xHf(3xxn+! z+CihWf94;hvMlm>S>{rfddW7>-!j@Bi9A>pp|J z4FBx=ThP>hxl-+)4V^}n!av(OK2Aptze3M_q3`f3!oSS){Ig?^$LYvnP0UTqVIO0* zTOoe!pWO*q`)9i+t1Q{}9d4F;0I7UK!K?kVM*wU8Z1q%?50OJ^h`kd6{}*K4&*Js6DQKMk%|u zhk}2`s6m8E{_Mp#9XT8d1d~K~4>UphX9HeR9KN^_#4(2QrTLe}x&9d!_c)=$^>Lk{ zjvOumi;f(6ENLy4#kr9~51srS(8@oXq8p-CBr|e2YI&UNpK)%(KciM(!9TOmMfT5# zZunK_B~E>xd11ukO)e;of6;T+IE z-4G*6#9HP2+ipQo$$LuG?2dBniWkrL#JQai%05wX>Z3`5-WW^XAD8+eKE#|{*9!GR zUYpK$35m*5s1bxpZg#VLXC?VTiw}k|_i8FR`8Q1(Z;(zADeVO`fnHxpUZx78yds^N zaeJIC-&*SnKveVlP>PkjIpapZEt202bt1-$mXz405=?oI6Lwc3$M5f~8nwMQ(guZV zSc}a3Uff0ikn;mnLsE%2HnZB0hDfLG-T)|l41k*egb5&#CzZr_e}0}G-q%JaisU1i zaK0%z9|1aFCI23rUb9N~v?|o=fp#XZL6TIYbZ_~-+S_234|@4*x2Y&IIp_V1nh2PI zX#~*eW>Ot!QzOJwtngx1llLQjVew%+QngGPRcc3g30}ybIS_of>_GHHE4<4Nn$r0c z_p$>@*)0iGqYh4O$;%GfA#H^`l6%i7&0 zAtp8JMWjBche_iN(l8>WeGHOTN6tZcrDRzhsSQdUccTJB9q%DVt&TFG)R7YQeMF95 zr5m;VVWdMIg~yK7k!n!t7(ipJB)_MQRyuXJusRZk)hd?O)d!1bA#oJeM8bGkE)FYJ z%bH#)3mqkAr6-Kel2r{kYWKwvwQ4bcjibRGT&m9PXtt+6zo7N4v`8MFZ&qo{aGhjDF`2HRe;npdLJF7b}Qtp5< z<4%ml{fpg+G5mAL&%G0aQg#P$+Yb^nj((;QN2dR7_f8BtucGe6cxRw{C&u#wirtC9 zr9DU4-8(TDwTMu%PTYyXD6Yi46T{6YD|he2aC4jZBdQ2`LVd-yyLV!6cJ7@~9qz>N z@Z4)AdUs+l)hpbf(w!JZs9pii!Qla(4sa*NQgm3cvN)V;?pL(ZCXMCdOxLuECXJuJ zJ7PpY--$64qhy6vk|>=!fi83>hD2`zny#+Hofy<>&0S$+K;MaBq8|lX-HFkrk8ZEX z95+b%`M49~OU=>F8ps@6P3BT?koS)}F&aJ)(05`O9L_U@mUm(pMLXv-x{q0&llNdi z--%%svJ_}_C&o{1`)uM6nSTzIFGAr?j0O)Ww%09#?RAn<=81dcRugw(%mN!7aKN1y zP5SEI+HW!2S(K*l#2BU6-m<)wbET5k`AIXh^gRXzRHM9w%ZUt=a}4gpX#cP(r;W+> z5s%&~O&j1VS_hZoGGtiwFu14av_(uc!PK+WY3+Gc!D{mV#0)=z) zXqB%n8b9gk0-CxL!_#*~`x-QLCx$b^9X^?_ z>*!FVgdxEC!#4u>G>bErQ ztbLG+H>!?29?*AUc-_G}jXSUou|5Q)VS>fVXL zc-gJpZYlDg+H5G@}IkJq(2qJP58riVmQzYz7yjlP;@L=-HAa$PrZEaCk(Qqe* zN0aZi7Gwq7J2AKw?wuISd4=~yWe~mriWixr14Zt{@G7{$Z9!%%W}PB;Vie)y*2rrk z=uQl7icHd-7|cwP_|JD@aD!wHx)XzQw4g>x9NmfGR%zUc;quu=0dyyZ%Pa}rofu4D zW{IOaF&O8yuQl~tN{Gy*=$#nM&3@RGvN*dMNS6wCVsu17W?!5)u2HlF_$ajPacq+#Je*skfn=1aT(@c}uct5!Pob=}wG3jTB2+AGu2w zYpHOLT+*EwZLgPe9qz<1N^$BnR_MxRPA4@RXj~kIJ28v`9nnNiintTQL>~v5JVD%v zLBdnjJD=Pj{YLjr47OcoZBsN>-ibk8z2;t;BmG9)iD4G4`KX_3vs zavFC~v>AqSC|VVKgO8jf+=)?C$WEw0IzqS;Lpn)ZpDfegS<&YBq?5$cucQTTk;m0= zCkB=2lT$NIzrrcqMbQ?UG|FecJA_7--Y8LbVwCI}(05|o4hB^Y70Hd48Jxha0evS1 zRdHpm$YpT3cVciqxEyX&B-Ab7-HB0{sC2PP_kg|=LpH_ZqBLIA?}2qs-ibl-_ZgEM z^~VhkV51d`A!Te&V24Cofx!*RE5e;_Z_TgV@;a86QjcrD2loh!)>GT8@k`CXt)!@ zqe;J^|ImPYCx%BGK%Kbaof!Y?BjTAM6=_etn0;9K} z0wXXwoEUXrR3=nlloIxXM2@ej8?}8L(jkxH#p$UA6&O81H5881Q+EpoM$I@q-l#>_ ziew>i6b_7#RU^FJQY~h61=*8Jg?qBDP){gj(yAH zX$&54yxmIkAVwTsbG_baD#7G6_vyz9bdk`ZPHEEqy z9Acy?Tv{!{RE)HSb4$t?X$@)0LG+&T40W{dCN_Rx(_cXG6$C63EL~HjlvJzV+ zPl85QLB^|B>>GSNM#;%p!>){WJ0>eVMylZ#0Gk*oTkUHPEYI>|q&B<_u!)hLd7fWi z6?!#Z8U~Bi$p_;iM<956C?c=8fM>MOCws{2e6KjTCSsi`f$?r7ro@zEI&qS zJIU;u<;O_#&iCsVriO|&xgv;>KIf}F;#g|y*iW(Amj*G?!Tt239Eg!lNO^l!)N=SxN$KxRI?26 z6aC0nn0}Cgcqm*}VLUKK8q7!)?NXWL$4F~<#y+#YtV!6Ck;P8N1C3n=IiQSB>BDI0 zAS3H-+i@85SQPGrLJ%WmWmMtR!C9#osnn0NUPXTgZepaftqFShkSsq&dbI^dkIV97 zq*je}t#0vUw@EGZR1a%etD#wbj5IahjqFj#OpLVSf?)WxUEhR}Z3%Y~8K=9k+Xk75 zk-iJm?xEO!gMt|8*kMNP)3BxXp)~$0$V`mXlIfz)7;a>H!k>zJtLS}@nSFy(&B6X{ z=yMYzwc+9sS$>Q(1L9h~dz9%IY0Z+NCyp|*9tYd)fXu{5YZe_nwJIw;Mk*^+ z^e@0^F;amG7o2Ed#zKJLW(OIb&so>JE!ux;+G13&CdN%I7_e_kGk3~w1l((!!oZ4=ioqdcq)}RM-{8kTNso~hq3kd#pz?nGG(AR2 zk;*IlJcyCD0FYBkG{(xC7-{D(f*2|Nh(ee(Q4L4#NX1BLCj}YVk}p#+Qt_F$erFIP zZBIv1HE|T)hvzgd9j-|}IM^uRAhr8vaPB}ZndD%gc1l$TD7kz!LBSqBj#wY)@QzZ`Mkz}J55pCCqRYk%`^5F@qWOr=j#h>@mXeaJ^k9DSNXjMS2iX4lInX8C|M z_6_b9(r2vtqe47EnF&A(Rd4|P?8iuda`ic-{jg1VJs8nCS?MuSfeXv(8kjLs znTsYyT2EgjAx4^-MPccz=qWiyw%D38Ms`tDUnC($TCPr7iIY|QWkM&t-{*HS*aMQv_t$zr3wc%&Pv5d(}iX(E@+bF$4GTmQd-R8 z)sv=KevFj;A4;9qq?%zCWPD}CviumSr78;S0#U`rL?u~%j8u1`lqfM$-OCp@Hwt0# zYf6+DsaANbg;B@|TjfZzS!Ywu{+9Z>9x+mD;&2gB(IZ~2# zC0|l%WUXyG`V5QX!lw??_X-jtWy4hAn{D+)m&8be-c`|^?Jz-gjFk6hrkvAgQ_vkJ zNblBM`EIw7->*P zbKUS;7b8QAG$qs54egH33Sy)w*;#Ca9V7k!?PbN7zuy32q|LqI3lO_199-1&B3!1b zya=*KSBBF4_!BQb8oJ`+o&+ z8>0R-OxPX&JAm8VyX|h6@EPl6(m8{WwV$zm4d(hiM>!7cd9idQEoTWN&scL_)O^PJ z)rX*z79Zw>lrSfo8pMY;u7w`r!%2ixtoZQY_mK_a!_0+;5h`7@PIqPP#bc0na#Ero zsw%ef^1qG`-}OC?c|F5h#w#Bw8*btm>Me9 z>-Hc%+^@i>J>pnuW$dR|yPJdf@CQ&c&(O|EdFv)>N5Gqj58qMWs6A?}3Zue!qZ95Kw9*e>o8%I*{ zVOB;JwrCPb#fPPSob}jG2e^q3udpU)ylKRb4?keR9{@Jb&{{RtwMsTKvfHE{rOlGqkDsZe;Uf5kEdW;?7|Bv|YmzBij-_QDmI%#%>K{CO$j_sNF-cW~D&oh7Q?QIG z9)Ez$#D^`JuE7zl&1%rVz2mx|fmBnm;W&&;eE1n(t;Bs<)TE+X?FOis`0&6sW?g7? zkXrO3%5;3VW=YXWrAF4{V7on#nfP$cqNC>@7DrNyUc+mxdL-3OtApr|?vKIKK6N#)tjaa8-=&I1j2Fk@)bW2u{|B4|g7h{&jNC z#|#2F;{+l5MhRJ2Mbfm}i69amUW8*y;=|4Hq^|W0El<@FAHE7FYWo@5i4-tCd^`-S z_^=opGCtgq7K{)7c0b;jT!7$(`L5hDlpSUTR9@%RMr59$rAXzS^dK%m7Q$exvm8Lq zN}@4V-o%G5dPu+Bif3r)M-;-WiE4P)!}^U@K0`}8Dagont}!w^Ln}V>YCW3eKSO&T z9ZA*1QOw`C0rBDXk7fDK&<0wnVa3|4;2Bye=^+-U|=1RVw?jt;=`!|o(^gdtHi2PBR*V1uSR@Ws*;Kii!yuSf5(TVLaF$$ zSUk^4rsBgvkyd;-&bHe0*FAKo_^@cpMc$!IqFtZT zKda*z+PC4zR7Khn9s0D9{bkEI)_DKu86(RGS$1-{m5L9uY*o1US^YDoJVPthp@oXx z|D1^`7KV7WWF}@oH4Z;sIWa!GX_HYY4)Joyky)w=E{2L9AO7fh6LV~4dx`FO!N4tS z%c%R3i9)tXgBx!)0myb~aOW-hNdY`V%g!^!M+d&FpDPHSp_OAdI_VWuR>y~VRqtzG z`l^1e0MF3cPL{u>f6c`+w7ebgwKu%3f5yZ!w6^w#TlLSFc!t)754;h?hf}aV;rba9UngGZPUf0LOem42|x=~a6S6jj}ISs*L3K(gY=@&_l=K9A)dW-TXZ!F z?t~9NKK$u6;J{=WiQh99p_z*%dxH3|u1ZRac@-W1QxG3!|A+L7C}pr+ zVHRY3-Mu%64_m6D5U8r?_df^mVck(uqQr-FFE{@+h!0x|5+BwIV}1+b!&W&`CDvK0 zq@t^S58}ht#MzBDU?AU+(_(Ofq~GK~!J;gn2YH}uPj1o7dN?0Yuikn!RFuQyAH z(V_ngt=ncYuB8xyt-k{09~^?^RjeI?ZLGLQ;u(IKjh;FCn zybVbsns15Trl{e&C+kxxL$G2&TPp<1I+ze_6a`oz*nBGbAy}O;Ay{U@4JnSSpJ+;c zsX6jFDM=~>%Mwfo_HUMu{tPXf`+tRCo1*?TOxPX&I|SR!cH*pDKq^q&#RuP;sMmqdTwli(t1%^AMo!mW6Vx&ZZ7^%7fp~x>5FcjJJPTi7Y zaA;aB>B4Crw1l}Z_nT3r$KB<(ggebRIVn-l60wzfOUJPRevI_a7qI}KM8rtHn4r{F zv=PtH{{1DwqvwBx#Q7H$t5OkEtZi9Dx_E1P#TN4ZJg69R;iZI1$3tH~rhGf{PEJY` zR7`A(4!o*IRK;$5NvS?Ct5w!+^-&T0zEao~WfnbJ^aoU0-xk8lB5?J|Vr-|fAx5nC zx2`IBJQlr6sYh-Hx?U9w+pbiXBBip!PP@rHBdT4v7jE3W5f8Z7V&QTpui}1JO~mzD z#ztol%)(2cA8z_OYFw}YEIno{bPE24jJF*bS2=m-_$DvcFbTJ%UBgw7-$s}3Ioh2# z7N2<^L&o@F#-Gl57Iy>6&^to&W;5eKN3|=%YhKO0OCCnMic6e^qaSqD{YT}f;lHNc0Ru|9o9n6?b=d!ySH+&LxrEv+{O9o^>Be z7%E@e5|PUDP$uI~#V0!H2ByIFkafI1q>86FYv@oC%j;0c7ysa?;%SGLS3@q%J=c=6 zLg8jBQOmrgkUxe0;@J*?@GH_AY`~hyjw){HlzGG_urw`@kyxm3p1~}#mei$rdw>mOd$(r3t6;8$l@iRQnutpA=iB@WU2ER z!DWR)t}hdE!yq9yjump#X+myZCghg<-IW$Zh`!xjp}LdRfs*$eqUuxoaFq53k|; zda7B^GuG=NRy}7LF01FohRf-BIXKS8!k&u_R}6P6XNjMC?h$g|W+AJ;5%N&x7c6m2 z6Csaw74q1LLe@?bvhFe=>u(kE_@hELye#C2e}rtTyMtbyEEV!pUm;JA6Y|VeLY`eA zWYZ=gFMKHE#b1TIRPRfgZ*D7OOMf9Rj}r3A3?Z*B67t$=A+NtIWb4O5-uOkxn^`;Q z<*g<{-tH{qol1~iv0Bc_LTfwogw}EH5!%RMeR{>3IP9EWv6#bd=@o0?utR#q+8Dc1 zV|SR?bvvxXD=_bNSlQ=7Ivx;mMD8wvo!baGvXhW5y@VW9A*Ac^Lb{zMr2A|kJ+2qh zYqgMLo)^-4tB^iBg&g~rkiPZ4VhR0Q3K>u)B;H*}MSmd!6G8@^B4qGILWW!?WaxcD z63>zxe&nk{y1XgmsIN%M%6}KqJL7BS`ZN%7Y#Skcy9()7DWv~sAp=eq62C}D#kE2z zmkSxVM#!K|LQZ&xTywUN1(yoB_Ie=; zR|#3PN62FDTY6biEabYwge*N;$g)Zy*N+i$!`VV^nlI$$TZP=RLC9_I30d*8kh}g9 zva;59bbWV;kbBC6+&fgrs;NTmyG+OfHwsz3R>J*6CqQ}gq%K7 z$Qji_&b&g%Su2E0dtAu$H-uFGCgkjTKhVpJwnAnO5Hf3ukaNx#a_$Nt=RGRq;-`gN z@|uv@p9z`syO6mVKhoK}LLrxy3YmY5kjn-OxjZT4igScqd83f4)(E-!bs-D330e59 zkVXFqS=?w3T`%b<w1ro89z~WLIWXH zZG?>ODr8Khkdwv>89QCbxVb{cUngY3N+A>137NE6NOGHylfM-*`ClQY)Z5E~rZf|B zYDbb|hW8ONdAN}Cl0vSTDddi;g{-|*$d(6%Y=1_`k8gtXIz~BP2+ebT7TU(i{F!)n zr?Jo>PA8!goW4S5I3tA4cBTrw+nFPDgR?~FYtCIlKXcX!{n>d*XsP>w(8JsvLJxO; z5Zd1TM`#DP?k_C2quW&I5pJ2#PHu0ZN4mp=c5x>OJ<6RSw5vN`XgBwIq21kkh4yqe z2<_#*A@mq`m(bqs-$MJiwSHxJ$GXKr`?-e;?eF#yI>0?nXoWjoXr(({=s03mxWuDs;H}o6r$%t>0MQNVm1n6Wn8kR=MMZp6JdJI@(9wpU_Ee!SD2YvfEbZWVff#Q{3Z(p6X5zdYW4;bgDZ~=$Y

N2J+#N!1asL#0t6T3+mUEliO6YR8 zr_dE{mC!rfnL_V!7YkkK-X-*Icb(9C-7P{_xgQC=&)qHb0rwxFtKIy+=>I{ttHRYD(erwM(`y2lv#%a3{g?24A@p^RBtPsm1?O z=BWX<3Emr&_v(E{;dW)f@-T0!Rl((Oc*G#Q>^m;f+{*{!)H{%QtX#dzeK}(a1#~OX z3_R$5%p54K$Nzw5#H}N0_jmBHI}+4p?ZQ3#sdwVptWKV(me$kNGQ3plSzX;5jzkro zm8z*@`r^Ig*YIDMRrniD&`xl}RsQG%k0^tVm+uhv3bX?QUkD)=TgZE5x z=Bqk*8!4!)Jm%{m5!LxPIDNSRpVUh^E&30Az>ii1H{`mQmm55j<(Oh#X&`aVz6u|N z=3kBj4`=*7)VN$NF8ek9si)jQVf?x;BCqsP)65Kj6zkN0p6m zm_Ix|2g1Do;%&hE1*Rg7;`2>`EVl3^ry%|%d=7&^RqRJvm@baQE5E6&A`y651SS_u zWn(0&;t>~j#J2Jlr#Susbe@Dj4Y;PEqo%PYTbxMz{O@Y3^71KmNA1I+;4lz??~)^O#(UWMBr8y;R&^E8YX*V&vodP*zK-bY#*K$)I=Pz8{#u zrKsZZR^=)_&WI2HzP9SbhFk`w2iq_>j&zi*_DM$k2}p-g?FTTUsWxyET$YVQ|Lw?# zpS-)a+Jb!i0Wj}^sr($tfIl-FH6AL33((x3A^I0U{HPyltL#iL7lEk{rs8HeoMB4D z(5b=+X!;9~u3(Y-z^rDGL$<2~+faPW zkG0hc^!+@T*TD?Fz|xXQ@JT3M3gLWeEd+Bd7+utjR#AnY){p-VsV<7`xHU~0s$>)N z-+=$nCyUq}YZ}yv-?0ZXs0hwSgUJOm$k|(4H32i=2k5;;y?t(BybZ*^08j(UAX6s* z{=*H$C;n7hb)$I^m}AMT0&^Ug%F#$F2BJ?^nyO^6OZz*`;@`m62u?)I)E`iwPlQmqM-4tV z+fgn8E&LPPAKc2hz$&jsGI(%J>CchM;lSe0!NWMJO+`{sQbR4{eWy-kJL>%ky(6ht zjzs>3o&}O+N(`2_gI6Min1(^~g^mt_UYWNcs1kC#XMrS&HYk-L9Ft+Hwyyo@$T(;G z`;St?$0PU%JJraGgv*9yLV$U4&H=2PMwi{+$SaB0c?Q!7c*Th|gmrg0nepvU*H%*~ z?O9XW7}9$o9SFhTW;La=L-839wg)bM+078uZ0uds31^o&M>M^M$5Z5{j(E;zX-L(X zz_W#pDrbET@KSWdA|-Q)Z`0 zwkHa0g-B$bvze7M69ccs3`;lm)=QPn2~Mc7@i;#)>R$)@3BQJVGGJV%du;4>9hk0D z9y=WxjIY<}7Mle012nBpZ@B7$LfE=zirKoqP=;>Z;>KuQ&g%fPD$xehx*`B!ChGWw zK&{s8Mb>Iv0!^`6w-Q;abw46&wT@*;>o{{7d*h@^=g5YJ^4q|v+*jOc^*ho;nVX!AY|J)+{8o!XY34k? z)u%o!<4wgGU{!2os?}cuHLX6)HyD3&%HVD>*bOby>b+o1tKWcuZnZ8!s$#XeBP#B< zT4Yo+t-cX5yVX13R_{^HV;6I9|L^}Vb8y1j(DUaYGiDAB{3UG;idtl;59&EMnYNM7 z0O~m?UnAF=kD^=wXUW&dMKjoa2y?J8HW#u-6RK*&N%OUqi zLu6Dlqwzju_Gqwn`s4008m--jxEqo+2bW3{{W-{7_$Gn;R*ORE?T!6b|0s>Pi;90r zBlr<{)9O_~O{+7T7=!Umo@1-UpcJf%JqRt+>PNwvR!@h4o`bpssfyL=?U4Je78%t{ zs|TP_cB@&K3ifBh9Q=u|s$m_x=}HJ>9ef;|wGJk5e-_L^X3QMC9Pi6n>!7Gb_W7Wm zgCl7hnT&VE^c<8Ap=!<9C|A!x`4FmT25&fF4zA~0RMu#8eIKrZImleNmq7k#h(hVS zNBz;bU=uqxPQ}Z>su&A5qrrFK%xL`T8;oC_GI(4JSTQpid|SBu! zgWMktkx|WzMjVZ@M}xIfcB{MK{U^KCH%b%zImlf2Hi7(Bi$dv?xBXU6f1a(rmx>pH zRWW|Q*0g#xP}Ax^e1q|KrVJhwgGZocTD=~uY4zpr_^s9@NL8#>*MB$FYLQXRwE8~C z>{hdODtHGBbFknPJgf76%|W#d7XCWOjG2QcO~|t6pr}RO@5c!C6T@M=D#V$H#|bQR1&=E6@14?|tCLs?CpTsk*ZVlA5 z`gPx6d@E=8)mADtN{Q zW8IpM%UEN53Ic1Xv1TrOx@=^|1dK46cVq`3B>Q zH?!4Z&>F0Y&4#VN-hef&z6J(*_17gxRjgJ&3%TEFkx|XGdLLx=ShFw{+#4Nzcx6PL zjsM6Z9f4%vvC+)7c#7jHD&~kgHX|%~RmW@EBciez=7dMQbZbaa(l9TqLiOH4u3^)# zlhYYDP}uIA+2$r2?n*5B-qCnK2#*9cEDPssVZ)ClT=3JKdOkEP4oAD->7jX4=^XB4 zsr(HU&Yp&i!_o7hvg#B^H9R^z81|;X=+i!YO!yh;Rn|j)b1SO4Mbr;8>6>P9tPc-7 z*yJ+E_ySbJp;lePn@}fJ;32@sXO|i_3P)dsUdbHj9dEhTdeJ)FBdQB-HyVyI{@Gq5 zOF-6#c4H22eyYM7KxHGLR7ZB@hw!LKM&wYv@D)YvP-qdvTY zZH+ps$VGT?N#DWpVWsdL?EkE%0Gd142UtNS>iB&?tvlH6tMN%4-hu1;^V!H+cd*YO zYu&;Afvj~0>pvJ(JP?j!e5Q&IQq}1h<3m>*);irAdxztJDW}dk5km9F*vLU7xol$6%z0R<9Di}?rJO*bx2lwO|8AwLDOA&2<%gM?qnfi{a?n3}3E2>Hk z49-x~qu_I!mHg)Oc}JIohTt}7EAWD$C0RaSe^f~>cz)e1tHJn^x;|exrKAWvpEk{E zIIW~vT~Ae!FFLnm9e!l^5z{BD(d?2XKV@jXctgoD@XkcwjrX2#BX)=oohEIZ6JDyT zRLgT9Xgc0G;oFn4RKEqtG`rDJ9*$6z_^BAJx?&@^PuMha9=Qai9=~aqA$sIuoVc9& zk)B>QVg#c+#&!|~U^9ecA|LoQ4;mIQlJFG*8W}e_i5^sw;)!1o-XppWXyP++)T|P9CLXcG^o>Xkh!k9vDA&S>WQgwqa3_XaAq}@>LQZ*PGv~}k z05{7!3cS$}HLWo?9aY}gbRgwYdAD>%4K9W}!#xt*732hyEIIF1V*DtGSBEOhCe{#> zECmU2-iyROCpU|F%qBi0CRqv+5)+Pz2olxA zs8YowA<1RLo`p&k6OSt187zJ|1;X(YY~Dl63db5Iq%F@A<0l}zMn?f-Ht_*5$x@IY z=M{8B@)HHZEkiazF7Y;{t7%&Yv5<^U!BsIy6f-N*R^+JS@l%0`Bbg=Vk@GGd3#@{e za7^&XA|}fMob_DSTYfZ@PNiHpepxVaF0;Zh@oEvfh8Vdj$x70t8>9tD68BSjDzj_J zm39Xw$qUSGLpHIM+yM&sk-Eeu%#!oSC4wGIup7N+#smA0D#9`Gmi7de_ZBeWn0ROO z0M?oqxhl!NOsqRGavr6gL*6!a^gW^50ruvm8Y0}uPw6dTrZopUw1(EeF~PB0pqHf*u`wT zDY!l4hLih~+*op< zL%p{t6^`3ndtWds94nHLdhxqK-d_|5cR8{NatVHm%H!vR5)IygbUL^yCW%(einNRz zRXlF^oj8VBavnL4->OLrCnlUEuN(`(DkO>1DLBCFEOPu(ktfM~W>4z}m4)OMg7dgB zcj9(t$$8`wL5mV>mUqo8V4J8S922kg0ATME6OM_;?+7KnBSx-DvZIOpLyVk9skc-( zCj63-*XUhH9|D)S;WT8)c^OmTK(MZq@`EQ;FCj@#IWd?RKWmZ@l`+inD{>ycrBual z1|+5td+cmrJh>+>VRj6;E6JTg?mBYS=;t@-%r=b4H5d4%x_9bTLGs`4# z;VIxKO?*ZHv);Gl;#UIug&ePLyk-NDr67^<9x%y@3OTQcSV09iCJFA*l)>j3($3_l;JJi!^ZpG2tYcGz5Y^ND|X1xSrYb z$&EY?oFrE=%N=PG*O4m)=QVjA**lpf=aEYUEl;rd-s)?By+jq^n0T8Kz&;`-921ZG z#3p_uMy^V-zY}vl07lNE)N4;=Zhz}>r&_NmrQBCH@g%e4yu)V0fnYr;-Nfv7ND@>| zB#7;t15Q-NGh6#om~pS%D((rFm_ckCIFHw{iFwR&x9Y?Ka@?RgaRWJS$ey@^9QCS1 znTba%v5|sq=R?3<$rGdmFOC z@$E3L{tDPOAtoFXkAlPz#K=`iR+Nc(&PXIfDHV=yNO|L!6^;cZq+D(};hjr?aBGoG zkV|kI6OTJlB(A6Q0dQ4J5_dBz(uc`W#pAnTiD#H4=aKU=?f~`zF=iMr%o0q60Zu0&&I$$8`wL5mV>miHD*E2oNZOgw%CK5;xT z;h1>bf+8`67`ZCRE+cj!F>)TI-W%ka(}J5|csEnZEjtn)GfU2^ydDk&+dwJbm9L82 z02L}HUMI#k;uG48S#Ch&aT|^*zHXZMiP#_DJl-`W{$-XM;UuyUTgu?xH;G(w-0LY( zOpbb0qRhl2mN=4v6Bj|i4UZCinSF&>CW+^kfTJ{V5(UgAw$+9$-%LwPCq~XAmymnV z`NYU2$a#EHA#oEi;Urnbtay1o8}6ATo+2h36K?>qw}?GX6=ti*C75^}ne3sIT;fl1 zSJZ-vWY;=WL6V4Whv0}1xJKk=l50th(kfA5;xVL^=tTh|ZeE<6U`#Uit-&2ZmPf=F3C^ckKStD%i%NXIzE`Z0)plrgala$Sb6s$jjctp zYaQMI^YBUYm+PqyTXZaWv44itr9~%IvJhsBytL?&RdTD(AC*&bpU)p%Sn{~fcWqX( z+2^~pDS6N5yO))G>GM5~F8RsldzP2%_xbX8Nd)zfvU(3KY3TEPMwPSzU-T*J(06=E zH}EaU_n%VI8$A20MSNOGh0j;aC`o`XrB3C!B`1ULOn&g}lIh^PlOHm-WH$IdNxU=D@sNHA5Fe$QOTX)CzBt2W649{r;#7CqT~tiQiqdPm23fD&N_@;Q}Q18 z^Qkj#L&?^DrVqzISMo9N`NSu_i1QzqvJOBzc72TRg`R|5%NsKv!4aJq%A69xbaAYa zMHuFI7@d3-)LOI^i)FO9$(u@F%js(-xd*_-urR3&^_6PX-g1$zlDi>n{%hzVD26vO zVb6u11*g2nkY@h4iigc)Doo}CN&Z5MU3$h)BP`P<`4{28Lt_35Vev8f53t?=BpK9A zD!e?_yr_CMU`hC)u>A~BIG((J!qAXz<{|b>^ z*qcl-y||bw^%A9bvIp73E^-mT&@+QueB^Wns_KI2XpF( zPEH~`vPKVvmwb*&#co6TAmnYDox1E^rEUS6_Y{(sXtVB+Hpw?An{=r9X{UJ~LSYA$ zo~lttEl++=*;q>^b;P_I}^b*CV3RO^aMtT*EC_&MfLs=!OC_2IFrP({uC*yqNJ+>n> ziK@>AmC-$uJdNmij>IBmVm%H6HTfx;vBczbDqQSv6E!(T!=ey6m+(h5>LjA%B^0f8 zxS*vh%wc~SWsf*qn`+8J*HU)5R8V?Ys>7^GUQbb9eLQlStK_XjLK+E%N%vQBC1n{- zjml|Ht0}9cWuhR)TDFd|dX`M4oR*!;SvoK^OR-cv4fV}5xzvV3TM4a9`KA*UdXMNU zDU`*k&?iJ6N}*bJ7t!}psMg(0^q&-JRqj`cW;++|w0l)$UN{>u!kpxON}q7#cb#B} z^>}3dEEiMBFkbL({+#oCnggR!#;d5T*n5yYgNvTh!Wd7TPl0XOGWI>tx-c$n82cS; zZLlp{XKv&rX(*Pt3%|SE2Vqf+^LjJbmZh=AKsO!XsM1Dq274B4%XZ>(0<7D16ZA~7 zJ%qiGY)@gYBHJrA4ju~0wv}4d2ivl9Y$njwMB7QNS`zINyBg?GL=Tth97*)(*d0Iz z5N$8j=|{9%>~Wwc5ItE+8$mQK?DzKqJt6iX6lUS9+^#Ujxb+OMEnCI*0DT@UZr3oz z3ykN$wrmq~zry4ExEyX*B$s0qU|Sv*D*`&TF3?7Dem)g!%frRlcosZB&@;$Z2zvq9 zN@1@gJ1{l|9&RGrQL1wT*p^4es)61|^a!cWy+n_ST>*3>(N0pG4Me-fZU_1r(autx zSBQ3xtp)lC(aBQUcA~ltUlTpC>{z_i9;!gn{(P>#GCRV(F|O*g;Y2Um3lH9_NJ3+g z?{K=TWlU6PG6B7~Y2Zu(XIdJw2%KdB7ZaFn0hbY&W&zg{sJ4LX37l;Kw-cCQ0rwD? zX#o!rm}LQv6FA=jo+WUR1#BTOHw7dY;Q;9v*Zn~lKYe|pltZ-F)L3osihTcxUQWk8 zB}d|jo%uPW*0^Zl?}STAHc9v4dXC9MpV!%UxU^a3=D@Nm7-jHXX-Jkm3gRm4YG zc<2-$og2!EF2j>Nohqm5wNfL~iJa-k5-mt*7LX(JrBMD3C(jwn`tJHHN~oOrxe$-C9p|d`Y@Kxt@|%x?ZWuHF$>b z7AMS`HWhl2xtTI}Qk(wY0i8S$sV7%GuTj26Iw6qj4h+3R(ONmR)(|DPQumcyWp`+882~vg#XdkK{-bCpXYwGK$vmla9HM8k@c6XbS(zM{nWhVp zb(kAuJywv+BXVN6#?uDLhGM4AQ+iT1CGxVIxN5X0)S9BLa>A-98bHwna={XaRA>m% zi{%uVLglV^=7M^vOJ;1{_X_t9*rN9M*mGbH1ABDcvSuI+zQ!Tn_4iQtUEuiP5NYTq zLhs8eAZT(Qfj{(dsFD3d{<4tJf4Hyiy4^AgJq4Ao^pUBJa*2GbjRx$-xC}y~CQ~>$ z0oLQ&`^h3|b=F6RjGp+Uz6#yJLiW)>&u6w)CHK&xzb;Aq5`eHwkWBZVSUce)5rxU+tU+ID9Z0W1Smb$wAR0mO4F^|c4Dr>e{xZijJgVgB zlzm~z#{K}m!<@g_XK~UDb7nRuGwP zQQp%q+)U$JQ$@%;Iz^qfjrfD?-O%S`pOnRciAsJ=;F6j>k^GVH2&*14ndIg#v=6dw zt);~&H2E(rPO4Eca~D|{#ST3aEt$+bQ}fKHU6q6Xt}h(2xV%EhVwAtE*W@7BGc? zo)21MI)N#c#`y%62SAv+PpHs5qWV%x+g(FIUnXf_83BFGqk-EAoEtb&p?eAFOB}7S zhQM4);|T(nTfp-KuCajE0dzl#<~kU`EizQ-1FGE33Lwt{VQPTDx%8+RE1^{=w$&f6Bu9t_YxRq z0SgJ-X#qfZ5dOV*z^!3`_wrvg-ksUmxRn z_F1yaLR+XdBBd7EDuA4cncyy1067UWQK63soM4&k5Wq6|RshT7CjwQL$?pPKCIJg87ds_hDl zRj7*qft?COwQ79V5$2fd7*{_d)*<)xrC3a;Y4?A@-i(;_hj5%t!3%%jL$`sRn+jQlFKxl z?oK6d(QvvamAr%Spo5&;qv4uPR%^J1lhC7tuM0ZIOqdOV)^HJeR?r$AlADPZ>Jtq8 zsO0MwLLVymu7%KEg|-vXi^V->P040j%nE5Fk~(P!|I8EtBp7SSGy%uuQhF{ufy$TLrL8 z-V-2YlKh20H+>7NJK--2(amvKj?t0kBqK!1ZL6q-XsaR%5v$PV(T?i%id0Wu>v~PBgqq!!@0J>)@o4V>!`%yq4NII+`4KQpsmET+_*`gge!65|(pk@@*{( zoJgCD>?18pcV}e3a+Fodr%L{yyN^B9>oD6YmpX@~TB4GTG!m4G zn`|N_DJ!|7QOWN#9298aUo;%p8+bqAeA@{Qd(;s>h5@#m2%N29%L(C7F5%tQ0n$)_ zz*>c30t9v{dB(N%RIm1_a#gaFD(zE6s$`i)QdY73e<}4XF5!9?P7VEl!1J-k2jL;> z_9Ju~Mdfn+n3Bt#N$75h+Loi%VY$T&?%h=AL5ezvND?vCR_iJ1nG%U>E&2`BId-nx ztBm*pUU}WFLi>qcDQZ08%*AHt8K8@5qS-`s)HCHF86_IkzrCbfBpVW5;7ECNq>?SS z1DTUjRG|{;%ulb9+@Gq@VHD{r>%gfI9YN7Whq6j`qo^QNglC#`JMt;FTRPc-#}%v@;+aL*YPQI6{Pc{$$#n5H76+AvgFC%W4twp_6H^ zKv)mYmpI%TM1%{q(1Gwf2)opV@J?SSmeu2kt+%oAi%_Auqn++3r+kj)S$|bMY%_Gf z^mYFQb2fD&=kRT`8Ig1NB8h%1XJ)t#RLkc>iVc`2;^7$a3ZC0@h*$8k8}qEaIWElj zEIdrks`v-ruEdKY?ZbFlq#PTauzT2!ils<=T{uy7SA{a;XG4Q6s#uNWH{&Ub(m_tB zlI@D$1C?jNRK7;NF#P{%^jL1)agJLV0T}-XdIexAV@N7KgtDzCo5Qf}@!HSUR=eqM z9}@nZdlr%d#-}gNH$%#_hp>mT`c_B0azV15OrZq|@*} zY*>?e*D#oq zMB*DXekS=RgjdylIjt9<_~0PX)jwViMOA$SJN-dlE*;FN9+}KJJR>rhtE`&2hF)|> zZqyw~CG1izGk502sG1|2xYd1L%9Y*He4e|d`8;<^tNVfzLeKUFmG3jn{61y=hGlMe zF*m%JzbWSGf@!t&@q(r(=ZrZxR&K<9qsWEFU}Cnq$^pw~-v<7RX}otRve{wTMd;Ex zspE{h2xV=yb`i3LvWw9BFIl??rAfJq(4CNSeUe>-(xkIP@v|Tdb`cs_7h~Bh!D>V+ zc@$K}kW`$GWVLCC9ENwh8I_j-j6Z-@ETP`*)N5ZuFJq^ZRmp=T{u%T}P;WdE{Icm_ zFvp{ux(~Q+B`01yieDv5z*M$JGUy%Tx`DZgZKrwIaP7MKAq z!to+_?7tRE2@i$%3GlIvW$r{WXgP8}fvI=^$y25=T*c~soRL?_g9@^F@Z_4F$H{=R zHCD-q89y2&Uk|3@6(m{K;M6_A$*+8qDz`)BW2)R$LnY%$sBrqm--gP1GA^pU2@L)Q zv{sIKjy2!vG>G5zVr_LefXc2&;?t1p2WG&x(A~@adIwvo^#r;HK;_?bm5m(UmQ$5Y zsJQe|rJ4_0?Xt+AKIzub7lA*=fT=49%{{{u87eev&W z^yDNFEdCM9+4RNV)=Mq^J)oDi_^Y9_QDBa7D%*q&G8r}PpFt7z6<3-D*egv|qQk+I zZ!Yxs>a@HwEf0QHZ^lCC^zfDRX`62dRDa0joja|G^*AtiONoMGwm@*EFQ8jBbK**1 z<)g4PoTu`O`>+bdef46fs()fB+*&PFN_D-uz}`&5E_ute>{~S1 zIpc0DJKuBZsl)Z=!tPj4#wD2LC%I=k5KrgE<%fexf|HACTf=byuPejd( zhzbz3jBkdahzFdD0>6OI!div3<4azytuAI&UIKF!nLoi?&pK7SgtW}|Q>(B~ydA_G zKiNt$O(Gq5hv}$#VR~}!IndelzIhH1; zW;&{f?%HF!P?@dEft0_ETwx<^ye-A|E-ZFhU<@vGJ_T5@P0ALB)mPBlmQ@eUt7#`;Gt&=f*b2KF7W1j=RONXsRTvFP zC-I6Iyu7zx{TmIqcW9uiyhuGfUQPRHFSPJf3*?*`zQ$58XFrYC>`pGuomzKwLB>~Z>v+X4%Vs-n`giKr94m!O=t4_0g!;y$aY`XaJ9!?wTMT9-<~U4GkJ7Hxz~Isi~@8q?nt9ro?r)8|w!$j@8>Kp6-if zZLI#87`NI?nH*jVCL8s%i^ybtBMXaPTZdm{DSub<@}ZIHOq{(PZs(b@<^(U?t_y5T zG54+v#A@2&Z}1opaqf4S!aap0F;N$<$Y+rA$R!4%QHlO+*+yUvx0)1-I2dy$#rN%l zJ1JVuycA;{+(|8Am3h?Q?umOVq}@qX_hdb|4Q5b}voFP+M&Vvv{oxef;fr;DolR_A z8g{{RW+iCDd&x7lw8s(G0SjCG3;)1MdJ~tt`dr~J9QvwR@FhFn2`wIf8Kq75Hr#wC zyzn_(J|W+X`MJ(zAJ@hmL0#1-R*o*1>%5Nqy_7efhgQvXaz8PbuPu2x8Jve1ve(ok z9|nz@G>Q*-9V);pJ22^vq~bFih`ySvu6dzId?W5Md4yK}%_M_*D{Ja;Q`~9L;~G%; z9Fy0We1K%|a3pC?u`zBd=yLU`tY&gCldF&n`V76W1kB*(NNgi)XIoiHwIiAIMpD6T zY;BdoB~GN0TiI61Hn!Kp6}PdK?P=5WWP4h4f^0GTr|A`GZf>X`?xI`t7Q>U#R8>!( zYvhEIi{7{qVy+SKFTq>{rt%7^slolRo)sGHq3q&j9pi1b)>hTP<7a}o7)-_OQ1-QW zaaH(ggC_B{ka7)){|)95Fmjgh)uiZG-DdIfH~h0q#S2hsV+t$RZtBMOK+Y8={v?>~ zbi+NAeKm1&I2w2vq|(3v+%$F?&cB5nLbc=1ys3AK9msuqR}lR&Cw?_RePXNNHpS(3 zZ*&P|#D9id_9<@lmf5Gcg8LN5jh=MsQP8V`ST-uY7L06ET)|y~huV4_p|=U*cR7Tg zBZ>cp+-@+c;uJU?Wf$HvlpAmJHm-jlP!-%JcucxD6dw(->=V2QjO-I!!A*z9+j_@@ zvf`cIHMUMCseS5i7%aVzv_15KhZj%)d!bTxYL>03%WR#)F>jiqr(|pD zQDAbRj6az(Q;epbGd<$3q82h|mVpW8jIR~UnemXyoM{Utm@~dwFlY9mYGwdAXU;W+ z1#{+2G+yS+tzd#V8cHx{ebw04?%<6P;C|(Y+%$ZqW zQgddFt;adD3vav0PStC`$WGOqGihq+b7rmWfpg|Q6i{Q%%(itnXFT+j%$e?B{5iuN zqBj^#oNuts6vZzrJ%G}t8Cm&(v$ljtafKVxRdCedj^9R8o6l6oj* zljs-i3jW~68+=$>rEe6SrtxzmJ_s7JS@aw*>6=B{s=OtPuZ4tw0!V}Y^rikJdIZ9tKhuQh z&u<{KCQ-f>FD^unHU6|_kELm#$A&{gdhALt={;tvN{>AS73r~Gz|`n5HoCAzqg#Gv zHQE+Rqfdl1XtXc&8@&+1pwVeUH2Osdtwy(~(dfS*PCs(eG|=ewpPNQc0+ZfoTU8o; zJyfL8uYoy4qc1h3%atFFoZG&z8f^=u(NiD|8tqH{Mt6cRXmpwojs6$KTa8|1ij@Nk zBmE9+(;JNS8 z{pF%3gh8Wyp}$;AgHReR%f(82ps`%s1*u*xuwZZkK4%o@n@8QbJFRNjLaA0CNQ1HP zrT$pdhA^mBnh<00fnP1IR4n){Q?Q&fT06&u7mr^a^oK2E!6FR`_N9Ko57`B$2~qG) z2(3x*iQOTX1cke5PJ%QIOoGACki&g0nDj|ttI8x;2NjtF--Ah?1VcZV(%aQl4;|sv6!WH z#_uX!rje*=_pkKSRTvhBA3zE2Hp?ZB@S-De1cq#GrwYF&Qp6u{4;iwdpxlIP$R9Ff zQ~fd>@$)6(=upub+L~w$*&tf;GcEaXl!Gn(XicgLwImd!X4c0uw~pLr7hYpUrwlLA zDb1^yb5~N8Asl>bl`&WRwnS@wkt5YH65{#Q?G14si74!I+d@HQ@Xow?2o3lR4l&@3 zdHD&5s}}Z^U|IPXix)?ICBUREcdGvNu!)0ng)ts?C?!F!dZeOro1(FQ2yI(jb zle_!nKp2jyOz!S?Z5VuRvrO*pCw$(~ncUs4)x+4$uwZB=clQ&%{-{ju?iVNCV0rzAz87+Ca#??T=u61jAR<(M z$AJf7EApJq0L~@&UA=)ch|XhXS;*1ZoO1peTmWdV0O8JXt#Z#n43r67siK#% zGhTG;_T}tAl&?A3QGcV=BRL-;RM!;o#roSVw7{JND69U>^^4I8l{pqUj!pf0RRc=u zuc$Y(!c$>l;R$T1hVQcA^PzxoYz-klFI|6h_KO(O!L&X;XFTd6L%v>@N=GWE3u<=( zYxsdxm)!k>@f8zJkJ=ITx}zsR?&VOt41-+%9vKG%Ba-5N@K6Xr|G7@XWjwitit_M@ zk`wWtz1raf3Xj6-rHcOb(RCW#M6}VvH;2?V{AWKQXwf&|kGuu>=N%8Hy>N|W`a{0I z;^kO$IAODIb&4B-zX)F($-coU>I-Y}@XG)8AY~UVf#xQb^~V3yRMD41#EL&fxRza>eXpbC`+fO*R#%j?pG+Js^b;1r;y_w_KKhB@KFPkt(VDG% z&0AQ6#=830-6^bxk5Nw-)kNypKcq{duHbqYw6O9Zq4bC@W{mGLFg4|$=?f0y;-#Cl zll^y>5vbhV$nu!ZUK_d}1)J7N8*;O-*Rsf-w`J0n+!nrUn=NBGs_AgZxQ1kZ@0UNH zZDQ}KrZaqDgRm(~jB-~2FI<|TvfG5aW#Dw8hp%{lwWBVdR##=OaB|C67?qCUlSJhg zdMsW!!%=5ZIy zP*E8Xe%mT@6;xiO%3V(G4$%APWvuNb_a7fV#kR~Xf@W80Pfx2#IiQmWpPvR#1T>fM zyfi0Q0a``)nl$(!Ks@5Juao)e)RPX%eGM?T(9OQlhMWEXc=j3S@q7G{;4rDC+4mTH zqm7&4YYX8Y55U)UBUHHwKo?`J$=+$Z&#eZW%tK{<2y;;}m1(*N@Wc4ec3kVwQn`-< zo2LFMFj_hrKm@|`;pvikesZ>(jfa?keRQ!NvfyBKh1EUwuz(zGA+ z;Y-rAUj@tsJbQsVQ@To)uH3JEc(J?O>cQ|Te8&m@*(>}W)JImCkFW9Z44e&A(_z4? zslVCaD)$0puiz;D;HC~XnRt4bb6@Zkvb~xL;xspMpYhP>AO(FqCw+y^2PvdhgWLz9 z^&_X|bv3nA?p|N^P)(WCR5k5#e@MP7pZ$_&rVE!a)pP{#<1sg~w;5bDtp>CL|JhwK z%u1T7MAOG0*g;{rEmTea02X5}oo3_aKq!M?Hie6QAv;PYnbBAX=@Znr-q(=hEB7^E zzY)JFg9nDLkIMB{qt^J(el>%hOf|XCg>{!tg78r)y!$^CHbMA36+X(iycRw1@Ygls zb%81#gflp|fX=?#$^8S0t=RLsw6fNdb42dZz{gYeqmdQML^>VNGQ$7(4dTgO<=zeK zd*YEytL9`??ytVAc1@Wq&?>Jxu0`hHKRZ9uI{(QPNZuk}*3_2CnJ=Fw;5BoU%IC?P z-!aSmd#$HVSci3JhsSz_@_Az5Cq}I^IH52TykhU}#;3jtvlGni~xySsGB{uURazf)-d)1)<}jUDYp=Sp-gTtOEaYHc7+PXo2HAX~Mg!H1`;k2H{Uvvzp2rDa?9 zGdRl*YZt9p!%B^-qRz;TBXYdM{+D`(rCNDY0pCo~Xyb$mTGn(G@Q)}_dQ3u6UXASs4dFnMS%OK!zU=hzeq{`is0UkkKjV%Zv4AWh|f}Jjo|Q- zicH0R&LKd1SYs=6xcN~hjtmY{Rj=v??ULM?8BKCdgY z7Qc_YEoy!rL|Hc)+o1mt;K60!JjgQ3il2ZDH(SdHIoXp?;%~SLuQjm1`vBCb)fL;w z;1^H~aINl6=uBWsDetuan)OcNtjXr0%S-oKJwgwHbjL+Utz%R2e9F19v?B8kG_dvH z>o9)`_m#DV6nKkp$CF-=3iSh~3);tmPN`YYRLFHfDfz(#VOO24xE?R?I^t6$PMt^d zIT2ce&%PN9zrIjsL$*IT>O7u330I-~U`UO7ya-=tc9g=^u~NnEp*xI6b`sG|!eXSP5%aKurkgGM_b&6r#0WwhVRQ8h^*Kw(*??FCBqu zAFA%!e78{(4Xe1HY+PC`!l-mf2)C5%p>WE%CCxfmnsSia6+O%Yq#(y>js_b?(jB=A zeObOOlYYtF<;zNJ87rW2hkTqNi*>E<#yhOy-zaaPNJZT z!&dw7Xuw=V3c9Dk>j3lKt)QQ?4?#X%UzJ^kBa8QL1sCPk`qXF)aSHL{it(2{92&fJ zE4Vm!A~bkkR4~le$lXX7H*^J~ZP&SY@L$8pH0?=%c^6eMB@KQ8@XaToe)l=INa-># ztO#y?N^tpbB4n54mVa*49b%0GB?5S$>mUvaZ!jzU(&XI6XDPTGr&740R%2yeoLX zw1x+bk(~?Kz6~hqh44v;0jIU}LtnNfJW*tpUDt0je1J-YWW9$hKb%yM0!3RPK*}m)-|>e;PdW zdqmRj2kg43H9$15Y(Uoh8p!I{GF^knZgZ?Ra3lCl(KL`QRQ8iNj6Qf6c9-Oi^VLe+ zGEtL?YPJ8M_7>G<=dOpEtP8CUQp>ITgINVS9#m59L|@k9V7td5lVzg(U|F3XGt}vb zis1RSvmW8_uv#j2D&Q%EhuCn_tv);w_ttXw&`33Hk5lN*ZBU=!}8>#%HK}{uIHBkNkc^am9f{D*u#WN_`5m{5@cJql4Q5oKesF2;R#|+`mxD(fJQH zd><A|$F~#m-QhxRXirlA@D3o&UdIHu0w<>Y0l2QIU#8Uc_`XN}Tg|os z=czhB?qn6W#fh5d?EIsgX5T>YDg_lzPWAv8@Pi=vZ#MhGH>h+9n`L1#jKe7_f1uN> zSwm!QqQ!8htmrUgIxm35NIApQTfmbdE1-%h0gLFwlt>lzyf#C%UI>G+&J9qjcPn+X zS@|Q0zEU&*WESf%!J!{f2(#)c@2Eu?stxLue}95`J>rv{8+{xSMhch)T=DV09~d0A}w~eU%;`;dO|6vu2%HgVWPLlw+)A@W|J@)h@r;$2OCvS5z+!9{gS})i^646B=2t91 z8d0jcwwSia5LWOQY+kY8Oz58iYTGt-+VOEILo6v!x5#S&QPI_2wwc>ZmA9?ZA%wZu2wZs3l-WITMbo>BAb zm%&F)(UW4nTN%9VRP71oyN7H%Q+(X+4(&JQHwzgiSvZ^qV-bPodxiAsE&MHD`i=SC zWlG+>Q?J(fJ|V*a%RL_pIG3sX&Sl(pPS?v+e)lqX8dfeYQ~A9;SU>XdB;Z`8^85R= zSK0JgCXndS<==|WpJkf(;E)TH82~a76nmnbxnkwF4&u%4F%86z0S(x%^Ux@T}h+NBTZH7h?X)N2+eGW>1$ z2Qeo zppoOIaFFOE<*yI5lO$86*7@OMhBhhGPLfQ&n)blFD)r8Okh@KEhI(q|B(37d<{R2n zpGLXp)OJ_|vb%ItihtTB|9w33@hWxu6S$laE(L?pBeOsv5I+Qtss91j-64x;oU1e& z98Ww6t~p_-r+m>PMwJ$Uu>2_y=QSXjvG@n5(KFz9(wHJmAu4E^irawL`B^YLC++W- z!Fok3$mrS{Y`ZT2>&rf?FgR8f9}N!XW%F9hDC81ldhXcg3_~P(4FgvO!*KlbhM_9r z^yHgFo5ds*k9a}*{Q0$n%RD}utW-SqMMEq3G%8c^#S0B>T`Atk=>c%kONQ3jm!r-| z6qg3StYd}z1_%uFBzw>++Ud$~Xdu&CTfT|``Wjkm^N8`8Dd$r*dhvL;=M32L+Xuyy zam`RL-#3Ua!P~wiZ{m9Y2IY%jyb?sll=}_q*U{RD0JkRjOv4Oqg2(-$m)$lDXBcOd~D@-v2@DrU4LLFT({T z%mr|yBeq$@=Q(Ohzq;4NvUHb8y`>V;%mZ8aXGHJme*8e+&h|@pQ?(Fch_rAO*T_}8rNJyYH}Gg{XBG5P_sPM_AqoR z_A9-je{F&8!;Yot`{>}f=GPQ6Zn;06JfH@#f&+%w5wW&E&Gj7qvoJI%6JxX}R(~R|m&XwElO^ znp9~Kp2^D(gUYpFA?p$?BqP92IG@4Gd3q7JWK$T1tE(NYwfZ8Cv2}nWB!R^zg$QT zo)xIBgYc-dPoIlX+oq;9!fwusg|%^e6#mx~f_WH&xhFXg^LCb&9z6kMBz@B_VA^g| z^I5AqDVTY5|0=b|V0={mRdsmf!By&A{I6MY9Ch4H9pN$yet#Fi`vu$>I?loWnxC&p zIEPtq^@WbpnSg?)qp0ed#hJCw%SKx|Ll6B-$6u?AV&COx)J1j3UTTcoLw*uoXl$t4?NEeC} zh7Hn*wVJy;l4vU&a-t#43^!syy<9#z2=J` zY&Q@$j0bAI3RJtHxZ#9c^L0?Y4*6@I!lnrtDjBQ7&48HT!g(76a>MaM6&3->o(gnf zKw&}k6kccrct4U}Z9qC6@MMw}2gCRCr9{-oD|Ay2{IB^Sp#P!^l!t07qVEQEeej#9 zlA4dTrK;`>i!3*`Q<8(Q=P>s9D^aUO1peh#mm!BjA0Em=Yod75GpkgGvtaak(F16< zFgJ&dS7e&5C*j(tusweBr9sVR(b`z;g(I3TY=2<+~MRlhPF>?JPU5sQT{=GI)U2i$NN_B09V%w*m9mzIXD^-{~ z+>ED=k}%CZ$GX-%b)G@HrgECz-bUcZZeHI^!;eVLxYbo6*_V zcfaVnXv+jzWuWZ|6>fn{)g_SoE3-2IEnD2kqy=lf$P_jJRXD=xJ;-qoP-BvY3{SsT?*(|!nHnJXnL7W*4E^!kG6*B8K8I^ z?wNe9`7Tp;2YxegThrP|4*^m0Y|2^XQ?8GGEp<0>G5b<2sGl_U^!gXU2&)Hig5zo1} zP9mNY{$g+cQ^a%2cP`=?f(Fa==S!Q$Bc4Gd=>Uik4{samBo%M_y^DC*385%$B;r{H zzOsmih3kIwBA#(S7%m&}2-m4(mC3HS$7ZH;5%Ju=+KYIEaSa)D#B<7TUc{3SsY;c) z{q99PQnx_*|3%Z1&-61fQciQ<-`G>^uZ{j9n9Op5;`W=5kI0X z?4n{PJU7-S{R9($^-2Fo8IdWT$fgu2EKO(RMKFBQ3T=g_s|;yo*oy`AbpE4SaF>rjqfudEOIuJDeStixD&2rA;I3k_UWDSY!z40x9ygg zg~Dx{*ED0@wzJVXVeVWuYGOLvw%N@x)@^$mCJIM1QrNylO|0AY8?LR}_AnAO;_3B{ znqijHB5iPG}!uQhUT+h|DiD>~(0Y!lVBV@*bNeXa%bNi}WR zCUDz+Y?;wvfN|R{VO{I~Ze>uoZ4+pl#0+&!+hpWzHr+OXE8I5w4Cenwk}9sjNZ{LCx@~`1j<7mMj<%GmJ9XWRbK6ASI)sb;Pcly%+_q1^ zV%@fcrS9O48RxboaN%XZe8&#AZCz_fBW~N)sIzt3MA~!PXmulQ+c)jmOmN#s_uRHm z*(QYuRO7b2#g_U)(4jz$+qRVG4@5n;jjCpkHhBP@uj<-S13c5&4lklqN5lduY1!!c7^Ss2&0fMcq4Oq&ii)_vVaFR1YsBQk5!Qe~TFwqio%l5|59( zHKX0Oi%p_hS}5*(n}IJgiE3$`_&dOosJ?Ai#r9%Rge zPt&8$MBRfQa34hD864#VqSczaStJB!VO7ojWnDi!AK zW8|Dgd1+3l6(y#{%*UsWOH)Kp2b_jLMrH*ig1;2lo;C}=>_Qs5H7H21%i!Hc% zvg33nprL-g(=-&HWv`)DP-S8DG}lm^DWX+^4uOnmC{7enn$w4CD3zzGiiT>L9whT( zl2Hw${tYv#%O0jd@LuQMZzMG8mF zcHV135^aSu?swj6Zx)2pxlKWh48(m=bh-EXe=-TWH=K4hOcwKE-?I|$m6N*lUjM>% z;=L|^hRp)+b=N-Vr+?Wn>%G=K#X{k|KKiKhUWcM}!rTZpYGOLP*LNRt-s=RIC>+rk zVY>reWWCqfxVGNwm5)2`b)gekj4LBIAH3FkeF4|jdp-I;iT6rFqSmAT)izOGC(Xn9 z{?Zd%-w$5MHi7s0=yT=X>p0f6?uX|S@AW#`roGoLFDBlrz}kClxVHX}#+UV8uX&Z$ z!h7B8m2&U(CfYWQCMUfJ@AY3ZC>ikZUjKfdR>6CHu^&1vNjm;cdz|;myXfx(g7+#= zlSjc-czlWTUTXjdNfnEu6Yq83cML~ZT}O_!DOdL;P@8lVbsY#7M?p}YHh8b2-%Y&N zgr#ns_Y&_lfeViUHr{Jz79%9--m;|QUZ}J6UWLW;UW+Ka5$|>NVm1@JSJJ(?`E#~O z;n_uQZeGHc`bNdnnmRWUbr-6N`2UGtf0jPA}ut5GDp*Eu_)$Ohi) z*vFtP@m_h`m}3-ivB19mv#ZO!*UQK+-s@~QZqY<)EAF_Hne(vC;znFs@3r?i)k)G( zO1hE!aj(JEHtEP>!W^}#xcd+TZ<*2FtJsz{65 z>%D63m4L-fwce}de)tRnTklo4|J#uJKlEO&J+WFll}&cRQ&{d)b^uK>kj;aWQSsav ztbN{&?lPzH@5!4ZOIKhD5A58EV0dEDUGm!fwoOvh~ zaCJY&=}f>Z^7a@GW%zLYhgI7Q@^&GLW@Ej1Twpb=58dDR6}kXP?3R|7d(!A8z-X zX)S!X)J@f88OT<&tsPBHdeQgc{?`VT`EcE5(kl3HS6~(Me7JLHkMrSp7Y$1w_;3PU zNT~4Uv}&7yycB?tRB=0u1e<|8=}yBDR$obu8z@(ozN^~#aH8%O!o{f&v_9Mvu-FV_ z!cw>W^lF!ZOyI&NfQ=6~#TwE`2J*Za)y{_#Y0rnF)s6UY0jelI9O<49cQh?7ESOqt zGm!fNh>jEV*gLAN4|h1x(}{XM9932NaC^Rq(cNV+NB48DHAj)N(}lLUxEKFx9!zta ztM`GAy!hqE?GfK%HJ12)790G^H}J~0@X#isz-|cKe>uyVmM&bo%#<}-AsC;@aqyTg4J2TG`2tTN+9<>auz+9lQNytq20YBvsY zqaYh`Kc3Q1cLQBXsL0`LmA?TOJL00q3pRPvrg&!F`iYw@x}g#k za%>Zkn_}g7VddJVU&n64AnqTunk+5!5NIU8piC6W!2(@^ zYq_|R7ko@PbTFE>JOS$KrphqkpE3$$^CUH7`Q0Y%sJjCPC`>#Vd^ix}^!?Bo$$=OL zazBwf5QBHoVT3wvh+TI2K#YO74{`~~9f%>auDF)zAFgK+!}HuHy#m)+?p*nCAkHK_ z57vA(I8aMrM5cSo^yjDP;n-z=Hyl|dI~+Oq{o!~c&AOFlx#1|#bV7yiv8#`kVmRId zASa~zskv}0$`R67kF=bmx>rE5!%-wCt6NrvBW*Cl@ii3S4ac!$w8K%~nBmBq=rWSS z+19896LFtQDAIQ_99e=Hju{veG)*VNG03yJ<-?JP467>6-oqM-usO;{B9TO7_1O(d z;Ya==!ma-@=!sa7uAL##dEij&BuxEzAv^c9wzq)pjh|-RtmMWI?;>t(QXStLYsU{a zH3hkZTCqP4{d-fd^c*qS^Duwe@T5*J>Hf)*RNG>*& z4@oF2TF%Fr5k0a4Fu+-X)aH0Pw(fz{NNQ7g*(-e9(W3e8!uvVLH|#6Tx9|CS$;|T= zispMBkmFl62g@|{(RCAj3|2MYH-HSE>KZSs^p$VURolW@E<#-2R&M>*? zKs>xS!=&!W24|Rz<7-lPh6(SYr@$SJ=haR8F^wGAb0BKYFya0pbB4*rN4qmjnjh8R z3=`3IAI04nCIUT1$em##kQCz1FmZyqaCe4@llJjtK~8Y)7HHIVcZP|uN$tGiaE3{O zORa^NoMBR-+@n_G%i0QRq9A_voQzBdIK$)#RM@aebHtkuHnhA?lXi)(wzLjDP4+^> zYDmVOVe%<@Dabv;ri_mRTy};+y zKOe1QC7faMzUA06_&_+Mm~87~bOePnOnRN0v1gcg9PxF8^%*9f>iByLAM5LjcN>Kkc*jv0dxlAcW);6-Y3oEDjh8Au@O&e; zu{=;lr?g@Gu%-3!<=73nFG|~w&Ln4;$QUZ!2FRUZBKGl#Q1PF@%^4;ydjoX9n2bHc zWQhkq1=yTn;#sV%DqUb`w}=&bs7IPM5;Sv$NiyCI?L*Ma878Aoa^0up`dw&f&qo&t zjls>|N#G2V&w=_alwEIgokYSJCRJk%+ftwH8>xJM(99Vol`7(SmbNnbUetR< zx49@|&oD`!eimpl8?;Wna=2?4vZ?GS zJVxdWlguTCtwZW(VG~0&+cRKeCK+d#91AvchDjw`{4{Bt9C|b;DK1`WXuTV#kB5L} z&M;}9^DWTI&M=XgD(;C0rtAz8flIepm}i*C@Ravsr7A3;?hF&brDCN4z}*=p2`(P9 zY)ZKu@vAJ@+|N0`4ju!)=aDl^>_#w^=`CK0pxlU&C+;thRH!) z^cyOiVM0B^5YZA^h886qXNgJ>NeddhT*S&o5T$IK!lZui^|7F-4#H!81&RnJw|pXPAgVT7qYo zh{T~ZQe!;B#1-kCVdD5APXW&`am<>KoM9paVb&PWFcB=VuRm+9TZoTKZ>&#W!wYXjP#nC+=2qh6&47rHMWDGA3u3h&hzN z)Z0r>f;hv3-jXg_741G(o?&t>17IMm?W@% zC3^QL$6ux3=`cMgZ9j* zvNKEsE*-v?fq90Bj75Eh$-aAQM+j$_B%>&j#)|9rF|_gC;4rlH_SH@j&M>KLZzI2uZr^r8`@N#M!9H{fmj5x zcF#P{Fll;7#-3p^6bwcWRf_RiAkG|`v1gdDh{m}}Yry5sFp+wQ9xCFujJo8@k2AE+z8rN%qPTSP@j6zJGfY@9Rl48=?R3c*Ca!gH zki{SjP^33-hRKnL&rCTZC{w%~3#C27ZArjPqYCr0}YLPs{t)6 z*9aA6B4uq7qw-mhkQP#NVd&2;F`AJ6B&n_*CfLNNNRYwH)8CF;lNdb+1$c?kab&cK zQGH_)qr8d6lN@%kMlHAr_ql|U z_2g%blFcPT^P3`P+;viOOoUtFOQQ~{2THmoC*jfbYVs=0b~WK$#4jFH$2sk6P57-t zkV{CeCL$|#&qhte(YM*${=)**0~(OcRR~vaLmgAQbq)5%X31Z%SaqFnA`EMFG7a1G zaBOKYIntRhjyckvXEn%?Ud>HAE=S6{=reFf*YfH%{+L0I?2QmLIZ|%sH#yS%2D=<- zk8>L2NJZO&6n8mNfgUI1a-;%DAudPi1a;vqN9v?~963_KTaSj>joI#Uq{1c~UUA5g zCb-mEh)IsLLb*p}j6hRz=RA8H@tJ)A>l~@4I$mwzV|{(`sO_t5j?`C@ z=~r!Yq!&o(()8p|*(>p0%;ZR)v~2eW9^1=Om-B|Y9O)iA=+h=5pi#r#+ zi=#h0xOT5hqQX}3t{=%F5ITBp6MZH_b=FUx3ZzNOwKR%nO|wu*GkaHb8Qul_kZ89&Bj68_InGn#qw? z799^dq`Evuswc$X0GH)R1uk82sDYUymEoy#r0ou?PI9DzOZ`hTfV&)Nf+zb6ug1O` zuHEtlljKOb`9*T1`<{=PO3r!aXDF?)M(~{H9k;|{jU4Gneq0)~eF7s0zZPvLzmDuH zznX2&U#+I_m*hyhVPr^-^m1(K=TRHxoM$f8k|TW^pK$m&(g#Rjj&wc*yd0?rG@2tF zO$p{m=X_9}Bkh5*BO0IzKP@fKk&>heZ9Z~2(s}^7?TBV+yvdPn_OZ*6Qjai1v_#b% z_(_r@rJNLGXcIn7a-^cO@W?WkBi(_D#57TqwV&@HN4jXa%aJ-RRkz}^Bu6SG?aJcJ zInQ4tInsotW1VBaOmd`Rh0Bo&XCt4M>Ky4_P_MEa0~I;aq<}-51=;IHH^`Az@QF1# zoyl{a#grsRD$Hz&=)W73Fw{m9I2Q?2^D|!gUPJ53F$4Fekj_nshA^O^P^!YhIE$#8KtUdKeA$uw8hUR z@7B)O61V@wz#V-}Z;gk@`v=S>tk~3V{hd?h=$dP)q zGuia=w|2Ra9p^l673vi$e{jeJ$_xNXsN%<%32lz_yOds2^8Fj|#R}1#$&qsP(sj{h z6jwlp&5_QpHaboWEBWGAn}Ejb^=S=h%d&dS$`5WxTZPSWe6Qznq`EU|n^%|TNChr+ zuQ4!lq%sywjx?v8B;-hwu^35X#mBcWwDI1UF|-l2+DSr=w6c-oiLrKskR#Pjl9Z=) z{+c(mNuhRSUi+U7`EMB`kgX2t3xM=JFYJz`X8_qD5&9BDbxjKwR~skS*%ZA!w$ zdwk+ksahv~n?P7`kW`0inMP8p>_7S)Qk|TAktKwzdFhF&Vl<}Dl3bN_?cP7wNtgm>sY*^&gZXO4roVV$k#+psnr%zxe&D(Une&wd?_3ftX!=Tq~ zy54>H4s^P#D(|8}ggRdRux`rg@n_*a$R#9~RTWt|h=IkmOi%rq zMGTkysgfTq0(SY~Z*dsJmQc$4@CNh2S)Lz`!7I(k^HU^0OvL4fznhET=kh0+hTZCI zU6ac}_iFNHSxtBs@tb1Rao#uS3qdWh?yXwGmdQle^=)wA8^HHgWmkg)ol!;e+s19se?m_jdrB&VyAhKg_!* zJq8bC3tkoYqa!)8k3rPrhxxgz$q%13&gF;qxx7JsShQ_KahD$!s23rZ9~MXoart2< zs0(-bVJGe5$PWw7@7)@;-Q|acO={;Ahx~AYORa^N!yQ{RvH4-v z+H%hZZ2k_Q4{uis-PmP>zXSN!1>|PcRJPX@E7C&rhCxuDF>oP=7Jh-h9KBEDHXeez_FbvEOyAi44_ko+g16ZM1 z#n-K6XzN5Cjh8Ckt!QW)%L8R}N*l)SSy~@oPFh6zqIARBO_KbujG+ z9%mZ?H~HZf-T>XX)Wqh8*Ye=SfXyCS&th%WvF!})7HK#=)FVy%2{f~ZHW}}Rc0v0l zHb1-|={_yjwu7NPA1xFbpDH6a8#I$29thNLq3m6|xcqSax`u6Otg`%0eD`KeBtJZ$2^MSQhkN7mb|i+!U$puJIN22M+T1o$ju{~rST>|JmOycg)sKe zQjai1v_#cSy-$A?%ssS}lY$Iw*=$3@9$L{^X!=04-9!5%6^Uu0D9dk-`28~S!y7$_ zOuXJh>$p_iE)P|^J+xBN0v4z9!~=53N|?^25UUkLlQjP_MEa z0~PtWOq~GRZ4=uw1%l+uf z`ZXr@(E8l(yrN%YVh^nkuX)wwhZ9&o^6^@)yZo?6`<6}b=ZAZ~VVd~hkPDO<0F+S0 zTQL*b{P3E$OoR4sz!%ppGCBr?T)lK%v>C;j&|&k#OP3fOCpO@Ve|pFC%xMj2&E9kQ z;Y$7Sy6;!yhjnN4{h%U0EO2SyQZGL&V^QaaFaOZxhm)}wNn^!#eB|=O$sjbeCq8!h z;mSsi-~GhphqaR=@IOpMn8@!4Oy{4k4XoU3%>H(q{N>LGf>sM69EUVgZoXvSiP zl`cQ5O-Z;B~O!ybd=hc(0DKfC;}SB{uOo5dt-J^IDvhrNNrae`A>SGoMKN8_c6*IDiI!&GS= zJ6&?G-&}s!lcUZ^6qnBZ-OCTNVyblYA6|agwJz*i1#mm^h|U?TkZ3Z^1UQ*=%41Kq319(;CPO?Vga z%pTQouc@{sJgq0lB_vl9krlh8;aCBiBRzgppk6|W$dT@Spi-}(j@U!{`=>~c4*Lv0 zg1=zcA*u;pkbIA9M~f~mrZyRLzEVHHx-R>tRa9(wP^8WT(&gpUI#J8C>hfwTR|FQ3 zMQP}D1NA|dMf_p#_YB@1{AyE?UTRqh6_z7}{(eP`>asjVvD}%0reMjAu(r#W9$MEC zsPO)7Rj{DC-j?}KA1>?5I^+Nkt!rXC?|82?Ro5P{FrVndg)IR~OPrEA1xmHal3FP236gZk*$qeoK#~p_ z-hea|BvKy)+9dblkKMwuVxqX2}WHB9bw1EyH&L0Lp+2CS5%&xkcNOHX3X(OdN5uMl61)OG@DY_Jx>#*L%JRg-)Xbv zn*{2uiduC3xNgamUpx061=5u-kYP}O9)$5dS^Vf0BlY@Gl z8rG7b*Re)b%4w%UHnJbvTfR%b$HPq5S-8=Qj6 z_UU8rGpIW%*pwG_M+dq6Kt(1b_3SU9+PnUvV3RiELv=e8)?Xf~uzjk>55#+ht+u}f zeC@to5vsj#RlilJ+N}o~-*(s6ht=)IT^FjuNa-E6Xm_o>**fgL4pr1|8|I#8QTnc* zzKdQ?pj{2LIDvLI(EEhywuYJm@W*lL_cidxgjF#d9jFl~uYOrj96VX66ISASld#ws z*F4Oz{^2(h?n>RL8r2KI^g)MYM7@ZU$ zK9Z`$%Po9#$o39(<>S^rhH5wbuOAprxRueAZj*Ls&Y3>}{w|2;;`dj)9uz(-ETXX3 z4J?o0Y_j^VgVOIH^Mva9)A8rsrLD+`zYzxP6yifdju%6dLnuolfX^mvq?I9yZsgL_ zApA(;SWDDGDGbn__+NjK#YKoeRB0y=hLd=4LtRY3JO=@H71z%^ zAX2INOT(Jscs6j@aAC7R-o4fT&IA4CejTbHb#YJ__hqP#!B|So4PLzsW*^M1eGdJ3kb=Ki(|>N4>F3m~LE%(zOhW}yLHHgG5)M}_F=P=Q+tfWlvH2ZJU4tIuHC+Sxb*XVd z-3|THYB2t%J_)2@c$if0bGoM0hKHh2OdVOfNbccxPDYjJK^O6qsllc+h1jFn>h~ccZ)NkKozNtSo^8+f<8%5S%p|U&S z_m>=oBeM@qRcZ+@hh~1kFX6bdI`fykzN$s03ey6ohx)7AWJlw-OcSHBPe8K78Dr?y z=it{gUXJ02YyA)}C**FWp;Q=A+Q8QdY;Nw-JX2ZE@L5Q)p7pct!M#uU8kE9!(0QMl zf>HPY*|SY?DU;NBS53-fBq!OOBLmW$nbekR#5V_L^Ax!g6~(dH$}H_Wv^f6 z*rWNZShyi5Tik}yR*4L2Ybbkz!X>}{&kC8snV^i{7nC5V5Gq^?65k2dR|j2fm9@UQ zM?v}$|Lbc5T@&diH;(dbx1T}Jvw=8mWe3zMb^oo9xC{&G6F`FA=ZC8?vf6XJOt=k0 zBAUorWNn-Fz95k%_8f=dW!W3SRI`$oD*Fed&ZGQp?bCZvXL+z&jVDhcIzDz1(eXke zI_zETya^;ar1r(5$%pC;FnbSGcTDEVL&dvjb3z?QgI_;X+u|OcgCn_zN@T@&adNVw z#sum(h-JFBNuAIwO4j^|D6?|S?>P;2$eO=Bt{PwS_aeov`Euj0`R~zAx90OM`Y3_0 z<_q*y0%6S;XeFV#vF#(b<_r82VNA^zCTo8EtYpn!F*8~7;|`Hs^Us8hL2fl=izC3o z7er-iet0rS$(qmG$~9lGOa*~!z9V>RzF@Uvu2}OELdBZz2;Q3Su*fUdt@)&?csy!p z*8ElgLNQ0hE!Q>h(IML#=V!C>@g%@z&A;eQuFASidZ9V(n!o${kzMm=2#b_c><1RR z=Dz|Kx8{qHAScTpf$~! z-w&5|&9`HVYyQw?M&yN{T*R#TzkzPod{HM{dd(l%JhE$kH<%nvM;Ya7{u*$YHUCu_ zBpi8LEg9r{oqy#Xr9SGcuh{^0&F^-1bG2YrbCp^dNW*Z=*A-)xRNd(>HCHnh zf)1a6a*0pCJC8Lwnf$6{Y7h?2WzO^A8Kh@;zVDd_gl^mE$IWoPq=nmddIZFxV<_tm zR24|n71pkbWNt&w^9=ChgtRsKO%+;Z3~8)KI-R7t5GL4j14M$dDo-H=Ldi4h4r8u$qiy>#g=EW@Tt^^HlF z@+R7o(ZED(POyFY475sx2wPG_ z+^N7stVoB{HccUd_2v_{UE;(|1XHr!@GiQMP{-C7vwFRmiu)j!klcDBvhG1s*)uS2 z+|@J^C+?tjk#ph#%-VF~n&G!`;)Y_N&TSQ0Cr&tw6DQZkiQ{}vCvHdlHcs3Hki4`t zCAWUN4IT_E$>mPmeAa>%_SxF;3iDAXz6)Y9jsQ#!;T_CQck1sG$?L8-@*?xW_Q(X(#Sj z42kFgFsrO>Q#f%>nipTxMRelk;Iab-Pj5JJPeSU^mbiu!w;6u_lM}}oP@FhkSSPMS zYDy>lJoUJ@?0MQA3v=>3@h;k#P{$FNmi6OV1=z2nR zvwlkaH-T>^tcv?yocM2tewp}hO>u2=Hh)0Y0{u5f@ccKy=90O>e@h4z{+lCs{+q)huUzN9k*eaYe|G-ce*lDHj*2g|@X;aL zJJgkrUj}Uaw;gBG!_sYXI-1k^Z$GYb{@Wm7k#dUXfyMf7Tm0(zZ(<}lRXhr~$=Ptc zXj_bn_B3eDe-jz97-F;4p8qC9?Z52<-1%>b5G7UVCJ9W?TD1`zxDnGPZj;QYYuY$+nD=db_;f`_*%t-pws$qc5KmqYw@-7-^xXd z|F%Eq)_)Uq!lnJUn?W-A9l6;ja8eoSqcv0zg_7#T(xA7w_2%vwiRD1^*TD0 zz8o9C_-{oHz{C5(KbslUt(e(dJ%s=C)yR|hYQ0#rt}kmE$$j0cFE>{Y;y-;q%bzeY zAAH@#c>1zqg0?H?p|irm?gJuqD6&P_yX7wi==br3`4)Xxqw=(@)$Q0wEtv$~#{?~m z!2RYo;r{6$_aLmP_)&ib?2^Z+xO%>l&dA;z6wk&r^SasVgTgAS;l+Q}AY~U$8yKml zSk|lm$f;_#{5Xd*N0IB@4n?cA<#wgHjdmbbJnlbwn#tZ3X!;+PKK5Ru!GuZc$zTql zo=6CL@k*vjuYRW&=5*DGtrdrF`ep3xW#nEwkmC8O8o`8Z)ZKV$JE|&JRPm{XDS6bQ< zpT=@j=}XXN_H3cDU)%Cs>#5Ra#~Whn$P^|*@ioBt6-9RasNcg}5v2Qy_gostqLIBl zh%Y?Fu=I$I7nT{Y7=MQ3ay>0%rv&kpXGO9nI=hvxC4SSw+xwDn>$Bmd;fv(#?$M)O znSGzcLwN__JA!z9JYvFfK=i&>=1yQ)NS3KVyxrhP&7hVeeJ$}=3m@-G#xDWpSJ2rr z%1o&n63M3Q?65NU5Wr)|eLySD__^8(K z4F}(1WKpxX1*ONp7vF{JuBlMkLG#4f;gNhjknPi;oOlmQ+pmG{csyvW{(!zCJvkLG zvG5>I1e?3gi_~V#;Gdpd#y!Boqsq8v0ABhzn(B(wwA1ZFsN$6t9-n$fVBLb7jfhmI z>9FK>+k(1l##nr|#UGb0dky%RnHlSc@Rzp@q7}; zTOu1u2ASdb3LKA-<2uVB&sW_00)#unZ>-{jq3u!em4NrZ8}Py^YBFYWqKkBsXD^J@ z17vvX9~dqI!`EbZw`%-cYH*K6)D-#X#7W6c3*vXc+=(r}Tr+FSWpRtUkB!t(q zPfNRw27E2yKW&A$*sFLE@UMwC$#|CYQpG!5WN6JQX)-~px<|n<`d$d9z$Jc z_$fjw`7~MiB(WmyA{TSIi}4;eHCHq7Kl_+|=JY!*F4Qsu`y|b3hIy_tgO?+-5mhRJ_TMOvaTdYwsR{CP1QdA)U`8(fI-`a&N177rjEL zmyyjMfy^eSQs(hI*K(0L$jUsECB`ml{&XVql#5Q_OJvOEjKcw)H(*Tam~Hjb z^x4I}Vsup!v$eX>u=I%5dWI~oQ)BV&tCN_m^&}Uwd0OHlEWEuh8Q%fe#B3*vLS5$b zsD+K$9>2-OY*%?@z6=%{vn{>Z#cZCIxZ^DbK0fj! zVm4pNF1Nav&4(udE{oZuf#UZ7bAEL(o4}<`w|Oy}>n2q?&EkyN93JWJdmKa;vq^Ks zHMdv9Y`WA#0hh&Wy40zFUCidR2a>yTP+fgJ>f z?+x(Tm~AllT+GIzHBbB^aDMTPn60v$xMqr>?bkqeygz6rW=rH$e6xiIc_J$Q46upW zeC}>j4Lquh`)t4_W_uayzZv`SJPVIceJ!wV!RQVzW|J1wU9+FX8M6t#T%Ncoz+KFy zyX;#)Ja_>yTk@F5z|-9vA2ZD`WYd)lqBLG&8P;mRAd^6R^qnqdtJILp2JsSbnV7AD zOT|0gj3hAKf2|!Qo;yC$8eIGb>^?(vVaKY+^QQ3UwE9GKh4O{|N>Yvo+2z ze3pyZc6fmr+^}yXW_u0HCT0_6ZMm!wahJPY%%*8yNxPm0*u`v8A+EwIeiOKf**wE| zsp5Y3xR|Yi770V$V_>i`o9N{FqL;q94dAEPm@T2{n2igt#B5y5C1&e0rMbEt{}Hpv zGp7SG@+sYxTf#?DrAafIt96kAPhvKYg*HXPhj43GxJ5PyyA%#fc@RbyMzu=8sc}JA zCpMD~xyI&r6Ln3HaT?h?L9W)wRtYjOK_X#9-Vk$IV?h|bDI0{zwF$!HItjv>i*gf$ z@g|CiwAk%x7laAgTF}RUa_cmLFhScB#b=o$Wge^qAdf~IJb+S z%Yd37Y$2@GXySZ%L6~T9K^X6%{iwnPVFHy0VGi&r3-n|GND!pcQV5Z3bYBnT6A!li?-vp_RJ*bo*M zvBG6R*g|laAgrz9$lJ$H`n3+@hd~%CX15P5p4?mw!G8u}#FHRQo;zJH*2p|}9a1e& z4F+L*(VI+yuS!8-xnP;-Z8VSO_g~!=B1BbCq>gz8! zyC4XAXECZ777l%-u^{Yji3U!tMs(*@mR2r9B;bG^tB`vZXEYX)H&Tri12!FezV}m93{ri!G5sm@`hrt>3_y z)Ir#Y*Xdk~eZ}F|CqdYqiwsMT=yqZGmKuv4Z%l%)J>PRdn5QK^+rr!XlJQM|O%V2j zSLOt~xwk>s?eDuFEdK`0(q&!`78``!{ecU@JT38C7Ct`mB;!8-n;^`qM7-Wo7lirn z9)L{{<|`Qr*t|IN;mLr@f-o^Qei3k45GHWx7r^etnd>H1TIWN9GYE5dq`Pl-5M2-^ zT@;T1RQBRbmpTJ*SrDd6eG{+?!kl&$uK{j?urY7i{x`u@?KMdd*6t%0gv}H_sx^F_ z!DoZ89l+;;u!JWb3fu%?mF2{@SlWK6O5O1@pqU^nk;9j979Qk@s5t+z3&MQvdJB&# z;~oIm1Ytj6?K5LPzRbeoQ{UpvuNix#2LQVlXVQYYYd*C&gD}B^bNIy7e&PjTy32Y4 zGC^4Kn8>4{yEz_j8M5h022mP+ZW-2Uz#x-Ay!WRr2&>eP%m(qD;4(p21(%9fS=zk~ zir^!nO1mucf-tEtrzurB3;6!ka31;MOe$Qu36KlIgf%guv=~GeggK%r<(7Lvn8VG3 zup@{r2ooYJphFqmAJf3$f-onp;`e};y*MLH#WkO~AdH$q-G!`aq?`O?Fqj~$afXFp zFfYy)E}{lE>>CNf{sOZJ!h~5{E=ynB>+{IIIMcK$8AvAqc0rg_h^sKpkppgmFwZbv zs`w{MYnG{?MZ!?GGkg&ngo(~8_&nvz)CfX=L z#^nU*l^|DZWa|W(m>`ibs_gF*8V|DQE!iMTu1%07*GZ7oLX?{zi#JhAA}yvbbU~J& z1wsD=YJx05I}%mdD$JWE$lB*67i9GXF}D*r3fEb*WxyKeb{F&mpeD%L_#K2Kf+o(D z7i5VR7i94+I*=+{kR?!gkmVqs6+xEZM9RSq;W0f~=m;Vht6ancSqFn|-*kyO;nG3YEufho>jM^7#R``NS?`0x1X&{; zN8UbO(yu3D{4mI}-Y?#CA)ILQET1EU6P=e~G=+t>_cs+ys~6+iZ1Bk6ZKJ(efo#62k3h7)T);NIy}2+OT#(BZ^M;56aHKXH2D#J(un3nzFR z9YoB1Mq9QIPv|n|2vZVHB!r_A74}2dvT#B;Pht^CI3d_M3C3{3@o9TpIN^8&uLvh9 zh!x>PIn@g%gmCj`=owut7fz6XkGIgIjEAugZx{g2HWkmYw5NTV)Fpn)(w6u%mZM7H zgI+ixokg%e_I9M7)^Cj>5S z3fP4cuA5Y8AB!`baCoGpd{k@r_5hy^C%S;og%b%+ybo{_PE?i?pJZwKr7CsD z7lCHNi9}AtQ!PBm6H)O~fXzD{pL?l=N0o8^4%mbf{1DiT{kYW=1|FZf7rQKioNmEQ z0lRQQT2Ob*ffi>tA@~A5AElwd-8&uAWq?dLkvt~yXy|T^Kei0nbR~l*jXV9vXjrQO zgG>VPXv?r!1BPTah!=v(gcB9zsJQu)?ww8rO)OQV{lMVf=}3h+g{jh+z+E^Y6)s%` z$b}Qanix@f97GpRIHD?j1KjPybGUgBT0Z546GEhs+9}ulF%TRsoN(eQz6y9*I6<0< z9|dgQ=}=RsyO5JXq?*#e@@YS{lNM zgr>s@F2E8_JbJqcCm#K*xoY{jgcGzY%yVIoa6)9I!wE(F!EoZ6*>r<+II;Dz%5Z`% zifZ*Jf7)=Omd#+p3Eo7l5@cLXkah`jwMN!UkckNr38Tu|lV-9N8|UaP*>FOxO*kRf zNjS0kOqyiE3Eo715^1p`oK>@NPSB7>w73+g2`2qnYBX`Kyl_IaxNw4Z(Kb}!!U=)O!wCoZtOzFr-#L*+ zI3bWUvkNC2moJTQLU5KHX%#k{Ag&5Wp++X0U^{DW9Zp;hk_{(B2^mZ{F&8u!P6$zl z6Ai|w>fCx2{`_qEz6UX#;|&65dwCmR&*8u}E_*ygb;r;Lp0+#}j;i)O|*5R2f zu}0n?>;~th^IQ1QAvIzFr173)2ot`^dy*enZMRvCchRqeI<5l0eoqo0?g(-T$-O5L z*}M&zRCerjfqDdDneH9ZOJ9pri)}W}tc%~*qsVQx!lqs*rYpD27MX5k3ETKv-1Ae&DB*v&~Lq402P*-f;*}x{urJMjaNN z1(ZkCZ?l(&ipd>t@)kPck~i3>59ArZNuzQFF|TrLP*>RzZ5LDK@jUAzGW7UOM-XeI zBc6Q^tP9^~N6h*P(&z| z9Ex)1l0Ew!F3soB{JwK6c<_1jZTO`>kIsGNSi3-g-Gei3-UVHsakFtkw;$`_^XR%C z;8*jcnt3Cw5jai<`pxIjyIcD6dr@AD9Ci;@lW;63`t#^SGJL{-8zL&JU^Ej5vTa^on^ zc9YMe*+30HkN$Zjh9f?Y-U7edV>I=iZ~=xybQq-Yhl?P>=K!BaJ8535`BpxUJ_<~m zVbt*R=#L?`;4QFOHLFccw~o8lh0 zWaW8cSBDk)%_XxzL#)UPLAi*@22BUuW`jhXaOrH&`=FU@(AO;PAe2#_4Qc|*Og3no zu{@s{9hX&;WrofFr>w)hE`kWA)PKENr)4Dh4<5#3rpVJ$sp9wl& zclH_T(WU&I(ORl75%l@^-{<^*Ky<0J1}iZ8I5(hBZK`W3V@@(*-K#`(*;R}94ffU`sRWKJRqI(dipQ3B=L}*iVTdjn(6+gNRhnYG>_x7(zif(UQ+Z5fkR>O-yg|OU; z2A!fS{3o<2x_{#IQgj=kXfH*_+h|i_#rXF|-uMe${CHtXQgjJn>qJF6%*ze7T?^+< zEFwwK3ARsyF-7P2v^_3G=XeFLNYPagD^hgjR4+v*gwd$5E-QKCPlAe3r+9kor?Nt11$3fI_s8Yna49+`j=$jnyevgWnu>Q`2CMHz!ee0-HHEqh zS<^^2`RiaXZ~Pl)ICyzzQ*`rxp$0eX8%fbU0%nt<6J~9>EPZj|v(TpKG;OxD>kz;$ zMJE;FDvZy?ftwVaXBaPW!rteG)+|#&i-e)>O)%ILo#^EHVp4Q_z)!K;t`nM0(QyH$ z2c73)E^qu-zK~WIz9`?e(ylPig+WquA}bwEDB=&M=zgC^H%O=GK87b${>Gm!ifVNj zf7%q?xAfI)ijFtYj|nm^C&-!vxmqIu8&6A3Opr(z@#nuVXEnC1n%?qTuz@iJzHOZZ4wIs*g59~M zG``1GyDLUe+@G5F#Qgm$R#0FKj5eAD*(TNf=m=xVa z&|Hd6h*A~zhqT=oMO?JtL7bS%H~y>feYn|Hee7>gbqyNU#CTi;Y>a1pRmOO2A8@BK zmy4JfZv^Nz#uIhIrDMF$Kr=Dkt1NCIyT0s=|BkTC#CWGW4rjXb>u`)JdE;-qU%v70 zklNvXeF*GedVfj!?-7>ZqGaAh^9XfZ1b!VQFTj0}OGqwC7FpMRDtjMB=wygtoAmkc zSn+pLo<^C-t+A;jPj)vhOm59KUuACX&KD{3c%F-?$nekinA{pMHhIOjs_VQFs?KxZ z1GY)M)I5c=XZMNP_P!U@47VHfn@LQaE2AK+?Xe1JpljeW9dI6MxwhO+GPlv8#FC@H z21lBHm!%&Ix@OXP9xNlA?x^lSrTUX1&H1Y39L6Fvw$x%5CfFwyBcET?mzF?gpYXRO z9E>xn452$KxiK6Jsbu^D8i8F|-#c|Fq%|CgCGl^TwzE$Yi{dW78@a=L8p~0oQ$b_+ zP=Bf^CX&Ws8>rGWOPpkhA{2iIoO4nA?WwK*p!;|w+2alV(3#u%8L0(p2#eW8o*E|! zzSE=lFw1g(>Puk}$>QEP*xAf;+AU+{EROd?*N!lMg7aEE&oi) zJO-6xR8fCc6n|h@7Nrgs7G37?U}02Ie`XY)|EGTOU;m-6C7x~JFMP@P6Tplr>c1~D zCI6Rx@n8R28N35vzWA>X(_ZoMxqul})Hf}IX8~qZQ6Hz-5w>YR0L%%czO@gRYX8-!s`iXQ^R@S*;Mv_5G^cj)JUCFM9YebZmI zadi>Ji*aI{ehSL;!UeelTSfqRjDpS$_QuV)VH^|=HK1o-7T*9F9be?`gbt6Dm?~>u|xgg7K*0|xytM=7J>i3SYGR1hBmF23Hc&t)nM z!5`tYw9b_@u~e1*0s~*~*Ke6IZN~Xam3pL85onc7*&6!X?9J)t3R;45Ysh@0c zRXPq3gOB>RENfEr(w!g<`wPVH9RH_)9w79CgG!l{gedjJYEv59Nd~xi?nZ%Q=f5Ge z!9Q_)2##CG(X)($id1R4YBVB=eHsw;3#QUkaO|e=`eaw117EZ@Nl7SCzkeAX9|oME zMEw!fEW$He#rIm;QI)hvo0H0>B;cwaXqB?bRNNOh1FrfLs`c4KdhHqo_}T!ro$Bk; zA}@gU8EHcs&`K?uB10U4Hm0nY(gDEFB|f$szY+L2yn6T1M2N7T<|T zsAUhaES>jAbM*rL*RRN!dtKr32Bnf_%xQIN>_m964he1G%H&VD}*I7Q7uFfipTW8n8aoPoaxvm!~Jw(U-6|o zl0@~FTN;)gQN6I-PL0L0?@SWa$M;RyM75_Se%->``;zfi+ox=zdYo70X0_U-t%K!i8-gB;H%$RXpOJg!&ij-tR88P;ZeQe>H3_{vu$r3_DM0PC{Duq;( zl=eL(MWv+W+w$$(rqZHK%m4lUJkN8^xp(N-|Gr-5d_K=-dp^&;oadZtMEW`RhvIAj z5xY@+eJ9s$REMm1M=W_%Sko<2GRh;KTE65;Iu*=$sY$>(%-?M8Jddhaff%|>;Y z>=n7m8`Y9Q-gJ;TrSvzdg`9f`WPhXDFD8{cpo^h%quQrCy7*oO(?3fpMdY>W>Lzbg z>sYsdoU~D`W3AcE4K}KM>&m+pbhA-?Vntj2W&`@cJ3<@PRt^hfk)v57_cG+{Ms?rr zdIl=rbPQy?S3ox#)v57#`8^D;PZ`_ZYVgci(m+pn<$49OnTk?z~ z>GOKIcBA?!3_GUod)q8|soO}%ItO!#_54%5=_om&d2k(@_%4Zc61&1>N7MmIUYi42RD^meZf4)wF~; z8Y?za>gX(AI0#cw?qt7N?$`p25}4&t;N5Z~(rLl3_Q%+$z7xV`qgsTu=Q8wpbq4F{ zH@@kpc{?RvZv@%js21-y3M((GM9(hqO~;U9M3uL}^3qdz(#_-F{4Q|)jcTzegP49b zZJ*`gENQ^gvnLL~GJE1+&W&p9JipkG^BTSLJP0$4q}BdFRWR&)TrKRdp9wcIR1)Q^4#zpNER%?>q}r?>v{Sbai5XpJYxK z{hsZgF8VMNrk-cv$u4mYdv&|>Y$u=GdH$}pQP~wqRxvxzm*xhii^QBr>7D0qz%x6~ zojJYxo)yPmBJ=+MN5M0*^ZXSZ5{bBNFH)|3QLDJ~Y^Sq&=lO#ZktCdVJk04_u=D%@ zWAJyL8FD@$DQ^Xmp?97SAsopJSpLql=*DgSskHs5q0OL%o#%s?)mMv6&PSZsd1hA0 zE^(KElmbqep!<@-$|APRecA)yM*U3g@(1!Q$p_L~Iu~r;axkUOv7B zy|{T9lIBIZlxQT#xI&AYQ49tjtY^@*I&y z&tw$A;zqO=1T-#gghn~-kH5I_Wrd!yxJhBAEN+syCVnn%gmC}~)^P==aL7>JJrn%J z&0-KjzTvahR~jBZei-m1E#4f4Z26l-OS8L!#m$FSuC80Rx~&98 zt}Ep1;->TR(Bg(sYZ>op(9Pl|H6E|w3V(5vYTH{0o>|-kddiEg^cOdQit?@i*(`3t z((haHjF9unD_Z3*ZuVhJHg(^7$dZ@3`~beG@40nv3@vUX2X)chXz5(s2>nHAag}Zg zEpBv?O$Es;Zh~eaO+y#6SM6qhag!<_M!oy3K&@D+fOG=h1-JN%n^b|IH}HOglv&)Q zNZ||atNq1I3Qs&$xu>iNEp8;i?21(GO3?kqjU+fXdTVHLBcg#5xz~W{zbNN3u~mFq zXmR7yO+%Olrhf`Ym~>Jv5p;Q+v^KQ3@zwEeGU!RCaL7|$)ph>jhL-U0LsnXL29D11 z9S|^!n_~+MT<Tk`c~kp0Dtc*kKE zFT>s8FK$AP5mnxMmX}^Wh3AMs)hq7|7B^y(;)^H)mspk-WI!oI_QAfOosNIfd!6iyH=<(*g>cvgjN{0_=j5Ldznx+2Y=CK@@dYdaQy|`hoZWlLp z^2x^BBd8Mbw>D$o0B=cbC}?y#m%jdFpHa)=#WVG?M2G< zcGM~^ZtQecFK)^Y*NdAyoX!P{oA0<@^cOb_IX{t<_blY~;^r@e@%2HUbKVya7TN9cCiz#%~U6~zifxA5?hgt?XNUgh4xn)EUW!IU{~FX zZG=b=Dggdu&@3*EGq8f{3AQY!B~*k)7eIq@lk!v^vyK5AH3g;=6huQ^yfXK88G zu_Hn}VbF7q(WkuXbS20u@I0>P5`C;i{LWhs>PJ++`FV*@sH$zxqFHrNYwO>Pzkh4n zvqc*mdOhz5#F{(?(T)zos&o78XnVzt4@^Y?7N7YZ^xGCU`BgxE_q|1cMCZCV}kSBd@rDFbOA%{stRbIC!j+! z0UbLD=ybk-^DYw5d5VCd1p>OP7SMHzfNoC+IR7<*0ZsoyFmT5A0%rax;F?qLmD#of z=bRy6Zbt$0O9U(&BVf@?0XHlYu=q{^OTH4YG_sKD%W4W(eu{tzWb?iH}^8v%D56>w+yMKrykwt%}%7jSns0UJjN*mRA6dsYb8vQ@z0 zmjwK9Sinzz2{^KIGbSkmf6lsrHh--z;I}aXes3Y*XkP(;TuV?gY_)*lcL^BrjDV4E z2^jU6fQx<+FuLMmDqNf`;F8k?T-sZ}WtR)Me2#!IYXn^Jpn$Qj2pD%*!1zi_Xk|iu z0avycF!4eGlO_t7yhgy3`vhFgZ%4N+nemc&6S1ze2!*Eds9JC1BB;0v7*Qz>=c^meyEC)5{tO*jXgt(UAfkn=9b)^#Y!F zmS9-#PXzS&ML=H}Gl%t$E+_B&ssaY)2}m>(Fu0R|lEDHlxJMQN@m~QWe-|*S(h5d&QI3GojR;2cX)R!6PXSX(1uPsZVEsG++iw!^(k1~1 z9~JP;Zh#IWROEeuRU_XBY!Go)lHM|Mg1{b;#sY^%+6bHwDHb?0GD_fv$aH~^L~anc zJF-^bhmoxUzmGg4@KpB=feqac1U7QN5O{|Bo503y+A7A|#H}ST-#uO6S#B$V&D7F{}SmiqP<&F zU`O{#1@>_d z3+(5X$A6S`7}4LYC-8i?P~bo}A#jj8P9V_ zR=JsWN4WI`j&xfH9OZTuINB`{c(HrAz)Rd20xx%$2pr?yF7OI>yTEboivq{H2Lw)V zzY;jf{X^hnH{%w@H^r?jaH`u_;54_5!0B$Wz!~l^fivCl0%y5%1kQF>3Y_EKE$~`* zr@(pcZh_ai9|)Z9ekbsHH?o@XEp$DBi`;qw7rRXbE^#{vTF8-w|;Bw*m&>v>NmVdIAPD5|HRDVDNAOC07Z!V5xv1TLhFoD`4om0)~A@ zaM`)#))BPI5zzX5PM!$p5-Em>Ndge18P*M0|^*gJll+Uk&-tA%6y)*`)d3sA(BKW=OiC;2@d7yG1w@e=L z_nlMTcc7a?{&i2|uJb+OU$tLA#)&K(^51+q$>MfS;@04he-kUR&D|p+qM5U1ZE(nc zE=0^B|Bw}Loh3gP*7P0&*&On(-6)7Nw`p+5Kj&8?vfphhB0A1Ih}c8^3n0RO*~KCM zkQHx(C4U~)^qv9P9P$q(!ut=%d}x6~{$cV_kj)|gQ1o8*Z~E0?9P$s7&jvZ^kiX8_ zJ|HI@@)vUMc#!$fLJs-+rKfV2SUL~+`*cT_>Q*rQL;g}k-hPmh4*Ba?e*oDW@}GHz z&0KSM-+r#IB@X$g{chwI#5Rf?)s39}Tpthl*MppY$Ul(rx`1vD`KQL?4Y$0<%Gma% zgJ%x;2YSl8*^>8#RPY`v$mWoLSbCo&e;Jm}{RU+JkiTT1&b=HQ%ojQj`3rrkw3R~8 z{X_mC`JtB1L;fN8Ye4r8`ID}4w}9jy@)we~8zghcKWGdNtCucJulyfIU`@GH0rAUg zX9YHu5zyc8TV@5GEF%zf1>WnBGKc(A;!$4tKMk*b`4pabs&d;wz(3?KdB8qO<(7iZ zM-y_$Unh7PNM#TCOLypP2G1PwPiul5edi%s@i+N+$iF@M8g4i9kpDi2`-l7`R$YRB zg3bpVa>!p|&25MS`~D$+5e<@_+XqblkiV8+0Fr;mUz45#iBCY}kiVEZx!b_>5BVoEov9ZyJ1Z(DIOOk3sN53J`J_S)`3H3GR?y8M ze?}42)l*{g_FGI8@UgJ^QQfbJji57C!`?jQ0G(ccE$Kja^xpXfNjA%CB44*3rR(?8@dOb)2} zaZK+0mdQi@0aKpGb8@-W_hhIpxPlY>{3x8# znu6x^M76gk_)qJBA+i1e-U=}E)O7FfZ{||d?v%MyyGF-*Ve6}Z2;dmUo*xFlR;x}SiN*%daql7 zHDv_EFK<`}V_{Pn0qFs}w2nsL$ua^#SK!?WDKnQ!aRmPb*~#$gmrvn|r&yCgz@JM= z96}zlSVyDV^Y3Kq@6n^fh)awH)I9TuNfq zC0Mmce^puLQW9(KGLZbal!yjN&&}-O1am1Ze;r8vTuPIoUD4$1TuMwZFZ5hW$Ga91 z{#@#q5-q#oUl;gJBwv^eBxp$G9t6{$OC>X%n=fH@Ue!G`m+~c4ZoEfmE)~$dEufpZ z6r%`5sl0Q08eVCI6rQ8qc^v{g_%CxQG0H4cUYA}eb1Cwa_dLjEE)}w8REqt%R4Om` zb@2QbCWB~li+hLWQX%>qp!;*F5WRPw&|E4+e-m{7g-M@o=2AWThUQYj#$R<`j28tb=o@^kLwR?%9kdaqY1=@e`=0G^!mg< z3h^Q*B#k#C;c{#t=VnaY?NNvfOwag|A&)}LuqwME$tvb3#5VBlQ3x?7QerdvbMVYL z?=xE?x~7OOXxTjHT^*j8qY!Vvi^EHLtXYv2DSO0bfQhf;Z0?&pBGb&t`pbpop0Dg z9NtvcPrt$N?_#_I%3ZXHIJ~K>KfiNT;bCF(v!=o(;_#+a(J7y~YAmktGa`P*bg3Z( zW>1$~A5}%S0so2N-GQwCT@|ggJ5Um|>-bmsT^3ce`*T-S{Q|l}BY{ex5U7GF{>ZyB z)YgI}(dr+zMY^iL(Fyk|Giti3U@Hzix4joaI{1JII%jfU)w>QN+)*ruIh`P+MKv$? z5%4(B6b!>`nkGa9Un&HhpVuvz>~s~KUNrAjJi(BsJA-^vs@oYL^JBdQvz(W=Fb0wC z*3Xi!b)FZp_}G1_CC_(;1V*~Ax8z06g+Y`(c7e=C_ytR(k1@8r?A} zLg9a%N~+Lry#(%{Qdll9$`7o4i~QsmHveu9nXJ(Xy@&u|%u( zw~Xlq6O->+IA=B9dMnCW+YIGpKxCine9qiJYOY3nTMLFps=pbeW@IGuXR>vSqijgh zc99M_M@2wLIB`R9Cnjl&*aTc2Nn_fCCDPe#ENfDTC0fa;iGxa4_>trl`h5 z2ENn*@yc&-s>UsMpx%BMs}GHzCJ{j($aQTXmUvKCQT8U=u0p!&2;r4mfpHIKV$ z8m@xdL-JYIgTm9o1=~XQv-W~onHBLbp{nc?5Re8{Q5uw?_O{dvX-}EoGhI~|f-23_ zi)cB&+-tDp3dV->mf01`+pJ|PW9ma(1xLzANhgRykImQ(PV9RMGu|aGSelPz``Agu z;^}Q7>P%pmYi;fvQ<2HzwZ?b^l;}<+IUemCQR{$Z=iMDsSK*pGDRL#^h+l;p=ZDT( zAo@nS%Kk5;3yMUL|I`q-n{p2SgF)X&SK0Od%1}#j!6H9*?tf3*`2Zn(BVA>$j8;~M za6yoBKKWA!iMkHw8*(FEWp^rHS$%^Gf)9fg=Tt-ln_db*xslHQHTZI02Ht=hRoz4S z7`~RN%@|(2t_c@xV0cLNdCO2J z1j*>l35~`7JkvMO=K*Hb4Uqx&!H?qiVYy%<2s_GHzjMMdt?!7Cp{*NStZM_R_#Rkm zzZn+yX^ZjW*x47dV{oyf)sR8|?Sc%LGDKI6#=xV$!St9-F*RklR0ta042C3M=6j?# za+8`7UGqpxeT2&>keIAMisRo@^l!v@WmhUlO?rQYQD8`7AVvPI#*r!&UH)Z;dIy(L zAW>rQ6^MweR#1HpAOX#gKU2mt-iTyRl2bCjoHCxtkV&aQnK@G?P^aIy`9SCD0=xsJ zGVVdRNhrIM?D-8xY6s+KS<27iVme>+`%lS_>_;4`_?d@d>JYAD)H^zH%z8(Lt#^V; ziRy}*T<#8gXM$EbJ5v99Zvt#^TSTknRzTC<&@dUqTi%D_kvJahV(EO*Du| z97JRZtk=QW4QIyGW?b+}G@dJ?L5d?c3ZM>Mi;Vh|nKfTBE0ncm^UaO|%mUjQ1(({S z4J5b5Hjl;BT3l$26#N&~wV-W{fptw+#ec%uBag%4K5g-MUTU^&je#9aSADy|#%5eo z#*1TOM(R9+?2%2KXVBDnL3N!cn$%myP=m(dLY*g1ukMrV`D=FDTT;%}dBIJcC(hnd zR{h2Apjw{&)G^DaOf9wLLxwFM!H-)$x4?4Cr=@(jO%pC3ewJC+HZa0{5*fC91Q+W& zBC^j@eCIRhEuWS05sUKK=VRE}7YXbbTM`-q0*Ej>VRQ_=4h#?+uij6s?yZ=yg%6o`Zxc68p>m}JD7SrT*6&1>Yr79J!ICqOTv#P!s-O zqPayE-?GFg_}h1+IC7IcJWS8WeU14#KenvC^0z|w^@h|!d@|E)g>s&3w?Yr$?}F@B zXgjO2E0U~YwnFEDZ?{6loJi@d(7oW9ts#OTpBdd4 zM3?OPEs!v--{ecg8Naw*{K2XWRryBjb=Q_Hl!(8IiSv)>tPK-2hGi{PTm!qELva<{ z>T(IFch;!eyQ-$jg0gr90x#k6(?1j|D2kQ+(<_^P{!5unzx-oa(IemEg&ab06`k;dtGeN0Z)9ctzs@tgQJ}P&D0(CQ^`0tvH1SA# zDmvpQyeEf?@mSgTN9pJiMV=F3bhJcLmoX^LeBNHXjIDYzLRi6>8Bu7u@nw7%ot zTGxVhfDEi_x+<=}GefPxg$WFqx{e&fOU>4H3~mNUs;RzxVB-c{Q^p5olDc>)F3pwV zGANBqnLwSS2}}gj)2_HMfjN#nzYg084CTZ>qtjbV=ZiikFjA$9U&frb+~dbApE6Tm zTRvpi@)7*F-CyuD1cF$(0TX3-j(NJgt!=PzFL{-t{&t<56xY(4fte@ScDF;fsiP|os zcmNhOvvHyRvmX!V0Jo_m2gnF=V19%Qo4dPQkR5}Y{1rQWzrt?Hd9X8Od|*cEKZAZ|PZ>`S zO#K&>My5=lP*VMW2BuEy4ptMLjpA04J%8Y|_1{k?bo_Lp-qSYg|Fzu7OTYE1n5xIy z2`wU-eK3tc9=!Gvo>$@-bd~fdpD0J--3K{pXa!88>i2Wh2p}>PflY=CMZn2Z#nD$Y zRA*c*$3?EZgSvKC@_6I{?iN9aug1UK-p~8q!s9#;lkc zit8BZF0)p)oe>!}-GU!C-Fsnq#5Iy`K3NW@n-gcrRWgEH-4P+frdx2az9S-!ri*`= z9aEF$NV>&h{5W>@h3pvIq+9It{qfqE>WKWCGCs&YsoV^P8ViG_u?R{dQzj5iYAjn| zDr25B7V@y_!ad2JKbYIbLJ3JH8jIj!I$v-$7Cjv}d>wLdzFzgwbKkY`GZ-|TrlhH; z{(_jg8y7oGE9*yVI?X_7H&Hw7=zAsh%-uIK)T}FxVka#U=e;jzafSD9F9ss|nk$hS zbRl)dQmE^!v3#J=Z#gLw)(t_|RxP#;fk?)3F~{#UG)enwd_--#EvhossJ`XiG?A_i zBBfMHq{7vaYE&X!%Scu6B-nTX*R0aaz=-6$eTpF&ZrGCH7XKWd|DH88a}&1OR8jrk zT(uAvr&acROcy<^l2Z>wAN=mBjz=MY;fs_|Nib+iLd)Iv*l#n9~8b`G3-H`i$vT(%823EBr zfzocGaHJci`>OAaTX0C^UN#Y~pd+$xAsNe{AL*3wTzgBT2Gvc3LP<>|>%N$J2p6jR zaqRg!6t;=@8zRsV+%ysD`x`;fVWl$D$oD`W3FS6^{R1 ze~bzz^uI~ z4D~mzDdTmil-aH}yCtL>KLyo(QYXpJ=W#UZ z*T&RmxY**k9~KNT=MM^6Jkw@|7$Fyp`!hp5jf-lm7lB$6E*i~TfKeGWAs63|Gb`Wn z+{%18w-O#ZxW_6zG?Ac()`F4_qhv=W$|a9XjsMP2V{oDSCi7od*Mi!*!I?|OfGXYw zYai3%K5a3694|Fn+cCJ<(Kz;`JyjVGl3PVXXVfB%IG@k%2hMA_Cbx~!`06O(NxM1<0kMa~BMZE1JknAIIr)JpqU`vXB1|rqU2BNu~r(GtJT##kpg6soC0&!NrcoRq@}jaT>A{ zHHujoPB+6+4T*%SA;a3DRZNSu=Xk~?$Z|I zBp<^|&DM4dZmOZSGXmA;7FMA?Q4&(qEjdX>xV#zG7PXQsZ_<;?`!!g0W3WEr-&)s# z+Pc9_dDFToZUJkhv^Yy!lyo1%OU>4H3~tI>+nEC!waeiT9LGfp@SG}GfyT#TO(>6~ zxLgb#NsWs6!m4?<;@n5iZNhMg^r!B@wK8BZ?t?d}xR2prke@12X9xhZG5>nGG z#X&~6(lD$oY9(7~NKdXbk5#U$+GfJ~h<|Hc3u@~IHc+f%8rcOBeg?ZXk-+!s(8{;{y}YXd<`H{F~53RCiY*Wzu|vB z&RG#v6^DL+u(O+6B3WHPm_y=)&VDXxc~h+xgYp)sqj(;*)nTB`Rw8(@1dD+#X7Dlz z-U;*r2CtCdH$YE8#1+Rg7-w93CfkTxHPvE6#HC68S*Wz0 zkOoj-pb^L$h0twTUW6piNao<37jKgt0`i@O9Zc-)~88>Rb^L=>`$zOZth9cLUfPMwq+ zGAo;!H=t4e2pJSq=Q~0L#fp+rP;W8!gMwnvd6zWrf^~jD{XBtL{3*#fvqA;+Fhop2 zop5C!vM^LoKSIP5)Hl$NWJ-kI8S4$XP>%L$vMH$1;F*F7tK4bHUCXNc2Ru_yfv?Wp z@JZ#|7%He*xBCSZnAUP$fACB}@i47Uui-5N&lFS{y*=QWf-0j|5xH*)ikWKiP|kQK z7gV)a>jC9dR@R{EEBGbW@{jZ_ryc;7b%Cn!E%2<;%;K#`jSdW#fFmDmjs6XGyM7QE zDPMmTv1k_%gm@_%d*)#3MsEOdFD1u~L|7Y)9zEX>C*Dn>NX8E#>aDZjNL_cyrR9?P zw|3iL%J1J8a?TTy?cYQouf-+hO#gPyBqqF=g6)B-G)8Xvx8*=h|2Ew!l#UJ*CWrzZ zGyU5fpr(I&77Dt5(=muEq5iEL9Jl?O@F-^bw;tey`!{;0!m0jkPI9Whlq5 zs&x$FN+{J$;J8h-@F-?deG_=$RMR^gpKV~ux?1e$k^iF(PJR#?whl62>R{I&lIoy{ zMORp&u7lI58~qSOT?gkOoT()rK)gbn_%4Ye8DDXcUk6XDSU#x^cH0h9ejQ}UDHf6~ z4H3xOSiZcegO5*PX(TB45>S=K$W0x53#ciLAFM*@H-W;hqCm$?9ee?(DUDVY%A3;A zF^DUn(wGOnEe+vO%#_A{@WQ1*?^HO|_vI$1`W{K5t%D3XTZLp(EdqJBooG}2z*S83 zqZE7ss7m`LNcB^onpBssZ4^pB4HUi=h36qmUQB4$fOvKHLwASoCL0 z)OGMO>PAN{FK_DLB!n}y)=Bqie$VWqTV`7`oSIBlS`x5!!YI7L57@uLb9bH z0(r9^u%*#v8cSmc1-k-OX^h;|!L2||Y5ZsvO2-BY(?o%enbKGf)Re}B58BeuF^DUn z(s&DeTN=Wnm?@3UNL08q=$#6uy7^nlslH#5XzL(D&UPW$REt2~Mf+^3n@?w|pQK=0 zpepUq+mH-Q&U zHN8{u%Ub(&u-d2!|6B)a?1YA`gAABDSTeLixDJX~bgw1qI+#PXwchi(#2N`nq3dxp+2;_B`QNi?s&tJ{bI7q?QfvPk{ zZt7qkpr$k)u?nR}0tGdL3UthrMhBp#G#bsUV0r`{gSZkZjrHK$Iw(AfnbJ4`i3*nn zy;I>-*SbA9)eRpFre6*K)j9@oC6wwP!MCXv9>q+m7pzZCHN8{uXFL0K@Ww-W)w~HG z=2X%Deq~q9kF3M0S-v)xRqtzm)y(rwjvRVwRRU^g)qFdGp;hze2!>Y8CnJ{7s`&y0 zL#t-SC97thbE+15QCynjKTt~>4!&76SBq7~$6+HCC;9JHri}@>X|Ev_%yF!#ci{0E za~x~xsgN*h>c>E3w#u6N)-RLS)Fs>k^XoZ7&M+a_5*LBIN58OZ>MgTa;+InJVW29F z&-P4-^XRoH@&8$c(hmZKFGPVy^Gu2J18=6ptHLoo^641Fl~9Sd1>csq@F-?Vd@Ok3 zdQR_x_gXu)=nzvAamAMCV`Y4*q>mKnZ_SB0Cc}|1X68M9OwOeW-1G5si6JLLNH&*5 zAg}ZXn@ew8!(6IC!4H6{G;R@^T*?8}?YZd*)-zuoocbq#idF9 zv75B>LH654-5PXwlK&cU+VFsz_AF9i+C^o2{>ik9F_19rqAI93Mv)l3C9Y!-S3)IzZW=xXW%incM=?|4Pl6XNaeAlxyzJQi9-O+u69kXA_P@8bE-LN=ORLMKt+OXMaOTLU$@n0vC#MID2<63WHfz_+<5 zJc`+NgG7aMk=_NbuA`DZ{EcomCEM6;#(r(v&6>~AZrb5-o633tMAL3~F3XX_S*_xS zlG@GX2!`6tE(Am4NiD<@YB!@147D4^CF2QCn^lYbAudhwPl=_~cp%hnntrF-4Nr=3 z4xUyo;HF)JRG4Y1TIt7k}Mia933sls6v8=(hKjr<*Ja#A)z zFGH4wHbNP6#*yZ|JIb*;)_+UFr;(g<2*tsi;g0o`i||oSy<=T>0rN(S`~nf?BX_L- z0}-C!zz`LA|ZDzt1=!uvk@Bj>THEiDku7M zuw(r$wJd=*`SVC=c%H#2DV4;I*UP;IeuZk;7&qw2a;u@XSUiGu32} zoL!cU(3{Y5&5rf^IK$@`6f0IrL0!+>4|c2>be53j?Y_(}sEs(863M)UP(dAloGGZlw3hQ)!#z__+CI~3cpHG4f-0j|2{~*Es*K(^@JvB5 zQ%xSmSq{ksRV{YuV(>8&`(n33uexxd?Nxac%J~V(D(hzuO|Qx`Hu@-4tHh$DUUfHu zp-1l8|V(-$Chp}E%EOpxEJGUU7`B-^WsKwkgrY_EFe4J`7{DA*FHO5+hA)2s4z z64R^RYZXd|1`3yo!dFl*y(-TPnO-$E-}b6H25}|Ss}2U=_Nv08nCVp?1~1&J(mUnn zR>#cs8EO(P&ZU^4L9fb?$`o@*?X41UHd(v&M z+HWy)>JE}~#_kCk>sha*+g^2YNMssBY-3#w5z|=jg?=PcBJ`rK8*-uJh^9oWp978t z&otJs%3e$ET2|%kz3H~G2EIDwmawtTgE#g$;9AI;#u}K`a$dQ8>9(Q>$xLT4Y`|8$%*bLd5nL?sk80zXAG@Oo`BIZOMg>9Bvn~sfLrm zGu1Gx@_;3GEvs?}JTtflzB>H4@_%0Zzy;X|gG(7r`?H6;_En z;?KhPRzs4?x!{?C3Ve0`1D{mRpP_=93^~(Z1g5o|_aJztptOCa*YLgr&lFS{y@tqP zQ&45}MuKMwikWKiFwSyFE~vWhlo!Ac%~RfGZu|2ThMW(DWalX&kk{sUJ5M>Vikb2S z1wRF<()bdMnWylb1~X5&+A5S*ywO*P1I1%SNSS#G-?}mLlqaB|SARMNaV0cQISRg= zrwET?W}eati3-nC=$-QWAIv+xcq>#r>2ON*+%^FULG@(N*+H6DxX-Vidn6%Glbmxd zwkDWTuI6?@#PlPFLn7xv#P%aq-tepEE6|T*N`&4(OD>epA8WFyp6kIg)ibQ}r6qSQ ztJ366zj_9~I#=Js>e(CK*nZ?H$eHRHnAURMv*4NP$#>WB8X5CKYRCo_4S1${GE=op{UI)?p8GJ=nto)#yP<+&MM){B*P$OOCo9Xz6 zBO3aiYq#Ra)aiB0*6wZK@=||21YWk5+prHE^9fPPPCqaodjwk7A}Dxd^;) zKSJ-6zu(xgbaRHb13#WyK97N|<&n-C@!4*)f}c)nFAy)jU@T@?7;QKMe8P%gd?zRgA9QOx9GT_h@;i}WsdI|CEMGw;P0nlNWge9bxQ^m|}gmHT0~q)XwLd1f}uIpH0j_+;vD%>T&tXilAgJ)LNGM<&f1am%yl+`p>%wYU??4oOV7Pg z`qg4}AJI=$`TyqP@o(_W&b==Lu9KFwW~x8;j=_SNd#?x8%)RTnZMP*qFT9Bf^6Mr; z&aFbSbyEcL2HtO<7e?2zZr)A744^8FFF2dJ$v2fv-F(z4l%5qRv=#+^5zo|3zKU$> zX3kdoyims=u7v95bntE66duJ)-TVZ+aNVSLm?@at!c1Z3OQ8d>bU0-IN+63u0}z8w zDQRBhS^og+FOrapNzS-?#H~{sGtt(8nn>F}~B1 z3*}E5G}#P54WIW9z=l;;TXNU3D(Nry2VetVosIBG<=h8v>`dWm$eEc!U|P$0-+^Za zAbzG#C&uuGzUUu-Eu;4acxC`9qt^ksZw4S{s>vYvuAdA*&wb<16#jfIR8XuaDFro! z`4&v+7<8_dygch=zo6Ewr{mX=obzg^pfX?a3+lO$$UC8ex&|UTnVCWvy*P5%6jT|#dEl9XVy2orjI$h)3#wYI!^yh0-gTIDBr z?xwQ-0MYc4hd^+6Q?2IIP3rAy)Jy8^HzOG8?VIN%_4ZF780sY%m-LdiH06`Tzs03V zafYOq91p(jB|n6prkC6>-R~u5K*IErn?dz^$#+jg>O%9Nm+89SOEToVCM4TSia_3k zTCRD<-r!Ca$pH$U1yrRy1=RGCH81je$#1Pf>A*nYLQ!Z01=CB`g@WlNN9X8I8OBEH z7{rxOFZn6>wwDwh#Y`_b6p0G=lJrjbxrJVG&pB@J(1i}CG`?$)MWM#Wpfis&@0%w2 z??v!F$B7%5@}(r_cvbYdDz2yA$=82Og7-PvghWn+i0vhZorS*`(C>4shJGYdBJ>Vf za-p+Za!DfA`?wSFQ9`qx3ahAQhTOHR$^!7rG(GUuc?~|PoCfg5_L9|_ySDKKrnQ{6 z7Ch5SYL}Q^!)ti9Ya3q~z3t$c##ctK5V>y}A2ZeDVVvb4jqg%7qSsUPJGFID-4|Z0 zTi~i3w!lpzZ3`TIB1-%x=6}{Xqx=^57ainHwR#rR(0uFsi;`O4Ap}D$@T$>CEzm)v zp%%!vqy_%jluur|UP6~9#Tk+o*b98y0w05)rUgEHwci2Y)Do7P}^sE z4exRA%-f1kdlqONzsmfEF3IPf;&+1c%)oLgdg5CdYAUXdhvk(-zMw|iT9zUF+IBu# zG|y2TI=hilfw9PJz_zi|`H7#lu|~uBZq>kDFX5SK+kvkg7VySj0uE&1QEA(OpVk-f z-xdNs>nq^%F#^8079iSx8#)nO1NYO6GYt{QO|>n#zi1h3lx!U-VB1^)53CpP;IjaA z-P7@*+VB85?H<%Nzj-p`%o37qo+6M}g!!;OgjRG9E9vzV>-o-VBwE@0z6_l-K?uW#7}&x(A)r z_zwuJ`<~#c_#o;_-hSxXc=@iS)JPPh)JPj|pgZ5_?!X7C&cPR_eBCmWIjegGzBFll zCXTxOK0YHAnbSmnIJgljY#MJrfjlQ)75Di%L%oL!Y2x7${h1r_%bw)0Y0B+mZNKLb zSH(lV%TQn9f-WDS>d&-@u6nm? zAXUO(jQQ*iBW*Z*b}uFNDzHQqe8AFWxhH0lwmAGb>a-1!#41wX05!3W7$r+YoHv&} zOkyV)tV8Z|#DvD%pr5xQODnj1gE8?TS$tR2{eqa#cynns@$FdLB4~jzVkL~v&0>(7 zDuc#URH{NGQHKQa_cUM^$p54`JVh>;a)}O_H4~~8-0p#doNwk$xx87V7v(ZU9=W#yE8#717K6fVMT{cuXGmb88-v7LV(zz$qm(qkc#E;^4qAj0D6Z=cISpVY z`GTF=7vhT<6pS}_Y9G+EQ0iE%A(KG(vDUu`h|q?I43Uo&k~n5_=q& z``#qD`6GkGTw)172NTRj_l$nfsQv&%1mn%^dnRZNNfV4Ww^3uzT9ZbsM1t3m)|)h9 zF1hYA#Hv%{5(INteHJW0rTVtKJB@^qxUC}LyYlYMCqQf&2(dxH6791QB<4NLy?cU}PUWi*_HW?o=xQN)gvw_KN4TC+-fyiCN#shPQ zTm|zFF-XiMmhe-QV6xml7~27g2*#URsQ|P?qzT5G`(IjC4}nIkM1qAaK#P+`%q7>I zOl%KtB^Th9Pi}2siSk1bB<4;8RwA@sg%cN&)_5p_A~K%A0mGqo19VF+ z9tFlc((1AN$M#2X6@#x5TSx32Vw;J5LTo!R%9V&PZ!T$xJ!H%s2*wcH67Ms3ghAdC zhZ4ZZO&lSELHBQBk4y)x;tpV09IxEg2$GRFku(X42r;(_X}`4u##^EdgC{{P7%m3J z-2SA#cdk;QL85_j`%Oi5jw4SnzLV-YGhk&dX@c?Qu0-$x8DyaYp~PLH1FS@XqDY#% zoi063u3&ug(S4Ia!RSFkeEpoX-L&1P5Hto8M@f?)83|(U)vOrthrtl+FIF33iBHLW zlDhfieg~|Cw?tb8h1-=FMci+Y&cq-FiMhnw-ZLS5Icb8)?UJ?-?t)ul9vQbWxRlrh z?SRQ`9fRrZA+niR6JYMA(_nrlgT!272|witCg07O1&#M9A{cM(%N;;FOqyW4xwq4@ z`v_>nN+kFvX*EeB=923+r||W>%^Hteb8_1OOPn?VL1OMLz)FPHm)s^-A~+DY1ceh9 zk=AD-f+8}B!D*AB_5gHCZkPtf^`xDLy6CRF1i@PvJWT9PVn>PHN37hXz#bt+xe^iP z%_S|dkBrTigE1So#77LCFa|;15?Nz`k(>C93gTrv_xq!BBTpa_%ZRxEn1za&jCxi#(z;mWur zqIh33HjKe^Vs*O#lUpqY_ac}$nb;9BM$LfvrVJ8ui6#6LC73L?%_?Y|PZ7a*a~Jgh z?Gn-ik995C*{Es_YBYB`ZxPPM8rz3fY|-jqG|vv z4U1s&MK*E7X53RpFfcs7@>oze@~6#3jb?!5%7vbBAZnC3h}{rYMl& z=g!}+r^YbG#=x8q1wTs|L+dxFFgHF0Vv;3OkOVQu3|sf6=FYau-+usj4Ca{HKR*) zJeh}QkMuE~jY8G(J&Wa$yD+E*&27Fdgx?Q#A~#%=2caza#tJIgKt#+j8@6>$Rrt?8 zE8NyKRiRm5Q!?C5ml%lnF^n3VsxZnbFkzzLr;sk)F@y?p<6|KvCDV9dDE*HP)!eC; z+ceCbR*U5pt~Z?BOZs_SQX(Toyem+3W8LvEqC)n>^4p=f2OApMlU0q!foD(2yd8#B z0|`vUnM;HmN~pZO;PapBv!^kPGY}N)SP_;w;L4sJ7LHSdsW_FJPtRiKcLtJJ3EIhS zvN4OBLu_p&#k%QUSdW$GvU=jp6_Lze7-dq(`6F<5tQOGjj`*>zad(`!+p!^RiKFAg zVr3o0KTPj`DP8s1l`j1rU!{|NkB?QQ-{Z@D4xdS)-z!BAC$*bm$+bHT<;jHTe(yhd z5JWddIVs(s8%rxj=XH16bX7YKdE_;MAgV!wtBl|lL?;FVc=6)wlk{p~;QnCi6`Nm=yHg{Z0%a-J zry(cRkBB6Lkv+C4RpIJ?R_JnXs=}ZZrupr#F%a=%_p8q z_TUQ#eI=Ngi9%SKZX zlCYP(WQ`Sd7@HHs!=O*6~$xlfJ5i*!y0On=x- z<@b$v+X2^6WKCE^XT;`6RA-JPdMsiJIiBiV@6O)2yhMM$$jb2_NBjS5^T~VsSynj|WyIZQl$Rj5GAKMs+m>BBBy7h!Y z_UCx&47sF67Qg=IsA>at&X2F?iD&kg>`2P@q6S)b8I7DJ(4b}AkvwrR1kduS=j~=k zLTSmbUI?-yIjaV8^J2<0s8Ri4^nEIR7@koEvD|(M7&&K0;$I`dq~*K_J#o7Q2iNP# zZXtDI_D;*YKH=YJAy z4%`8&Tq2UaIN}#$PBY9W=u0+sDzINcep3Fhu8a39cyWe^@BL(q;*p%5zP+@u z#$HZOn0sBgJ%SO61DoiwsH)dUjcl7uImarA%pbIv@`~A1m>Yl0rfuc$P}v@;rMWLy z?kxegPVCE8;49;)$nHpvRfwMUFYe`=pu^n&SQ5p4AXNb9NOcxi8Q87J{rlx@TVA8-o56kJ3`f zlBRf5OIQWx##f$cxPM~0DpinuUB&t2hWolJN0=JD5pq(aiHHK5*TDs;3RnHJ!t6z< z3OP+o47b@Bi1;zQu_jfahgG2K;*y^Ry7c5)D$I=!fS9EJ6?o*QaLszn9cH<&hq-U{ z;VLVf{zE8gY0+G7No4-Qi;;Efm#XmnKPwD4KULwpd=mrPQ*xid7`l&0RhVKGxKSbs z{*DP1Hjbjg-1uyWN&4H43Z=j1Xw6+@xt#)To!DYL{gA50y`Q9ML(YBYXe+v^ox4q& z>DR|ZG6~y5ekRZUnA~tSeh0Q>Be#*nXCi(fPx&-e;irFA7=&*XB**YRJdqf9+FoKH z;>Ym8NP`x*thE((4cn2nWwr^4KLO^8W0@|#V53TytMxpghKDBxCoA3JHIUryOg z8<=`&62=WPlJnB$YhrWuaaV1$~zYQeajNg*^^~-d1 zQschS{JqeML8I|QIAoV|(>oD03(piAC!+bw0DF1r;{gEqc6 zs&@=F2s!T~e8Z!mQjIT3B7Xw%NRls2BCq>6UG2bwfX0_4kq3T~t}eqCQ{&5%$lj-V zsA@bWiTozW`S>FNt+$CWmD!N8PT<9~)Z zHOy4G?|{B#4wPnv>3THt?)*Gm^{<6Q+^XFQjdb4SU!<#7$h)g7?;Momin%a)fAs#q z!JJ=E4qO;CE{Vojs%s$Td#{uF+n*_MTPwgi5ZfYXVTG}d+w$%Wtf z4_IJgo|u?X{hI?YG4fs%UiGFh+U7dk_o5J-2U_LV+{7}xO^~u%SI)!thecm;ao0BC~^bv6G z$%T!r=R#da6cl&#B=|4voylw!ryuNHqN^UvP=6s83t!FI{G(SYb58CNNplH4I-IoOiv~go&7dQ3$SyTb83Wy5UYwvpN7pZ zimNJrQTcQmRCU}cXoWQkXFAnaF~YN?;8r`ClWBZ9RdV=LO-gRIBTv|vDkxt2Ar%`q z)qgz*#eA0Cc9_X8u_J4IG`v%&hJ9_qqG@d4Z9bl7u|5$*BprEqeX96XF<&1a3w z9^5-a{eY`*sFPF`LhZ{>Age+eQXf9o}t>*$XrS{!U5@J zRn~*(q}WllshPQo8OJX&>qWaP%YOn(kiURr)x9#N#^P#IOR8u^e34LB(HSS<4Smt) z=;*wIO3d-+&Oglf)9_F*{(MSL;;+B=kK@l>M?>S!7tqk-Pt6aL$Dh1OcKn(9pMM&E z5|oqirxPrc8GlN_b{LC8gL?d-it?I$pECZ85b`0Alg1xS-uOex_@l`e{+KfUXmYKe zQpO)megkAKmHhEXlb0Ux#~*qc$)wZD>-Dog{?PYGrby>z{Sq2~BzZwq&VAi7IsW)e zmAmNI(D>uirNSz2z;DMNe@^=S_~XwP;FXB?57t|ZKMBO)k3ZFzb$0w=z{w^>miA`+;S5bWv1)EqOw6c$8NAcu&o?Ll8GjBB zNE&}io<{!=8h?I)oQda_Oa`1kNJ%^Qe1H780wt}-p9AnPvmBiXiYjf>MgI8nmX+L` zEUBVrPm7rGCkyI2qQFM7h=HQc$9ACj04DT6@do7ne+G&(7~NUP(P5w% z@r^%FbodB)-AcR)_6r_rrq}m{7$`orvYnh{S@h7~`UAyzu#hRS1=*eRG|bq6;-Ho7 z?Ig=8@BHsl1`4{PythG48YqM;uLsM@kC`n4#XY6}=Rn~nkY!c@DGJJrS+C11c4ImQ z3N8}%{uy-AchH&m1QfD`n&ekZ*bY=^Np zG^jgiswl6y%1B-$>=*JMASZRwn*35EBYBaa$;+bnm-g@?L6ZkK8Oe(TO|I=`BzMx9 zdYOggQ+M`IawkwD)gnIfG#zg$MJNRZ?O)hPG>QFfgHR@7WOGnaPn?s8%1 zaF?YFTwrMe(vbyR5D=ul(xi8!BUJ1QzYAWb*%VuSR+3HX*a)&&Chhq{=8`<4lHF$MQ48|q>T9)?|e+{GxT*t{xpGA`kD zG0M9Ym+Y+RnMN0r#WT9tyz)jD^MoSnwk)HIc{q2m2P#~=i*2ZQ@h|%f6BD4;leK*g87XG(&cqr#t4=&3PZ{LFz{PO>2O!UyT#WJvv zdm&QtVdRk??588~4k$_FD!Ks)dI=_b;fv~p74;>}1&PEbkzeDY=4QkUOB{0}Y|NZ=KRa*0_)6V#hpZdOK8Y8LSfoN)d>vxrQ} zR;6IJFpC%%&(O=wh0q&!;HB9CkhlQgY zls}V|`M(UxL#QrBQVtUIDpU{3bWP2n?1MCTqW!k~P7a{ndk%kb>kp-`(NIc$VLXbK z$oC!Ei=R_cDsx&QUmdyB9arisEp;cvXHy2uA95fQMSg}@E_Ely=TS!gb*Y=RJVPyY zr=(iy%J_k$?(4T=N=&n;(iqPLtpluCpYs#z385l)LaR&a>_O~MBN2WC+U?stO~oJA@48^D2C zl!9l?wSu!K1s9rU1!qwTz8^3T@sv|5PMOAOp?J;8uUaYZ_@XDlS)T&-UbV{N`Q0dM z+D$B^S(GOfS!p-pp5RZuYV~j);^~7p7n?;5zQwxeEK1-`@>18H;bk!OEQ)U8#b!}C zm_hw-vnVg;^tPo}U7pC_h;8q>2{uGVMDZ5q|FsFusAJ4Bnjwa2g5kIQIV6!ykR%sx zf*pt_n_$Yf{Z~O8p;RKIP&Gk{BAmv_&@7{egkJ|7Xo3pvTP-xpQ1G{a15HrDbE=1C z84Av*5t?Nv_+h}@1SzLhoH8w(X4&2>gYs_0B|GaVV6O?v;u%eFbWLNH;R!{SsAbGD zJe-^0ItVY;1l!cU_$=cy$hZk!<7Y7S+kU!<7i)qgp8sDb@?OrV30~5Qo8X{J{3f`R zs;>A;-~MY8Y@TB@!4-&+dK6qu64?Z!Km1!0{FHbX9|g}s9HCSqq);_Mih^Z%!%!1E zC*gdJLQPP?TL1?PP6{5`IMf6cT%t*+2`cy%z=0Qj3ZB-~Yl4(hD^8gfPR(Xs6QsOb zammj56tLF>W$}zAxT3ky1U;e1>e#|)f*#IIF#WQNH^BptUCiLLprzLYfAKSzdK9Fa zc(Eo}@znqN!q3Y&ttAWL2FjUgYv}f8sz;HP$T6zH1er?pOjWyMAmWZoDI#X4>tsYd zJKaMO_Xi{X`|MOL9zzboNT7vG0JGElKk3=&%ScMiPVXr8|9i*vC}r!(V7AB@QqP;6 zR{IgN)6GQlTS6l0`0u#>)ZDg_AXk(fTi=_V?uLfAOwCYJ9BTACu2Y)ZEfVAkr+Wjm zyUK;CGuy8bZ_MhF-8Y9^~7ONiF)$r znI3dmzxT|x8KO)(tcTvU)rLV@4@;9w=h4_XsBNI#-lhfnyEg5R>$VK_cQuKF3EzB9yw^hXL+m9@T1O_jC2OjMP%zD&FOc5J__(;_kx$)HS6;a~G{K$_Fxj~hB5 z?*Si^L3qI`JwQ@zHSArpBRct&$XBKRAzzh@d{r{?RY~Tn7j#tr1$iowf6;gxEu7dc zU*f3UowTo%mLM^@kp3bsirz0G;YOX1czUYDRb8YTX{O6GMemVUp^#k=?_kP?LtdIDU|^>k~Gmh`5y-FNRm*N5b_=-R1khPWSplUCa4zhZ$Q zUpbMnty`s!3KL3hDI>ezKQTZ3_+u7&mq^gRWrTFFyS|0URk~$}DR0OXm#@HE)hJbv zwy_I?B!KEdCV_pKCKyu20ZM*2YV^x;|>7c1s}7IsLh&J;D+e!Bqoy;$2G z8KQ1a+?TnQ=iegTU5pX1See1Nc|#OQ8zCcPlQc;kCT56MlN3q61dq@=ag+2OaJERRNP3)5<4a;)KA>%>HA(DLM^bkp&WNO$54w3tR_lL-L>6(YgPjHRl#IxgK zh}5@-hDcg3NzWrWMAqreL*$~X{UK6%zEZM0L|#0;8o&9HaRz8RusKje!>$N!eEN)bO_ zm5h9aM#tVKpz!McP)eg-9;JHJ^L3@GO{TrCACMu64@5i~_43y3MMphf(?Of=jyLKV zBVBi61Qflm8J2;=6~Zae8+_U7{->14mG8f&^deFjF#;*k6u>K!mr{5N;1}gxn-WOX zzMuHZZ{M5gn%nowxJLW-Okil=dSuDlzJDFb?fY_E=qUiD9-(Bz?K@9?!|nU*s0?w} zXcRNhz9|~H4E}5T_KO*O`cH>#2E{Skcki)dGDNqrNG8x+FOp2Kx%$b3o2z?mhIkr( z!RD%!rfROFOLRRlJio{okzX{ND91J5mD3pa2Zqb za{uel%4Sz6x#j|XmRdbEL(F#Lg{#4H%lr{3Mu@#0V%pp@yGAB{$15R_enPy%XJ?Oy z+~G63lFVj%sFoMqae*1x^@wfFE-s)sZBWd-hg2$nl5JEWKn5VN@|zaWvG)xcO*pfu$et* zw^k=W6op0q4zmz@W(^kd1iA4Ht^jYKn6jJhsbmbJ^)Myirq zImGqzR=k>xZ+l=7BU=oW4F#Kq_Tew@s70^=pd1n}-Ev4tGN5sZN5scb4#*MP*y@)3 zA(F0`zs@`;npM;)`yHx^dfTiLRwpE=+H!(+tDS3zGir+YlT+Dos~{fDk*CY}NvmuZ zT*&y@*6k_cSNG#1Rboi)t8s z*QVWydICr8>-qslmSDZcT^O;whuU(w=JoDFxW*H~GeF}3=b5SBw-egXjfWlTqUZvY zmDaeGZ}lH=l)ChqR|Xqtu1cNX@B^;$Z8-gTAwS@#m;rbE;#5p?dFvOmzD!RQv%XAL zFK>J2lf_wtfBpn6{~}~Nu)JM@s+1Er(kb^V&;@UB=)D#EV~hET_}}tXDdOj=l98`U zGGE^EwqpLD?x4!cv5LKMJ6B$7D^iS%A$i>i%+}C#@SPcACH@+2wd7$W{zA*^X3_xn zK}oDIs~*NTu(qmahG0XyLjdC2fVd+Fik`-LC5p;WzwUe1%&?u0-_;x9jBP z8R9YgO_~}`rSUXYq#u@MfJ7l-5c+Nj^ZykO{Dqae_aOA-VWW1%r`|x3iv(e zW4h*P;up9^FY;`B=tX*MnRl9Kjiog(deIoX60ckWs~WGW{-?DDY5MPLjpv@q5VfA>p_u%=<#|Gr@LH664mS6(AB zmcxM;f}=*w%rEZ7U&A(5?`;>rH{FlvT91FYM$`4IduY1)jac6CZ}Z38bj#sFH(fdYQL^Fj zFHe5MO?US343TjH#SDyp6fI@b_3N>I#4l!O{6iZ+am?`#XIy=XY-d-IPv5)`WOYEhIqOgUXk(43$!*_`Nm%GD^z};5ENPy#+46 zOA&{pCdw$B_5@9lS#|~@ZQ3+mel{<#u8>(;4VVn0<*zqkIaN7;LdyF41t(ytvw8mV zu528psrIP74VsdEL|5*b&KaUG-rko#Da$C0J$*5GR`qu^tU99Tv4omcV2RC9DYQA*#;4+m^YGDmuhc#!J`nJekBy9JEZ!CF^W%d%e*pJA?y?X)Z3&>Ic z&29TFmK`_*Gkb}pPQlE*14#EpCh}g0qZH<5eHSEhIwJwoDVkptPRMUi*=!!B~5G4K#bSyGc`@ z4pD`B0V3J}mc8|Jsf99XXmLCL#PU5Mxo}r&(HkMHYW?n>)AIL2a^W_E`Rw?ad?Ne8 zS6<$QGhd?->sv1~BI^j?xz`pD*`?5bLix+egzZZTFExcCYm~-2Yy31Cw#r%7UM=jW zg>ubK43Sk4Ca2cuRoU|cLSl%lSz35^K&WD#*1`w1&`7h>Z>)BM7D|oIqrhnd%HGc- zkSyU(D8DHB;we-SUQ(#$lPQ0G!#{aYli05s`<)6{M^^UPZ41TEsf~89G@1=UR4+5u0U=7jwLU;do5AT@wa}BQxO> z5T@2gz1=R&sAlu0K7~yn_$GxU+>wVMZ=qr>25VvisJSc563z!&wlpl`JS6Y1#ZHQR zPnaN_DO$EXEaS+pfRJ`6BCiY+gi{pH6e(L3mZ`|22Z6Ayp2MSV(WXy;T-;7cbc$mVI}?ANHk!Z6=bzNJm?jrlJAXuy zKY=vbd_YQqd_X#nK-lPK5R}72%A`bgXB@9kDgUr@cyaF5Ei(X{ta0(vPD`}uhOvJb z-7qU&q8Czh+hE2*-|DMUD+|9Fjk!1(I3JD$sZ!bf9)y8(*`a7jFIwy*9xzLK04?T@ zcnP-ubA?5fUiAz@5u_Ho8idmBp_eVuwihl3)Haf+k0kaJA()2KuUrx^KeGnb18ZIv(h>>w)ea@8w*?dSu(8-w>c9+%|_Sv5hWY zGYGkK)RQw5=<8NoHj3O+K*kWVj}iBh!#H`EkONZ;)$7oB>JJAxA@|E8mbjZP59%mQ z-a=y_!oaeo2p6kYyxlUD%QEFuf&rVX3(4m>gOX#)43 zr6iBtjsy;l#_uU^?RQypL5ieq9uKEOGCP4JG0ie)BIkC% zOU8m>D>&yUfDZ_WFi_@wOH{rVKt2Wr0JxTb{0eX$0kDgJLe^@pV8W@7b0B(+101y; zG~m|(e@}2a&rak`af*MyaA5;B%Hj+LVL8=K5sN-1rUtOcqtGmz=OFurWJUAJ#D|vX zGy$?=d1bvI+eEVBd1X&QMjwT6%jA{)4%tAGWm^xTin(Dq^FOl01$-jJtz*%8jK^5# zBMsLziYA;oA7hxtb~v|zHPG**&UJu4oCLVBwLw;!s-K-2Zemdv*Shl`w*Cu$bKZv^0K*y?lbElB50Yc>+rt$j1#KL|c# z%`@PfuW?S&e87jT`5w$e!+tG0VlDDzjc_T74#m3IJ&Ki%tQq;_RMsa$maIIRBbmZ(8{V_W+0x3n5wN=Wr>nF zXesM$HC4Nw8kKt%D0#zYeQ2U}?^7Fyvd$Q2?hK%`TFv_2irW3eXF0GJWAPJlr3-hpViuV4YanGAk|jZWfiD(5=|t? zM|DUo#BOOhZSH5v<<=lck!4HVxdR_`B1&s3tHcAA*h|-K(K@9DXBeRWGy>G#S__rN z(<~x0kr;y{ZmtbN0m~`1hRGdGvgA2~w5$`$6uchrJ6Qf?b+I0i`lmvlddv`k6PW<8 zNL{cBSPthg6gsk??d~iEadz)o)WsWF&slp7 zc=8hrZ?sBW;`MxIFW_JP$}h5Buo8Z6cM7e?;mggTWLp5f5-?4DvbG1{y8u5)>>UC4 zUBJH(yvw3joHQco^X0S6d?M1M7g7@5o_!Grxt5K8%oc%A!%3HN~E) zrAFwiflh;`EOE=Bd?M>?p!%l)Zi?@@WqlEVw*&6;JlJ3Ii*;GM&IQ1)5&Ji*UllKz z#0lgfJqPeP%bAY{g{1sx-5@Dy06mN&sjM5f*hWh<%N3$>&R$QipRj)=Vm~0QmREvV!Ck2%wfi+iZp}!4 zL0+&eB2{#&Zo#L@VuV1Fc>MTz-*9n-kf}vTyUKa5_VFnBrBmL%C2{aaL+V zH9M3(6FvuFR7Ys&W1kO~gW5?mYA3~=nlCU78#b!zE~|@+meG)CC7das-9eX2^JsH+ zXxYj?F1` ztyARVa5)O#e#{|S+*t?OXD8yKa^Fa#M(FMqfwsk0fmYP1^di#+M`}o#ad*?8?N*{W z&f}mRqs!@$UO{bKgJq%e!7d;Li)+?N! zv}{dS54JyJlKt^!lx}n0c(b%@XP$UPw{^vU(-~F^S+{aRtgtSOiTaY#pBZWaAR&C( zM@CAu0GNa%>Frn6n>Y}5Fy{7FX3{S6n_K}nFW!qKIZU>hP1TX3@yTdy!f{qw(qx;N z8-Pavu8J@7WOfX|+X2)5z|5WjxG>V9{ehVSOxRnQNV{(*$Ro(t9OT2wtZ9{Lj)$SJ zoF?}uD_v#}Ym^*0$03xrNZqG|wpM4>x13!d7p;JV`llv4<(FgZ&IDofMF^uoAfsXC zO<{s?c0hK5A}`A;E4YFcKbBY44YHcpv6%UsArsF1fHUuli_EP7_zS?F;RA`8F9+cI zsF%^J!9HlhdF#-^;_k0yREL$yJXwdT(A~IL9e`k9neC8 zN_$YBySZbQ@u2m9WX~?^K>`hg95FJ>c~CDvvg;;1=m|iw+h%GgZ*!A-0nomza+&r` z3-M4YBSg7cNmNL@Ce@0)UxRfoA+VVQi!8FlO~kA(nF<^N@KXXC8qDValG{MJX1RX! zp8=BBK)K5dunBTOZms27`=FO!A-4>Z8*HLt_QKVcNEXIxf#hNeHejirjA6k%hF+yL zsVhXj3InXdwQ)hEJBkIGRq^T;voU#n1b-FBk@-S?F7#>oIkd$_{3{9@M#U*K>bCe8 zKMNyL#hFBGQ687==;w{(d)VSCTu!5(x5}S$aM|aRxTv^T{(KxiuP0S^(NF0aLmNay z@=2_Ml9ys}licFut`D1*-v5*A)uZ)7Mwz6m0HY4=mW$ zyPjLHyLY{|V1Iqx{-uJ&kqIhEr4FYG?rmE@U3WZPiqfofY5W7!lKLX7e8}Y6f>%u! z3y|}+(3E_Gf=VXucc4(=QPrf4#EaZyhtml5Q!rvSs_CoGaW(M_Ou`kv zz}1@+jQa|~9~9jBHG;%B3%hHUeS@$@H>(02zDyf`YV^Rs@H~Fd=v||yRj9%k^bPr= zmsO-_mjy!9xEgOz?xc5(ner#Oe$h|%w2)X|jZsYF0jm@Y($afKi*p~cLMFc&qpURm zSeuk7{uIrBSn}V}{5d9H%8Fh^8N8MGc%OD29!dQQh#CvD3Q9pZmjS1dpvFR8<31tb zDS&A#sIka|v(^J9SC<-#wU$t^vc3a@URc&xdJ%?G9W_m^JT=xzr+F)`QXHV+2h~P2 zRk2=Qm9v>Mc-$*LwTt?*so|#1QW|cqu?knk1)9P9-_h^#om^mx3bn5(Q>P(4z=wZY z3G37zwy6C`Y1{JcUrm(lw8lxvmk_ znEUh1SQ+Bh)%^Q#Z%Xh3gd+9_gtXnJ=I8D;w=m(tXOi%RBy`0%QokYye>ks!Ko9tu zwsqcP7~R6DKc5MO!UU0dA`3b)(XL2sgl>z7-HpWQ=G6S6s1#!-qAyl+StZEIBT!Oj z4N|09tXauY)hM<9Ksi@2>4^6*R*NxF^f+b8`zd`(ynRMA`=*)WeWLxdcc5`7KJ|<#!cZiTj@DK^`Q9M6(lOl8=`;Z zy&odBp|xu4HUEQK(-SpI&NVv#;^NB7@#(8>s9ScfIY_<9-33%R*Ssq`nnYt2(Rx-jW)=q@2al(R$dqX8Dz@Vcib~p(!-5bIrm|82)<0g{8tbMiMPSVCR|}JKOAB z^P@qy90Yc*nSGVb&NaUog!Uk?bIo;KY<8~s+aPoXft_onb%nBi_4c-LAZFSX*2&`(xj7&3UID@4+Q00V-VbyIOF^iiuQ_$J`1$L zV4$y>Xri~x&NU{w5U6slsp92a#Gb=VVdt7ZKv2##1|fGsA8ctDiX`A%BO68TaUj~c zMj~$4zBW78)G$=HK;vQOn)~|Oo^y?gQurD)hT%|qxK(qi28qVTq6*o$=3PxVI#?3a zt?Ub(>|9f7AZs|iz|){QaqK#%Vdt99HS5eXo*HJ&fG&2fxpc72&NWTE0?1~;&Ncam z*z8<$8OcrOnu%I;L5ieqm4I^sB6hB6L(vSG>0HxpDAO#S&l#JFR&c=VT(h&O*GZi|*V@{-rk|`f*=U_T8g61y7uUM+ zK_kJ=HOq{g{H);|YmmWyWjs0+dC_R+8Y&Zxkey%$oof{Q5a57wje?^SZS7n$+|d0d zV0NxCi*wl|H0tY+q;{@RN*)CqaIR5se6k&Mu2JxffCJ7o3jPytz_~`jQ>WmL&p?tx z*||o+e*k9ZnyYfW`i>dSHDjjQ+PTIU)12dg1I{(1kDY5eUS|iLYYf>I$k@4NlRpYO zHKxJW7VA3Cxkg5jQ(`Z`D?qT=x#n*_w~2MQ$=bPQ>~u``uZN=htTFzLNIVXTcCIOk zb3Z)i8rh>JfEk&JKsa|o$j&u0{rJwXS*V=3P`l5%!Gj|=Q|Em)l`E}DWjv>wpxw+5*D4N; zhm4(TF30lCic58g8R&)Dx#kKNW36(oxdmBZic_qLn#{ntW}yL})9^;?6>oqL&LH?Z zuyf4}zqdQD17_zM6Rw?9Qy)0jnDBDI>|A5Qe*+FU*Kkc$vxCkx3O)*$ookkO`DW*u zM__Me=NcN7xu~&dSI@a70|wuKbB$6u8F0Y4M!_Ed4mj5+xE1WC>|C?WPbRSp+0o85 zMQSqTPwQhzk;7l&EmWy?t~mw@JJ(z=w5)`d8m(}*;au|=jBb)r(5{5Fw;qN+f|fc& zfpg9H+O~GCd4Q_Jm{JFvYmRANn(gyMP7dsZ(l;kv!Or6V*tuq%U%j%Ut5N1UJb&1^ zW{Z)h&ygqXT+`$drZliWkQ7;MiN~Q&JJ&?&*}ij)tQ(j1L@4K)N*#1r{nGeXBK9rP zV&|IH^*K_zr&HwCjI#1mw!OCUyL4FJ<|*l<}RD zkh615N(D}jhD<1IrPgo&1a_`Tt>LmpOc-(z4Vyq<=b9Tk2C7@cen zLel6~%4!v{t+-_8nr=;O?OYSq=Iqw8Z}X^dYBjaBb4@6oO2fHN6RO#v^qCNAW^3n~ z4p)ZCLG6T{Yo=)0AbX;u8Rejs!Ok@&L1X8dur{YdbC#{lqr%w&89Ud6;&C?J7EE|M z9GMAsgTT%;4&H$ovpVcb?cq7s^u3H}ogz&n%_zqXl!KjXYP7VqbIri8whU-v=bG;| zZE)n)u(p?>jh$z3g0bb!%HY*M#&6 zXP1_(3F{F~6+D61xh7A%MOwBqPdwkbMoxOv5dqS5hMa5UAmlmMNQPPfXy+Oa3NHWx z&NU@5x0lW}J@FnAPAo4KRwfwFxuzw`FPx@vWrOjYYZUxE;DB?Df~ys=gU&SyUIRGb zTqEJUuan8S<{IQfI@hf1BJ*`Vs@{Ubx#m*j$ci^bC~uLvPXXteAu&9*D!_!;KQ-Ao z0|GnOq}1m0OylHk3TqI~0m#_7CKMTdROzhvvAppfg^ZnR{CL7Co?&a}8WX+|Fgw?n z@OOaOxyFF=)*+cl7NO3_xuy`t6)f)F`#b1dQ#DwFZl8aG&NX5A3CNXm4NXw2ct~zK z*L1s}ooiB3-J_7p`k$Oy-bN^MN#>%ET)0~xQqDDbL{%)V{Ec};%OFzDHNFTN_H3^D zS4?ygP~}`>qMrbj75|=rW_5{hJ0a(qy3|#&_5$*pYZTNjA7;eV9?7{zK`#M1Ll8OF zC@43-?K{^f=tV%DbB%&7D*%f_B}63W8U<|uw2&Zju2E3ag4{95xkf=x1M-|}6jZek z_iA#kQP3Jdo^y?Y=%^>pxkf^Hn;W^G%tren=bGF9(9SiqG>B(Vt=PY4ur9rdj3*>G z@K5brBbf?(51?|cF_`WC3OLs&<}&~d=Nbi;KrRgD8VP#&#R&w(ZIN{GE+F|81zWM$ zNZy7uM6yG51W#rom{Ai!>sknkU=o@vfeB>tBn9g*PfVV`v@iKIrg6yx<{HT_DfkT! z!{p0&)FqeT36=a0oj?S^0go>a*Xdm`A`7s1SH5VRhE;HH5Hx(!0GelUVpha*@$0>O$g z2<{z+V8D0;Qzs%QJRQMt1lhmM#MQZ32nNkTaOn*QVsjCkMNlbU1a^44R?XpG!;DW~ zl&#fW*u&>l<{v#QyK-BYUu!k8;svC!UH)pRenrv%$p9X=#A?U5G`+jGLCbllt<{Nm zR=ff!aGwTx6aH#-F;MB3@D@;Y&dyhKC6Z4pL^j(mqHLaqWxNPZB%+VVVqiO0Q@MDQ zKSbvuS@CrGkhDBw%|DTdFyllbNeP`uB(b8zbE+T#dL@Mui42ue=ATF;`6VeWFA%XN zFXugxCYYebL1yVrz=0EqB>ZnD5~*{D=tLq_kHHg(Ecb9v1!Lem=E`4rlj;FE`8w zVT)rdq_eDi;kgF+k*!MkHsRJ4!I4H~QEhyr(eZi_b)->kfRR=&2Bqk2Lxba5!~7(x~a;yjkG0i{?QTNJE}olzRZMdA<@W zDt3E{G}Mts!yyVNQb!tX2ds`XdUFId^|uj<7}XvhX=LBQgk|qb!Y4##9`o62zxFg36D_ZW<4B`wOPKm}h>ESj5RunH_ST=J7Rsoh#oevtdqQ&I zrrpU=-w0_{Gd;JrmcJj83-?io)R9JiczGAjw;GLD7re}ftVVYUb!rhEX%xy|){R<7 zM;duTk@beg=}04q8^;SZg=dsJ2Z@d}@*+jl!9>d-^o}(0h4L*$);TStBaM8airM{c zj!8!vh11-wg>oR2iRts3j-XZt!>|3_MOjS-t=HLG*Hf#G;exIq&Jha)rL zEfDxfBcpN1J4Ag-IBpFl++l|a25UN4e56r`C7f5aY-vgj!ii^N-%SHF(0jrJv@|VS z9+q(d9tDAqG|H3mk6N}Wb>z{l@X+y&G@{ch$u7pH6;V^g7S{gw+%g`IIFN|c+y1jr zHf8y2bh?kjhmG*(k-UeaB&mmE3=cV4!fj=)FR3!PRl}X(%AJUWF=X`k2VJZ9uhgD*WCLYqGaHOZqN01;N)Xwe` z86x+jk&hrrYQchYJe=*w@oV!)IWPOAs|YxL9UqRw+%9khQ;uI}@!N_^G*%x^eRljR z1*b3N_%#AET}`my=**5^>v{-w{90fT>Vd$HUv@9Sj$gkRNwh{1?D(|-1nD}q>VVYn zC*>?Q1RB`!tIXA`VcpjT;Yw&=$FE}`D90~>7NaxS6$EztS_`i*b*fT+gU|~EcKjOK zN3i2p%pmjyfgQgZ_Z95;6*mY2L14$PG&p@J$FJfBVHgPP_;nft<@i;`BSgyM(x0co z@vGD|f*rrAg;;Kf0fHUBYK26xDM*GLzqSlij~aK8>WfsHk$RMj`v*kI@vA=8D!Q5s z$FFXK1Ur5i1a~=5<@jZy=YTdC46U!4XbT|o3Eg9&cLGt4UyZz+i`e=pp5xcZA%Y#h z3_|V!pxW_EHj3N?+`zQsmqgrIK-8&9%?;Jd(0JJKD;F+a`cx$qel4c2_`|765^yHt2cN3c$19j{3XK!m z@oRtqKMI&nRq~syaQ@bCVV*b9y)w$;v>z{mj$d@IB154Wr!GJiI917z{SH~c@yn16 zm>`0VUxsWiWC6!7LsoVohD!X&QAy7tlxeRHZI6 z;k1rFoT_AuY0i2;?D&=M9vzV#zv|)CBtBIs8kRi^89RPG<&VNn2AsYEj$g82g{SGa zfW?kqzxcULY{sCY9lvV8>5Cn|uJ><5Vmm0>@#~Q}Xp#7nrz*)Fbt9OOTM-DSp+Fb@p}wd{zs-j{_OzhuqGC#UcDCA*#P_$7aOj$blD z(DBQI*zThzxUr6SDd?T5^lDdBE*!sVO|@yxcBHxpIDXwhlSVhIh6p%*DRcr*`X;t^ z{E}$y%Rsc_*S(0Xo(j47umqJb9KSr6pBPs_#*SZV1eOFjUv-v2#*Sa*@y>}OKSbH` z-ax?dt4vMIFO=igvQe5Q67+35?fA7+Q!cl*N{Y;HVldvBTvH3Bz^O{p@ZURCi86uH zg8=cVO3wi>o@No5i3Cmd^{GlLYBRZ`WsoJ$IjLoxSf=2rbx^+gNFJvu(by329lwac zi5$AyKUJx1U5?SsS}$YBo*E)+$FGf=j8m0-^*-5&U&7jYu{J~22Qqg2GKxdV31_vI z4Ka!;a*k_wsDhpH^@Mi(%A;eTmJJW+cu>P56rA-b0MGGDwhhXpaB865_*5mM-6+{S z$k_4AkcFzsIiXo&`AO($R~7HnY9O@Zm#;=RGXS&WmkI9$%#L3sT;ftpb@1n%szfa> z@+|I$3<8c{zc$3P!gTzSTzOL{f^Y^x7;yXw6Sjd6aQyO86HbA~BIx*K$ht!oaQq?} zJhcD^PE}Iyw}9F4%P%TdT2nZEvEx@B*)5Q<<5!DosiR7Di3NLn$FIswG1lS_rz&lu zHmfMkGl2M1rCkQxxf#P7t!DCpr~2&!fZ6eDlHc2%lYrUr%Y>^oS5qH2ewpwn!0h;C z!W#gy;}^Z=*BQJ3m`_zQ;m+9a%#L5LdiiF@uc_Fd%#L3)Dzm28jA@?Z*9%|-9KTfc z{|-3d_@&^>T4Haud8(3v=K*HNuZ?~(iG9dUdJZZYrz%y(e?C>|T}hGEnCO5iElL!e zsizgo3oNLMB@n7=NY@a7`UeIv5f}KABu;bVJe)W2@7vbF6Mrg;cXN^2vgFI=+uL74d zrGfpnq^L&uG4yH2ulqppPF0e1wp&h@%+MIi}Y-Ju5&PmAF@hcRMvsu3r6W$I-X2SI# z?8F~VRZ5#2D#yzx2cN3+m!@@!)RQ!$9Q#oYcKlk{S!l3v=g1js;aR_ZalD?Ee-BtXt?0v?6x;@B1^mqA&>2DUrGZ^{0!&OE| z_?yk7;>2&z32o@7!<^z(U{tFBOIrWbWanBC*xxLrHfJjcWG=;FP9cJD3RV@` z-z<-;3uIF9V|nAPgpB>o{CL9o6fhs=WWw2~0QNUC;VFRG-^_sX)*<aKW0h04!PGR{;$dtbs&5NvfNN)O@-IzcX;V*M!N~-%E zWXj(xwY+U6C$%Uf7w$5Ml)qUX(U%ZOtsC=*>X+xb-{Fgddp%Hfn3IXV4pjM@nP^e8 z2IX&Npjmx^%63BjW>cxFWIYc^HaB!4pn&BxC(1d+d)g8sqJt11Gb z!<-b<8$UgNGX=c~s6r*M$lpvs+4#ATAo4d;(1Z9XJ0|&?Dd<~3p1+xb+EnIVP5x#I zS^>!OH&f6LfINRQ3FU2WHF_HuD3L^Odf=c|fNI!4R7SL4KrC$7gi-Sne(5xeq7-$X^- z%kk}L0BTf~(_J~Vx?e#^Ij-B8Kzyf}23)t-w^5npx?N246`)T-bKM>km$`DlJ_Ri@ z_jIa>dP>x76?jU}b3pL3!gxNQZ27mJk4p336F1w`|HnQY4VeE%_oW>D2vnK>rr@^~ zmuRdlUVgIqFY#!U&40t;r=|(j@$6#r-`$T#+5C5_LFfYloB#e?A7%63O-2$ukp!Fn zDnG>7EsP&i=ctce{-H;4eP!#2m_#j&3}(P8)fs~?M4zqL16RWkquEc|1C8L zqd;Ku-`~$g+5ES{AdCZn&3`pEMcMqf+8|5@fz5x{JRfEA--8BWItXn3Te>;Q=D$Zh zLgYzY`mfMn{%f{1%I3e#A(ngkg(#c#>Y|0Lob0iw)*`wi9S(RkSWciSsb z&-|yN6nzzqVK{PrxCy*2RSk*Qa#SIo`;fMW2}k=#g6b4$7#!IA_rP8zoSy4x;Cbp= zsA2Qpn%9_h=21@#v#LYa*ip#BCvMKZD4YL|c?FQog3W(z_D9+Lcbw#=`EQRFU63Mw z5E4$?15s`M`;?*?GSmFGN7F3Jr-__a2cz2jC*hpk0NDJefEI5=wfRp0F9Klmp9GvH zZ$`EG@2poa;j}&!)#kr*2Hf>ImO2xS*U~Qi5byDX^z-<2eQ&yX7%1({<7;a)w7w6&GSr3@afBTG_ ztb3o~9IQNi_PS%}RIv4V=0BCesvksy=062L4LD%_Q*iYUquTrzH*{C{D5}kWW^o<` z95DYWC6zyp2F-s8eh@H!R7IKpILYJDp!rY1TLJUA56b+f;I=1l$7i6FLoH?gQ}8Lk zZ2oI^qgUUi`EU5is5bu@W14dwaKQXW`q=z8;Z!te{xf9XLB{64C;d^_nej<9X#SH? zyccL{+;FT`0p9$Xun9YA(ygUeJ+u-G{OpHe(SXhGGnym2 zlZHnFHa~^_2-LLsNi=uLh^S}tJCE3^&E$TsVc7gUnA_9%k!rGl!yeT5Dhbk8&iNWL zw)yS8n|g+n{Yu#~ZGNXmVN#)NehY5VG?CbYDB9-t@o1)8Zapa}GQWur4V&NCu~FaV zM+xCo4j{Jq6`--rANC_M69Jpwv}>8%(K5)A=lrf^omi&end4ACSe{_>OOyJ2n;#K4 z5!2@9jOQ5LtRjAnLS$|8yH}HYnCgA9Q)dEe!(p3Jn<0B1GPd~{#i7vvhhR)(*$|_s zBIijB4^^;Jby8H@{PO5{NXv!?bYxEEC?gb{buR$V=I7skr^J+~w)q+Dh6*5@RgkgG z&ydNH%qXEdm04rWmS+&227wQI@YM(>`?{#M`I+z&fZ66}!qul?8f4o1sO3dUpt@xc zu=%|JZouXzxiUu-K{!`Tj|OdiVZsp*0yaM{HMsT6hz4zbhU^Gr0h=GmgwuIuG-&fv z@L|Ag^Ye?UTC3B379P$`(5B~yYZWfQkg?70lG~`GN_C0f&}p9 zl8WNAxL(a*aM*)u!0qQSywN)54G_XP3Ycwv!~NdwbiN^~ZGI+v05E?^#f00<#hMtF zJbX#TgkJ?5u=%MfX)`YxwD~FcRlscXtM28SZGQW1jB1--OKfH0qQ=VJ<=OmlZ;A$O zeoE;}fCDx^1vk4n8npQ-_yxdh^Lx}!CQ%#N(Kf&Bw=m^TYrmw(;V*F(RjO@%o99Qh z&F`F{r9QN1o8Q)3nNrY>V^@|MtwrK{Xwf#mjSHgM=GU02!yiyZz~)!?Hs+<-K2PL4 zt>JV9J2e*K*0sSss$sYAtJj;dpsy~9YMb9WBToWTQf>3AxR@yo?AIhkR$HPq^l6)4 z`P-wu%}>^i`!FD7^NTOmW%WzrUx`=@X|c`kkvlk2yLKsZYeu>fa<=(By(G#uzf>t< zmVPJ8hon*}+#QfBn_ueqt?y#_wv_Rm{gAWGFQo#f`%)$pwo+?20RkWPkXpltyO}WL zA{xF2Ap@2=d`V^e?SbkRvEr!T<0LEPe7B5gTdn1iMz>N{tB7?)jUFRfY3G-FqT1#c z*5*uK&a!XwsBr#-jBS3Qcq$EN&I%?}vqR}K!M-=DZGMgJ2$iEe%E5;{*ejVf$i7C> zjB@lsIoReGT@}?fzpysvHZ5D3M}-r+FRE>Rp?I9l+cn|saAYPFU5!VeviV&Im!lfW z!8X6N`;vYmP2`8GdU8*1~2XY-STkZ1FgjG)cWgF>_Zm~ZpL0$>tm{A8dhgE1Nl zfLs29HzQ<#VFS%Oy8EcwaLZpE4H#&`@~x070}VaItawNs+kpo?e{Ew-?Hn^ztjRhha6D z9E$Z~vi}$aH^VP8`6_0m$$glECa<~?K_kqUl8rGVN;bfpCwVDmHA$;Acu!$Il6(Sl zj^tX*Dw37)yiZoa^E){nPp0H}Ja>}w@CZoWhygyi2!m*HK8DETd<=lec^KZ3^D%fO zZ^EdQ9QO!lp!;(O=59pr^doo)wUq^6YAA;edK^Z>=!LBz6JA`1-Q3TcAM^Nb)f~j~l zm$czVpIrYTey)a#e6lz^-;-OWBPc|{vlLv5ms`ogGZFkv!40zz-1;eE-1b>iWS{#S zSH;dEh<}BkdlJc1dR^e3HW2-dbhaHu7M5jhCXQE*Eu1f4L`OCF`5BRsAu z@Y6rc>j9i zP_6+eNaK2|$}EG!1j_X%$g*4y&XS&DbE#anAP|*%f?4lDD;|a(V#p|$q^=9&TrMem zB&G2GU#{Ydez8T)RcUmKR<=l&-!|xWue?P&o2B!&4XVnb)TL6y-h+_8ZBVW`6D~BB zgqD(EeA{3;2sE7H+Xk0=3?q-uhni3*OfbG}Kx!k;tU#V(*+ad%inGbcr8bilK5KYm3T+qlOVgpnYyjeB~BG`4XsHj)^G zB-qA%bw}2)>S?LrF3MSKB{Z;&yId#MuC=xdx$}}7X-F(i;Q%(agQ_z_k+MT?sFih zEw0ykgvcaZ3a<&n#@#ud&NlAZA(p$LNIKiN=Y>SEr;rTWxNAGA)4PjQpQqZ4%%^1B z#SkeQcgfZMy)OQ(A_ZWZML zAj-y_c|TQyL}Ob}g>2*QQicgfFOvk-=3jzNwsB7`%Y@TIJq@Z8$6kV(iDbP#<<>06 ztTPKeHOx8zU1N#$iQ7Ms&Nl8fUIApYU>kSo%yhPKKTPu2%NW`5hCNqMGOmQNEo%K`HiR|)6*1b}Va3h0)Vu5H{3*Z_cS+!AmKS4h`3 z?q|G$3Fk22UgJ>msI|#}msd>JHg3P!3g=G^7v?7z-7BLk&Y()^K^r&StH=w`ES!Ci z1#H}gtWM?hppDy*-49v7#%;*b-1MN0+mKCwjBVT>pcQb#a_Uw|*EVjN^YIYs+^^xf zM$v>5t(vZF+$-<%I;k@fFx$9ak<}&}Elvq$xQRtwT`j5vRZb! zws99U;Q4^r#+`1!-vH(`Zm99@FW<# z#nl+o9H(}=wsG%8msC~HHtwmA@fOzuVcENov5k9)KMFgS)kzQ9xMjogUKn$?eiSU; z;`)J~+r)X?WNqUfST|kUxZm<`MB)cfw2k}QOVA>ZNNN_bETV zQ@K876UxT@xd%tSq9_3y_XY6w(bo$0TRu-X{Trlf8@CC+2$*f$CS3Z`bZz4{;i-Vx z#{I3A2jN`WFkRcYe=^`70pB_wBh6v!cMs;F;n_wkJ7WFg%R)A8Su^s<>D#zvxASe> z@~3CxmJxzBZV%$OU3wB7tNnzr#q|=*!pPjc5>G@-)gH!bJMy3GFmLa+^t4nNw|cPc0PiP&D{&1r?xI- z4N2zBU9iP^C(j;w^m7t%x~g6mJfQ1Yrj~`H+NG)!r23e z&E2^GjHg*dW+Jf?N$4%Et1{CRxua!}CC~Xw%Q~@4!TrmpX>)fOJU`4Wu0-HO)_v!1 zaeY_E=w_9dF=S5-k+r$ISr)7BVHxUuva?YWda*V`R;mKpMq}KU!DeyfJ7{OJmJKmv zBIl5Xhbq{qUNKFZyNxPQI&RUj;Q<||G(1AVSuO zeXFDe&E1kKb0oRWK@b94T*HL=RnvmzZZ9?A+znaa+Xja0N5}%^ZjuS7Ycefp?pE+d zz-;dJi>g|ylU^-No4fPKhC{~Y?h21nN0sUl1@`;q?pHuzb9XIj;ELi*ua0t&75q7? zo&h(n!SF`w$Dh2O?>q{a&D}ly-tJi0Y1-Uv!u(1h%-U>hD-PEokmm z@S}hOTU-?!sgtJ7-S_y(B$^{T+T6WUQ~tDGkQ6!mC2XuywYhsj-860P{>aeM3R<+e zyT&Ccl||b9#$wvwF-+vwfb(xmUyK3U+=5 z(54M^*RVU1KG|9frOq?;)3mvJ>3Xk$BuXMr+T7i*0aF^-ngcYhBWZ*dK4bGkQU*|&LAI9niN zb9X47O2aABoC($JQ2I=`9)wXH(H8pHRi6%(qXybZGioQrol9FVZIInb(u{HpKsg!` zt%UOvXm`-%(mdLn9+$CfWgZpIX2^JpYbY0-&C)HI@OC&d6J~?J=I(F8 z6@Zf+i3RtXmX_0iRe+_@GuNiOV#O64%@+&qHC6B=z=6G{3O)fiu-8<=d0!{fUelvC z<*TMuW-1C2wR`)5P%|*1=wAlr=CihQGb~b?^joza#LMSC- z%0zurm;lcP$oSg^p{xk!G-OioV|nA@WG=ne)Q=~e^?-S=sR?JG0(h^f2~Pmbdrb{E zZyl0}BpY=`t_-I)$;I7mKL%YHF5sPztUOhNuKiQcl_4yj1-Wu%pb3f<56R8Frl&zw zdrebP-9A5SSBBK`-HK|z}Ud9Dl! z%Kp=EWl+$)fIL?Q1r`0vaAi=?3_zYMgM!Wi@?04d)bnq{l|ex-0rFfKB$T(gkt;(J zv@ddHSn-{9WuWPQ{0y0!?VmMRmtIB2f0kg6@3kv~WGZksK(*J@U{?7d;L4zw^8gxq zO%-??pyA3OK`*}|`%=6qNS>qMe!LKi10g- z+Q#pGRSuITW3Op(kT6wCU~z-Zt9q}gLiYeQ_nJ!7-)kB2*Ark<<_jj#yg?V|_Z zjj?I%HG?n`1U9WTI)=9?y>Rr@fL=xt-H`;F)&_mR8deqBLP_+coW)i`1Dn=f`iM2G zt8NhbLj#-EzWg}GrnP}a5`#ft(^|Exr;i;hac5uWGN-%-T;v@txeqO-%G=^R^ZDRo7N11 zdkfG{1|j|{CYttDj7@7MdIwN-daQ{$U&q+Aw!+J~h#f!Rnbz(FL7CPJLauu*=9$)H zqsV;>h&HWB#J%Kvj7@8+4b=zGczFBhH{ZrQ)0&Dh?K?CExqWo{3x0cBf+}Rw+T`z< zaCD_4s5buvbh2qJ`Xdug@AfpPCu3|S)UatS{U>If`P@^(tOBqbvuSO^&oMTwJ?Rxd zHVZbbZT=<3rnL3Jenjs6A)_!A}W%)FbvlTF#)+C(M z@b{QDttntL06sld0S*3$Y15hnoJ|1u^w{lQ!SG?PKV#aow%dRY{}t1wHNV*kr{~`c z7q)!ZD2wwk2!YRr)4hu9L4cO?Pb_F!Gi2u=3!ENn$Yx!L1x;&)EGE)|rZq!$CuD3| z+lW@c1DUhRQm>udI#v(aBPoh-s@V+JHHs#j&4B6s61I>2BnLaizBH1iO>2i_waKRJ zY}RlSi@G=u&rZX9Y1*{5)yT;u`5Df!jvDOx1=511HI?L6zyZ^mf?F2ED?2!|;q+K# zT2t^2z-(GOX6W8rC{3Hz%;GeUrUgxFO38M>e0r=httq%kEG=kSQ}8Q*1Ew_vcTGzR zn${Hj3E+TfO~JF%)3j-A{tkaoG(H<1$wA+O(G6 zgL!E9Pg#~7v0}a~WLlFoBcGhUX-#%J-?S!wdZslQA!u6jAYNIM4T!gox|ooWJ?%?8 z1~E}9UOs3~n?@@H_a30;x55=#Dl2GDlW6WrpxT}`53$v=Cbv`t-=5~dO6DwwY@xEJ zsqs}3=2Oy6v5KBO?VmTPtx4G;l6eyr*waR=U}IS;>-F85CKB)c=-bl<-OH5At*<0S z<~Q*LUM^^R+D|JDdm1GqoamOSTXE$hTG1s7P2 z@~Q2kpGp1x_E92mBBniUjgHaH`ohmqh^*~tRqto@JuE}LPj+@`LNC^4$S!{XZA019 zjN-_bT+Yi{HpD2Z$Z4^LqYPEBvkd@$D?E>mhHF_iJfLHvhDRtktM-F2-=5~*f9EOS zY)>=V4HZB*^&X08dzvAWgP2jmotib4AAg>9Rq;-{bun#E^VJCFHNbpitO@5nj3+bg z6CH1;0~>I_o<=P%avnEN1_66ouSYN?FprFtT$yExAe^%x1ng;H!h}a-L3^5)nsB~{ zEMQMFWRo7l#GdZ6UH)AqD%Ns-DEY0#qWXqS=^U`deCvu+CaJqt>IxpbXwLxpCVVCf$*O;x;+ZNOIv`>vZ6~a_R z+tX@nXG#M*|7+fDNR)*>ZBMKIV$8Rv$wz~`0g$q%b(WFj*x@B?lq=>SEw-m^+QE_9 zWu?fi8Oep5?P)uA#@L>gDkb6O?qd0nR7!<=2y$glOC7)GZkBIL8Q(b$Ios1xDsV== z#Dv0DY7IYuz}rVtYnbyg6NX$wL-duHwx>Pwx^AGdzJ#n_wx=!7w5`^=l17b`X;h6lOxx4K+MGpN_H7;&PJB;H+tWhvR2t6Rno!LSrO$-Ydt=(3cHO>EITC0mY)>ou z8q)^Z_e+{lj_N1}+tVt)9@F-;ur}vmEnAsKg;RB3Oxx2!@i?37HR0`WWG2+vk4K=| zK6=^yP&uli9Bfa^KESk2kztZ%l%qDv!S=M;2Vp!=_O!)eZFQlI?P=L>Fl}&TQ&?Ml zXk&X?oi}6Jo^~>*O=UjT6e`)CR_hRR=S9*m2Udf*q%pTK^s+sz-r<_=kSo|Y%xV_LQ|PdwkACWjU|A@=QQauD+DX_67Nr+H9l)*mzMX_fNdok@19 zN@cFb>>3Mz7vgv`Vr(BBsk@J=4Yym7SYZ2TSbh$2Wpkm2m=zDn&F!Pt6@^&}TTn7b zrlh(V4x6SXrr~x0eLnT1@$k5SyKhxKB}N|fIORvf^IDx^S6&G zs8|`S!zvqY8QlkhgtQLH*0IHI=rHD(D;_&*q|_ zSqV0mCOlR_G$YUEB3Z@tDl@Qsv?baX*<7}yVc?S6M`?-}zlv(bzBHY|y7Z1JevJe- z1612bB~yW|GGc6VF_`-R8rw$|Gq*5ilQ3ZL_E81C0?@FzNYKl#$i4%M&Pw@8tcZ!y z_#kn|!?I^IU9MKCu63@9-Yb<3MDy7W- zAhF~hptQWeU-_2brHDgt0#^#6jADF{SW;w`oi#|CjBDNpiQkb~`VcVP?DE%JG?T&h zZ-W2rgTyz;+iNcrsXs`JdKA!E8lMC1CoNXP*TKg0D_p&^7YW<_^`=;!5Aq7P#m%u4 zp98)LsQL9=k$V7$`2}8)TlAJ7hd&408?Z^_&jCLO_#&SJ{t}`WP^j!B^s!${M&Qo@ zUotzsSP|KIoP^YPqwJ@32Twf5R;uf5M+?_Nu7 z2Rs#YQW=tty$d=|8EQM=()Xu0QriKK0j;(J9*4%aGAHpAMA>?JJK#;8!GbB$;9eTU ztOr!@ulBe)bBb*TmfgSFB9mPRmP2Q?r|0?}%zK_U6@=}8Pk5%QQ%psy`h#j*tG4M0 z>4g`gc>sh}tqQW1b z`8KK=w*yY8UxgO4wUXNb`$|z^uE%pbV96WX0iX7i+z!~!q_+cZIVT!y2OKEb^rFI3 zo|4-E2THXaaO5GKliLBOmO0u}aywu@r*Pf{&lhLd4p+E-zW@Kww2@U|8yc?SLg`6vOR+CC39bdVtdt-t>0BeLuo*66Prr(bs@_ zJK*!4Mf=cnX~DB6qPy{nQEvx)=REDBV<_;Ux{33ir@O_-t#!_Pov%x3K5fv~Gw7C@ zSsT0ng9qZcc6x@g4hOY=12xp!0pIknw&)#dCM{I$KSb^IcEHCyi#~=A?Z56LI(J_q zx7N+{bp2EFX@k!^gMq1;wL$eq)!VUZ4~2}*A0=zA#Xq`c5^9s0jldkFd(c)Nn7X@qW#8!=N4vbUZ@OK3+V+Ov9iN z40Jp~!5l9hVU}Ug3;0OG=;*V4Ji@ZUUOa+f(CR0!-g4Hm zQ?zP)YY>khnb<5aYB}pohU>ZLJUSks+0Y;!L1lRejEYAn_!*l)ve5x(LLH9~9i|OF zx>_2jKL0X&>Ue}NJcE-ReGlqtjE;mG9gom|xEGHw$#cT0ssLvjR5~8vAhQ`dGaex{%8y3~%tUr;&^jJL z(%G{?=udqWaS()#M^HqG(SAIFB%IzLbUebx{(%YS6lnda?@@!EJjRbl2)Zq%F+IA7 zzU}i|8OP!j8=Df3z;hKo2EY!Q&?SB9Yv@)(mlTg+=tARC;t>p859pG1vo&kRPd zMiwt|&-W_OdO7R4MonT9G@WgoH>_8JPWsfB$0VGqCPtIv5fuF*=%jcAMV|w$;}I?y zzK2eVdhrP6;cNt*^r^3MQYAN<9FL&rrJ$2O_0>g!PKrlR^z_@J$?*t^E-@Kr94r1{ zIcxQ)ucCK?*2`I!{L*i4^Hbl#w@1Br1Y=BdT+m7J2=u4p5k7}5=~G`r*JVo7i$|Ce zjKa=x&`G=5$}Fi*nLooy$0NKG)Hdq?PO=w|aNE?V7mrX84?ns~WF3Zy7mx7a9q5r> zJc7KUu7YK_s(eFRgk=OV)t_F5)A4z!L(Xy(@e>j8k)yV3BAhp8+4V z+6TIncm&xp^3EB=Bgo4xh)0k~KORA5NRCJFDg9>Bcs{!sk6w&NSdQBu9@H}HB*!Bh z;ro_Ycd$dM;wRNnb_FX_u}i^jB74eUTb%;y#UmU?ZgneYRkdyqkKoh#HZc}D9gm=f zU1{(wi+0vScbKsXb*%+IvTUh4L!B9qP@|p>Hn_p+aojT#S&NXx`@Z)D&!nX_MViQ? z$eN00L@yp;a(yEnfdvU?Hz@sm@1G!yTUc0DA}JoB*tLEDKzqlYTG!exz(c!c2mJ3YYb zcm$*0@BnbBL#My*HFT_`Y*N*(&aa-;D1H0$y=#M(P5gL-z>RPo1g+x{OnN_P9gkqr zC9X?}M_|tj7vxAyNQy@o3EQN21ZgWzinMj!fqpGU$@x5vaolE1;9&5foj$nIDf39I9@#(a`C5ggm-6(CP1c#YulG$y$V~&|A*B z@%0#BRXl>j4z7k9=MB(09^rC>Zkw&?_10>CfDq0S&^jKWesHxrUxLBM^JSA=6*avmS1oEeeX8t^cJ>7zV%xpdf}WO zk6^V(iAPXQTYyfAM^N-k&`IC-DtZrS9gi?6C?@L)RL6@)=+M%SM|eV-$l)(*E1J}c zN7xIKliBE4cIXYmOJ#VedIRY5mUBxhKOW&L!^3ZmO zJi=$lq`vRXuOxi()Ygkf$j_;WRTEcVPcS+`0vo=R=T7S-_x$6;2d zExdi7$D4C?d#$^W$AvQix&zF2MJS~fstjkFXHX@SQoc4Q*ujrSC~!LEI8LLV=y-(L zp4ouVHPXyDj+QtM9gk3=qaTlu>doon=@#X2;XDVO{=PRQpRVS4&)`sMW^K@@lOK<; zKlM0%!Exw#gx5T?_Tk@BkE0EaL&qaDzQvD6$U2kKDwp6*$0Ka^%m#*ANHe2VI>4Kb zM`+sFk4G4r>`hfZnugyYIv!!GXM1;eNwQ0A+Xa4gJVNs>emp{oU*X*A>6WGX!9yf; z`upBI`3m6yTrX#xQoab{5#(cud>{_u5#%7`$0JCKm&D~C~U*V&J1Fn$T>L3+ehK_rP1Xxv0^fz(ChGM=bv^yx)q0D^l)2j*0@NAJ z@@CukC2+HAbYMVE{>IKzFwkED=j+Y+9tQFY&wElm2&YjE|4ZPM%)+?`I{hVZ9^F3Z z^scjkPB@q2NcES%COrVO{u0=vUjnVa1UBfrZOAWy*P_iBm2&=q{26#xEIBG=Lvjno zjzMqkI-9D${wgmjg^w~;W{TeY5_ld=Ra8p8rm-KOm(4UGe|^KsUQ|koUc~N)N-b)h zM|B7)6_t`lRW9yDr35Mw8wOTIrI_pnuR0ib^rq3T>+Be!{4fZM;+}EC%IA zr6}qmC_gGiQSGlbqEZyK29&?+tfE9!BPvBv{XqFqDT>+v%8yD>)MeF-s1!vF1m%AT ztf)<({HPQ~WuVWk4lkL-tNXPf!m?~ScppLS;>n^;SYt(#cY+(Qyy81 zZz?likmNTYRaA> zgZNJb3qPgfGw~xNUKl?j;t$}_J)YST@F>B-V{QB~LUBBy#@pNo*h6T6r^I+sJix^l z5<1|%9zR5wf;(gUB4H}-YVp4a_uys}594kTFWL?84xx4rz=EEDX1yr&2DESiKNFtq z1L&LsDBKtDCgFTPK=}cHvV#GKZUuZi6wqZDAT}KE0^#8ifFdIS&yNPw9|Jfu4sdQf zV8jH#PlO2*0re*VE)quP0=~Qr(426DkUJT$;&wo#DS+#z0^R{s8+Rw9GSdLB-bKZ9 z!25)pyAh>ge{>J9YGlUALj<9vYkKgms7hSw(a%_He%-J# z0O`k%ZM7QvsbWH}#{N4hp#qTp@uko#gd(9M&c#V>Fc0wee88fI0pC9k_~r?~>K6eU zUjnpT3#hXJP=6z!?yG=nUjwY)3|O}X@Z#%$T3Z42wgH}a7qDa(;Ke+pePycs@uj90~1c<~y= z(nYmL@jYF9E54qKZ^!3r@!j}XE&d@sO^bhnZ_whEuckz3j^(@J1F^PNyewAFiXR|6 zfEBRfJ+LZOJOk@a#or(t!CF%B`B>&D{sqm^y1 zD~jiQV2O6{UHnI^7QqD&qBTWW?v_&bx@ajV`FVZa>+pQDID$1o>-H`EK0d+5Q*Kg5 z?m7^xzhCX=kr8CDnE`PNP2dp1!dFt3C`UtxSnaj`66Hu^omH~Y)0tr}Zeh+kZ;A4A zXkyQx#9lvcVeCe4iSiFRPEkdxq8J^w&~;C`ycNV|KP~$tTQmF~i-~;)m5N)~axpkn zM%==T_tSOUf?*IV@j<$dTQJ#Iz}6cGuWy@d>%HkZZoy=~0;}Q{_W3mz(OMZ{(Pt1m z42@0Rm#)`QFbrCi+Mn*nEyzyM>J>2FItr4BwLg%q;}#AXu2-S+=(vUPhtmCZ6jYYX zkI)(9Itn}gWHU%MS`SUA;})76)&?J)kOu0a*ae?DZlT-}ZE!N}FVBPit=$Z6blgIx zPqfvkYorz3XseU(<;5+0maf-PIN=|F>=rt1VbW22axUW*PEl{hEu??0RsTtq^sNeT zo`q_}NVKi6&N7>!GvgNOf1%AR!%SrF2Cd^3WbW+VU#5F;3yL@gLdPvAV)|G3#(6Xf zj3`geWyjLJxP>461H;~u$J4#Ih2IQ%-idT?9fhFV3g_ytHC@CCXyaI%cVLjTj)H9D zzu;Lo{l7_1j$1Hv|3H@%w_xa&olH+&N5RlF|2AbE1w;1*bUJRK2YP|-SWe0B{B;yw zlvgCP2xqfL*D?-GIK962*HO4GxJaFIp!E{vw!D4FPV3x#TGNdzUgCOqc1oV{*HP$W z)Z~V<{yGYUq!U$>2|uK)qoC;Yb1Ca6D0(I6q__n|H$3mJqfo@~J>Y`Bj)HkO|A0=4 zTTo8s{+P0kf}*eZDPFDdIND0(Ak9k;OmQZOhQ>nL>m z)n7-!7}K1ypp)Vj=ugKj-1A$?Itqra)bIW}3Uz|f#d!^MQrv>flJb!3bos+yN8yft z{n}=Y#7Xwz7Vf|3ucL5Ta3ZqC!NiMOnE#itjsiPUxD+hI$nAzzWYCa9R-uVO!!Nb*Y@imoc5N# zMESJ_Ju~DlQQpL-!)j=FBkV6xo*n2?;ud7f$UA2cw;(UOAZ|e>{kR30Avtcrr}P_4 z?ux>=(&&c~^_UmyibpkpXETN{48R=`k81DTnx3>o`9AqznlmIlDTG0>zkuCjgfK|9 z)q_LR{SbyvkXzjqT9qB9X)ICh)B29F2D(`cQz)&+BWdsji*~Lbjy1Mb2tzKO+jQm= z)cMaYSW@B7k$ApPJ93w?JTs9s6JbrMgyUI;^IY9$!3F=!;B`9ocHs$qQkqy1-weyr(o#ow5`Bc_9qF78*;GOAoPM zL8%aiXMDdw!GR>An^2YxVTeEOFHxRPZOu%*q1Pb{1D^1fD9^7X5xeB+2X)KGDK?c| zq?aIHpMU=Pi?x1BzWJRGq1Q_)cScEoWDeQNekOO&Vh5zaB_bO=M9d}G&W z-L`OQz957_)?Ypl2O$h{5b{G9q(yQFgHNUY00@>;aHi%K7S(PmEGq0(H@@Qa{UE^l~XSfd*!6Shc>(dQyQjB#MwtLr@YO+|gdwS9gcdC9f^lIG& z-s!B&6ur6bLiZl&dWJh+)0ov0`fFXk$49RUqjS=O8E!?D z?u$pOikQ6Pw%v-_3hET8;yyL9UwSaZt*p}f zIK#cWE4mwIxYu{W=qA@);B#c=3bsn9)h(K=#dlhn8zuP}NHxPPEfslt=XAa9f?-*_ zi&{ClY?D@4)kV#oOVTC_Zf-V8|nYg?Jo^Z^r{i{DH>+Tk$*)ANCAj2}b;QRScK$9vBSc z53T}i!gv?IfYB^o9z#$3&9#8odO+w^z>!UWnp*(BzX9mF4X}PYpx92pxHkbu-vTs! z2T*z!;Not;HwOSKJ^~y%4A^i4@ZBeXW1j(59|N2{4oI8=yl@8a@mauryk?7^{{v9z zPfXH%@HeE`CBXA|HxfUFHzD!Tc()OEZNMYgcQt-n24E<*M~!zX0$7hNP~(>u1LR_J z&-j1Xt~0*AG~h6{-Hgx0uA1@P*fcXf0b5DN8(@dX_(ANv7@rwu5}OvrFURhJ@eJ&P z7vBY_wi7$r#g}1Uy7))fKra3W_Jxag#s+ZlGT0$E{!S|lTy_ZrJ#xqHijEw(rtQ`{ zTaR6eop-Iw*N5QYV3pj2*W0l>mBNnQk}`I-mZsBFc{TQ_?YyyLcXB4F3_$$1OKgR;fM9>`R0{ihOUh^kZ-4J(Ublj`zjr>$|9dM0^NW@2 zU*A&ud)Fy0PiVO}z5Tsic__E?D59@HsrUDu;u-umRvJu{2FCv0M_?c~fDT!=`xZtW zodzgT8Wc=55aqtAV2SGG5H&!z;klQw@Qx@vb$@SPt(qs;-#b~Mw9exwaTeZrVSjJc zO{LW|);!qXJC)=9-sD8FFIg!+S-ecKaGw3W?fpB|{@xFvo9O+$S?~Yn{@#-@S6uyI z(NL_x_T>G&8?xxw0j9gcJTN2 zCKc@OEmL{Vhfr5}^=e61`G;5XT9+3&wp6a5UI@qyz`xt3X4e;i#MS)8eb`yn*ri~| zt)OGg@6XVy0*pi2%9L!hU~PYP{fY-N^ezSMN(KhjhyLvPKM!W;T?$4S26bSdXV>4G zjcuppE(LcPMO=;|^z8ccbF_!WYov#JS+nRMc+j)!x6aibmLD(-u7C$UyWV_WhF%rm zL8FMuFwnE>SI);?%yLzLxrRYC80gvc0uOr|fIn&&)PjMYT|W(jyIrg+(CP`ppgs)r z?D|KKcpHE}Wf(Mufu3F8_Ncc3__Mx2cqK&P_i@awXD#$L0AH746`T5)w*mNTDXM52 z6r*R?e}7z!3bEO0P+)6@-(WGZE>CzHfL~rJIG4uk`eqoYRRIixScyg62H+-pJ6JWl zZn8(g-p4ujcTD!W#oh+sJN=rA=-g`l?E2F%P`eZu2Cbq?f(^iBr)V`2j5oV3nb=2Q z)T#jQ8m~09RRhEY%xxA1Gg%%^=xm7c`-sT~Ax44L-VF8mNn6J$&lf z_4w1;;N-2o2X&Q4bKpkLu7BlOoto{t(N+iHOV6%nJnL-$e%L<%*)8wrtz(+_u#ya(0(sV83&@hn%x`o=MVDaUF^(D}HcKr|8 zY_iij?#uoL;Jm~=->-w#s{%|lYBGGarn9Yo4C@MO{0+b(xNmz-?gp)QDTo^MccAs` zx=A;G#oqwjk~e2IjBqZ1Zj+0H?`fHb({-)C0eEr4_gc_;mx9s;U3i_p0eE?Xo(Njc zu3u@;CqOTrj3NhFRSdf0dVd4(YYh55(0X>gdO82#qyOO=X*>l^#yi(+@HYTA#x&=UdV}V*%MxrOCbLSon957P^zx$Mt=kF`N1gcYz3V(yDr`N@1pc&edVkE2H;17 z+GfqdN%m&fKZi-~ov8T|t3YrfvgX0Wn_VBi$=Co~UQy|=3>W27i1P)MEBQtKE~`Y4 z-&wrb-vGRfPlqcoOVaH6#4Y{?;DMcRJ_M~-1u*FvulpN-oAfNudQ||EJ_TB@3J~+_ zAe`sk@MqVrHt7Ca{n_;zKCOp_GI%!9s{+&wbSbmzvSs9*GnieMmt8QsE|dQ3y3CL~ zyY5r^<(l`D9j$qlF}wZ{p3OMBz8H5zJgQyWD$X-Dm~PSK-5>jeVRr2k-cod&v) z{f`D4fS>eobha{r8l@O}v+Hg8Yxi9(!+l`v?C=b_Yj1|`$^qyb4bk=k&BNiqAe?EQ zZjhl9*`Ip!U`0E124;A(>qe6(9}juDAxS>I^XQ?9u5iPkj9|lp;QTvJf!DL^M!(?! z2*(9N}4wGOY}QLom>@>p>C1sd;OLw?KeN&jGDx*G>8?=%m?o z_PlU0oID9hv+KQv;9g;FSRid>jhF!|Gr%Bec0JXg=1>f==Ipv(nsDYqmo&R>=*~fx zv_JrLxB!M_Brg!4=odlj+4bO1Rd02|!*QQ(gtosgwN(-81f8B;zaqv9Rl3W%_-3#` zz$TdJ1p>;lgDVqf`2&P-9s{ix2dbFwzfzU zIs9dzxuA-U0z%7+z|^i#NMoaJ)823;kz!*$gk0#r>7l?*WRLgg3`INpL9}RrJXJ%D=uh^RV3Zcl%!wJ^0s)U!rhz)L zw@@c?#*dm|Wnwf5bUeB&?M<%sEKz=2OSZuP^56aJ}h|PvxEfA1@{vSR4mVEO& z-EYUMv>Q?XG%H^R&JNF@h?T#GtEXgm3k2lv;bG5U(Es4!FBs?r0{T_)PNQru5j}$T z)wAobOx0$atox)HPo*|%j~3Ol>m%>T@D>P2_2%sLbQkitaBAF{;mxk6jrp*R~I!H6)I6C7v^z8bOyE42D3sSu~ z?|QmLd0aSGP0#Qa2uR7Nt9id?a40piHaG(VJ-dD(^*GMpIP~oL;=8q3`*6vsNtdUH z_P}xI+4WmyWOy4EG?ixZHZLC&qQAnMo?W-@(Pjg~gHyfrfj2$7z8Pkpc0@Z)4$n{a zrYax(7cTYe`iOhA?cL$6$u70+0Ql9j>sQXq@HQ++@rzIXJl(QXKf?JGIz79dCtn>r zfa?VUQpz_L2#~EIABcn5bvcarv+L3#d3N2WQhxw!eaqMY{8&#sGEU($KsH}kXq zF{p?9>^~PbL)7c)&gwOKxvtg+sF9U<(7UkJdCKzM*7LLfV=$IqUgzX*>~!yfVVE=P zBmM`2EijOi-S?y#2&Yol3~vMQl&WBz2f=++-ALJ9xP2JGiOEBBM$;g6z z!9nZK{!Qx)w2S`i-=OohAwT;+bPLt@KULr8 zCN&9Cu0J18tjrX>`Pu(7Fjb%Z=W7}(*+w_hg#7hWpjSZ=DS8n*0hJ1h$fIi6R(oBa zN3{|vwE=jb60vAI-Slsn>}aqmD8gh9f>l8g23w)-&AOlPv;SSZR4P0P%Kz+NQBHe2 z5qm)qinK7x(td?)G%}-KPW;{dAl2fBK~TP?uMX` ztrFVmk+t|LGIPBo%e2bSK@rkYk@tdB8-N>@r$HK@{VU6sD9{LsP~)qd?gBKJOJo5 z3vksOKB2srT=pzf1^O-lj8mI3a68gTtH zfJx5+E`J{I8DaQ~Os)p(COrEJ;DJ{G*{>luq2XpoCAI)sya5nf0ow`pZUa1qu!Q({ zJg3BeCA^8PiQ-K=0Ny9G#?7^oeH_@Ze#6pyvm~r5_w3FP_1jsQAK|rD*q?@1qq9?6N*@Z3B&k^E`aa40@`63Fa8UmPfx(rm{E)WLfFw8FdNfj z@mu=<8sq>*^aVW2uR-4*4EPz}GsedZ1#}$-_=IqFIA9NE4dR2x0EXe^d3@vqz$wCB z?1dZu@(#cZyw9xG>n=z|rvt`gr_%VpgxU82vhEjH70eH8V+p-p`3@MP8C=L zzg1XZ_-$!l7K;~1`;w-;)TxCH%4>U3AqS>%VS@^u3zi_91>ohv1{L*<{XNpzdqDF- zta^o_D_jC0mo%v4<@b+8b%+Yxu)=^`(jfjnSU3;CLM~}gFQk?Hls?11s2F1yM^2*oogq=POmCZ|S}DaUj-^uPY%crE5skSWzq#D;l#zF8@^ejIHl3k-GLJH_h;_yB@FdrGw$w1c&Xpi)&(G@2l9E9_{^hq3Sw(Rk z{SHXcXB(=w5H$uz8{zc~!&PbwMvKit6P2p|W$DWrz^N5$R?$+i6PG?l^WgV4P(&Yx zQU|!K@C^PtEe*~~10%qt!xfen;PQ)aA-jp{E6x_rprDmvU zt$YRnF3AdA;*~f?wju&tR5MDei>!GN;F8KQqJ^9h;3AX77o&&p!!|#J5D#beDFnfk zs(w}Ji--IG7uNfKAK)U&S@K$}-dlC6^(;Cz6s#HGqS*alRe;M@SXr5p^-n7TTntB2JgdVz#c`ItzGUpdaJDfSpx zwX4M$d7()*`d$}5e&vDVLdUP9H)5MBgPT6`<5wQ|TIl$d>W0DXFwpTUx1SU`e&tW2 zh)+<2j$aw^t@f~ZjP&p?YZiSG9(4Rlhwrq9XWLaz>Sxnb}Z z40QZTsdE_5cw_ICrfGGSfjQEvV=Y?J!qFRbo?4JuluMSZwMHMa7)sJ79^^>|k z#%8N)o~;?K&thUfLDhNygq@!>4$h?!ztaC_q2pH!gV=7cCz$Omldb=Y(D5rK`!rY; zzhbf(zY4uNL}S0^BHE#YAHOmM1}c8VFlcoithcL$>=dnf{U-eQ70JXt0Hfkpt~XqN zj?SawR|;Pg{^}4a%QP@*b%?K;uo)y9y$nsL<5zC@QyYBrpEOY2=}-97@hf-!r43GA zb)DxyUBuCHaHHc_Zv0zYooXko=tf&ze%Oy+dH5fpSBL1}AAsx@I({YRlF;!hU8pzX zS9W`<|D;O#Rs}e9{uN&QN>64pbY}d@BG1gS0yB~QALx0baK=N5&K~lg@ZwjbUG_c@ zI(|hF^$-}V<5wi%ECHe8S91IV!v}+w<*g1e(4bp|EN^v)pxX*(gGU$9cQBqS<5-+Z zVJmrc2-(O(;aND3K$jH1V(3D)l^nlf=x&E@!#Es$alJUTq5BcKr1%v>*EeE$@hjJ& z7wC@V)GT0m@hf~>(L<=S!lP>$hbEjdX_gni(mS|Fof)8Y{7OPLo9wjC8INvc@e=oZ zcPVIj@heS?nv^J{>1-?4u>K0P-qk|Iuke^KXBI_&pNM8?WvM_FMZXR@DSk!K71Awl zSBt5J?_;2K{EB%v9WpF$bqE!|qMU35ofN;K=(2?^Z&wQyzoO_lpp)WP6df*NCC9HQ zdMfDlx8raITPl7<(f@+h@hd-E@3){CzcM=0@^-Z_#x&!JI1D(Z2+)hQTVoLDg{IetZEk&nba2xlRz^sW|*v;Ep;wZ%#H;#c}Rc-+VDJ;bj} z4^Bi@N0@l=D^_vz$Z0THhM!{cikb<_@GJo4#G%yjEAxWn!u08*n8FjpAIi# zmZbQV>q=VQt`>nEmbwS6<5x^NdO0e~V3`jLufiDzTF0-L)<;0=_?4x89fY&8l;!Pe zvD~0@OIzNq7OQ+ZtcHdbWwh>~wK~wH#IMMfk$27@ennn(LHvqL`td6=Lvs9zPwCg! z-a~Zs!i`4!%KoqLgogN)-nb*;QEkS{A}M~Q7q7?IS+HjOiekI17D@3dl5MpEthd3% zAoff4A<^opHJV2Jicjl1#vJJQV*&9iY6O-B!{ku#6LdO$r5zqLS7ac}kFS5~hRLHr6UA)NB-g%`ha2MFVC z7M7JrieH)K8Mm_xV`=C7=IPpNoud0~!12|^v3IiWmi~kI6&mP5%=ne#UXISzeL;;< zjJ^1kjvKZ6uBQ9I*g4=Cbl2VtUDH?5B~<*1aX9jPI?sB#LB^qq>;kXpEQ1y8i~ylm zhsfjOfTtUhva;u#&>L1YXCl82v`+Ms5~f{EDHI-6h4ZT!e{^Us;GMXcK404jflw^n!KPVuN0=Q`76M ze*OR-ZJE*zqc8zm0LO zDV*%EOnNkE9lx^7ueXk0Y4VQn;#W8-YfsVVJNfY|&%h!nenmBZ*zoO{jpp)WP z6ny}+j$i41lV42MbEr;6HY)ss}zhvz&7<(eW#5kkc4YljB#q?$LJXp}~d(4Xv3=5zWP7<@p3+MzCOXrPX42I}O+ue|VqHmMiNl_siFZiYWEer4=l z5yY=Z53#R6snsEN_>!-4jsQz;)pgI5GrzW zQnyAp6prIscBc}~w=kPa@sUufH>blVTDK^V3uiNQdV`CUe7c&kPqo3J)Xdu8VHoK6 zl~-g1<&9ZB97JElap?G!uAgbM_TeL`$MGSKL&vX_KPtTVl}oAKHo}{ZUpe8K4GhQH zr?kouc+>GKFMTe&_?1r5%&(iOd~`cp>iCs$UufIA!*?XR)V80)uZ~~2?n~jtucY`D z&eNW5S*jo5MDUQU<5%+J8}8}0<;fSU4k7C=ABcna6*&m`@hj3IIex{bQhxv>#jjL) z8Bc7CU-?=70&tGJfcIROg7M>5I^y`T_{EDNIetaayFe$!uPD0VOCmXbMbWE4C&jNw zI`8Xb#;@d}9x{IATHFi~zfyVy?!^@__t({Gg&JW!WS~4n>O5t6b1aNsc?ibED#AD? ze`BY}^B9K9$@rCgy*X21pyO9k41{wYIvGK+Al18Ydau-uSLW62f=XAov5-JtH5~xJ%mZx;nzh$!9!K(NbldZN?H~bNUt?&d`*-se1lFdt{Li#e@`5d2` z4QdMeBNz2hR-vaw5Wk|RnV|gm6-E6C%8y@B)Rbp1<4_5{F86)?2+EINQC8!h)fXlg z^-$C|p!`KW6xDmVzN*XmRv&`;{z|xK{ED(_g>K}>uShCycVqm@S5KgqA%5l3Lfm*t z3sLqOKK^HxW2=M)Kc>lAd=;5lU6Ol2szp7dr6RK*7dn2$uzUri5x=4=i=#jzenpYD zgEZn-B7JC;PJBR-vQrW z1ibtw;Jd#7>;DGWmjH$Enmhg#VK?3i$6v<_+4!A!&l-OaFGS-u-qFPm0IHqD+qU>& zyjzPm#apa+VZ5`7e?{1YH&pRQP0R?6h7E>PyzZSwg zzs$th?#{eK!S?32c(;6iPhn9AJ1|YPZ2C}U+;%~kSvJjDP7T}37Q$Qz_jpD~*e}%# z3HMrPA~KmxiCmP=CZCl=x2$Y;BYE95FziQ(-ffwzS{)uPRs&3?qCce>l=@YGL~xmO zA0wAlF(e{G;5G6Lr2OywkpwYLLpekA$P=Zhf;2x#|zej{kh`diY zOgMKH;2S9s{;CZ4gOXJTkWMH;r~t6bbcdIXC6N4)a5WV*2wh4-D;2LnihM%2NGN?d zpfSOPo$Jy;e9l((B-ascr{W&M1I+Odb8yx!GN&|PKjCp|pQQFBYQLlx zS@=s-tR=ikc%86=@D5=QVL#y`!l#6{%ONi-8W2_e3_Cyn+%ryBeiMogfk1`#VDFMrcXJwhoXw zP}7ARvgyhQ$`G^izDKERz$ZS&ShZlm@s!fwJ|!VyB-Hh|-l&JcRE z1^i0sUqV5|!$cfH7QjA8f5jRh*`83DifV+lNZL|ySz{#Y5xNm_36B$c!p<$$3l6q1 znZs=VLUN_k4NZ_NavdN+#ZRBFz5|NLCMLHM-X!cIytV_QhlHo#)Luu=xebux4N8AOaw*y5Tx#vZRCK!*CSOsi zNhy~=$))5{Vdw0`%#4MorU)gQkwyL}c1=yUEHxx;O1A6`vR@3t5N&hx%OSWeXm>|p za2yt04&e6W+o9+~g-i~iM9v;ZsnBhZ2<{(~AiYa?kcw+4Jxb}-VUP$elkQ4#@uxED!+%cT1cxgj&*Zx3=r&Qj`h zAK*@aTgHX9<^xE6MD3@9F9}~0ejqfM4fvZ9o*P zBwG>MQPGL83Q1ck((gdBI-xyb3}GJOPT09?>EKl+XE59EkX-5Xr8|)xhzmbyn`gcy&p+if;`Fc{Pr0E zR}TW*jWljD3dw8fz6l|l(2CHJ&|)m07o|Y}cNoAvxd9UQs)@+tUzEt%HugA+Oj-wt z;0{^~sWzb;6^mYh6sPpWa!3T1Nw*2PZqK2N1sefJA-Rhn***6`;)ae9nH)rkoIRS- z>GvT?xP!^>wp~ zKMUz|N|TR4BDhSt7szop<;c<>0k2c4Z~|~Mz%7i;HY5LjjpQn7xubJrJz*2!O+tZF zfP<8d5-$4=aFWt_!bL*pCqM?k&Y{0gKSr|n5kN^Q$`Wov(w2&&RQyfI`UKFF(3fx% z?A)bva4(bXneAOju5>!(QzSno454BiVG?2OXMmpxcQJV{z&%MX7K~k4>D`*_W<)QW6zPD z=5v}<-3gdS*a~oerpcJMkUUQ9w}dl<3xq!jx$gqPzXA#q?%4&noYED9YJ~cP>j8H2 z{_uCxt4Q8UXhTH@!gom8QqlG`Bu5hF5LOfR6Q;t>y@w8dWpX;R)!zh8Iz0m^(rPnc z0ToLL%Lx^?00t6PF}WJx?xB|i^U5N(Qt>9C$2M?u?@}8%NbX~Ry#b2IQ6`TOP7+R2 zA+K6_{a(KU+$exs1*=3x%CAK7JneoVTqIl~r2Ph{{34(jrLu&&F9EKiRFlw%(1Oq& zU{9vMbBmC?dNH5}6@3VEkhG=Z0u@D;jR_Z4Q7$t{$~*>6)CkO4`;Att$T zmQ8S(bWf4v3gn}>_m=woV^egwr&xqiWEsGg$>~_!Hgcy0_?nOzf`=-!dov7}NiA1O zkIW-1AS@;9DF9eSX+7ac8el7>U4(;#qlA+Hdouma{~brTmvEknUkEk-z_CijBak8+ z2!{#35lUVJR4j@LZJ`71%M!T?$;h3MTbczrejnXwPJ4fcqc4 zaBCD-7CC^5A%tcBf}?wv+Q=kwQvmkgP(S^b{zz+%RaO&AyONs zFw&VYf$%Jh-P>rgh{=_7a1@d&yTrUF!JQ$zLB+d-_oeg{xU{8!156$UxZCKZB#d3z zVZNc_d%{1@fTMet+Q=W01K2&EMbg3tA&~-vbV5;pT@WAqL^?l#ws$BUf#g!M$+^_p z)u^cbI85qON~hGBK*^=#QsFM(ZJgld&`wH2DYf4Z1vxvH$=bVMlKmJQ5ZqbhWRkb% zNT+dt5~!NX?^kSoBj>KBiA-*yM9zMb5h2Z4^F|PS2MBR4oZ83@+jj9zxQViXW*cb~&I9p$lOm;dsg_#gk6M#0Q+M~HR?e6n#R$7 z=uNE&4Z%g45?(;kmWqu2P+UXkKp0DyPZ$9^_sXF#eoZQv?GH$Ai1CL5#duR zz67{i=ub+79D+^Gy{9J*>$)EB_XSO4@)RY>{YdFYn79O+Nn0jqk|RwBk%jf(iZNX_ z-|o9{yibkDWNk|1>?V{rePR>bSVu^l<*~a`!H6%rFC~WQ+XRYlwL}=d#TB%qIDe@uVXToKT0rd#~!OpEb91_DkBX(E75=gFe%0S1+ON3HX zR3gL)_gx2gk5HY-+5mSHy)e?!l|^P#(TcDw8ywxc)JD3J>jkh&-vFsElY z$(3(JH$M%N=~PHb!aOFK&3%74^70EZJC5lGcNG;WqYfl1<5#Rj5pkl1s@hj2R2J zF*zv_?7f&zvtPyRncIa5DG{W?9ZHTSIRsb2{*}-s?uFBt)Kao3*)+EA#MGy|lnNmz}Uk|G3%_5C&{^y{7H|>DJ_7oA{jfLE? zRGR&8Nc_V}+)^v;kI4uCr`)+-TDKlr?$R)Aj3;-!E^W3acgs$D#*@3ZOpC&g%-idx zw4$Ee`{uNDH~@LTeLAI;a4j(xb!^(VXWH*MTJAS4ZDB85S?9nHcpz2=KBkCwet+fgk zEMlwT#_Y7NWTP~#VP&p;8PnPb)E41O^+F=di(g5syqw8T1=ct$fprYCLZVd`d>8u{ zF6(NSfg@=Udld#J?1*SupRKNpL~I|}6%nx4vi&vN>Ll1<1;94Y&XkL^O!SpB&<&aP zjH`m}g8xk$dCYL69wO6NXZH_9w0a8sa|Pj}iPp(OSI2MxI=3)%*Lj{Yi`t@M5irfP zwW`R~po>>7AevsEk?mDPwu5S_Q8rqx4dU0s?5Sb)Cah}tye-z_f79l}S9?bqwqJuP zbQtsimfMQwO`Q>0P|ofDk*d;)VB{nZ)n4o zR%+P-OorLc;fhCb6^JO`*8Vj=B$}2iVQ-xh5v!V3Onc0+Rgbwsq%HR3N=4J2f-J9* zD=VfwCzzDk z?%Ilxjo|)9PD%vZCRZo{ZX!*X%%S8G?DKB`;?z=dYg1~q4JI;Kb_29LaJMZLi;#4? zQu=~YUrN;GNE3p+`a#tGHY!%I;&)S$9Kr5B8`_2B-lldLCCL$N`g6ze@HbOIDMuEx zn@L$0`AWVtW|HkMAA;R+Dk#~MBVi%2dkY_P|A_+4=~9ZxYH0MV9$IECf|^w zWK)uP?aNNVD~o9758aMyUkCL)`}`QJX`EG9+MBn_{9_eR~F~YOkc4l1sHc z^>G~68{~e$8MWV~Bsqc|TLkTA_tj>6GSBD)u=P5}0&fpcmH9evw)!ZKPBi1r2S& zRh8|Uk61Iz@UnM?g6-UzoYM;nftb{Ah`h7x(&%SOr}$k zoYa=0wgS1^eF3{2$B=BuWU1pwHm4-H*-YL?ZFh1nP`a8qShzicoRlU~TKDDu zss0mBz}Xzadggu}Ql#2RxZU;*xLxG_p|l?go5uE0a#A`;sXMg)%l5*x=Y9g;?gbVQ z`5sbyGFL8bqnWh5wW9 zoiKMlB|O92KSQ#Y|BU2XCjWtCzfMVVV}C)iIko%A-AZjCCck8|I;Ao{f}>OWCvsBy zo6@sC{jckV%gE-hYn#6(ZH`s8{M9UfC(1FXBCa*N#49Lo4uZ?vK2uPDl!j2Mgjh3| zVBbVZ!d+BQvMIT9ne2WJ+HnXyvtL;XSI?58WK(iw8QHHP>HGz|ozzN6!T}~_UiS|S zj|BG{a#AAL$A1U+2f0o(VKRr3OR(QZ(k?L-T1svON>^NjiA=UW4=sNNxecj!2T8X% zrL+r>Zl*+Sjx-_IE0*C9Zl&TT6lss8BsqfJ;TdS}A-9g&hbT#oVAG%b1l!OHKG5Ctro z19voXM_3$S*4AT+UItlZMH~o!kbE&1@p&?BbGX}iY_Cv3DMz~6&Lm44n$-+HKsVw{Mn6Ob{v+V7Ffd#ZoFhWSv)0k{rQi z4mX>}_9hjSa-^$+OtQ3;7Wtn1&-Ky0#EZz!nI!ukaueI)aWmttu()lbEp99jy&U2s zh^Pqsss%U$sU1NQuZ#?`4Wl z+tp5cr*#2Ymv(hU+B{@yk3pl|wFT3j^yCIb(_Zl8hNaRrd2*wQX}dhRah0^gp4_BX z+Si_ZUBk2sp4>D$?Qc)czA3E`>%p>a=#*C4lbiQUs|-1EH~5zQ(;7q0q}+N~+6|D| zX65wav?|4tzHoPIMOZk=u z(z=1ao^r4GY0pA#OWA!QZ4KnEl>0oLwgs}RL(ZzS-H=_3gYEjRO*;&^FKzm5PTSW? zw_*RCX`h21PJZA!mkdkfK}A5}Qj3adQpBMRAch3uW71LXW^Oyp$l{+AN18?8kw<&#hvx z?*tl5V9!YW%p50GSD{5%_Lsz;r2h)Z>_ZJvg^ zfga8Vv`8Ev(?K1vtdOj`Zj!c8cA>%j%0RZY(j{E-p|HG)gG)Ivh;;Xq77XX!gCmLF z4O|UZhER`4k2xXtXt@j!K_6LtS4(C+kw? z7tsGuwIx-Rus4CeMm2Mzd(pzO=c&`lK_NGT1_Od_%oY*3mysPIPaHd9m>_b?ki93B ztwgp*s)wt|z9COQ;2}|)Y;$#*lh06iA8IEi90J;(03u%is=dEAQ{*;grmuWgBKHOo zwNA4h+?(i$4S|%}q?Clnx zyW}MpUV;o_!qd#g5)%m;OtZ$WOESovO!~8wI?23=yQq5E;z$;_)R+Bz)UC5PHl^xv z=TdjSte|XR+0U62iN~mFsjf$MbCGzGOh_^QX;ST#c#gUPR!ZfRrg2a7e8m3Ous5Sv$*KOhDmcjv~E9YgUt zDc(V`sT5~XY!-Flp%lex@+U}1h|TLo6JXiHZktJN(R;zZPPVSB&StWWqKmAQhf`#GS8MTxjnNCxZ3@R_*}uZP{fWt4$lmz_JlMMcxqXrD zK1z;p1d%(0gc|e|F^0q#!y=c&Sc8~GB4H5skr-zXb4iRhh{s4wFo>ljCK|-^BqkZe z8WOn%v5CYKgV;ghPJ`G@Vn#qD=HvP)b(3lj(jxlLEX>J~ZFYOK;A{*4lv|ID6fM;} ztv)VD4wto}jgb zMd+kWSl(_3B2k=7_wXgUHRw%4BcfE5-(8q zl**E#E5DYyW?@;=;1q>r8{N@|%CY*OCiZ$VQ@>TCig%5(C&BC$Q0TNlW*0PsWLfaK3ADq%tHg+1P~LboX{Sk z{XC>Z8Cum-SBE@%(kJaj?lUapcV^+?|rlH)e*K`X{*tVW}^3GgRHEemrkg`jCG)XfJh5vr-~4 zin`;5uJ?SNihjU|Y>|mHSQnBPhHA+}Y==3ju8+emPhB}~CBn>i$~Xg)r-12Slf{;w zL1kK4-Q^M&n7Ub+>ejoOR5Z2qav!9N&aydG^=r~@va(ZM`(ZMVNE1aoL1KYVs4~kl zkfYygy62Ty2Afs1TWr>%{2EfVEZM|ib_bDol~g^Wje}moQ-+bcWD(J?gEEjhbwp*h zA>%G)eljRR_M^dK@+ah1vvqTiQG7!V4g`@nMdGg1mPni<-OZ?n>`d}UVeaqH^^eOV z4%o!M%#o8)G5zbZ6r!y94K#GJ`{|meZL>vD{O|X6zQvU(1>F_Yzo+y@nN>&+$(Qin+U=aJ6uO6*ckI%h>7E5?= znwW%vdvJYuMVljzTKB3EAMs{GpPU5JRyMpYk0n7Fjxqr7Z6}d0bY@|V~ zBQeG&!VDc1x!hNF@SK39ByzbN=-_Oh#cxp(Z481dgASf&5YuVV+#r4=(Jmn5^v!D^ zhddVLeRc=Mg}J+F)-5p0-6sioCnn(6u_WY8m>_aLC(*;mazYYDmhUBDWVt}1myzW+ zNf=rFk%W;YydGJeFtQYsgps9)B#bP@Nxb7{(WkMTWc_?$N+LHdSwC}_lE{5y13aAc zJ&4@eG&|{M7P;3-!p|pin~?a{$dWAyBTH*Z7+G#6F~i7mizJLJJtSdd$suu@k!6r1 zj4UH05oAduNVHaOkAjSeTt)jiReL1vP_&<4HArFx>5eH*RKq6jQ@UhN+TCoWOLnJy z&Zn+TicgVPsOV&OBC$l#$(}^w8PYfBaq_&PQ=Po5=oBZp>q$TAH;(QwnSgku9ZeF!Uo5dkuy@MB*cZVSbT&l*}o=T#Mu(gvfdSBcCNqk2^&VN|cCB!cSYUQ1%8k)??wj4U@u z!pO3l^}o}|vQH95mcx<=vLt>c(OCTiR*mqd!KlNrSdO-lhm$BoCfm$a%wSZmG6o}a z>pn&M`SmsRFzJZlL>@%qNks=v6unB(sZJ2QBL){WoTxV5Nb92NEwk@QBz7n| z)yey$>!vsf%X??yL#6Yb$YavF&y+6No!0%rvn&FiBJr1Ed`}_~Vt%3Cv#O&!{dq(T zu4?9TXj3&f5|JpY7{65f$R<-M$R&T#h{S0{`vq$HXGQz@HT^f~;)WCXl#mGFH7w}B ziK3&54xFfG3WxMr;{quy2|u^Uy+RUxK9LwbH&YC*5tJ(uSJR|MP^3uIQcRF5`o~jY z@&B>+?(tSl-~ay_`|Mpw=Tedo9YU!%l~f8H$*n?8S0yTRL3EUE9Qz=3_Bnf>N=k^5 zkdWSP?_A4UE^k8O?S2Wpa|_8W_uq4jxz^rm@6zY<`2HTh-|wH_emu@RV~+8f_qpbr zYs@j{`kW=)=%!OAZ9y+RwtreZ%fT z>$%PF=c(gOTCdzPW1OdqsBXqhTE%IYOL`l3nsJq!^p;|4tlD(*&YSd(GHQ)+o5AkH zjT!bM6;0MC^Gq~pvobCZF}5mWaHj5zvR6UdAKWvx&+++Q(fImxe*vha<8y*_J$Qw; zK^N6?TmSW7^jKTof`6BYoATQucbdHD*94nf9z6@I+R5dy*B=+Jq8&)R1yIU>U3t#N zsCO2GXNS@%&O%tt2{XAQ5Kc9r9Y@n+JwvPT#|~@*b)8b@E45H5l@2qAI#J~fGwEY0 zZPK2kFDLfD5X#H2Ea|r(yr>4KxarQA*Ds%>zYK&wm=MEBucGk-G20H2x=Z|!4I#MX zj4hIi9tgK<$b$mm;U?rmhhD`hIluCygM4hPeh7OsIwCU|gl^SN?mg*hZ zmHNDz#Cn63uCT1KdqTK$Dz+e8u!5Wn3WOs}s7Blshnc)Kn2i?auWyE&?&mQ1~mWwsm=2#mWiTU0* z1)d%N&rbty&Z{t>8hcmDe|`W}wqY9fxnuKMVi#3*eTC7Dure%r+N-1dnHnJeV`H*) zH}Nz!b2dKEX4Sn~W8QXt%xm*PWH5o;A(1N&E(5L8ZMKM7Qy>C;8`Xs7WU2enqk2&zXbe(JE@_TFBN*-Z)#-?rDpvV z-WmDcLlANRVylr(Y25cG8cvP=ud?MwU^N;&4NUB;pT&#+`(470$7>(e8+U2U^BQ-< zI|<67n}MfH3(|dryJ6Q32gFBenhylwI!%aqMSmB=3qcGev+c8%?wr8T4X|Sk$ivY0 zmC{7xqcFgiKcOtH-8d6aWVwkKdoDNo-$f;Kd8xoF-B)!rz1lQs2>BKvFd((2ift!~ z#(MtX-kIDaX>C?%ZB{mm>nlpGvgRl|>f8dac;q zmts@9nKFLgn;>rrkePB`?#fwF#wa%dSNneM7E7V9`RCAh2km-_-yW2|!D9 zX4)P^Z8Ou=(q`mKh+Y^*VfVP(uM3-(u93SUbv}uD$8r;|93F^l`mQ(_{w8K>IWged z#5-MnjGV+7b{Q716<&4>=x#G3r?UqsR2qf_K|)9!kCkN6+PkAmoD(e#!5> zDpYbkOJ6B<7Kchcm~Ir5{1uYVDtY{A&Hpz+w3Z>Q&~D=+4cZwHyp#mbrgu0QkC*2Zo2+U;0L*Q4ncM)y-lfd=b>%UQN!dUh8YMv&!orc2(@$U2op_41<_iGr!(0!+1e3-SJ88G)O(df53>Kg zet}y-xWf_g?JDRT7Faqw#cyzc!qS0uPx07AWdGa%8;9_-A3>1Lz8>zVl!cu5NN0a; zDEsFj$jW~7<%`&7y}t+5wVEhnN)6Sc!b4wCuTs&^dm?=uXXq!&Q)-xb)rl%E8dIrv zA5x`;nOB`?=i?FVtpcTnnOB|YhsPo4paP|anOB{to(mtUPE>Oc9iR~NYF>t!qk{Tp z)23@Ved+_TO z2Icjff3F`JczOjw;BWqO15d9(2>f6E)WFlL5CZ?h`1MMI@_M@HpDC62^;(1S-JHKS ze!beDd^dgCX390huU8tB@1`${RkE5vakk}$33(%l>FZ0ijKK8w*S0im%dq3p2dQ&)-=j(oH;OYBBQdWZti(M^rMy@Y6 zNm&w-^B(5cMijZe8CeR~5YZdCDO~<*15aNqk}@hs>{2L3uJ0vDIVB{|r0_K<=u3^I zp!L1oPoW+hE5nrET)ii)-os*7|2>dv{U@#dv*gwe4UlU))L1)Y$+bP+B!fYF)X1Y` zrQIIx*-^K=$-W8slo<47s74m&h}#Z1E+H!r>r0fj!Uq0#35VZnzl8Muy@99iOfGy_ zY~hBc4!>_+LaxjT9~N8qe}uw+MKb5*hTjZ8U(Hko%YfEo@}EvtSMZ#amOf;=jx3;d0660%M5y)95F z*>3*j_@fr082@4oagc^M5B|x9*dMCDg&2-oD{p&fsi3Om0?np|=&2#DgI{j>>;qK+ zm6C+zw&M@v_AGFhheMlm6YR% zXF;gOOWut%PTBizLQ=#s7U~5T5h^8*;MU5=WcVqgs-pSci%?04@oKj?oYhw&4H7Z{ zxxU`k$QBX_%iG-0Js}4o*4JXL$&n7gR%Sw-{+dD+?GKfqO z!g4FZP3a=g0#hig0PhMtO9M8;rUi>UOB4oP)b5oaQWPp0XGJ zq@0*5yCBjdW!eJIn=M;Or&h)g(@JpFQp1bq8cln#?3J?D;e>pG^l|t}>4)2(ac1x< zxh^s&WiQ(a*|T20H`P#0f0is%_jB_aB;_r7NI2}o*QCK533F!2pJ4Qtl#hw2adt{g zQ}!ZVBli=3SXSCBmXxtM%!%(xY>tFsv*b1~?w6DnyptCD32cQ~vP5DjIRb7%PNpc` zjk+AFH`E*nV{2sv{K4?6Wj1axYmbr{QjoG&=Y;%#^mdbu!mU(kMWm35!e_sv>_PcH z54YGxeW+FCfr@~(ZVgo*ss=lAe&CcSC&*RU>cY01scn*!C~P`pTb> zSx{d=C1qs}5G4S}A;?vMz{msjJQTkg!RXX$<|l6pl-A7|SxH`%00}tHIsW ziOZ<26w2F3LjFLm@BK;XoFlHkOlOMck*mHSDWh>)`N6fE_4^3({1Lk|h9gPHSg2`G zDVbsTr*PZ)culnaITB6CLQu~dego8NhX26ub93;~|44p9Vh!>=)hi^V8`PbK{|B!9 zY9zuNa>v{k=wb>-{5#rsP<-Dd~lql;5{! zBRVY>2DXy?e6JDm8rhU9->kzw32a5+=dlY}>Eox;1)kOWNTN_RL{j$45qE1BW%V!* zxvDRc(ieBQAG{gCyWJC^9uF^|-H;^YH;|)@8UgQ8s5uhG*UAeZ;_#EQ33t37m$pf_ zUm~>Od4>6&sv1)Av!Pbyq9!P+J*d@&dI^_OlGP1qr*znimzX!^G zNx6U*`^s=u?u$g3*5Rh4!rTOIQjX2VT@{I>8?k8@~Y#T|LE}}-3P81Y#iPw-&5^PjkL%Wf5O;3 z0aWvZH_9ENO_FVi7e$JCT*YZ5Y-2uqQt zqz`UVrsF>0V{QCpJWWXr+=M&__6Eb=ZrC$(u)`8TaJDpGjm*6?8&pjhpOPjxaV{j+4OdFt6zVwJDSl z+T%LOyQb+PRhYU#DlBG@a$?oDx`FERP}X)nP=yh0pt_H&WCp4%xeip*5QhdToqM;6jSb#ShXeUmuTvi!IC2ARJa zn=AJ{E?zsojB{lXzN6E=lRpEQ_7#4aStGb`6Voz{WqR7Du>{kDLoQ3p6uCCb_ePd4 z=rS%ZLE|{z4?fbnUW$9_bLn~O`IB)|slq2Bjo6`>A^kUU$^i|h?gY$}`|#D{+(Wl( zZ3|$&d=FzUWjqzR0Q1WEvhCvn&-PJXv<-v#(&du^&o)!m86znlc8hs^{q#(I^-N^{ zgsdjq=SUKgg!&FDDNp4hr$u&S+%VLcpk6c7f*e%zap4tViJ=Ywbq~}H;yuDYe$~?B zh^SZkZ`71;Yr0pGy*_Xf@*vazC?7IjA@4+3T5nE6_Wjg{xW&wRzZ6<`-8SeN?KA*8 zU(jS>cd?)e zy%hX`a1zoTstr`NY(FOEZB>M|Q^Q+wK>wu{MA;=OA*l4-&c&R0}8{T6ChT1$|+1&AK`b{UHOrqh8eO>q9fm+VaZ+ z?|vjHS!M28+@ws+#agpg8X{@#0>gFB!MSEV#SmrY4#VZ=nsuFDsJYUUIthyC9{m1( z)@atP0cp+JmXYm=$a5>TS%-e@npKTg=E?K;vYPdXZ*rP-@we$_&BOX-zHEl!KeEcG zmIb9TZ#K>1n)M{aOW-7=G1NU!=wfg;D#DsIZqkoQsK%saxb0pFn)NJ`u0VReQKO*7 zL-9+>p+`r(DJQwM$~0@+t=uz%ghe0J(NI2gwhzrT>-A~qzcbM1CF-sBp_yj=9l&cy zQu403n{ktJb1v4Jb%`NXnEROFM&#gJvtDS3iRQ*})6Lq)PkyefrK~{_U9-O7%e)1F z;>Bxf&6@WD_G{1IMBU7g6PX5eB-X9^d9n!K3+xEie<*S@M|o%SiB0itlrx&8`M1C zJ84SHoBT`Ceb^#6!&;g~NqaQI(Yr^q5AyIM8prP*(FdUP5lz}7nibMYwHbM)RHQ^LxK7ju zDqS+SbO?gGStam=W|bsmmvLvlqO;1YSl!H!N2nj2Rn+Qco)jLEo>flbx;N&5kvb3D z3_ColTuPs4$9!Y6%Et(=fI;2X=s*9Lo>j&mpQnP^Qf#rk-71(>x_+axit4w9Yiyh7 z->H^?TI)JsPOY^D-lu@7oLUR0sk4T_cIvD?KyNpIsXVh4MTt`7uV->autFf}gs>bSpIIPAB0NS%n zjddA-Ts2k}NYz-&068_*dr-M*tT5b-v;}PgHP&%ZJ5gg*nW}25wu_GZ`yZO`sZ9~O zW2js$RXBb(@-GMFG*ur!dc!U3dPpS1o$7oPs-lk zW>>(Jfx-a%H1ZZm*h+(H3x(|l_~55i)#QmtAsa{~`CgtOhd?#R#8zc>+m{E^rk@m2 zzfP;Ds^DjJuG7!=?XWtw+Dt*MF=`0ZI;+>Ca)P*NXbtkAhHMEn%BUYmryQzQ)@X_r zu14nc%_M2fsAKaX?MV_rO4i`AEW*DIDk}| z+mII+ejmdh+=1m7RILn#>R=&{%2b$_X~rb-G9)QE+p2ao{tKXTn=y7ozBd{E-!)@D z5#k%(0>tJ zCo*~~|FLzrCli+rnG-JDBPE6RYCQYmg3z6Z;FlhOx$agVhKZ-cB z^AIF%Bf1XRTM+MJ$fj`T{|^JULfmlOywm?YTr1k`Ih29k$zYA@;P+53+21L|DHU4^Q1Glvvr$Tx>^7YyqJwc4F0;|?$M9+~NRZT2$T`FXMh z#<*q}8#zW&n)Ql#*ZXnl%Xypq)s*i-48GeUNyx2GouO*wHK-m?v*c7<-c`=z-}<+R z>tJE>y}4bXcP^ZSd<=DwQ3If+7*z;09m;9I*ZK)+5n9g|l!duFyJ3XWE)Qv67}9`e z$yK}D60xrVua-uCaxUR*@meoX6=NrSwQ^JkvJaJ%({b1NInXDt(`EX;a6Vjpwc}qY zK|4)SL&P=2`XC%eU)=G^f3rS|AJ|vJsFm-bQc(JH+S(WVm~}O`musV9{>iwOD4@#^ z>u|B!qh3q*&{lHxs2}3fPdt?$=Il)yb`^bqzhTb;c%TNRF%92U@HK#IU5XM6AZMT0KSH*mNvif0)1{^bJhq%FE|O= z7sNoQYODk)F9>IIw(jVB?@u@h`MhhsS06-5nplX%_z$!Y$0A>;Aq#CMP?$B&%2(vl+m9+1*e0C+oDk!F1%k3aG^xK^W&TP&e0vCsqkhUByeATV)p9NsGF~%mHfMj(eAioLy$H1!Dkb;g*2+dQ{E$(t2)+i2 z7ZX~r*w3m?=Ot!yb|1(SkkrV5IdU`DnufS70#&zZ1Sk6uX#XoQi?6+o4Mz}`TLhcv z0xkk#SV|22!!ejK&jWB1(u;T=hpLe)a!_W>Q*EFMKywW=CKsf}JS!1jiXe&cadt}1 znCDaEXCu*HQr1BY_H$Frljh9GUWZ#NO=#hdjOqpTl~KPy{R}l*Hqr#O@&NwmcJ1}O za93)xm@!y6zJ#zHxnY)G`6qeY?#^;oHLCb11@YD`xZ4A zHjN$FD{LA&rKy`V?9mOG#vVy58PnJ>Dr_1X0hKY0%|h8Q^=gm&Y}44;nqeEJmXa-J z8e0w(HjPaX$eG68b5htewlbVm8>Xfp&)AiQ7(X8i<^+?r?JZcRW1AD zu2-~82faX_Xt*+S&&I8lDBKI6s%4I5>q5{r6+Cr11GnXCsktjHcb$JHcZ#uTU<#OX z;H2b2b0_20N*B_<25OefGXG^|`QFV?)$%fnz}Xtw#^er!{u540>LX>%ZRq9H=Ke-) zgK7=sR(-$wo!q7l8;}1Yoy@W^EVsdI9pdn^vDrSMxyMGs_o(_z1Yx;Funck5vayvP zgDtW{%f{pTg_n(CRA|{)1Sqp?%mQgg|A0!$EE~gO*U^_F&nz1Y=tu4R-1OI{-iFvc z;nqq4$ODY(0d<&B%Srqws5#Qn52XsETA2j@MEERLaR>V{TbbLyc{$vaOgDsD`DY=n zi}*uXO6oE`I9vZPf&mRRCTmJ(@gElHu$Gc4WOF3U&mP?7lkjb_;on^O zg^oG$nk!gK- z)_XmwrIUxr01pht*$idJ4nXM*r&oyyxq55zbP zNq;yl+;HVTo(XqPI$ToDw(zc)X7t@Iidw&RAZt7%33-*=l^az~s0yP_Mw)J5tf{$>MYVPCa&IQHPIh8DSPIk%p(0ZP|Xb0 z3YU@)Ye&O>N!-CtDYvWe2KXP4FmvE0WHI=9LCi@}vyk9tS-~Qm*Z(sa#F6Z17LtYC zg;_`#rx{_8w)nElLeT5{6-qx_6PN27ssQL$+$L{64ua-+Z`!%&7nJB}iSkq#O-um7lvzH!d5>V21=7XVN&`s3QqA)TjnXM?<+>t<>198@~lY zQ%H%$?!+6Nm~Om)U?DM`W;~I+;U}Ky#_P_?_pU;clp5U6!(YDGcEj#l`BE*9qKj8>slo>; zP)nqYAihlRCQ+Lq3EV}U!jNhS6;;x37Yhj$+8H)B^}V3H1uWg`}IBrx>9~7Z7+5% zw{=&_iKl2Rn&IUoF|V=0(zjtuJy-d58-`D6WK+*m5J4wfQ1$FAsPg@wMuvjM7k)?4 zbSKbiV1{lg+UG9gjkY1s{rrr8ia1rXsMl2VCI3eBhj1l6LsZ~O?9*0aN4wiqru3IB zng(A5T)~A}=U+)J^rI&%rx>C;UY4509EOH^&8P#RK7dNe7r063g&X`dq}ycvmdGzM{1Z@dW z4OJ@xpi&mjoxlmg>vFsP*D=h*oNa^bU-&=THUuYdI)eS5>>5&bw+iQ?!DiVs(5^7OzC-uYv!qa^y!!>x8T=S4*Wmiw+H)FmES0* zw=DGPv}cSsUHw(kf&H9zZ(^F*kIkwwJXKP_qdOkfgx-g+!o^c9@0=X-R>ErXyzZ)P z!N=ORRiXDIR7%7!i=ekEra+G=Jz$ul4lVQ^H_UV9zJ^;R{c+o|!`I}u-BWS_9?q`< zoM4c+xiz@8GQD-7Hy5f(TH%f-$kiWn?Cd5|E`h-k zK$>T`7btb1QCCCl3zd}j!3IBlHEDuHFPq_H|F9v8$C-gE&mAR$49E7Vc!r-&)HK8xBOii!J{I;$3X{KY@5>TmIG@df4z=0DrgX zZy>eOI*?s-x9vXw>hG+y6z&#&RiNC)|Km_QZv5vA75YTmM6ZO68S(e^@;Kcc}_r9yi@RZme6=L&y7f4(f$&!PSvt2;{{d9SBhO zp|gQ{>8O8eq{IDN?~GHGk>#)xgcp5uG&c(_9ZUqOYBIs;CfKZkBS~0PuagN8Po4=_ zbwL?$#cg9_-og*H`~iOvgnuF9?~^p4p@=K;E{J&@6{j1T7XJA(?)!ZvE3PTxN?G)t zR+E3H#ApNtl8UXU*D!_ z#Xr!#uG;EsV5qMfu2On_tcm+Q=ysa*|D*@a{FF#k%ea%C;4a@xUj;e`l=Y=_Pnbv! zD&=(R2}*~1f@bJ{+Y>f?LMBujXsw({$L|R@N#!Xz8hYL){$yOk-}1aic}8c*MVQ^F zmP1F3dGa>CEPJG$M`YO}p<%~JXfbv+&Zwvw@y&1&vL0%wQB67)dMk}O3+f3dXH>M( z&w=KnbsIf_m}^uNMmVFQw}>HgtTs!oMny{zXBic(Cugk>i*Tx?{*i^AGb}3U6gDhc z<>x{tUo|Y^&L@x|<09{!z_{oU1R3L^cFI@dqHAC~r7%Sov(qybL)2%^#uOF?7pvix!tU0mF8Zbv{2|6~ zg*#sPrZ(+_FCl}Fc8Ahek170L?7}fm{&Y^hceP>K4rkXA%H4`F*w374mIl@18iX2< z?pBO}Q0`WYr=i@f7-4*^{6cz}TQSD?acTNa2YK{}9dE_RLYeZW4yf?07_X7T%&iz< zyqm*sMjpNuV-)`Mtr)stwSeMn)S8^ehSht-z66HT+!bFE)Z{Yw8O>c^3=LY(`0z#-hFKN2P0I&VkY4f%s52@=MY@r{m4@0YWE)j-cM5kK2hr-EQ!=J;z z?zDD462fWiTElZ%yD+|17J$fT?bhzl@MF*4QEQilvW7nbR9I{GZ&J%>?ZSB1@P8l= zYwhOYPiyVetZyAHa563XSS6)r}QzL4}~v?7)A*gr@mxK_A`Yz6nJUX38@LeltUnjzg^$YjXBTz4!I zFa9!HL#CuR`OHkRqY$K%-2>0i56W=ngNP|rDZ8PkO6MX8Kgh*vh_iEXx8_2(7IJcN zWyGpQ)i>R;FV{U$b9Y<%#h+GX7ThPo6Fw;KTTylY)`o5()TW##EgCs(K)24;cJm|- zL)8I3BeN}|dzbU&J;Xm9U&pIFGp~14wJQZ9(usMkfK(3Ed;50V6T4j`33494#pA65&n<@BWKtCf$$OTXl1OCz@^9rpI+k4-`dlY)RnR2Kjz{XHj@-zV#zmE1n zFPP~B;LRY3?A+-bP&r(03tW=UUAHEGpF71{?k)lDa#s)dj=3|S8mk`-(B5xMTLxwRaRim%R;8J7zCkdvy@I>@9-YMfSRo zV357Ja?Oiw{XumwME*bR^OmH$?-&x4aTC}8(B064yjWPc%iYgJQK7&4IS|V2em()U zv)#`Y@OQQQ`6LhV|GfKI4Jy3*IS~J@c0XGn5AS|{OD_Iq_p^w?ceDGrcD?gyxc|k@ zr{dg}(N1ykK_wi5P;}O=+FoZqx*Hc5A_v&K>R~8@hF9LG7C* zI=gkd3%0I3((GV%(_1it*-h#6?4};_+=dIrMb`ut@*4<$c3V3=G|iObsgz$em0)(8 zM7Dx?s$dhG(}6;0L)#BFN6g7n%#*am>lZl@Y6!oy=}CGHJozsSe|A$wW_H^`#Pj92p9_N7t@0S1-L4I$62xoxbF*8W zzY4tDZMs_jXMwi@DkYEN*2tMTcpIQ^0d%p!M?+0D;D*rbrV-oh_U9i3-X{pSNe|%H zP&LveH%6W1-u=D6JJsT;*^n9iEFRTtKJr_EcMF1QyTz{ZB`yffi*aG>-M;1%!lR~>{(IwvQH4@LcV$mh;Z3q%CsS{3o zz4A5jHnH?OGWBV{?Di{$=jQ)=>oQVXgPc&W@Ne5s@z#D*fxGr=1boN#GoVheM*wu~ z_Yu^N?WcpB&Hqz~XUFz4v9{kmh_(H=JUpcQ*42Zyqr2M+kNuQOD>~JK&tp15^^nts z?xxBx!nI|?-NLGeEV)+ehvX&Qrb%nl025>=A(M$CbEQ{UZXK*A;>?v^f!H#c)7F2N z$q#m&$>oUCnY8$`oBkkpZdH}2A2j`eyZ?RDE8d!ZAaK|8-$L!!^aj+XFGB2^{t2jE zH2naQ-9^(^A^v}@>AxYdjMgdKF7`w{jyPSbf7kT=8|<>_4?z5XujwBnhFxTGCgOA^ zchdC5@G5P^Ix0VC`oExb)XpBS6={ur1Y+0d>!5aQbOUOme@)u1(QgE}i$?EIu**h2 zAMyWdjs6me?V>&xAWqlk-!*!Bmb$xm-v1MKyRF0?R^B~L1oXVOv5Hm&yDh_eL-_Abw_l*|PAw6~ z=eFgAKo#?Dsm|SwUVLpkc&fw?@!E8Nr;7MAuk47PF|S+yddrEyix+i8uIg%&yLYh3 z`o5)V=QJ+}qf2z`nJSOh#`C=E`IB**Kz`)uTEDo`t@WM#^+)@0qugVr{$@iU|LOwo z3pgAlzN*062IVZRi+CDTmCYI&zUnodv2&^NLzdQeAaxen&eD3Np9kxbsIwDt87VkR z>t#^R(t0X6QcG)eI=Dd?T_-t}b}7h^owb9l@}u@)sI)g{!-!7psn>_IU@GlJFnXOIkL&T9e4kfQJSyh( z(B1xhIEiX~Y)oJ^z>$@Q*xL6h27swEl-<;015C!Upl&3pmIW2Jf;n1uTt@~N-DoxI zgZ;Ai zt@s`C(6-`w0=hd3W{=GeZ7X`^@O4|U7i_n!_$HLUt;jVrB+=K8TrcftEqVub;a~c0 zy|1|~ag(BFnZvkFpXsFuak$vonR^3ntu(uUvj|Y`w?NkWajVspT+)UUO65n5wHiJh zWKhF5%gIRI_pzM+SYPU**r>tAorf@rdB^g6-BP~V52#-xoyVqszGt5$9WU(%=*#r| zoFZvQsa;bHxiH^*5)OBTK|Ke>M?r9hgK$mJ;G%r*MnjwrwZstG6th9J9;r?76#Pt6 zZ1=O4X^QB$tfp9_Rc_ZuT!0|6!@E`a+7z8(yQa7W%5Mt3rbVK~my+mc*+~B3|`*Uo*d zopqC~3VmKe4!fAk$e{S5ijUB90=2Rl{v!D9Hoi(~qx{5<37G)fE*E6sbsdqk^8=BQ zzCKw*VPxFBnvvd5SqH3hNu~qNlxy*Qx+gPAZ}$qe#EeF#-0C*hV7Nrzf?j0c$Tc!XygbuW>OHR?B37ZZ(&5=q>s z2jNviRmnF8qqoyY?j(}m@$i8VgfW9nC6b0l9RP1Xqh6!1hZ^+`g*_4~Den^QEWc*8 z1v^aAd#+|7--IM7&*jM5MD;5zCm>&sL=6eXQ7vmU831xWf@v%x%O$JY%iEovo~qZ7|TpQ!Oo9ky%*No>g<|WAS0giaSgC;U;C+p;2$4 zUmcaCJ8g;3%;&*P$tAe8^4L`FnSiR1mLaT;A=CcFf!X#j(WL?EYShnDC>K;xej+vY4{B}`0mXk4N~$x+=QG3>c3DmoKnlninZf80}^s5;x7mSb0SlFQ4pLX*wNP5(YS9wU2A3&mO0<+!R?3Y?C>>Vml&soH z)^3t`TB4L_X{xO>mCBQI9|!0!0nu@~e>>q7kp7pJ}R} zTrh>NhMAI=%zX=&(^Z806e=ly0|C-+*;{Sk?);n)EKDoP_yI;+@#z^iNXbOXM0z`oh6Uq z*2?pQc+UJA%>Nty4~_ckO0MICs+KspSx@zqG>H`O<*+Gw9D6Z5OnTZ6wZ$B zk1ruJrssPtq4=m4E@j5$v4-0ns#-oJWM2()ZG_T%jV~oX;U?r8FcHH%gnzMOChO<3 zp2BCpq#P29czyhq(Unq3v&ac4=?6C@=iu@^J+ghFQRhNUHtGhbYoM4V2m66_KZVn8 z2=a(Mmp>}b7q5&z+{f#ZkD7+RAN-`1d`vhaEh6a}SYPRCfSn5{t%X|Y2&Lucn`=;7 zCrPV`tT@s&l3=Hb>oZ6xA?rv}Yb7aKD_Qt-?eJYMP|qXR-yE6Z=gh4IqE~TkGcr!Q z9L5Mgm3nO%!B{GVkM%Cn`9@s{wFIhG{sFbZs7+9hK~>9sxZ^eKP1VjcQf3SEH&(BU{@No z&ox|l1(lS+xZzZ~kCA1ZN`+e^x6;&MS^K^Er(~73Kfh{uo@Cc(L6Umtd=tJJ`4#DG zKhrvSlwQ^|DbMCGC%&p*t_#Cz<#cki#YKImw5b#E7KVymdfAcgB>U2=sQs_jg_-VZ zjxeWIt|98om+NTNm3}O$XQ-8bB0kDm)t6sS$64}OVs$ER@rtf#P4!=(FM@D!G1 zJ%yEuN%u3Yz|1e+rz3Bzx=u;IwR-U-YH_Y>8{_F)s#md)B~ssKdGXX$l<|A8I4Uc+ zl2y$FF~jI?^IF(uf+PlJdQ8ayEtnyaV9fyI@01y8Q0=8 z(u;q02~p`1*rIC9D#`NHqBI@eCpElJYIsL_(TB&7r)OYXeIpU+V$LEOqY*_SF|X}C zmn^`3T#bd>-eYm9DY+xPXc@AKV%Es+xvW4^X2F}gYPRr>#_kU3 zT{7)yX&j@ib&+QgJO|-LH;mw;n^G~{TS(-(CN$Y6CY$19b5^QM7n3I2jdjF;PtVwm zWn>csUi5297468I^U$Vtqk4{YJ8= znzmR*Ky&Ewaj>5-hE7{VTz?3Obix^0fi!lRdS@!7yy)&Kn6KWCHDL`Iy+gf9RZ8aw z1t@FF$<@pElp(x1!<(GpwQ;=owd`Ws>d|ud9pQU*c?spyITj@9jpVGtRitDqQo|g` zN~i484-38S`$e?j%AP#c3uu?W_>&$1bjfQ0`e}f#4`h{fg=?v6TBK>0<)NDIN?E7b z>s5X%Yv!j06R4Ng)3m3wng*2px4@hB^kxua2Gm<$+K?stn_x`8y5*pXeTg<}$$=)p;KqE1 zWcgY9+2A*>semY1W4w{B2c?mGKqB8)fP3|yCY1}|i0 zw$5I1nPuKOyH9)3x2Wd$sTx4nkeL8hM_0K3Ru7Kur%y`BbmRBaC#d8aS0nL3%nG&& zXxxn}X42<9E+bYRDe5HpPY!d$&(~(vC5FMa{s%&f_{ki9aCusDJM_ZcJ(d-Eux23t z6%hP)(L`SY7AyOLyx)mqYn+{&UdoQTDeDdQ)Ni#Y-Ba&q&ti;!sTH9MteqTWaXC&G zEK{x3p=xzBE%q4^=_>Dk8Ie`@{7`i}+EwuaSKU_iH~Q6mhIR>EL0JN9Yk2OUO}v(Nu7_-`)p7l)W?GJ~*;&6)#=URk#aec(E=bIVZ&* z=d(eTpZ>0?r4Hn23iN6-WemQGGf`fgUPR!TvJn4hriAj-k0aq4i4t;(AD6~h-WNlb zHZ!;?8$m+01K$e@z1SoCyTV7_jqYx?PwS_rdb!MOw9KprxINOoRL`!D?BuMLPoES+ z*ZMdwo37LZYRg>!{DYNAHyQxYSxjQDxr;|x(p&x_R12KRYM$uYZ zZe~Lr33Y?a-0BHe~zaZn`P|v(_6v0i&-na=_d~~6Auuf_==W?NHA_Rm<79eYL8V$6BXk z48D|<8>Y>%^g6>_Hj<%Dk$zN028EZ-JpKcJyX&jt}k2{?j!Y^ za$Ds*0vn)OicY2Oh`Y(|P0@sP?2dUq9BveVYGKq(P$f{rrhWGPaBRCb?SUaPv1R&f zmfZU6U&vjbr7kJ*BqG~Ll8sC1@WNMViM&iA2`F}5af@h>#)~5dQVf&sK~oPi>P)Dy zhSNS)3a(&cj5mGPzg8o4{VNIO_b*K}e(K?jj9+!|2e%&~yy!x;nM?d2uu!AkLgFa=E zg_r5H5YHomg9Ewlojdv6^`xZOo>O%S4s4TQItFafWk$xWnm&2`$?K&>(zX#cKH5mQu+2NBWge3=v$kGP43q^d;nRsSBti038M4 zMK6j9uUwNazT|OI9|-H{%i6@e!!8}b8s2)sMH<&VZMg*H(P%?6kXY~lwROoV@RtX1 z8OXl2wlex8yMtcEy6a=!rMd~dD8OVkp$j6<*e0|$FXp{DgoWcX0VcBv{j=<5o6skN zSwm*zvjCIXgl;I7q4*W76J*~`EV?w?`i;`uLUcpuEV^ggVPP##Y_==T%qo2=J90JU z*;#mJVE(Zz*S&9@M57;zWkKVBc3J3i2U(~l6{|C?f3IT9E$l&^P1f(xto_X~{>BkI zohE|tYIA`B`{|2Pn~OxR80c5M z2+iHaqAwU;{49;&q@71#f&Sz27H{?ug&Pgf3TKD==MX{nN9~0!-ghJ78G$%+tp3D2 zlUKwSvn#d?%<=%U1|sO6H(sgz^Hk*V5BC7{Y5;l%!i%2Lka6HQI>F<*rMe{$X0}u( z%2L}>Z8tyW<>{7cQ5Qd>nJv|ys5a!F##RWTB%UutUVTyLH-`b`n15Os{FOerK{Q_?^ij(Z{ic4kQ01 zA=i^LiR-u!JdQ5IEuI4!JIXJ#$^9pB)1_LVSG4L64&++(-p~UE)7wgJM{!(0ZS+Ri zSig9XK6;<2mMKz#)QfJr#0H__sWioC9tD{k#5m->JTLDY9IxU*V(g%E#3F<)=Nisc z+vD(hcm41ZMsBOJt{+;U=;t~|G+N3=%!!12XD1fU&05wD20rjppc_X=xqoy zMyr4BS5&eWjU%pTa6`=NqPVXDoYyVDB@5_E%s+}71@4w7!R>+A(mWVqVEy*e$w1#Q z##cN5==TQ!bqPQ^cn_?9RODO*Rs4+n_P3A^4&>t?{7mgRQ4<@BxT5=ln0KJ!Dg)fS zG%nf2aNoQM?rLx|-v+lVz&!?`nHp}Ow-xkHKu5j`=;Z+Pk%5kiqzv@h%XH*1e**X> z0Bnb#ewdo$@BM|K?$Lgk?a1z3Qh9V_fzTYyv-t6rUxL*yrCR;yvEX2tGvsq!<`mw= zg}~Z{2L%}GeJ8>0TBH4-*H*^UuF22tr6#QRoq^~{?R|+Lg!Mkf76zyp@-V1xwfEg0 zpse?0P!)SGg>(AFyG%;33i3k-mV}X>a>80BiTk`wX8KU#Sn$ zfyZR^VJof`MTeTMKUxorcT(hWAk$(mK0$c{vUn9wc8Yob(A&4uXj|0#KzsF-VZ2wd8U88%fPOozBIu1g24RuQ?gu!aKHBv4hw{?=MB&R$3G_V0 zYyir*`v8~sYtFndL(WD`l+iRT#b+j5{Zz9wQ?}rLb1w{{`ZLWC4?D^k@FyDo z6x>qf|DiX^^@Tr3k!ttwF|Vl&4xm=~=`Lvb5NwgQfzTJ(q#W3vvvMJEx3RHS+@+Y{ z+rdas5kL)r(x?g;-dg$CrWRFyu7w4luer5ybTt=?LsiSKL|v)b`6z}$?iCRFa?E|b zjWJMGz8O7t!k3UJp@REW4hOYSBlDqOf)0SP%)JS5 zMF>}ZmVQGRgub_8lYpC)M{_{D#Zr&kKT&uLG155w|zmZ1K6;$6n_0X8jN2;&nSQ|hU7-BRnS*nNu5pF-M#D@VZZmmR8 zSPVdMv7$%gfr&rOH||1)<77yK-|OeR89DDZFo*_A9U^d19i0``%AG}3Eo+Esqvm9g z-e!F-LEeFbQ90Bms9EwYuKudzWAa{9!NV|uk3<)f8B6C+;!2 zzsYO-y>j$y6wvteb^cyihHskhtC52llN%rCf~#A8K1Tm<5?tT-IcG@BVR8LK_4|gZ zGT`w=Di5@)juJz>#!Sys+MDM zO99mXhu+FQ8onwM_>ddaIZ#zn%3EtCh{+Q;&^vM-cj3TDND0(vqkg$Q-`6 zMmjz{4PVs_JQ+~y3^50{6hxctiWm%El@?q^2(=8#|5e#x(D4AvM{!@pJTk6l!rb}Z zl^R|T7rz8Ma~AC6P=n;2^L1xG!w7dkRZ#S2&Vpsh^?+(e#ObqORq`CQu+{RkXF{$< zVWzqR)V#RWay@QwC1szgCF_J#brC6f2$u_^Fs3*wl)*N8MnHL>&Q>!EF6Ra|+z05g zr%lrcC6onxU4+-jloaC5l6`S&eX!x6P zGeNp<#yt+@z8SZaCUD=38&CDu$}s$yZ^o5sli0^T+&AOiLYnzz+!NtahrStCA1zwu zn{i=O<||2IuKP+-n3MaJq_x>8`JWbXrdVNF`YTCcrZdF~bFx1qqTh^L?a^H*#V{7Gh_?d6UE!GMPeKYP0q?vEV@$MD=N>a59cYfDT`R`QIlnF~XVzMYGQRVTY0U{ zlUI{hokM4#YP?tWMIEVgsHz`IvnY@-V?wE6EZqN9^WM zRcrEnPEZd*X|m%<)~%~&&xv^DV^p_RCBLE0Yj+K^$5`gjCAYCcLf4g$flvide1ZtT zcmQq={hpku29WP`Lwy5PB`MsMAZ!jjLDgOcQ0>`6M!k;)ZVeRMP`F!xx;gZ2_^Q-o zkpoq3R4LRIP*rjWZoBFJ9GVYX^`i-SYe~L$3=}t8;Eo62=Fp|^Rm+-?i=p;5#D^4p zB?vc%c7w0FT2=^9KU%eDbCH(b@URtN`B=v4DP%lzK}S2P&F0V*u=RotcgaIls6lpq z$wL_7=Fm;VkeNfXk7X|X0*q=#Ilu(fABqm5xmUw9 z{n;Chmg0|ft`s$P%}7{mrFkB)mPW%jmN>!oC`9JZ>GQ?krp zcj3R^V54x`DeNN_h#$aKbu{1gxjWyhG=MG(hXXjKm^the*lt-EhsrDqX9I9u`eFEP zS@;!HW?8rfgzM4=EDx52gP{CnAz%6?o$aAkvh=mK*Gaxf?TsFtEYacRs#s*fsm2kCv0sp`TxRfJn5599W&L7F-!Awv+VLY->Gbv33b zuK{4CYPpk?i<3dhKTxXNlq*$gDL;)gH|32g)s$-y=BB)wluJ{7%BxrKq6i})hfq6j zTFGw0tpwo8odltZa!$jT^ite4Dz((lM5^lclq7Jgq!%uWCYSml2vujFk`c-d{ix#C5UPWlyP;;&oZIy|tOkgLMoeZ=Z>U#_UiQf=06Rx+lF=CMDn`-oK-)y)oFuL2c5bUht^ z=FoK*?+#s`hCF=edLR7$q3fg^N_KwmGoptsDvwj6p@aUxK?)=s&4M}_ieHs%f!L^p zoyhs0Sx8j9o{)b*)kWW2EzjUDoyE8_JHoKI9lmPoG5mUf%_XR6xdnHzB7WA7C5(Wt z8h>6`40k>LCk;0lm!*O~aJ~p%_YYEXo#Fn#e}myp!5ywR8#s@65cQhjh8u1a{tKb1 zB%l1PQQR!De(FE@I5-SuI;b{KRiZ;?@f-lZ(2$!R35LuSP?;gK5`aAA}66rnje3xLZ>M*x|e z=ulhCrjNDpk|%OX0NLJGD*mZPZ0%-YHaU#qG7XlhQ(SDeBD*6mfpCFm0v5w z{VqxBE?l*A#@(oVKKYlBrSNsfPJdN$4^;62KZz@dN_W(%WG-%B*ruL*0k-bJRm#zaxUaan5Rr4F~JQH3T$jExhNUs$?|oO0afA)Y-7FFu)L?GY#+@QEpU#-VD_g zz?(2ICI#>@6x#oRd|kj_E9+XrHSaFL7Hrf~0iF5!YX) z6Ua#9x?zJpSl!S{ynY{{O!JWI{!Bt%fSLxy3#;K*p{mQmpQE+;8z{Z2JRyg#%+=W&|j`t2`msLoGIZ=&o{I-i&9PuINT8*)qJD>d-yHr1Zqy;tzZJ>fkcm z>1ifiBo_&fFjmoqOrvX2$QsoTUWv8qt2tq; z0~I6QWF6=`sBfWaWHCvEBe#z9E@`hsz^(+q$DwMZGx2(%rnZhWh@|^if_7(MSgakX z8nM1vx_7d0XnQAn5^?4YGwO%ddf53JW*Fh#Fk3tue#6X?>l@})5=g&c5-pYaJcTLp zQ_|mWP5!ZD0+9i;ES!yP0` zt{r4Q#5o;gA%!{GPbt$ut^ue!=a`u@ko61|({+%?k?Wp!LcWLE+lIV@ZOD6R_#v<2QFKM%0mfU8)BarLtm$cb$Yp7D(EchSf!7Nx~vtVNmqv=+Sp`*khP6#1{ zat#xaOJ$HFNBBM0TJQJgz2Bck=lp)(|9+pxW8Sm&Uax(5@4esqvi90*`(d;V&w*{D zXG_M$29R%!SCHv<-g&J02|)Y-z(gF7roApKX213Gn05 zvQ-#+JosD(-$u*FpmImcHX&Y0rm;4i&q3K}xx?F=kCr~(nodtpHdU%|IgbGLUkA2qxAFRB?o6_kydDX830)5lxJ7lN`;a|2Yp zqh`-Ak!+{f`dxq2>>aY>PO;hYXw-ZN%0|r(2osN*ei&^~_rtbP^J;>`qh97`e2M`bSM4VV&YEVuX~n$x{v zu?F%mC>u4ufXW>;eY`c09Y2mn&6A;WN6pD@yO$dT8;fnwne4_qU=9}jI8VZMXWVL(b{AuyhT};@Rnpmnj8M&Fth^4UZz@s<7g74>|!DeOH4-&5FQfockS*Wn*3?3KF< z-$n=zt7JSeeh%kyJkstYo*Tjhi%GD{MI!7y@Dp@+lz+5~`BGVB2g+J~2>e`OZxoB5 zOxSxHC|}sS40kN-_3`#$<$szK_8yKq6!uoAu(yW%m$l2=o!v=TCggnpDircox-sOr zJ0=9=rxVs2un85^V$ugjmAelr4Q2LImq|gXD&fKS$M#d@+G$fI6g4%jhk%7;1|)r~IvRe#(4_p;EWaYY#AvOfEBy5;Klz1c z+KGI|M_KE*0+fH3+$`L&e8$IH>-Yq|%s4YnW}9pXu14hvieFmQIp>5Km65_)NlzfA z(^&?U)#)5X-WP}9{(wtvLY;0Nh;jN-Z}I#fWNUq1AjQA?m#DbF$++(n^4F5XJ``@+e% zjyzH2+A4{%;(Z>JZ}j;W+}kOBNe5K8zPy-#r=xJP5K2ORj*GhBen8322F=RqMI4SFmB11w!60t=i8CzNZC! zDJXkSO0xaCT)7uUBvaFp3KR^ce$D9@7#KK%Iu;6jY8pr%$*h*-x%kVqLUvbTnfQBm zCANke-M-j|&~vjdc_yw(Z8-yTU(y=S&fkQMN2J~V1YJwmk_tB8hJVjC03IpVa2?wK zQ01h40K8=+9C;8`mnFw%$81tEqjq9Y;3KxN!`o>i_0 z&LpS`H$<{|Cm~d+@l|5_yXN!v@7R@t%D5Xfx94F0Yp~!{vGGQ5H{*kB8{92W88?$> zm0Lg|&4!xj7O1=T4^4v?piDbZEEmd8p6x!$;{?83z>GF6vBcVeKFZS$JO@y$9hd-# zcHq9SW9>knZQ6kwzKyj5E8Jm}aE-i=s#)Ght}oHjKN;$3sEoUTXO$aDs0yVXg_;Is znv%o(H+d_M-IGr6V@*k)ubPqpY`ODV`kpTQzsZk4RV}}wk;D=Be2ripY>OZ)%xXUd zPt|hgI=?V|lvkL&0mX%x07+q%!j22mXIo)D4nJ14{D3AhCCp8+=na0EhtGQIhmcFNHTKYao zP0L%!>5?#kwem5jrsaeBCg<@c^OTwb^)IMN&c|Ze691+6SGbROwxw{i$_QIhNe_F>f3U%b2bb>tg5`B6^n-XV z0-!zYre84`sDK9m90OJ1dNk&obWPO5E&y>MKIn3RD1oYQKWv>BbOT{M>6@)005Zc4;M~KJq;ot=!o`cG`*LYTOITvzOC{6)U6^kT<_OLVY zcbd<4{@pZa3WYwD=JsCt7P(-}df0*BUdM;oGr0GmGVTkWRqibc>3gV&?l*PM_#KT9 zQcAn+X|+qkl8t-VJ@8GrVZ^c@RHgfl6Zbw!JB45IqzeO-r=a(9LDDJw@iT%47-{!n z4%<3~SK+?_M}8IVddjPtypQ&i9iDkL} zCU53(q~c_dUEx%^-E#Q*&p0aOc81+XlV?MU{~!1fXczqq2^47rYwt_)wTCT-{cjl3 zMN1A=CnMOK0}sFXIq>F0_|#q)PQ!!Rk$$oN^7}Isi9C0D7C{Mv|^~VyNqWGKh23^uynNYdQc(> z-X(d*u>XgzC=V?o9Zp^l=f6N#xcv86iAmbpk?)Ty<$97%XDC*GV7mF~Xh;4nzA1Mt zsGp#$Bll6+j@KywA2z{!jSPCoe6Xp9vJ}+E~*!LDt5sOT=%{ z@(A%FZ#Obrw@h{ie@xrRxk?5}vvBw{kyneXON5Ql3*wIEVX3pYXlD8Cw{ZbQ1l`I`wW$usqQOWYRF=K-i;UmK&$>f zIhl4vP#7G0Lc?IxXS?*1`yzk+BtKXlMk&MTsLvQqp90k2Q_`t)+wpI$&#&cF-w*u>c zszAO2-nIp}7tmNyrkGT8`}#XlwynQUfW}*Y1COy%5xIm4;!n!wYEIq07Dbr^TLkfC zuwz9TpKV)z^Weu@e}lr6Pl7z1)GdRS{RKeumy+PU5Unx|sqKuC> zNx|cwZ0qk!sCu^k%2gqz59KoIE6Vt1ipzHNx-=-Qw+nBc+|jc}G|a1kQEQR9wP=`aM30}2SR>@i4)Um<$nuHsSHQ@)RXkJfdfe-v z(r$1LeDsG7b^L$8&nSL|;#cFoU-5al_UZkAjnNC-Oww6Zh#*lbnyOayvCD42IyZzjFPQ=1PV9+=X!;Uib-}Fwh0d z{L=Xu!OT^7g4&vU%#_*{Dg%Wqf}HvAF`XQC7eWBq8L^C^2#m4_GqK(p$XTJtZUFJ=3ZIX<7?Q| z%DRNtB+RSDG9q-b_9#Bt+QnKO4_Dm4c=)iJhN+&L-GEEX2&kCbnCiZ{7(0gTFvRw9 z!|qQ6csvhVthwMJR>-Eg<1Z}=4hJ!6fh)qq&or08<23PjBJ_9{kG~y=$2=#)=QP)Q zcu{b?Af608Ub?I(IA1)T3WIEOIk$s~$3NAh!hPNslWbqo?B5&3@dFA?#-G4cE%cbK~(G-u^4%eA0EwxZNL-k8yvV z1a3tXQ^LSHz(3^};ddtA2f|6YTc8fnWG>-3Jw!^wY<#*y4EPfK5=Cx=8mq|eImrBH z1i3%2ezGFZfjV8ONm3k8noBvt-d=L~yy%YJMZw4!c1}+6Ou2V($LH4vgR}jWf)Pb} zem&#t?E0a&1$-Wcn!II!?BJVKe8xzTVLrYs85vo^~$2)8>k9b!E-R!#_z~M@p<@9Qp9km zJC$k;^$=9XJ2`{J@uTq>^^R1|=rK{{90z5UQ*n(|PFgF+4`Y?I z9Z0LB&qha;bUI<;N=j=bB|>Ut%>i$fH3rHms}&)ovN)5&(+^{n)&rzf+V)UZX+Mwy ztF(uq;!3NbEUeO=C047n2G{zPRx1dtv=i{RN}C83S6VTapsmtY;BS?->vevm4F;i= zb{^hVX%9lhl~x15j#;e3-zu%sSijP0L0F}Y!QU$FUr@P~CW@C&g_S1#*QgD03a#M! zqELn8P^erLl7%5Y8k_jEL7584OsHHH5+83<*0({K;$?nmQBs9uvU`rjSWVd1*^sh0 zOwhA^8QkH@PPMisHu>G~&MB6?%?pElc98r0HdNd2B8C#Dx|1eh5?E|SHqRS~dBC*$ z+W>3}hry*gHS-V;0NWo9pWi|J>$8p`RI?DZw-g0E@!=RZ)TvNau0Pb-P!rw7Jk#zS zG#6^ZC?#L}4|k`e+#aA-!l`sMIsCR~9-VS)NpUs|`Fy_P|9!~_&Q7_rCNuJ6Bk=ic z2NA(Ouq}cL*AffBWs>LNQib2bX^RgR@=jqCfvR#<_#Fc^(VfJz(tV9^Y(zgR#kP{? z_FGlDf!|}OEA*7IIk*S%(#P&B3WmavA69~Si6s0vs7Gu@&f z)Dp(``1iyoNAWMg2Wux#W1%=0$P)`3 z8~BC=ryEDDr(wSuANI_khCyZANS;;h@mq_6GN_3zt?p-T#}+me=l6(bsaMdpade8N zRzoZUp}0{h2X)jP4cO1!M^W#BYNx0_sTx17qYiGs8Q_Mby)}F-tl|IWB%)+k<(8Mi znu$-!9R@WUD&rRLta3x9^Gzt#Y(`P=8kC70m-$&$vEwHoW1*kVSE1i**uK!OHW>k8 z$J0n47JT}A75b%MM`A~5l^^&KsN}Q*NyM$v=WDCnB(Fw5Y1Se+-Q-80a?9^YB7Oy* zudlEWw*Lx^`dZVIXFH8xz-|63_7XxwbyKCsRrYE`45BaOr!R;L`U=3NH6T zq}V4+piZhucc41qi$V>ra+FdH=toY3n&ftmnV2wk(K(2-=#)(e}xH@j-aY7t_J-N&i!5M1G!Z6jtOS;XNHuGz$V z?=&}PTz1X&;v!kIO~fNyvzf;WcqGlC|5I1=adjBN;0-~tAd|aC7^4!E5|d-Q@aReH>Dfy*ltQSIGcPn#b4~E zaHj!JPG#OyYVi2HFb0&B~HTk)Txh#^o%IH$4D)#`? zO;BmKo@cGsHf%X?0q?QnFd5gULG1~Z)_O@Gby@H#e5;vFP*OA86T#C*S`D>JF$vPT zIUh>w*;J}M8y~65gsHHto|ZsKJ*CyIjSsZt!f)`c&JL`wI!imTZ{s6v*>E0wtG_8w z+4_?fN9i8x5_;L$}0CILQ3VL7M2snD)~RWi&gR~P*%ye5XLI`T&TE`n}_cw9e`Ex zIlPNi@+7FZk`qX+kLhR>?0y#g*&>t&;x@ z-zs_EiGC&fNUP*Q@U4<3LgiMnoZ9Rf7DBu>d;z4L+WZ+R_xwq>5Ff7%+prX~^CxFP z<(@zB@wPUs0%hko*;m2od!=7P+o;7)P;ueLQa-Fx4wc*L=@0ZM+sjBD| z2t;KNJBzMyoRj6gPxO5P&VJ8WMV-mmVn*u*Dbe82i& zc}KZleLCKDzq;&7&LPGcVcm!7+Ztke7LRgQfwjh3yw&i*<9JWUgNwd-7C*os)IjVB zjK%+2^%t{`gYn;gwL1X)0Q}Y5qa;wYjs#$7O!E*F{0)x^_Y29?;caG3%kVEy|IhI6 z_8|Uh*7PL&*J*}c;aM&IV%BsQyjS3%ze?5N%x`DTK1>oy9%AKu0OpQOm-8#oqRUyS zx|}{xHI4=YG@Z^}v1lwhooUtS^ns?^IT@tscJ=`&x}9m&?evkRf%Gy+)A1Y+(%13) z6^`h5rd7u?5mGgg4royr>Uus+NMF};FdWhKOslSEBBUrC#fRwYexA2;q3V8CxlOwk2B!bnsb!(3{~5(5W$x>Lo%qG)i`~=E|sUj_Vqwpg_+O@bg4Xz1mXyMzD95X?1Ua@dp`zG5A;=l zaiRJsuTVDuiVHOXl0t1qMaG5dv#n6ihaVTJ=z(?)b5qO*fXxUn8+jc}8zaP0=AuN76x;2}Em*>r$M?^PJ8T3)$Fp{Huu9)Nayg#b*|@<;%& zs^wq+*5Q4;XJM#nxiyGb)v_9db#${pn5yOS;=+Wg}>_~JeDwjk22vl_WD|wG)pFUqBSPVOgKwhETk3hTA2S_4*1)s04 za3yU26{c(!L6g1x9Qb_A!H3ybV0t1dmwlvVc`BFN&}vNO@+c@%xm*twt6bLjY38V0 zCU^7%lJrtfKertg#6 zXD&-7l;|^kUbfHlJ+065eUg2qs9dfL6WAcFUHeQ^xtze8n9AkTP^NO}W2@Xc{9~2N zS}8BJQfw-ho!S(7Dwo|JhMVj&P37`F|NT74CIjys1pKY_}x$tH7oOUvMPVjXW z{U7);i>`Dsi%#%mHr;*Scs5<_2G1Ae#VY*d>g|$8<-(9~)kP_mJo>kcQw<9yZ!q5^&{eoB@VS?Dbk16y7u?fBiVt*uoND#{l zi=CeCxp~YGMQm}vXKNk@!j3Ht^z`#suf+i$VR`&Hk;epI^7sO5FORLMx?x@_C67^# zXB}G@bb!I-B~XV$Q44b3s8(v>v4Th3o;aG#VW__KC|J^GcEhDC(TX1tvMN;tUT##7 zpFB(E7CfMu_r51xAhGn{iN%`4GOrCPe%<*7@u+a^dDh~++X#0^%8kJPNcC^RvzYd= ze{0yR!*JzHyl=n* zJ&+zK`9awRY;QloSz&tpbJM#&PEX`-zY=`8*Pixsa@w@$PZ3b>s?XLu({A)md}to- z;5CkuRHgWGhk!nB<%w~6vUD$${wm$^)bm=us^)dYRyUYawJGEsUl^QeP2pPp_2Csu z1aT1lDLfu^7xApdyK(Eh?JL}BT#L+woZ#vc3WFca)E4tI+gt7*?9lFR%v%zu5U-th@7RtD%=TYA)=m3Hue{r){he5RrsJS z$`cXF$-EF0hl0+erGpcNRQAllwNzYd#r*)TBNQv5e$0lU%3X`^`NSkdiU5b7#8-|- z#&zYHa=lJL9~Y|JJx;{60=sZKv`2xhzyq~lo+)=Puys%sZZOZ{f3Rty>cB69%P4M! z;x>W1UvYUn2MbQMQ=5>lc8cqwxB-1g7OKiMA)o!AD%|^&M2&<{t<=7RSc6Z-{lt?J zA;h0hRqo-wg~2vtIr`bfF13U#nTI;WVj{GQU4Dg<9>*?rDSn*7)r(yY>|YpO>~aCr zxgg3-3k!rArC)JcVR*62Jy53EGaM?`?5PH7Qr$!Gw~Jj0piIYS*#O>_`nQW+7J*f{ z?wxp>j?XZtSjVRhfXQ=g4@VV;!KHlWdM}Rlo*$+?MOn25sa*@)@PZH60YI>$WlKX5e-w%i~9?8qX z&@xxaEoZwp$46LsUqu43?Vto-%KaGFIpsbjH;=Qx#Jb8p+sgeD_;I->_*(AUofVb) zWXdJC+^2glWydOx2XEzm68PM5_wiQl*MYZk->SZH7gLxux$pE3!Ys?0!t~i%?q9)< zXLc7yDRm;G3Ueyqo0R$jLgq@T6L=Ns3I1?1QtG|hnv^=SP;ht$lTe#YfVp&y zCO)a-Eln1@_W?;+@N>jqvfv+~Vw(U_E~GKo^-GoTV^OZpSJ}fr*uE^dMMvwWGy)Y~ zET<~s2z>X=x;$g@SM3#**ot{#$#J>6RUR$+VBkN?CkQ zld||exl)!s$%GP87N3`uviP1RW$}HIQWlX+4+;}lE3L_sOrOG=m}L3}D3eV4*edq~ z{+?u-GV~?Wzrpn+)51+kSx8TQp=5div!N&H^v*vhl1%qFG$EM=pq*Vi04AB<7Jw(2 z24J1srp}RMdgUPr$utP-++GD?lIaIQ_(lL;?UayAO9<`MrV+v<(^n9}mrP#($CFG; z2<^<;<8PAbBM7mXWco>P+KK&6iYA$E1kRUCp9klA&j`SnF1}>CXD6>8Q8OzhnSS?R zUp(cbJn_^_K(Tl#0g~_TV%V{G%4gem*BO2!o-)aFpD;JwsnKwojoh1L`cG=imrPHC zW0L7r)L<-`j^fasQ6+qou32k+#ex{_!WGJheNXE%eV^Pub8#}EM4##NvVErSX?>>elk77^GQBKJ zAl9ih$#fNOVv_0Sp-eLEW2@W-{5{FEl$R%&KKzJ;Wcn$%$v)F0)6@O;^CZ(fXezN} z+DCbx{un^j~f3`Mc zi{h49yzX;kVQ97e8z{3syDL;|f7TD9=SsgOO0z$^0AOr?HUX3~ruP6e`?EI!jP1{U z9p*wla6R_k@+hPyr-|54)(Hu=9D6?ncDzpT*}6`+0d~AjSQ|zzq*JP0S;)l@&vJ|#8klP3nH;@ES8pzE6t$|zwFm51=y_KRiklT4+fca;#K&6$$v-b@AcsNaG?2%f8+hG;)@CQWTXxM4 z?#Q~XLVmb0>kD>d9%BeniDn6Gf~U5OMhw@qEvbBC0KI3fnEBu3~%e?-#b6DWis`G$d*YB zez7f+;GdzF9E`qInc$3nM=AAc(Mz&By%3aDJ6TZES(#y*usS42X$E>O8bHy>}G%4MKT z=yo?$J%$48(x1VUi)Hv@ibJk1s8Aax)#9(x!PY|}BPUlv0r1KS$N zFHl=(AfJ=AHIT&sx6nY&Ch09SkZRalXdo}b{=YSleJ|Z&1Nk=z{7(&J5bp~W+>yV^UTH6$wy)zO?CZOP7~&~cf-hg+A+WQBYnm<*CY#51z-%FpcmALA zc=+X8%;Q$Dy*$d=Ci-Rbcn_E@G}7U)|8I@7@rW(v@%_Kfqnyaox*kCko99v3TGvOw z-aL=e|JA?#ipoF`R@d*^RrLFR!;`sM^h<`j-6eT` z3YZa``-4^L5<*3oBZI9B;XK4LHynG2Z@#zoBwnZmE<<8K2yp3y5 zgR&XgI;g*#p_NfCmf>Ts@@Hss#b0M=6Y)1QbRR?I&d`>JH5_MjkE^2@+UZcaGc+G> z8La?iX6P0{Z8k%b>ljytiRb{_0twJhAmi&8YeRNCLwj!&BLTB(=0T%TqfqK@{NjtH z{4hF0y9~BnEY+1D@x@XJpfsR10PSL_tpUatOMUH?gf^giV8<6rCD_t{R=|$?U!Sf0 zMx!zQ7_l~t{IACdA7TB*WyBDV5edHZ8(m;$`wjWJ?K;MdVM_8HSi`s*V0^LErjQ@E zmkAEFwuvtq!5|kb6yAmq*V4sh-2J!$XJJ|OzRN`P?B-m>dCUPj5 z)}EyBT7QPtBxJ`80t5rxPTep(TLQK#m1yGqhF! z;~83WuOzgAJPSLXp(WVTK!GqZ(6l{+(Q8)9Xolr9eCFk(-+@4@EEYJ99T zij1=v*`9QwIWsaF0izznMytB8%^ELiEXHdYX5)4zV^_D(Wypb{D|pbAwapvvT;Sw( zpX)`yaJ$$kDP8|31Do6kesXb6)~}z~QN?EYOPhGt(vjc5mn(3T-yxvNO0ShL zPey(ccV98|+GSJ0i0dSs7j7qQxsj&%d6zZ_%C_f#?N$311P2^?6LvW$-jp~=v*KGa+V|k=Nhjkz8r>l1_a7o_cbj{T-MxM{(`?#JG#M{EC90S@SMfjky|1U$76nUJ~Z0*EC4} zHlrE@rEjbym|TaT!4AHXV1E_CEui{pqSbj8!_#EE%#GYg6wQU6GrYVk zlfC-pwN1QQ5&K_Jt)vMQl-9v^X8_bhmzHE}MdA!fUtUL^Mn~)$AcFie#_*}SroxG; z>tMY8zf{-1J|GgYOa51-{U^Lcbsa*ZEA8_=!NlnKf3L2iK_#o}2r^#gW@vQ@?N^t) z$NySgx34D?a;!y5E>0(`uJNv}zl>Tzu$n(N{1uQ#v}m#e6MZ_Oo89a8n)Mjzmgc%v z_Z0=wDcL>Ug9cd0&VcuK&OK%plo8eHB>w?^uy@5{~jsY z#PA+~@x(9zlyScrpiK-f2N+KbFAZ}cQ)C_YyO7CvVwhmdxPKY!cw*?Yb=)6(0Bq8~3+*(6leYtV;x-cajuXWsyCxvApPbZB! z?%Ra$a8k;h5Z)AGbpom5zD)*)gUy```dAzHZ6a6$w%&>0lrZvc)*!@gk_hT5^j7ZT zx@bXp|E!{L`ZwgEqHx>pT>NDESMCP#>;qP-zb)Q2?b{8gO#8~6+`?TZ0IBwO$%{?* zJ^&g|_vVCI$yR$E;p6FEf-Tj)*X$y1y63aC+E0TW%Ms>=k!!Wrd#cArShX)ChIqP{ z;7hfqU?-}*Licg!N}*+^c@<6!Kh}z$H@%z9o8?aL7Kb_1CXt=qiGktV$(@gkCwGF} zY-+dHnFT@HFyhJXKZ6Q_u36VN=N4dW(fR|M+KtS*WNMerx4Q4L|i`YI>`@f_z6$)Ds(8(bR9Mn~zIoNnO@%B^^@Q-G%9)g<IG*m-o^iR2e(t2}VI*LL~{xj7JX?u5&@HaxLhPJHo|oj%rD z_=Z5Rzw=DF3&4igbxw9`$Z6LwaWh-fJ?qk2DzYwZx1q~h3CQn?eNn zc z)dK48u9P%_i(2+w69gAt55FI+!Ohl~*IoG+F$*J#S?T&>ej|+eW-sQkk1yg@=v&FQ z*nih|`2(Ww%Pp`IwO4}$ylRktE&S3s%Xs0YpM@Z~LxXHJJW5_z_*buH&Lr=7<;CLc zC9i2@P`XLt7whiX__^M+&x!J$K`@;^H~bQ~v)&T}ca4v+j=^r}xB!5T$20~@r5T4v+c78IX9U@!V9oxfjQtlzBACUXFrcMMb`LQBfskK~w7n6l0W))jDzg2@`!lUA;*aY=}kUc@8@wiCQZ5A5#}SH>N} zGws$PWA?H3$(f9?KiGtf(LS^`wFUWbrn(-d(hajBYdk;i@3ePrZ24S{CvU_%zOkiTk3IHbMW#2k9N8Dc zQF0`)()GZ0e2d=J=%j>3$xSUU5x5TwVyjyvvHdX+!LfMW_OKHyj<2tDBV7XEg? zafklcz~)3#Ur6^x8~R-do( zOuK_~pw@sFfgPx*3-oyz&nlN8g)vZ-?m@mxKLKsT83HZRPxy6xzQ?oDNzo>ta{Bg6 zp!FB854FbJ8f^VVoWN>>-armFFXl7wjf*)EN*nd_@Ha2&ea?-GnkG@{*7GK_!cvtL z=P0@LruA7x!M0jPf8)uU;ocVtjnf>sy-f!Gt8g-I1<#aQgnJbfjf)S_kKR7fpWyqS z=sts@PxK5Z`9!VpBtq(2W#GqeMM}7>5&Z-eH6m_L5v9AH;d_~oc}VCA?sUygvaY_7 zjw<6%byyZWo05^q!R~>*Wq>LiTh;SEjX+b?)C+pu$~t$9%`L1S7cnoTt>U!4a6It86N@G zTJO3Gt@};6zF_U#_~GY8U2qvx+y&Q2DCvTqCXjT&Tn|nlJ3GDvXxt4i6R5P_2|%SA z#^^n{vh(AG=lfl8usZ6B`-7FPIOYBc*3OXk2OD?C?FFl?cMq^q*XY@TwJ!NKu+}Bl zLd9M3UM+oh`TRI3Q)$wF>9spr~47!oF_lPYW>WSm$)ct9;6BzWWH zV$f?Ou`fwP%^uuMd>MRfF3?{5)!4yh_{TGV!Q!tofL$n&c-*hX->`aBNRRm)4M8^UE8WXX-+Z=8S)PI|+xC@u*V5PC3#v$Mw_zB5 zM>bRGM4d9h7TL(_>{>pT-N2a_oHHlThBl{=u;g?O!DRZaif z#nFJ;2P$_!_3<{K-U!MD)CEw<0hIy@`;D8zbgbXl5V~~9HoIN8cGLN3X~_Z>C}QSD zS1-*Vg8Xw3S(om;7=~CDRmQ%`7*9Vj%atr{gq>3-)?1u2f)O9%FGfw&U;1L*(QCYqE(C(H@9t9&eE9_! zu|A@hCn19Tr|=v5$?*ljxxy6tCCdB^qL*yeH6FjCq>+Dw;EH+{1kbGoCw5U3*Nf(F z8EosMaCM)oaa(t!1S0o{}Q$sKFLY3zorBBHjaRB{JOLCL`Dp-6Mt%^$SVkTJ zrKi#0m62ZrJC>10Y%1r!=-LUwWaMuULo6frV^BLKx4}-x z$Sa-5!=s!-nyQEjV5!7&nqww;EqvKl$NCRcY*E=q>hbMWuw|n@<(fb2 z+p6$^c8vRY_-3o(8mQP-g^#r3+>gLFTNSlXzD4Ej=g?@gwki@K^;q}u@Xc1mHBi2- zibrtAwki@K^>}wJe6v-t{Ue*(sz~7Vn0F6QW~*Whly9rz(?`+4M%AIpjrm7pQF$)Z z3;3DAhbT7r7<_{dbBHN6_~4^F6APaKicKseKyu!5J5rBLEck3Y?|B^j*u;WZRE~aa zAnd63!(hyc#%L(tqVkx>A}bn?K*d%xqB!)8^r&|a_^}ZTpRebnw}adj{M0v@_VgPx1`5*sX|uvZ?3Wt$2wyF}oETq0DZDkF9e1&-3k8 z%$4%eGuWc_l5!<*W4jg2UVs~)!LD#;AHt@kdG5izGq|`hfFL8FXjzxhM@By_% zX547)Ti*vZ&f`Zoqy{n-nMH%0S`ZCjL!q`XfX#qy1K3ii*w|83 zW-=z)0QM(*8^Ag~x#a=uLijd-O^5Oau-9>KX#o2Zz71dp|&)D{Xxhr3}COr-tqwUItgqcg6Xgm zW}u=f(r(5Z!2SUEUkkOv!Yvl+5ZGHP)LY@lg}S8y>@|=!fc*hw1K4UBM`(EIMft|> z#2pV{wbHwKhL?7F?tdA;dV%`?#{f2#H?aY1E>wL3*cbSFhLxnLzr9dCUtP=&AcR3+MUg_eHghEa+iG?qFi)I z8o7re{|@pdsEn&t{O&n;Q(?Lj{1J+u3BHHoPvyz4+$}(=R3mwqjB(*ZCKLuA;(=Xg zkY7SoxI01C0@!xjJT_4t2JxcCwNp7Cn^O7seE?OVrm%|_f;~+xX0HSxwy-g^3iWp= zvx+?!gjvNtHf2_^Q|=C^;}s$Hv1>q>eeB=x7yH=QeXS@A_ELmc%B}@rma^yJFP5^? zYAL(BS6XH%)WcvDH7_sT=KH@K?uP?;gOke*1C8n?WnGx%eVdNs; z*pd-zANN;AtPi15vPP_>BDUWh1qw1zGMS6W^Qy33j|XO|q4t5|E<%cUE`Tl_8nOj5 z4FBJ?_-}`52%_9g;#mu#Y!

b2Rv$)d1c-S^S(?|7C+mxijEiqtsBS z@lfTi6VJim)bej9ypL8u0M!es!hMKTu?E1l?Hwv2Z%mAA1K$P}+Xk)$VYY!U!ryEI zcZTw81OF?s4eap0i&#_cP2MWB4P2oY2@VEi3EeS?-U{0swAWi`*-%`p$+HGTm=FlN zR4yMxeA{DfHldCn>@vBxq5R9_%3UP~Ly8wkO`xHA2@%NYkqRe=uKVE4xe~7Zx)Xm< zm@e15Q_JvIY2Z6}$BNSVvTMLkp7kqA`-o6cda~ceCHSH-dpPWD7ssA5;`BygD$+w( z=4t@N{jks1Ob&+~i!7V?nXFf>*GE_;8&2^vnczz%-}N&|5xq@wnJXnag_{{JCG5xA zk`9Af4Q2Y8t-RN;j&9sk+CF8Ey(f^SulY4ptgq>ZvCeKjVN73hS18lhJQ>RLH5u1_ zAi^=iou1D&h1suf#bWv(=@=h}+7C)Z+6Bc0!F6F&he}k_ zo2SqN!LS{SwA-0yb;vG;-K9@Mdc}j`w^sgY>TXKNmljgiEswGIV)*OfWZW-2)9$Gp zl<0lZUxE_tnT(T-K6ZwuVJ@$cAE%G7cHjCozuhPJ((X5qK+eaxEKDWNWQI86kJIOCCeMT&f1JzxOxF8x z`UuP9Pl-$>_>##*u(O$@0=ZR>+FKna)E*ycs2SHUTc;6E+s2V{`qJujpWFR9^-+GE zo&hSZQy-;unuZtFEWI`#QlTpM7=b^5hmT=kwz@ex*BgYNL_G{KkR+81`V zxU9onyIGyS04T0gpRbvm2s^IRIzN;3)~S!MOt!hx&t!rxnf%$$q}J)~jW7@9B_y3o z#_fx5#&zVGc0X|%(MOm<`G4@`wi*zaEs#VNyCerIol3^Nqu7sma`y_@ub?#XX2?tO zWe1#J+@ZV(M9xB{+^Pud#qUGP+dl&2RcV=W{d<_{Ff38czVDh#9MHlQL>`Q1@<9`W$47yvoiF{>0SC)T|O4A7E?US7t zqnnd;P1=*j5Pl=JsB4sPHOso>6hzysYw+Ij6v7sf)3ZD|=d&!~Qq>V&&{Bx{26Ju5 zB1P$YQ`U7OR!iE4uRhs{t6SD3$evl3rk8NlhAtMSbE#(eZD62x!)Fz-Fn#w~U6|g@ zN?DE-*~0WcxZc|d+aT}C!Q2Vx1r!EfoVqpcbbrzRy94+0tnEwQT|?*zZZ+<)1DVgg zTdd08tI-4+f$XGYIdiEKUuFV>2WEG9*5JLv_YHR77yo0L1bzDJjvyO?j-A zAL2C*fs=My=kl8rutd8O{`PQEt{YTKD2b~HdXlwaTmvPpKk{~G{~OYG74K1a7~fb@Ip{l!{0-NH7v=~(S5WxgF+Zi@>H_Cb;?yx z2diPE-OD*_yJ~s>{AF+?0=cWYTOtCk{@MT_zU&VkRi2qwaha?pzs?45|<9Htil`orKAj9A-}Vf(F$7n z{clFMY5S}ycMksXZQ8+0^bm5Jb{o9I+q5g)1mdms6MX;hl=}e0B(2MHa@dXcl`E$% z#W&>&-=Z&ol6=*j>w+m^G_xdM@6#1M3t;=fvTVC&86!Ismrv&a#|}@cD%~Nu$h!e{2Y7}8>!5}}W!yD9tK4q{90yhD+RTabA`N5QNR~(^;+b)$^8`^t zuIG3!J#I8hpm}&^+(LOFLptT-BS)g!2JL??i`^0`0Z&5KV-&-R_l-CdoLZ)lu!a}VKQTKXQQ(vk^087wpuSS-Od|L}sh0R{f+}}|d5(|>9w36taBxsY zAFx$i2 zZH!#0w;b+!_^@c@nRb1!eUkR-djB2dX!0%}uyF?mz-~lR9Rg%-ynhRs`j-LdpotvL zbE50Pv&x->Z(k@oWeQr&-NfuHg*lMj3{?m?av?l>%YR10^daJPm#9G{FEqtEd? ztK5qp(dj`|xN`}!2(;apF&6)!8rK#2yk28GXPdmBPB5xQbqJW7@!@QRK4^?(PxDDKzT)c$PdiDDcA9C9V{u$RnpGPSAcS0Yh)UohSh2lIpUrLQv zdUn;%bMWIWTA#0IQO^C|qLVd`z^P)sT58GIQ5$mT0h6WzP&ewgC^3~G{F z7KUg;d#Z9n@L!96h3j~5LC{C4LHBjfz?E{J!aW}Zl7EG~vk5zmvWr-*!zVIUhIC{Q*XPX}1b1JZrr;ay65DURE>7_cYBU-zTY= zG?J`t3=;^X*z`u7oAgz>^D5O)8FvTINzTVrxlwQ*!oR{j$+JufOSO`o$HfQ__ci4X zeUN)zg&S|`>dWc-eanS`Q@YvMrQh@}c?B64i)5yUJeh;mZz9u2*g|x`XZ}Jo!55Lt zp0MMEXr*qJ7aEQ)FPvFE+gG`LBufyoADb1|H?prAp}Tx>Nx z4RO>a*1k@2Ax6D4=i3f&YGCUijCMf_l*1)u_a1x%P}zPnBM4$e%6sYXwS5sSLC!)NpQ8{JCM(C!Axh4)-ZPQpww#OV@3r z)=;*Mly-++LN_1A)mGyAPL6*)1L7DsDYqW#L@1Jd?g(awXIiFZmR`2jb)c(xhXem` z((Z81wD^3pyD|X29hfhNl7n-oz2_k90Nu0j?cjVJlpUqp``zqOI@3sKB=~sSq)Wq>ZXn}C8zJS+z-<}{wi(qqOhHAH|8~1&oNYwyy}Zaa zq9*gH$0cDWTw8>Jtc~j@FI9Y&mDWbB;yFnCsN%Evd~bH=eQH%Kt!}D&8dq4w()81A z$IDrxg`q`&VpY8TXGK9V9Qx_YFi+<3t%~o3zX}d71+@-J>a86if;O(71~G1Lz5d>1ht%s(1qYz2PvkhU%cmjYlP8vMOE=KTnZ+tm5RT zQUjoNgyL7BS_H+vIWaax)vo`%C@@um;?>xy;!CG#;uotD^Z{$tT8_V|6Ri7!6N`!+ zfM2XmPzF}j37!UE>I8cNh}8+^0I8KlY)I@6!iL0!AYyfb_M0Mg zf;~XkP?!RdP$w7x$Pya#C1!I}o#0vC&{HP>VF|ScVd@0sAYyfbW!Z#&#NX5j`a#9& z1ZgK*A(w{L88>I!2AM>>x(zbfokHbDwQkM1a~R0$vT4q>XImp`Lc4OquSF0|b8eF_ z&H0V*tvO34J=Gmnmu=3mrKq)GXptaVbG{!~Y$?j;TXR0>hsaXYcOWB6QB6l806!#@E95L=4!`PQ6w{xPx?)f+0d6y+nWIhVmVOHuQn z%u>`EsL)cBsTP!n8PM-ZoAvykB2!SiY@mD7&F69W#i|8<7;D}q!#CA}HBhEnuq%|Q z7MM+{5r6XGXpdzZDJKzoXp>4df0p?rvB}kA;>kyBZsKV^(Z!oSKGt^R{0*Nnun7}S zBg4e4eO;Gz$>v6N)+O5u%R`s7J+;S*VfDIjW8o>P(GB0wx*#|ZVIWsivLn+)sb`?N zLshw*?k)^YfijtBo37SYIMX1^~5y6ou_h%vkpKTGm z>O~+T%g$j0Dzbcw1^?ssL?TO{RptJUe=M@B6{QssSssLUD6*8PbQH#>(*488gVHr} z23n3o+RTK6nU1VHiFr$Nv8k%ou7vQdU5PugNu{)&B0bd!owas#o+^S~)G}{TZ0)M_ zi%*GI&QNG-vGLT|YWlRy6`m{!zxY=P3nNNc>G~4>C`|ZZFX6F=Ud(<7Ck~xxs%qlf z?1%ZT&=}SgoGlIVAAw(bLsJbdhPN7mBdmkm)5`Ojw?3EXbGc<-JB!;hOEBY(v z>4slGB+oq~XIgLj+4?z&ZL0eTmmCz%8ov6PW*-{9I*l`{Q{B-ZLc>?$G0h$NYu50U z98Ilot@hsgB!R>Pig@+?g#gb{uI53r>|S%ANibnJAI(WP-a9 zx0xt0_X6B{jQS*T&u~S*MJ7tbUGBae;ez(mnVKlsp+roS^hdjNFkWh+Bvx0g#!J*y zGcHz8U4)+~sAgQOl3ItKsiY1gEm29WP?gkTmlv2S>ZAByh=1CBjrcA4$$aqOJzN3j zo#jk-_>;N9!9BJ~x%R&o1#;?}pJ}l6k@&85tx((EROD%}R*S!Aux=ok8%UAlV)`dIHZdB(dr5vW~`hj?c>O+5Hzv>MLPyK}o&n58vi#lxLY5sIJa2uw%hc#Fp}}Uohk&OfWQy7`C9K zeiiIkFcj$pMA7Itp*8}fotkBhZ7-zV%l5bSqBlVF{cu{-p!vOdmpy@yAc96#ka?#r2qmt`&My-XDZe$3g zB=lUj3OdODNMij&VigU5Y^gHW;5b{9A)qP`-Q3h5yKLtd-QH9mz9eMc;# zSmqUcA#Zw>(Gw{geT~BTS{kSE|DO_xmc;ymb(D5cx z;w$~fXYgguS@~khBp6%Do9uZdlLy)UwQvy8v}69Gl9Au8AR~Joq2{>f={m%%bNzr)ro(Q&-DR8>2;EnY>#G>3dWwhqG@pc4p@wl zjVkrur4wQE@>sq-d`feqZwn@H*YCqJ1M4-sCEHp`@?F9k`wXEU-=5I2DW;*%g6ONE zcXw5A`fBjq)#`j-4R3Ui|J`;(u+w`@gHCUeE!mgT2tuQLCpF&*TOdJ_X9V~Kb&Dd>)&M%;+qvR)eT{UQSGrSaac@1@Zisj(WV zkt!MF7fWV8B+ksX#3|dD8t0&FoRx8$={Qa!HO`FsYMe?2`MVI+*w*hi4ZiF^oU)Iq zao#3z9)?ikpc6GtvFCr#i5gn2B``9`UqPVKFRsK?knGQD$o*Pl0Oq@{+Xj2x+CcEZ z*jI@C0l6|kHVm6fg7sXP&^&Mb5NS|P@*JD`plPt%>4cCC$YcoVztx=oZlm2=;tNV& zl&EDBF$vV$7=F00AlUyB1@_aM87_6RNT6TET}^}iFVpK3_`3gO6E1tnfJ&yrs~-g0 zH*v|pYDrACAnQp?6IfyIQRb?@r$I%R1>Exg@v?yTej*atn#x`l5G3z*H~^m7`akMC zEA9NJNvibS9|$KKU-jG;kQ2k@Q4H;(%N-Vx^D_6`Mxtmgw0~QGyvYB0TflCT3E5E6 zb`hr&-WE`LCEv7L74d(Od`Pdzkas+* zdaWin0p`ZMpHGlA(#Om(B*Am8E?@=J`Ol(2d-2(Mv;HY7ps}u55Y7O8VFobGZI$0F z2&VyMy^_;_X>R7$&4O?)Z~^gExC2JA8e+C-YH%51KLnqY`wFTX6eojvk>5NJ!$cA8 zD3&^3;Ddn|sI^eo@#Wd7FZMpN$)GJXIYnVIf& zBAO;)3=$79fOrqYesI`i&uhllUl82tCcN|PQ%$--@~d!t$zglRn`#!G#G4P&+%Ip? zEVxjqyP-<-J#OSV7_8|QUQUb|MKl62O{o?5%~a|#{ANRu0@H|UN#QclF6;`zbkFXA zGTpN-k^(4xXartGhQb#aflsIrh%akDo+-C;L9<|grM@D&hd?2ypjM8BLN|~^qwvEB zAL<6;i*BH1Z62XMRH_W>OQn>c@fs&=&vL|5Pz+<)LsyD7xlHOx~A%eY~< zP|D$n@dz+up(@-h=cAegX1gJ>yq<%L(~@wXf=atyV4`%j88mLOL&o*TH)Qtq+eqUU zd!skDRkJ_=6oy)rld$$x0Ojd6mhOBb9o#)#qJfWdYxUY-dswzLZNKbk*AA4<*|Ij+ zKAcI%_H`7?7}?&HIa`-ewqBU{1@xG_TR=(Y)ZISr>u|Z@t-2NjU*zqFjklZKxG$_X zlnA)e0M`+p6Y}P~Q|=7#Xu6t1s?yK-T_PS zxOpJsZ1=0nmxbQ$mya^ZjqQ9j1Z6v4?~rh4M3VN+&UDu>(H4^Ex;*sK&c+v|V}cA- zY5~+0P?MaGt#TvqFU3FYTSrWz*x18J~ zJqd)i9REm9>vjH-9v{2;k)EGOIXu!6wVXS`i*8a+Hx#6D@>WjQjVWAZ8gS9`2V5&PGSJ?gUPFRAc?a%H@`I?C0T`(VI?ay|==7X{wurjFZ4%j0BTIpe; zar=83-;|sB6KX|Doe%XE)FkI)t6WR`SK@DXl=KeciQ8Z9$)yBhvpY&Q5nH^0M^#pm;EGhMO9yno|17MpD@C*f51QbHaAmII?1T z!d<*auZUj?zuwkZCvNx}6_}Uq9tq4(zFP$7``|W#xw&uK zEfSdbB*Gc)C){S!TioUDxAR<3y*#w(y(?3%a#wf)>j1n|VBQi36MxLCHe2C>9bXaM z-?g|n@w^9H;!qjq6mu7JAHfvL1)Ps7W+Iqp6!Wq^-{y%#o@ccnf7>SGF2Rv0K|&9Ks&pMakbGY|t_0LoLC5b^6dWh)N+%1W=%=Vpcn6(d zRwi<4JYtYcO2Ef+qQBu|wx1Vj^w$vmOBVgxxu}((K33EtpjL^lW0Ra#<_Bn*|d$#O<>Og1D(DocFJa&EdChy zLs|PZE=<2?#a6)R>H1N8voD^$maLdNfPA)~&&QJuhFA?V@fuMkDD z{&!UCydLWlZEMLnRO`I0{PW>Q6?mR%n|_J$K9Mp)_9T9a@|Sy3kN$#ART8lDRY~$0 zswt}#b~@&=82>ECkLi}Typc{D>(KL`L~83+)%7Q(t>2pnrPxZx`;I?9B`CAHU=Q)L zpxyF5M_br|^iYMvdOmaO>Bf34k^XM1hP~ZWE?-2wCkm&NBvognB~=Q_xl*9~V$q`y z_{4e=q`HyY6i%@yixeM~Eim{a3LhdqJ>+42w>ss(-=|W1fY?+~IBaUNQa)t%ur&)T z;e893;aMo0MKj}YfG)~{A2^nH9HQM0f}C>y07S>Td8gbzA5LS&HO~Slb|zUc)&2 z2PsGjjda(_p&$>GEAPM_pJKeTHcnYrbC_K3c zG#bNV+VAiv*&vW=-Fs&s(u^4A!PzWCN@noEj%i3EX&>}etZKv$E829Nv zLVKTgTf$z-q;6};dzAC5ubI6EsJXCJ@!nN%NeCE+#zBo?(<%{ApU%nP1=J1!V zjtC&LmXXFl51kLJQGfYjjrz-%a~F?$Sfl>(MH)rn94Z7Fq;VC(e+xmQF(Rg|gvWdh zqx>~r!&F{>$$5QaZ%C-GVLN?45s1Hr?esZc!ya+v&?BxdVvqP<0bUfIY7P}=O{C>8 z5@f!Jaisc-*hQdJ&Q>c^X%AUM60SHmnd?k`K3YhACiwZ#ette$@bfXLKh2(L+d(}n zqHrG-<^aUz*bZdpukqh2NeApU!e)UHdSNi{-<; z&MI{79G%z3{EDsq1b}+E&B$Ezp z)k!idfmJ8TYzJ1IB=Z@3&Pg&CNQzIAx!B#DBr^z7>Li)k-ONccPa}^?og{qw2_Z+ElVmbJHYdr916>UQJ_=u{lVnUXg79$P^hX$i zbCQgk&ArkCU^^$t7&hG?_eZmOyHApdU{il|AlS}HGH$jyNoG0t&Pg(cPd#foFc1M{_P|g zBNx@vqp#q`P2Dv`sBRC2#ou^6#G(JRwdZf(cGft>7)bs!NXbv24NhfOX z+(zy1PjkUAzmE!vX|$PspB{bXYNBfzB6f~Q*KmU z`aujG-NK!MvLD1ykGFs2x`^_lnDqYWZ25>g?B?t7#Zw-F2AW{VH$Vr)MApXGSwiq6 zLgu$<@-MaVbW&q#<45URGi8IRjf>>xvUw$?zMJ?a3XNy(sf0WIk-^m4;94(KGKetKF! zJ?vRyrUfJpj+z!wxPla{xVi%UsedqpMB&B1kZ_vr&!%;m=5rTzvyi6;4UJcLHT|u; zXmLmExP>Is{A>w9reMPOeX-QD-z+Z3r(Y@9Xd;!}mSAx)v2={A32?+g&@SxQlD;-wLAEsc6 zx=sPrp+%2b80<+oiG%v4((piKT(OY@!nyF_puQ-)YHk;T{|Y!bs1Mf_@=1h0fe&8^ zqVe41o(F#_njqu)xoXqpslenYo$H{DOcYp6>>!6#2#u^Sh{d*NFtYvDQ*xOuB+OV*b`AI!LM zjQbVgnT&f4cfW&hlRQ|En)A9}T;cqQVcal;6X9Dc*TNTKiAzXJ2}ulR&7hZ=Lg}uE zE4BeaxC(r0WzHKo{T4p@70aT_RFF5lih`$Ndfp<-*(_f?n^j zL8yw;!vBM*%b=`~4I#M;zLjzwu5Ey5F`vHL6*BjG;8roWAFf5F zh=e*OfPLY)_*X%aihm^+e;-0~Z|g;%onl`jRgqr=+7$U}c|u}rUa$S5N2=&Br8gHv z_$D}O;mHV{YGi#XBWClp5Lf!Cjlc?Y{9NxJ zx3JyPNEEMHzp@cNy?%xE44dtSp0KLmB=<1%PXpDHyfsuc_Z@Ud+$GNqRFM}W0djil zp*~SFIYE4d=H@o}4m{atqHgN&vB5)eB`kwH$V#TzCAde8-+bjdRT0-y+(&#K97)1!~ckV^P^fChY zoMi;XK#+N3qnRiCLMYro(ttb6rF*vJb_h>%% z(T9M#LZ$&V20qe5ixQef>VXk<-)$BpJOy7FEJA=3e6%QGH7`eS%c$3>&!JTvFg!Kr&@IbHe#`Y`C6`ZtJMlE!y#HIHA#nH)-$#DF*fUz;n+k4 zW_=gB3b)BcP)*aZ=%l|*@;!w3eD3O=B6JK^%Vd~YkrvOOa%A%kK8@N|nfGH8FiVDP zrv?o_p9EtcD459d3^EixjGN=STCTu#hgQVd#%8_=_$`duf$J(c38{!ck-3in=teNe z+|K}Zfudt`zXOqc0m=$l{aJkIfN!O2jXqcgX8b909{>dP+E&PO@b!alrCf?@A40IX z-}anetY$`IyYfy2b8L$`OTOufUj-_K%m zLoJ?xc$K-A0A_uJlwctxdLg^XcG%n(zJMwe6!di9YXcvagX4-?0@prTkz?*%fl6Xj zWn6Kp^Q0&gnR^OAe}X~L4FT*NMaSmeYoA|?1!aZ&5WZ>ft(2QFHWv8Bn0qYfG@6EG zjPN}IA08Q8+Yo}yz4-xr8)U>U`|-#y;(1(W0-?(w-B{-N|c*rk$ zu&)TT!SG?G8^);JGRoY0g8wBrnCS`MMfRn`_ZNI?>e<|@Ft!lbT8zDhvEO4$6E{|w`z27Z z-V<2C*mAhiPnr8{t$Ty~6Is7C93pc+szYK?XS@+rKY;!Ubr<;Mi4K0%XQO)2HxY~O z17ztzK&a;t^=cn^ENX4S7dEB$cj`t&VaBl>@EOGC?%qwMz`w!p$?0AD(b($)FPgDfl3OOPM_7%;s_^H?B6@kfNiUge1-=@K zRZHedP?zn11@n@*KM+t$=1M?{S~4eo#nSnxC3AV8MK75f1)5qi7dY%*GFJ?`S~8ap z`v38gxzjI&m$0cNbB9SEFPVD-`kX@_1YUJ`$=qEat0i+D$o`)$nS0QQkBtBS?1I z0q<4jr}iZ>AzmsPxnyq9&`agTu2*3D)bZg5<8E|r^aERqhhz2tQkF)Fs4vA3XTT}) zf$dND!h?jRj!+cVJg{Xhmltmr(&2p!{6g;$D55S4gZMn`yJd;4 zYnJ1#Vc*3Dp>|Er9zKJP@TsQ zZVeEz1vs&AWY9pYP|}F->dRjc&1YcXwFp;C*Fc5o2JwjY69Dbz`gA|8*eo+2A8NEF zG7KKqu5k=a3mB_-zy1g|jcX4D+u0}D&1SP&1GckQbR*Y|Tz#)-H$tt%{23aYm6#EH z+M??)*pX&M`$KzmM9RpTn%to*XCtG$fp=$9*=PW}`^5d)5u-;Ek@yb*+m0mlO%L<~53-U|;nmTyGe zp*hnr;HXnT-5E9D*afhy;H;4k;EJ<;5#9|SmZn7E)d2RSNK@c<;CR4sDCpmSvPS-f>k7FBVGnR?br9DG>G4qx01mF{AB;R+2n?)m@)?;ddc>BI1VBbD1q`4QGC%!GC|;J5+z zPOBGi#uFref^VffgzIh~)PUnL=2ijsP3CUJ^#ZtRz>(HZVC4z4>|$Sc_@0N4vyx0C z56Mykjw_K8$23q3;I3q|7zK?1+EwekHV?} z$BvBX%h%zI^G4xRzdL~useH}Cm40e_uL2#vGvK%m#jCdXIu0M7HKU-j-B2EI{5=e< z`%!o|Fk00hG*k~b>JVzTC%JZ`FM00TEpw_*u?G~w^t;bQI{knE@ z6qwqr>NTj{XwxvR-D;8U)%`}mZ{;2qdyRS2EMhj2)-BLqu)w--%MD`U#8l-@*O6> zg0e=wiR%hk=X<|63*SoF2iH8{RJAt>^hJzY!MF_wZ(`g9`WaBx$ggl+AvYlW3w&$karne+Q|-0+hpN5QZ=pwrGoo8`}RQJ1^75C$wZ0(Rn^{aNSb3BYb2S)N;Zq#z$kM#0*qr0Yb2S% zN=c@0jxb#96$9g#z#6HFKNt5&#gDy~kvRcmhAQ^qKs&{bebhPYih(vozFIyQiy>BR zFiy310+=VkStIxI^(d|wSc$@_YOjb9tNFT>ajm0ps@m(yh<jw}7tHgI?8_?>F+ zFBGrZ3a-JAdMh{uebx=-YHvIM3VMfussW5P8mg+jB|3y^?=)9?v^>FG?KMIt&vfe8 zudBU1z(sZH?&oSRQbAjfqd@z0wdW`>)m{S&wHs{+$F-aDWm$LX3Tt+z{;%QpgeP*k zr1b*&s{`?wNYVmbRASDV1N8z`P8f$cpulAQN;%Kmwjo3sj* zg}IFMG{o{?D*-bNu^HVkt!H(LinH(@59i2Ja>(C4(X5+%TJFZ{E&VXZ5xx1n_)hYS ztPH^enw|&x^+-bZJ*b3Ew!!on`l9STjwrpWu|8e&-v*y(Q(0hv5P~98%tJ?TP)micbf@dWZpm%y5{MH=05ZJ(&ExE@*rKXW z+>d{@Et7~s)AyBL&SAbhLDvcwz!{JYKQY1F(6(_PQ zcx3Vi&2f{I5voYz?u80}U)(?E!ONVnoKGp4os;RX(JFKZuY~X5^=J3 z1in26HAJ&mjUwOgB3}RiMYIbF&g2C|_OSSOkg+{UdO-Sd?5JOTC-S(fPnCs5rYG!J zY>=OIGa`D(Tjf4H5-PRKOI$)__l(qKSK)N5PgEgoA1V-+O@&WTqE%5o+56noQJ}K% zJg=yfZc(8La0>|go(pR)1BGVBXFtS6DwS2(ldyXDFZ{D}%aJK7vbA$OrTUMaapEl5 zW_%o#iWUhz2ly2d*`yvON})0n`-a|e;%WS|gng$Hls5`^8Xs++(nIT0`XW3+tMPEcMXjnk-B)6}XbK}kgU`)@F~v!Gld-25QY zq^a>M5J7AuQ1g-K{$S_%n`J+PPhd3P28Vj7kTro5 zJ_-O%c<-4AyIIhFOH~{+oHVgo(=xb6nOP2FP1Nu)$Z zHAF#?kQJi$EISTrDbA$E@^(<&D(t3)*VD~oUDa9F3=Q8%`aGmB>DyI;JAtBx_w6jC z7@HYaD~Sb1=9CPK5r5x_3UVQ~;2DlaaXWG@(9)apcRIFUML4j?7n|tAjRi({WuOh(bImItZ`|e)fefFrCMMgRG84p#5Ym+$LEa2< zB@8hHa(tE9_86W1HORjg#E3v`9i2rtDOARE^LaQ4*7bDDoaMpk$mh>V{Y)SA5I8MX z2a*YwMy;x=aT*A+*&}NB*29&7FD<(R^1m`RCJTITl?7i0{J4r-Dnc%rZ!CKkAh#0a z7psy33HqSocDnyRnXCk_5?gJ`2BEH^j_)kRoLH?)7|C({hRQv$dKp;EIuvYdV5BFf zteqe%+(97K!oT>Wc9kj|jw0GS!l{bk~N%nmst5lsexFE^e3jpDw z|J>6Y1Qm_Ny!5@`{YGW+i;*FSu&;o=F$mRvdQ{Q1W^xCV!fjL%!cyh0$i*OW0eLMd zAQ>RCDk1w9@V+EXu`Ur6yWJGo!Mu1kkMG!3pydL{tg4IOOAt$5K#6RWf!AL~8mn%) z)h|BAKY*=gn1T%Mf^^3Qf|irP^N_(!p&(Gjl7UpZ3l+@LL6sCm%QZAkf}-UaT6LDa zhEz2&s_c#ka^AMEYJsm}(08}R@H)GBtlECd@cO%X97TFOa*NAkxQUun3%dvCTqff! zRVH~%eh_5N#K}4niLA`V{?YKJyLnvnt_)7`6|6zpV~5ovH+DpzF)0>#+s>g;p9ue( z$oGmdGOrmP#JmZpG~@BXT@>7l#f!abc*kCwAku=j$ZDy{pn8J0)JhOTQAq?JlVl{; zhqO^b@U)>mr>N~Kfm*+AZS1~s2e2vO#&;t8vV1-svQd`@?l$^zGqLWGI_|-{ zWbWOFc+qA^ZIQvFM#C%ru7TqYR;`1RI4Q2z{}qXzFY+Mx8Jd(w5Vfew!5?(cdV*-V zBXNJ!KMg)C75@*z-%H75kkV5I4;ksPm~k}B&E0_J@IK12JEcNaH^|p13Po#XXr~=o zOG6`^imE!Nv6Dx|L|CS)Vo=O(rI?%}Dw+bLGAyd&zs@ioL(%Em`jqnTe$5c}Eyz-O z9D>h!&LU!cw|o!w6NdM)o5%NJe_(j;yLl9kNUu~E2X9@2?ES{XznAWba!;gpH_TK# zE1b0~WEX>;wlPKob1ZBhqZ1->Q`QQxY$gs6-68Et^)#fum4J~!88}ZGb8SFo5ad2- zKLSXzvG6x{Yq8%p4#TA2KCD#U#?dHS~RMx-P!T4HLvA zyn+Nj)J$Rb18Ff{pn{*e)!Vm#Jgy=V^PR5AxU|xr1o=s<`^IU`u18DQXF>m{G7K@` zy$~?v&k9BE-)QI0;O#uPUE01z8kglwt6+>kP& z(0v_o*KJG1W3M&5{-t!=d%;Wj1Nug|&y}^*zdB0$?%E1>wruXRJ4wHlG$@U9giZOCNa7ubrO+Y zu^D!oBxV~oQ>6C+J(F^2ikq$Pv$ugaig@2^-XEN=B_MAi@?YkLsIeDz*_Mcx=y7FS zDJQS6M;TsxG>euwmNkbh_2R)2nU+i(?9kay)>Y`NYbBNTPbge|RU{Qef+|z-j9IysBl+}td z!l4u^%2r)CHgpBL;8St5#5RMR3SqeQF>lB;+Z_;-`accfCsidkpyBk-tIPrWQ{ zUJ5dgp@sqCnHsQ4pM>`5q@4cAqlXK)W>DGJDa*%Vqhl@s%83&YDcL2 zWafz>2_k(3ww9$BR0tpHC}jDFl+^}!>O`im^CRqLWj=x}VA8j0*>L`e_zX1FnGma# zmrLVsdy)4QJu?1t#P|!k)rs9xeDA?U=ej|cOw6H!-ozHte;sHvoRQedj~-Z{n4*uT zT9o?Yi7ow)!)Z|&*!B)TiTG4iG$hYkKu8ha3*rYb%$V3K#aE2inaGHQzawZWqIne2 z9nld@1z$zv@JmM|MBZ3*l=Et#7n%1CE*ahtFTtBRE^Q0ywi2k$+#=$qWeCyrAv87{ zGr#{1HN_qon79LX)`&xgRmiG*4>Eij(c^s$)C)}JR3-45hTKS8MS540iX75;P3qYU ziX3e!mTxqZBTy=SaA{Q$EBZy3YB&9|TR-bbtg;h#RU2*{qO@LcFZpIHjz2ot;3#g$cx;9_KzUb+eGGV@^M#;%W9~% ziOh%W36E*S?eYy*jE@3AFB6#$+aCcz?-H3?-8$_4k8AS1ZbADMkm+3_b5}${+CHJ) zB{H9lAnyU0-X$^*MkvX9QoT!L9*-bD3^H}!GvDC%e3PxA-Rc!1^BuW97|!kZlR2tq zk@7oVBxiPmOc_q66^cn$)rQf_ff_UGW;F&uIeJo%_5v;k7_i}>$qq9ZXByhrVY z&uG|nZkSSW2|VgMXWro1=BPM9$%;P*70;AF#V&itvl=$fAE63q;tHLs+cks@qHT!aXKI5DfZ9<7^lKNbCI`& zgUCA%l6?Ue`u3Gs>`sYF<)nj}_lTEL6=6M}fH(A6$Q{ymM>U4FtYL>RB)<^xeO+4T ze+|#$E2XpG#RM^JG2~KwuAEkBIb(P=OUn&Ej4{W($gIx3*P4dSN6DQvym7v_nCGN3 ziN*noN5zP6Tbx9hHV?hxBx+TtCmsLkT2x4HB2DWsKpT1h4OZw`*_e9OOEU1O>`hE8 zsN>x=nCSOAD-bVyoW`R%oXu&;~7*P@yMP$m-~jUeKi8L~6n^FKN;M z2X)MavRw36HJ#frrt^*5JqU-TQ#&t3?lIiPOX$0V_DDMjcR%@?c!of^42+;C>^BX$ zxo0esr!)Ebp{h*@werlv-Jyd>_QP(%Jbyjs;kIQZI8Ve(CqPmd-+?hhTFA3dXvcMobeuuVixuXh8$wG9*c5M*hLet z^Z7)evm(%WATham1o||{oWhzqg<8oZoszmbC5l{qGQPj|gzg5`$*OceoRZvi$e{T| zJ|OK918HJ?%Mg~#-3-WVf*h3gf+-2&3Gz30Yq6_M)#O%gNxKB(In#jdW2H4V7H_>u z_nLbM7iwigwLJFA*J1ni8Nl@~g|iof-UWT3P`;Z-JtVDYZ4=d53bnWF&U0bb^8g-t zb#Sl_n7nJ_trYUfBPSu+_^9alJvi@Ab%=bz$)#nOkeiWgStM0@O zbfaHthOm1fNbd=uZ>@&VukPRC`?Ak~M@@g|M~hl6T{qivL89*mp`SU^O$G0}S(7hu zHXHOtkm)-?=#L0=#x0usPXzjLkf~=Mvb@xr*Sd3$plzk^1fh`jL3cT3t;Z&Us6P(?2{XR1!Mp9YzR_(Q4QrkpdX(r>d& zb-F{go1Fd@$kd|>RYA{*Y>2Z{R2;J$ul*}<`;U7SnT%Of%m#_cyIo|?31OcBk9vfm zyFH}!7cum!W(s>JNYu#-{pD835!+4IYM$_sa#dQYO0!=9k2-lF%cl}d zIjniZZdaYWP>j!&2}TCq@lD^L zd6jf0&y~)an-auf{6j1B^bTbur$FMzYK_nJSn<kz3YvXDq>C6y=Q0dW`rk6r~;`ezy)(4x~I*W5h}DnlWPYqCsQCV>^b& zh$BVx81cv8n=xWm$0#*MJhD@GjJP$7(^^KR5dI8AW5lO{&|}1(P=Xi{eiO_s!du<- zc%h~-VoKBkycNQauPRg9;`Og`Nwuap4O3WYm%sOj$1#vw`8|=g8u>y)I+fqgsQ$`j zuc%y42I|m_a&{J4{1Jn=*c-jA7OZ#O-O^sstSz1;_(43tTiP6+Y55BPg_2(b?y_5P?5 zK}?GnqI%^I75>Vr8eid5X*@A4VnBa1zFx_{;E5rs&(Qdu@B9z_#MJsXYW$+p8h<~& zGDN4JnAS#I@EzvAD*ao#Np-(Z!V`@rrbP@o( z>aQ<`j=9pMg2j}?pUr`z3dG_HL}d8pz|LglLzOzBlqhTE)E+S-zXV7WelG5{;d&1V%b>!)=(P{h2Xlf6?{pZAm0g|T=MV~!*a2r z`P)CoKyEtBJW7rp4VLR;GQ7@4QT&7Dy{+{L|C?N$~Sq^-SVgbP@iphB&uAv|4n*Y7@lHZ_$(d zOTg!s=*2Ff7YuQ!BP3cJ#4yq~NRl@+HsM3KBHu8Wfhy}iBkfMsU!j`}e;}if z^$(Gvtp&U%(jnvHuJ68>Je#Y0fAmOS*@(gD2?G!~7~vCIkWOsfo+>?ic7 zNUH%qy#R!EWmF=5=1(_&3)6C6tx9Y7l3*Ulb}PdD?u35GK^&e z&?p_pfQN3B$c{{-#QyhV!;R9@bX$8!S-4SR(n~}NmYE)Il#YWCU{)^-cwn-eVJ(#o z>tZo>- zIWa$Y#JgaH)=5!)0*xCDlz~q`5KTBVM1?HEXaH7C5WxC^NY3C-4;kEY1HL-{h!=}d z@&n{-Ag}|7V9IPXVwn9M8Ye4Yq)1V7sbfJC#6n$Va5)e(KRh%^HgphF2~qDV)J+Dj z0I_o-HffqB)1g$QFqek1?xFbl%HY&F8gYXhNIE!)*CBopJOkEuB)q^S9PEiKVCpT= z0#0pO$Crd#iVb1i0cF$$+;ONKGHNkpRCyWrld_-*hbpL$MHmq*27vE5S^AnHHF5{2 zxzyR=d$wfoPayc7E6ExT!t^LZUKyNpy}qN$vK+)!WSrl8&v7#Nwn1deuB3yKW2t*? zHA~-JZI^KH5kqYlEfBtEXE?l^%%%F4M?1?(k=GLAC3zEEbeG>DvH5I#c=js z(l?n&^k&3uH&;#>zPlerrIA%Ht?C<=7=!4tnu~Zc7n*jO)g-Mp$V;I)t3_<3hVW;# z3KSz~6$5G!L!s%Dan?1NjA$nrBC`5Fq(*D9IulR^HW57QB~WRoDyuu`Fw{IGgNCHC zdb_Bc;4JJ5E1G}y9A(VFU0BdbvrW1_>NRf?Rj8kH1*-L%1bRH-Hwjw)M^l~YO=7MQ zIVmGW^qa&^@Xeb9t7DXUllU)qdbY_5itZn}lZZEoIHXL!Nz@7>k|=)qrj+|6Qbo%; zQ}2|yT_8)VEmPOaTmm%5l0JH?$jigXR^GiQ6GY2>uOK(>MLpL$&U$LI4+7|kfR^Ih zj;pNPqaL}HdjwhmL>;ffCy_BVvSh_!kK+J)%s#GBOInw}wEiSSZd+Vl#BflJY#Ce( zNZ$AuQKO!k*-i)r3vLIi!dxM0G%UqB1Qx9ZtkFW!V`0TmhmRb!I8NXg)fOKTtS*L~*`HD+F&KMQ=m-FYrP$KR+0 zQW@L`{sH`J6iFgj<&bKTOE<84f)q8X$>1yCULeG6vK@7nIlqE`f>IrMS_2ynpdn{D zC0xG&$g_#HmIZ>n;Gaq1^-2Lpkwh6j4^)v$Yag1VqiwWg4eui*r~`A#d8*C1766$z zs%MPIDZ)hYVU(StD0PZQ2eL}qSp@@&# zN=EVic%Y8 zW3{IO^3Q-~&c+>_i`Np?|E?k4&qP+~+)5Iqsu@zLmT^_epxasE+zq8ty_BN9s0dXu zw?RE}a~lL2l75g!Gr4POAtfTMF+wBY%k2)SumKyLRyQ_|QQS&84ZzN!r9 zT*vnjOd_g(MHU>{zaom$Svmn*jS?XPkL+I&#fY@3UGF9W)Xv+?PW@-tY48d=jXq|l z@i*)=`IVh(#Qh}DtQ2jQ%u5Yr_{R}%jF0#`z_5qUX6=J7PBX;_BBd1==f$Us6m7P{MveRY( zJ8f@cr`=ubw11kN4ky{^_$fP`{${7M|3OmLC4-&b7f>Lr>hMzmqgcq&nfK0O%>ldqUMx5@fdqF)%;@g&RgiIB!>USO34nnQ! zH>-rYy3MbI*pGili^8I9dwc|G)ws=O$h2y_=2v!Z7Y|XWIFX%ozduZ&^|f}Av!NY3 z8z-@|sgRw`TiDt13_Dwov9s+>cJ8>u&YfwGkoaAV*tvToJKJw$XUB4O?t74(`(I+` zfz#|f6#FR2J(9!DV_n&KVlq3si`aSkPIjKz!_Kp>vGd%g>^%QFJA3@QNXy=8?7Yy4 zoqdDY**}Y&18dkhxRaejZ?p5_*X+Dh_AwGalEco?_Us%R$}nUP$oI88#N%OO<@Oi ziu$l~%T4SoxtX2Ywz9KgH#@6eW@pXY?5zEqo!c+5Q+(}iQnqdYJL{*iv*9LoHZEgl z(>8WC?_y`m%j|4>hn+jVW#`T^Pmz|ptFp7B4LkSuV&{RO>^yiqI}a7I^Y9()?0k-$ zM@rb)b)KEa{$}Sw^3$aAVk>rj>A}vg#T$tD+XxO_p2N=X2idu@jGaI3W9QGe$>}iW zYj(!|!p?X))u>g630dq+Y{<@}j_gbx#LkpS>`a}{&a@ruOh3TRb#JjV;~REn%4bR0 z^=a(PYQ@eCL)e);hn+d=*tzj(cIF;sXWlpL-1H|qi_1JmS_+fdDav8z=GN@oLK`)= z>Tv5Ac9z`0&e9d^+_r_CWlylP{3Ui)oM&g{6?RsoJWt|lGTFJk0XxNA*;zN9o%IXY zd0`7X`<`WI|2ym)_>rB1fjwv`(%(uD?K{6__3eyWu51oM9WrqdtpfS9CcRZ)&}$pu zbnVv|=vH0(cVlM&SAbpf2Xbi81a^kZWoOuOb_%w!GyF+*MjU2mX9VP`^5b|#KsXVMIICKr*@qxm{=diA`UonCv{>HRi4eSTo4Z`=z6 z>6gt;|K{ur=)=yy3GC!AWM|L@b_PGl&X7Iq41J58Vc)Y;5WA0*4X?t^h$ife?90xm ziR_GC%+8pN9=##0@VGU{W)ObY2FS^xbH5lz3VtYYQ(AU?!8o%LBq%Ef*cj1H!7^bSw{W z^fTUB9zYCXf8Ec|JtHg+=m~H;?W^*w+rgsSs*;Kt?y} zZuR4+o+dKJV6Z%3Xm=uW3gRye2rmz)JWwO1%7u(z!T9Y!=;Z+`fS?f@EDvz$urC_& zBDbJjkdG6yFo_7u15UYOymL@^dB917xLy9>it!K-dU-(OK{#@ObZm9&uT#Iaq#r=fH^&lRalfuB3=v&FAr!oT*I#OxL``fBjD-f z0ec-4bNEJn85&+5(0PQ0&GR_6!!cQmwS8ET&U!Mfjbp+|na_H*6oi)t^cCbvey&J)c>oJiB_Yz!fKJPOd3gXo#&+lN*c7w~ zPv#tN)83SM>e;1lXL@xS{{%yL2ZqNol!c#n9UheunFHPLUD z2RNp!d9%RN%L7X3{L=6|zEV1ePr@-Qi+OoKDY>@{uV!hvE|YPns#+c}4fUWde{~NB z4R4(9dgeJ#0FR;Y@&Ibns4;csFj1?*3vFw7tzKxQ%$k6$Xr7|i1hnW2@vE*0m{^E1 z3$F>FkTuOAVNC#&ZX{B8O#qV?I4G>f;9oFad$Gnu#Kr2P=c5o-b{$E}^XM6L;FQwe9t%s|@Ang9o9e*j*@ngHfew@54MIMP`Y z&?OUQJr9b^nt&*9Feb}y)&x-BOFa_K97KLNa<3cZtO+;*0lg+5N`SG!TdU$3oR1i1 zSq@*Z8f4?R>jhw~=dxFEeMUE5aX(mQO#mlRNerrn-LV%!;;txV?ll3))ir2`MY+I+ z&UWEm6Yw5DdQCuNvfP?B*3h7x|E|ed6F}+IQ~zmA04JMkzONkytqEWT-=?!BfN3rq ztqBO@EEj{;1Tf=gM=7ld2-6feye7b*Q~evYCLoH*6MwPZQ@0MTYB+J}RU2yntqI`N{Y6$s7m@xLnA9)iH37sFcD*L5XNNTbt^{+$_Opg3 ze572Jma5Y1=GUm69o7V>1XEUO-b>(7&kkz>O6ly?RP)M~)_Ddz>e*pUKq}|^qK(Gv*Y_#_mJIE^D60{ohzLqTH(;WO^DB|2~bw@HOTZeBDBWmdaU?quQ;_e z9;?9+!I}V$g%Em8Kyn++!I!;z5Lu8M>}f*7Qk=T1l-%%Z`K63vXN!%NnLOT_UHxWFfJ@i~ zXxmM_>0wO(z5nSHvGLiT8(ylL#|7bZqp3^6YXXXp=EyYx;r=wH`d`LJL7LU^+V|o4 z;lCn2>*!)+xSAin9$qs)+;lo=R>zXx!t=u;Mf9wWU%@xCI#?Z})U1vvm%{VIMx@|^sEjUMkJY}=e~z`g5l^!t2yEIFD77H@{($OhT|zOJtv%ADcp0ychSx5 zrYOVH@0hfYNWqRjs;{q@6aFFy0cM>h&B1LKG;67gRSroJ70>_VOuu6Zl6B1qr!+*( z3CB#l;vbOz&P=>5Bx7dcseqn|M*-_DV*6V_h8~>C#~wmB;BcII!4#REiT5z>CTe~! z-Ff7fV)wk@I=(Bo%P0}bnaD52kyC=>e}xF91TUn#aOS0+rv!)RrBcZHl1Nz%VHFa(%82iPAS>bu9ESp4TtmdUA;|1zfL_<@8mrK7G6)`2a+#RS%FeUg!;n!1w$!r5b zs(t-c0q1$bKb$3ECJ|XPPYKTO?(|{E6sd2H4x}sf{RtONJ%y~nM9TU-Mpa$u>&74~ z0}d;kdX`OEhU`$O-;VSxgjl7#I=%%NII{C!r!78BQG};0QYdQLB9rzI%ITkC+Ty*H zaa6^RcugE7i*X-;cL@iZe&Zl0qs+9$Pl3?W7C(m4 z0H-jQdfR5&V%I7faf6H>g}6D1*C8`S@JX=rv_(fan2apY(-xxyoD#3&`!Glu^>5P_ zU!offPg|srp0>C(UEg!EJV2>APQYAx9?i7H-+|E67C&+jrlO;1i$iUFN0ns>-7`nV z`E8~x?lXvNDMlj}PJp`SbflZ_uC_}!INwllep;k}bI*C-qj#6rw~k*lU(y_xr_ru9 z{}`=P-m@M3_~_8SCoGkwCze2i2rlp8S91^xy=Bl?1>$kBxZ(+ZZdkW^Q^G8+^Efs= zJ#l(>(l?n&(bE&FVo=;nPm~x5r0I!d7XLmyu@yyM4^V6A4kVA!QPUF%BC@XZQ5{D! zJ+VDghxb*z=B)0dLk1M}B~aD$L>HA4tfnWXwIoo9*A1sUbB9lq?x=2>du}F00Sb{#F=o(pt7LJq0&=7Y1+J(ehzpTLRsaE@w?ao|GT1;i;Vy4}oMNUSE=vMn-@J*}D z>R7RAwVTgY9eeEjm5ezq*6)ZeveiBggl@I>P=XkdMDf!AUd4+y;;F(v^#{olOpCD3 zk4`j_i=)C9;L!T{;D6%quevzS5sF?MSMigZ@v@D7X&pQ{*CokeJXAj|LUxYMme+g* zk6r`>vRtgl&4?^Sx9TlF@#5@YkDANVePast<^GCh>3DXK_hU(ZW~$lCo?S#fujXtr zk7@^=%w_RPBkurw=Ih~W{FGOeiS_Iw^cOBPf3z%f9Ay8ixX_6z-X3H%>SPA;34g^@ zY`KKLcPMjsvjEYP)}6%=!7~v&>zt!i^tzrXKXFnhQKHw)Ao$*80$;v`u<+6prxag$ z`|=`Crfk~p?aGTpOwKA3FVX~P+2jwzig=o0xfjfs9lqa?Kwm6VVgZRc>baew`r3)y zxp$RA6=o-4Wgq^rH>*tb|C}ns@A$_q;tb<#>b(_e=*wwb-#BYEH>ReqIpwprPsu1RYxph>&)@W+OK`vz z{&55PZuk)^i*}B0l9!zvmF#QVy5_R66|<`~lHDo`TGsh~P^i z#&8cKm`bt(TN3zaARuaSu_tpU|UPg-&>k)Ay zDh%|jo7o*fG2kg&+YoVZM*hMI0dWN3L7Q-y3F2VO7oT5PF(4iSVZe>J>;N^ncbWWW zL0n4ELAaEFh%*7I=V<{~H9FgPxz891tDh89D-1>L~id!%-}UM@2!=3>ta_`wk%*&Y+i(ZIeM5)Ebw= zpk{CO#O2$G0nrVFA=$X>&=JH!IQ!c&`Ln^SN6a`ElWslxd?5cdFq1$RLuTXpfEHEU z%K6oi$A!cdLp(<@johvIJ8ynwN*{v(1#tM%Sl`cCc0ppc@>ehKc@x60)i~1%R0it)=q)x_S4OMWI)Jpj+}Aiiy~m;d1Uw1w46B3-o`vmjF2Ee)#wO-p0dE(9+N1}>bMOq9 zg-c#p^)%lD;v(XH4$m@p2KB*ZCb&txrJdiw4v1mIUJ1{5cnWIb63_{ubOwI%dWJP4 z$k%|hhes5AgKJtOrpmBi3DY+i5dXkau-^rt`w7(ZB@8=GkR^bWz%$|uE~22M3p%E* z8xPd=d4_!rVtxp~U*H+>4=zYJRZ_c=a86OUhPpr$)KJ61wNqX>P^fl#0Sdyk(@dhG zb}Fc>tByo?!c|9YodS35^sJ_t+No+)U3KKc!&S#BcwDv94vGS`(;<+#cJgMsqBwVz zD0WUzC2pdq-9$$*5+06XBRo#+1Y@Q8DR!I^qtwQY_2u_MJXB2;P&MUda&>hpxZ&!` zaM{LCUF`)kTwO&lQC)oxCRbOgLQ2xnvMeg3tZLB}QUn4O(jXwXLRt+^WQF90a)tCF zAY38+0#9UxG=y5MG#&diebY6ntHx^x*@c@)jaUJgWFiIBh`E{En5_es%%y-Dvka|w z9Q3l;oCG&)HYM6@I@Zu-`UkjSv&nH4glW_|XqqY0RgmOH?GQX%ra!}@%5(^|o71!a z29()+s^{pahQJe!YNkd}jf$vn)y8mOVx%!tYUwftHqd!HO9~j(MGmT5eOK=tw69b?1d-N7~D`chHn93W5~Gns>X0i$4-StPe6ab zs3*h5;AWCBEC(}e3~nYH!$EMv#_*2Ti(w>X48MR&#=s?YT643BOLa*rT~amR376Cv zjnXB>J)H}hW{l!?2(VGS3=bQ{C3sv$kv54k7Pd=Kp-!pUT1Pb;o^Vt_jfyY|YJUrK zWy9_7=yLfVg|6EE8dxl1$)@&qHgH#Ie!>?-W3s_IF7n zMz_Cj0TXV24TSE;X@7lLrP|-+t{ZpS-+Q1dy8S(jgh#f&qC6-O?Qa{RQ2W~)F@-DA zBBJ7%ISV2;jvL?!8}e420(bknB&s4^i|UY{nU~<rCYk*SFvC@@o5@w~pWue8+zVRoIOHyyO~cwQvpJ{DW;clH zr4pWSnO=4kglT`1##8>#L`eNo2?6y|Sx1}A2zXpoZA&d+s@ip6b5uv+2}jjNqavzW z>WsD2RXcaakT0^S%NX2DHilEMr?4>?t}%u!V20b@2quhS445us=%S-F#?S=OMjAr| z0>&^E2sVZt@I)Ge8_LG;HXz*o#x}dEG4#-}Q=!ol&;qcqF}Rsz3^TzD8-tt4#_%Ax zVPhDe^@iKuGvJ2X-@%%jjaaEJ>Cjx4lpmgONfl_6yZxQ1X~rn#LV%6pQFyp6`4}FT zQEb%$#wZfe`(dN#2v0bwyCS1Pvheyf1rz=Q31}Q9#^sNx8xV649#)9UpeDGq0VjK> zH#WZxSZ#^b9hafM!`24DQ;>qoLYE0=_rm*7We`QdL%6QiEH3umzS#V?>IKA8VB~Ly zXFohcNJ9kdtS5g9B4Z_#z|{cEqy$dz=SxW4i7>yPE_W+`4sZ3RAg0>K6TlQlvg7ib zK=?f{@~6Uc4xVA(;({2czrKTFm}KRb!K!{T4IX4F0g+6iFNkCkJjf*cstL)z6I3z< z9%RZRDm5ctgBor|MiCW7e^Y&39`)b}m&XB}LU$d1TGLF?zX$;?`it;z(bs5Tik`=@ ziYW>-BSS&vBHsZ|I0~Qks8tW*I!oyMg4v(@f${%h-2D=o+O_TX68oKHY zH0B4N~u_H^%8`Sr(1RA;?D78xaW98$ScV^+ryk z=z7Bq<$7ZnAY5-0!xPzv3^=_XV`#`*y4jA%k1r7(bO@IVAmZ?al>FZz^cn~SJ8_xh zN@(aSD>45F=>~%`kPK{+?)(;mK!)~rYgZlQW|G0Z0%o`lax=LOS`Tix4w|j?E`eUv zAhmJTLGv^>o47E96FgxnSs2+d=XZc&O*4l0It17dWm|0}P2h3WL3`a%!5}At z%~9P2PdKUrSBa`5Dylajz)^YI>8P5)6J?NpY9VgOP)5@L3HNH;Og6}S!3`Uv;TnT{ z56rMZMlfNJ<=RIWWb9;;!Y2g$vtf{Jz>YM?2m}mr4iIdRkHQn#kh!63kY@p5gG}rY zZIDCAAmerH{GvpL2^bk>0U4&7$p-oqxM2e|TuL|_=mK!Hf%4#cMgYc+!S^pgr@{9E zvf4Zy;c`gv7;}0@m)W|xWVXG*44bW+$!5C*+_2d;)ryOtn9X)SxZ$R=rRHW67iL?v zleVQFfC}4E8&__a{?q_XGiI9)Nw%dG@NngJ2p*T&E_6o)v;E0LmEGADRnb+V+87np z5D0KotKs3OUV_IlTOO?MgIwl}?ATS=D-YHefy#FJPZyV+?$r_S3m_`ahrkTmsbR7q z!cKdF$rUFL)*sNKid#AV7o@~BSbxgRh83?uVj`_L0s$*N1O!|0Pw+%qu^Y-(oZU@Z z@gR62t5x-#XSX)BmEea>Ep`eeR*0~v9R!z}Vjd-NbIH^$f*Ce7H5a6il_0&;~gD1+=&KXnts+Y^u0u{8W-3My8N-Wk97*p#C zX4upW)0o-?#O0XUMlEVgZ40@sg0B;QGtzCRy8u^ln`A^pizks<4j=OJLtoj0CBdOz`Nsx*l7aWP7Cps2|RrU zO@RJBGD;4f?Rd=>wvl}%;N!8TkL-62wx>r8IA8`%AbdvC;f>XAh%B6@1E8BhS9l+D zsOANn(dM-k5c7%%?>ya|gjeVu3cR(ocjWh<3DL&{{vL-q-UKN1rcX2S_k-Bz(Qsb< z0*8s20Kv>V5)_;F5Khr4{kj3V86SjqfNrq5Rq@4{8YFTV{Zsik4V=?3u|;0<76P5CaPeR<{Er^S@@iG!e(?HW+)2&>VqsA#d6dL$4B>_A2~L&x}ud z$IzPx(*A4wt&`F|h2KU@<=Ui)`0DTk5J7z76yIeq0`c|JzJc2X^!SD%?I+`J6f3+0 z9@7>{7&{a`ktfC_p^A(x^jTAf;oR=K3%_LJMF|8`eQHCPe)H zN?3S*FE;WXtOT$T6?6Z)BP_5$lXz-N){d94H&xF#k-YdgOi~8U5s)14 zy+DYB1GvhBBe;4J9{Lb-k`hkB?@f3eSD(mw7tRIzlZz-5w3@8TL^*>0&2DNHP?{6< z7B{sWC?kn_tD8C*l%+&n;-;MBs4A?ilTc|$!63ayn+-f|&~wLYgj&3f0c zwz*hrA62UyOAzP&gSC2hDLvK&mY8bDchig)6U9nUzs5iL0ovPG^0UtZ)`e9RPr2io z|FGh71wjfme-ij5_$NP2)}`ftWxfMCV?cXdAeWMMClbUk{F4tm`Df96iL41A7ZU5G zQmhpq-$$&MOR*jY`8ctTlw!RJ@;AgfT8i}x$mLIhb*vOC4dgAvddqsLm?)7{l1!Z{RtNzKRerw|AeW0HlzE6?Y<8@3er5aEov%JY& z6MjUgh=j|yV$xsFpJGu9C9OuKR6;%qmdU`*iY#(-Iz%eePZ$SRBwUB9Oqh$S2bJ)l z9E9u!sjD%|OZe}ro*f; zQI{@l2X4_tOoV~COZQ;}U8UQsTSVy|MbK5c-4Lm(bSW;HZJK;*T`JvueJM$E!#iBZ zPXSq%Zi>%(Q*jAPGxg(dbhs$b#vLNdb0{S?T%HuNMl#8iCj+wHZEMQ2{q2-vlL^=h zUJ-Bh#zlFWjdW3-z1o@bob3n{vHet z2t0RrQtH$e>AY4U#rJM+6lj%tlW4E?9bi^z8Y?P&h9$#Qng^aGunJtu0o9}M{|a`y zfia>=8)|wL%s;)CCUzhz3%o$G{x3i*A!HZI3ymC(D4E!UcWq}RPZ8!MWq4x-Mi#_d zq$*qx6tdoDk|_uVWOc^G3iV)}DyD+?f`Ragcr!s71@SGY`oVhJ2#os65r|z!0vCYN z1@SAqx*$gNHwB?$;H0<;;yduogT*|8>4I1|AhIARbs}u2Rnzor>9ozxZ0G>%po|k$ zzq?7zmQE{n_*b1R?FdEBmah6lk(w=CT1Nwl!zIaKJWqMpZI&wVE6u?7FWTkR6*%o- zWW}Kg5)}@Bs2}l))F#nIO#BU0R|VeUF|Yd(FGA2&fgeK9^@v|W(DjI${gRT~LUH{6 z!`HXKX*I3?@BPj@x0kJ}P$8eO8(;$TK|9+pn_S$Q|=J)Sowr4-zXI=JM&-y-V?|1LDxGpfi z+&r^i$~K5x?Dx#`Q@Dn(BJL`P?71`hHi_?uC4Wf=Oeq8Y9e|1saCN812krWGJ%Imn z@8@;{?TKGOp79XmOIl2<_2j{S;a}p!pS|<^GW?s9F%{XqQj~xtsk;B}u9O#6E8fMs zE8b;x;D@H?XLfw5FaDRe$6cXque(Cq`|b*DAG=Gl{nuTZ?Mrt}w!`k4Y+tzxwH@Ws zYz-Z}(%cw-c^@*HxZ_W#16C}1%3Y4E(p`@1X?HoYXWZq;p5=06le)Z*Q4S%!`z4UB zdks^7AMrOl|7$!^vIjQATw!?r3CIJ#+S>pkFU`8HG1UDC5 zwl(xuoX*3-WF=$iLPI;elx{svbR4UFWoYFHE(BIG`LD+;YswVZHc7$hL^i^d(Xega z38&Z7k%t|<1Di<<30Wo6Q=K(C(=Gc>+j5#is1KpIDGz7i;QoequUkVNb7qIqoNHj` zzhkp32#1~5QIx#nx(Y(-Ztoq}=!?j3wK9$}uQ{Qxv;XCEYcBvN9>T{g_e++0OROzl zQCbO;m9+iWj&y51Z8!7qG!8|%I0Q1sYf6J*KM;E7M%Wk7G|IyS97di*-KIe(vT>ue z&A5c(0}0MSTwn_HPQ!np5g}Mbt#I6KnjK7VE(F?+0KO^r^S>w*e${B+u zc@!vr1$I7#&=!LG!ty@TPF|QQ;!n+A8tUSsAt&#ZboZC$%@E|5<^`Q>Z6*DEFyu4< zxB_}-I)t?l+&AHms?5afP!s19pzae-{#<=5fU4iSQ9a9=T4EP1RH%Hd{0)3w2868H z-6Vd;DbC2cHmxp(b;CZtdQ(V#`s;o@n!W={6<_%IXdDmLwY`1|OdKW!2}ID{{O5Hq~bIaBU{+KU<4;Us?iYE1gyWOel1glBPk zMdcBf7_|EA2XAgN0iU+oX&=*YIz%hQ`w|hv<$bn@Nn+$jZ<4sqPq0Z6@Vh)kT>QpQ z5!VhRaEZ$;L8@X9SGyDb+(a;%DdO4y%p@+>&i!asO%i|oE7i(VlSB)jNSc$x2K?gE zn$DHYxi3ee8$}Xm|>umBJO2IEg?<41lO2$o*b|l2+?= zf{qZa6fQHQIwBvU>WCI$_oKVa@oouH6{906fO`={Fq)~3I2#vbb_8o@X;-waAHD!f z3E*#dRK@J5A7!HwjITcqI2|834ezE*y7}?Cn`@ENzFrBWUuJ9(PFL>Wb1 z#!Y=V8+W*o{RAk5DMgq?_*?2IMJT0s3xj0#3-cjGq#mY)2_o@eZbi|ScR7bw;d{)r zcBBiO|r}fJjg3Xi~~UL=J@Jt$$O+8KOQcZWQUL7#y7l^CL(d8 ztMI!#73oIYjYSUflu}r9JdJ3(2#v%1gf$X=0Cpnr5I&8kT-qiE zxh;Ju4-p>13$r0zMiWYtSS@ImnnhkID8pL+vp4B8q%Vh+7|-JLiPCKXy2w0uZGL zx9SNu=BcFNZbcE+IMSB7Ik=uusXGsPj9_h@Fbgi_KBtk~&d6c}&AD%BDiG&|S5|L6V@h&tXhvqze3=gQo{DAa^=}Yn3 zRyXKUf3p(!I3$5P0)}~Lz(=a#v)iZcg^87V7)LwRdW%0iG{Z42wFiz?>R=r0)N4dP zS2U}5v=X=Ae~C}xFoRnrdZdq@ zIWH_Iv@2ia|EGjr!vC$58f3(QUGMaiZy{DeOlTATH2#+u3Ulk0h#YL(I3!RCQ;MYV zl-stH?nEYGZcP%Q6lqIiEx#32bJ6uG>gqyEKhR}pkn1@o4UP4xpaRexp$|(;C zQ(4D_0Cr+em-d+{cR}0%G2!g^2^irCcFKd$q++jy_NS+8g_r^{p>_O=xPbUj%1&tZ zJO=QL6y~%WVnW-LebBzr)wbH7Dc>vq3t~bC$$AV@ckC_NsTBK)IG18S5$~XQeoB*v z@hu0%_ENbf5D{-WK--$y4pOVLsqK++A+$ZI?I_jhPHnH05zt;jZ6~SD#nkprnF?(o zwd16;;nWTi@ta4XEljx!2D5PC^)gdPcQe=q=cGIW?RD^wdS|B4ey~c9ZJ7No}8$3!ptn?RY8eQ)=Bh9HDk(N(l@q@dH*-*ez0g? z6D`I3{j|Lk-etvoBHI7pm>>y0A+$oE69WB8NK$=9Xf`vC6Da=(6*n7-S}H~yu7E|} zBRGh3F{R6Jux2vbnY>${$znri;WPPo+ooT}@vD3HtN1W?!3dWkK?0=+rBaau;QT4E zCw{h`)wTEd3z0PCK^V-2qFX}BR){kpp4)gfHs5O?KW{U8tb3MO0{xr7&&>#ri4UKf zmN@|m($Tq%tjwv9j}kl$*2YiMVM{)tp9i={M(A;T;@|Upn=8`0bqy^6(DS2^XmU0q zZMZFtDcx}R^0}~eUVM}I@AovcKJL{ebJxHGi*@ORU&HT0GB!r99!Z%SJh^9D=3}1R zD>L&2Pd+a@bGIk=Zj-ssll$ame&NY|du1N?G@-*@fLJ^OCH2$&w*rx&%iPM zyDeN?VI~b`(hovEFvXXyW6&Z_yd(50)xU)#c@fo;$IPoBhOfaPfwm#*d06#xt(Zx%wE>P-hzCxC6P}V@MqCjAMc%?n&$lBk^!RE;G30jKq0(5E6xc zWaAwETbuP~4&VA}EA($_^4*J-3Q4t9Yg`8KN*XM74WyY}EL2Q=C{Bi}KW0PMQ0>Gt zUfc;@NeUk)J^{RU_D#3pd_BZwJ8*cNX`ZVyO=vH%YwD_>n`yI;VemPPcEr@t#Y5i^ zyUM_%F3o;~`V^sm#zLX+3s84-n_0M5oK9LeKZV#B-+9>>R{m+!P7+U~`^E8K<)1>=UY71j?XiM!&hbvTKH-}IcYARS!oQHYA`Pb0&U%E2t8YWSDqb)I3{KwjAVMxT|7-or~ zX*9UiZV82q!Z)L)v?LJ@Y+I~yz zAHLS8+>eCH?023pTh)r6TZXPm3;j;?pSJvTq_$(T87Pxn z{Q8ub)cYdr-<5wU4t;N8s1;D&;Ijr_N$o8cAaVF~9P+QidB4fx(L7lBjBJD?;UHAA6A79#mT?mp_F^hSZ*ab4oE}i}JwP@oDyjncdOg92xciE3>yJ zUz}vkJs&6b<)P33{{ONNrv~EA%BP1?eWmMYk2BBkQ#jrdDx!Xbq0he-n*OKDxE{pn zgeKEuqB~Sv%`|GJx+7FH`Lm$8FhdIE6E1fdr^6Lq9hy}lqqc2uyp>7Y#DzOjmR8XA zR%jW)tiRQrzhBzJ;s&6?Ml;=ZHLWLxTsI3Yy%pk8SoTdJ@ie#2sm$ckIAIkYtWX9u zPFw-AHPkO$%b$P!N?4)$nAv^4$Eqf+p!yNFk%KYc3Oz>bem6-Bc1|U+^W)rgz+&3y zwkW~t)kWP{v;mK+Uzes2Jx}Buw_dt;t#fu#{e~U)GOsCr7tdx&=gAD@o~NOmIg`-a zgev7iHRQHk{`-Ws38}_Fp-%~=`PXiRKBs1jd)X334W9jm*n_UMw7n2gO7=6B^%tQ6 zI`I&3V$zA7?>e!_mnT`bC9+Fqs;dt*;Mox4H|x-8)QpUa`6)Yex+HTM%Js(<)a((; zin*fv)`Z>_s)~g!A#}4uEDc%t`PAMjx(w@GZnwML(tXyPR*}|CjT$oA%#9Q z5`}iaGEo=(EpfXpj(pUOZ8MM)Q0+Gw>+a_ov6OSRZDY8-l1+(-yS+#fy~d_hJ#3Q5QCX? z>HGn-Iu)!zoZ!ud02)sC-oIBRO8r*9z1-oAHvC1r);m`<(6Cp|FuCTIqBX0hkYCzu%L2Ds31o(*y9ty-@wRrO+9 zFMlbs7%I)_R=+dt=D2pQYpH4x0bqGm56;ch10;1?l&G}RispZX`* zO8K8r&jQ%#&m^29~!-Fr1djM;I@7# zc`sPjMKBta8@?D~0-s3Aqp%2+mz|UE@PDJ_dS&*SKbnehhGGI0u2Z-c)2NtWSlmR# z16mQstplz61=PAzEjQgVD%@$3tGI^>ch2J~Hc~N1XJq9+N`*VcaV;vTm~UA8lZwTL z;#De^8H#tH7}S%=-8)b2Z)oLzM6=CW3+JKYF+;JJ>AKO{b^H9ev{=uJa}_BYwp-Rw zCUV#aZ;t|zn;+VWU!J!;)~w4XyLo!WGpg-B{Qi_qy* zFSn&UW@LrV#s>_MdA^~Q--jcVw({E%a{EfxOF>-;-BMSoP;Www{UTId`cqxt z*2S-R{vfLFmWpewDx-kV0l#GT3JR%hWBY1KR{m(JfA+Pm@wL=m6l4-<2c21LisnB`f75j`t856#fHZnJu7| zzlpk=ncP*(vmb}1A{#TFvtP2T`SxhMqm>KE3NM6mo;~CPe6w&iXZ0GsTwwk-HqZVD z@B#dCWnZJ=sRHxota+bw#pu7=OuAhrXArRz{UO zwV_Sxsg+TuvV(?>!l|r`>Y@+hR8~fH(XVm3m8+dzPh-5gR`NuLcq_TIHC}U@(z(7` zHuVPj-jt0veP9|;xp^xZh6;`?aqE-@Jb6}}(=R2>V&fHcj{#f0kmw`=WWz_B#DH0q zaf!}*$eq0wosPo2zy6glK0RQr5U7N@v^|3OSR2_NLkW5C+gJF4k-i*7&LhT90ON&*1Gn z3OyjSqWx~HS8Zl1-^We@`W^u1eh3FBR6{tzrLEx>yOFMgstIp%v+h7m%AZ3L<~$0* z0p@&vtl4~+wFCMD&3@XJZvB&H(__q<*4jzVt3VgiY&nFL5Q@0auUTm3+Ir3ifO^5- zYBZgEB3}>M&9IiWSS&O(Km6YDY`T2-Eo-slLMb17Pl9$lOl2*W5^A{?%WJ43KlFAN zN}(2O30(Pny8G32G6enAbzjvC9ChAW0wau0;)1{HkU+k=eg}el;BUWxmoHbdEv1Mm z7J(1DyFo17nJWO_GY}iW^)L* zP#n|Ae0pzMUTa6NhECh)(u>Ueq8L(<)leo-3R8;oM@Er|6x8G%q@gpo zY2Jf0@D`AC=4`&3zTD27&9@J&FcYt^3wy)51^2vey3hWt0w4U)7Bat~Xu(&`A4V~7n<3N6Lol}c4c#U7ShCwH7a2_Np%r}D;*khXk;*!&D+F=6SjPh34$NI1e zBU0k6)}{6j52DynuAK0Yssi+U6A!l2S%nsjfahE#lg$=<(;f04z*1evQkxa_U1H12 z$tibjr<@Jja@Y0-U$*YDi~s!(TK|Y@WiYEw*e=|^$`m}kG16K_qU z4PWbbZO(=?@MU~TlT+~ruY$glQz7|D%6azM{TR|5vs`N0O~f(V;xP1SYr|L5{TA4V zX~Fd}V=az*7QZFHf(u@|7ONpi9vKn)4sl_59h7ft-UTA4A_;KuPS=_w5GP-_F0fCL zUv_JV{Nh&TM5s5+R@&U%J?-a^5WoVvGzsQEX>+N2?KoI;h#w{8ev6_a+zWn%-CUe^ zZxWohz5UCB$oK7U9lp}(ye{?v!^uQgIlD|Wr}ANW;O9; zN0JbtU%!6%kYADmR$*S}Wj@0MlrBBBb#%1R;%b2%0pGsjM|=w7ubPq;b-; z@kwK!S!a(lcA?@vX&f|7Jkt0DCO&B-m2;qBvd(J*Y4idrq;VH2qDjNEl0ga5_~Cj* z8c|sJq>-XB6El#;R+zc>btH|n0Qxu5=&N8&8sm{#lZJ^3X=DS{q~W1bFi7LmsRn5T zK#<02fKn@$GzOW~0%_y}4w6Q|0;G`y3n7hHarMFbNz+tF<5hUIkj782t%Ed%sM0ey zl7%!lf=$vGgq~Stmnb`z9SW)~YZ2ICv#>*(=_WhO!&!hG-he_)89F1Ku)_?MT^TZ$ zslz8T6gzB&5M&3>R^4yzSh;=;*J zm)VLPzMU1z4gp)T!y_<}sl;dqb+AJq0odVmmtboMW(qhf4jx4tD|6Q;GlxcDNLv z!47Ryxsn#_5C=HO4gm|W!^?14VTakc`XD=)ros-hVJqzLIBe@+hYqTApB*@YO?DUx zLP#jY!Fbg;5qy!SQo4LmhX2)qFFq2!IE2Fd*+h?9G+#tuw%DEvh2jf6n;53DD|4Ga z?5wy|@kKF&AYXX4nlIYG#OI5s*`nl&S5cnu#ZM4o_@cyX0F*0yu@8CqvxylBE^*;x z=SZ32iwX$A*+jsWd@&Lx!WS73>fnn&0`SG&+Z10cfe^zNiBM_2m}^`i`QqpT&(X;j z6$;Hkoyixg7b?E!xG0t{OjF^DH()D#Q36}xi{GHpe6dw!t@+|^n8onLcGJe^i`8bG zJ-+CK%zeJtV48S*F$N|+U+gh5Cto~-E0@{Cuc(NgO?Xx^rob0bSP5V3=2huikavvo z$QMm?GjcXj9YFua7pD}g`J#Hh!51bfd~pX*J)7`QsUP@a06@(b0T6ug=ez)4B&}j9 zJgmbX*KOVoILH?P3-HAaun@lJaCXZ6TA4iqGM8vjMbebSg~ns}tq1m*jrvBk)oq)~_rgfyN+MKo!6Rx+?a8tJeS(zuyd zrAcF}Q65R-?PXpwk~As<=-)`=pn^4NEJA8M$uLnNjSGNk((q8JA4ucZI}OqZfFO-$ z0UDExqh_^08dCrVNh4qZ(r66}A&t**^}$JoX)2`gIb2pqBcr@d(m19{&)`TF(jXfc zlMKuzX7jSV1$Oox#K&{DH?+E*L1H*(bD9tXUv(II7$^PlPD0Bs_$~3!+i=?cP^#7P zzs>R6#n5MP%7@%7znolw$8|ID=xc<^nN8mEaI#bWXqvSU`r;Kl+=oN-q8PKR=i-u` z%V0N@CQ%+H(2g%3nAv5$jh7FSw-_%Ul&Hc;GJN^qBV^*ed{Fc#@|d6us#u#Nsm>mx zehGS~FND`2jGPbQ5QM@F_$D%~C4PLrDxBb~+X_1>{(%*y zAr!X3A&;p(O~N%mdkGXy_{lWu3K5_gMWGzRLwYOF9I(rtZ)Z41A4{{wK;dkJFa<*Nk|NtWrmnd! zt~qB!W`;8Y=uiMoDugJ6k!PdW2^1bcMQ2iYAHsYJ8=p$E?t&2Qf`gZpjDhy`TRJ^q z))#;a*Q$~P?ohv#Gs%Ms?}t$}>Y3BIeu~ozd2WKjiHA^0;W`LAB%e=soa1_<O;c`D0hP_#U9zOxVc==~BrP<)c_ zusjIVeTQXqOBA+Nl`*t!U5+0VCe>Kh5fpa2o%pmrHW%9^ zIQwKx1FPkq_Vx-3FO;j6&)_v90L9Pa z5WOwdue*)eMz>0o? zW4VIoxNw?t#j|PF5dhBnD5;jhz0jP3P@II{)nzzXtuP!`Bx2u}=hbld@HsUc?t-9) zLoV!OI9v>^42QqAxx=B5!=VJQ41?#Om0@r_1Q`ZxA&ApoixOl!taw3pq63q3IrJjtx<|Q4Cv@zn)%R?mjjll zB944Q!2w5hUWJV~^G^`8GxM#5ZOUF8@h-fz@C2?>-dd1%9`+ceWvxuC=llp*-g&@P zN(WS-;w|GtO^St!R>QZ1i#~;*8^6|T{G1n6<4=M>E|SL2#t*O3_}ieB#{Uh1H2&6? zR8xNjL3&}(%Wj*Gycq(!LpUhyMuQyKx&vVEH-3f*vu|d5urz)FE5OG8Vuxz{ryxk< zH-g|cJ~^n3nGZSWV!)b%0w_7?CZKM>7Y^zWOx@CHj7#vlZmoi|=|BMv8g7r*opuvi zZHSRk%fwKE^9nLrLu%iIE;Z3MZ^x%PCxGq(;I!R|@dhDU8f!Kk?=wY#E}_{<2&-t; zFV<`n=EA#x4yW0#5Jp4bztJZkOjgwbHCcDN{jn98Jth7y>U=w?=@Lvvct6o~9Tw%Q zz=>=Se<6Ph8Tu?v2@jcFoZlDuf$)p&dA`Xz|km*54%iy9Z-3fY+i^Cb|5<>HVBq~QanIj=$42j?SS zLh6el6s6#hp{}G2>eO&-y3-6`7WDX6M3)$=a9(fnC1*I@R;T+OVS+jI2pg#D5k-5E z$qbd4qc3?-T=5~6x;+MH_{eF_wMh3G!F93VtVHKNfd7D=RbsAdRj#DrK&~dhT&;VI zTmv9-eb>)*bm#GSqe110JI0EeRPUa~-u>!`Wlh8{*}2lgz20_%4|{mnwKLGXIcWHd zIA<4tSvVgy2!}E#8y3eqE1@jJIXa1Nr&cN3@^{>~Qit)aRO@Uo4Bkc^1ts4`E#%v% zc~Ht*sO_NTTd0Mc2$oUHw@-gTzWVLc8dY84I7|RvLlSQSh}SGDE)H2!eunO1dd%tc z#iH9$r|g@3PDwtqy>sEaY1T^UWh|Ruj*Xt34OI0k-=gcF5;GbkpBe9L1+4EWOi=DA zJ_oArDLhne&2UfAWUsMXiU;yq_!8YpvW>KBqtP+Y+Rs$WRnuJV<+2wmajF#X%!TSKUOAM>u z86J5K+_p`9=ji)sRuh~%8zE#vDEtbyoq0f8_P4X05zwB1!nyptH0w_Yg)ibz1~{uK zA<=0B_zlAGfZu~qe26xiaHyiq8rZx8=qV^<3bo6u*e~Jw&N`s(6pAlWS1VXt`DD1B z)9C}R;)R1zxmsqrHX&5(u*zcqmOv<;%zC%OA-gs3`{UD{HGsO)=1m9}K#=#e!*gAi zm+aq4bx!Hr*2K;?IIkj zXef_ZaMiMQ>;R)H49FS-`97>FO z`uj7V@u|5#^Ms&{+Ml@$HhO<%&xF_G@6Y@!OsY}HRR?jfqSc^{$;O5I`!h#icmn8E zf8l_N&w3TX02L4J&s<4OV1MQsYWOnuQDmTB=1yw|EneoHb3kpO)d_hIY)VvHh7-|9*2sJ;zLPAaJ|HOtG(^NvuNSH{dxeG!t)X09T zWoTVq?5lwJUbDR8UkN4O@lX29-P}#y@vmV&z$Kh~Xvf1;-tkWZH;G%Ug;u*o9<^|b zHZ`ix{sUC^Su=ITrd#w1>tMBv;PvmX(~?9`EvEdb1a0QQ^+2vm8$f~ z@J>3%y)dJ5$PR!eNGEv<;39z0LL5v`oaGOobe8A`IBZw>jzzxWG+hgf4?`-I)7%H8 z4D@jjbdT;)X?eTuamhiY^PJ{gBoL>uu24PN9fI4VMF;Q3uTIO{-sD`9&NBh96ty0L zE-Fb`siI(ue@pDj&IrTn;ALYNhCApmT&a958&=638#qV4aKmtMFa+mzK;U8sei}Gm zyDkof-xA^szjJ{z{1yj)bCu9rP9ucgOJKvFO^Rc}?rG37>=rTXdKIJZBK#IJ^cL%| zD~p4hCJevD486q?c0a?FGVG3G)D76VKXCAs%024R!z=+mO|<+{Z7coVe~oRWO{*Mi zD}5$F{(vI?B!pL~d^nqu5MBTiKZL(y6eA&g5nu`7FG7e7;Z`p2bGZ!z7&EE z;k7{Nw*Q8bZ+ttU!$t_t?x;feAZR6o-wZ*A@PkG@{Sf{NOfHhJ`wfm?DjPZ_Y*Ywu zeZ&aio(Y@H58)$W5);CYn&oxEmfl|@XgeoRUTg?2K*fV0yo{Pa2(P4uA^a|sq`A6= zT5xrXuN0Af2vm;+>sD40)x@7S?3yW^H|)kCr3|~Z5QIqIg#r#o1n1u>p(SIdnhlLA7uRo zP>1jU2)6G0bs&V#RmDnLgz&L|8|=c6Xo^G8ML}vN7`HeN zP9UB)8G;n?V8AUTgf~-BLP9v&Y4Bx62sc4-iY7p{Q+TN76rW#egzx|er`QV62;ps1 zv7S?uA>*J^1T5eb&%r{R;u{D-r!Y;$DVh&fA$%x=pi@W)@1RPb40on;EP|O1;U-8Y z*$z;La1#_~`4*@S;oVfeW09{oP4*BYgqJC&Spuc>=#>z3j}B02%@969={%=-2??Y} z{|7;O^eoJbj1XR?5_lop0W3u=g`kUC7%a-Ah$VLExd`ET-=$fT8Nxg35Z>W7_7d*z z@Ryw1z*+vkIzxCZE>A-E2;g;u@a$X_!p{Q!e}(V@8X<)L57nqEgue*A4&h$K{y!ny zG>Hk}w<9YZ!UJ}G2p^y>oejVczUR0K;j1CY+XZ|vz_elre-#%P4B>rMK01W|0uw)k z4>F385Z(dVO9&qWAvT1Up^cJrn>v30lMtR;YlQGhpmf_=P)Z1Y41&H3uK_A|;m4ts z5Z>y0BZQAI>gk8@2{7?Pc!{#1Q~Du%FKqN(xM#v<^Fz4(!{0*qShGAG!q+3O*btu9 z1$6j*I8?0pI**z_2rs3ET-^gD=@4E)Ex39&lrk3PLeOJjuBw3`@E zPR|oY2sc4t>&ZYhTYD(`gdzMvfI5T+K(O^k01dW2sfv}f2;udAiVfib3$S$_EQGCR zLI|?8X)0{J1txMAeh5O4ttEt~b)~;2I%z)}Av_OCy14_Tc8O9bg_Sozt3!ANwRDRk z&}z4+rWS57>lf8$9U$mF%P8Zu24{A;O6Rfh4kQpZJ`O?LBIjhlEz&@!bc;f$#VziK zpo@ssQAEa4w^*-;>)`}a#6zB2><_qwIK|pK{JOH8&Kqcia1#`#2m{ql;i1y8aEgCl zY=rOt2&cFYpy3poRI!p4PB9f3H`ry)>jD;Viicq#PVq5>pi`Kp;uQ5SQ6W4JLeMEB zgl|!$Pev#4qNl@5hj0_5lWYd4L%0cwvwQ+nhww_3?^t#|ohEgV5yJD>qjVZ5rAPZi z&^=nE(wZTBpVE0f`WO;Oj~;{|PLqzAkrBdAsRUjK9{^a2nhil0Wz`+Rb9*9$e+4g_ z%@E#Ihwv@R*Rt7K=QeP<{Z?lPuf*j^2>I&gw zpw}VXtJwc1gqtQYA-p59(jh!x=ZEkrb?J0dhVbiuS0TI)1RcUnD~9liXrN#S->&k} zA$%iD{1Cp&C`Ll~2Y@AnC!w6!5T1uNN_46 zsD$t}&`Jn@6N0`A-)Gd*58(~}Fhlr3WkaX*L-)f{|77 zxrxqyP|if$1k180CMaxunq{!Hhw{=G!UqA=Av^$rt#1Knu=Na8tfU27KLa?()&UE! z^;fVEwr*y}vbAX{Y<)RQB!n-75M*l!;niqeUhE5i$ixhErs#Vm+sbqS&BQ1T5ebD`6o{u^U1#gqx<~6u-hmoTAf3u}&c& zJV%u-AsiPy24*^hn;^MxH9#H0O;DWW4WK%NcTo9`MPrK7oC2zy2CI^b(~KRUoTf7b z?KFK=S~G+fD4pjt_acEf&07$}Y5sy>gzz~kffvHNV&Wv6G7f?+YHqM7`hu+1)f*vv zML6A>&k){Shwz;F>?L&<-lKtYAm05PBIZGQDK1Y!_-5dB+=W*VX9%AL{QnB!)ilCg zcwgAm6~dFC*CE`i*#9Sln^hEgdzMmK+V?FrwCZUDQ<&>IK?&yL8mZH z#VNjmi8w{G3u2u@LU@HLT|zi6`f`}*5N?8WlKB922sc4-mgj)#5WYp_JC>bKF8Kzi z=8`JqG(+=Lk2Z&(dvv=>YliT5l+JUSMMxk6eLDnkn(rVOA^e0&;DzvPOq|4du7seA zIvFgAz5s97h@Y5OE4RvlBDohLX?mT}I=hdG)``IDh}H$f8Li(>`@f@g8I2IF?}trY z(Rw2EjMnnDStX4B{&TmyWmdy{fxbn^n8bwTYO_2YmM?>0Y*?;F#e-ql>IY3AEay_gp>!A-=%G|XE%*gZy*vtkJr>*na`m zVc9z0b@TYsjj)^xr7-PaXmwaFp_XoO5474X%Bh80oPCDsvjaeNpOqO6?S^`z!(JmC$6wAf_@8n zeLH0)`a4m}dr78A3}LT9RwQhBFDYOryp5}qSBi2}tLQtS_i-6M<#tf8xHLbQPi(Fz zw=aZP%C#&>_>zVL+e9D~;lNib!WL&uaR&WCt#!_xMDjuZVDry3hTT2bc z))r)-$5wV8v>02xvX$fi52$wh5>*3}59cbKH@0p?N^$(BA&BE2fnbcS5*C56b$Uxx z#Apb*h%I##(Klvno$|(3=kBVAu@L+zubT8$8(Afv7w`T13t`21X96eCZnegZ60;x;HJmY)mIM#;S!JFfy0e*Ou9=I1h? zbleNtDt^8Jf}Rpr0u_GV0j==!aR{29D~)>k{Cr+Jlb^Q-Z4^I02pc^m_DtApK0oh+ zNen;lFfQEZ=czD^<>wkyJjl;!7eN!?=R9i2&&lnLfmli{2I4v>Wt3bFK@Y@zss`pL zsZ~0UpFcwa86}N6sDXG11Y;mpvIq>so1m5=svzhhnk{z6wOPdEn1R@}hbm$m1R3l1 zLHHX#4=}Py?j7&c>uB(^2?{^=1FHGiLs=I-sVW7ir^Epe{QNLLgP#jjv62@2{1MKlg&uIf(H*e9|;O9Ijg`X!v zJKlRzRZ1=0;st0mKUYu-x40x%_1Palb)QW(8rtLMB}(VH#d4$+x2S?3efARs!!2r9 z1l*!c7gfYm2)c-Ebri8M#x36U+`{Uqis%l(cMEw^bx>u*XB%v%?I=YDZ4(ry_ztLc z3J>Ka(J5MWHJri&g|y%lg#g7Ves++_^y>Su;P>+)U zh$gANA}~&JRk7YU*?_dciw;=eqW=vGx#-Z9u@`Nc%0+jFiCpvq2r(CZ51hT5Dt)!O z==Ct;c##iTOpxKB8sH*;@*#@}%J_*NW<0#>tMXljd}SQ<1**qU8a|WeINAiIaNqS1 zw381}Y0ZasB}(Uwqy0!AVJYaGhK}WLcsTui&|DkQ57*o zeToE9R0Bs9bs>b9@w87R66e9ZFr(0L9upMj`3xCo=kZX_c^(I-ohJaod1eAMNVY~5 z>p9P*C^qOk0Sh?Kt*{X1c@{!&#F(byJV#(6&U5C7I-TcBRr+K)4=y?%X4-j7kj^s? zpmrV;6zACnl;kU4K^;^1j`f`9YoOYB@|5#jQKWjb83f&MP@G{mQ0)w*DqrmkzXR3IP^z5ano+8UIziAqRHo9J z&ahhPJSJI#1mX;DLJ(*86N2FkJ5&PC8M<7hiW&<+7gZH3%5?_rAl6N-yDyQpPuxAW zeGNAyi*j8j6XQ4U1obEH9?0&L{lnIwJoU-DH9BRSWgSzCQH*Yilat;_C!A!c&*euy zXe>T4Its*F^g$M!AK;m_Lm4By6D|$qEe;?%3}vYAen-kGDr+obg^(q;x7b;P*EcZ^BrT2y%jQXk7}i2MXvrsOP5;y~o#*%LHG)%NJ{vC>1;9 zoiNM3>bV2*+2o7f;~B}a#@F{%H$t$Upv2Kj%dps-cfu^adqx;#s!1P2?~X#U9OmmQ zebJj=y3L{Va^n4%h@&P$@O7+zr&F6)B`t;nsC8eu^zG@i(mAeGj7)cdxMe zvRBvwyI~wuTt3s^@@8Pi`q+u+MfquBf!(Mr47e7FYan}H-fOQ;SOyZYxsHjiZy{S1 zZjL{<0?S<3S)1cOC0X8Uzm(96##|F6)_8e*Cm3Usoe!~uq|HTDTnnxtS#D!Fl`EzDqD2QKEXxT zqS*#r=etSryynA0D@$iXZ58#1$NrrGFtzv+=xpa z1cueMcHC;r-A@bgwU1%#Am>rWTR^Rf)Qh|mAV|o527(*1<>$sy7;@5o5^9cn9eIWLi7f^%0q%pwqX)j@KqHBb%UH zcOVybeE7TxN?8iI6apVU4_kooU&36l z1acoJWeMa&2<{Tde2X$_Ha?zBPeSeeXVX8St|Lqf{y6vmOyuG7J_xZ7pUY8P^1@7K zD=IAypMQX$A3j$BC4=<6Mt$ipAA)}PTnkhlKEDI4JbZ36*7(w)R8@p6?LT~u!o>e^ za8A%hJ$&8;8~yOvGoicr51)U5NzB9NxyFV251&`UF!tedc2jUr;A6!CY61_R%cvnE zb{JH87tH*C?HLPgCiU*?&DU%e>YjGkH3aG}RqmIlNvF z4)U6P7Q7OvGynV`6I~6O=%@5~#i?Q2xVPQ0Ko-+jM6;;2P0I#0J9Ujw0z@w7>mj;WxGr!_F!jBzI8 z$pkr`-Ug`0lL^XrvgR7&X{*Y28S<6!)Dx&4Pq~>c9X|l2aO5Ni+R1mQw5F3+E1fr< z-bVs)^7vbnllO*TjHi<-K@KYbI-UYpimHI1i#kxKYFP;L zP6&D-%nG2g5N5w=2&b5)IQs$Xg)nOX%R-pnm#T#@&w>zK2s8V1wGiebfb>F`xyDe< z;zF3$1N9fe9Hd~jVHOv{T#EAD6+C4j%o1j*7sA{DFt`wAIdLw8`2!$X2=nY4jD;}E zRQ6<7FAVqrn1XuYu?ITiu z1VI;3TSpOdVn$ypP?!`k9D)>a2Lyje$cCetDiK4BG}I~-qsN4a%9wZqs2&p@O8?XV@$RxR`?V#W;{^iE~tYEBgU);9HiTT1?aXK7DBi2b7JY%G!?q- z1rv!eQy>KC)^*EDw0-gt+o=Gq-LeKsS)cV7wEC&i5TmAiSY51Kvgm2}N>uU91~d>| z^Eh~ct{LSd$pcC1((>DZYF0N); zuDc9Mq1r+S+OOuQv?i-BGgyIc@=JI!_ywH@0e! zXHvf|G%r;0(;DTCRG5~dnQ#z8Q#$RcGX4KK#(qa0)jzgmCO@F_9N7i=Xs0GJZp?R)3V$= z7r;Wg{Y?mx=V?p4Jkea1Jd?_Uu{1#uFm|^*lPZN)y7^IP+0F7ys)AZ{?@v&&d*zu_ zHI?YriD?E1@->N##-vCi)C&%|!A{s)Ps_sN)@qfo_KIH42esHszUA zIZT9kUI8S`)9}u}GY_Y?Rj}j($l<{CHPy0&HGJ3rt#;kj(_P>5*!OFI+I2n9W8bW0 zCi`wsNtpq!^-7=y`&ODTu6YSyea*6HUBCj@{xU3teSd(UuU&2)O;c%uvzMzj7zrWB zzCxN+s`N@!j!m%~W|}lTkavL6`L6-hq-mlY2fqWXSrm`}N>Y#L9QT5AJQRhRDqNYQLiTedAQMT8Rn_)wblc%31DxP-`sP;S$^*pc9 zO2hL!(DS@O0R4N*5vo|v^KJ!dc-~m!QaIYS0SNzie`%oxbtiY2Mb5Yhkw7E`~zwC;Jo>?(Xy|yE0@aTSHD+?LLKf zdPC3)3(Mp9)yh`JA|J;m!o+`*dV_*xF!EvcgDB5^m<_>ym>vDjv8@VaOyAt)51J<4){uEH@wbLdniWPl?yFz?J!BrPTz(Jv7!{G1@%ej*XGL52 zT?AJ0yT~KFDi~NrY{nFonV4Z~$e-4F&B$v_3!s178nUl~c{eQkPd|m!I?|Y^M4E{} zb)@l7DH!v&vjFNjP5{I_?$EueR%&;8vs#EH_X2LP3q8;j2bskTGA$5Gu7HKalKLBB zV~J@hv7|n1C6=5I+h8maau}lW&frLvtsyyrjjbUg?<065?8m_%jd<`yiAw46g>|`Y zZ3JJ87rvN=!hF7X3ukI8*>{o8Vms}A%@>Uy!i0Du##8~OF2WP7HY%Pt4yzzf%uq#Y zp4b5spC{&;?L?ly*VZmiEQJum6J_3o)1}B06Hu=3g!}|phU&;qfHzere&_~4^Mm{r zSV)?Y9s`Lzw zRN;f2xPFrlzQFt|;VT>rKBxyis8Tz^xqOgzrERUp4zg>64?6tIxQ+#j;`7E~I zhCxNX-YcVdC?_L1XJY`2s5)u*@3PHN^+VUybF18rqN#9s?xvglizw!3SwME*~@pEPSvZWySD;1C{23 zQ^u8$4|?wQ9GQHOt==rnK~Iqn{tI+F^v>KjV)?){6+UPJ6XAoWAP65^3PJNh2bHzv zgD-%_%ny2*Ha;I@C^h|9^T92sn$HK#OcRd}Dq-UD!4M;J^1=77D?Vtv$KV6cie-@x z{sAkQ9}I$(&j$rYdE|p}F!T9fSOEPSAIw#-=7SbUt@*%2g%3X2W$=NAO8vkGcLUV( zg8&FVhyXPBV2N2R@IfNrARh!Qzz46uMTHM;#?=S;z%&&;xEZ#>2T#Jb4nA0>O3&a( z6+YkyHTYnKy`~Rt7+N$*iMLu8*a?W|cx&(MIOtL^OLX7b8xB$$cnfYIa-RPKI1KvG zpkvUWK|Q>l$k(SVYo0ynV5;?3HjKCjw3|yVo@BP*X4BaBnY&H5;7-$!hw)9pd3IMI zC(lL-?k;V-Ehs6Tjq_7%i_57%iUsyd?P1N`pEIUzw5-QF$D7HT9!BOP!$exN@a2{E z=+97tX!tM^TXI}rkLiYtxGAbzY!-Ium3Jny=h<6uSKfl;rerI88mb#%>U-__iQPLO zCAWyq=!$}dT%KTM5c&;e7?&XLUyg~J%Zp|+W-0mob@*j#OdON8SosC2H74#XVC@&!X)J&GtLXq$i>r?yQL7Mha}zDFub?|{4_DW$1)X4l zJ%L(o66Rf3r{2Kn%zWz9b_LcS%C<8n5x+l#$Ax%d) zu~yi##9v3yU;Bu^wiso|^U%D|@5Q6?b@ob|nMf$aywYxj>~rq5n{i|5ghPPuwhK0r3NT5-pFQO~AdjKNuxDzxkxZQVHtu5k zCY=4F1G-^`G}cnPeL^Gak~vV!3b8k%$944z;@iMcn4P`jb0KFT46>Yj2FPoc{9v@07?h2(-FR_tzK85|b&dVS~_alXA z+w{M7Qt{7FI-6jE4fQN%8ie`~kaOodu<^8+^AzOV8%pP4$9!*MN z(u6|2q()XN+U{N&%#MUv{2r7}KiD3i@DYR~5cqHO7>u?Fs`$}`sL~wogim%>tCOBH z+s9jt#rds8cJ+O(BlHc?5e8rf@RdmuG30KyzpQb$&vjkl0-VW+bmBN77u)?lPnWH} zvkK$h1}!YL--P1a0q~90Ne5veyKo;>xu>9dS!gc7Y6{#hT8QZ=sle)0n47wsb8kMdphR9U>t$h0Hr{+`aKR7GVb$330_5U@%_Sk?!xw{Y})6Ox)fL7#NEF<8^%yIa1wr2 zt^L7Is06S^z3c%9Z4+HjF8?dzY6u{EjQvpkBpFl;Vky`^2$N%IP)!MU8 z8vb6oA;zK4Lk@k>7pgN@0y`rQsl}liK#mf-0Oa&x8w)jWYQO6O* z2Vfzve;-pl^%gYjsc3iXR&Ux%kKG3|>9KoZ#vY4af-5l1r02%LOnPoC%%tafey4hF z5(MeF_x`7PE(~hWJ?CX5F@rsqi>%z9>w=QXjO&w-5=M3c3msO|b=cR{@Y&O{HF5x7agb#&-u1`Uq>2l}N-btq=3 zH}cc2JMcn=J4@vZqQxg`8dzBg@tiBbVs#5xY}FS0DobuyT7DgVvO+ALZ3PQX75qGK z^KeJvaNc1Z3FzI=!#2cmN-DQHSsUD26)E%nIL_5EOKyD@Qo6Qh2oBwFU)Rdj&9n25 zrdnwiz;^gJMC_eNdpb03HLind;K98OtTqez7Tvy1 zwc12&H_gm`OfwUz%OTmjV9>J<&Kk2Us{?PEY`3@rO#3d=-Vk!rzJwpkBIiAbk{^c8 zMtCUYVUeA-)}{1qGLuUkk12L?wM^=VzG}|oQg9~ow0ya@T5RuxLT35-;Tn{;*#6#E zOu|JjwtK#&Esn!tsXglLbW85)HYCe^z+BAEd#UnA;2N?vB%kI?LaGe_oJt6rDf}10 zGZfnHO1E}G7`baty7d->Lf%Of3;_}I4k8MecMyfVgD9hxcMcChYuq^$^3I_WpxiMW z1z7hTL%kKYRl_`Z$IuQZ&Po*84MK4q4?}P$+_D^TAOa)a3%rXHr^6eV-$E!p%(JVI z-7f`8>9gb`buibLTzoL0c5%`FMZ&fPFtOZ*`op5)<09$v$tFp3+EYFaLZWeF^= z<1I+1*TIJn|K*eeNVX(xkLyu5`Q~qYU#b-gzFX$Y3`WJ15(+OrFJz+Nr zc6=n{w1Xgz0HZ~_FuqK?F0gwIa0!6o$v8Ma<7^HDD>@&oFvl#sU#OAO?yYodIRGol z9}>%gaL9QLuskUo1woz^MtKbjO}q0$NlrOnUPG~4e}2NX#I(5pHtjGf<+qBTVXPMt z3z!`;A1k8HOYGVLPGH|eQhAnAk<4c)g=fMu((*AL9!_rPT>lQn78K5N5V}(M9m4q( z`oD{{DIknY{3zXWAjoasF{5T#y_0jDg7?&IpTzEy3Lbz8Wc5j|?<@c;vHN)la{Kou z1Rc9gdx_oWzVF?HK+v(8g61!(=m?1f39n*oLnVKOv2YKs|96%Y8i+~y-IW3sFr85gv^e1H* z3f7adivY_6Aq|2|5OzXvCkULBWvc{r#PEG6*_)JEg;(I2LmvD5k>rHpD4#?uM(>V? zP`De1GD3HRLdEY9ssVI>(ET`65t8Re)APkQdSO z0A;SN=X?vL{~|h+^1|AHf4j?r$cyMz(DFsKhoM~bD*Uq$2MeAnFQ|p8-Q_^!h0Q!_ z`NHP4(CQb{%BaPQ==I=N^0rtNQ2n-8wdzkkTKB$rDpAeGM;Cm5vo{=E-nEqKJ|(~E!?+ww;35pLybc* z`ey(Wm7f9D0@XhYdZ;)ieg=3Opk~zo2v+?QpzD@J{Mfikl`CnFg^Pnf0R+(RlZ)l? zf0vJA7mYE^>z$kVhx zAn2!Qrmg=ptqYo4o~Dh3;5|*Vq8txl^;~ER%YWP(7ZnHGaS`RX@JuRbqQ}P+m~ebV zIX(g=dYtrz3CBs4YUu%)Pre!Qc0N^Z8`Xndh82)923IJ2UH+vL8)_ko`z5>T(P9 zhEGT*Qp#QORqYbE9)_h~y@@o1`&A0we6e5Ue`q&)ADD2zs%MAgH%+Hs<=B|hucjk_ z^s76;NTYuTjBCT^a63RM6M+5|{gEA2dobasivA<2nU$it904S%onR!Y_rO%z@VVX& z#EvQjS@mOA|8h&Ee|3U1+`k;D)4ygx817#cgy>&)LFnpV+w6G%yMI-XI{oWiSg81U z&8-&cUsXQ&Kl|5CJJyQ*t0Mx0`&R{(aR0g-D$>7pf(iF8w{E0=y$coTUsdoD+38>M zw%VEgj?Ti1=WX^VjQxYx+ua_lGc3t&A*cU}=cR~}(?+206tk!}=@HLfJFof$IF~xL zxtglY<&#p&jBeelYC9V@6j*t4couIsp&*L6%EeN{69Aq0^m~PK@*}iVUc`P^LIv= zX%DPpGlw16GRltK5TicE|LBZXD90hk=3~*))1yXbhUBW?6Sgu(jL|ik6i(h?UllCZ zDNK4sDMv&44)0BNW#Mibq$FR{gyoIw7U3iM%7RnH|2h#8m=18R|F-7a3j@42 zNeOV}ei+io%DtX##TG{wehsm#+!OC`uiR5?y(q@UmHT3d!v$GEiU!mVLS2rs>dkRS z!j=0W$YtgJ6`07%J=YxxSMGH;+bj11Fp-seXSW_#?&T0iR_+Jki>%yxxg+Pw{VRwg zEB8w)iamvOx7aK90x){z&H-V7TaT;qgInzpVG)?{h)_W-yegMc7~;0TwSPGxh^+nX zK0e&m;<9dZrnm4?SP!>$w@~_c0;J)_?npVH^0e2Nuph1>M<^ADDmn3&9L#m4e6*G52 zWHgpZh%*9+XQmxgJR5C~y2EI9d5kK?|LE#`AYuvc{c1*xGD@nZ)mXqM=4PWio}$GI z4OJ2}zIau4Wwk@}=KhC086|$^DFy z8-*ORT#94uV%Pu=%cWRX$QI*a04$f{8g{uvBZ(}R;+l3bw1J1^Qe4Xh#=*mKDR#xT>K0eD$1#SL`1 zd;y;2Qryrfm%8w=T#8e}fkwc45^bb7WH*VK0N7}X({11e0BkhH83HI@gS|@me?Z=w zcz=a!gnD~IWI}yBu{WcUsLU02D)kQ$ytPr*Bw*I9*l1)8D8?6yJK^;SM@Iw&hlx>T zCY=It42Gz^3Enp;C1;VdsBFcTK=2&}!in=Iy$m*X-xlX|QD{~Ly|Ik)K>IoMX zZ?F7YAo6X&QIj#6Q{*`4MW)D~+g4g=7B ze_uqF4HfjbZ1`fwfBw#htQ{&SW9_gNy0Uio`*?)~L^I&BfZ&_{S{s;PlsNveO}Q{| zmp$b)P z^}7fuTdyyN&PF7$a0d`>yuqf z-U*?6-{=TN?}X;rhYVMCupk;0UJU64Os*}Cg_V-H)WX2st|z%$C{OYZkcOY+j#LtW zC;3bW!%y-GLOjWLK&a=R@{Y5cJ5`vzyaRE?1xy7EOkbjR+tZi!U@A^u+^RBtnE@4< zzHA3mY5KAe6ZKwp>>12-d~)I2P}>2#u;ZTUY9E;Zn1{irAzQFyEJgj4#ADOhJ(atQ zzC@7K$Hj0b$p7P~b3UbZ+O5Uq z^(hF$Evkt35w3UHk)s%QBhxZCT!F+y1_w2S>*upbL`i~K*d2B_rs` zD4Uzym@tzln%M_16K-a+-LavW?SjxXVXPocDx8I+xaQDzxW#CMb@o+mgcUT<2>U`q z=FsI}DmFs5sx-obP?1LXHJD0`kXb)s$L{pJL-)CQo?9qIu^7^D&vT?s&+7+axJW7p zQ6z~Fx_aL6N}2u&;)*@5f(9~O_kKIm1z;*>+N~;?E{BR_`XHE!nI64%f>OD5>@p8` zx}kWsxg{rT4-Oj*Sjk*swTFMBY{7CvEyCNnj@NPH>`NtjyG0AU;v2%-PhRVe%PKnK z_NLL*BiH1__OP$X84fgj+sRDZF0IRLCuxw{x1EeWfTT{g6-FP2$I+I<-Pbr0556;R zv_0xh;}^_^Q)b4f;5QzbiPmqeJ=u7BpsWQ*@>1g^FS3yjKyN$YOT3;PpcXTpK~%wg zW1+fHnARDj~C*-DrU<-usZae##_+zU}Y1Gk{Q3D z6BA`hVwM`eFda{ajmXQy#YO@Gd`|Npg(WnPbiZr@<@*qwZXWZf&%G_F>-}Jr-V$%~ zJRkzR7jeBkUUXpP0P(|-=Vld$iaZdp4!`?wbW=r z4Zc0l8uIRQsnLxn$Mgs)2Uk*yqa|IE_Tp&93L7ogK%4u$wf2wT zBH6Dc$2@wdE*mLGX*Ep4h)c}?r0RNunW`$$>m@z4xw=_LN( zO5zWOC@wXQF;aeQt{mwC9qD3Y+ng9Rfn{pkgoxY2JP*+%X?-iD%N1c2cwoq0N(bO8p z)aMmU^^o+Or==c}9AR%ZQZGEm2C&pXvas##zXR8oz*Su7&^*f2%Z?*8oVr5G%hHf> zo1Yco5k*bb6!%K$97?lddx)RN=7eT7u|LKZ7+oD{LXYVBk!JIV(`=Tpez;F7Qa>;s z+XN{0ef{TmmWXP7`(z0}#5nv^bRLK2PO~+J>$C|{^m0eo?$LFwS7mJLz>c=kxUK`B z`Zaf9OI|1|BvIUQFL)WGwf^E{svn z<{$>{8Ed;~L5!*`<6qltU>gr*Gg9sD0pD&v99_mNoBBr)FzJvn10_=b8O?tqWuJ7| zcpHVX+5qz%7=?J|`z}Bw&>Zn_1Dh)zu^lmsP;-pG@?evP=fLy(Ui}*vA+9-weCE5= z$c=s|6^6Kx%P+JCQNf8eNxJ1~tx!FQM{L~8+jk0GT&W=h$3a>MMyx`up+4^_;yv+dn zyv=+7aTir_`mQ7bbLoA!F-ho&) zUFH65Z@O9thTEe@o(Chlud@HuyRVA4BRbbEiCC0|Y`V(&$Gz#Q$QHA>WYbl#BbE)* ztC;|9n0^MZ?1x$lM)pHp0HgOqad*~Cw;k@zDnTN`yR#}txjSneq!^l>$B}p0=3Z1A4Su~XjzXp&t~sh62L?Hs^8_oV zQ&g2vvNLXss-Y|87BJ!S2WOp1c^;@#%0FPjm6C#ka#AVHjT*XACW4VlF+4T&`GZzq zq%J0!HT1EZSHOgKvA^U>zf{U5SZI%8R8nWJxy6mEG%S3@5lf{EU;j(lu2Nu zQd%OGNTq!0w!=zM5Qi(Jf|Ql=GOXB@!pYL-6+<^D+=S2~mpc2)7V}dH4@SApk<`Lj z#c+Mi!nwXfE>p>QQ89&0QJ@Rt+#t`2JYkFR>PjVdi1O((Bk0_bcEx%_-Em`#x)<}k>x_;#wdh>Avfa29zNBUb!wpN>h<(~< z2=G@gye7JaY6hUN5tw#hE$lJasw;JB|eF3Sw?TfEg!@iv0Czz~itEJK!UcB^$^aAk0g25+N5RO&O!2m9HuO|p%+v=`zEde&048!d zQ>t4p^4_ME3+8*9&k#sn7WR&*5qVkYXt6Z-vhV?D$;-kz(287}kZT(gHC&r;4W!b$ zNAOi*`wCL`tHh$4(7rm`;%JtuNsT+?K1UpLskIbZOQ_YO zl2)z7{=)mAHI!QYpfwsy(Ox*c>?k?Qk6mT?3sb8j(^UH&YR^#Z4LCz=HO!w>>?!P6 z9R;5>?=&<`zUQERP!igPn$ zYA}`xPZZvB5S4(5mdpALcrLJ|JhRi&xO~ga|QZ&RY zAuYZfvDD|;`q+;=^{BPfI1+#c3rB01M0Xe?{_(2lfyPebEN+M3AIs7x`vs%YUB=hY zzF^}Sz@wG?beT0+tE#HM>`^KacSdRc8JRMSS#X zjPF1yHKbIOSZJW0!CY$TRUU=ILgBx&*LalYEeMQ6u|mgE-md%MSibim@T6FU08Kgo ze|rEt6sTY6+ZZueBmZSyo)&S7?jn1f@K&0L^)kpa-F9J_1L1 zTO(S3l>Zp`D0FRA#ar%84>Ux8cPP%p{?5<9RQmyr!X7gQ&4kpO5>pH9D9Z0?1)r}) z#CR3v-5(1#+S?Yg*r=NV9YI?FiCU=w0~~&JlnQnL*c(99QnB0 z97hAR>lp`m^mX&VnoC854|^*1G6v>rpD3)yly?T2OqAi7L*4Cn0Wlds`R{>S-FpY% zcq33Jun5dgfC33Ba5MP7$k&YutOM`&fUh4LNPp5&LGmdz0xh1y8iss>nz}TurQ-S^ zE35c03Ui}(KMKb0@lKQkRApjnNbxB{d3HcMdV^$5lH>V#ON^?rTL9)os?}1yH&37) zOgE$*h;S0(G+Fw}KMib6-(_(@r6O^484yTt_)CTdLg3N9Rkd!Vfjsa`bG06m16{x~6V-an4D@#R z-m?P(!LxR%^_d%(0G_o|t)M(`IrsqW^ji`r2Vb3h|D}P)P(aD#2VNf-3OtMah}D7Z z;9HX)wJ~rX_)g@DwgnyrFKH;=9e56WZ{j5n1l|JQhy3UxftS16Wmx(|-~-@8iH|+5 z{H$fa7rxkLfW4DZ_dY}FUUwZs`5Qr6>qbbcWlL+>0M@_BpT|I3$@Ar3?7iS>OJ_Jz zN2y>_myKG=llDB`xn@cgi^B$i*0L9^%99}jhV%%N<*i$bZykn@*sDE)NN@2ShIZ8y zlX=zJ8m@cPQdL`NMbVD5B+rrIhN|9ITI07!rSg;YJPJeA%YArGn49R3Q~oM&qrES@ zgq)Wtr|G(@YP}iXB<9QEAW%U$HWJIclg+P z0pn)de)W_<06Y^`qgFQVEYdA5_ufusgVaw7LHlhEeJeG4B?*M(s=M zlGeU7F$g96AQ;Qw{*@S<<7OoF0yUEQ!}TN;5=$zE8d=YB-V2d{*@%h#4lC~erTU$ja{@feNPr`ck20u)VlVY7G^w4<$Y z(Owmma9e6kuDb&z@X=Pn-71Zegl&n1XQ50?htTj27d#3Ih&LGqKFo<#38R8*k%R(< z9ul|dOG~|v|AfaSi5sXJx_oPl`iNj$G`pXnQyzC3P{vn)Po18D^onksRsiM_JfpQ5 zE~RIK#|~7dGp-s6)&_J|F?HUJ@~Zkw;rp&o z4VTgMLBlqk{@4!GQJGIAyku%f8xLL4KUy8Ye}al;KQgp=9lEidF!O^ekW*a))hpD1 zbUi8j(9=l4joB#ePd#5i-Ht>;hK?YDw8{U_ zR2k18B>{efDlznfKw@H!RYrBZ=^u^%gw<{t6;yg%gc*W{kziVOW$W5IZr8o};Y^zN z8f%08cj;`gp+>SLPYrQ&w#Gy2IclEIBpOLqeC5_wvbKs3wKKnEdu;J{uBBKSVVT{NCOJ(!00JG@OgLCQqrM!5Kxk} z{vw%5>AfvRh1S6FptFqZWVWkD^Pm2N{A4rtZ$UKj4Nv3Kq%o%9iB(1tbP~NkLj`w8 z-Wj8s9D^g0VoC;yL_f|p$>VHOQX5c})CI1Q)EBNNX(%O0rEvK?y#iD}Y_1c851Sz4 zFS^sK>h^DHnf+o^PW&OGSv(5rLqrq*Iu>j>*1f}n!0+^=F2aLUrOr#Hn^zwbi{_gl zir?)?jJ_P0_T8_2W-tOhY(w#cT1c2DZ73Sh zcx*B71r_m;Rj{xpetiWz^e6BsCBWbIbVl;*s6ypcZTLOUK!J7Iebr*rt)rp+Q3dVQ z4t%PDc481+t`yo|RM6h#z-KCGw}`=FZ@o{&fA7w8=!gUVl5O=+d5svw`C5EkDR_^`m{lmTrVS^HS&zxmQ=x|db3zy2u!8pB zS~eW2pnVpwq%g})p*C`JZ964R?UZOZqYn1E6u@>1Go?E7BPq!qh61{p@KGc5oTJjl z>?$e}GP?*Wv#Ii!5t{2!Lqr`t-q|8GkTyJKvPe*p7J8LhPUpzSqf~32BP2x&-?>QmAcZWOHab zCxz||@TVR4ycDyeJuwTP*f|{iSwZ_N2mZH$_LOX_o$o@6F|ALqR<>{O_{K$RY5s7=!twTD)!xUGbaIB<+RWGKIxo^!?5wC7xUbUy}| zllu5LtFDxchA+v9QRCRA6Wwt7^MHRZLZQ^h3|6X<#fgm{&2ezz24sJqrC~N^m2ts= zA8^4^5-N08ix~AiV>n{5^V;SlT&Q15TXx(nqnZl+QtE`m>0!vkEJ8Rjj&Fq%Q&%xJ_?LKC9F8CKmg70mH?(7+Z->N~FSKY-Z zVM3F8#i+}+LiU+kChbQn4DB7G7HxyV@BfEFmp(D-wqnFo&DSlGB58b~FC1B%TP78e z$;tBSQlHA?l%&nTpvvrkG}qV(h6B`G3jD(%DxvYUn=1; zr0`rh@kS$S*>84`6P1FPT^KIoSI9ThW`V@yj2wwu zjI4K|aTm%q(eV7m1c^qt#Iu8_gJR776ZaW-k=6X?pz2)vwbsuiB4RUe;d_rdj#Srv zM+H_aicze~+9y+*KYsylotqhn&ogtcz)>2?v7vVfWp)1%C)Dtms(rQb5df{-A62cg zHl4La*SbW@DattgQ&0xw+PiII468Dkj4@HBlJ+zKOpr*u9e8Q_W}6d8kC;~tA4L_` zK4h4!xO=RTyasB;-D54~V~A?Y-D7RJdrT*%HQUZUwxSouf;$aIHGgFxY|JrSCM1{+ z;q^g}jnS0GsB*olf8ZP3$J4rdO;!7;#0Qw(v~Kh~ZF@v=Ts-DsisSMTM#|=yWAM8q zl2KkvFB#><^k`joqa=-bfv9#It{S6KR3=NkBe={nV0wVbCi5HKP}HjurDESa=R>$Z zP|TIWv1%mTIVT($CtR*o^;ZN*nbG!E;Xq zjtudsPsZb!^;JsTF@;aQ!!h=J!#GRS2evd|UiVF$c65=dpwMVeoK828`%j9hEC7cU`D^3%~HT_yiG^A#?6 z`pl;Z<^S%}kE@h5FT-ynMnvI~m#~duB!#mk;MP(Esh<;V-GkQvM*Paa+l4{JK{$T3 zO1mByE)_gQ+uE~HJTj5Cku4heHlnjlBfk;}zhOYjYt9%NEih7RV{xUjK1W3PNJgW@ z2Ago=8_<{KfL;?wTbITW?OngqkC0ahbp04SH#q35B*T#1@QVT%r&{AtoDsh}kOa!+ z5`T{hq=VGau+P_#7DjiVlc2 zw0t@?4PZPRkOBog9F%Uh2^{i_knnXosAkrRtAfm^dMseIq zgwX@hRq!W9Boc!RM2x{6h}s~XMm=w2ATlzU-HHPd5gAZ?QD_OLFAl=us5k}@i3FLS zf-g$(J&g9gA3SOcMDc43)qEls(nF2JdjO~w;v1oTCUtCuA{)A&P-MA$sgZSOQjDtm zBc@`d#yFI0;(OG{s-2A8yqkfJH@M4HquCr?`F=LOw~=)XG?r3hvhi3%gJTXK=J9=u ztk0madlIh3m}YziqdJAzT>Nikd;^WF-t}#bD~wNQgL%-O;j`|C=sO0U?+Tn%8$}@K zlF9)h18I);{dz1Y{L%yq>S5T7zXS!fkOfuENPLDFY$3kt+GkQnWo@i$=ef4A3hxsV zUm%+Ok&|cB$od@`lIH|te?-HXz{Fcd*2qLVM@hz82(BZO@|HYD8(EJy8mY#cw87-q zd9I6eOYR!G0%u+Ape-v02cquWz*X9Z;iQyAHh? z80s&?S})&-n+|L}-@)Z^`PlkJ|^r5vpF-h+IY-4omXf<&TCSq9+mj zC_X^c>lf`^eOu*-R9tspI-+kGQI*OOT?V<1C?dZ&B6bigt2+*Cg11J?^57h359bps z3pyU^j#tj!t_65pG@5Uv-i+zA%DVniobN~a8!fVO5M^R(I3}x9Wqsj@mRg;{BDQe- zxLl1n6o$I8zO*+*ikiRMA`=lAZgadt@3ruN!R)s8J(e@OeFf2){TPd$-SYEFcy^0V zrTmP^+3g%B$O)rj5PNpJ8**oME9OK?&u%|}jO%vHZgXMM9E|8xwtIFPjg;B5+xM9u z(a7YdTCOLu|8A+j^CsSoDL248d@RIFH=AE5_!Tp8t&z>|AZ!GQ*xT4K2QLqDyo>Hf zep4G78Kd@D>Ylc-*gtNVmou+dNeUR`7#7c|sYcd9sN_uWVPCR5+C)REWo?0|`W(FX zZ+VgEaftW@Dm7n!Wh$p}ahN+iFd^rc!_)x=0THPzFXH5)J$0l}F@POmQ^=a%f<2^@ zjcGI}j?3x*$k%*_gFG|;TRsbN$?ja2T;hKOg{QLCLw*$hspSR%^I9p5_7FWV(NL*r zM%MF?o~6ch#)%L#q`b2J0un-*rrxLvg5h-FPAve>rf8)E$m$1vCjD!*0f{1$1wI$3 zYHGc6ABNPlB}VINIf&PjRTEV=68~v?wQX5jXZ_=#hczmz>Q48g@14Yd+QWioeFeVt z?eITk>`h0KDmkt2Jz1~uv*ViU)}3~Tk-ZKPFF+}$-D+fYLuj$^{Qqr1;?7zN%_kYx zEB~h^K6QT@qtZUd2h?_mT6Grh54P9rNGy9Onl$@X+TDhh|LMqkF}b3o?fCH-opwwS z3<*oKSz&DPX}23%GvsKNK*>%;I|rK_!P+|*^>kFtC5=5iIwtB0ZolpnVV{eHQX)F) zBFAJns2%@wM{vBQ6Ia8}SbjTffeL*KFXt|4hdgD7*v_rwAry6oEqlr>le~md9ob2@ zjPa=S!H}^Fq8bSDjxY}IVx?#$P-r)BzFkerFi&9*q+Na4Tc_xk^=aFT zQ0Hy7N^{f7qRMJo%4+2o=6{P1|9FPJ!~RYg&ohO6YF~p5zW0ste6_)V{nz zQaS@FCVX`Tcr2hLgqKz@awDMKgjZC6?*qhFw`uF7z1js7dJ!-m0cjiEaQb(ExveB^ zms1n0CY2u8W#f;yal87mAv}-mAZhR0LKPYah~Kr-K69H7%>v9%`f1;poFmwYNnZ{4 ze*C8yc#j(HTKG5yjGy|`Vy!RH9^JC+<&*VPGHr_ydd<;mXayTPW+h^ky%~D^dY87< zNdE?UHSPwVZF!`jXq`|4U|#GgOzUz{JfVC?Huxgjp+d;&{0Vy{u5c=Jg#%A<1;JN$ zz}%6LHoJoMJ_lY@LHh;3+=rBQv$YDty506eUpnv_>wv)0-qTHNPv91Xv~5la>YkP3 z;14+XPN~m9z_|?~?O7XFq51G$&szM>igY$&Wh_ER&R~^fvc+WLcN?4EAbBQ{oV&(uV@)tNOH) zHm=fV0osQDv^G9_B#k5@{U8LVDD3POs`T@~8nBe6x^cTBX$q*m* z_;3S^pF7i{{jQXgRiSf^tZHSM4A3egA9E4D-A}9KcRl~~+x^v!tiD?&Pd?d^%XLL2 zALg8>;+4j?+)$A=us!#YG{OucZ6IIBj=h!Wf>h2qRO%MGX~fdX6EAS`r9Ib*$NW2j ztk8&`dDl9tHBvQ#tdAh3D5~I03_>!s84_*n#}p?%ZFpb>D5pPZBUNC7!;gvzY<2je z*fi>69iJ+KToy)IKwfCNz|8 zLoyH7P-7S5R&8$M%_5;&+mIBq4xQ`La)<72oz3Z=-0GZG;M1mcASKdz6hgJgzYR(dcr#Z=mhT!Y&J~&i-t1cMF(WkAk%qb{y56 zg`G3`*kvPLdtq0-C1QFTaa3H`jev%|usg^E ziAK1;NWET$R>j4fGo9rEF4vlkX!#oTVc2!OMtzbogkPi5XFf|Pe-rfe3+&h6HxeVF z@M}~F8!kT;+=CXn6v67}bbJ|8&}eUSydE;r4`i~a(!mG!f#Lh3^dmv1_|hK=I;+w2 z2URw=m$$(en`G1I_ywkN9miwJB^tX{<5q#ODf>aPOE6Wdx&~ir&tuTr5~F^^e`dKy z&q?0=5jGlk!Uo&SVIISS4RFa&PZU_Ce1h;%PkvKk1>2hNT5Ql~s;ua)a3@%@7==u_X@1FLRhryrN$* zW;HkYxy9Ds-j=fYuiCPFx9n}o(nlgbzWK}=j_I1j!QiS@D(vYmI}LlB!8M7qJVq=2 z-ccjIDYmz_X?^+pqjIdK2oaUl!)QII4K&QG-7f{z%P%5mKZE;%%_!Q<^1f`N12tNW zX!CJEvj!W9arCti-!Sbn8P--9Z9@_!YX-uwO=XQUXj;OWE^`xY?RvDC{v5P_V?OUi zhh;Q6J?#!c*a|6i=eWf^_-QEIZZ2=d`8!fNfX-;Nw-eN(vgQW<#FdN0vhGr8QOxMo ziJvmD+Ot4BI{6wY*T^>!oy8jYC4wy1NDAu4Y|9FYn*qyGjN7CXP39)@17qhN;xszR^f)!jzHSqAqE6i^SiV7QkZ!?wxuC6A@?)-ym?= zeIXhpqP}(VKv@CVeG~to#YuR?;;)Ohktp=c@qUaZQRz)KTX4lU*+e3*rJqAvtrUa} zyyBZ|B2JK8?u9q<72a&4AW0iSHHGtw77iFeV zqjAr~JlIlo#nVSTCN;!SaY@k0g@wk0rsSfDb)s(EK!DkGs;kC@5m28yn?1m%8h6RN zmX@a)iM^@bReUqG&t+TVSJ`+!s&?CgfG6;Aq;a_&IRAMk0ZSQ|kvN!o`9C=+Snfs> zP!4`Zy^^J1>vrqzptrcA%3lKb!t2P{X19sGKz}B>(}iZTK;D5Qzs_bHhroa1{UXl1 zy&W#mz5}0mnNxEy9mz<3)BU#M-v3KcsqWs{2zq_ZCNCR3{2OsuDS|gSXBa)JJDy(* zAm6PS)j0kfoG*7`4^tujz@Wn_J`q_#ME5lQN4IPg|mnz3q0jD8$JS2 z6AJ_Om5{5>;^m7Ydd)K^M3w#qR91ghO*N@g0q;Fwldh*GDIO{sz0U(+6*WoMK>7{0 z;d|rlh@hzx@@mEsN(aW5)lHgfMICv@Lx2aN;G10S(TG%U2@n}TCWA>4j`s$gwS?uJ zU^kn>@`P`F;dmR8gsUPPf4Q2wxnsn~d$|0<@dlvsef!U7eO~^fHQvQ9 z^Ocux{3j?{U2cj|HH4c9i(jnW@+p3n!FvTBu|~Z|B&nR!2iYWL1b9@X?7av5aV~a+ z$85uvvXw??2!I9nkK5s?jd_caII9-+9*`ABW$(fF%_UUmYJ`5<8>8yHjhnST^3-e< zRwj!tJ(>L&`)!Q9N$(D&*pk)pDwJp+9*BzlkAkzeePfJ#fI*hUS)h6NZ?Zfxs)TbP z*<{(;#mo{l1Z0`$4w7$nACK(#qyGLbeSSvSW;pon=DqS|()IS|N8I60-YM zA$z_Na_?V4_BNhJV`sYx`S}VVzbqE=Yk3)EzpWGBg?ohj{#U2u0~5Z zd&I)L_h-0KE&B%)_7n8RoAQesf3}=YM<_N3u#89cBRkUxc_L=z+g$Xv~;SL6^HN}QHQ!D=i*ydxoHv-hT%ePnJMJf6+$*{5whtXA-BCI*75^`TxArFica^OlK2iFKWbhnVhj|qA3O(74R5pv{TArCiONMnz57V_vQAxEzg z^4J<7j~^9s>SW>`a{Ue z)yiq*l~f_G<_URifRNWG3VGuikU?##7`F0rM1$!W)F#X>33AffH#B;{FvKZdToBSWxD?&0#gv{O~rQ^>=Q33=pwA&>qc-61T@MTC_M(vP9}4MlUP#ZV8yK!vf{_00gbbJn5?}X?pc>rwW%Eckg-cX2 z;2Y8ajw&cc7gBPikkQu(DZN$5nB79g zJ}hM13qrR3YnZLWJ+t2!ofX+OdKX;-ee&w<_WoTm5@W*ggm!j z$oo$T`Tk9iL50frTxd<>SD_h3m6gQvjRr#d8Eu7*F?tD|ZHy3FZp;>XmvN)eBgXAQ zUo`d#{n&U+=ugHgLNl#Tgl1Xa2yJ5hDzvHPTgCXAS#d&}TNy%ISnY(iwE75bZH*Gz z#+oLyt+haCJ8PxTJZr1aeCq+B9jqsXcC=0k?PPr~w2Nh~W_*`ewS;!H(u8)m+6e7o z^%UCE8ZNZAHAQG2>uRBWt($}vSa%5RXYCW(-+El=K$uR-)(1kzSU(FLYelW4y>V8u&kFZ?t@A?XSkdbk-(0J% z(0Nw2(D_z-q1RXiLKj#iLKj&xgqB<7LKj;)ol*&gcC2#j_Z6^W%VYBYH?rZ3S&y1@C=F)HUS2Z?!&{smGjy za_F9Wv4f-~ehFiiF%76~gBRDzj-?TohE6&f*V!5jXi^y`#j)aSgZ~jvxD|Y->!}U+Qf~s_V-uK_(E8jy# z;BEMR(t9f;WDa0%TPZzM z0X_|w+g3^+t6*fn2yA#I{A>mIC}8dsDSg%c!lH{cW28QaSo)T6&Xolond6bZ(w(7o z(BLPq()ZjNA7>v!C&WMQ5GSQ}-+_!9 zMoQy6m92%k6xp&A&xaBdQ*KI3p?#3?uvh6s&qMv3Ix<=PD#+7cJaSfgPpDn7tv21Q zrcLaDjN3Fyukid4G4Z8jgh$$Vg01x4P|p%uZLTNM{v;+-bVJ_Jwn78*IW%OuFMKO@ zc%+OQ*-EE`3QBFY47b{^R7*eV$lBvW5__1byF}+Pc9@Z7<+#Ou=ru=S{6z|4IW&5# zK6P2@vnp9op)-!Gs#``i6`DQH4wr4|<{_!l1$Ww!b#jMe+3N~OpD|t^TP+=fJuwoH zgM>=|5IDDvluom873w)bp9U_y(z<#83s3hXp80qeM>0yMh8~2*$)jKwSa(D;I-Uj; z%9yCnh?cH)r$nc6gCpBxMMed?^_Y|N8PU?m?cBLq)-1?)Mzr+I#WufkWFGHDHj5|g zbD*VlysnbgX?equWnCPu*A#sYw6v#vM$}c(k2$jO_8HMgI^~O$99!f^McJ!y(P>51 zu@T1U*elUM3+LU1TU>aZ(Ra8|3I!eBv6{IlO{q&JVn4OBDS6m|F}O$NyEuLc8+L^J z_i?htCEA;ZedR{_=+p*-P@ni(^*Cr@i%7yVJ`2F#4X{Vw;%H7QyGVH*HNnP57D zDZcQdj*PB_{{-BmTl5)hnw*vtuaw6)g<)}YQQv_z)Mf~Z)_}PiOvwSN72n1n_Mh0o zO}a(Lp>r1nquxb)otYBcq+2w9a1HexQ_>m?KBlM=j|X?p-VUyuI=D%<=)*xZ)cw@C z1uG02OOIHzBh3y2~oLh7p(mWRN zc`!YwG4_ZnWuhlH=Z>jd=%Y{7ElNRbQs!d@S28~OYfn+}uo|j_wx0$w8O)eJT&AVs zKJ*l2LFi>dSA&TGqb`an;iEc5zd@>_a_2*geB>!%7WCh!bH8HHVsShWSFLFK@EYnL z07XS$q7ZwjXC&_D1vBasz}u+zn-yP_3GtTz)Ts85y+-)FW7L=v_^{YaNyGJMf~&`THMZl`5S1Nl-nC|Ae9OvikTR%6ecM z8qcvu4{U|PtHO7&J0t%aeCdC|dw(m8TzU(KY}XjZpS1wa(NHz@MlHmbq^xOX`V6Sc z=8qY8X7ALA z*!lqR_@4Q-_SsrbxU^oB(&*C;Dz&BecHqW@+XAGEZ?#5+;!Ax8--HoRYqH3v zCVJstJ zP{G`I-1QC7Ba*Q^o{~S zMYr2Ppi(wl?G*Z04F8eUrdBk}#%3)rTYrXpIy)2J#zW#g*fT$7)cV13(!sta7JB+Y zU8Grut?wmf(eE(^MnZ)T*|KA9**wb9KZZ;mPCsI$C1Duc-lxa1X~cTK@M^6?46#`c zr+!}oZ|kyB-2Z3BH8~uk_su0KSL+tmmHyYX)iS6v1P0 z-#PM^o(Ts^lRb*BB)&=ub;a|BcuX+zk7s6e5uzoiWa11D7{Evgn;s*>y48=zUyX90{&}3|c$_Jqr&!d#C*C zW6+Q{LCxMN&)Y4Xo$|a_$2kIh&IxkDs2IfTf)FZW&SSXs2s`$9!H<{|Exl9zU&!p8 z^7&&C-4+gl;lnVz;HUg?{5l18%j1HdkC-6Q$YlIHS(1_aB!-YDuo3bHL(X<{B-gR< zIKRqhgnN%hKMnb*i2OhAKZ*qUkNb~)T7cr2l4`X28jO9{4oc17bRKY9!nocVlm8z0 z958izkaxA7!AFg$cc>^{spF>;pMpK}a$Wi2y10kDPV?mPpelJfTqAi7T<*3%`WJi+ zTBN?1fb_@Z{~lDi>v7m=4Bz(aTWRVX1-Ojhc$3%Ch@+sBw#JjQ z!Bp|~_%oxdM! zAJ1oKRc56pSQTX5v8g3>3VsBZJNJ{iU-Z>e_`N%wOsbhwQ2BR2#+I41jDDRueWL(N0EP1V zzd_ZxVY8{c$!8)|8sutB19p- zo*83T#4{6^)qAM;8dw!{`aCM)exPa{uT*fOk@CF`)XIj!(i=-sBh^}C269L zL6TC3(ddfU204caR)ol?W>-WSGUcuarcQ;MVz(ja{2Tz1Zi#eoZ9@itZd;zx13=R1 zi2OeXfJmT=27qX94lXQUr`(f@$m15^S_ZpQrXihjQ+u7G0PRjWX%=$^M@{(+sH;=v z@5Rq;L^@?Tysl39IJ~Y-c^+POr$k&F^BQp>8{~}<{MOQ-LvS2eUiaUiWAGKEj~%B$ zezdm#0He;FOw%RBVIJ!R0{t#i2o7a9Nxowb!5v+Ikxd z4b1+M7R>(dNQBNl4@~KUMs@mN=7i5J1=~aJtbTI@s;LQu0Eppcj8g}k(1Io6E+~ry`aoEY- zZ8kCK;ci2pxkVtS+lWH`B!t)F*I$#_ZFW=9KLugKr=rkpoU>9GzixK|ls18u9UxZ% z96(sR+Z+XJcbhK}K#yNK21$ym+tfnBoo*vCs@dJ98)WWo!_=v8Y2jVeKU+O2Dimur zdj`k*d5kMm(^Q^@ufZ3pkA=i66p`vI-bS|9oI@;h8Y;Y0D3oLVBpF#uIQxT^x}-z( za2+tjT(O2)nYE@euUh3xsIXo_NoHsz#JpB0lxyCE@OFfu6As+T!AUzw3^$ICYAjYQp0`|N;E@Hg7UWZ&=8kttrz+evNkBK z&~V#6Gh@p-1HXjfiY^X!HDqfBK~{QkxWkY=gcoF?@lvRE0fmp)WwuUN>Kt@b$6h!- z*VMal1Ln6*ZSe?OrP?}zB)MvfUh^?xp+ua8vukVXWh~H_2xs4n$qM@gYikWu?Am(D zrLqw!PHp`N6}z_HL3krkA`D%+)`mNo{QVIP+qJa^GP}0iL450MxbMY5#zAJ+RwS+F zfN4zd4x}brThOy>D`Hyfg_76fRUJwWwWX89{Mxc>AhT=hqHym)X4lq5;o73~?b>3Y z+GQ9%UMQc_q_(2Hf8i~f(X>N{4?uZ4Q_~*CWnY1R2tBN6&-$00b@;w=@&0AMIsSe; z+Avpo=#wKbTP$dPLT{gcMQ@*fLvNpdSMQtuOz)fjTyL2FLT{M=O7Eion)~MC3h|>o zwejElZJIHsISzIc|9NXU_WHE3>>a;ez2i5jG0)8uBsKZFB}ljX_4dpM^!CjCdVA&p zy*=|Fw`Wdkj-8SxZ@{+u);+=HT8+=(A?ccaT*~+H;c=8cbD%)ZI4TPHy)hu@akSfX zmhC7i_6Mti&RI>2qs|FVjH6dN0ZOlo1SppP{L*NTqopuokE7cWK#!w321$x*9DNOP zXB-t7)$DOpAye*gl&RD2kYygI=ksk=;@xdj{p5x>$6!9+1g?>s2iKF_1Fo4o7_OB( z8m>2a8eD(!)#Ba&H#&J8Twn5bxKYUm;RceQf?Fl|9k^AKzlK{a`8T-1WFO**Nv;Do zHaVTH{ewW!W0HS{S0(=q*GTrRV$@aPTFEux`jYFyjY@6+H;|kGw`y_@+@SJ*hTQl$ z%lGqA)Urn~*^Cm7P87dkh_viY3aB@oP8l8VX3P{kM%fP(6=8KUolY6AVfFJ8%rZY_ zYEk6;j-3!1WQ>Ig^2z4FWE)bI;D#S%9fWrL_DmP=s3KZag%RfABf z_5(7ZIx9af)SPh)? zNiV;Xm+^8|KY#S1j9A%O3h13q$Isuvm`jUOees;XOGB7@l_GLwZ_@iQy%L6({gpArWj_ihZVFY8J{n+#WJ;bxGs5k%(!EgMIUn$ty{j-T_TvTG>dbk2VrIl<`o8KP`0^S+e= za?{1see_Dqjqr%|^Wj(a6fr4yt{(ia(<=fx(`8uTVe>L_Wj|6%?{qqTz9;kZ%yOBi z@Hl;0joDBk=chAWIDRWF%cg+bbn(*h^AN4S8wJ9hrYU;;!->%w#bG3h$1-{2OI^VBmBC@ZiaOrPgf07R@u4k8f5}evA3r zI)<9{8a$_QhPLtk#n7EqC#R+=e;M8bJYIW65xm#a`-2xhZ+gX3@UEfvd-47W?`C?x z6K|{LHPzkpek)$11*DgIu_<&5OpPhcGSqH6aZF<4ALEKv!N6s})$HT81XZoBm<&Vv zY3MgGbUVC{(tBRKufY2Zy%*?Jv!jmb9OokFl|Aucw{eWY7%K=yjznr+VyGGhgB4$g z%*WdyB{{W>V9`1#ZGfQYSuk74`~l`3F!(E;kCb+H2dQTy6g6pCQ(ea_j9&xyLpvMd zQMT^*>yVlh$3wNowkLe78GQ^f#J9y^$*Y>>)#(6_Z#8N)wwKH;^#n6mb`|QBXvaCh zdEgcK9#y=tv6lo|_xQSz_VMsNjM>L=ly4B>!5)qR z<_X&LzYKStZv^q-F8u1NeU}rnf0k6XIC-uD(xR5wWeOWMO^fTR~y+MM>jiE_R5?Go!9jxMnQ1r+9RkG;eDMa%JDC=lS`YV^*HANK8u(P^w1U~e~J|h=Q`W~btq*EKN zQq}x%!p|9|?11nbr|(LBvDRt4ADr?oF2}a0s0F<-WO`nt#sg9~k_&3+g7v&X(IGa= zNMJ4Uy-!hWq+pcq6p`IJ{qgeb_*s=#+U4V`M&G5biNCKVk&$Ml^?)xyf*G3Tm<)hzpj8bOm=1myg*Bn=`axOzMkG}hL)^BO?;ezBZbySBr|eq39)jF=Jc67C zto&cW4dNx0`W!z~+s^Cz79{tahmGEpb}bz{I3KzT7{d266+YJ{Si`2+@%>Kt4?VU> zLy;gph4Zbs9W+cuJ00T*chfKxrETE{eSN@VC@a56=DUGuKj}*Q!Z>PvB#1ACd~ZWW z!Eom_pOtjK2-nY(!oGBBWoWI6y;iIGno%KDU-)WX!vcze8zq6;QZ~>PxG6-sf9QBx z!ta;S;T%iji;D`W3oU#bftBx7BK>q`B|(w_79dKa4}^oMuv{xhxoVkj6mgF!H5sW+ z-#EgBl?u;%nK=o*3wIync`4;ai_S{j4nFHBoM#y5@P7vKy+YZz|4N{?n)NOePEqM- zr9^7E?;FZWTrx>a);Yj`QS@+Sk&MjH|xR@p)((MP55BNlwkiC&_sxMJ;?DGL$Xf;71PEI3hB(Cs{V)c-ha zMR~dqm{2h?J%oCCQzUctNSbZYK#Gd~E0k{pMZ;WWa{!UM+u%b?5wqYKN7ZBD#OOlt zO(i`j^eaA?%KR9cB9s zdE``*c~(-kToNdSD{^|3?-q)>>2Ao@t$cS7!96M9E0>pVCuKgPQsT6wy_8kaGEtD~ z)w08s#kgeB(6np<+h*TL+eBA+4C>D^$TBzVd7048h;4c7dEO%Wd<12*%JU)7`y!~; z{ha7q5mf7bOZ4vu>Pp->ipmXn5QR%s`TivQuzm)HVY?zs-azq$AQ25e=)`kgvw6{)&N@-tUulR2sST!J;78UC-y*CH^?e^7OX!rmq+b4tau3C)-}wYshvG_C~TDgV(?UexOTr$d**q0qbuSTnjXv zXk$rL8qqev-9XzCZ6e8OO*A+7IMAL%n@V!J6U__01#}qE2@=~-qP?=e1^Uh1mhx0F z1pXSl|COMzM5(Ky@!C2*$X7G7!TLkNIG|4<_Z<_0exOf)^=AZ|0PTyTa~C_Q&dbogN^Pkm=M`$Z=X?n54r)hAZ0}R6)3BS`A$cc0iTpSP zhhCS-C{9|OjHs@1&Zc^5$#i(bO$j2EI6r=jFnCarkyPkTO)JJyG1g*SM8$=c;tDFp zTZ)-fjI$JTshD6X>Zq7#DQ>4?lBHNh#bitIAQcx`ipQw9%u+l{#Z*i2G8I<`3K=C$ zz9Cngn8;~00}qg$lBpV=lhYAmJBTOcr^A=j2<=hdDZ}nKSp3R?ckWQHI-XmB3ZbWl;6$#CW@0 zO*9dWN?VD4&$H7s*JNK?srOb>xQ~9`R4YM$*dnW0Lr!keoU&9yn8(q5;u$II(Y21pl4b>y}XV(mg z4+o(;Nv~RA0|PnLv+yv(3EAr8gj{tVgqT>Gb1}3}Ks-fj*HgRvD(5-;&+p4UL?SO! zJVS3`-$QuG7=Oc?~!)BlmSPrDzcr5xuW=1Xg}hZ z6z<1_E~d4pK#|>4OtBPusVI{Sl?vf!tsWR>#!61i#?n+)*6$$Fvr`+YECpTpY{+>@ zC7vgtNNkL^!oPe+=hal;ddQOC9w#|B;BXc0%$=5$fyR{(6Yoam;@=r%4|?1vC6)6y zj*E!&O*{kfYDXK2+(n&Up^_GsObv(s-(a-V{~UkGO1NeKejA})Qr7}pnnGkHq4w;$ zbf@O`7Ao=pp-uwHL4xW~>j?D>ATh0>pHWfzUoFMpH!T(UliJxrV~f`fJQBfDWdC{T z+AM1I#X7JM&!;wD&lCa^@nWiPa3nq&Qt^Y|hvuq)i03EBxh9+>lQZoI%?YQ#K!+2W zy1!8IV+a)nQJ6mRc&hvBv;--S^rd=%)F@wT;^9=@Lk;|w!%2HfO#nF~x1{K|XMO25oj@o6uRz)tN;#f6Z?qKC$T-1L?4_b#pva-P4$47w zIh^l5OL0-;Wzq%)w8(3skQD(QRAj3tWcta2ihMxDAS=ixqOgK|DGDpd_f!nFg6tE8 z7342bSV8awSv7Ep6(lJND@cwgtRRi4*ysl_W!YS`ez+(l6**M2e&8r26?yUzSlH!T zP?0XA?eYVw$dRJ(!>LGjDn7S@^b&;?q>m`9Ag57rwH4$nQCL9+iNXp}LB+*Zkl~`R zf}AgkAV_>X6@B#LPY^JEkyiU5b$-Mz*J?k!&XD-kRG*ntxhu%`5)B_{LC>GX1!?BOhld) zZJLGnOVpXu<784^k>qK`X`+zii6VX$6^8_MQpL-)Ch#dfQfn-y##0jwLYdYz zMXUXwreV$0YCpVbQ}d~gSw_T(_)@J7jA->eTAgm>ON^uj=2=E`9*MfSh)LCo0}lYy4PoCzP6lf>7qB^H*B!M`+YPYPBEUsQ;w8v1LSt3h@Z;YC#Ww_d-5vH8s z4x$qi?n2o1#X075rW2W;+O`Ggp;%E=6ZZi9fTyjwJX3Qb4qqB;H5EAdEr=y=xlY{@ zsGZvJh+!FH=`67{Z&aYZqMgostO&8(sD9vS*G28|(8~y*63gL?Wl}F==`@^N>-+<7 z^jVpTUwgXN>C(7BjmH_EKf2bb!P#Zzta|GAcw)~4Wm3wHZ0x>@z_XyQ7?1`Y+%}q5 zSq-JT1e6OP-~pN?_*WLTP`QH8q#C1bgOiDy5$o4I@)5yf7ZLrqF76bd9o*gCg zNt0(C45fydv&5XBWY!q5FVs%$!^p4qm}kdHp8X9|`)KO8ZYT@MvktjPU@z`vGx5a2 z0`)J^<4LaBheN#=OJ5Ln1+l0*bjkdTRWqlyQBjVnz+c(vkK@U?3A16R-;1a_r}HiT znNIY^dC}2myJctmI1E{`4eoa~;gg7??95Cz(WF3q27Sf)G_dVek*4k&F!%xhrDi$v z2ICWTDD32Kc%!MT;%``-*b|{=euW6mV!~%RRp88a{_Px7WoI)*)s6Pz)0HMlR`s&8 z8@c}=(4o+~y^FB%2!(af^n_4(3J$XKju(c`7PpKPy5m66JMUD1bGb2T;7s>An7WXr z>LFZ8Q!{Wt0v^S`S2RiHLNFZ=S?U~wul&pid`N*#DF{%x=W56X5Q0{kcR z)$gQ%gCA|;UJh`l4jcbjsc-Jog~el8S+VQ1#EvM?tLm0G?lowhpn2}CEeccz=-t;L z97&q0=6)<&ObUco9&sjhHdu@eS=_>6efe zD^rMp%CsE}sZ0gU)AQG+N@Y3;6sb&CKnUk?#X=;auZg`Gk|TNWFnB8@b>+M9Zw>rK zK4!WD4nXEZQNA9BozP-;&Zcg2XkUiH{Sv|6gg`Tmf5L-SF$4u$5J4%b}G7e+MnAzZ60t^bRCWJP3-$sgNh<{RO<7^m(c4+JLLJKiaXjNcHq1_B2yg8Fil|tJB ziWFMx;QbcbBojL?8}HrsA`P)R%Y7DQIvx6ovn^2ig>_D5CHD!d9F0SD*L3*9i2EbL>Mg!xqqsSC z?SB-zo|PSFHi|nKLabary$wMsc@V-g}KUeRMzrS8(#f!4UW<<$Ow5mj&8 zP%Nuy)(_*IwXpv5-8|)ZXSTBp&rg?)AT)7kn*wz!Pe(52sB}F}Pi+k!&s&M{RP`UY zy0$TvrMyQR;#M76pfWM^s=g`>ta>cr9tLn8^cBO>z|1ehh>;~a_FjNJ%BHU$1auj$M0G7Q7?|>kC5msMWAU-D@GT0nEt>`w zp|EAsz=Kh6jX|&Arh!ZCEa2vWyTA`N51d9b+&r+hz1ci4AA)QixCKIZ^T4}o*ZMdu z+#QJ0Y#ykFUVzxvz+Bmw2JWqJ^-5N;&mqi)P`L;Psb~FdBL%2u?Yo$ICYv1YWP%z+ z4s|y{E$OUS^(!i`$&)JPNh4IhPrDYVCjhuhA#8+DS&u`-dFfp4m^lEHspK|oiW+YdfVy7j-Nx3ZrSm(0|cpLvg2o8n}!`f7Xp=5_6h`P zWwMjzBr6i`r1>h6AUkPxJ<8fi(_=}k#!i}bU`g{)UQJLCWb@rL~YC)%DP(Q)+2@oSXZOn3e;l|%GrF%G;Rv{%LdfR)m!?lT?Q}cKqnwY7tcTZnK?R2zfR62`$?7*4PxH}xCr7Sx`&|M~bx79W;E84^z z20KCTwl)mM-Nk^Vcs4`Oy&HSp4K}YqG+rt7;cswsugluC$>!u>VEu}hq`uv~B+=Fu z!;@iEE_e?D7JE}51onQjc?HoN_aDz*R!?J3Z*IEPj`+t&p8FZ>NdF|4&mA`WQ>2NT z>S3}{cBNgz68{O^?R==&_9~^_^~0Ip?!Gi8{C4*qP>%H~gEpsD>F!(HVw;nVSCd97 z)&J*6iQ5xt*J%d3JmBO}vY1+66N1Cywstf9RKBbNJ*^J3xk zvY8zV+IucgNosEhI;m{YEo>SF&zAu8_QxH{sp~jcFB_9^C!AzWf|fH%E_mDxtv?B> zrxr8U9Z>pBcC>xHL6hy%$8NIc*wLeP!WK(4llsef=f=-7Jp1I00NNW>&9(o&Q!IizNWe^*btT+{@zYOA`Qc;j4g#i6g zSO|pEJH3L_)Ai1Fp1|p~2pe`f#DLRZfgw&GaD2McHdUNH3ly38&4jQYr%ThEejGG^ z?Z*bi>Fdm}&x0XO{|X^o(l%9`Zg-+_ zdMJebINdwV>6<|Fowh-7dJ|CJX%F?B{s*96(jgE|m-Y@h-9OFg^8tsQ4l&^Laxlc{ zcOitGwyENDCYqs?^l=dO~x3$r)Ps9PCo-7?6gf4r+)xNoId1~{W`rh&FR6Q`6X?G;`CggzSAD+IsF1a z-{}wtr+))zIlVK@>BCMCK>s)Bi%)Pf71ebNcXpmeV#U zPLBraJME#K)3*ckoeqI;dMiN7>Ah)AXPuVrbcg|`dx0TNUj!lSv`rPK?*&Di{usi3 zoc`Iw&aonU?}F1Ur)^N2J{hR*w1;|5Uk=cBIt0S$hXGnnE4*vLpLfaH4LDrALku|G z^bF&4e+XfxZK^mu9TahTJ%lu;r(nF$(8Qji(-R!*5Pu!C71e1FKKRoF*f?VSER0D{ zeHkrqzlQm90pM3N8jChP%vHQ*Ax%_|T&$uJpE)A4V(VotD>)!B$U;gM5&E|#$- zb16$+u9$Gzd1fhV5^wuXxCy5p?#7L^Nqp3G!Zw`BeYQ!w6FK34^D&9&gS&7#Yz^=Y2a_QW5>Mzb)>xh=mM7p;LeHnMnk$hx$$K*(;&+YH%ZM({oZ9#+_|z@_ z%9fBjVI_h}G3wK=ae4sLxa1L{T`nw8hsY@(gPwRXP9>h3C7xl>jS1peZp57uPkY3% zdJZftmmA3UA*d{lneKBF%o5SIiPjQPIhTm?Mj$AchDL)UOGB4}6J8n`%B7)RBw|S@7d%-K zDgiHTNoekPvn0gHZ{z!Pq4LO&sdSlarsFjbf~A#|O~ca4t8hW4zW+dwsqauOA&o=y z{FusO1eT?v^DeTMj%3=poGIjz(TCv3lF=jJ$keqJ1b^z<#>D7PUH=BknU>r6VtdJ` zx8ZTpQLLAYI0r1Vf^(5)$)#p0_zwhG)#RklW6}F!O!`Iulu6&K5Q6!sYkAL^W0%WJ z)sXusRUy=ypTeRn^6Uy%icGf+vR@W?${|>bJk?x~EVaBTyF1Gr0bg0$^m-(#i^q`b zC07;?M^d@67%V7;D6BRAUZQJF+B#y0hf1>rG*%jG`EUtTvV6!qwfW4`5ddX+-35Zb zQf#w|F+*Mg7rYs=&XOL+NpXSeUjKk1S@J3bD@$rFMZwgY3`Dmx%>?X?%ynufp*whv z-Ohd7qG>`63Z>tR=qc~>x&w908R%B;?^J*<4MlONN7XA^o#k!@Gau*fVhGJ4=#)3{3Qu`4T(8uGZOTQBa(#^=`K6Q%?;d+mm@==mlYTrEN+<5#QhQm^y>9c`5e?pc=KwB8<}dp26Zn&`(K0F zYnhg>K}`Z0+#dNk3}?F4up(cBs)G>RXfbLKN~fsABNaz6RBLn)NlP*4UJmKOWhE-33tA z6SqSMIw^0WDVS=%GaS3 zDAJ)l0h7|9O@iQeXuXVSze9TqeCg0))9ntezs(Cev?@!@##f6#()iwi;CE;qi@CuL zts6k;(C&l~bZ9lkn9$InC1=MCJGaP`V$2Y zm3Xntb2mVLq7VWxQP|-nN-y)wvQvd+p8RXlCki13CJKGPklE1`2;qr>O_hnlgP_Pn z;WG$n69q2otqnUpJbGhtneVg>(rH0`r#;kjy5CI8=@1B~n*h|^i!A7ENOO7`;PC7y z#DLR}f+0@tfe?1uri#*I1T-%Q+ovZ zznSa^#S&fyGx~DfkPZmjZCtLYPh(mx65@#fO7d zf)ttFedsE%6vpIb>oVQbp?{d?GLUSB&8+#8ggu_`E&%FZEo@K*k}vr-tDl02)h4ja zvo|zzkGl>}K|t?Lfbb@TRS-Uu$XN60ZT_KaL6OFI7ld%Vl!a#QV9uXpA+qG%8>}p`LCKO8K>fz(p01jtKh=DA*5DaOmcR~nfiA|L(c?T59lH`s5$r3(@@ugKD zWiRHt?;+>>DrtjKC9^!oRLxqf6|^ydrO|KkPPmG&%R3?MXYYhaZ{zOuPRuD=Gsoe_ zvdY%5(K}5)#sEiu?TVAd{)V{?CFaz=iYLmsm0Q{C(j#<-JBN+n#WPz!sG90TyU>T0xzt9ZFMnDLEoO2#I zbmKrkG923u8~YoMk%;6k04&3?(;=h{$4*A#_;F7DY8D|?<4gik_MP!9IsUrg&#A4$ zg+a>xZCNPz0g+4Dzb$3odXXu6K_{M%Qz`qcQuce$A)aQevBb*W$#ZW56 z?HVKIVYS4m-GFF6lM2RkDx%9)?=b z6Xy4_7JM9cF9NeK&a2lC!ec#N6v%>_84>~Ub!0otKY@pFB2;ZvuJb^_g;{88`2N> zkN8`c;fNiB_!DDy!`Q`$zZ3xCKMwz@|0dUv#8yoccQrWKnvuYmQPgr9fv+;^aT3JO(m1h5t+*&Uz&+{SHsE7~MO zp8?@i2=bd$Wq6%&I&nInWPP40+sOe=^)IkiV{qxeK1sSif|42x?;eBD3PSZD*qUTz z(ulnc-N8!>)G$VNFoZD><~o;1l-1YZ-{pqQd@uVX#{ruyc}A&9#4dp*JF8lyPjGMO^$)mzYcG-yywuw0T^6|>qBUBcRu2_h9)~~ z7}w#?5jcDu4l!^YK46)-4iAD5z7E?|xei|kid=_ZfDj&<$kW?9P3+B(iINAufVV;h zPVykII^R49ym-0wAaG}Byd>NWtzT$+p_K&BzSAnS78jU8>kqA8X#J^0p%p>t7usl( z5~hcR_7SWHg*GXKHh0GYwF+&T4WrPWhvjggg%~KbKf#c}Q|XHILbIt-Xrn-pLR$`D zKZQ2K#GXRZnFqsTHzr%9mRZF%4IcCPZJF8aV@|HeVGXn_Hqo-!hDT@QEwhVlrw*5J z-$u;3*lu*3veQg0k%^U8W#q(53NB(BOsZUTEl%y{xRU(MtI2M;b~d;Rmp*)M!JM9j zQ-0P|pWDdz= zhaX#zY>uKT_cMYDkud~W46dwBhDT5HoP;b;a{1W{!g9pwO(mD0E5lDN+7vEBS8~Nh zo}8NRB)C>1U+508f;E`mjGydhxd!w0DzgT&41&J^YO}Zi8UYwAfb!X8Ztlz1KUQW_w5PPpAC7a z#DoSt0ifTYLm(RT-2kOQ>nUIxJC$g%I{=59Y>0s-n}3gKvV9s8uOQly@luXzy~d_ZB)E&0Mz%|Lp`tGeZcZM1j6e(09sz>;SELpcnQTjS7`Zp z%feoV7(cMb$Xg~I)iR_Z?6pm$*TNOA-vT%6wW|IM&9Z}WTdv?=Hg-Qj?tI4!eD(3z z$-I|A`y+8>U*@^@+*_dfL+>7ZAMPSTsQ4XRn{`+c)vFS;1Zh7)$cHe=HHJ8dsVai@ zKwI0I+A^3t4BGNH(I53f?=k8ur-7SsKi*5|iPkX+&^TxhTaf3z3F=s!SKSWbQV9B2 z{UpRCCMM=;*;hT>sW7k^de>cDpte%@1)7f`RC8N*o8DmpS_VMb)x9m~va9yB)j?d=AXL5kd|GHM9iBIW2*GX2 zd5D^;``0{TZc~;3_OBCio3fs%<88_T;P4vZet~q#s(y25c%`_>;X507V?hiq5qFss zu)gsUarRnsiTE0!{AGHNC53@y`UAj{W%~7C1rM9vV~j~>09*P1Xbz>;hB(?G-ZLCSC%)6Hx3xOMw2!wtk)hTVbxUuCE+1PNsr2WNj}_|~Jk z4CUrLd>~_OhklV{i3Ua&NE^p-a@sF9@&W7M$kZl$( z$QJ<&UywIgcBFC4LZ$_cgB!Q-XWCAtyAuA&1^ImlLE}(zLEdTDtO9aDz8~@VE4DT& zm!_RS{Y#UFN=&#Q7p}K1O(77Mrc(i0m!@y*RN{hsCE)O-Da619c`X=nY5EF6_|jxk z<$~PoadSaF3qttPBwqK&Ln{3FUSIv9<+Y89*QW#Zz4lPg>l8qL7!m^E^=BJBuMwME z6!#j(W%`TuFas$JE{fdxhQD+0SN1)gDSg6R6mNszUleVYTonI-5xFRy51L#QTNp!~ zVW{dcz;aRaw5_SF2iLzS)}yYnr%sVYmqIrDH!Q+y@YMEzT=1#-Y3vhtA`X{ChHz z?oWV@BXkN5Rikh=5Q5y{nPa7{_>5RHH};&VJ{8P?d12Vx>y*43N9$+ClI~j@yiq;` z=~TE1yU-4aTd3VUyVZQKguCnT$0P5$1PPsS`i=elxjTJWfvR@tdJ-~iX_m>4qn{W7n)#g1^ zatJ-$@c{ic9|F+K@at^r1?u$mV`iLNq>Mk zOHlBP_!2u=zdFOC^Lqt%sBMrD3+ng39_mFr-Htc}BI5Oa#BwKaMp{{X3piXBAqL9g zpqEWq41y3Y3!5rsaUCd97SBQmmxYY9y{=!z;9hMNq@hWdoOnLS$t;6liDjNgLj84W zkHW}&8b{~9%jo<^L@Cb~{?6xjCjP#uKpoK=FKPcFYq>9>jVv|6x!70sN1@vflsDOk z=0o^^!bS*RKu~h)ccbBReWL8ITz9}L=GN~u5aibH;}G<%U#`FGFnp;?f3|VI0V+c| zc{`OOagQM#2uE`>Up1q-dZ2RaDnyY%IVduq3%^ww;$ckJ0yG)Z1uv6+v)OtY%;s~X z`#3UTO{m7>vF67UVADq*Okxb_@W8gR9|AnKiURX(@b7g}*lVb82U! zq_(rP{*@;U9!GMAG(_?ID^FW}gVUk@X$5bQCQWb}DN{~Mcl{Qm1%PyQHY)c>uK}tX zn1s#?hc0vvv_spdgdX6B#@16NXa`C6=ScJ6+&?MmFyVv022&Cqb(r$O2fSuduFoa% zZg%7uPGk2hko=_Es6;*ks7X4Xqv#P1-O+svxPFqXtjb^;P)D8G9!S@9Ok2WX6BxV) zM3+;}grsc&rlgycY^juVe#3361z1>YBReQ%N`N6hyiuTP7$D2ph?T|)j!dSRD5Mr= zI;i%qTbosQs1!ekDzjli>d`<5emx4&P>-GgXof7D-OjLF#E_-XZH_pC$K7Uy;Y{~i zz%rsa2zG+U-IV0^9E%M{j&q*?+s|zqmE67-sLt(jHrjeznalFw=GuDQTHVH5?K{&< z?o%cPX|{Y)_#bd3x$>m2nt+QtZ&-iywtd6;OB1RJ^+={}Yu?h0-MtCCjcD+}GoT?Z zTm49I+3MXs;O=L+H535NzZv*!{_Y!OO zI^o_1A$Y;HgU!=(M=mKeG-?{*lEMO%k~}zA1tC~c$g^o!QrHAkzeEf{KRC!|V|!SU zus2M;XKL{{2vUnVEc956lf%Ndkx&^H_5>?TLz8B>?wg2<;(M{EW+&O)Fl6XHic8 z`Y$hV*$^^GV^#2I;@;+r7Vb7L;V3eWQO+^Z$>22KiMgL3xIbXDQ5hXI*=`LOJyeWi zz}OF?F|FQM*)WiDOENDgOojB$bj*{_tOU{HdO{G13-~M z%C!)}gB0<4ud$tnQb#7o+%BJ4UfZa6{nw|K*BktU9Zvtp}&F^aQCt>0B zNJJadn2w}K&F*Fy*o&1|Z89o=QT?gk<3wd~*08J$>JV<*df0=Xjlx2O-$CV0J# zbDV4^jvKF}c37T;PW z3#NYTnbz1AxS`4n1f+L*LzN2lBx`L>&q&056p4_o#un`6=4AEl2)Llj<>9sy-PW6=-~ z7o%yQrHw^TgG!c%nddg2y>Br<8AE)IRQg$Nvp5z#4PbaIy3lxOuFIM3|3Hz>^GXO- z=ULvf822|=!wVg!@-&>xa+c$Cu2Tlt^mb3#c?O>QILguQ?QB%q{dYk9DVc|Q?Y`9~ zR_h3XXdPt$t#-f3E>yJp8vuvfeTac}|2!Dd?tg_4Zud4-+I>58GSb@(g%ED{70eZd zZ(Q)lJoIyClC2G8Qqs_+Vj+`o53EfvZ?#c9Zw2aSl81Vkv>ZK=-#LarWYPrytxRfc z;`KVmcL0YoDa1e~Wqock={N}COtPtxNfSVkOu8FFIFsbH#--*eU4ySssI~UVR_}xl zS@Qds{K>p^i+$qdrywcgiz;hjq|ONB)Go$Q{(cVUiyVHJaLD^e%y}H0H`V7y?k-Rh zc%E|jy_Xt%0Yr5(7Han5q_=Olzma4PbKzPTeT{}&>N(8$FeHXsYQz7-`DHZRO7=e= z@&(SnnS=9#Lu)@>u@jJMb6Nj8R`;9gI-F-)FG{+7f*x-@)htpXLDQ7 zxS6h|Er6uIEMDidI3Eyq$_*^2#3MLQR+cJN=M2Zu;ij+}e_etSPaGh4C*s^vR^#6Z zPAI{zf!8@Radg;SYCH#$h88*}<51d64=&of%Wb%WnnJPl7HFLMAp|$P~6kJ9AjC zb*MFv@GTvIjwQssV}pdLL_N-v*{3pS0geuLfYtcd5|ntI(}oatj;8RtlbHr?u+feal)F67r+LuLU$K7s-2oa>knw(cMy{bqcH zBHGImQi;z2C7WZ$Tjv~vqr->dG*#iL9*rl6FLZuco~uqGrx=LlbQI~xJ91T5VUw6R z1wI|Nvx1j=PYN+XZVmV-Zdzlh0f`B=Bh_o zPAh!)K?zAXu|+tKgYzaiFZ-MwA_b`>G4Zdk9lTkbfei_reLg!2SJy>Oz$P)l>a);k z0`{?x96r}%asrZumpCh=d|pq+RO|N6_z5VJx3zo`WO%lLp7A1Wm5DT)_oYl0I;#>f z^)5-%LnOpJ4z1!(wib?5bntnotGczU2wKaEa%jOn6DjS(md;%vHJ>fr@@t`Ug~#EB zk^x60oS#uQm`Qcc7xb2UB5S-EB#qZOpEIG{5LrX)D0C;VC2HL1yER9Z9|#t=SJbQu zF>nl&3!T3Z|8J}Z+?!FumkYcD%7xB?yK>d>jR13FM-AU9@J7H1?jl)xAI_7*D6OSL z-BY{va;HMephW*u2BV)Wb@i8wmKcnyB+IzYxq?Bsux7bk=PaW3pwOLDoV0W-hecD@1Fh6)$vNMl);I7|6JEq|d5c)!;NB z+?hm&kp_61GtG?2%8(&W?E`>MMhhN)XgL;;kwCHrPs7Rfx@=YTkMkZ{_K?2A@gzKk zSXI%;QW&kMz)P>ojh$J@MCkL~)h=dD04gWoP|-b|vL~a^9SKSwQu>p^JyAR>T#id6 zVh6enL6JRCDy{^FA7JK>N5Jjf?MT^m093^y9M>555)J3M<0~*z2jKn)Gpi{)2F-d1 zl^by=Zxuz*;SrUZo4|{0RRyXe6z;yE1*#i`hamKZP`>h9d`AGhR##)$d<3*_Lg5|= z;X?@JZ^Bj;;Nr4WWA~j(yi35SZiKL#$SDwhq;M@__=m!S)p%(DhN~_chF60j$lcoY zCiy8Ozqmt#gWM^g$r8K3KU>Zhw{OtW?c>4aSHQ$PCZJP;hHhinyao#Q6X5eHoD9uv z5cC3D2ENV9ACCyo(tQB1Olm3~2dS}vQIAw{mj+pt8))KFaJE3GDn!|Dqb>X@&V{hm zBn!Q@O5KnCs#Eh5S#BewYP>NZ1+W1LuZl&QR7&Qrg?-8VKOp#- zzt_wB-ZdukuY=%cehY4Y!OY(Ztz>@52$T6+AV^mK3qeX@^eCO@RkuQ5aY*iVwsVEK zTLXTO`K30@vRUlGlKK6a0A_v!HYM}l7-=&9a0oi{_rUAEww+E54tGZY-UmRhecEU? zHaorrsGe^MewvN5=#D^iLDBJJ&HS~%pI>y9EVkPnXQW?hdr)V`SeB|1SgiU4mg0j@ zXrnTm5Zdn5SdQCxG}ik8xTipv522!KI&C60@w^;pKhhqCFpxBrPOHFz%`TuR(u&W+ z3-J*6t9cB<9Fr`y%-Lzg%Yiwyeg9VK(nMVWx~Aq|=&p&K-r(Ul*@QuO>gMQAIs70; z=Sg_T{tal4Se&g=S0<<}{{>45^;lU+O-p3Bgk8eb;$cL2SJw5<@PQAq5; zY9pyg=qw~BZz2+U9a8YkHw9_|6Z$xW+aQz=#i1ABs{zl1_CmsEL6}1L2pq-%Zo1b= zx(7ge3gNH5E>LGf7@ERiIpF3?vfQ;$w!^u+Yf}&9A<l?WM{pAu5l&%HKCEMVdR8M&wxP=L-(dOA-K( z7gItEET)_bhO9W<03p1XVpApGH-I9GDZfGpFQ&-)dZ~$>ov-9YyYF;f$P@53DtR&# zsGlbu>gCBofPS8MpqD4F01Wb^o9#4Sk^Tp$l_$LoES8ZcUB6GylMn-WG8zoYliMJK z^Teh~p45XPc@o>3o+m67-GS#>DNJ3F$acG<*rWrO?!S!1$}1EZlcjOufZX58ql1Mm>XMgul_*!Pz)RjJwI<`=o98o!I@47>Rfz zM#}%!h%v7LZ1Ejdv9;e3BZHd}BSmY(cr*ilv;V-}h%rb=0~zsQ6j;e%vffZU#~KA1 zSw?|c=6J6OxEv}44xIpqG%TrP8Gil8$s~^d!Wi$Z>$Scorl{ORKA-+$AkW zR*Clz#}emCx}_6bB8i0Vfk1bVr~6Bm5@Z(BU8ZMx7Gq=%&|7zxSqx@*9Nf0-i_ zS0^PU)2&6;bW6*VWz4_W`5b9g$tg02dzb-uRSz--75j`Yb5zDrKzQwI%eBE`Xf&lG zRQ+~fk+0nhnZhOp9Lb6Eb`Xw$VP9j|33|$$c&HTf_RQg!lQ+UBpq7WRJS=mnOw+sv{yDX8BIGTZ zjf!z0z5=}l=Lm8k?uL`Dc(N&VM#iW4xG=wm^ZPr<`3eLXob`i$-gy%6{=xbGfDd`- z4?M8>X^u)Q&EzG!BC{!8Ni{K#M(Uw&8bwE^k%1hNUiw6uFZD|HJFu+c?alws$1YeG=ODp_uPDy9wTh!v=s&pTs!d`KdrX zs=;UFpW2Ln_?6c+!xN>nad9N0ave_G`w-~{2$frS*oH%SDGn_rgETUdtQ?FJ_oRIV zY6S7|Ji8b{ra~y+ip2H@vFT?{vhr{GQUGFt!~zm~gV-EG^~1pCm@MJdr1?!vD>smz z55{H)71yUR+Fc#Vue^nnk6`jHQZ7!XjCNYN_XE9xXiYkLhSSx(1n30-_!~O7IbMlI zYMb9wrYRpc!||%~U%Lyj6VfujW>99)#dl@p?NF-YUKbu-qy>5khdQc!SO3t>PVk zgKu=?{$}4Q-egD4Tg4{=4tBAx55p062Vl90dl3YE6PG@0wRyZDd@o?G3z-|jyal?= z=J2-jiNBkBpt%tId!Qkjf7@A=^Fgf^7ojw-LuuZR5L|SX=b-yTE6`IFS}5G>AUs2%9>Qh{P5vrS??R|LAl^uQ3PF|}x;??BW|ka| z$?WWoavGT>2d*CUHgIoHQr$BfxVHe7iR^0-WFlJ_X(SWb3a%p9d|6F66{xHx+ysFW z+6t~Fc(h(HD-+w7fy%@-H`++ADm({4CbmCAkcn+F)<_l;s#ZeqC$^p`8GmwO+Z+5~ zV%yj9PZk~K_%P?IWj4(DYIoT7=c^%<^VM-cO}pWU}at9X8%FKABO!{1u zvP}9o)$%AUNWqk=Ql?usg2L%m1*cmf3Z`9^GUa+66i&G+IOVb_oO)Htv}+$IoOV@n z+GSHX{c7{Ko_@*H!visB(Nm9dp#Cj>8*7K=f*V0Mw-; z6Rwn9I+$E^`X_yI5n^C+Q3HldE^dYpo?O^enOtlEMJ5-{zv+_;@w%Cb-S@f_Jl|^@ z6|YAD^}Y5`&+A(N`d)`Xc>Nkc%j-5_uhTww7(%@d9xBx+&0CvBZ!5*quHc2ImMBrZ zywJhK>Mbu+%F@C}1n`#@LKG}5RLZi#&7jD#!WIbrvVzT(_+?2!q05mag{~0Hk^gGXsWir*NX0mW|&A&TD^t_Q_$3^pZb3}vABjlrg{F&qq# zYY|c{JkYNed(j*F)xt)lT09BVuNEHaRg0Mb{b~^cQ7z5_XjO}?;cDTwPBuz=lq1AI zV;BsEG={kl!i~YEN@I8q6saP=KnPb6@p_wy-S@g}rscJbiq|es-)j%`yuJ~j?{x@- z*UtmAyxtY|I;}B;P_HrUgN3lSHZ5ojZL-omMZMCE;Y$-M`~4Kw+H_+mM*zPugeZPv zmBRK~L(F=@?lLdS1)z zxRESA(dMYk7`fAi9h0>M|9^*OSPzx;0puS*8P+qI^(o{GY+N<$*u1QtAm>s(u5niU zo?KNzxmPNy5c0v4k8hUM8nW0qp+!~)Pd>3tR#(V>(PrvSpy(*x<0H= zkF3FvyHkI1udK0$w zhhm+Ge^Fd4Vm3k~ZW6H>#RWNxyAQ<&b1*DY!zn(}klO6;a8MDf7i{80o4egw6Ybiy zqqyAhF(K~Os3EyY%n537`wVlNFpkdH;ckxs1L2xe%WWD%+RoH+hs7YGL1L{*16tF! z>9vev9)mqT^3F5G{O-NEJYg}bJDpL0h8Odz>rOu+!;1x|Js&kBaVigoVSA}5-EfHV zplUzsPIt}(CUg*#|{e=c>Uo zoiTvK8n(`&3>yo`=2lsO4SB3-@N*6yYf`m`084HvL&7P^q0V^?=MJ~X(xKWzl29W@ zMI{cXhpD<1oQ2LL1XxHz+>ayOP(loGL5%s)j|L9A zmf>eRoDCf|TWl?K-ddBZ4($dCUzpWK) zs+uc{m(rq3y#8S|8GJ1^U?7ecsO1ZKfmYw@KQl{uau+d=clSD=8MthriN-06zSRN9mkoOq@N@L}eheV|d zU?C0(2Sd=Lobr(1Yh7b`sFlMaBqPz96gj=M96(o|ibP>RW_x_?)!Ps*#Y; zaIW|)Ta7-*xf=;Ert6#zBf;dDSTh$wGEV`%IKqAka01S1Kdi=K1t>{MOPtJM2t0_7 zO5)+ao1ym}3Vai=^z^|)f&b=!%dxzUh)bcuPMsX#GA8OvCqAmdsb@N4mS)`S;C54k z4Y}&nrXX@0tcmwywHCog(GyN6+ul^7)U-w!|8c2Km`j|IOt#O`>Hp43|96ftS;Q1^ zrkkFksa~2JGE%O6YKCMVJIUrF`S2tjq8y2BC7D(0kRv9mp3qT|*7OPQnaLf@9L9OcPeJoaQR98W$OofVdNCAXJ2&m9TV(t)*G9%bjU z#JP-X;e#5j!rJ;7PEvO`y)VsG`>5yQsE$yU({F{o-AJdIW-Z6r)>5#z%BophIA7{u zU6tv8E7vloxM=HV{Qt+Npc>9&QS_sG&F9fOBhsi5=^GM1GgPSiwXI9~6RV^@k&>2N zYWj)e=N@D~_aI9Qb3qwyw8IBCV5YCMuzwG z&{Uk-%mZ+nA^99`jf{61HVW>WxR{-E>VztMZdC4@3;`&2_69|HXK%=Eob!^BT9_8@8LXfq{pR)B@q&(5o3p`na z{0*?ILAHV5KU6agu&h0{&oyh06@cZ5rVTJ7Ymf5*$=c%|d1meLuzYLnv4=^hEbwvd zu@d}X?XkCkW#-Cnbh*bUZiHBezAO57) zCA(B!ffM}z-%hQ{c3ZVHnZ37#$?Sd51epz+Qr({hESbFlaFE%6C9|&sESY^hV9D%! zXe5t&Ly&s^%Rwfy7qqgf`x@h>U!Tu~g`hrds>$pkE!*^hLz({ z!SL;~&c?V5*6jL0q6w|YSrI_YGkkYvx_N2V-I=~cDLsX^Uj)?3LaG zU-wFK%fp75`^UnHpZjGt%G_@N)XII=#`%cedmgTDc^KHg<*^NJNL^S7LF&SI1kiOs zZh4ph`zfvga4J+>v#hvN_aqy-*MOmmtfD6ykJU<3wvCFhxv2F8**9j1co$p*_mxtG-v=7RP&k5z~5?^~!P&!2!GdHy7# z3))}3ZHG1BY`}gE2%)S2Er41zU~4#ZOLwM+OZ(ep;QbWnDER6XXw7Vvi)nuxGZ$hM z!Lrh0lCy~>x?_Y;=lpRHAT~4&jTPv4DC?Z339+lRpk+>fW407FoZ1zD+b5@TWYVy; zH8L516B&v0*CUZ7IB)+UMmU|59N`Q}9^6Pjdf73_!S|3`a4ydZbxQJCp&{`@8mZ^l zFC3-&1y->Q>;y`a*>2B6P1TwXL8{hJ(EUzeuh$8@0$8fly@35rpv4r^3FNjhRp}?d zQk4cmBb~sl5Lj`l8n-ods&6}8r{sCxOH3Yc#a*7JJ{h#2DlN5oKB-EVd9Z%omkD51 z`V?xZN)JJhs#J(rf~vH}w!^A41+ZV0LMW@!8la{svGH#(p&K)i9D95YoMR8&U#Hp! z^+o#Yc~)$xBa#QXpCA*Y1JI9Z8(7xek4QGEtbi$f5uFByQpY75=!dYcfMF?=Mn-H>mx;^(*T zb+8Z=N}dgKy!f>TOQGalZVKfw#3F?<1A-Jvf5Z|LN(RhBoyrairo*P}K&5qANY?VzZ72|_7_jM7G`7lnEVr$LzI zYyi8eCr*dR={TO=hSSkF7PKa!Ik^JILIyGO-JsBtJWq_>R&qSK(?7skY-i=VNY(sN=+%KI|=ts>tD3^ojlowDinO6`h$; zgvn&ab5CNYHthbMfz>N@!pOMF$cFmW1rZffPbn44!a>DjSAya=2RVsyd`soNqwk|MRx(`-o#FShYG<}G=@0aGTtFhIDm<;Bd{)Y5j@W7{6K?p5T>@;ANc%l zVtCDI|M&#p;_f9DF7eMqqEvJt@Tc(SOmnD+{ennTk`AmH=_u!5C;AG|y=2UE7NUeq zy7&Q;Lzt)6>5O1F9XRuFsQI}KXRZW@o&k9r&u`KOBnrRWRB{i3u5W@06>+jUW2L^q zM?FzfcH@veWjEf=I3-^dxjC;XM`aW}kURTQN9C&QnLr-CJ)(*#^3K9*txND%^!&NV z*Zi#hNM-hX;KzTNp^B;sX5hu?q7D&9kk}n@z>PA7K|9VyE-Mpw%lZ^+3j>vNwaWqjR1rD$jlpah}f5=j7dtuQ$JszoKU(P4mdj z`xJ^cOw1>&R{5eVs=|wt!d$1*N4_dL5-$W!!C%q4THB1;)E(fm3Kgx6QsEdApFrJ; zh0(Kfssd>~WvzNJlF3m(6QT(rtIk&65;SAB#oqo^d~4m{AUEypC*>?h#XyYrFN zLko_^tE5Hw5vQ1KOq-QPCRvo|j+YBp;IF8ugG!|zL$^r6e19?B+Y8n?t-<_NhrDyhp$q2#3MZpn{%H6ptn`MrtxU7h$H9o@-zo3*I7RU$#+Fb@S`Bh&R$hLtYu z-U}%F>)Io?cSbBs>VHWIvg;fSeTt$PCWX40JmQ$sR8Q21D_E&M4^@;Er~wk;D|Up^ z$)=XPlczK3g8yWaCVU2h1m0~2mU!EU(qoR$x`?2 zteA@%$Zz1Us7V7}7}7ILmAteqM;&qx^6HeBDQb55DwW)xqa$5qN2;;W=+N1z7qxA` zKG7HzZ=#Pv{|B)}y2JM?j!OM`dZv89y{KU(z0<*z&f<+Gi}jT$@#S4Hb>>RsGa3ym zFW=qJRYa~B1Rpi-GI z%R1Tg2xkVgwuw|X4?Eq)#MS{~>q0}HO?$mhfW3_8kh^P8VG7iB!ACPG9m)(^`f><;|2U!}YYe(&QwWXpA^O8?gSOioLI+n7U5VE#B;Na84WZL7 zB>K(Y1}%6Ygbs@ly*HJw!;Zkn%SvTPvVXfA zmw~&xD|LHuj*9ijX!%b`j#`WJ*wk3EAcmrfRiat*H3_9pZ#1W|{?w(`9jHqoHZNm{ zlme+5E68AQywzw2U*ZKH8kl_7)9HdOKrj|;?0eg!@JogQ+mxT7VsSJ)Nmc3rsBS8N zs(FkaIr$@K`Jg|bUU)NxZY^TGL>hIfPs=5pCm1@y+~G2zgq1;r#u(g94UAc zl`FP9!>(zPef8ZKNjuauL4%qm=vh+JYEaVz4QiU8m!8D1-=n4p8q_pxc_`5psA+-* zHBHbz#uD9wnkHya(*!+MYTDhXX@UkdP0;1*rKZJhf@eevZB=MJJSK3?^=5iT)*O9nf!|LH@O7!76=J$?=HfO+0lL zi96ZswcR^nDsg6ujNv`8wvv6d)2us|dQ>EOb^9DO1QjEDwH|JsfE#rxy3Nx*sqRIjYRQ z+tK)+9=@8%6_U1-zz~CWVgju9(d3wC@Q4+&>{drJ5Am4KGYYLc+S6?bbUi#Bc{-{C zB#nI{Iwo>Oud_{qr~U_&9MRFZo=HEbiGQpIG{)S{xb+$HZ-oKydM~n+Jxli5$Xkfm zcq=}n9`vy1ZA^SgZTGPEY>e@!lH!gzGAqj7voB`54TOSbq8&2z57g6FB0o-xmgWX=-T*J^?}GX+C$*}xp$v=;5{izKPe^PgWrdR(*d<5Z zODmPOmDDs(J<1N5S`GElWRDLe<$b6tsJ<+ujvt<*uBLi=$jA{;-$V7Bka`%@oPK04 zh%(2Wd`WC-F4V&x0DFn8E_nv(X|>4lRbELjkSh7w(?4PBP4PAFnxlTjkU0B&1FF;j zs5q9*{>(O?x*F;lJVcWHO;lfPBrzoqLH*Dw7;tcj^P84ReF#10NZENAFJh(C#*&pE zqP=3wo_)KMij^APK^fl)k7lKLs^lc_IG4&^=9F{l&p^*6`a zFm!rUYADp_tcH4XoR&;7rA%~|KL^79NO=4IAhhb9qxO)nJ)VtaTdUg3WE)F>7z1#@ zCwrxnDhK%x=KL;A)+v`uU+QLHRm8qESgBN`dZ-ss{kP{3FZL>x)dTTTpP8^yPEn<* zJgi|lCWWdJkAra4g9zL>q04X!%1~eW5;+*B2zH>2$(1jI7huj!GI%lPf@EqtzFgbv zOcq?cx#UuZrNEr$bt5|(807_+_)iQ-H6)y7R@?_yMPj>T~kegkZe~1{Dli_j_Yfnv4 z+qO9>&QzbTwOvFz1=@ksPSD!!)T->Wkp>yLog3W(#+_v3JLLfLtH_Avv@_a5haTsT z5baserj~$P?A(OZYHcw1%5e@jlxTBDThV6+>9g2{G@(_88kMZcYE=hIWmCHt{iQ+Z zBaBM2S%>asvFy+%89n2UX%mMqg{Nx0iq3^cL#a8(Vg5_HW0I`ICP23kDmO+*&{#5LFj+`m>qM8g%2C4*DEWl*P7zE!j7vZ)gMKA>kzjcwZ*=_Z zOkU?iD-Sk7Hl+oLIEhcuB%i`x@)JiK=7XhHyVD7wM=@!4iIK)ei!fq5?4<$kyNL_h0TuQgv4q7^57iRV78OL7dDhWo1@QS`=~m!7x*0GHkkh} z&TXjqy*EWvgC!=cUmj@7sPQckEUR<&>4@cLjP!H*HHy89|4z=)ZThx!)RoAfobFEE zSm-#b&N=pCF!N_H-?G`Ub9#`|BkuwH>)ssP69YVhID4D zl$EzW+pA!Ck7b{ZkuGlqJdQLTE%sI~^GPmSs-+^Mvz=~(s{P$JMK zzO$_Ah_(Jl%e1Zk&9*Og3J$ynUUk4EQ~XJ_#wjagVNd6Mq|36eQnz^6@ir#OPvzcg z!kuYj^aHz60b^%dSmu0){B-g^rpKw``}CZtaF|onjA}_i_5%m&X;tB!sT)1U1f};P5WtGjL%Iwi`RXAE!YZg%)m74B__{R?Mla%gnz&M#HEQ+LC zOO5@X!CFLqmzY?tF^MVlIj~zQ5N>4T@B_SB5o0c??59yNUmXJMzSQN97}{8yrcL|` zj8llhiIK^Hi6|GevLA+tN9tkX{?zidhIUCLsDBbuOt`7@9yNrP(V3{orY&TOo%XnI z&0e(dywoM@46Th#YeZVfj~>!PndAW+2NS?x&TUk1cB3VSvJ^1xqHaGnYoZj$zQ_f3&Yzc>`~ z(&s|F2*)V&j1i6?e3s&QzK0>)u<7+Pzzr{WwICs2lQMU zy3!X;il&Hr@C&u|jRlEM3JlZ+|Awmp-fLt&40P{-hM28WfEau+CZD4KPrU}z!v87>v`DN7d<9Ng+X~h71@yQWs_6^Q1!>jcAUFNAajM9} zR{-<|fiwNwL>A?YXJie|^0T%U)gE3}IU+^mjs$h(80xwJF}PX`^?LxbhBcIiO31ZJ zliErX39dFOMYQM&+4cQ*R3!yjlfc_>d1n#$IU{^rljQlIV-n^JybqEoMDn~5o;^B6 zJVx=RUMbnh3c)+EJ{k4Gng$SigdnC}Y3 zZ4p^X1e3&BtkoN;@)%CzuiC0%ER&st$zvf zRVr|~!Y6^F`95^cPXoRho5RxqqP>&QPh9D$%EHzH1^$hzSyQhCnD$6Qf5uSfEL7ls zVyGVlnB4i0-y|1a$qvwEZQ3IVwfBeLy+M&An&iXl8RH^I$e$18`@@07(sK`$_DTt_ z)8JGuXSm7|>2!zE`1w^U{v^P(y%EYVS8&b9LBG{f>1l^5c)^)(0!(gHC>!n)_kXHR zk$Cko94c9k;y-FiFc~v01p~z3?H;hjxbR8f$PEnbGO6<_aT2%sMupq&#SxhZw^*TY zCrx@XP<(P2(km;WdcN>6P4|UY2FaHSWG=Z$3Hni&YphEV`|t}bSH~Hol^g+x zyVXj|)2+C-C-z^DZbg3E2FtY+y#{@o!rkY^ahFbf88}*>4n63_@osnGtlJfCn-|A? z;d*!A^_+Jizb7qvR8n@afm$;Q7ly858rrqiWqngc#e6ik$J+C z0UvWOa9?jD>gFq;MHt95=k{Mw3gD*B!-5 zht46m&FqoJ_|xI#-(dOiTWHZuTBTYAd>3cwAL)#12laQM)3|-o8Vii|JI)STvk?>F z)6?;Fm>H=eG(~z~|G^)}nwfV!t^?!RZ)m7bFZy39Tbd2yvrVwB`2?$)p|I}?TC5`D z3FZ2PKa0SjOrPDLf?u#r34fojQbfwv09R%W&9U%cx)de|yL2VcPzsCX1M1l#Qs0KF z%hR*jww4foK$a{yPfWK!r11ZFr6OE(DMIq!h(J>EVSIgRolgs3i(mI7> z6!^u}BWWjfU_~=;#a-o|^JD7FL&7!11xm2ScTj8A8&E-N&3bulsJ8|LYR$SEqI%6* zKTFV>^|1ENnsqFTTC@HHc)e!L;+RUVSr5r~)~tV`>|Q2)oLw$jvwja0YR!6`L*YE( z1-8`34Fo(WW6c^nJ7Zeosm?wgDXvS+lz!nmpGbvEZNDSZZ$e$rlcN1@PS&dz=tR9? zkEFtJRY_1?1)4@$_`hx;#~XW=aXkQ%`ZP;6S}D|G4=M*wog&eO3N&fiTa+;36(*@M zG=QW0q{DDTk_i&IA4c<5twW>_DI-G9!o=+zhQAtJe=pC6QLEAQ_o{RX97l%f`g?7< z{w~$|hx*nu>Sd$Q^{n~S|FT}k6?l8P;Ss@XlH-Xsprg)eac313tf?p`#`|*ZEx)i| zvU`#q<=Ro=WtCveeok2UkTs5Kr|Y^oa5d5%3>S1Kn7N>P5W$W}&z8s`rBr~|%4?!g zfCXC%#LNYVF->b&(+0{F(En&bGWX_#+?=A($_t6(;12Nvustf9tm zcNQK8k-M`%DQgFTauZ>ka%W*L(ik-zl(VzIye18gwB9e0kA03W=pma@bP|E5;pj;oit*rV!NE^0`a;lzr%?+qrS@r$D#4R0UgQ_~v&-|Mgx<)| z*?=CvS<=w!k`YF=6pzS342s|5Ia&>hWJh{XVE1?qmKm|Q0G6xX|ld|SPks>rGVl+B17B%3GM(4QnYBZ7w zH5yUE`kBzdRp22@vJd=?wC!Rz2Ofq~gYoMg-weB_RMy_`Df(B5MRKNAx!AD*+HSIn`gLETT~a0~M$-f!s9( zyzuL`$tfc99Q@T{!@yF5eKk?|%T1A|QbX4mO&n-|hFIDS3>6suWuTx#siA9)s7pbE z5Y6bJPKN&vP;40qHOCrbAyjG@pcRsPDZlQ9f6P=xG1-_yGN=p|o%$F4lR%v%=Gh)* ze^*oiLl?#~IHPHRR@r#Pv8RE0E{oy?@WmCbv^J0*YJ*CfOO=*v*xdjSH92L=ltnan z*A)opRBkBUXo5#pyC*>dH1Trz{f7S{D7gIPji^h}O_$#^{MSxYrK@NR0=vwN>z>P> zWcc6G6jhBmB!kpZ=bm9(aZ*}qjouZ(AK%kQkXmNo)3_VR*SDMOUH3XkNaMlMPb zb$Z`|e+g^xFM=nIQkQMOxeseSJO`ufY_sfec{}AcMo`*jdlss(R zU_RlX*y&*{Rs)Se;v+mF7-dH>i2Pli$9bSCb@xNa`pc&&*WTN3O^uE=6g+HdH*q@@ zuv%anN4be~PeQwi$r#G$m@c`A(>2Q>BbG(EiCcizZX%0gD(NPE2%I|Fkl6&;wWVF7 z7&kEqnkhH&IZ}uzoU4ujy$2q+%LtHCO>y^!jycdR7TTY}F^2%%M4@{{fm<+}S(^@F z)C|{2uX4;URv^!CQ;|FZ+0s$ga9(;%fbT#u+$>P;O2or0?9E78yGcDlNNU=D4L7RD z6m1M95xKX%pUSHs;SNM-*jtG_*ZKh0-?0RQZ7Imm&>4WzQct+h12wan;xfR)IL(@7 zUJhZ^F}fcCNR93^+33;z-WL$}xV(!<$>o%xGrBWq6@mQw-$|7N=`3R{05+p~H6zJK z-&Lr^9@J7oCBF6^UKXlcUgjWPIp^`{PCBU3y(cp8jP4VNQ2UxPp+gv!xj)kftc629*%kohs%^{a1ItTdq z3IOA)C1TrYO*RHHYlyE>sR}9LL$F#IehjS@v7vh{j#Q`6g^SBL`KC%*X)f%97bY)Z zgvJo>yP8*u`bg99cd^2=K|<4@^_8zRgvo3y#%1mT?pL&t^|R(75)u9b@U;<$zUY&8 zMDiKjE(_1e_*p_7{gvR=0P#%_(@!@+44c66DoFTe;7*aGfQLoq9&U{4U|bn5j!W#` zdEgJFe>`g#@SqyJLjL03cJI>1^C3>{zl->hZnG-y049p@CG znU5(}x?aP%_8Q>Ll~3$Q)}<4X>y^M-3=GxZ{oky&WjeXKtbAT3wBuLBO4oKc*K6`+ zuC?iGsLaoJ8qdFN0T-cp0lLTo6QYYeOy8uyt0lSLitF`fz!e78%Ed#p5cNj2gvABX zUxU`f$a}2-GV1?xGF9|FiD-Jck5a{_)REr|q*u}Lx5`ws5Vxip_P4-^E9+5ers2c= zc@ig~4cY=qmtU=UK3~x1#ViAcuDx0}fXDB_G&~9nceSO|)4*rCSlQ$9*4>aQKEcnr zQDvW3<>OQ_4nOO>f`sQFb&Mbpb^3+%%$xg8idckuMcC1nI_8}MQN2$<_=JYEMrs8? zo>q|DyO83+;uSeo{6S?d$2D+_#aJed9>G(f zK@xVkhVjrNVRbdECi6BTQ4O@HaC;=VD9!x!ftNX`QSCO3>)^$)=$6m9qyO)+lavr0L+8uC^dKzSWXw=a~e0!i{l~RQ?F^(z?G;; zGuntkbFh6C2^OWARE9q}q6&F-TT%0d^^4KC6C&gAvo0D`=l<|yB=^KzYuj$wL zFPi?0|At`n97aFXv>d{DO>5x4XnGa?8%?|7zpv>q{P$y}Vd81LB^#G-ziNv--OIN< z=`Nph`Ib^vKNp0{w+xbZOP$NN43l>>|2!ql7ME|Y1)rj45#h^`CD}oRu3j9=axUMp zsBx67ynL(2tgP_wxaK;-Fk{CqCg))bc6|_e^Ig_^+f$kNF6(6^ite)3#Mt)VcUfyt zIo-Rgl(gy)Ed1h^sxPiKn*dS3q5tV|+rM)GZ0y35KiSx+fnDUs*ABAGsO z0C3J-Ru&t62q1Nrl}cpT?MSi8KLH$bmzBZc7GI~v-er~Gl>o=wWo2;YCjgV{$#+>< zMJlAK3A)S5FkEQYcUgy`p1pTjNsP2;Q#Y5}aYE(La8^sp7uRwuRJEMd7ZuERLvMz4 zs=J}5Ve*EJZ7)2fkXU^;bmJGP`fg|rkc!0rJHYC0D1jy8CG@Gv)0g~@KD&u>CMQ&D z&UtAkv{Y>rwNxM2EmpF=NyVs{;H%W|wG=U(iX6bwt2RgUsN-iK3d^Qn(=6()-91Jn zaMtc9Wf8Z?O@%<}4yD&Tg|uP2C}-`Cc^%c#tTGocDVCmX{(vmb-iA9rzikuZ$KjSJ zeLWtQ{`?wHC{e0zGoFWAevg$eX)&?WO<@MJbg|u~#VLwkq+-4GVuL8Y9 z<@C=0)i2$k&V2?|i*<;gRcNHX2&l9W@}hX*USL^(7HN*5wvCh}iI>xs#LGwoId%xK zKue3vFPO3{u~Guw-EkE1Qf^EXt-c2GEwok2io}3uZ3Q?a6Gk%|DHE;oWWs^c@W$AD zr&z!}&$uC$Q$4PE7Zd*M4<4ibhtwyd*8U!hdI1Q?sGo&ck5LaGch50uN?F7$au0%D z8ubtW4ckRIM$NpAbD3uSkYuw_A4C>x)J-4v81-YY$&C=Ijr!+bN*eWP@<3ya+Ul&0 z`t36%jCvXAONA8S_kMDWS}IJqIHM-T?3Dy>-tOmEqxPU41&ZBJWz;UJMLFmkXVeZ> z8TD$AD5DM|Cz+j7NluG+jC$I3*Qf`j!)1q2%V#|4pp(K}NadR+nB#s__RU3i?Ryka za`QR%&7kY3$o^b#Df^}xvZfH!W8WmKgnbYERoNsxLj>+cW4Jasn{lv7{d^Ii2;*Us zIp)^ma8I*K`ywN{kj;gPyC#Ti98s{pq3q95_7b*G!)SM0gx9<--OTKIe%jJg^!MTc zSA=IDQ@Cbc+?#~U9Dw|2{>$zMSCaD}c2TV=m`mLi1+Fe3V5HxETpxHff8kkZw zIn`IDEaFuJLllU4{Nuqxoh^HqL86)0@`xLusJ|ounXiDFT;}X;xPL|2NPT$VX#h>V zC9e7KX{a+0Uz5P&H+?l#GRT6aSuH^x$exk@=iwAVuio^>HhC8Q!POf;Yd3XX?luEvdAi?0!F@Pr25&p;OG7R4m3nm|iA(U;4i z;w*AYLt0w8G-(iJP*Fy8&S;8|8X%{$ zeUK!c`5UBoMVwWI2|6TLAHyW#*2TzzW0%qh!uHP_C9l9%<5MOP1j=E25z>b3qMTuzdHGd1)cez{ zgLR~DvJzSFFrGZdGmMY@Mu^X$gdWCo|1LREAgE^;Ct)Rq@s(&Lb}cp>z%V`n3x4h}zKwAh#tBE90gC8hJi)4g1sum;evz^y zo778+u*o9^8O-=dxgIe#8KHMHI<5t!EaDcqNf0P)vJ!xX?V=o;WL{IRU!tFOk~Uch zS+Gsko8qy_8fS$#1tqji{%i$ByuaKQoN+c;+*8|R(RU?mvJ>e`g%sf*{6Xz6ON9v+ zXOpCuT}bfe{mfvDO?ptz0p+zx7u6yMI>)&d4p!OZI*=%v`~VdxvvVrRX%UZ2j+^S* zWU#l_CgmD1Da?hG%fGP6`)IX}TxTx2Ym-+HB{!dAlMJd$MfMK`m$FH!AuErd9-Aa# zC2X=+0K`(9cDWvfX=b#*$WL{G*jHg-UCQ6%p8dMkf)#gL+VpM(OV?wCj&r0{p3xE_4Jd%Boxx=CzP^?Tjbsa zdf88U0cc>oQ=^=I!n~&5k4du@ucs_#n;#(y?kCT#@br^v=Y^OKp}L>!E*BJa&jqhANZXXy-(zuD8KER-1R4xAB&_JpWP%T=c2>_eugZ#4}7xL(+3*-D8ye-Lid6Gm4c#UTp#d9y?vlD^?`N+bsu>6rxJajI?l~l zR7eqSlkM~YsW9Q<`T!|r*CKfHM?vnLD?F(5oY+3#qFT%WDy|PWSk(u91&QhdJ5XgZ zJExMI7V-3f3hUiIaK}sDJ|MSANntLeC3i?m)$sNKxeM#ka2kE!Ali@n09TLO2mWx{ z(dh#W`Uh~~UjQ!E2dEY;iz>_02S`|nKH$qDyY(y&HjeKDjddR=1$j;%_z_JT-v?fR zRd635vkKH0rX!{Y!n5VI6w9N#D6HSn~OedN`T5ZkK%=EQu zpc8FP(XO>lv_qmuC)y)1NGI}<&sZc_bVnp+>O=t&OLd|XcMDSlb~InDpb)7aIpF`2W!44L%3VQ$rRjL zmxHzaI9NA3wB(J7}aOE;~Eu zaIiPgCcYQ4IC!x&2QL?Mu>X1v4&1@P!JQnu@+Jp|zT)6jA3ivppL;l)gV(O&;7ETC zj$X&X>q|H|b~gvdcX05=YaG1!If8=R(#GE$mN6>gTM7la$wq4qD;T6tL2i~ol~a&g z$)IW}$gOHng%spgSA3T%z8cJzU%Sq5u;f(}c3b-YmkwRrNV&LElu)uicV91e{;HwTUOv{Mv0sajNY+4%)5bAb%SN9d>fi z@kI^_j&RWVT@Jc@$3a&=z5twGyIXk}~JAuhpi1>)^rNi|A=t|6-24?lot8*8cqRue!aYz95h-@L4#JCIB5M82W<{;(Dq#p+MVH`{hu7~G!%^a+Gj)Pm?=HS*ZI9U4w2kT6H;5NU}`V0E^7GHA`9{B<!L_e(FzRCtMxWFaj>`+2TPi9u(T%!%SLdpd>IEf-p9d;7dTk?8V5Ij#KG!cI9LCu-Euhx zyYo5NGn|8G7jy93Mh>2Ti2|z+y_7rO>Ray@1g(0WB4Dc#zjH9NbT*}Ks>s2n1|00j z=irro9DFdEgYT|KP|ymWE8#HB*vMgZ;~5T{8E4b6%i=9zUkY-G0Pu!-4|!=~nN4x5?NIc#n&=dgvjk;9heGaR-yU+1um`6-8O z%^x{zZ<>`UpM0|%haJr792S^OIqYP1;jptgn8U8-1P;5I3pp$_*K*k1e2~K)=3Wka zn(uJf+x(uxK4$4Eluuu?I*0wu_8bl{2XPoRr*b&RT*={J^8pTrn9p-K)I7oA)#h0a zhnfDWByYHx$>9jI7KbCvRveBpdvZA19M0hwb2^9DnaepGZ*Jglg84XylgyVmoNS)p zaEf`F!|CRq9L_M4FQfcsn%NxAHtTVCz1fz-Ic9GT=b0lpoNvzLaDlmk!yC-IIb39J z=Wwz4GKWjecQ{;Tp5bu0d6B~vW@|e2c?p%&$1yWnSQLw^{mfI<@gz4Lk$U)s2C&%xFAAZ)gN3g0EQw zmM40yZj5oSZoFJwu^cjDS=7~yg3E)>)eRQMRPyS^TfnKS8z(5cr;%Ok)r~&TOkLfW z?ogPt14r+03eYx{x}pJZ=&Ncd1{N+R0_|D2*hEsDg$qhq4-zPM5LA~77u%6GY!~G$ zTrjUm*=%0`p~(+pxcmf_RH|;5C07JRxtc-IcE~2=XE;iAUHmDYq=t}4T*25{D=30( zYj>jqMxOxGwx95Kqo@A;U~1bx;7_LdpgS>b>z3O>;u_drg3cm-i-?2-x0c{DB(~f` zM3~PIywDK|Dn{FG=YW)C?2QHMB6B)j*S7c18Y7YgWKx~At>>sLl4oMKt|?u{!D}$f z;Q*EqsFh~r(#~h#O5WY0;&VOB$LsR4lc%Ca=y5vG5Idv?aKN7E^tOgcJ2jFn2{DIm z`UFX*mxxVTJ(qNMBj(VZStsfAG8!+HO1cABS##(zX%z|i>ZJx=PLg!5V)enHoBW%k zqvKCp4mx=y>E1`op(~^VJCLVOewcKaMbbTnn4-f;j&6<7sPu7>X5-1y_(0|}jnQ6o zAoCDl|9v3yIgok|WKz<4kznCT^<`7y<07vCVAw9sJ&@^PrvsTxB0r$v9LQvtJdpX4 z7J1GqlIb(;D}(NVOcom+3XnRGNhLDucSy0y+X0R_kjdci-vGyaTttG48sH_&IHT@- zT!g`y4*={O$Yd3%ke&mX4Eqo;c}Uj(HNG{+i)iZOA|ysGo;jPd?&?@*F5};G2UwlWB(P+> zglchTGm9u^I-6N?hnX)3J%M5et;-YGuD*g`Yd4P1Id;_`fj?T4+!`b1o`gW?0;<)@ zOTd{O(px5*s-#7=DMG&y$yKo=eKg5AA_@B&D$^@Y_yqtdO|pl(Yur>XPV(IY-0@e+ z2y0owv~lPR_8%(=d#jz~sKsbxKhO(6h!nG}AErl7= zf$&RNF*A9rxYS+9sjz<2pje7ug=c+LCZdc^JzPpg5lv5^qyrU2+iF@A=X+9x??Xfu zPHI#*94E%pk0i%o$&p~S!S{UFaX5aJ<2Y=d1iRea6a|xx1GSI7^GRjWcRoYS9mgS- zML7nTKX`9KUkK{+@(np%A zF(SDtWGWv?*P}?@1Rv?uPUIuym|c1(51{#U#{+2G655ala2T-v_5hlL)Z+nA(rQDn z@QE&J7+!650l=_boa+I2*vSK668VuV#{*!P9H}aGRU*%MMKXQnSm2y187wxu3n1kI zP>Bq?FDX{p-!0AqU~srAz%d?x1m6X4j0eEr%(DPH9ssLIh4gp;3>yfT@&HbEkM#gZ zjPd~VQ5biy56wrbum?b%C>g)(((-T*i+1mJiX3Yk>Y6=(;?9l-P!$;%_T{7%pRv&% zz%G!eFLzz(lK6uVp*#QrOGf9Ej;mUn2e6ZJCJ#Ut!adK!9>7i%+wlNKKrnj%j$Qq$ z2QY^8c0B+}T2z}J55Pl09srX}Ad+y?LS-k#3DW>jIA#wo(zvN!oa8$Sobmu>;DD83 z&t`EMMR6X01djkX#sgq*=2HMW9sui@`4>Qr2f%ugS|YIkm7_fX2Gi*;3on&Sab$~x|X-~lj5e&*2e02n6w)fEt{Jb+KZr|4NkxSz&#H9R<$ z<#+%r>MP1tdH`DYtc5UR@&GPn#mwZf;!=x{Q=#1p6AXTs%P*Tr1Fe>IDH+-WpyO-W z1K=)FxD6uCl9TvoKGUZjFLT4}jW7djM1>JuNQL zEQgF(7Bwxt0=)JBSR7NyX|W9QRnuZ{HnIyMyVz;56DZWQ_#`RB6i$64z7KRYWI!GO z)t2i4aLJ_pY+0PfQ(x0!HRi9F@R(1l3htOM552Ky&!zktlP*atPujV}e1JZ*bJit^<&is=n9~BMuu$bZoBYzx znN7Mtb;IsX<>ixTdN%3a-^9-cjm9l%VjztAnD>FmOHVn>>$ZDXrtBbknmG9Yoc$6nE;vO%RcJ4a6Ld z6C-CSCepJMClahH#;RFr^|j6{)nx%Dg`r(hVRDw*<#~Af9ymQq{Wi*Zc#CCGv(%i? z?kvUPm`cu4iDR5uYA0nk3)#iaQa6G^%~Jgw3X}5Zhc{Xwbsyf!LwkC7>#>kcPk$O| z1W9!s-Y8{_AyDobs4gGgrXp?FF3Nd$V_sf}l@D+0f5Q_Q*zoYS2bI=o96h`(M1F>& zlzMn0k$8AJavi#ZTHxLckn`~N0GRmUjp`%z;cYAEEaJC_$a#2U@M9!aKfDn{1V4ll z^5Ja<(l(QErwR5%=JMffx5kL%&yb&bc+>SLl3&Hc+l>?H;jQqQ$wAR#%KtV)Hv3DN zA=`i9R*1-%`mbgvxp{%*u#Y(stelz33?G~BnBiME|7|^6=$Ii5KiXNMF00M(ykbJzq_z*c$)<3;zzz^%6boyf;83$BA9O|AAiCz-)5PxnGOK z-heBT=`+s*=d28{*l>#lj+aO!!rlN$uDk-^7%!2*;dcR!Ss9Sv+=X#oB7-w$0ql5* ztRiXT@e&#KAz;c&yb<*rvo}B}eiMvy@Y$WVL)DfjUyk;aTrW``3un=uHzBRP?UKau zoViQP=gdWpb!HxVHGKg5ow<(VcR#ejMgkRqk6&xYuP$iSGQyKCiT_4`^+p1~lJOGd zh;#fJppDq^D|ytL9lt(oi+Upgg4ywNjPPF_zi&uy*YTsIMOE){{5&MQkw7Hph$MU% zElH!bg^dINu#rGGW)GLULE*5G;Nm3TP~eo~cgtdO{Qh8Zj{+Ry_(|~J0LLsNFgUa8 zB9G(8I%eJhkmLBVE|j%MJO#LR{1_ajW6W|RLD#2iL2&#YSc;yFjRexpZ06avVQ~$xc`kVwK}J1VoCSMTDaohm8am$Fdy9k40TWdB|l1t$S8= z*gQFCmoj-~a!o#KJxsnNt+aTTR$6?i<e87ThO}Y3D94#&UfwO2&fHBGgxG{if-~3j z7IX~!+72m1eukrza^^@RoVj*uU1#nVfE;IT5}4STqxy(-=57O>Mf?^KInEq|H;`EE z%n?Kc``#*x(YD)tNZU;IS7|T?j{+l|xra1HBtM4ylryL6Q6&E`R*2u$vomMj5fl^g z`(I|rrhF+gWScJh5h4oj{8uxS+-jm{js)wUdz2a8cDG}O8&|?EI*)P8kcJd(hSUwU z8NRDo4jHj5$_z6hTd#bvIHrZkgEN-k@j+ z1<2W=PU|{zTuiAy4~AUQ#I{v!@nse1oW;^}hxE{MI`QSpZLtMEa?UipOC+$8_Vt6x zN7}NQY@heJKf4aKMm|!*HUG;;`WmDjABmFIw*(7U-=yZ3)#fh%7`BUZeIyS%`AAIi zhbxkNB!;n7hG%Gz=e#1BKJyje93P3rhBNMSd?YH7VT@{u;d_|##Gqg+34QW5xij`orM0*UgGPP!!i z{t%&jBm&#a=v?q|%Ms@zC7_MiN75yBuL7};RKT{Ve56#WAUbT}7~#MANM)&AT_1^( z7FE5+NAi%6kHjS9i6s0eT2lE)*#IaUvxooGxTy&qoaF1c+3}HfqVF4aRTj4%;20lC zg3kaP<0CORv*`mKABlC$Tn3QiBe9;8wMcvqaP1>8m@cX*A4%7zTl4Ud#&4BA5^3l0 zk*1I|$48=+HPZ#bM`F+o1af^OhRII&!xmXzIBc;TM2en8gexOU_Mf_XaV*R6kyz9! z%2xVFTKBAM*gW|?moj-~a!o$#7)-t-t+aTTR$6?i9?+_=@L|lo+jw$XeGBTtvDQoF zrza=6RH=O=?t6vlj|9a&{NN+Sijh7N6KNlb6A6}or<$CuebSknny%qi664ghnkF*eU7V%p| znj}sTM32 z3toL+fX4g&w;8f2U&;*GrVGoy7!=Rr_b+BBxs{K^90^v(L&^-_Ip~<-eq3U;*3NLu zkcJfPBT+ZhW*C0OF~e9EWrl-**FF-9V=8He4+5vmu=Z`p?ha%ZYlf#mp?sv{q!3d$ z-7;}56u)>t`bacbxIPjWQ|ixyA(u2UTH6-0YDpg{mYzGLhn~}kdH9@DCVu22X?m9k zW@a_Tx8jZ9kh0%Ee|q!M-YS&t-^SWQi1wWd|C*R88Wbjpj88LY5za8_ef2YNtJNG% z3?uNKetMfd^{S#Lhgw8OZ?P}hMe)xvxzqOXIa}^G9d_P}WY@McEZ`~Hy#qyGBqAKEs)dA+axsx-ZKDVE$)0r3Hs!BG zRKnF?;+p~;hs!BFqyL*hu@1kEqxiG-(}1+-TlV}M0Y>wGO(GQH+9akO{GBmdBQuzIxv-w5IzYPc*dafG|$P+}2J0WA6+Pqh%>Br|@-xZjS-2J|oC zmw@%#^4vVvONztp6q)Bf9$7I^!jf2DbJ1JY%FE-Nb5M*1dmeGR`D zFlUt^j=zi#py94WbTo(;0U!qaI0vnTcP)c0J-Qe?2J{-RqB~yB3uwkpBPrVBm$G6# z0MRT&HX<@`4E_}p`XgU-7kDNiEySQ`5rUvBgb6^#)5Hz@Xdt5BA~FS$!Sjer4C=ko zz?-*SYX2&;N^~)@Cw&j4wdZ{$P=gM{;hQe#m1#)_Z}2>h#& z`x+2T10uQ~k@<)WT8AQNGA`+1Gbj2Rup4FBu3l}3Yn7NFiMhqJh8V*p0z9Zo94=$M zFA2E502gmBa`{;9w~5g~7s`rf0WYRZwNOTW9*ouiQs!Cw69i20)Mv(7bMW7Q4GydU z^DFV#ACd;Y4p?+GBz!<*U*q4PJLAX#CyeC54-nnUpnII?_TV4?4XpvYo1t_3_d$w3 z-TU@Nyv6xOGZ2BfjV`c-e+ABLUiMB<^v5r`IFavpI-SmZE35{%L+C9)(*tNx!`qT| z90SZ{KFW~>KPyFu+o#?4h8ApX~1fx-~+FPM7 z0+jjz^t$!`R-s(A!hhncpt$~Pm+gPmD%UTnwj;7yN!jiA@2cJ5cdJ-69@Kz*3 z#$`3{R@MA25M4e5^8Np==J!3-tl}*H0|{sOGA{b&Tq%dJYtSo|Aw7KDuRd@&=ddnh5e#nxj!&? z0us?5T4#t^6xoKzVnhbk#=rBR>2yU#bU1)l5jGoq>+&`s6iai z`putoO;$YcFMk^pg#-i}xZ{5$&q!hcUZ5i&2IvZ?8Y>`^1$cpufEXYP7)}~A_6iWp z?gcsQF+iC=m8+wdy@^pZy0C4AxEu)laV6)JMu7td09i*~pd%m#=nA;t6`-5h3v>j;09gQ6@_w%XS;=0I z!yW^a`BNpo?PaG*E_5q-gwbz;LL<7!jXvT=_qowe-RRG5G@x1$5^~&V12@`BH*<*@ z#iVXY-^;~qjgNx-35!r~c?G73<}M`Y)37{uskkWI2g-II2Sxhh@>|F3;jJ!)V^1Fn zC0DuRXLwl}80ayBrKN9|Us@>?pJ1&KKW9QJG2H42i4b~1;y4dI1%8UhPDp()C-S_g zC!~LoS;cf^syNG(aZy9Svj-05@hA5xEhzafND(UxMw^Tg>6m+#i#f=Q`Wy!)DDk) z6=(TROSqb{h&gu3df{|X^gZL5vi?Q>`<{kSahCsqgsUlwm_^~U-v-5f)F`Xu=V7Fw zt}TCqe!4@ zhWL^q^Sfn;z&nT>MC3dm?9We8I+DAdaYgA$(E>2CKhNm-3e6sK&C->lH*55Oj*u11 zgaUO+mx(SwE`od9w&T?S2!l*!H(8m z3<)0W2#vu&=wPL-^n$zsMby{FqibUij&(ii)inl7y50_~t_b#!JnRvgycsNfyUcazXO?ADsos7bv^ukzMS9i|;}j-;Z=q&bm1B@;6E3y7;h* zLaak2VO{*PpM&B_{Mrs#f&2_dDYY(6BC#%B<5zcG{1iaWy7*&Y;&pMVkJxqbv!n;{ zTSVlni!=BK606t62_k|mf6?pWzaecinOqm&0gPN1zo;=H`5WY?*2Q%_isaT<7r*`j zuZsu&2#R9-aCRWnmI|i7mE(MCg+HcJq;Aaemr@EhgW*eJIvmHuv@o#|e<>65Uvx}t z*Q03jc{?2wqwl-uHE((=fi|%=n&prY%c4wd5%Ai?SR7MH6FUr?TJx^_7_wW0>|#wU z37RPr+fNEHg;UnVJApp+r(E-#70WS;LjLq$547 zh5G*`M0K#C3%!R*8b)_!>2P|L9v~yOHV^EpU!aX>R(T1>><6~(;1Yss5U*PGdv`8I)h1GAd+yERAqX_ z2?qdBIA#w|(zvN!oaEaFoI1g}0J}4WeVE0i29*iuS7Au-Fo0uDXD~SPX@H%pORQt2 ziAr!zXRw~6mPqUkxIUf1;4p?=bvi@Wr(5$lo$*E*Y7-||NjuN!jLhAT=A6!;l$Gs* za5{rQmlMc6oxw2KuZkd+#uS{+r~@KJ&mzJLHLj}{$FiK$87!&+Wh+l-Xx+0m!i?#} z#igv6nLJip>M7(@*rlv3HsOaUz4i{2(Xp#b$OvTHFH)H7!0%3NeLKABjDn_&g{;#{sG4-K}mOE~Nf!SzJ!NO{?-n&YS+N{4Vp&vC9|B%`04$EFWKo+= zN!3L)u`*!!UyCp5K~SioK1d2Ng-Q9-Aei{$v{bPLKiYM_qK+)8RJt1$CPd=M*{NdJ zEZ|WU8ZTRX?7Kcu{*lf?l&`-FeaB_82xHM#i>%p*iNwzqq>8TiT|x%s;pL>XD4g&~ zig*^kjNW0nsq^n!WO5(BcbIl^ z94jyvjh8*vpE(}nG^%8e$LGN&QYofU0pushCMlSxOwW zzXZ!5X#m$IuqeC`u|;A`*Gzto5R$5aXLlYW4OY^jf=D`I_Aob}nt{6)86DW%(1Kk3vbp&sHp z7%mEbM<#hqkkQ`%V@8rrW~Abr(F>l8Uf_(xsD%*x5(!`KcTZJtMbd!emSEtm&}g|7 zFw7HYt(Qw-3D%aT7>x^t`^#SgOXYw5e*hZV40~>)cn^*DV}AmSBflf!Zuq(}I*D`U zjbxm>8CiA;8$CYY(UDH#3@iJ=ZDMEKeJDBO!<{OCSblvnT5q|}H z@R2h`>8%hyhFyrrH`kUUd694JTTLikYd#V(D(bxm70oWMW4KIsyM8`G{-Aop5s1+# zpoI7DeStr4E__63KjnvjhG#xV755BF5D6d9fa&uE4Hs)Y&m?6&OcmeY`_~B{DiU8j zNrPG-`SdWpfO`@W{2p{2mM|CSBQHb3M>KdD_+G0^A{uT6_E*AwOfPH)*79Nx0-L=b z*iU#w_XQKY*l&RCLD)~{O38^{YzDr3K98`Ut&-S)7kd@3A6LZ4`#JS}iWP_zlZ-K-LwFJbgb=#jb$6e9IG{5Mix z#(!VxgCCf}pLz&!Gxc@+w?ys<1n2Qfn9qhI#pGT9B%O?Hfft$$NK=9?^g`PJGK8Qv zc%h>JSxnGHUg#=7{_2Ytz%KSew*ktAe>@=B-yC>!`{ zHgH8d1W-2YTiCD_bOoSnt!vp@6?7kSCckT&|y2FEF`^d{akRp5Z2H5}> z_vG9$8hm#W>_D|m?u~$+!7pJmZKfJ*`^;dScnLO>Tl%2FKP2&FTweUOz#qpi;YqSC z#oqwU?j<^@iFSF2NGp{|8*Hyd@k`j})}KY?61gJ)rY+Hg7fYa)156up2``mEJqqwa zLcLr9^#;J-5Ndx3)XxAX9|Gz?2~-&1+X!{kgBqxdDUzo(5#n@bjKxPL(paE6#ZEe# zH!*;)2UwW1!;9go4y_Xd#h$0sjrmR?lNfc^d*Eza;tR z_f)ghE+Nsd;EJ zKD8cRGL*4VvR`6;Awnhh3qX-i^SVMQelV;<2oqF+#n;&Y1bl#hFyS-t8@peD*Z-~#8rA6NrQtR@l?8t zj;(Z`NyX(#mzLNc4@1Goqme!bx!Ou!kWNM9G3`{)%O~xDctMt!dL@uF#6}+1K7|L_ z7f3F~cFF-&X*ft(im6LM!KHXYQTXC0YLGIKr|=pOdS4pP#Zxf9$#!8{Lg;om^;?N{ zX%2KuyR;!e9f-;43=HZ*poX8|d)PE5dO8DDgWZF%WgtJUT^y`xmrfvwYnM2Z21`KV zX%`nA+b)Jl#r3pH4!)2WjO>hj{|dLul_JPeucDWxET#7xqUE(NekTQ|y4BH<-b+SV=B^w~_FHB1a-7X=Bi|a2u_<0AZ zPoTH;B`NQ;3xm#Z&6oP8M7vNm*ykAA2-vuGaj>dgrh+7{UE)X@JOL6aoLpDn|Yo3%{OZ^E*eJnq&|!rZha30LzHAa8le}K)E!mlc-F? z9qt{hs>zKYiL1#tk_M^J(o>TzI<_YLd^n71a>^GcF}cwM$F!ubE^&1nD9ec)iR{9y zUku`9ZJfG-I~6&qA2sN@u3a+;98;SBNiJCAb@sFHq~Rc?Csu=`MUESG9_TH0v?b^b z1!C`dN-n5a8)he3tEg+CF-AwW>=z`>!U0veF-{GUTk+&m_k8u4LRS2^0 z8#$q$)aWXZeTX=w&I6L`{~cBTr5&U)c9Ir(&#>R5I^yS+8Vq`0f%su%N+VEl{WCk! zYHhwPPuj%PKR>T~>wh=N<||81{WFMfJvH2rQKJ5-X!c&prD1NkMEyHhRsS!8B(DDB zNE!@+mY(`|(XsV!ne@ySTmMW;>f#eOkxJzJPwQVbD8}O#`Tn=d@o+rt&%^kL0~R?V zKXENjABp&UO1CrkVWDWQOwbxjp9(ABb+tDd(T$iH3D&Exll}HJD*14qhQ^;r)DV>d z$Af|%#3KWZK&7&4e1i0h3^Ib17C{tE0g=H*xY7zF{Jtb_C@%(53wsFZX+Zef!n@o?PUmPY zDz7WY5zEXf6>Zv>^fob`9x$g*}<&Y*LF`5G`P*4 zhzP9_&z_|sv$}W07lk5IBl% zM7kwKzkjxzXbE_9HzEay3`&Tj%GhECqDz3aiL5&!6%ZM=3$k+&8PFSdrjGk@AhC;8 zKKd=7#Q@0Do7bq!Ok|eP*{T%H0=GQ9N#`cFc+uUgNVL*(<<#Lox`ehp7VR6%H_-;s z^|c)eg~35&6k37kci`k}Y{QA0oxBF+%t zrQ#vr24Hyz*og=a0gLxZGH+QZkuNw^R&69b=tfeu-xVg z5aBj|8j;vG*Gx{Ep8<)}<}^-(RhzStgYD>7uf!|qrC=q)hrCL5M#>o{G_9lLJYZSL zClO&KzeXfhNzLRanfYp*l8wDe4z#0PK@eM$UJ6!nK1ke}dh8%4lFDAIU=lNxr6aa zY9>d?P9TX<@@J)FRq8ms?C2a2#MY#jf|cA35?9GDkaCpNw2qP)FmYD06C$kSTts4P zQZqS9J_(W-B|Ca+vWFeb+!wE;mx7h-3KCbz`A9iRYFbCh9l)}Zrx0N!D`29ERZ=rK zN*01dD~W-O+`8-4Ak>TMa(q%Wa$Jq+g@`y~x|fQ_^hLn(nEnhRJf>&A;Th94J?Bhg z`dN^1&V$J7Tc$F_^=3J?_W-jyw(nAC=BBZIG0^VV{+vSd6y448j_vyu%5m?yzp2Ld zEJU2KU6XMJ7~2;S(iz(id9%mZ{w;Fnv3(aJ?%00BOXeBd#msbUIq*|KL!)=3AuYH| z&%Gfz(_-fL8eL#?WuLo%+;~Y+AW4E)r)3FE6iE|WsFWm4h-6lG_J*3>@)te6%zRhV zw^j6Q>Df!tw-cFK_?F(OWEbZxz*<2dO3I;;U!qerks#tZnG z^XLWh@$3{BL%aTC=`ndRKQE5CmD0H{U`sv+&%J5Z-s;%4DO11fcAQ2K!TYMEh{kJu zqRddbwQv1GPi`6K0bE4DYb-i%!vDk)qe*Uxc$>f@sV0^fE0J!v4(ZV{{Tb3XQ+k|C z*G5hsQF?+*PeZ!edZhV5%Xv*ec`8Gi^*ie|-8rR`JQ@o9INTCtW{BhyP?ip^m1&lo zjfbR@C`p-C$mxjP*$1fXA0sM~>F^HapVTs$_R1*#q}I9Rsw#$J^J9l06;Y8) zcTEowRjXurS|rty+T`{C10Bv!8XT9c`JdZb9PD7m6}Ax1S0ncaCD?F zX%R6{@a5S}ZBc|@(t4NPB@!aXdaibg z2&4x6R~*>j6I21IX@21g9Y-n^JL&ejct#eNak7d^S|z5(`0uairy>kofIx_(XI zz!g{vqMA#M_`~POgo&hqznO<54Gr20q-icfz2p=jn1$ zZ@jSi6Y@ku<=62v6d7JzLtO;Fr=ci`ollH$;ks`+4fW!ulu2m<2gZ0B>VA-@hWgS& zGR@Oa=Ru+xDjocW%^8NTdP{*@`e_wKf>lE;15P!Rm*s5@?p%^3=WVBTuLp3dp-S-G3!G{ws#H~ne10vqq0+45 zo#oJbO>HP0^mWujZ>@T0ksVa^8LI$PL+@VFjs9V%O)rQYdLKgCJM=c`6g%|pN7_5| zc0$gcp_ekGv$y5xJZ+k_r#tC2-P`~$U6M)80$2^b7)~3uiycnalTOZXN-66u2I=9H z335-g*28J#FR1w+Ai`RRisWvHs^Ro{MAdNGt&JW|d%6sRnc-njso|6s$<%Oq2n=#K zl{v5~p5e50TX#5R9FeKvbT4q;;gqx!e7=~k38h&l3R6Vgv^q-7r>@94v2DJ zc1;m!O>F}Qsa2vmC*;AZ;4eV8!FPnyTG0t4NfsQ}O#$1{C~qeaZ}4jX>5Ic@9jP)D zk@yM6d5?2!8Gl+_0eIgta zTVp^~OT48Sia&B0PBTMuP^p$^gQ#kW;-0!CWDcx~rzOq;uO~Lf5t(X<>wCqv1ZgK6 zTg(fqk-5^uX0r^cIFWaDraT@_6Q9Ok@_4w*6n{KC@3Hyvc=#n`P##`RN~6ov zebi(xYDHt}%5%1v%8N?Ih-`Hw2QuS1099A+3xGxc(3O7$*y}|#d&G?C%JY%-dQp3k z_IBmpkoI(C%8n$({s* zY%-YxtKw<0Ux3$5#yBEVO?DLuOBi^(diQ@8KU~T93(sXEji^-dy4h)+SnJ zw)HNj^CC{`QOc^#Al-UQkb5_d0m)~b7rvp^8$*PL5f#b$)4*uG34p5Bdm0Csn4$Q* z%kU>NOa+x{y;+E=*1G@(*?KYuR>jkLO`*7MJ;o84YQ6cud0UUP!<2A9wO*gA+pAhZ5HSGPH>v_?Vtan_3oh@bn8(eVp@;Mg4H3-)A#Nt-r#5eW$RJS zwxoPm1E*0X*-Yt_1Fd(+z&QZVaQPaEa$1j4)^P^u)?* zZ9URXI3K^vd#|_r#v`>J9i(zwkH6_?vpCN;9@DI2ew?oQuaUDE<)B-S5~}q+#DN>n z$jM~EFr;}}uNCnI`v53gk8-vpVna$1j4);I>~)?D$L4pG&5J-{GaPv*d? zcv^2Q@VfOFM`Wt?J^;?!dZe9jJ_?t2W}5uy6t$lI$dh!p_+FdM;;0z%YFpmIx$>h^ zCF%LoOdfhp=k3mxADt>m&j-Fd^qkHciw{oGN2ka=)cUwY0tcOxo3WK!uFhOoLoQ{&#GxI!IPctH1gec}+M3wclLR48#Pn;Q(eg9#X z;b~@Q4=QCnoe)*lvla}}dSni)ipP5123}ha`TC-D7vn@CK-|d zfq{^OB_R6}1%mARA|fbD5J5<1#z0V!Ndqb(Dr!WcD5y~*Vn7LK6crU0a97*_6%Z8^ z0bjuv5qI1-gzuc&)jc&My#GJXlgjCPPu;pzU0q9eS2exECWi0mmV4)N_bV4XyA;N* zeZHt=)f02EuUzz)i!WU8D;NLf%j;(bUygfB#TPF4l?&De&wh-=+OV)e$ZC$-@aQD3 zHoOgF)P}3+u~!>-plie8jJVn$w9vbr(5(&g88=i5Nw~FvIjQF|M|i?HEcAN9^veac zVNXtcZK$Rxzc%nF_=t$S+8~5>1$f!ZtqnK+#ME0IJ=n3{hs%yh`yus$y zhUa1t-jE3U!P2$iAfT=d8F0+44Q>kJicuTJL+{lF(UGQW!!qd1+Cc9tf4}`6!?2e( z_w(l2_4eC#+Y;H&yPlYf?dRR&b-eAv{k;FpmzUuTz8v@1(aqh@o3+8SA0x3gG(8D# z+o3i*QRvl%tw2U?XjIdv4Ls1bp;5EA+90%0fhTlpLo>z=Er-yp4a`YBm$}yy&S9a~ z6Q*A-@axF?m{hgu-+mAN^R=s1!_-3cB@XyjajP>-)s8W{A~y z?fLTW$ujx(RF(XD`gQ!fNp<<4j`cZEqwZ$_T`~T8EPKG;kU}-8E|#baDV&{)_o}|! zmJTSdt6lK})b$pC(oIvk-R4uexs+y54L!qw`Wvshn=pLPZLkfgzUqGRA{2E3OGoG}5sJXlSKV|# zebvoq<6U)b3gU`!)qMrMch!lGG=0@gL#E8Dj^0_xw~TSyV6-*=435wB=Kf}`c@*3# zA}`lMX!p=SFV{ayCO#(dsAQroIyar`y^!i$Hyh-&HLZV_#)%O+1LAX_fI8RT0P0*X zK?Jw0aZ?aij9jO~aWB`RBTeUeA#`T0>7A9_;%qmmun%k zd-QxS*I!8{nvnR5WWxJ6En3*-km_8wy}-+L<3E^diO>enN^b*}&UI%%o$FPI;O5#* zL0mC%-Som(u0=KW%v>`uEB58sCdm)o5})h8E;Mt^qu?5iLGO>unk0cYlanDj; z*X5AvTwmrzC^{00kn%Tk%@=reuJ1wwuZAOnTf^NH#1$jg+oAVzEjrS4t}SHB%r(8U z{M(n-&FT#-X#5#}Lq_j|x4Nw#9c$}HOIv@l%0y4npS?+*!OM$v8+n?S56(5@4K{d# zWA+A<@pon}AA8Fdu6Z~V&=;WICy!uT z55D*7Zk--l-M60gE&g-_KEaa+1hEJ_a<^#bvhVwTh_B#doV!IzUNp8pO;f&iQInSE8=25VPh`d}2q1|&wyd)BkEu?a}s z-AR0G?S45W?$M*{M!oVmV`@Hv;_vUC6eBjOunMR zFxrDcK@6O+l$}Z0Yr^4inIeudaQZTsPCZd{Hqjkf37>((w+*8Eso~2I&NoCNV=(=iB~ugc8Ti$^ewTp5l*`o1CnLfx)~Pj&kl71|>xo3h zd3W?J9)3#1m1iZCl_}9Ma43wfX$tlCR6h$;rWi(#@|c=3b!syl*Fo=C@-h&Tl~5|Q zv?AO9=eaE0Xz3K?yJ}H>TE^is$>>Y;XgFgEI-7_OIZ>PlCi8Iq>mWyon)LzNf*^V& z4+SxBsECqMrUWwZo34i49qy3eJkB_Ro+IK80}hcRXbWZ6^UXVX{jMkKxO34!m|_3_ zMi*r@ZZ5~sUrGFS5Y)$r$cYj~i5zaP8EuGZdrA6W95RSvDsGifQKsZrG~_tkYcEQT zLypr3iAKkhEr>yxV(3s9ok@+2D2}`)$W4LDlt2k?rMie}zDhXrHgz7hAb1MG;8B&D zmNe_$Ai6;ON}h#mv8>Y4*EH7Sm8+ZH#!DyAH2upe;giP_X1wG{+G7yia5@h8-lW3~ z8657K5G6trMqzC{Z7iYC;X_fU2@h8wioc$Bcq8qUd@?;bEC#=rkQoHG-&cE*J^4n;asCL75WBUG1X3P(xIvX|Xm<`yXty^hZLseppfu#~W@r!olA(6vJc_n;<*5Qr;QEqHdrsVisawv2r z6OkxvhmoUlNJW%^L(@^Q&s!eOmVA09LPF<`ZxF1e89`5wBSa?R3>%Bc8>y`Ta&o`L z;Z7bBIec8@aM^s6_u{5q6{2bjf!dBnQ)56(K!(kI{Dur zI6W0+1f52X5SfUx8VJF7x%CHd4$`Wij~PYcF-<3ME^H;^j%G}&ej?QwT1ekSNEqi^ zFC_9aIIVD3xI|ErjYEl7GmPdrwI{-7@Tti3_hFeu_A%A5iGBDEQ?8P^BE5t6P0p?!l2^#}&I9R{d(z;$2ZtWXP~>hMuOM1Mn$Yp<5F z(rY0&urAp;IhYaradTa3S8kWgH;2^_hjP1GnYSSt+o9YZshP_?+%uH=2u_P4o_wV6AB zx$-pkyyr5vp03NVXhY^6$agUAls7GB4nXJ5kT@**bS{PtoTbKbB7?kH=CV(q9f{-pe`fS4Fgx!75vMgu$J5R{Nz zp{(`b^>=xU>ea)kln-^~j2fhoyOotx1B$v-mi}8=p>9Gw>F}{peV3|il0Owug=)@& z5sJkhJV3L8z6L^$c%y5HI*bG7Ldje^vfI0CDUpOI6{<5Ct)8n;tjC}~rTIPTVYE}rfRkQA@D?MjJ8q;3wT;T+ z<9X?tP1*&*ev)2FaMaaTsIRGv7)o&`>1T+KQ1yJGszN0{3wcMk$lrw9L8+7a{Ib!g zRJBQ&9INFl8i+F}o-Xy3bu`ET;>HwT|1WV%iqHL*kq#8UD5oQ4q(XI}cu11S<4;)d zybzLEqRz)ZXF7tCnFu<+v!yQ5?!##R@vT8Jn3D73lXW+VsZ=AVbK*VqbYrP2JYKvC zHHo@&jUqb&58`TRpdOrKekxTl$*=k@xusO0rc-={4D94W4fa43WUC)zGT91sF)7!m zNst(n>9=68nw(sz=2HDhf`?+ILS0MU8rcvc7S(GgZlLl>#mQ%)vQphj<&Cj&murEC zaA*m2L)}Z4R{})KDGInE|NOaSSfL)E660c44mpXYu{Bh(p@vcdiLO&xM>&ECCwAS=mAH+c7Z{hj=f=kH^HCeSqQ}F|lTU zL-9W`vFYT`)Rn3%J_43(%bA%zuM{UQRH6Q+`gtW!h<&wtf~Nl{H_<9o(sST!P?0zj znv*Ac?xxRz?iCD{IyOva|N9bPi#F*uKw1ZpJ2pzc9k4cFi+0mrKra{!q~8z8X6%>S zv9V0yHv+ckkp4WRubrx_j!mQwd=;?8DPnUnVt4K%(iw#P1kNMuFYso<0qK9kLPNrn z#j7m97Twb8HBeSNN>355+ECgfy&a@IDeWlkbf>gedVfgIptO^?b2_Dc(#Ju1E~V#7 zYU3##F7WGzAU!vIHVCgHZ!H_8b3C#Eutodyn;|``CZvsJ{5ArxMQ(Z(q|rK%Hc4mo zzX-5JN12-yF^Mxo>JW|)copH90&gNbEB$j=xQDQd%d?x;`AFw7@ww8C_)oSS3VJ zqB12=G`#)N`84eJf@TfjsaLY;mdX-jZ)q)4<0!s*IpR695mc%O1YPBJhFhsB)diHe z4I*1baAr_4Lz+k}nM27;Q*sR@7n_nBD4AtSZl&ZBQ?i7TOHIjrl*~3I4^ncODS4cd zIi}=UO0F~|uTpZgDcMBH{FtOdmE-#9K0GNVN`Em6kIg6@uw12Y#(~9yVVFvUx(~_h zj%$)5%I-t0%sw7IJ=MBb4ZuA$yVJh!+BgKzEt!8Vf8;~RpCl=RARY>hjow=oI((<}i_qU|XD%5)F+PdEP zXV_}?3dNgLPbN^=m3ux_mho(ut)ngD=OZ%9koVQmQojpYEgGDlK?SD$a5W zPtj$%ASzTk4@V}&-e#&$859*HCA{TSp&Cg{w_DRy^(2ZmOXP&CRjPK>ZIur0U%E4> zyGjN>z7C~0n&NAuTaAfjvVGYtb*(-r>DS{$tX3n^tp4Yu-wK!u*so6K=J?m_Aew>x zzXpOUA-5bnjDfu$DBCIRfQT#9ZEVH#&o>; z6z$O$IJWE!wm^UiLG=>V4hPO$zzWrv#BT1TBPUc0HzB)Htz=TaF^)R{W4;mRd&U{& zrbnhI@20i()TFt|njUtd{1R6#g(nGAsBVKqxfrleqGRsE_vjc@S6AQCa-9$5I zOY!QAbS87I%hZ+sc8cy0l9nu`q{5fDNjIB}O=0@4*EKU~1vsn8tBmud+2fSuDJk+G zs|hl=jp~tF^?td0%;f;^cE<=<$Ye_F7>PALi9!tinM9b92)I7%Gu2i29zbK6f z10;Kpl4}!7r9yp2`FO(}sb?|^tyI53IiQ{7JtnSDM;Rxa;Gj37ZCKB;`cE;GQZ2nK zq`aJLh49z^jpHVn)DXHB)Ngk6X0q)mzusWy=}KE}i3Q6$m_F@OgJqBp&eNL()SeepE>MQu2ivYmi9HSi?kO#u`bWmJB$!3}dzUMZw+Q(%R~~N+@|Bd2{I{J4UHQN4ta0TDb}H3Vl;7zWlvkIY z6LEr-O7*IU6O2@-jTAR@8&#Tue_IR@%|P^_A)*OXr`;4C^izjqzexOqA^A!qewr}! zBPIRZL8(se4@0Drvsl43OOmTlsT2)~ix@IQI$|S3r2TA3(Uqp3?L}hx*;ynpKXLg` zQf9{LD-tu-V3C-yHZdz#o3XZv#Ei8=B(Yd{2ti37cTTCxiiQ za7AVYFQzCd7SX#DuX5#nZ0{<(!Ik?aybJJl%7ca-$qsIOy7HJEEnn@*|7GV8D)7LN zVMmwxGvtTdo4md;s%UL~P=U{Int3Pf^QQM41yn{*^2DllA03 zxpLoxC;yxB28JCOl)zU!*MdA|N6Txv@|Ybxh^bHcH|BNJNF=@iv@I<};zxzI&aHK= zft_NhL)3w!PO*d`%5z1rh^y4Eco?bp5&8SodHa&B#(1;ATBSDCf|MV;cco_n;gtpq zxmT&RR29Ul9>7i8WVD}HV1++5^J=I&V$V8zME4A<55YWup#Vi=XiAeACFho){REV> z819y!4E~;!W`7PXT?sc!)c%t+#Ln!IVbOj3@VWbtwv2by(4JST>*v?C&SMU1<$8H( z1~e^rTXH_$8F63fs#foV_H+tpr~0&^K;xTScZIO{{#LbWczs&4`(b+1&$w7Bs`=%Z+F3YD{F7_11e@L$9YJB3$|l#P*gK$P34})= z7^Gt&Cl<;f#ZKv&VKGbLD-ev-+B|Ca2Wr{^Lu7xQtXcr<4#7c*(<}k55WCRUVpN(9?)FtQPn&v zC7ahX`5@gtHu}~ z1>)FEUWVpt2qV8B2v;PkFI35qC#ims>KX~^;Gkfg$SG9!U@!zhsWP1@-qt458Ut~0 zv$mO*P4Fzhg#h6T*2El7h2z2MKt|+R2#Yr1O?%G@HK$F^jBJC?gqdwTm#>^AF9jf6ehJgP{UpTM;b#>@O*Dn;>|d*Cj|obSV%WR zU=`d7T`9$_1Idy5abWLlmuWr07-u0^3svfWRcd4^RS!co1E8=Af_+e>-H~n2fp8Fx zW51$raX3qRBA5Rc9ql~Of_Tk7QWrt^r36NkRF!Oh4X<`W5&2Ba6-``+4<>0dcth37 zIhY%+mmrgqJ`lq20DL#uWXnmP3}GaSAp9P_6dkALN&gAL$PonL58;)mmXm&r{-%+W ziJ(-OgyJvTXIh;gF7DAG)9ORu>90drRAD6Jo%Cgp*(+e}A%O7E z1csdSF{GRe$|Qoi08;_*3*Usi&C_KhS2IugMeyi;W|}8`p>ZPQ%DzJ7!Zv2Wq0eOwdJD6+t0`DitBS#Q~A5LIM9Z3S^byBtxij7ZXGcR#i^(0I&v<6)RCi|j5^|R|6NB+4I2ijBRg;g z{5oPXVs)en6saR60A?L|PL~lIZD|;8hDWR;1*`<@X@aX7CvPis|2S&mRAX+V!mV$q+-5|=u$CtJt^#g4fKnUNX|DwyByI^ z$8li}f^rBmpG~m~AUqkz1px#bAgsSODaCFLX+28w5gev;bs*X9(i!~;1Vs;Cp{zqX zZI*ofwJCPDyiDs!$mJ(>bGzXkDwVw%IghWKCPV7x9iSL>v+yVMqs{SYZn}RDQdbxn z$+s4E7^!EkS84WzNM63RupB@(nj~J6~D*3=gx{!OB$Vr$b>Y zSeXqFxfTIB?94j2n6)D_yJT9eaa`~>UhXf2F#Ui^vHL(;lhXZ=uBEgoq(MjzLr}O0 z!9Ge$1NL?p{|LwY6?M8D>ov07PJAf@Ip2irJ&4sG@^FI$W$^aolk5keZAI-=1Pyf5 z#fTc*jd4im)J$t86ooVX#xN6KAPFw5Vb6u|S{&P_0o)Amh+2ZMwT>*~khAL)y#iS; zEvpTKL(ZvVKZ+RdG3tK+b^{b=bj`HB0D$vMqew?+O%EQbX%B;1(z*g5me$ncq%}7o zt;Z2V(%KIoX=Qcu(qeKfs|R$PatK&fBf#*>%2Y~O&4bo2t2H|6LVC)wdJk3>}Q|5^a?{}}+Itp3muyt4YzORI4YGp!@XNh{RQts~xf z8G{&-)_ed->sbIdE#z-<0}KJZv5XveeViP4joAfiqIdoPm+N!^Jx>9<>69@NKdc9y z?nrz{4~)c*?!rj?HW`Tz#7NZ}iI2}Y%Kd2E0l9_CHs`22AP>FH@r-4S#9z))yitls z{(#(6azOqrl>UIcxsK@%$d5wn56Dl^T7N*^wYM=K&w~dXkS~L9)UT+`7XZWtm=Xu%3p5vROM?*|+Y`^ih#aD*yr_RZWkgY;Rch#O7_eUn z=uRE)1{!r8rZH(3a0TZ0vK@z;cLu%Kke1s~$3>H#fP|G3D zr#0YYKF62X&PtdlQw*aFoNgsRoI*#r`&YGE*a_dzLh-83y_Dte_?66M2;8mF-Q`4f zD|4NeX&pZ$AFK)-Ws*!D_%p1+$me(EgDV51UpXPIbI8KLovBW!NBmHLdrnN?78k(> z1La6>LQBdY2rSEozm~HEqM4~Iuq?{&4_MK{nUFsQc}ZU)IjnGi<{*e}q(TsbGR4rL zFuISLos9A=1EMm;Fe*Z-tJQ{HAuAm+)eby6SCY!shYpx!1vd^#Hi}w3xbI(WGP%SZr3SKL&)XwRqD^)$XhP+6u`@ zt~a~^;@-2UO5Tntf+CrMy+np#z@z#dhdGP~O%9YP)V0rlLYCCyGdSV)$hD zKm+ms!90M+IiMPa>>SW!Hg7q{@*wviZkJka!8yM?=I*;Q?a$cE?_`=pWlD}E_?p6`E7_L4FfL?$1huL^=zk^G9a>2aosORzu$vr>R;$j~ z8?!G8O`QX>+szo~h{f!6Gdz)AHzSm4wFHstZbsxA5ZOJe%Yk$^BVQht#f#PIH83|~ z#iCm4Gg)g~=1cNeV3j)QI}pAA;dr}ry5?&P_PZI0?{+h8hGgmFQz)QlCRimzYgFH> zVDotPyl$ozxL!9ylU_HYvp9NU$lAtk=2Gy)&I!7iu{b>_&u74&%5LWV82$U>q_EiJSt{2)7erQ>$YTh?1ql@C zJ6eOnS{S(+f$lrJEL)GODsA!*bjoQp6!SZ!zQY7>vrO~T;*6{K6%-tZ4HGjSjn~f4svID_DX<$V8}BVlg24uDwLe^*)sq#0pwxKK5dM( zRvyOefR=MVJ8f`=HH9=jmHAfFCV>|N#3q49bmRs| z!+R9M+35mNDgmCBjS`Gh|Z)!5Q8$s z(4jDT6E$tF!C^lJL}izCjZ*TV8YOp~Zg$*~0Whe7yoDI25gDIu#hkm>{3iIWRM>-7_Ua_A?-BT1=R zEt(p#zGXXj6-{wP_X*m;E8r87{uTWBYzH4b4&Q7C1JI-Pmg^HR5+_hO`ytE;DAm87 zwdWN+4jYV9=GWdz97ydAD1MbT{427!TE}mQ_=uTjPZ^qFHNFno#}l+{BkiY7%dqxB zVP6Yy2q2t|Buyi1Fzw#Zvh3{7U~MQtXMlWw@M`2Uj*k}9{u!R})Y^A}wv*rpEbM2I z;1|9F5jSW@Q8sim*Y0q7hQ&g%Uk6x6(^C>?a`hKN%d)p`11JMP3s7r#%pPtAptF8d zRke2SHFX0+Iqkrx8dA?H!oX~`%CE$S$}pqi&}-tuIMDO|8emOqieo(lVp>YoFazKm0Q?Hp;Nzf0 z$IxQ%dC&*&aU%qF!&O<QrS}mqB3f z1Gp9-vIs#z8wBO#)Ir_fjO2ThQwh##-Tua4L!xK|ITdo^&V> zkq0E5ae2uD5`J#lW5~(d8;Hoa2#>(F`z=Cde6}_sluxsC#`$z*Zk#6e5o$Ogzi_9C zXj=@|f@=bSNPh^60tuSaMkGhlAhYux#Fr@vj=;?p0O8%|#v4i9snR1~Kxn@W$`1s0 z0sIAkpWNN{uFJ`}XmmDvUb4ekdmYwu9;eSt<#r(6JkMG3J37WJv;!qX4pCJ03(2L7 zC`zH?-4|2(TX4muH_-MYg8A6{v3KTBGud=3i^Hm+WFFqwug8gb#4@7p$awL#D3#}BA>}ON0 zD!~kqS>!X>y}Hb|7h=?b8uaP+AlwCl{~Z8#0&O_7p61=#q7vVouevG8ZaSZ#21MTi ztAuEcnzn#>V|9=1R4?|t`Ra?{dh=D9^yaIsO;T5>!3Y(*0ymFs*bq8Y;Wj8fKRcP~ z-f`-Dt7g#3K1HgHGG^03b$i9EPq{669 zU0k}W)K11?Q|rchRP?UuYpPz1SFKX$PA$b2KIXQRUG{n=1B;nSAh3Nm2Lr$7k@#_hboXO*VxH4HV{pr;od4Wgi^MoMiL!sA&D1s5_rsj zB(|j@iIdf4n*GqlTY=%@L>gdYZ5Uv}*}KKS18Sch0IsGX=S?u*;6(pd4C{6h^c{wo zG-v$tuD7hin!FI?oFoiuuY-0a6yfd(TABJ6LuhXTWhN;P;6gJE$UOjFeUbMO*y(3v zSf2ufBZ)lT4B)jMSw!AA@a`t>6*Nz#J-I8uHY@TA1B>K)K&}l?s!V2a{oxr_BZ!MD z0NM~-G&;lT0wBXekITL?$alp2VWFwx-920 z5%+F08xi|6xZD^(hJ_v}l_b6_HW?1P!@_sKsp2%0!@@5Zv*OGQ>qmm35gFD$00nap zYzIe%g=`w^$>6LY=m^du0EJ@_Sl8)0(9p7pvHwCc)2VHTAP?G{xAW}35rs{ay$RYu z)aIh{7g1Z;*6w^(hQ+Jc-UK730m!hh^;_)h(Np3tyJH~J{tH?e7RqZAr^Kt%?2Sl6 zhKF|oaCm5i*CNc*JeEUt=Rj@yZluO5wus}3IPK>ldn%MNsItNwxeYQC>472m`6Dyj zq1!tk%Fr#$q1$jXk)Gh?fhXg)f54ORTbM(ne3RD&yh`xuLJ?_#z}||Zb^w?rAe?9> z-ak;^R-^E8t*AL_DvVbL>|$i^)q`R6I}eljndYw&TU=h{7RfpA_J@#lmlMdpM_pm0tY(epvRH{exZ z>_~^BYSr~h+$-kb;*1F=9$d(maNGv#|7UPPx_?{V99*o1;(rV-9)~({aPb@b3v+Ps zANm(RyffT7(cnTT)#{R~Le{)eSZR%+1y{mj9|WLRIoa4K9ST zO5M(gw;`fij%1@pT6&!RTq69x`g3hHpQBWcm|d$fN|o`%<=m5heA?xF;{fR_xDGtm z<_;yJPkD5@Lyd&O9f|I6Uni(mwXO+SpUelJ!+F>4a3FVhid!+dCc<-cP$kghB&#!V zD@MI);U>azR674wOzIeYD+Vuyqq-Fom04Cf+oxpoRmEd*rvie4MhG@QDt*)$IItT* zHI6EUtR1F`?;`T#MLHp{-^<617l48nQ7f9yhn{^Bt4QP!0=o?QUjPc4AjpSa`XW~G z$XEtp1a@DLE&?c3Yjl=+Axp)NA?-O37aswbPjLRY4C__^>5DwB^Z;>vk*V?eBKv2Q zfZrRL48J$B9|c8jQ4|Asw!6Z&7qUJHuj~v!?)D4j_HeGumsvFS;9A>5IY( zz}alH80eEa+V4Qk3TTBZ5$@1x&MT$MS_h$hDzf?-!9O5xB^h+i^>B-XSXMX0&-F}= zKi9kG9NghWH2Zu2f39azV{^SzL6N!MQ6#SCdXknjd4@>?I#% zSz!q5Vt@+)B9|g4NJlV;9NwmB1XT-i4(`mdP9~=ZgTV+2UxUe6B;q#Ba;QJXv3(K1 zet^h#4E{t=d<4lWM3AvSm64OA{f+IlAM0C4MQcFWthLQi?7YG91+-5?Za3VOWxWaz zc^84)U@@uLci;xgS)j-bmTLg+WTYnn{2MIWwQ2tb%K>QR221uQ<_(s;CeOXW!a>SQ zrr)@|lmXA=_R>C-ko3`VdufA7+grmP4w?*6t_E;#G4XcIw?-nkU1MJh7i7HfC4hg+ z#$!pP*c-6Vgi>zXJOdEBZFAU2GyBslyYX(XNO|k#mpH9?>!yf9%RjU_A0^KBlfOk| z8Dc&Q;14mYaGE*9TmYdAF~%Hx!@4_PqkvVjHW3N6f?Ezv#$L5+R<5LbDZ-rXUiwzJP zI<_}?96J61b!_N(@~5~Pi!ybGj@`_}IdnV^>e$e+U%WbCZ-QD*Uj=}iK9qUF)VN`@vSF5Er zgs_nuTC|o$82xak+Sp?y`AnVL$)66b_gJYjNZw;5p@<_+$xX0)4tOO*c)rDB2`-{= z&dnTBzHwv7Y6_%o|DVY{<0XejNq%y`ZgMnQtuk*8Sv70H)CV-heRxmsSZO;l3jWpL zSEYg{*Yi=DO)0i4&uoUWk+vR7DueG?1~(7W7R1SfW3J!&Fm zfN%9NNr>?EJY$4aww-S34om2(XkJBHS?>J4D$+4(0EMj(gi_qc zN>4(2Dz#B)`%!xoo)kfwv%Q-gg*KhqHqd5MyBWb+YVlZUH9Y%Rw4m(=C}@q^zYp5< zc7Y80C#X9^U=?I!Ai-1-r`cbAk!7`n!0vJ|%Q^)h(hEWOd&J*jI+m0`+BJJsm_MF zfa)g^9H#nQ)xf^%%Pi|TsxOC+Z&G~|g63%`S1cm5&w{#w>X)Iuk01$>hXLdl-n2Ym zeXH}rJ}&*_Kayq2tRfvmNsg?e6Op4tXLcY>(|N1p56hI*t+s=ZPFL*owp}gR65ddHCDBx<_Drn`!j-AM+yx4IP z)O@j{fG>7zrhvN#(kvS3{aFs(?G(JJY zNlzhUcHsLgYZ}2eK3E??3HYjN1dzWHe7DL=I6@HlJ@u8BvsIm1_GZ+HJOM?oi-NpyNI55_@eH z!PJWgq7hmVB!R<2YS*Zv=-m9LU1K1Rf7(U5!=@Y`ct99s;CzmtTIJsrvPPocP`ePz z{~&F`sD3var&jF7HLNqh3 zM61=YyF=Cl4yI;8d1ALtG?=0*$mQ)zL)HkE(YpU>bP4S*~>B!eE3t2VLPN>$?z0=+YXw+tW-!8rQWculB$)vMyf>{QnM*GaE zK6CLHVU87M@^Y*)q0PBIa}m(A^e*ZOq4gD7576eOgSNt_Jtef>a;n^qVpXfjpnZ$F zt~UC#y+HbToMb~j-%zbqf>}=HVV}uyiOYO{fQ4>qm1^=M2yLReR>hv58AUb>TKzmu z;=9k|+?3?w5o>NiZ5q>y?|B?ede7s;<^yV$9+%BR zX)EU`kUR4sPbo%Qg9$bQoW-X-BamFFCUfeRQv;*T+LJP@8Bl}+30k?6mItAIHYoi_ zxdTSozjgSCID~@XE+rgUi#jCwJI*%|ylB z_ULh1co$MytjlsJ6LFvR@FKFO!=+SIA{nh!7^7y6*02DropfD4`TB>hpEs@!D*nOex1d#BPdB=8LNbF@%WpnKs z@R#$Bh(G5rDNVT3!H38R=Nu6|-{4~l?{rzwx69EkeLMqK;A$c{+<~jmS&txkma7l0qhMBz#9=bOn-ZHT%O||u?r|ox-b}eG zNZw3YDB_4yeg`aH!!(J?lpITNCxw-FvSGdT;gB^LNWJ(!llzaC9A?LUa=>nKG+M3R zc`RhLuLV;_Xo_EjIl)Z%FBAs&-5w8FuW+V(%B+9$&6)D`u!ouQK7Arb;zTNE3L@pC zsGBiUKK)hB@q!U!rX0b6%#>5qP&B>agUI3^I(|b|gcP)0ZHw?Sa0MEs6$x6IDbG0% zx1XV~PXqV_AiNZQm_}r#{0~xM+1dBQ+FJxaga1B2xI-eJGv#N&=c%SjK@%rtHEeDte$nF%#>^YVa$}z$AO+H-w4*kPk#4j%B%zv--lk$lvxo< zRfV>^8kQ$*`^%p)UwRjgoBr)jnV-+alzFq2?Y)V~F9~~7<{xYn!)QeCjIl7J5xx+@ zqVODSYO9l>hK=x4$m|#X%(7+ygwqok(hN5wG6cflzBb0?v(lB#+U^$Hk;qYIIx@ilVvR>Scd#R08r2c!C`Qu z+0Ccw&=E`u38sN_K0sk@1bON1lzAPrO{nb-Z5wL8geSA0&Dqt%o)7JBbTI&}MeRQb z)>4Zp^B8DrH-YvUxRC`=_%XDHq0QWyV&_165Xbg)&>jXTcoIQgog}ONbJ*nRD`aZ} z)uW+)hidN7P(<|;*rB2EQPd3zxI@EsqfEF%!0Jgug@Zhnb&6Ne%2ARL@_i-JPiI z3U|jqyB`W9+aM>&s@>7Oq*z1hFHXvgG=VUz5;c7h^De|pg~I%W=Rt6ewh@9xo^LIJ zuqZ!4!>Qi6kl9OAwpC0p1z;vXxP1aurg~jT=?qGLg1?dYZ~*+=sh-aDZ_73=B zW1;p&8giNH9j7l!-H&F#pX$xW3@-Y^W$0Uo9HJ-*P7*G)5~3*4DwXpW8XjJeZeP|N z=y+2-u{Qz@wDTE)=m=U7B*8=;QoBaAMCecT`am8()g#?u6NE(w2%`*~8cWy*b$=mb zz0RrL8;EtHtnw3|$C>J}N%W?AexHb`-VQW{{#1`?c`r7$zC8BsL1K#sk8+`&8CRlM zNB45bx{{-T0w@zk1EyPO^^Z3ipexAb(pT`AM)Y8+>VH}}Q75mhIB$fkztK3WPhrKK zXBaLpL*7)6HN~6i>B#-w#EXqv5V`JL@3gl8(i15m$+zaJ)kZKwWcK!%?6zFyCyls& z+bY%JXAow9Am=PLkun^*jpp5lq!QnqNVzG=m+rQs21M@ztAuEcnshg89?zaPk*WaK zn@G{5H<8j=?D=-cx}ybb`~;p`v(wN}=5sb%|M|du3ZBcCcdON2P+PSFwJ8WLH4kW7 z{dbZ|dCKGiyw&QWcTnP}d}^pqn*cOEbElgP=C)e>2do<1z?$x}N`Yh+UH_Q{lI*Uo zEVYJYmB+K1@4?4=U%Q#CRjLySY{gxlXa*|)^YnOR11qqf;}i zqXacB%CKtEDhDSX_uqpPQ{xRzFah+3CZ^sWnt;H831*0TSQ35%DUH-+iT2BzA@bU@ z?}u+c(-ZC==8^otNgFuq4o>bzMLdkTk_=8>!GXQ&n>0?Y;|EJHAh>SqIX%CroN72nC??IcSgg19p=l1NJIVIAD+H z!8)gz-s!}3ci3=G%^Z0(J`jN&tL)yWhgSiFxr?XAk!0(rA$AG0{x+VbR<`k60j;W!ba&dtZ@Y^}9#=f73y*q% z;d^9i#iJ;+zDIFddUPMOF^@tqk38sl6ukx>h17KM=>0^GJg#^Yf=9_w!y{8G9`%IQ z_b5(FkETN#^Qd{uBM-VB{X>uHsZ#OiUc});T)&Jwu6R@r9&I;0GPUASQiz}naEj`*6=TUylBM-VBJxz}q zsMp0KH6y_zk1HNEfJfcH@I5lM;?afB`X0q;=}{%Lv9ng>d9+I1!docauk-p~+4c7+ zMX-0Q!6f= z53TP~oR%&vg*N6=spryD%7g40)y(qwD71#ke%Tw$zs#}ZQ>t7?a9QigYNW16WL3qn z_L9|D-JQr1I^TraUM*A zgthBwHF&FK<q{hECFk^4`@Rtx~<3 zqcG1ve0NkD0g^#==EKQf$!PgKgsW6;d(dY1v@3w{xoAZdCi9lM$yd>W^^7XgNi3I~ zJ`Q0EwFkE?SF3kXqu3bj$0&bd>x(fQIlqpT(?Wcm^fHdy)IcxaQmyZfPOl##&eo=+ zKDShj?3+QN%l5edW0_v~8iaFAUMtl!LZ`yT37X7nRAz)Z@k*wgCDTf^om^ZNvmxcZ z-76+!r?Yzxq5@b{n|azI~E4Pn%+PAV1l@43WA*fo*&dmd2}l+N+@+A?kAwF3@V$AjHmzOoq@t zqj5Gqst&LR6h94cfZ$=+J4~>>DPj^V zZ-#p@NFhA_7QDl%-9}x(LbF;e?R!Bhg2GjAHZq-ka;+BjG*4YH940KhMUvgQR&Bcn zY>uJ(NdPv%MF1C)A}gAAnRYtE&U;YH`-S28ARW@`2K1s!t(uXWXd)RW=`Mico&YOp z3%_tV3UIaNv-PUKA|=!Q0lB;z3aqX|_>z%Y{go*-?e6gUQL3#li#|Eetu(_Kyw&^{MCuz*7Q|U;E+vZ7rl*DMkD=8sgi@aqAG?K}=IP~xcGK#H%!7AABXTm& zMqa&>iB{^ny0~!pLX+Fh^#QV+O?YU%O1+O>Rh=29l6zd~EtA*qsrEC<+QL%6U32^? z=PFR!C>zhCSF5Z`+{WzmG+g~NaUkP^HtzUsy5OnP17+jhpE!g?M*^AD=V`S^||S#8CENTIRG62Wa{vY znNnxGWYu!EF~BmlGQj!)as5$2oR*`4m!Q?70x`Zt8)q@)bXJY+7fs`)R*Wx%);Auf zrSb95n#K>9#!pqXBmS_^)X;FmHyWpb(THb|pIG=d-e6n%doM-onYvjk0rzT%&n_fy zb!z}hy}5=}QWo0|AikJA{X zem=b|G7Vxki_49IFm>W<8)$uBUg_#KTVN3S6XFIQu77CAMn3Y63Lws_`nZv0f#;_YM>0f|Fz>(WzC?O#FQuW;c-~X89k-@U-k4 zwfk<%8v7|^NgqqDR;gcTiA!9>(t$Wjqr}qhOk$K65;#8lkDp-%W!4l|lHwAY+(;{5zt=y)`N#T;4j*E_b;OcDVqSqP--B;m(!h z{uk~TCqhnPMGCFupPQd%Wos-as3JwI6jFYdaA2jHRyrVoL@R4*h!u&srUqkz&FA>) z+&DH)=-vD6=kwX+^y^025Zk0OqZ^Wtg!J~p`gUC_Pt zi(&;esTauZ^MD;{0E>~ul)6K$g(7Yd<0^HK&K&g(vyP5hfM)^OhozjW)h#>gSSkHL z;vV8|&Uxt|FB_q`jh8U@9(OgogymYy`Uscz>(EW|b-WgllktNf<&NWS47uE%RU34B z(T$bP$=Ma?`x+kIzk=4MTNpjzt^g-s6O-p=SPgDRAHFNl8QGfH6UU2i)#G?45_=90 zV}}nNQ4cqH1M@KFdrl?Yw!u1vp-s;209y$euH|e)mhoelvoFxlo(?NA9t&sUy6I)A z_Xm30=~rf0y!`D!0J#7%-ZE*~O_S5?OQF@{t+7aZkT&xiQ`sNr9+?6mpB9(Q00?vS z+X79QP0CrSw*3iA$TGNZuFgnU2Iq06)ND$w!;|MVCh;rdp%;xincIU zv@O*s6fqW8w%su=!(G`{0-nFJEzFf|aa^u&8wswgaBB(f$za4*xD|1QTU-RJbgKcr ztaRH2kg(FN?5Yf7rJGU0Tn@-QLvN*6^7t-MT?5E8VsN#IJNSsj|}TLQrI- zTc8ws)WK!D5|Y?TH*K1?%4I8|o}kG}x9I?}t%UZPJY%Js={HuoO}j>~#_tYbtaLMJ zSn0M5T3J!G4Zv9GW+cLuZXdt}S?Sj6I=wQU%j~~3jAdh`+X}E`sZ;?Z(g)}LoLvsXgP#?y8Hx)St3#DM_eT{u&5{3mMEwflg^Cflw7 z@EySi$kd+%DTo-Ph5I0>2Y@uWqeH{@+$(#Kn`Rw5b%Ea6VJBkv>+U?7TuWScR|Tzm zEpgpl^BZw3alPFx#O8XtLe8J^DaAUwY6$gZ&ee~3I!Up`b#}GNbfp*s5L;*0OY=B< z&E`70OQDupu^J$@&Tf#&<2t)NP{-EU)w#jkqG7n1IM>+?fjYL%Ze+YVU|$BcRGvow zr1Hon4f!UIn=}l)QCGzffWJvY94&s6hI32{+@#@CB)~UMSo;)wEoR4o(>@`sG z9Lf^gI3>>I<;)(GxJ-VAf!U^q-zM89&xUtFdTob;~2>GePBqg-v@}#wMms+ zCztD7_XJ4D^-Gw6wAXE@)bRhJsks+J5YAfckFP){3Q%-=0*#A`wu8lqki8PDN63mM zu$ml8vy-6Yq{@y0EC2|9ir^HZl@BgUu4DIrmb0PAPY9+QMZjOdaMbluv~@WL0?K}N zQHI3Q(yKtsiRPuoy zQ_CV-1*QLi9#bhrHyv9413go<;e{|PMOf!{qX^gPBAf%EWN$D)EPJzcWL`~P5iU%~ z-ouC?+1m>s*{gSlmp%EI(OMm$H9bI44ux9Mx*Q;u)-%URYjZ+cYY;=y`V2tQYH+8Q z7OY#7lkdZRQhMl*uVdi0tgfbVhpvHl@K{Q~Z`oyum)EAr!9smfabMy<42HBXLODkt zfZ}Bj@LMg#mr*c#a5!aHtE~6k7OAL_%tYW|oNYd)c<4h;>vz|>;&-5pvPK)r_)WdJ4P>%}I` z9~rTN7feKLse%VNivkVo%~cszF$BdU035DX;)HYa2X2L9J;>=7NVh*(=}tH!{$$gm zNL}D$^FdJD-YjgtXIbBB6V&GnMM||-WmqLp*aHFP63hlz0D!N)A*}tOo2Enj?kxB0TIxDByH9v z8efA}uEyU1M0#KQVKyN>-kQjjfS-URTcrXEcSi&N9vpp8vUt5};jHQn@;F*V&zDTcTe5b8#O zEp&UGq}bxr^e^Z+DYH9&ZB9+|G*9{=PEDskEw$oq0I3zSdtfh<$EoQ%P{*dG|KKRL z1IMM6PI)xHPK|{&R;SA86YJDXKNxjt z1Er`_6CgC|RE1emtWz&RFLmlifY|Mh<)-hfQ>_o{IyDI(R;L~?d8|{5p^nw5S8)`p zQ)|q`S*L!6dLT}}6=r+1HeMaD+y1EQlnoH8Q_q+@)~R2imXX100RHWcI9hz2dd{@K zI&~`|Ce*0~CWm$Edz8A=sa7Z{^LED;&6LUD2=xD(eln)OrdFoFcR+hC+9}{G6lW| z6q)#M14x(x^Cr*U#9XUij9i;q$#oBC{akxmFV|5h{anW>k?Sfbja(l}$n{RB<8vLy zK(1^4s&hRMAU@Y7RdRg^D3a@k0FIOEZxeI98$ACekExYhhki41?PH@2W$Lr*E{dmfd+-gILO@R#J{Y>zB8u^-}HtrJr(~5-I;OyMbBWYjnEO zilLTmM%?)Fj$@#_{{cg8w46GpK|*<(R4MQCL6P#V1UOE4Kc`doudS`%`Q>eDCD%!p z8@cwhUaosX>E}95iCoWw(l2k0u)CQf>>+`A_F8X*eHDNV$%g^RkX(k)htcBZoEB(m zcYNTu)5W3MpcEvhi~mLR*mQBEk)8~dE{7QzD!m2}8!EZe#aq$3^LbFM2ah{l%%`3M z>es4IJY6g$34`g&!8zV^F$Hpex;W2pj|0^2kuY0K`$d2~0PaU9N=+IDsI4B--Nr-! z={98Gy%tGx;QceCGVopqE1WLMOz|)sK zVHVzq*rrBSMe_@0Mf`A?sljq1`EJ=GiXSdJVkDOHQY+Z>elqXQGbUg;=U@o4^g})G zE(VZRp%Xx?RhWe;nlm1)!V5VKCQ9#0fW%4pYxoVKnrdW*_e+QXXDcVXKe~&hc7>3Z(0|3X2W* z*eYCgQUkYD7!D9?70OK-T7|XH$^_*LfLN4Ywq2B+`eQ3^{h4Hpg&QqIZP62O&U1It2Or^ zUBA}!GTdXWDcz&{l2HJ$TGP*@q1LQ}R%*@H0I^!r{0_I)lFl)`YPjz4N4PyDV#$(CliCWVPEU7imfhDy@?k}EW zaoVG9_RlbW#JbJ>&6yd~ z1)&HbB!iGgG!a5-Bvitn5~4wf!XOI8q>x(%A%x$1t+UTQ`+Uvw`oI43di8Cc{aI&U z*WP=rwfET@dAi_zBTt7zs61ss1mYpLFXwTQdFq^Go`2B?<`(9oAmkS2a=C@ML|}9K za+%z|JcaoiV&GfUWN8s@seDlTqf5j z*MR60BG)JTA4ok2F&o0YLV1;`!!A^+P9b?DXfILLd1SR=vGd5KumtmnT&BFqz%tkC zJffE>_n~9iOO-3+Qe~GAa(dTDH|b?;#2PxwoaVJJggwnG#wMqE z{XEk-&C5kqM)fqWWw6-OykaaOuhD5HmK1jV6=#aDoeI$(qI?ZMO?02*F3$ER z5%{B^FF^by#19ay+Tqx`ji;hJf^W0^y|(djvcTmK&j~RF;#G)pS@wvn(+u{#*jn|;nl2=(KKMGWq$#wm8q(OBkV!8YwKwW>m5F%QC9c9?uwcctICS#B; zm-9xjT)y3`za9e-EM;q2bKSIL*&JBYdKe-~Ye6$<)u*MkjyE)|9sV?F^@WI*&2<^6 zkv2@NOqTe|`{XyXj8t?duq-2ec0!=-`gfn4pSBZn!Nx$oXUa~x4%%m7CxZO~rqxG(T7CQ_gJq=qAaoh&eE97$QjA}gkw(I%I~;pK=rWQA zq02}|@M2aCqOgi$I?G7oP1Z`JePtP`_mKR+<=+zGSn4CVG{db9Sw>n-d_f$#I zn#ASbrYvx2=?=$Q3B{H5Au$E6EL}jE=Efy1|D$p(3WZ)mHN)_!O(8D-hk;cp z)&JNWsI%fAm#j?3RoTwMN_0v}C-8<&3^PWtnJRd_yuP~p*Kq=hb@ zxctYJ8&T{F5xM+bHmhfAEi7>%arw97MX3d68EK-+BQF07sY!MDKLinT`5R7kORl7S z{!`(&C09A9x+M!hPe&R8m%p0|F8@X{@*Ek_9gg9v+DmB5N2GXwW{2Zi_g$Q^R}*pE z85`rk8M_b;b;f=L@ez4&T>egE>WocQ8fWau5Y0Ga*E!{)UlsTh;j_+I7u8Zf18Peh zqFOLYy#>&gItEhe&S%6*z1hiVA*CJ+94~c@gHqoDhnD&!hK>rB)FB#{dfQn}sbe6eei_hd>qe8V_D4#67ZJxx9pj+X ztKiU5Cq|~1+GW*J_ku-BeGWugTZ`_r$~fL@C^=eaJHOqy{783lQPG{&U6vo|PA;gr z(}SRPf81IV@kAn4-RU?Ywz|_ggLV-V-RUtv)n_h;i1e98!{+KvTTNJ~J8j?%)o1cA zr#57(VSflmcS`YF`-|DaIE! zmpZ{`%_WzwIdkco!}87H$1dmaY1n{z`0+*vIrDgU2X;-#DadM9xxDHNuy&P;Si9A513w zoe!`X09{bCQwcn%`{_SveB-|ec zS7(T-OJU73eSHRL_ZyY%{{eWjL?K-<1`gZN-*1@H6J1bx;!r?q#kipM#A%?mCw4T6 zP9st6iLZm&&Awx%2b+D58*X~Vc2K8Rn3rV+40o#bHeq3}n9Qr%E0#fM58Mh7^a|bV zTPtbM^Y$KL(ija9r7^OZG$y8{@icE}8ecV1bDx<#&JK0kioomt-Yg%NqhA6Cz#z18BWk73byP(ME zFMw7?T~K9op9zkP)|o`BNmOOD64cHXOAJ~hD6_?@fI5Otg^1)RWOGOGRp!-DR)6CS zm80%g8#x*Z;mj6W%?sgdF%4MLdJQ5Y(Z&o zuu<>5oflPR?}E?DY>7ct4n=0)1XY>MxF%g@`x;)!h|282u&B(Af{4qk%d0Xw3l^2x z_aWjkTPAllH_(k!)0xojdDPt9TnZs~Ha%Xckq4yI|b`U=$gz5w~oCkmD zg5a*^GP$d{S|FLYUgIISqxm9mxudyE?r5$TTqdmOZsxAwayN6C+|BH9(t}P^X?HSz z@~7prw5aAdWX#^I#@EwEax&p-rL>kedfyjupb;`6DrV3p1Xp6q5_ z%*_R~mYSOzAdI<5eU!=hn{`yN9txhKo^;UyME>;d&~hh7dTH`NL^*zUsLP_qLUw}1 zxjQu2Wt1*l|%cc0M`BF?K>!dQ2fE-aJ5S;)P%+3}XQ!Vd!X* z4bWZvexw=*1I3r^>qYk=fA1yt^Ls9AZu@$bz~Xm&e!bbge(8qv?d#*+ML5}iGYQ_v z?^r_=>UTVbHzU7eeGuHzf8|rNef_h>^zG|S!Xtjiv*1y`<8|;f^MOXuOc?Pywt!Fl zj$PnO^E*!b#M!<+-O01~9UuJ6bRqRSmJ*%#9X}#e{f-MZrf*-bmK0^tya-7Bj=wB9gl=f`|3py+E>-@Snnhve#a%9jI*a`4}=Eik$&3|a;ePVcf1ZR?S$V!XeU&U z%5rD#fqWoxs>DI>3%;yg5ku4cjuV~ys^2k19WC+*qIHCAaS)fZ!Dc1G5dy{f# za>c={$gVZLTwO)?CU^HgMS}kYP?btU3!ZM_&j;L>@QP#_*uIX#X)gh7C#W2lzs^J~ zP0@ZX2j}N6V$B&qPnB(S1{V&_uQZ3|)1Bm0uJg_E)GspE|b%gO9YY`J32-AGH^LXxlB$`9wWHS*wN|9 zJ;3Gkje&v6Qw;R+2zoQS}$<85*EF{;olJ91rBmja)V@3ChE({fS!@O3_{LGE|Wu$ zy;?I->mkTl&znP#dpzqLf?NfUPSkn`^0K9@@AIa=@fqh3>OL zki(FV1Po-eT<&|QmNYm7c^Iw{E3&YfNf1;g!Il)+odmrJbq{O*o7zv$P@I!&Nw)|- ze0qQinV;)9Q9B-2-{I({5Tm`-dmbBux|nmNW0h0Yu;Gt7#W zp54)PUGP>Fx!3(Q`)8Szt1mO1l`B2FBgQK;$$hZsOmZqjd?wMeJ7O=$z8lzdMp;H4 z(q@#S2ud*G>u^|XawU0_8Rhuwa5$9D_y!tO+E905f$Gfi6ol-liEgQOS#^fl42#Y% zyRpqVFtMQW`=o;%G4R=N{DENDRtSHVK##5 z4AYU^MKjEJClQ%pigL^hGYP`ZFd>)JmFx-ohK%YAa~fRH3{&l-DKpG-5{I2(CdSb8 z87AeTvQz7RL`!Fw4|@n30WRjI$* zV`uPURt+Ow6SWj9j0OF)L5emzd942|dg(tuP|TZS`f0b`rk}24h=_lXTW%bzT72oJ zcfb<$(-NZ4e)=;}L>k_hAh@MJ`DoKWdqBijmTQGa`sK=_Ourlj5$~6}vfLny^v71f z+8-Y|@*n-N8$q@|j&t%X{jt8p2#;!b-h+XL_Y0xg4|^Zu^g~@)E`~+>-wi<8|5ib$ zhS#Bw)Bol=-e=YD%0adNO@WB|-zJwY>VMPReA53qkt6MYTd1t4|4nz<=zpifrv2|0 zh^YT4zsm*p=mw&32%Up!$L0roN^FJxz%1Krw#l zK##$u9q0-O?LfytXa}0ei`s$O6XL8a7n!V;$Y3RX|N7%h-#-OHOm$sZ4%xI$rSIH!41ZvF&Hu|CNvb@;nlfYFdo`+DO(3Ry9!>9A7 ztSmPHt5odS&s|yW=kke-J{UOqnCxbrA{)KbOVFU6t}Kr+ zoN6x2rhRVzk7Izls2bpvpr_Z+Zn`bNO$7sdAHe6NQDy%{_-ZgW@R^Skk8lj3pNL?* z`>uTE!@Kd-#u$fu<^xCYna}ZfF^M8tS$0{~gLoz^55nT#1Ch4cC?7Xfo7C0qAfL9v1=(_ zYL`_@-4_-u^%W4!lzOYPB*AD>;2(94Q)(C0Qs;o$whqy-)bEaTN*x0!^$ftE)F{P1 zs|@vY=+pvE132if9lenR_*X()1W|q%KTW{msDF*XzJlidjS&G+CMRDOJ%llLQeqc> z2%&ojJPV>bM1^egt97*HtRFIymAcpO8(3topI0#s#<_8x-7Bw?Xa;)u-YpW1oOctl zNCC5Yve{V9y76y>CEDy)aRVRkE^w5dto^c*m9q%+JHa>~V%Q>nD774bQ%c4)N3!^! zr{7dd$kfc;EA7cQbrK?5`j!%bT?}iKP!<>lU?iy1KM4^z{g<08xK96$>m}#GfdJz4 zzpJ%z`o9683srwZI13CV=7sLOB#UAPv@vO&2@$0=z_7V#Ri&kM4{zuK!iGfDc1x0oOq|mATfu5LV_6JD9ZkKtyS6Y9_61 zX=z=?8=BU92u-}r8zXFDb?(sKXtU=- zSZ!91ge;|+R9!u2N7t-eYoe$k3NNUil8 zH(>^9?Jc0Hz`O(zskPmmL`1Fqlq{$&QN9z^fwrNJ%aBXzO3cbT;8M+GAGjj5w%AEi z)Y>T$M``G|>=i@P)!J1~vD9(-CgP=PZIV{|hgy56iL8hmA-yI3ktw6r-m;6M*1BwZ zB;>K6s@DFovr%hX@uF30WBj7lJ^`DmwdX*nTH6Ui)!H>grE2Ym6w}y+dQjI|4&0T$ zTK?%Eb^S%oAmySmNSy>|2PqfSL8=hc4pN&;#M6ja2dU>k?I2Zc2C2>$n}K5sXf$wa zH7~oPa8B9=q(Qu@1IJAeI&i!I;S5s6=7n&O`XNlK%UCz9-py=wDosmk2ybXwlOZ&% z7a^iS$}1B!Ys_4x{ij*g`QXpstM#%0gw_(O3dUuGih@xt%4CCtqE5BXGm3>Q+I2M( zojP$o+tnWrsOvPUV)k;S4z=UoppLRtV&G8OdIC7EY{fWGw!VNvm91SEP2m0r|m&g1sQD%ez=$ae05ee}3fht|C+ysnz9O3nUi^ zs>{1Zpt#F>5V&=D*9#tZdA9+#F7GDr=3L${71M6w^7dF!7`~i5s>{3mfm9a3!|dIF zb!N>^sx$8Qb`k6MzLj{b-`nMg{N81-sNZ`p2-ojjG@rbR-+M5*P`~#~2~~g5vjHad3Wc`QO*1ZvEbQ3j)9Q1W@&R*MeHVcPXg)y?X(x-+K_S^?TO{ zEPn4Xhhnthr1rZ(Sig6ZX@{<~gZRA{1FGNqD+qfDU>nEdA%5@FVWERtmuqs&HZkc~ z;{RSbFoX$^KV1ZFASdeo-c0q!{NH*+M3u9rMZ5XcS2*^Bi)wdY2x{$#5Ynm)-jUqJ zU$89w(^@@Rp%z^Asy^Uy0)E;@)D41*E|m)|x>R!?QG1WWg#NUa)eX^~(of=>L%8Zr z;&dP9EQ#QBuM|gLWn3$ASwt(U6pg4-wV^RYCECykIXW-K7ic-+fZ`z3KXo2eJ2^$IDDW?XMV&`_5Os}{jA|VnBzlVP9}nSZ9ePM< zF?B>kL% zHj|bl5g1|yB0LcZog)9nsO5sR!s@7s-AH%gjUU52)Am?3t`oK9H!OwLN~2R@w9@f(L*;) z`-tl_b(?h4m(#ncuC6s2KJk-jcfAb0cz0D3D8?t2yF zkOS&A*Pj4rdtMEpB5rRGXdNW=A~HBg{0^@;J+DbZMZC@;)QVTp6M=aBLZJ4B1rU*V z^)hDxx;<}3TF)!&Zp7<95Gr0*Lpb8KJgw(F39M;-4iTlb;(ztLxn`r0_B^SA9;2O} z=b};-zm9Txo(pP~ECaPYZ=s3U_PpUlY^$cqRLx2PHM@60MA=>L?79j!Q?E5)VbA-E zH?-&Nf4-@jvml(R@zQ$U-N2gGDu^hp%>UK%N=^Gn&rMCC=WTs0z31r!SwmU0$5nyH zdz^lSSueQsv<~3S^fX;3YZ4}U*s52X?_m=Ow>>P(nF#;?=wU8PS`X_@RJMo3_@W7N zgmX@%OpwRFZYIbK2s=T#Trxo(wIY3j9BksT-E=;65OvckCmHRg7ZZa{kk3P;chjOL z>84YV(L2b5?WU!KifnEm(00>m0#zn^yy0}yIti6-dKIBo78@m$2{L!3>83A(M)FZ> z^5}Ncb!pvn=N?8DPk_*FdM$(_iT$4BI~@$X;$Yl`8n=T&J75 zs8q!wKs!OYpjOFMpthTqq<7O!=Q-W9=&7J;ZX!^#I}jquZfP^!bVOP=UCJBUO}~fG zs_DWo;Z)6J^FmlPrvqzR|AmOss)?tCcA`B%UyzOWB9aV$`a&oVD;clhfoime%zYx^2rk9O5kV-@-LpECCHSU zxGX^)u(!JeSrmtp{+Yn)=(`6(9ew(7YZsSKmLPj|HEu%>!j3*Mw)hfcS2qS(f_#$% zq!yed$gQr!P?jKjP*b`DISj&Gg6wT#6V(a{Yw2h2L1GOmhK-? z<9R@OsY~FqOOP(ArM?8zmO4bkQqKpprH+A=`cuH5)bwca%B?UnvaRpWP?c@UE~+U% z3Tjgh(J& z{H2^MU{yz!-pSE=7X*9A+s+zFtgH7 zK~mv^AY;P^K_-O{5_NbakQQ~7Ik;1c8XhsK58=t1dY3_X_{z`?Rg~16kiks@;W-;} zMS%&`vTSu9a*TIW%U>EkNCj4f4^n|+!w0!MVOscb-nkq!A3jLqG?`sknn}+rO6fzM zc_1_4q9J6sBnKI;enF;;(^c!Yd-%|e>ggLkNS;dFhjHP9WFzdfnsO-1lAP%;kjo=7 zocIYXF_XKdTpK<}!z^?kx*Errwo15Dwk#*l-J zb4&Thgbz|GxwTLJUNL8o5fNoTTcQy;JkpGB5$~YyyTahqw?TI676}I}+{u zqN%}hXxbr(Vfw91*cG+UH0f=jFH0{*}3#9C97cP2MqlwpLcohaXo zH9F;xa|Qo%tI-7uAwCvGL%%}V?6R?#`#9;VD!2(kRYBc**+9~=2YSF1vsnEku~@gP z?!ELDQv~_CW+!-bk@{+Q)Ghltgjk)yl_tf)7@3<}O%BAi7jtvx8l&(%Nj$3X$&Rg% zOPhrS;FI9e>04Kkw>hPdRpifkRh7%DAym24qX)OUY*uR|T@~WxE-FI&E^VnTpQ2*j zmY+ah^^C|%wrTnH{&(c)HUNJK#0()OLd+FbJpn(@i9U5L>j1s3X9Z1n0g10KW#B_4 zzUz>rvw`E1q`3_Ftb9HJpXTxph$xrp7%Vc8_99Xhzkl7BE`I75jPZ#W{&7RIVyKS6 z7&C*!6Yw_IvyLI$isPY9=|vp7O)}#6D>;h9vBYIV9H)S)I4*~X#IXty5^?N7my{I( z|2CqFi(^eFj=uw`IGzEa;`jI8C^0I!#>7h-_6(nV`!}M9g3fhFnd@OpJa7UE?)&(#%af$vfc; zHh3Ek*Kgng*fSH8)-jtbBCAbgKXn#!)lt(}`5~b4J$}wePVqkF|FUoSDS8@~QOqc< z?qG$Q0DldB189puh4)C3EkBP54L=@jRm#=+BTmPvrzT4o__=1t5yPNQj$vpom zsyY}cWGL+A!as2)VjZwnXK-M+G~7?vy%*eN1b-h075t4bis0+%Y9%Hb8NdpM(&rb! zrhDKwLqwZ}s@>#d*w)c(q8qw3xwF5PG6Z>)MYc(9g$#FXv~Bz#Hh7U1za>j)3xGer6kygx=iJ zUqavsJp1QE42GDW7{TvyQy#I!`&6~4x{2gL2joXuY;21geX2e?slD<`@YTukByt%zABWB^0mi{UomL z!afj@yKuXkZ*%uz$M1syO7qRK<}k9WuE{$f)HV4AMBtj#<5(Ic4VE+iBv{ip_5nAI zz9v4c8bz+)^Z_nen*xC#9vJ8_f;Uo!W|BbreX*W$!+=YPYJLqbl=-RqKlv%H<;Zh7;* zh(_rn-Lt&hXEGOysyaLIO*@$71l}M8pUB69i9_DW^Hv@KmmF9da9z+% z-@W7$Lghf+Oi819$IO4G_%7%PSCPw>HBx^kNa8JPH0{yV>)GI*xR%9&L~{|8Ue9Ye z8xl|OUa3R@t!*H2K$`-*+LHHWr+$#N-N;($=WE(}S>I=#k*V2i$xNP*t^NT=-;iUM z6A}}IV{sz;r1>wwBOeO{Jd#e9N#NvGK(dG5NucS>EHA5jR++p$`bApeynA4no%l~@ zcx6XUz-wf1IFk0j-XOA*Cx(0na>FhlvI8hUjCAh*Zl2e!Er^`q6(HKN7bLb!Cp1%X zcq!hY6AJP2^gBl@cXvzDY*)RP=am$~Drf2h5$KpPJ8_PL%2_&5sMc?;pZFJpOsNPJ zG+q}Gki$QLTTaLcxT6NW>^<7=w3e5BLQZJMTxrLk%~m^YwmR`X$!VN9s}q@j!&{eV z`Xv~>$5VZY(Hn_8rT(4Fp#@euR<)$~*ML!eQ_o;zRlpG$StSN875G^^4<7)h8Ch~z zNyw)vo$N5EfiGIR?B}GSOP8r(1%VAV3?j`28(^6GlBU{V4-79zTPju?EXF4`SOt8| zxB}D$i!oz^6~fz`4K|njSQ~7NlWnoVt{qVj=(8t5sQ#%gfw3+dHrOIiwZS$+L^fFC zdw~sh?U@CE4VD6q+hBRC(WJyBa1uOfgMCFlRTbTZkjMrr5yr?RFwx{dCTnpCoX9Mv zdfH~*vMzy;OWIoYgkJ+!q_a(ON+B+RT|iZ5TSOd@&NkU)b6o;mt20{ra~j}QwXhC--`RV#dAV)YtX5SUn7ctK1oHIJsdsfeld9O!chnr;=2p_oUL z0JR_-^+3GCuOLn}xyGJ@6ozrmHE~*#Ycp&%&KOFZ`|)ZJrb+zg4yHSRnk3y(mk zEU3w~-Q^RL>l5IkQHcYS%i9)px58FL({7Zh<-QPF%lgq{j>{(|*JZ#eQ}ZDr6DiN- z6O(H_u$o+hMu*uFlPllwS(9riu*P>2L=<0<%O@sR9{?T+ z*sT;Xwe~na%$ryWmUSbNJB2y1GEY}#As52pcYe|Qce=nqoTL*2yaRGls` z1yu)H?-&|0wMwN9#MBzd8`jjSmQXRZZX{GQ^{hllw$;?C6PQ#cjR{i`bE~hL3R&I4 zE1K0#utif&wDMFqj) z?Wqv)&Hcd@%#N_8mSSxdA&2Uo`i?=sx~En+Z0eqR)(#PRd3hUy>sreQQzGW#;y;2u z@8!x|e8J91??j!8f4hywK@$*rfWv>L_B-oVt`J|Jki$oYymvbtqklUu^-1Dqru2#* zuj1Zu6Ojlme0ly&FeN51WQtgasMh~t=8#r*83}snP9xUmrL!Rf1K|pUK(|+vn=~|* zMTr9cXwnEKavy20io-4a1BhGq0gQ)`eE^kL^TVAZ)!$&{=%wfz6M8B7X{f_RYZ>($ z6Fd9&kZPo5j5o0kkb-SU?CKvqy;&_ITW|8FfL#*CJ63%t!~8M_j0wTwC^+oEN(y4MW3Ysit#EUINJ zblK1{N?_9w{8ETW%P6Ia#nanvhS4(S5KCOksDVYbj8Aw|wTuhlQ7vO0A(58RAdHcg zQEze})h}8`BT48Gbs2;mH$yI!AO@rPfI1lUg@^{DO+GYxu_4tpms2dp$ta96SGkt>WO#we`Xo= zp>M6DJ~TR|FBFgM64-2&#^`Q~? zXu55nK9t7cY<5YS%Iy!Km8^ZZ@z+ zEb7B{VC@FO);rxGWDC2&>u_l|=m}TQ4Wy*sx`{Ed-yw0x2&(EsQw)u%55-akqCTwP z4XZv>NvNm~e-Wyg>h(#GDODe81SXZNPs3D1ec0xvLXREEE1K1r5K)ia?y@m+ybEg8 z2mL~@p6Kbc?fmr{0<}TE5cEDK(K{KAA12hQ3ptsN1fVWl2xxm#45T+50T}cq9K*8s zS3;aRJe*HS)E*r}sIDB3k>q6MIER;Xhw;UD@O5)>tw1t{zu#!a@PmOWkKrdce@AeJ z?b*OOY=1|jmA~;b{Ct9B#4Z;R@YXTLG5{VypjL7V2-VSKhAjq_4Zio2HCsQr6xq=& zvrJG&NIMX{zZxQ%pu7pC>-EO2DJ#6{l{gCj43vVVhYP%Eq7<}Bic&D4j+BOUe5k;i z_y(Forg{@~!@xE(R;eD>B3U#-Y;-qJ_Ca_RGSIdWPoNo@Qm|IY0$41NVODK2H&B+p z<|pK%&RFPYyAo5G+;Uh&)>7HYPW}wCH;Mp%Jek+q=yD+RHaf3t1{r7)&OZ}-_>bRT z;5{rO{m&3j2yw*h0`GZVqDl%ow$AY%A@p*Ae}K3SqH+p9jF7VAHODPZBDs@) z$OC2o4L)M6CzjN1>+|A2BjS{fI?|8H%9*B_!H zJB_VyZf1@@8@6`B)&Lt{ypKdGiFSDq%H8j-DoU@;B*Y4V2;?^e}Ffm!`!Na;FkX0Uj$Q!-xvIB znIr5RQYSnzhphNKm_z)}VQ%Iyw?<)PGC2o6nN0i};7dCNV>2aCJ3v%{$xfc-6pR*M znFiDiMR|>ZUf-M0r^u1t_Um-Lz62K4>#v1J_4>i^s9wK<5UUz3H3?bOXf|vzQ~B>h zMBbInE?-~<$TI(2H=o!m=WaGS-XRdG%BsDxz-7Z;nFXpU<7x<18TGi{ZB8OGr=I<- znN#0}utr75rJ{t2asZ&JC^H};ZECxdrsz4z?@Se{HsxhGgR|?p)X90A`>ssR)ijPy z&Wj+N$vOCvBGW`xC7r)Gd6?hk`-0$_unV^oM2ESBY$@3E)QjGr`XxmU#DR>;{)Z6u zONto3d`a;hMbIxPWOsk;rp%WVY63S<)ks!HzX!>y3A~8ttO;DS0a#4nONuYe|~XH;PEC-Z9Or8Ux3ZV8AFLPlUE%PnVaqO zJ~4qiwdfFt$UuldL_~vI;PQzHd?RqwnssqF+kYNdhk_=EpfyF(mbiRk0(Z{o5R5;A zAR?2s-sKY$_$FYL+}16_Y)O2}4WBiEF9g={>?nvRz6O_1OyFfEzCZ>7jbpRhIAZ=D z^}CrFbuMpmVKINl0&7*O_q?7KQuFsaf+O$w!#vqBe!Gdnj`0Wn@elL2$moM{^S7%B z)nP%*->q#s1hcmGlJ1TYSt#aj#SR?;Bj{xaJ79-w;eg!@P+O@6LR%>~P}oh30s9w; zgW3+v-(E2^)LC?+Qj^qyn7{kvb%@O0qR$8w^Y;uw)iS#SLM=0yVM_%jm9yG~sfhX8 z+f9YJ<#k@sto{uVWL5foiOYt0cOa2i^G?m*YNDsZw)0!(2YR)dzjczR*cR{a=;+e} zOl(^BVq*Z>o)iP=N#_6tJxQ&I5pGVziXgeT6%peQD*}$dih%g2h5_jdek$(a$7Kzy z2v`CuqM$>%w_Hr`flkhKcuKbK5SidQm4+m(;<9N$>Oi$cK8MhPoVdU#NXTysvJ+@j zkdm+<*GRA}$h3G)Q~qM$s70p7;dnvjxCPmZf_%ffT9Begor1V*T9ARDT9BI{v>-o1 z*cJ)-Z9$#~jS4a*EXbZnXjG83@tmgoGT^8n>*BC2NLjbigjY+HsV`Z<=>MeAzNbK_ z_ATml8`s4xYWAe399=4g(gRNg40@m{nnmu*qHaGAu1ZT2M4(HF($dxN=`17acISmg z-5vxHC@p&OkL$M=b^E~AU3L2`o+5R-+Fdjdb^9LRKtU5zV4@3)5z^U`0iRffe@jF7*`LOJ{bmv3S=cFiGmktC{=R?b- z#`$nLAyzS+ZW6MJ>8Y@(^Wg@F$oVkMG`sRe&WDL^K5;(mLXK4MH&YQR`09L^ zD1}Xx_3I&2?$!A)$4NvKfa{P@6)kU-5iOC_kW0r76vV^eQbBzaBGP5&x&n=sd7#9B z=mom$f*5Lt3a0X@qEtEg)eUm(X&lv<{tXdnOt8x_4s|B7D&}B>wVS`;E#rLHAHtp_ zAF^5J!zjZ#u_{I5f8f@x($c0en!z&a@oex*?qB`0Ed0oev?K)~Prj@_HxWJ5L1= zWzQ0n_XRw^W+wgqgv!QjKLPQ!5YLdUkL9f|`3XMsGdb6GIWAG;PlQG1X2e~l(%yza zWoiqz6CC}%k*PKiR;EHWD^nkk_eiEnBu^q!?LKg1YK(*;Q=br%BU1z2+7y}U%S$R# zS3pEERqp0pX4pr8Ri-vVL^JFNmrrD>!x~qn`tuaY)F?M`k*TYIBbgc#hm(FCu*%dI z5Yfyz*5wnK8u6i#sbUB#Q!%!8_VX99lKM7!i3HA`lUAXw7i> z#G&;IaMYT$aX8!W{;O%tGa!Q26kTqv%O?)4+kjQlUV#WCP4urimrop8+kgYf-4kZ!I4AjVxFwtu+Btb^@hJeMQ?DngXXxtH@lxB&-L($L+h+R!n}!onQvf? zSR7h!0|)x$cGF8_AP?C>C13_zfwl^lwvx(WM>jE)fRPf1$f2%4q+)2O1gJx+Ug|&` zTKDpX-Ote^q2kbbhfvK_i$8-*sW-l8Gcc*Fl|W5Jvf9N>1%2fRP|fOv5J6VOq1Dx8 zLt}mrH15zUC3-q+JO3)racEUbqT1AS5al)0+4$$_b7)Ve0_-~Wn zVEg9)Hzzo>p5ooOLo3FCL+dLz)SrwDHBEbqp-3p0$OD)H8KxmAIu5ht^z58+T~MSVW({1eRtTS}{J<`983v zIkegmWF1;Azv#0clRK4~hb6zXxk{nS)r>={)Z||sTGIN@QE%3v<)SJDO`ui^LR2dX zDcCdVNI?ul3d#V3@l@TKKKd)^u4_3c6<)DHsZo zCI#Y5t4c5RH27?(T~tf`I;bsmh=!&93((4b45ZWtW`?CUZoK8jji;M+q`qqkos?Zv zQ}#h^${`x2yceKNIR=vQ57v#R_1$37)gDWIzrwrm`i^l>-@n75_1&{$dVRaBTHnK9 z(O!2KL^Jih&UIc&so#Ll*0+mlss9GGr4G@s)V5lQq!0`GqGcd%Be06unm>C_ef>%d}G($g^a2+BKLeFE)d5+;w9r4m_{tiq)03I2|llv=|UU>Z}Fx& z28P0;yAtjuL?(E1%*j_U2A00e%WWJhOvbVXlF+g2YzQ68WUdRjR1}!&?g7-ft`|f! z*X23Ii4S?Y)H;Tw5rvNagqMwGnhjw!(|UnLGkt5h(M$(HSj{x$MlPCZ5vY~N7>Yc8 zP0WEjPAK{s&GhhBjAq*FRYx=J?v!448_$K!#u-D2a|>V)r@9Bnx+AG*rXv}1w2|+H z&_>qHa^qY+(M;b0KAKt$7S6}V;cP!M%dCtY0-=?wyNxHhe4?423#^*teGri*IoahC z&9nhnvvo>#m@UyvYYd;&OqT#_eAh!n@y&4gL^I6>*7&xB@fq#ZRf$DA?eJTu0m`yq zgA0pxIsjO!Qw6w+R#NTs6@nw}^lF|W?bJkJwbRzW|3f=n>t@$#r;ToT>HQ16%Dhua#M&x)j28gODxk2J4ALyTP$=1>HbOy4g((y>Xtzp?zKy!f#_}OgpWS zIuPx29dB6ev|d6*J8j?EWU3#8WJE=fA)Lwags4+*(Sg&KQ#jJ)Kb1PBY!P4!z_QK--&QAiXIC81yDH zW3+MJ)?s21C9=DYbv6iDv;jmzyjBX$Y~!Bh7P7ft30YyMIG0NGkZw&VR`r<5mcE4Sp6=p(S6t&K1kHzl9#fDa-a{rOsnfdXhi5ks9Wnp zxL&Rgt4$Zvha6LZ`q0%pcy);}<|Dl&6f7~i_l!Ic*mc&B{cR-WZh2AxRfnuw%@Qe%^Q`oF-W6KR<^QyckeGc_)Gr2o?;>CV)m z4;Ze*nK}(9a;6^2lXa$+3XeEbw~RH;)Q2F{nOX@Ecc!j#Kcy6B>OQa-XR5ACRtG7z z^*3H>oT&Ff9Lp@Ai&xv6q7;f_{%p|5iCQObixYL_WkI*qk-kwv5!~qn2HjQlki6fd zLd;iB;za!mTqo#W<6Ku%N5iKRzBp0O1`ZSmh+x8(Wy%tlPn@W;u5g{G@A4EmQTw@x zixV~bO4sc+AP%#t1FZAV1rUL9BWh@=%O_6Mmg9{c`aXPi#Eh}Uou~ud7{rM>n-`@P z9LK!p@`w|)CpD!`)H5MMC#rldk+()==|q1s`OwcL9=^(aF0qIZ`?*9ZeEPY>1%&G7 z5<}s$pG&CYz1&T;Hy`cyhBtJ)i|cZv!+-z}_4gwVmFtST=-FcpJV(TST(Y149q`Kl ze&-1YD8%reAwGr}_9Z`>X!w$jW@`#N`Ga85M0K})wd8wk;lBPd3DzwIvPXZslastLSabc0)qPoDl6u@5%XSHVW7Jio-KA9d0KPueYpLT25>642GQ2OxB{Z45*f%8Y*`L^}xbCMzRrO`0V^nr;1KuQi=I z55jipkWK4cI`zjS6?N)*sdMSnJ6`8>>Lv-LQ#TTm)2W->%9Kuh94~37z7irZE<}sp zX83HUehgSU^+t%OQ+vM$gM{+w%E&~wQ}^d7>eM-gSqq{oBfx<`sx=sgSs4M=PW?GV z)T#4aKIzm~UvE0~@esCC$JpYXI^T^!I(0{0OzYH*ZcRz29!E`Tr+yT|bZXtn)z!qN zn#DN2%sKf6N1t+0)u&RRry~Ta+J>lB3HsERWW?%IF;Mg=DISf(to#!Z^m0pqW^n@% z$2E%>2b#rmaHu}j1QFLPTvpXAI^SsYslgC&%|c6ks7YNqEyG8ye=~empK?(x^$Vc3 z)FG;!l2ZQwXiFV}DpHiX%Oq3kD(UYfZlUS#r-KIlUF&3k3sWcm1&-HAjDtFP9*&?+ zAmVl6vIcc>lc|$I5Y5y{sY%^R!cFkmI&o30lVzZ`PC_)4gr5Ozoy0)uWZ(bBB%wU5 z)I)*erH*k>>bv03QojiiFSX06rS@(%r9K#SWlU+#|=@uGEI1<#6gt0D+BwPd>uag)Db@DJAS|{ru;&tM(YMtzGi>Z^o z5Y5y{gGpUBZ)oqxyVa=^7u7mhPb{`hLNu(C`GB@gLNKh8%K&vu(B84uEi`p`oVzQY&gp9ipKmoJJD1)FBv3!hZoHNyu{#Q9u%wfjW|qa$zK4 zD{#C{VjR@TKDU`Vsf38viOZ^WG8GoBlUE_qBtbOOB4=(*UBZ1+4Oj|+BCr&7vDm;m zj9$vUtx0TyHv#;&FULs^Q8hJA&_-b}N zC*%$OPnSYZ4>f!>TaN4-^8B8K-r?ZKEl%8wU=3;Fd5}CW3Z6UfRp{-yAJ0!Ee(ajz z4LOJBe+&L}@Lbrn&>JStO9KA?@O-{JKcmlOOL(cOeTH}3!bH-4fW%)W!0$sUZ$eal z$j|Wq^7J`GMHkN6tThD_DbM{ldq;meFZBdKO}>EB^EMe=dJvg7u<|wnD`(2NdKLfL zF~i&L;!6^IwN8#p0sOZi${;G9;K$oPascI?j=fZ{ccHgL*!n>%7q*+y*yMg(e>~_k zVS5~6rVtw;<_Rl%s@AY+szyrtB5uB?sfr&7sQil`|7)IFaXew!Z9LV(BbVU%yY5ry z$)S*y&k0W{Pp?9hi`+NC)AF{$N)`3%Kt$BbMbwK(4H2(Y@m>rf;$1G{E#*Y4D^;Yw z0a2FFuUhBx`R`{V9~-mwJub0JO=;t~iS zqHH@YRtI11yDSLxAv8na9UyiPV%@%l-YyW82MY7~&*C}}=2u{z2Xqes{-qEP32`jM zlMrQD{N&|lcqcAr4d735x4*z|KpZK=T@d{thMx>E6ry4!Kc%K@b(G-5#TiMzZI43l zC*eN^;%^9Tm=cM%CZmNvmQZbzhaqg6i~-g*`G`<$j@ov+(kU#1 z(K=vly@w&vTW=<{T}*N(PNkrq78iQYO7)NBr;5;=CS+~_p|=rG-ft=kG=#RC-paq6 zz#%;AA;t9sN@m9UM4%p0+>TItkJ>1cyJ?bnIjp$-{)N$D#YG)>hr^1e5U2+U z{|h2Itaz+>S%&uTy2Bb1CjDRTV11uA^dRA!0}6wKgpY)94l6E|G&rny48fYlVu&b> zrOl+VHZ2YBK$FIS5PDegNQmgLVzMHC71A{_4+sX11_F+ImoBo`L8goR)XQ{{3l9#u zNQHC}mtVWeqp)dLxdKAF%D(X1u2LagCH9hZnO^W}mq|cqm-(DzrOQ-EmvQ;E>%2w& zwd>pqp9Nx>~e?K+bVce+k3q1ts$Bh+@C212Fl>_MRII$p=1G~bhe z?K;H-YS(#|P}_A%Ozv#gd5(zeIp0*{Qcl;|z!>jhbfCSdf;+Jl@bW)=kilAi=TCdSLUnSGnh^1!}5^uu7`M1cwZ3S%hGsN<(S^jspCr`a(hHhHfh7qU`SQJHkk+KsAyImf&!viK_y0C zcW%;qiKBDoCO&5kMpho=jN-vZr8;;Y-kIwa{FV4AiQ1LjrGxis$1Em>WFb~z#YrqH zgnyGD2yf?~yDLkR0F@*7spyf;@^xl`-vyRKg{6Mk#G#!#a48&x*W+JI=|wp#?B040|1j99M7N2- zQuxAsTX*s^L%6ITQItvsdbV!kzf15*lKoi_z7ScYayCS8K#NHwI0CLG@tg;&)>g%} z!esu$v@P7fb*svoB#K&i?tmEn9>o2ItzzoRh+kyA{gf63{>_wfx&RedIj}a_)E2G$ zcYr4vKpUW%j2C1jJ5*}rUxaLFKfGf@F5V=9L?A69`OH<%9pk|Erhl5^S(2cU%$7h{97Qj@|$1`D*q{` zcC`_Ewm!h`4Bra?x;;6pdqs0w=J|s`12^eEacR1rLOj-VMQ+noO0zwYNStL`t>uz1 zonS?*poOepQ5kyzR21WF5C0?|yRXb@>%R*s3psv^edyH?72DGav-`!UPlto%3)=+{ zy9wLt>1-8@hOQk-<$CR}ZXtnXKJr%eF8#c^1zTJJ&mzEo4q^;M z#bHJqC3PKnZsse%#NYz2udwxkI8oSg)7kprNvy4BK=yI5W)(sG>-Zm=J*0T_)&l=6 zV4XcY)mp+t^}@{X0oA4%GRDt!2A^>aS3<7-3a&Gd(~Sw;Dxq?BV-z|_?|Hmh?|Fn{ z5nC@3avxl#T>RL?{jCvesb1oBu3lbJ`m9_Jd2Zrrx#?hb;uCpIuJO_vF8<%Itrn-x z?8FcZvV>gi6(pkfet5088Kg0Je|EyVVo6*rTwmRoXg4c49{G6q?7xA z(#b3G`Efz*?6-ni%b=rqwU$@4)4vRAJAK}BL8m|UL32A#ONgk`cQr4&oxZOL3oV1Y zc|$w>DhTb6iHGvtPG2f%(CK>-teyS}h$xLQ&7?6WEsf>8p=taIp=oq~I81|bA%UaJ z8{GL5zU)1ns53VKah4=?oBA?&<%=lSXYg*X3YJg447Tp9LRfED38;wtjtjV2j1v0CL0FT145*m&mlLQa{Q?MU(ifRxOX1ZU_95K^i;6)%UTko23z_QV6l^LgURG_0`27MJ&)W^&D`B@^_X)L zSFwbOb88@>wjWkWD3k9d0=19a0}=I+a+6cHAC5C&VL$BlxalJm5ZXs>gK#F_8cBnG z_zJitq?&mHLYqlEvocIU`=Z)M3mOVX40CTmexK`nY79wG_9!+PL*!K z5MNQY!5P5P5azu%~A|1DCuneZxU z?-)32M?bOHX>J#k=I#Y(o7)Aoxz7f*&Ar(qT1}$b+%rIJbAM~lu(>mzHcjw0Tu~D= z88)}MGk?q^%1CWJgjZFn&xOz?m<8c9cX#uGrbTnV8>W@D#7(Q%u(@gVO-t)=-q5s0 zLugvFA)@A%e3kX2-b-na+_}jXm2!<#nYg^FC1gM%S*dQWNi;#+%{AU6C4+>xxhloQ zbw=XMxP!~(61}lfoLg|Yt}UEfa*cdAYYdfp>j#*jfVs9dB3BtwZ@O3)g;$$uhkI#6 zhV@A3NRwGr6DOJnZ)qacHgVH3ChIG&3U#Ho1I_HHdP1kBhrW9lp%2^8C!xI2k1=V_ zPW&a%OL2(!J0yORm_D|E#9zAine5!{kdU3cT;cT)yM!l+HYc}eINIFo#GdF6i9#DH z@1898b7aqy>p8g5EH$~UupAy^IYF=Rm@LYKH|lHD*x8A@BzoD$7(}lZ?afX+CZV#2 zFiNyk)z8;6TP-F2*@-uVLv{~39P8fC^9s+)PEq!N`@C%Belk&GDz*xNPmKP6*HT`_ zFm#x?iT4pZaVbg>2A};*zBfX&7%!t-G@eI!Rt?C@kW5$HKyA%6afwZpN@TS1mpz;B zNrP04PD8V=-_xHAC~a7A(ms5nZeEotqJjJPLqN*_Dte`%S--Lkb1%@N1>G$j{WGJF z{}XxJ2SEQS+EAu0T*@bZMf^)8GxqbZcp=}DMjHMoL??)X2tlm^!Q z%^@f;70LxCZ9#P_q<(MH)g+;?+@i91nYr?GA%xu-7-Qq>l-=sXn@jbyq3&)hi-_ej z649N19f?JD{+Vl1s(O&GV#6)NN%pLk{x$H3T=~aC^p#Rc-G*F}v(znFm9|=4K&rLU zR%r~ON-Lx4+|DU7eNDPm5@Rx>yZ_uv`N0vkEg|eFG9jC6MA9Q{pMQ~tVfUba351>^ zGYNisicE}OPLbIMHr>~{fm+git#?D{zSh%tF-xL4nUHo6Xx6f?b%e=UNswk+f6&YM z!4bBdA&!MZ8#83n){=d#TZk{(*IM_2xChzSy4P~&qUJ^k#iaj#une#TI9T`~azAPV3 z_91GOfgKDp z4)RxEtsVUivYJZQ?;yvl4DQLU)Q@<(@npY)+-jnbp;s?$TMU|ZO2;-gyY@Rs@8_Tp z+Lh%y$hSWT^Cps=X<&_5PU$#gjgjp8AXKtt19-@$vG8$WCZP6{b0M^!=qVjJZeo0) z*dTF8&(*Kr+QiV_!Qd?;sB)RKKPh4I!D*uVeD+fl1}a55rU> ztNCs!Wc7Yt(X4&|5oA?9%IxT}G1IgnlJGl7b%CY~gJ^^FwU&OnkMbiIsEeu#bRF+o z7ifrTb>RYi7|`~=7)W2aD9nDacf6~cF`S&ok!;+_8RNjoc_kd`&QP#!aG{y$QC?#3-6Vss-cfr7($xThZ+rE?sof>yS9s z|M>ZQ?;rrxzFah`3AJt=?^;zMhKlwz4>VL4Dn#*XGO??iwaDn?&n0%N`Gu&KRW!d# zK&^`6qN@4z0kvtzP)U0S&@gTNfUbldl*-8{_Mdt)KkYQKYUy0^0o_2L=mWZKtGMeO z50supRwq320o`MS>S<(WLFfl`yFtW1pvyPIlS+qtK=&0xm=2N{Y@(Yq1}V1nA9%~? zBoz==Cn<5?7oB8p&`2lAdy%||PIB|xfz;^`Q6iy8+h78n`Dm~km*^xffa`p;6(X3A zWTvQchg8u?_GaMMnW6$B(n-d;e4>-Q3>=+o_X|&vPBPw2Ty&Cd@3@m(bsSFm6~H=x z-3}4yBokde(Mfu|YX-^R;IleOj4iH{OmcHAI?1cND7E0|B>mh}L?`*4T34N9PiiXs z)<%qo8pBy6eJCg62>(^`qejGU5Y~tY*+L`Yc0g-HgrLfZ7!g&Vff3=8uW4>(ME&pa zp288STzUveD7{x zF}?k>AfnIr20HVoe!h3>`uyPYy)p>>e6I_H{d_ORFQ4!Iu+Eq{&qJu0a}$J`IfEe7 z%;^l_m^mX&nkAC;k2u(HpHIw?@(W4XAthu}ag!nCMbKzSX$*&y-*{UlvOw#2DHu{- zCD0jCs@-W@hLrA~njvKMm)*)pjL^Pz-x_mOE9P*jzG8quI%f#5?L&_XC1{qTRB7w9aWsJ)s zLrNtzsYA-`5aEy_X3kv0IXM_o+W8F|jJb0!gf(|UHf=^Rcg_Np_EMcRhB6iG4;ZxD zgc6!^__-8K&7Ex<9dl=in@KTumcwS_jG@H&t5gpO8bhSseOb(%SBP4tm)jr$SrBt) zxyvW!PB-AF*&5<-wtoh&G+SWqtaV{AclO<6Qkf4CN!&WaXU(0w&yB>bhc7aBa?IWK z*4(KI;~Vvbi7yy8Hn|Clx$`d~jLe;HU0BSWD}c3j)Z7^({YNgD{E6V`*q29nvgXb< z6NQc~a>?Xjd%R(feQA(TF?Vt{n@k-E zA(_&F$3uG+b0_z!FcryacQ+NXdLgf9Rv&^0vMT0IvCGCZ_Yr8!-05W)R1M8R1>Qh1 zR`GXHRs0u#o?b&2(=!U)$T4>=1GIf5d{yg`zS1YmeqipDxbI@_boe^m+=+2u?i>$? znmg4HadXFIRdeSlSk&Cv3=!Ycq2^BC^iuEgjZ?)qG72|0kox#fs}d@pi}Cqv{JtS94~c@gHmsWL)*IBmh@7)tXk>{ShUo)Lo`$B z5hiu@zl(&w3ZE^ti)yL=0JUu$qB?HS*2UjDr4B(II4Sj+fWa^zpGA*y3(e<#_kaeU z`!SBo35m6aL5)wz*V}N|e7UIRE33)LSBQqKaRi`kjTlJ2E(CO1V}VImvrW%?7&zV< zF%DW|JsjE^JN}T~8ZN80#&NJ{YmA3zrZtwNx5ne}*;2cxmUfpK{7kWGNp|_dM z^r5fGfIfu%MIS;j(uc6^^r6muXR~==E$bUu%NlWaY%Qxp8}?Lvk?FD8ReBA}Q_!-m z{F^p1!i3?W1`1c#K;`Pfm zW)#@|)ru)@LE_;1fHP(JYyJm$o)V8klDI2gM6Jn5t>k3%DX{LkQgX7-Z&6OJD(698oBcfgoT@KoPzLi}HSeV! z;9zW6T9RFV3Pb^fe%%;yNjY;y&P(%qJWON;ULl)^L#k(@ zr8=|RKrvTG$O>XC5KEPONd%irIwpdhH3B!#Mi2{(BG~Rma6qDsM&Jh82x5Uj1d_4L zc9BG<4oK|fub_aTgG+mJqe+7Pxiup5%zLa=zO$ zdL`-g-;8j-`**QTYrh&_cE1+l*nhk9(Vh8TV*A^joB){{c1yjhQQXA!zh(telB zXHp0LEQmZI_(aD`LGY&~>gTk7?!_(I_~*iDOB6$Gi4KA#D3SL}Vm_%4425BKqD?mS zzHnwJ2)cPy$J6_CJf(%I4D%+kkQluY*5TSh=aDnpLQn9Z8y4ov+JDtlZs{It-fQ5! z)chWPt3-i!pWNO(5MnOG@ZXZ0^a@cmk4QuI?!rE{rT-{glCR1a_^FV~B3zEbnVB8@ zpJ0jHw674GxM?fo(uj~(9XaBzJq%RbwT~v$S^H=r5qH&wFX$91uG*`4!MJL@>O`$6 z%m{Kfd|3tu(@FuhLaY$t@JvqZk&=keg}gdQT$1wt3zuyn7tFOSbQ&x{3r%Q5D25-C z#qmePS1vVEO-SmpcK#nEVrxXN&!_{@npgxB)x>C?Y)x!6Ikz?O9dWDUx+vS6{5B9G zUK`;{QiMXOjY+VCwV^)31{1Anmg9EtZzNXTXz(nA^$~_#S{1is1>>!GQ^M?M=Q3vL zXa}ltk=H&L@OlxDx{_0a$ce25l?#_cYhw#6wl?Y$30oH-r>%=lElgbugit5`B#3xj zgfCgiSPDy67qX3blPM5=rPO3rcoP@wFgxiTrE0|YyrO-jB?IW9MCy*O*X4P4(2Wv3 z;R&|otmC)@@8Lw1i6W1u#OT4msa1tXweud(i1x?{BI-y)Rl5O>HSC+DdRF}(b6*~x zMUlKelgS$r!jXd9*EC@ZK@ z@d8)z#`Qv%^;lgOS6$Dqvf_cRuD|E0?w;v+iR}8>e}38ZrKYR8y1Kf$y84)&Cec|S zAkV2h0+{j~a<6L=&1jn8_-FqLkSJ&WS|w$uvwwdFAZPzZ0`SlNEd?FV{=E;5a`x|D zVEway4aDN?-#x&}*}sc{_0Rt8&{82Tk+XmK5WqkC7eeCf-(nyqUyJ(m#*dBU*}n!L z{j+~IQqKN;0IYxZZ>KJFEee&hf7!{_t11T|FpqeyL!unJ91S2i^Y@rhJ2IOio^RDNex0Z`}grt&yx%Jb^9?0h6k8IJ)7%7{-_rcCoQWpvPKri_H< zx{Lt;KRoJoN7P=cpU{I0 zsCv*@TjQKdUSjy$qNOtYdj}?{){5P^jiYQ4&$V43hLM7{KCEGMx4R3U|g(W!x9Zik=MYvp_^E z0lWsFuoy)eX7qY#=Or|c-UciypwKIHSsL9o`i76552Cd;dQw7W5i98w615?W>K(lR zx3DO5DYUXNjP6`iO;r^xh4`B^imFbVl+YylR%(WGI}p*W0PZDl8hGsnP}nnuUZVLq zARAAz(*Z;YB!hk?fYM~7%mu)|N8NUJVqsgC<~-@H>8}*K7f82i7J~jsGlyq6dJ^@} ziFj^-XFZXU=Ld&nIeIe1=fV{@5V=#cDFYh``u8Byoj^pJo|)x50HE-mM*^}AAWMA` z7qg!W>|P+Es{rf=Aa9QvZt)V|iprNH9?^wq^s&)H1}$%oE^X~OS;^VW zqCbtmB@BEqGIt~{VIVLaK=AhHUYk#H_R#2c$l$*{8p87J(dU6x>lcN5_w=Q3?*7qk zcJ2_CxeNW=YMS(x&OSt`qF;0!WRq#qO91?7k|ASVIZcXsqi}N#CLc0>+gOg@(E-5v z8}K142J&bPuzG$XQ>ZVjDu8*LXlkCt+{Oy?cWmY%ESYbOVIF^?vMiAt)2rxbHgg** z%y$CoOCG|K`4V7_{qm~D!pvCC2e0WLMj^y_gA3xKE4uv|0Qvza+#5rc@f6(md|=-OBDx*G zM*zgj8fNiemR6L|J$eAxz{~E{Woh)u(TrAzq{P$G3BP2crzNzF7G@bVUHHB*xkok?b=Mac9Lt6zjn zZviO!kWb$u`5=JO?f`xQP&gG$9LmiZ>i5XB0ElQ00LuXst>)7+$aFJ+!Xd~R%Cr%V z;Th0YvXDzqpM?ZI0{Q%YgDB6gh!VkdWLtRTQ1ms=jB^J@NqSv8LO$odOAOk@0 z;}$K|o!=v+h^AV&Ee4TR?)HlwlZ`1R5SUCb<0qD;^Lw-oGTI2qSmtL`;{Bv^O5a|k z#Vev{MHEZ*@@B0fC`r8}lDE=}SPmdNjLOoeLbO*;8+Db}yQrE?dLe%FU&&>F4{HJB zAyH>RH|&&yZZYp3(}#*^beObjf-ZP+t2O}rfpnU?P%XdH9K?e)Y5x=x&N`isvky+% zPimdve2etxQUK0A*hyO33?~_YnzU>3o{%(WX;Sn#P=zOFh9N0ra@MSkH90GN4^RH| z%+SKisWVn*1AEj-yDpv)j7(EEAcL8jVbZSA=)_LxTaY`86ktr<;&2EQzC{;gG7kmkRY)&n=eLm=OOUxau;LrA zuJDr1SxgcC3Pe8`<=bf7@XQ==*EVpVHXh-!y{#Gm(;&c~ClT0@%xZgPC>E?{L9 z;I9B==9_vVzorQXM)72SA;yQ#TOx0Hjm!jK2}JZLWH~!B!Q44@Z<|=Xni5m zffXVDhJr=N?MDb{GWkL-w1wn55!o54SJJcOT$&zzu!CNzs0ZLLRTwI1!>c3FF+ln; zkByYbArn|XatL7=IUIo8{+ett$N!#M238H`rFy?==;0dGpQu$y(a*s;+=pxm(cv*2 zZ5^J4Ctrt#*4N=mU`2H;^jM$68O zZp|E*E_bjo2)9jRb3y5b5`NM=%t{#3Bc6-SgROnscxll`ft4$U@Df@C*Np7d1hUl9@I{J~ z!7Bq;lnOMCT?n!6bPs5X$j7fb98d$rgnBh?q%$y9deiyaTF7F)@ks43K}I9oqCRi!^6B$~VvArYY}LbLxl z0#Fsx2+bz6+5H)4w;rIX=kEZG<&Id=jQ9TSI1`d)e2RZGzmn~MzQ@n(2gpSr`FV{*~e+ zk3z;aAh2pn;Z+UW$59THQ4i9tP>?$Wq^k9(L$v9^kC9r2R8ip4^mv=og-9Puy(O&? z@~VIR1KNLvO|S~6NoHm4F&EX5qI5HLMzVFY+!W7lGtwH6MxH;Vz~YRK0h(7a%=s z%p|XR1wSiY{?6u4RY?P&Y~13p)qN!~)#-IQSp0&l@#W8GV;%s3Y0TN=2UrzHrd!>MGE$ubP?~!?h>vI^s@8Nw)=ITYdubPB{s%Ju4Gr!78JU$8 zehz5tsE#-%9fD0|{vF1XTXh_-8u@TK#@GiR z_!Cj(&iNNaNRCYi1 zX)#c!2?BHXV>c3IXW{|?!Op}1ojC=W&CbM6I;|Pgu>0Yjp?4UmtwP3?)x8nnl$ZkjLQ)72KF1Bc8w_^-QWVfRpKzO%9 zE-o&H05spH2U{1aH6T&itJ7(!y{435qsw^}sl1TnGNk(LRKQfUQ+G7H=+&%|^;$x6gp}54#yG+lbexwI5_%r)H4s_k7RkTp)wP zZkOv)6}DY;6|mNq2G-hW8~}VA=Wg2W-%E?>5qO zhhxm67+GZ#^LhZ%#r6WQy75w$0rU8mDdUV0b{So?DcIfkn;7$04P%fpo-*d~y=@+% ziv|=!U0ez7zAg^1Z0h21q;g|dx=PAxS{H|q>g!?%Q=yCHBegCD00?w3wGlZN#>n{s za)_Ki0T5lB0K>L)QOh!*i!vljSGfy7P{x)<%4pU$+*P{g>oN)fNEz1w@Vko4SIe|j z%GRi{Z+Y0DF_?CD(G3Z3Rse1az?TBBgBA?5V*+rK265k+>CiYMIYbN09^=+L{}gWN z#Q0o@d6YRL$>|CR3qphkLAYNNZgZbSoj6%0shYi>tEssd8OnGp&h*#Ca^LE%LSXTC zOz_+@fLF2B7(i-%x!G;U$-q<}B{N%@_bhk_bKVI_3pl|=Jalz1W8JT2tfWfZ?@j=k>>S}uAux8@IEzB)#($%j#|`MBgHa-y1jN(|p$W|@V3k-@N_r;416n|COE z@gn@xS(P4^7hlBpeWSUfF>DZ+4qyX-!n0yX=|_rK&**xP%pmXrfC~WNPpNjHQEk3@IU=+#2;I#)tESaSo)JW>Wt!efw-jBqD zcAI+$G%V#?no$EHXVpOzSwE27BV=9224qjU?peWZJTj$(GR;D!*Cf;A#xlts5HfYp znTAlHs#}oh8_9H)m1*(oc(4}1?|jE`y6JqUARiXNiylB)w8yv%XBPlj_Y6^-loVY7 zWO&WarjRwezkoug8IxoOg3iPj&iBt^W*aHUk?|*-@FMN8hduWqk=*Mtr5U0Yd#B*nwM{O)6vJ> z5+5Zi0?G;OfO`m>z`kInzhBMtwG-F?M2r*Iq~%gh;3+UKi;-*csi>EB0y0O}PJnaq z!jqA~u<)G#r7vEBpDk9U=>%3HEjkD6t|hP)z%2j@C&rM96JR}~Z-Znufo5kx1_1a| zs@)c-wn2lcd#}Xe<0TMnn>z$~*y3!DNtfcm?%t2$S$A(v3#EJS(~SJ??VTNT?+)$k ze)~B}i9E|vP67=}xsC?X;P%mE4Ex-gv=`!>&O%mUksZ;!3qqMjBGU-Tw6U>FrhC`w zOvNmz>SAQ7kW8;ynHFc96YAd2p$A{A^PP))?B1`ldp~+^hVxeda^i9yx@1m%QnVO} z?AFm<0C)~nPF*^$>rIe9fKdIu z583c&>Lg^ccDbVW;W^y%FV_;&z+@vP4J1L&Z*ccn1a8e`f5aI64BIAaqH3E0whb1% zHJNe{J3*H7L}W;+^LruA*TggjWn&*|dWs+Hy>k<3iexH2LxQ7O4ajAtDaxFn&lcw&TGJ9C0}gn*5p-C zj0Q#gle_<$i;E*zMS-l{5|E7_=2eV&F`Hvt)whES%ie&*+k{m97>y_qCR$helo45kE zzGsb&bVAnw^)gbQ-U#&_q7C{M^YwBMlvULr?fZ&ZZsq0BlbUwVboR!hTR-i7iyewd zIMtvA_orRCldeCqOw~+AK^ZxF-PGvsLBwK<^6*ob5JQr+Ej}^&E=X99qPF-c9oi$) zISznaG%)1<(2d7LT1V$0HMnS?*ocZ!P{oeXmPF$qnfgq?1{*ytk`vtqw9H})`ReLM zjg}5SE@ED!#Q`i7yHg`&V*N){;EbNC0?|7G_?589q!KNFWhJ6@0Hh*+0pM3;si{cw zUUo$uu_a|i-Z2${AEP)8$d~gn#JB_bsK;ot-b#!q)a5~-rTDo(OYv_5km64VonL&P zFSQ=$AT`kAyS64+{18g#>#CyHAU_~ZbatC_cqtUVbSUS!=l$i4xDp1*9SKxI3z5zG~wE+x3stEo&03vwg zL`(2Kq@x2m1*w7H`|YABcmi?uDEF{p~}hK!0U6nhhU!imks{VYJ1QvjhT%S5f(_9w|M&2+*=rq@JmE0rvz1UukP{5q?mX&R#^Cr zrxfheazh+nZhFrTYI>-2ez`QOm%ymSs(#?ePb4Xh!vKjat(LjuD6(kSsVYX?y2ITI z1-S*2@Pe~@s{0Yx7Zh4BBQ>PE2%j#T$k#XB;qt(M_fd*pa9%-@leJDofl~u`Vj8$) z-QeB>5uD1CB>dXX3_OV*)EE1G<34HOAbxdRe(fhd3zV&qqDa0+(%5$q&$VB{4_!D_ z#2BZ&9a;>+&Xnt zaWk3sW#*kDAJ%ZHc8tbE^tT!cH)su6g9WYwX zSLNG7Gw{GjIc;2g^jHLp*{5d8=V|d=i9C}=2hTsCij%Glo-YD^^25XMF|xn6aMCs= zRdzyb*Zm_(t^OwAAEc*8pFyU4AfinNWjf~)7!078z;XbU07{QJBhy(3U`i|e6vIWN z&5z59J_K}orhfAwR@0a|JT4{r6H@<$1iZx9gvgfw?*URi5Ib~mrt_vkzAyhcU*I47 zO?l`ah{nicL0o*%8+eF*J|xpQ0HEj#{v5{7lymXZ;cF1hh)XP5goo&*r)N4ViNBUl zk08q}0H%C{k_$kXh|kCtwIk{r5FSUuzI<8;1{4fA=ov>ZwEZ(zq8OVZb-3(d+16~MqF3@rz)NXK*3!w^m&5ZdII$rhH5p@1- z7a=UR!oEaa8DrILNd_$*nfG&j1|xfoqMild9kQ2ehz*?-!YltC23qdtS^+@amc(m_ z&7aWmey(;yGp+l%3h)$M`DciwaNf_g0_fAprH~P{`P1mQXgl;I8Oa_7os491!EK0+ zw`+X{H0z)*>|-cz{)89r@LB<0GO`u`kdc*>D)T2~)}ScqOPue}ojVW5N76n*cixmV zq(8dMGidD&htL~tPih%`0m#>o5N&xTv`1h9fR72>4B!xe(voqR&MyFt{MO;Xq(0HR z^31mmGvGSS-*5nFrzRyw{|dBxK`$j=e?e~&0DeKQke@F!f25Z$>0J%1e8%w40Qe=n zLVm{3{0#vhpEGPaT7OaRYyk2_z4$Tui+U#mkT2?u9;?5o_X&Vs|DxVy;Gkk4`)h}y zP<~PGRUh5xhw_$yxBse>5mPerWu*sz)yB&SnE4YtKa{r*vZ?@;-%2!ps$<}riMIeP zFJ7GwKwiAc21E7YmHkn~Y~=JmiYQ;!EA5R&GoRLT;0Ux7Qm62HZu^MBcif8P8*bMF#c#Mx;Wyk;zJaI2$B&ETyKP?p z#qYLF-HM+Ap!mJEGe>4x-)lpne1z;)q)xsTCs6rv>^`LOSjf*v^!H3tzQsx`_e`gb z$_(~Q3z*8|1y3T?-!omqRP33S!O~d#29=kp0Y` z09bpb`&b6{OmoNUGUfsJZDo9YmM-JivvnC$0Qh^R>JA|z7=;y8J%Muk0|qu$4j6n5 ztbf43V8ys_z~I<|M!c#Z;Z-LAsSH!@u?pq=BEBemd?1AVXHt!4!bb;eGFk1H zV*`(aE_`f&bfJ$M(%#eXal<0{u;D+E;fN0#3JE@JSR@}c>;hfNM-9&daKuLqNh{^c z2MwKUQ09&RFu-$R}U$q`>X6cWFutOdyt zUppj8&|^wKa>SPoNy47f8%VC-7V^t7=5GxEF^eByI_yF6dby2dPkIJO|A3W^lpb|8 zu>R}i275UG=~=zbwR%<`3?J-S>yRits~EtMR?kVZIbdZNnx3^6IizR(3xM>jJ`;@9 z%NK-9hAxxd1>_plp*{nZ}! z5|Bs4EvAS40_6YJ!}^~0-}SI^(EX+!wgDObLl1iqB+|qF4d6fYu)dRY4=V>?dYF6_ z+9I z;*>&7!({8{$d?Ls;3zrgZ!0mi!V3bj%|j~lvcP6{LMPxkn^Al?{{r`yFe!66J8HD} zfK<+{rq#u9T4rEQ$qdZt*u;?wF_oJi$Eg^mz>jkhI(8V++HZQ16Vx5di(1nMNx4=It!B(ih-I`bH|7? zA%8FEC{+qJ(AIEwXskNu%gSkxOf|@=LH6;XeWpfvEA78;Z9cs(n@{G@udh5D0QQv! zSW4LJHtB^LaAw#jbE_@B8~b%A@|P^_n9eH8Biro|UraR~}qAS(!1JUS)max4kB z4Ee39%eG>fS}@|Nf;0`wDnOYmDoxzT6@h_Ca_l=;iWr1e#M@8k(bpyp1m|t;X_Kv` zh#TP%a&uw76FpgqxB*C6kvh-gD%j-CQ}j~B+Qhq&J2b=K5R$ebF(-NundEEg@?Gv? z3`%L65>ukDM)k}hZmOPH^g)XMZSFOolNrT{K+BAx9BBXB+tZdW)+0r+9`{)IZocL7L{ zACFRk+ZDiF{$ya`x4Ach?$@UrGl4zYl;bsn4}F_E8%1yi5zU;I>By(mKY$SH-oW&) z0f3oFNDK7&9xc#-7RUpw%{6|Kyc}e7#+SjQ|qwlEUm-A0E`Zo9K?GAlfSLZbRNC3rIYr6SpJmxSh42|1!)f@o=~)m z4@%c6sd==xTI;$O0QnMq-x^!jpc7sHSfzFSGw1?c11-9K9%#|^UZBO=$00>jybORS zyj`L`Y25S?9rOyWt1ZL zP*WIlE}|)`3328HK@%ML3Ft=>n-$6DpYi^(^fvrd;=jqYXt@Tq)9tFAqG*~9KcJoN zNbFfO!*8bomDD`Cu0prd-RJ9envN8|Pb>wUw9`VMrBCDn?YC0{(9%xBfR=Xp3FS*W zy#PR(XD>2HgS|gnw^JT$squE|fi;E}V5PiLqYD@pfy=L}e-yAsQ-3QIt<>M>0!9Y1 zi!uBiLWnWkgOvYj0b?~dn=W%?du>Z>7JUj7s?Fp!BGYU%(6pNpaS9u*LfuAWuS^Xg z`sT#s=y_$jrH(JxE!71nN32YdURvxMV5Pf` zE!P7MLcCcKfM0L9E5Pa~<4F7c@n@2CK(+0E$fVkw1Aosia5YUO?B+S!>^ADi? zu3ihYboDVni^22(8!?#ckRk^27IXd?quyEbwdJf_pe#qOcQX3pTvh^*6(Bo`!8~lx zGI(yH05q8P;3=K-3*g0I&PK{n4CWD_f8AjI4_Iw5_8O&Ztuw;tv`~$X$}La8ld*~; zyZMQUoubD;D(U8h*IH{f47$=zOiVA@z(g4<_pxD4PfRY7m}EB?OQReF;5Ul%FWo4e z7wJZs1i){UK0r&OT!~a^lsy2XQKA>>M!5!n^x{1i>0aFJ;-mHAL*Q_fM(GB2K`$<* z0Bn?RkSvYzBmilYt5Muh8f6O5zuqXv0eiGwe8}McQ!lPYUH$eNhqYVtCvJCOV$0~| z(D!5_3OQDqKZ)iCCt~$k5;waa9fzJvx?moHTNMuK)0sKauP+9g7eYpFL#h4^kZYhL z-l|Z#Br|viat{*a2FS6CGt~`{eSnsCAeSP=zX9?f==cs~8zjm*kUsm?rY1r}O*PjO+6Orm{#4q20yc;F>H$aAvcn9(Tkp2>#jpPzt`X$y9osEQpRflg2iu$;>Zn< zZ|RI3kl=syS#E!PS7UOB@xT5YU!NKCF604C#}Lr}`g8PT(1mY(wCQBESl)p=A9Ue& zAhFD}MzaLCUxVr_@nQXhW5_A(m2ISm;hu_#NzS^CIEKs%QMb9bfGr0l-iInzoOaRV zA3{pn@&_RB4ZHygXX2U_mVqBcq8Rw<<=VgtfffUQ3MsyUclcQu_*5i{fp-U)Z{P*Q z;w9hXffWP)o@BO#`hesfq_>VwL_1_z%SQn#=s{cs~F!Z0AhTP1F#Idfn~tJ|7prN z`7*nVosE>SFQ$xT$RTCy1R!O63ZM}KKWs6Rmwj_C&kU|O{mEjhUit-AUi!ThK=`F! zr-QOMj)Zc>>7yW#mwvwl5H@z3mc}0KxGGb<^g9ti*x-4^X@iyn;5QnSWz|GorZWEy z`U&Q5z(Ekkts01tIA>iE%%7LkY;#wk5Sl;lsF7=D4nX6y@V^7$UptfXZr@5xsq)qhWZh%Q+M9p096DzKqzXGVo2on$24?iO2F-I~8c(vKkL595Qkf>t#_ zAI9rLA;M&g8^g{}gxlQxD2^2(snSKADFJV$g)$C7#*~5>?pxhuIjPR!*-+M0;MEW~ z6OdDN8xl9WW#0j{z(?J1G8RtNTR}g68@!sZ!@d1{&=tt~^nQ0EsLX2!vw;Y`hJd$~ zv|Q{LZp~X@-Xlh?$xW`zG;ak_j)`O(=^uA9=nBUogJD6NlUD;NeeqiSthFl5w}Ng) zTJ$uqyOY2L03HBPSQ$eqo|pBEZUxCQ0&fAh3IP6;YBvO`-K4=;tU}ezaET)z+BUb@ zRY7}9IvWr6TR|)FtltVc1??qo1?|y{da@#X>F-q#nV0@jItD$-yE;;vSu zJWK;=a64$S{vu2_kbU+n$xhT{^FX$E79QlSzXo3OkNz}7=K_P`5Q7RZXeQ;{Y%_Sp zFt|@MSZWwt4p6ql0zfBtRj0p57__@zhAorR;?!_bV5WE{W_0xA8rW!m+0q}3Wx2fc1!dzhG&7-{l7;Cdjhu6O z^XR#dDg0KXO(7Mz3?%+rk)^v#C3uCuq4lNw5?GP4<8@lf2>`-UnoM+d@}|@(koZ!f z-D|astcF{2-!C}w1w%A1InoS4v{VzR-v0)OUKVS849w`tglxOJMw78H*uLXAx54Wj z@pYLy-Ay6Fo*>M*dlyL05EK4Nb7hB9y?BeJhi7dFWi3b6KO^JSX9qHOO@z$b-8~_~ zYe1MgR1t1-J6*5jCaEgn8B+q@9SdcA8X335a^LEfwM%t!=AoK@175k{&j2}9&(_fe zPx&6GAAMBzX}$|S1m_&QnECu%&>0up4phbkuLdH<1s~9IsYZypp7TVET$3lDUi!sM z%3)k^?m2M5`yh>B!NwLBOzDfW!0JP*(saScAT4?o*mWoH1b~wO6n+JIn^asd>lr-+ zl6cZ~U5hht0Pv?&`$?eMgBqMg1F1SD&U5~PDr|G7AP?<`?J;Q+9&8uEx{1;e+ zxZsq|s%QBwxZS$I1s7|iGU*j4<;1-#r2sT6c!(N*JNoRTl^3n z#05X9J?I9V3k(`U488z^EyCban?cTc&0v>i@K(U!pa#)YP)9G%b8Zwt$0Lssba6c% zET7vNo^q4+xh-zUbdJSy^c~Rj0U*BgQ~>I&O_GgBie3gXd24gT2IWK5Tbt;`;&RRa zT70JiwD``V8!g|N(?zM8+7#dUGU%AH4!2_hg@psSB}7|ZvF_wkRBUpAJ^?%^isLHtbLr2Y;}{`r#h2g zK<2~9ta6MQkKV7Y$kId=Ao>|i?Y4^;q6J{9i1sc)1Hy+4{t5(VgCPDTkOsF|S+YDt z&Jx~%b z*4z!=r=T+1-1U}>g_TG)gxyg4NUylKXv3Y@RtF+F0>I?}3Wvs!@u*t#B48AeBd|rt&QKQl{dtVh$4J zC>1}on4;^%M#{pc7M}!C?mLpV@v=kMl;}s0OD%26QN}Jd`iP^9A*?ydco_V{M;UE0 z86V{+V~^iAa?nZ{KsQ|~TBMH#)fj(zlINTgV_uVsz(|kr_4UCR|1{_ddr!hwUNsB) zYZ>DQBe6IRKmD!Rag0wwT67)QWf0g4pd*07znm8)l{$Qc#OO~T`HDd9U76000Pv@( za7s{xAsUGycB$M|>gtjBm7v5fJ>nvp-ocikS0@eLZu zTDmo}P|786y4&2zpkXQBvMV&Wdo&p)dJtwc$Zip`t1Pm`AK@XmTxBZ1ks_@BnutGSAe@zWSj04oETY^}T$Mjspf#-L^I~nQ^}6W3}9u) z;x@Mk%Ev* zc1-?+WZ5y<1VDC75>Q;w6n$(yJV#RrwBHmVER}g1u-1-A|8VY((KifUc1%WTbSo$= z<|O`EsH@pALBy&FmC+YA_nZ%;RaSt?ZKhx-vcRHFXlk7Q*4#4EfIl2kI{$0#~&kyz-+0=jSpF4WG!uZJ>Hy}iBx}#+{9EUt}hb(G4h~Y zcZ`v*0U3;uheOzu=+7wH8YAPo1yNAe5o2TsYsScghhr6HlLces0MLb%rPPzCi{w^` z29;gTNTDKn!Y&yzZF4KZfE|Gmx7cNlCKtPe#_k7!ZE(%9tH@y>Gwy5He`gQ&=juQ`CvG2x7E{0>me|1jPe%j3i2#xQ+s`vCm8PsABFmPBVIoB(h< zLDc9V=-f`NO#S)UU8Iiq0ja0>srj=^gD&{nVSDxLtSdpM8g9Qk9#m%atThm!)w8Yc zSKU&bJFWu#8lUgYfbfns60xk}ZR|g)dz`Ga% zZ*yl^auoJN@`sx68z^1oZ*P2+=?nrQIuyVt0EKZeWHNud3RsF9Jq(T=0LcEc&5iT7 zdw}%!pNkPIa%|f4Piy~q4H9MldH+GZ|6B#M>_2xviogH72Xs7OaT^k4|9K$D{Qc*H z#A5%s8d%wXZUU^o|C|Gt#J`RBj|VKi1k&Gs4k5As-0^E`|Jg=z|M^@X{db^jr0hRm z2CTpT+(j3<7KO?Ii^qWV_n$j7^JM>dz#+Z={1vdl{&P>Anaf>f|9O;7YsNGju($+S zWpDU?0J1myF#v1-xqxM0|GCXKx{P7~K^b+8l(8nJjJuFS%J?e)DI@J$QwGG4KRICW zh|bsnN#O$)k7-N}G5!IIGr=aj@4QFTWs`228($=Q&I>^o-gCC;BtDP>7TZA=v)?RV z_^#Dlu|u{~gR1+zrJoS@9@HQe>(<bx` zsDjf|S@@=Dv$@s~c$ryu(2RP5k!)bz0V1`5 ziLaq|PsL>vDB&3tpa%Ls;&lr>(0>aa;*qfWdG3^8pcj&@?n6DW`uP$ve}~MSojGkEid=W%#+ZZB#Q$`WJHJm$=o88HWKu`dJ_`5(F4D^;PtI1ideoB5d&- zoVO!OJfD9AfoilM@8y!WU_rlBC+%|YI*?9WO!x|Uvj?M9ZeOq%D;2J71{g{8U67=1 zmFcVQ7Tn>M1!PM!+1`L`pd#Ds4*C&U`{fulojBh#@q#}iCtfc@%tOo#y zSeGEbFIET4yF{!pNENYK0|><0XH;s$`Ulu3v7D02QSwqvP;xWWy~8{Z^OkuaCJ~_} z|Kw8eLHfZrRYYU8y>#1w$gP=sjOVl%nd*#<24Nc=76_My2seVTQWI`-UvO13lTt0jqyBc7Py%&T_MC-8qK{wg|6z--gC+z@HY1+ zOO7cYpvW~XFt&5KJvT1PIfR7hjR1ZDFy&GF>;YQBv@)bp#ONyk-UJ}$qz(ej@XYhF zf^$+GU{DOtZbhR1Rk30u$~mdoNcGQ2ZL(A*-xE0nSaVKFx5*<$Q3ysgNK)AEF56ZLs~R39!5&wQ~)&q3cJOS z$^c7m60HHrU;>)~i~@i^9U}x)IG{l_!2Y3w=iDR>^9J(B`WhN~QVyJgy>vYu&w7Am z`^o_8Xe0Iq*c(Bl2H2_;7^||881%-BPte|X2$BkTVR>4oIAR>hwAuZP z^z5I07l`%NYvSme3d9esi4$)vuK-`CUIA_ZFZG839=5j$yju09?R|v)%PNYi%TCTx zmplZp%glwmn#ueLmRB@w0oJ;rsgPGRnLiTA zRZVY#sPU_swswX_=yZ5h({4OOmqVs!2{Z-p8i2yp_%VMB#L{NQwTc!1dlM0b$8-tM zA{H-n8i2&;w&q#RnFQtmI151GdloB^j(0l!jKt_rkTfA}O8{vAzKlo}d)nVr@Iul6uMb4~1IP%u2XYsAlYk)oS)+(A?*0cC9crm!htyR|p;H_0fm*7WT zajRu?g!p+kC;A*{WLiQtkTh|kRB}n@D2%zKaM4P7vCBIRxZYR2!LFSRlET#&0iOCdp{xiDX_mo zdNijMJPUxLhw)RmbahZLNwcm-^~ZzcG9aS$0InzSAb{Tikeh%FYYsD6B~ZmDz|J`f zWNkCxhygfd_T5}USL&i(#rD-$O!hvBi!MVZxf$zY0CF?d5tnh{R>^Td%3WML0Zd~V zvYTvVq0+K&HD#Mj-Jr!szh0~Gw7S6i4M%3Nz=x50JP^@|S%|^_6nE|(=!axnoTvv? zU!+Gnf@%#AFoNxUB*cCubJ>y%)83NOaT$vOt$=2lwk{9Fxq1HoG@7H7}g{w0l#N(VTjfgwoZtW0S<_ z>N3ks-rI0*>N3mQ)Mb`C+?HLCQ_&tHczB_~L0VUpw%Pq69du9oB@A2zPO?DzcES!U z%F0dR&EHPoE#MP*xn=YB621ntQ%UUX&+)UvEkV6qxmTh2Q|^^`DB#Mdfw?ql;2TZ^ z{It6P*=FJ2p{=2?9q!9P{#UI08kYPTmi(_uet6}r@1fkwk7s!CxMSVeE^EFrZ(c9U zushuQu^!|4RLbdosaAbSm-wZt3487);j37@Jv1=Y5#R>^1?}HVaq=oWA_}@$a38|w ztMnm%@!^RZPQ~JCm3KTob2o7l;TnPQNk&YQA9Hg~bl-UrB@F^z4Ijc;Hk(g$-$p5@ zUZ0;pQ40zYqt9n43OE&j%F}T>*0%5cJjKcH&g^3!^g(C#Jvc{H`SwPHR_CGVs(u;c zI-w)ciB8r3&BQ&LZ_PuuaZ}x6Tck(47AaY6Tco-ZvK%L_x9hbSn0#t-UizTcr=y*` zh?56fiEk)zmLE1*p}5(YsNZCw#3rz0|UN-s^uQsqxj?=HVquWCp7&G*@WPq?I+PWbABwKq-IN2{$HyaaA2@;JY19DIs z>T{qi2kUaGUj_`9xd#QgjVcHGNy(?T?f{z8aHLP0hU1*>Vb)eZ$b! z#@g9+M@O8vEM@%6Jcf^k)7btY+_-k`3F%}qDS2|_Jk)hOiBCYT0t=H&%vnsBkYxzZ zjyNPchx`bf>!XEw!m4@~1gVgFqG}Cl`@C?AvPCBOwUVAns>!4p)Vja6t0@76Y9i7^ zZBFDfH4aK+cP(U>(XI+sRpjUPUE4HjTzN0{jN(Mmb2chb!d|q>1()e@B7@_U2E=jM z)o2#%mg?Lv02WvtP9Vz};iSIFbXGHi#LL~5%KT9xgU5WcM5 zmA+m{mj++&vxT`1YR%%S0|h!xjc;=r>M4ic0=llUsmE$ZhP6-Ehl(6iZi~N#&m%w(sFi2*1zKo4=k@N)VAb1y9S+?UW zKGOW50m-l=&TW@&ySqyQu6gNWlE-E%SJ4haE_JmjC5O|OxkE+2^{%pj(_6C-#leLy zcL%_%SLk$=O3PRoN^zV^!TE>|$|k$aZK`X*{&Bh6PI^kv30JwvlF@Ol0L!>+_OC0E zNA;(xkj9j&LB*l_8lRivtajP&t{<9B#%nBjDBrcNKU|_?T<7|R6FCLX*Go}>+gR&H zoSc>{Xq{{Mg2;KGT`wux8Q}Q_&?+%ExF?F%ZgjPC*Msv-&;@;zu^`8}*+sDHY;@Bd zcA{GXX%G`MPi`iG#jP%F%ftx36Zz3O$P=Y*a$Wbbp{bva5HCm(h-7ZaVLi)O) zt=R}Wbj2xhUOI=9yR8&H-vcR(`&Jb91{A0pX&S5)KHrDuBTUP2?w2+*(m2io#vHUT zJBe@3HhmDSty=dXX}ciL!^AWXo*xm);Q7&@?IFl6Uy!nN3`5jib&HWGU^m%f6jEWu zV;YtWsXR|2<AnCBO*R%MI5q>Po_|7DvOC3;2c ziZv#|tL%zu1efQ1wug}6^);V`)R#J;tWQKZ-)dzzk~9B!;Avca5b$+P*H!AV9JmfIBL3R%prmV(@C4EST{L# zWNv20?B?OXvPIzN)QH{E4jvdyq?qtG)h|sCmc*t70Ze)<9y1QR_bQn)?3qhuxG;`! zS$2}lMNI!!!xHZ149Za~+nD)FTQmIUsNuhz8C==mn2!W?smk$wRba~|v3pRY30istbCsSZmg^N}M&0!e zW*NERDNP?UVLQQRE)g1Il)hGsf;#mJC?piaT!g&T{1PdcjO4nmW2)VpkY;jJyB~|hauX1cp^VC6wz zF+)WnGr2M_D>fRbFhK{V0m=dmhuJD>sx&!#i>hK2RIL_J5c#VC%*RU5Z$_vKf5qzpkE41WC)12bW)RdPQnodW zpfat4F}F=@d03M3jY^Av7cu;5BX_&7%=E-&p-!&{whx$6Ue>FFuTEKu>uAXhmYpp5 zK-^iE;12-S(p@mj9qY67=jL65VeU9H%*BkE6!-XGnCl)M=CF{b7CL(R%>7}mmx>8` zhex~IfKZQi7%D@f-3c7+`UYgmclNWjNTK@M{+BaKYspSURwr3=WlRKQ$u4H>j9uaw zU>0)+T6qzPW3kS+ROo+@iF*e7ZSVJ;(_8Ty9!gqEG25e&#fO#|bMqpCUw z-{HaFi^Vw8OO1_;2$D=IQ!yihWZ&10Qo%!BfYPgWwu8k|o$)$jd_pa*TBjKso2=Gp z#>FP9b(-;kCTP+HmLcHrEIX5u2FrMAjG*I_@fGqw0FJJH?M>)0fh}a@ofw23=cxtD zNx|9-mhenStIC-Yg!oZ4xKHKSTd2m~B96V&)Yw}bjJ+kn*gIW~y`>1voH7oU<$mjG zGhls#bvM1dJClR-EDjkJ0lkvQT3R!$JDUaukmTZ;}gG$AwQ*VJy&f}z%p67SIr9p6HcVFH$(oYWY}B;;Qa#&M zL-S=Zb6>26nRRA~7gq_M(ccvTMq<({<(WlbOFiqU84hq zYyGvh>sXRRqSxys9IoH24Oc@gA*>68mcFt+h%e-s>tSkjWkWbSwZK{VjX?$pIk-G# zDT^dGhu4udhAEUPZ}AfmJ2BI(cJLt@_#H@8scg?p>PccR$GOeVZWeE3fn;+yncCta znkC;rsl*mhm|4i#s-KL1xWg7jn&(cda4rLFQ_ubq%I{5_r9($9v4NYlDzlwxvm&z{ zT8+w-?v@gR1&(`yXHmtyhCkc2L7I?`4r^)Jtx-ew`!)4fJ01wt1f2@1__fsz?YocI zKMmZUS@TfQT4FE=B?W_!tZ>LaM6y}aXy(T^5VE;HGU6eK;e4m-kBp5hZ0L9^&2|j* zokxk_R8)~^L}d$O5yJ#>*?!z0%LiDxP|i!aE-QLt0!wP^%c-@+#GKefL~)Et5Vx6; z#0*2YgwOa^L~Y@?tfO5z`F8U2TjK9}_^H;16!T{RPpSAA0uF zF(t;({x&NWI#{us3jadeuPp9l6M|v=BZ#*KAQkO_wGI=QO57IgVGXk4I?US{*$obd zv}(aa7Ttpd55Kus^blWLr1T&wiZcc@!VbYk+Cj}I z70KiUkxV`#j?u_L#SBa%#Mii#@U(fT0P4RV;tYsE)zLR4YVy1wF?A%7x5INN%5Eg|N3rQ$aBj>bW zou=5D7?;@L&vX^bl?Jg~SrE&W2j;_$Hbb>7RcrPZXZrT+d$L)6FH6>wn2I1p))3K| z&JR>N2wURVEDh{NZKPB-(iCdtpo;o14e2=53^K8TV*CWhhFTS^UZ7%8ESfmZ+@M74 zgvQQo=BY?;eh|LNUZ{x}7X~pQmPw3HQ+^XSU8@bJi&T7fu^|WoImUNORE&z?O=b77 zOI^m)%P^V+0b4!BJTqJ~cr&3I12;9gTL#LYH715r!OyS8Z}2_b%~ZRRtAYqe(yu@n zH1$B5D^-d$ykDg^4;i(Qmi(^Kax!uYA{mAcYZR4mzZRt#{c&s4)W=$*x;~u9XlZRs zfFNO=bgT7YV)nEfkQ6LhZ3wbT_qq|)cAT3al8XCo_QOg9Zf1KA6;g8#d$*Ieivt31 zGq;8)&1i`L&d+bs7{>Vx#+opa3x-MB>Sl-%9Q#20rt~8_I$P}Q)h)QAv-LN`IDVfr zYgX(k5i7zm#%R1{la{iao2VAG%&9PamdrjC2D!th!jv0n9=MSf{^$x?9D3w1!*f_E zX7EYX!>FFErRl5~QPb(OTLoP%gPt9`Gp2`Axw1E75{&rSDpYH&y1JYL(Bl|_8|5*W zm*Z4hvy7HwO(h{-JG01fj9GAN@2|`uf>8@P9qp(NaZAvn=_Wg?D6ESKyNl5*cXRM9&eB3Ua? zDz@ko4t7p3td&T8?MJFrA{Ta%{w4%DF^JA2PBE)Lj8R||*rTx|fF=e6vClwTanzEv zGozZEiG%#nMWQ;rJwvZ#HmpuF(bwsI2i2;Vc*Sl#*5QnB%rn&Iua_!tG%T`)b~VUP_Jb_s#7m6+m@kjfa11ro#8!o|p;3_vnWp*lG6oczh^oY*7tHk7 zP^uKHWuPewf+?IMlS64@Z!@x7M6Xy}(hZG;te_^!7-&?pa^b_Qr7h#K&iC8fL`$=S z6ca5~2C<8Zma0@hTdl&J8WrYX&&ZnjtK|!99Who?)9yLGPG!JGL}bTNb>=A3JbQ!= zMMQD{$gFDxr*sxEzQM8<&VQ*Or;)WR6<;kev5~3%C3Y;j)IYm}Xvnu`!@4wPW#Y2X%7h&h1s#eZ(GkVcEU%QqQzlBh3S=geaRZEy z)IlDuY%x4J;^dc#L$38BlIwzqMWXp5&wJ6tOi0L3$TTp6A(PIPEfbn?ZHwt#&Wc^B zxk=)on^n5M!n0B3md+NeUHL~?ZWSf6He9u`txndZ81)1Z7(*V@<&_WMx|LCsO5w5< zr1iHNgTN=W;MM4YjvDm6*nWp2@n*n`aInW=c;nhw5)Q)$Ih2hh+Jk7)kz++uGmbR2 zS?A}4mRs2IK}!=zSQ~c6{8LR7a^xb9B`Y|#GQmVf;2r3f5fv##sv2Oc&h!eEknJa+ zDUD6GRsl+53qIkoI42mp%|@NSjTXC2NB?Fo@j$^HeObj*1`9mCEcA?>^?;9AVHbiN z1x?6gt*LZ10Ywlh`D2;AwBwKZW@8TQ5HJN=QbS)4TQ-iye$YfMQ7#FWOtjM5L@PMT zqGG^4;kfaH*n_NkS?82w2JL2pF6QJa7I#c@g~!bk14Qg8SOiffk7>_Fj=h+Ph_7h` zR!2s~15L1dYDjuC9ZuV;E*q9>uwQs2jKId8mI@^r6ywX&t&J`49TKQrFAhkwB_1>) z=Xr*Pqc6ST#~y3Kx#0m1GeDlHBAyXJ#52P&-mV8 zl!N*?9!~OydL-cFj6c-N;}ky}k^u(mN@{^gR+fTg`CpBuKrb;-acuZh5(G)p)o6!P z`HFX0Y-Ck#XU5`^wL&#h!+LvRR3E_ zg*=HWr)I1UGGc)I)&zl|l8=WCdkOH065E0py( zHm4?%%W)K&=CMK_m0qb&(&Ie5aUkHu&cUPbftBm7d%2ZldLmbos76}1id7jr1v+BQ zuapDjS7FDJg4h3nb&I-*N4udb8Aq! zGgF&&){*h``jGhzE|*6TE1_8W8$)}eAC_|SPYomnhqy^m`+5q_$s0b@pG>W8m6PvW zCgT2{3YCN4$R}fTWTLp+t>`W$CSvrpRdj2J@6fAq+`hA7GB$>i!F1sFL7XXb zpSwaUOMH`Pdzg`8!gKN}n7kY8RPc(E@i8UJVxi;QYn7o6$6JDNJ?uU|k_`6qLLr~p z)6;J-K&GAHqSQ*~gGe;hR0qW#(kVta5Bu5RE7`g%oG0dW&k(=(Xm}REBl9E;g6-W% zF~*_%56{ahcB08$E25(%qg99QvY6+71i?=_L^BeFL!!H z-Q52~Gk1|D`E5n#mMSq6`^t*xxs{dkt9qT#Czo((Wl8nS+!Olr#{Z1m&YbeH>YBOb zxwFbEYf&|w^EXu(yz0v5RF_n$%+o8Xb9?ue5@(i{<{qhl0Yv-%H;O9l(Ia<2NH3v> z-13T<<<rw5YOJ<$ z-pq>X|DuuD+<`^r&aJ2`?^Rn;I=f_M`P|&k0F)F@gQDcjt~fbNo2G zn^;peud=*m`uXLhb-icNdkBAkxG%zhxLu%jQEkl}O<_}`y&z9n`HZ>1PME~=VVyJ%tW z(%M=F5l-!*xpgIV<*I<-0cFpvD?;}lFDX;(D=X%P*e@uV zQ(aL#Gf*h9Rw~lkMbMT4W7G+u;VI_^QXpYQWlc$lb7f8SOk1YfMWrRRbJ6~a<=o1O z(vZy6Jh1bs{qqh@G^84K7<7-sXvtK^{= z-Daaq7&8g6k)cYk*;ZB6R1aHFF}Hj|b;+DX<7-2NM@I~;2xS>jGY9riHoP3IJEx?M zgE$I>u%$Jyit>eQAF0(jaBy&xO2&f9l8Wl_VzPl)V@qm-hjUOlv3BSa2$k)OxpOOK zR-cI`nFqsRzXg`v4u(W6pvOsf@ofk#$mTDf4lfNn4Wh25s-kq-f|@zZfYzy~nLBN| zYC0$pPj#^TDs5KmqCpRxHmz!2WnD$doH-?nrj^uIfB~jonq$C2C6GgP?V@SW1C*^u zYig+=4C%mu9&)HQ1Qum;==JNS+gR1Os=T^xgdQV6i`#MQLR}oy4EX>&Yi9)NRESs! zo0tYoDBD3<=sD9QRqHWLtkzC}YV1ekiQ$4QbL%Rn&4*)_rT_(9tu96>uyPv4NSK8o zU*j<+Cc3tyf~^j0MRf&QqO#(`@;TG!pjcjcb;_n<;Fm(7$3|!MVqT=47n8(ru ztPdG2fG!M?Br2{jYmA)JM&yk-Q!$uk!4SG+4t*mk&f0;6t{otizkFe7x%8E3umU8Z z0ZS!lFDIpf6lEzJQiB4MAShS(*D!6`v>CNEb5H7Tq-DW1Dx(3Rp#?TS^}x&u>SbyO z!fEKb9QvnKl`KS0f?E>Cx=KJWo8P;kXh=eL&180T2U}CLXbcoeS*n(UL?5SNo`jZR zSEws3W$i=WLZ>0dknR)eCAvFm5|#k-_WOz+DwteSiJ{i_dj)Wi<#iY+XaTr^zp7@w z?uH}FtIOw9l!gf4b)ER;PEwq6E?g@9yp4Zy-AL1>=~zrW;p@mrO}%py>ms8Q@+0l? zBS{IP6Y3)=2`eMby{7e%q(>9HeLI%yO7LF)lM4dx9FTau^2a39$44S*3Et+0CHe8q zBQ3oHuex7Hk`6_j1n>7dmgGlTBzSKj3#gL3Clyf(?}=Bfl!W?((ecf_J+Hd;k(T2k zNz0k{Hs;Mr@czK!lD=WmlT6A?@SZX3{@k!6aS#g4^tKy*NXjR_1n(ag)dTha8HbM8 zSx@lx>{wDC$@ccJYMBX_CU}qSSdv&r4JCLt#@8q8@;<&OKf${RpsvPo3Etj6K|Lu6 zyHwM74^tT`Isbo3j>k=UH^%25g0dhQv=(s_yiX~b6W1j>(xj=E9@oW@m9|Cxda5{9Tb|3El^L z@G@$Km%R(>tB-U~@LJSIP5~OqTnN>8P2>8w5PRtpmn05~WQ~htfT~A5ECZED_&PGU zKGGUsRsyhR)JNJRcw11k_v(*YygQd!;&t>s`VIm>QCnA{4b#1Mest>-mPa}-k0kAe zxGCP9mrDIX@h_=BdV*JFmdmSi+6!(2CDxf`diL2@IN2PJ0X^8(Zn4= zlN!^?7e?BqRDrvon$>5aAn%q1`Eh;H4<*j~!^qK(EghZsQR3a+qFr9Id~e>@UW@!E zysCUJJ>RRU-|fBVUS^C8+*wiQiM1l zC%7#Y7R&RzlzgwY9uz1P#f@9C+h)CD)R?76M+q^!#*Xxw=6mz&rBEf8F2yR6a-wwg z&+^2Pty-q#4b$+B@f;WE`TsIu8_vB}b#bG_UE-rseq-B8+v`H9) zp=~yNl9vIjH#=WJ&ArO}NGlmh_A*~9IF)sAiGw8Nxz85YGv%>$apI?*Aq57_)%)mf zTA{T5^^sI~m6mXW-Qe>SyerbpO0M_5gtLZU^se8BQ6~$z2Go21r_~|)3JL>A;?)N8)n@{kbU6>E5WN&v9<@fO{ zfx%cfsK=Uc48e#wj}E;iA7Cn}n|RMOMU=2S(j-B~k_7MZg}ZDY=OuVIyyGHj`E(1s z@mM<9za=BeFyy-yVzfo{K~~Q#B@WVJ>2Y6% zV9)#a8yqD*p}b+lFM{~kMxc}?-m*8{uQ6~VJ;B@f4hDlr;(`S4eLQ==dq;&?3Eq#} zmgHlo`Nu{12rD=oHA(Q6z6t4CdM)b_qp`t8Q&bF1PhjxLM-+gHd%s(R!5^uefo%he z>6{-q5w@65;}|ESa8qDV=R3AzJZ$RyWj}ag+)CzvH7J5A?#CdU?fs!8ObA@F^CP$b z`03jGNL%l5r1cf}*t{@FTLgKv`I4z0p-5X2JQncCfxQS1ru7pzha|g0B+m&6)B1aa zg=AMi(k{V!UPzeMSKxN!@@PQPHes}+_a03d26&GEm5q9|g*jw-dy)HO#16zftT7!D zyg$~~qk2p@0dRh#1DQS)FohMqDCIJ(hrn$}@?by$lX^)=nAT6=RwUUOkU$473klQu z3oI3UARvMC2-Qi|%1f(9m@eJiOBe&wO7pfo1Y1n;RxjQaKOvIi-FgYCwH&6=%6sT# zv|<_?a7cZmOM-{4Fb<911$>ZRADJbsh|~;lOy3om81sBy%<}*~(*+3i@EGifnCCNM zo+rdS=fymaj(Hvv^E^(TVU){URN`3rvIrb%dVXXhs#yrZUM8ZDj`-I5pp$>N-rrvV z3ik0Bb(G;f^8zO|-XHh`V}Jib@zz@+`SB6&+a+;BT+CmtWM9LRa$AVayuE*f^Sm_< z<^r2X`6r_OC>YwR%8#JdN{Ab@5a4?qOMlt*zSN~Ru)H5!Z{G`G)XtN~4E2=c-S^vs z*-v4193f14eFXZX5>Wo7y8It?`CD}P@2c|UF~gImBya0)EB^q?zcVOb8^b`q@EV`%3sCxi8__p{<|4#ReYLX@wauw@6;9l{y}AUt0;6kPaZQoc}nsQ6Zzlwf~zTo7@n#4mt=s7U#Gas zBPx!^pyHC4q0*APuYOyR>sjPIwyr;P)Dp zhCcc|pd!^tceAZtalL1CTfI#|e{{V&Rn_D%Lp>#VfB9{-*v?w)wiUPU|8e);ab8wQ zzJE96({wkqbN~q=<^WkJkK{Yjl%pU{9eC5puf+FRdwprsZ&+woS1Mk zL+kzt;rL7w&J&x2v;tdueqBDFB3!~Auf|=@3tjprUGkak(i5A6v;uqW{JLDIE@unN zta*V_1I<|${vkClM#l4EM@;Ma>Ii}SN&wA2n}n|dTX23*U;v5dg;cLH_V-fFfrxcA zUMYT19^GFaF-=kUe_b9u9(V(Gn8L4EX7`IhtcgLK8iVNa{u1-gCgxuSHtqaCd`}=w z3GDD7a$vlwGjTTs^!<~O;ZuudkXWABB%~GCg!Aigi#i-0M&_Y}3g8PBVsuYwb3vb7 zq*@~&hpPh?>|FsQ|7;Sz3T(vr_5QJXe~RACd$|Im8`~Q8Ei+_Pk(KkPmAf$q`_0=c zbIUtK4Ld{^q5yV?8riymt%$Dg7~N78U0)Hk zygT~ZgXosOhOr-tnp;UF%Iq)MJXk4RE~cxvhYyk-uA_$=JAv4&YuV3y(hc(>hCHyS zj8Uu!+oItYxaqfrtqACp+f!-^bUq4AmD`g_xGB#*R>BqSqqc{lR@SgGYMuYx=q~%W z^5`2?(OnhM58FrA%4XQs{x2}0C+At07^+GPTNSHk9Rx*YMwE6sp^Q7Ek3P8DLzl^HQZz;O2 z_VQbLCx(E0JGOwX>d$A2!4>so_hx?A2ZoA=W1Fk=LmHZ?CPsv6P3@ppquAkpi;JO6 zX_Jp~MY)+?XU)t<;jeii<5mCAI-X~&>SU~bGq>KY*xzUQ*SnrG$$zr~)%zQASdl0v zVV`G+etw_u-`)Am_}RYA*ryAS6Bj|&0xa|cpFs}5U^BF*yOd2g&YarW?6+r&m_?FKjz6W#e22h%NH$g;0BLUD-&* z7en@(y0QUn9@*^oXTcHK_7^b-s|iCSsUJA-$qVXThuI_cBL&G{uOlf)P^RuHAI9E} z`NLh#H&P11$5vsj`@Xxxiu3GqSeEkF+S}X6Ea>n6qcLVA{o@kbzMZ7#P;_yJsKmzo zYk72=7LH>33^NLK3TzRk8@yl7P@JY--c0clTmGMw(N7qa`o4o_3j)BgP`J(x$prT` za@*w1i^^!1pFdaG4lY1?r^~jsBP!dbJYfH*lgnO-pv^nQ9!H?+%aE@*!%puOiy&@Qw0K>I$h zDG=KB8NxY+;wJ05mfqX8kG>@&i)~j{J0cyLm2JWV^`lh%WK;@HVE( z0NzAO`3MhVgzbAy8~bi${0nA^#|q&&aD6UvwzUmF$tBgLW=NLwRH{t9L3&0}`=ku5 zyY9o_e;NNXFC=eo$g`)li|LfigAXTX@^ly!dS4*k<^?Y={CD)*Ag`mA+Js?`vQEb1 z+|+t$WrJbscZhCC8122#ZYO(I#3`^Lc_?Q-=z&UOVsEjJ#o4^;(iLX&~1|Lmj5=-GFZ zZsHNGk*hpvV{?%}(bXNI<^kmHBU13BtE7ki<~;jgeJ&!6_Hj{8cDdBvHi&N5+DSGX zE}aleoveN_ptYi-T>^wk4fdY&D}%C5e8^W}Z@OZ9astFPk#<%Am$`dW5A zeGT!xK92i(GU=;x+*grR$a`NZ6 zQ_~V7=v(0J!UE0bOQi+#c+f8^(^BGvNna`@R;$Nk9%o32*NB5iNr@MQcr7V0Ikel! z){E2ywi`Fh8B$_XX6tDwF+a2MS5l4p(4Hi(ZYl8&ks4lPZ@LJB9oagy5KD>LdFwOs zKF+Gw+B~nBO}yY-rG#8s=PxB#3HrSk7KkUZhnr*#w^Gx?ef|psO>ASx^X;kc5XvH* z<38K*eW@5DNN8ZYzF!mFlt}k2NI{Ue-^OTc3T!0NFk#%vY&)vQKl61jD~7!{kx7TE zve!qHV?W-!LjRZ9NVao7qfpQq_OoLMd}0HLRY7O)AxbCH^Kdz@+S-4Fg?=Lw%mJ7Y z0C+sbIAwMq4M5b;*0E1WdYwYAf1T=eTe{cL8NH^H>5hybES^pedtK`{dgneLo+8-} z(9|ws^LHs$#vB_U5?o~aHB2%iSgi9+N_8JyXIq5bHDJdE5@$paK;ntXvF=`(coo&Y zl+?@?My6Y6WP9Tl{m1I-d4r)=!JWHSHy@9#cDw zXl5*9EJOMh{)Hxw^DAz0)dc8O-)3huiJFpbazwhxN0TO>rpZ@nVen5MNQ*HK5 zw>crSxiPEFMVW0bOSjoI)#fzX)aZYlYO^Zc=98h#kFwf)F0;)y(`|N7wfP)viswE} zwb?!0W}ndJ;jA{tWwyCF-DYK~&55)r=hel78;(DMxmo{WR;{4+tqmMj1K^ zGw#Y5$lc0}J-k$_Z=b87pWveIq8zz`-!e5gDA#6ak$gq-@DqM83zeN`YlFVhDC8Ga zgi6_o)EU9}@$9b1jLJDt2sO3AtwSI4JCj^sSGpOJpfmM!jg)TeSjn{BPm`%>?YdEz zFy}bHE5ZQJ%^KkCnQe~pUR_l5NiofQm`3|?Nr)gT2BaBrVQBNEtTxwWwmBu;=2uOa zo8h0Pw)eU;MSMUutq(zkGeTc$v-)~9v#)tE)nW#XnNfUMOV%cwnlQoG+DrgKfe9AT zDNvXRMIYG5>CyRPx(69{$+cI>!s);eOO4$f(;+LN~=fXu5pHVmp#-a;Y}yiW$ndlRJzfAxwc2Gsx28e zanfNF*qQqfo->lds1NccKPPfVO?Jfsb4HVc(oJ3yb})?|^r?KaIR8*w_3^r@_Kd5# zYL-{n|RZRd87li?1bgIS3!3F1vrvaic7SYk_q1<8)4lVurwA+|HoH!{e&D8A_* zFlCMf=D1mOZrZh{;@unjNpv_n)u5X41C#QD&syGhd&Tx?gBr>|os{>@Spd6M``WzG z{#GwPJt^-StUAkU14j9`y!?Wsyl;}~ET7s$c?_|r6R03UiK-bCQJn7*hC*r`ZLKH@ z6ehA43l^i9CMDr5_I5B<+0N|b^}z;Z+p?42j}=LD@9Q=B3am$33xr7`dr`}7ylJSN zH!mZvdse;H=6TKRWrLZ|$+U2un}&uq<2_l=L?{uB@q;3J13tELBI{<%%sn_|P-a`w z6r7T#AVxBbve`7L3HC61MadB6Ei85<9**rORV$!@iJ(wu!+e@BGR4*%C zA+0|%nNtE7m+S);cf4JbAC(I!7_?ma9$lO3P9>X08}aH>-`=4aACSFSHkoUWHl`RnuSfHaIYwiR33SD0^9Njso6nC0c>@Z!(`8(W$V-f|#`m-nB- zA*qcuV%VnKdJF2Idn>3AVP(6JFrP3eI@B>j_L-2z>ioM;(6l~ltJvwL9>~@4f}+Cw z{{+v+v3$)uKr}hOB&=;SA39BfMT){>m3py#phTGMN2q2GM5T|xXu^T0Sq8i#fmi!6 z!2_Odd2p_C)CP40VqF(4|8mOlj`V_!g_6+L!(?=(;>Q1 zNeYzi${P0BBbC;p3l&>p%etDJCR)LzIsA%%V3|6(cmsL7Dt3c1dSK5pL~E)MU>J^xzC$_9+xEi8;(=qve*@$W15|v zJ~2t3m6_hao+VxOGvv>W_eGa7a{R^%U^6J^191VX#lT%!9Bq1%#w^z+@pOg{ zQ0QjdC*aex(Av{Mfe~%`LuZKh1|fjhwriIQ{i1t4b-hwAv&l*=fqk#FzHQ2*e5l(P z=E|=k@MX^<)%M~LMzc7N&sX;_^344ghA{FacK9d3@cZdd-^Myoz7NVUF6gG#W*{rF zp}TV{J4CsxSW$8QHyK8qxU|;>1xhiS#UmB^kK(2F*)BMqL1}6iyCwe3!GOvxW#-;k zP1!RnISe@zL#VR?Nm()mPJ5%O9#KJs`QO1Af9jDMTUAvL#dpeo17QyxbYoL;`U|jc z)IPfC!RW$!yq(ou(=25JKZBrU@(Y#P-Y!7PAxj&o#B1(narE@X8o2k1ZP?P>*9Z;6|RQ7c+$u(RKuwiiGas{>A_1m_U32Oo1?-* zB>q~3kzZAuf3>Rt`0BzYQNs!?a5)sZtT2B!3qP_-wCTaBL{r7~Insn7xWl@3_LZfv zb?NMe^Om;aq~_kU8VfY>4WEH>sl6DnyCF=#ZQR(mPRG&z12JGlSmKZ2>o2mtG!_-j z7wvbdN9vE#9zP^)QxXdFltey$T8U0AE**%q%`qe;iG$Czp`Syz>#UO$y$i)5#XzgQ zD|Iflw*eEBswGhWvOM}OW6%;-hZN#hL678^2lPz0E@Be>*3U}+72OD_E)fq!H)6dH zKk8jos-Gbt^*=f{iDeEUi*paLjZd!@)eK(VQ;5#JQ>1mW3&FkTELa$j7Q4fxVfe zJVy!yI^$GEQ+q~DH@rJ)aVTnXpMK~RSwY@I>_gRg1Hy+W;pBg#2T^1(a*@4oOdF^f zOcNBKwQ2>>AutmBReDpoL}Ehfw<(~dji~{n&GoMpbb!a+f4{68{4H;&A&py(%~8{L z;DSN9b4z32(~mGv4fA*U2+x7bcT#M~1^kH$^MA#<0F&DO)4AoCG5DEhhxm;h1kTgf zk@%~(e;tj#dimF}_^YRX9gn|y_}7W}tGj=ljK8}1*QxkR^CQo`h`%cR>va58;a{EM ze!E%Q3*ubo0);cQQr&QdM)MYg`QmQ<+7yNi6T`= z-E|ptr)JcBr|!B_GV8vbQFnSq-M8wlJB=dI_j*J(g!R2Q6C#m}U{sya!1B5q(6mnh zuIZK#%-J#~7|faG=QP3QXV!fwsmstV5>%N(J3(XqC$>=vru(>p()I;)Vl|XeYH3SU zuSFNH+5{mGh5g`s1e9(hXlM(Qh8g`QhiO48Y>ZG~c9vS@FC+zW?KDTHa%}W&*3OFy ztsyEPe#=gp*0veB3^Un;&RPR83Z7=M=0iIT_B}+-vO%e_sia7r!YNqSed=Wia&(gM zu(p=kVx2ZEvWum#&R5-6QgxS{t?nYP+cj!&pG4d=@i`NJPiN^6Onl(FkQF}vwy4Q` zbXLSlUi&;_?sI^j*focCfiLhydF?p$7iVm%oiSP&bg=CUnckQfO`J>vVG&IU+s|2i ziH}D_#l!TIV^xfY`X6|TtZVK6R1;3s|1)%_O3=HzL&G_Q<8*nSaYp~g^wS(mx28Q5I!W=a z8Vy?mbTm|8GvNa7b7^;9lp}kc+N2Peoz*8m##b*aWz&sNtLtfT*Pcq(PI`5YAta&20rlS8 z{tFdb6{9uhOlnwZ9@mIM z5Aqq=t|@w)=oa%z4_byEg0s*LcY9PiMr8d@hyijIVR$K1ynR4pFCp@tJyL}+cpg`blMV{xY(Xi6U~!; z-zOQ|uS}~SDTCdBQ;N90Dug^Qws7rm>^42O54{nr$AQ`(&g7x%P0L1iI5 zQJ#|*XHwQ@%p6s1E^NeK?^MEHfWKayW*|Q@L4IFt|jmEv0t$BD_np~N5Qp^ z&>FR`9R*jSHSdIJHSpHATRhuOoQNgN$E4K7=LZ8k@oXO=c;IeNpk28(d##yF($n33pp;fXzPah+(TQp##K>~xUaTHd!pWMb23@*^rL5FWortwck`kr9$UbM#=mnP!lyG6^A=%Q!MCkk z#ZX{l9xD&CdEodMlSA?*mUboYUAC~z>~3ZZ=ifsxWL9`)GN>tgm3HevjDZxEfqqa) z5=cJXsQDomA;lQ2B8&<}9O==a_@Z)|6WVLx7e%o`Iw1Ce>fA1_d!a;^*c23Ea@aXA zNWcmEd{l~U%OIGh%s%&H{hWDX_n)-0TlS13tH_@6EJb5Zdkn;-h!xvB%-?k=4qVoR zWg#k=@8dO74RM#!o3e~FwzWApOzczHDumnTltgD2V5kRu_92=jDRb^-cqW zRieP=g42bJ|2d=8G_QgK4TI3lVkl4tX&*T(EE&XwP!{*oG51hlLn^2Ncx}(*mnPWnZ5{77i!B&#iWbfW?!@vky{ktkdK11M#snAthKabHyOP;^D7=!W)DlMbBO z!FW+=uc<@$f4k~8G4`D;WHK)>PUAPZJ1XcNHR-4gC;u09VIOydwOQrIs5}=dAh>jK zLs6w|QACJDDPc>bqRQauM193N5bRKtB`^1-3oa7Fk4*D~L4Y;Uc?B2DPi@{riU9 zqme3?#TmO_BYoCKHgc9H|9e1LV0(LK$fnm0gGf7_f6_%L^P}(UPN?#TXgc&eZcz9> zunPyi{+Z(dD16Q0lHag}tcmLBE>3E2oT8B}AmOZimDpSA3*ZNfx`jk9Kmok)s7D@o z@VW3Lat=v#5q%U?T9tCxPwthzbzevP8kIIkmSdGOC$wZSWBz z=n`4OJfw;+mnBm1xnX08&avTwWOtJeA5V+4^e><8hXs8@oBwz0=I^%wj3%g{ZlvQ3 z_(pK2$K~c8vN(x9a_mVJa& zvurOQOe6mz%omR1VVNiCW}ESKC0%T5%f;s5Theq^2YqKA`N;^Xccz;&CdG7SZ~X~K z4K8QT7>|m(LEP%=8v@#5G7*(g8U2-=c#G+Z!)$uk=v(e7`|1Cyj*<~+jg5>BBwU+xiduGwTH$Z9f0tm4CD$Ags)z;c14kES z+Lytd0;6$f^hG5Qp|e8?rQs&MrvMcfJt=tX{r3m17LWDcTReS?&_RNK%$L)58cLdM zY$YP4+t~W8bi*pQB^BEE`Hy+-O?DWu#OY;p_hh7y)||$r>dp3rXMQq|i`)h;&ru1s zF54GArd)VQ8kw}oqgKgpjX3gS)bbpf7E^pw?V*niZ1^jPKFV*?4xxdKR#QJ0BUM#D zrd6S_eIg)gd|_aao?VXiMfvyWnCu{w9zH~qdtC>tZv*hEc*WzmS=6ufa?i^l%-!>6 zJj!Z3b>3s_VdzPLIm_G9{H{LqeiiEDArj@sMr*;tdzpfGk*6&^s&j-2mBH#@L1@T) zr{#tKhfLs^V9o_h);}SI)LJ^U9!4lzv>Q`MA({f8G_xDOE9`U6E z7*B4}C_9iKJnj(c$vtF4UzyH*p%~85o$rGj2SvO+p5} zY_UKsu|e;n5nYYA4j#o)d-`!St1pv^$Vcf2SNZJ!y6sc&ZN!~rNG^PGa;wk!P}`K% z!)X}}@i`rqEb59glPGW*vAFl#%D3^o!HY*Hj^F zxNvYdlL)Z8sJr;~#m+>h1+GP9xS)-)$AFZ3rt|D(9rFG!+LsJ(Y8wu~fZXC`oBFUD zfE|V$W;m_|^ZM>fEw#=6-^Co{kby(F_6?#CI_6V#kt}3b;GhWkH{0G(E{7r;y-jDH z_l#fxv7w^ZCG~DCmCK|6#abn|jtZ*aB`O*!Zwr+@Ma)pH`qiqg)u%&JO&jk}E31r} z&YzYP5_~0DO}iYir<2a;A9m^CzN`n}8>Ry@s@SG5Q)#53^>Dt}=qFK&O`s(a&23Qk zUU9#}#kRm3h-?A%qmph>qsM5a)Sh_UWmJiM%8+}?K&5B_pY9T^#FnVW{jLW!6#vnWQ4VqVdWp8HS2rK zsSmZVurMrMp2I$rV+S4Z8vfLIj-`=}g?KAV0nfFabjG!^^BxP95SZ}E3u;nYAPe54 zL-H6)w7rXH3w)Xi6$*>;71YhMzhV)0t+1)fZs7Y_{!WzU6*=`@BR~-A(6Z1lr#5vlU1IkJ^&y+kT!vZ^Ssz~127w<~|%%1aDxvg4} zQ|Z67cKZzvYzJ7&=l>Qb&c20+VVQu^(N8>5WA!V*3%^tY?Z1&)NY^V#y50KBrXV(B zeL)D{IH0EN2O51305mNUAL_e_7T+?ehqDa?7HJs2Y>m{;0VXWcK6d>IF>yPmQs22w z&$H|pfON=iSD_1RG+o4&w6?Y#twiH$Bh#s6wlhiHL~3kqO!H3qSE9+X;9`A2@rXJ{ z7wT^3Q}4?Hy@4?d=H~AqDU;!2rLn{DMH&2QDR}M8+d(L!O>mE8 zMr)6&wK6F^&1^$|Rqt>Xqh13WwO_1?8!dktwqU^>j73OvDfh$1r%6Y>@eov2Wl zF_0Zkj{^_(U7pB-q#~|G?Nq7TnOH@YD&Uqy8|kHO2YK2)1sfxLzXdBJH;0aUR2%6w z=N)Vul~FT#G}&o>e2(W+J1YqUq2HCcZfP{x*9HdZw84`UQi5)Q#qlCmaVkDR}_R;f? zfrisM!ymwKx}lEwKT$OraY0mGb-Xeicp=Or=n!^(->?aq%>_2BKddPZ_E?~#g(+vW z@JZYP-QH+V=z?Y4ZhRyCfR_G*5C8wp%IKH%ZY$N1pDw;qA?99v!8f~Rt6s}NvMhug zJEh3sgK+Pd8?$2A5rngm3U%ZPE@B{y~O|5DeG#x9FjSqK7WoPtex+z zf)efQ667mQvi=bO#R16x-8dE=kD$1kjlt_8cL!`taHH9>=HM}F7>%%dU-OajwBDIL zjEZb){*en{X|EqMiG_RIQu6On#f~KYO}RwKWhz`)$sBzc=Fqv>JIQ;1RIf5dS6q3O zHd#gM+a#=fE_qjK3DPpNZv|U)L2NI~3D%6OxdT)ni6mQ_SK|0bfv8k?-Q|FNYN(_J zaLrr|@+BC1+ebHbh}ziLr+}Ae;O30u6ou5XV_i>3Eo~Ruj3KQ3r53`oZnHfE!Frzu zo}{1$)5;Fwo2z(z12_g!K6~i*{AzTe2HILPFi@h64H^N`=PdGRtiDZ`V$sar>`TqF zL>Zz8p1G`3xx{9u@=XvKGGIpov}c}+2{CFF6wI^jv*0K6nK^z`N0E-YA*vyN%iN|W zn;(`pd%i{s@m+;h%1o#bCp~DVS3~eHVPxZm7wF*FOd4!tJ>MknL1tWeG~DMCB zq_q*!{iWot*(9ViKx~`&m{xB0^N4&iS$p$rvVUJ!Xf2s`MfOV!wz|AR(fxSdev-!< z1a4k0s@BcJMR}dvLO`gzAP735uBQ8Kb;NJm>|N|9#Ro&d7kK0Am$D@f3&5wsRZ$<` zg;bhTXvQ5i+X>g7@EpMCa&qc}n(PmrJ_MrZU5hQEA+Kf>$(CAbrzIweuuD}UgFWR7 zQd~o9fGKBXPGG=MtdF8(qUkVzm1`tszL-IG*D^wU$y;=-`;4xw(C@NjZ~88^V>K{| zByMXTzX7W_6a_XoZXQV5+CF96ZWoE;Uy_>46l-9Mq$#8CN{G}%|0L1$uKGq5o=V>i z`ij|3Hqe%?hydWg(s{7I!$`npN59F@FZ;OZ~($ z7=8t@fq6YmgbXS&4dnh79=Ol=EAGF;o;)0L!t9x6=Y$7w3a)`xB_ZhR71lx^EwTA5 z0MLV%J~Wh=3zGhl(;Uq^MHjWlTm}A3L7`0^k6COpaHGR~_#94*W(eiUX;>qlQ55v*v>D4X1u>PPgdq>X9 zsPT-$XJ#DsjGE~ZQ1Ln%JB;9AGVMHpNveQwG0$0QAwtcA<(_BqOcJNv~BZ)(U9 z%;c5-;jEJvs;yER57;f`(YHIY1($1&Y7EU2YVWKwx4;fS->9rAY7l1br%ZH)yOj-M zg`tH~+eeCzQ5@2f3_B~sz_(Z#xQq>7f&Q=He;@qitm3t1W&=CLdhNMY$m+1Sh`wu` zLpLZ#qGS;%PY4qZv)L~E_%{44cm#|0q5;ggSUu&Ac8q)ezfF9K2^`3*QHNkYbJ7%H z!AdA1uS7>yG+z~2C!tJYXN$NS9&%X?eW%}G5Zk{FeVh(MLCPn>-c?egMl*IoC%q^1 zH6hXR&a&lo0whkdL~4E4-VC%UwxsIXJRA}S1>4i)yS4OH0wB~(a&$-grgOB}HD z&&u$V##uzSzeVfNYSc8iG*n~*OkRBl#U(77<7zD!zra2@gQN2DaqM9Te?k1qP=~T5 z7njivN4#wf4ehjO+RvG;UW_rFyp#KNQ$=s6bPIVOQl=eP7)Qhn zSmsI@#?3{(1vXp1IJaDJ0Xf!VF&k9`;OQl-g|LoQES49*W$7vAv}_N9lKPK(eXChY zSvjfn_JIcZ$ileYew1{%ijtp8^vEl@_H%~+b=~sg@3&C6A^=ffomKb_nqlYCKqskA zEElMvV7OTw~k3$^AQ5+qiL5DXsVCWehzGTB=)~@R4aVf*k}r(G2Q$#LB#p zF5uH0<8yhmLO!^X7owt0Xb+{jhi2GDhzzL6-xY?6)QNM=c-G|3#pu z>#rQ#{sI>OmyM_Tm%)|5T^p`1|5oq9CtS1K5+cRrZJas=v=7v=V4I`=B@lE&CH5zg z8Ig5-yeLuEQh&x&mu!d|U45EZ5>{G(^%mhkA*CHXLt~ImI z#Fv>`&t=vP7@6wtF-I`z_nL@4n@2A*0jFOBHbVCd@Z#8Vyg95L&7}u&e0~?SbDJ{Q3G|)k*8$U5k#0UxWGv z?v~&yOAkRDQAI+0{1O1t!MBNzOiI=nke0ld4f;7yjCRhXrZ~xIjcgh>A-CS0j4S5P z+qCjl+n_OuDU#e8j?7Wc+h^qTr&e39_5K-oOck&7(HS|XSjp7h!83Ad;+)UU$oZJH zs~x_}AqZjan))DD3>kw73!+0zkBywRcQdk5OEc^bhO*WLyL`Rda^bEJ--`#VCi_Fd z$VIm6-^2vNIhJ+CZ%zY^4r}@|Q*!J5C0l9S4>C^_@d_miH1}E*+f9h+BKv-M_{Nr^ z1$fyzuskcrV(Q(Ro3U7?7Ms8q%hpjYL~e^cp7<|K<*d*oM8)e<;C$k+ZwZ>}>tmQK zoc8%{K0 zlWTRdldx-sPeQcOQX&sU%{KtT^6J4(2aR5)7~FE*Th5BC<*E(*gbc&Veqn zegIv{>96OYwKIs$@}{^L{$Kn-&@mGf-p)W_RzRWD)=Z8S=V{JoGBN~Dd1@qnzj#2K zmo%V|82Dgpp)@H$DQjZZfztbql074KW8Q8Nr!;sF`F*Kt*Pp#D6MTK^IyG4~I%=(8_Pg``(1sh`j=oA%m7I1$r07H1cHC2IO)9WrqKP&O`u33`~m!-a4jt8s|IX4x=yx5Qdd9(_MdM*TH`rQCn&mzGLhA`99Z-H;u~xbS&w~CbkEdWo~xko zecrgtF2qge|EhN5`c9miVn}^Ip)m+;)X-biS$ji+<8cx9Wd}=7dmBP1yV~flHiCsm z%DI%iKFFt+HAE^Zcpt$_#~Uxh~RjU%Ku7A-lkb z1!ak53P;`6YaTLdZ?z$lVgYdi*+fd6&Kv|opK0*~?3Fk=EnhxZ6EYWgO>du1msIR-INb9 zq9P6AbDWNu=MaP&vE>_JRIwv69p?Q~I6eOucM z5p%RxSW0_yP5}9e#akjAos6~Ucb(VFdgCTbj7jYG>b|)vKDQCj0TZ*G3@jQG$2@cf zOKWCL)Nq~)!7eB=LIIBNC3GLOmDys$XThiuiT;%i+Sk?(QS$bCAfC+jnESc@#TnJx z)Lh?wQ(Cf6b`XH8NBCGu?t`}E+@*c;I=iC|t6d7Gkx; z%ELS_@lq^ScBrv4#forOteRUxe`8%HX$Rd+Q!LKVTx)K_2tuzdU@`)9?1{T1RBYp0 zfX4c@8h3W|7q+JqSDwC~`-MK&l*OMz{zadMlH7^EfXjyM0=~aM%Ln;TX@XbUq)N6> z(4)4mA{WS-+3QlCGOY@wwp5ZNvj0H1LA+T=4mMuc7uG;N>J;0YETLAnZE?Fs znpcW0_<@dBEo2yE!_yGF#iB3Juqd(U0tYCDgaCF%#&GS{H>% z8cQ3z-p$(eZ7_CRpSeC%%xY0qv)YbGvxI5;cv`!tNUwvZ=X>W=g5Nrg07xZd*JX0h z61}2^p+%+LMCtQZ+JtJn%ns}LWF8i#qifx`;_L{X;WYDq5%mgpckGv^a5%vQJF|EY85D|xe# zd!4CyJ6=lyeK_6tWwSKAD;8?usLiZahhn1T`@KeCCtc&aYQ~Knc8yhYAz$Lu`AQ(T zAKCU{0M6*GT0r_y__{<1#wO4{uIr9s$5CBT6;EgHsfY_kg&<<1Uu#r^&tyQc-<#> z!Ot`)-DQ(CyYHp{`Y5ON+S)Kp-k2WN1)vlo^C_1FU#_Aan2v`Ib#AS$ld>aZa=Q`v zy~XD7cGzRa&w`4ZT?Wk1nj1*9WlbQ}Gc%l2Tql}IsyEgIQY}_)id0Lf6WZ_2HT5DD zR{;l7xvTaamCm)Fh&V4}b@^?G^MnQ`MV$B71mesQ#;rBr$uT<`=&uGE;0U5{Gy7ch&s+pbtdD@U58f0Gx7k<~&(WvkqrEmW zxB3x|#l*ZkSINluw^fSMbrQulKWI7SydPT4XuHUgLgX_Q2Kw346z9M_Rtw-_x&P|Oa3o?1HE1e~V(9Rln7k+;{ zLnvdI7!Uys<`=&oTU8go*I_{H>)0^6IgtIJiwZVXck9qA<)D=xj`CN9N$(Vw?;>}6U$bm z>~1a;#U6Rp;z2k>0y=PvzT67F5!`*`Ccv?&D;M$~PHZ3&X9s2l@z-BPlyF#$y3*4} zjE&?P=A*rv0y}kK#nb+|HE=hBxi}Z^QWmycL`&p`kM!c)nmV#vQuLoK(HgG|TUUma zVeD*>H)~X$u?VkP2^>t>1W&z>Eq z0|)|(&x~bn?n?N71tpAMz_OZLR|94NaMr@`HmDNmovrbl)+}LGS3OV9b!j}i-pG*s zU!w8!QUfWCr%I9`TjS{_z-;FmLF0K!#dGxO8qc!lvoxLsN`~00R4PU6Nyx$!v0;)e zX&Og z^VDEko zIIIacl-ex#h|wzZJ(f@EKcJ`hc#OlV2@Y8cdmSh&&Ol*#g2I9X1vaW-C-w(Kp%SK& zVz=;IQFz@^aK*0ZAxwHOT$n9&Y$M^a->av-PYnF*I)O*7_MEH9dF*whi+<`C0e7`L z_*XD}=SbI_LNhuzyFQ@ErL4ltrm${=1377ng?NsV{b0VYz|me+paTafT%?~RmLh1{ z$dCE#biLEMBPtS|9FRB9Q3MEvr5Nb<1JDifbULJ&%?0RM%hqQ243JmIJ#d@VP+qr{ zbO4X?=$nMZmGB#n2eR{8Te=lD{aGI_KvP~kn$TqH5qHk}1yY}vjwURbr&g4TqSF_W zv&n3rgBZJCca4hF?FeHMMmZdeg#dA|eA_sAL2kW2k1b=m8_CeWvur%GUSfqLAne@* zsy68*(8Nr<_y}D!tm42&FA^B}4P;9WPkaej%s-(EYU`3$kvHjRTb14IO$~bqF7cn8 z0Q%3Q{7ku`mhw}}PyyDj@x5%;RPaHQi{0KGn#ZluI*cQa)kO!2*oo z8Sbd;S}J{+x;@yz5gZSjhV!UNNMA|4ww&S8J&)AkNKJvPu?p&YcL^w=rcPe0Ag4_A z?km((DtW+s;O;jC^H-^>3pl-j`A)CDcY;?fi5IBxOFbS( zS|ykEOUKT#55BmFTIkekbX4y;#j3LXX~4*i=OCJGB2~Zq8HI%^Qff0V!Hb>YQ9dU% zd6H<5Rt&M)h#(yB1D@AtS7?>Fnw;vF#~ewvu>cq=hQ2P?b`WCSX2rdTB{*#&l5dEU zjII?9)Ty{&77WW}jm{F*@_S|}gHNi4?0{|#+q_WJLy4TQESI2mcPDA{a9yTpb=tx} zx{a!ukgg$!4Cg$h?IKmbAm<)_Ixa(1Bdo;E5x;Z0QEeCJ2=5u?@oo7pQ?XprjW`(df~Ety8m+gUfU8o3im(FF!|0c^8ztDuDk79g;#W6qv8hu4-bkC{Wsx6oQ@*G2wXl2$F2cB zd=)ddFt+}?g??j#qztE(1UoM7J&g$9@Z>=d&$Gt` zHnnLQH^%5cLv_ zK*u{se$#;iL48JRB5yYba}#?BCE48fHF*jOPXcZ;TdJs~#4RDVF0gfsr;~8_Ga`p{ zWuHoWp%G_)+6d2PRzXG1Efk5fPQx=@7#+o6J5}~-Di+%lFe78j(*j4SIE*7yK=iua zs?0}3bE`7LzlSHFl7}p5xXfPP|45CGTyMV;waB)M1{%sy+&o8zw}li9@(_SXMw#Q1 zJ`x-8`UM6^vv)>TJpRf{@i33}(noZCFTyp)3UW@yB4VbBqnR=kg>P5Vd&a%JjcxBB zZhO^`Z{HW5jSazvZHRBHS8ha^r7!sf?Qo?k?JTRu{R^wOWwT-ae=|dh^B%*!%s((= zi9IQy(-^nOVVGMCGE>K>zH5JtPfo|(8*>u1$o{gLKn$OzxGWf@c)KPd1**}Z=EH5A zaPi^h4kH@?YM=tMK4FT|5;IiQxL2fMA#VuRXEyG_>}A6-f|dJ8R(PxCzbmVF+qO$b z$jy;%-R!_gX?)jZouj4?MJ4Sd(@5tY1L7i&k#7nMc5!q4-AX8|C6$OmDN6mS8r(@K(JyTlHv#x*W;8C@K z9`zok9zkMs076$=Y}0@3-=Y#g3}xm4uNThEKtjcR*DU zgkGbq4nW8eMzE=b271p!ORs(EmzX-*qZD!q<6nXio+~wqTzpz@?nW|xQg%*w-_H8= z33NK9Ayf_WmQqYVTVN8V9aZLKI*mUmI}ZU7N%mA9MGwFkYipR04S7^dB)b+x)|n1n z`IZWu5co4vuU1k!J+*u_Uo8Nc%YsbGsxZgLMupcNC*e2^i>j4 z?+dTmSW06FkTkA$bEz&)Yh16b|BdqMU01?ayRzt35QhdhGB_Hhei+k=Lo~>{-e&XV zv3N<165`qAkn>21{eZ-32xQ9zc8>p+^jauUr~$p2rH^5OLMO$D*IPHLKEO+~;C}_Z zUCI5ZJlFm8`E;>E{5!ZGU3`<6mqU_C7!j2?L5UEjFNsq@Q>;PDM-F<3+g0MB9k$5qkpDYbi4_@IUjpdga44FGW;3XfxOZ@%OQ z*G}=1eabLlzfPPGkkbs&oh>g3u*-p(2C!N-;zbH7 zz0Y~Hl=ez&pK3IGRQ(Oq8{=rrpMFFVFGMj%=tk|FpeMCt-SyTfMUUx$iHi#JKa8wP zbWywf-@xza+6Nr3|nP78t!}A-iu_J+=)EzhXay8la zbReetR!5ieTM4Tpdj#36F`F3rU;2lzAi#Gs<#a*U)AV(zE6x-?{tRtVcgH56ZN$~c zd=f9`+tgEAn3p&hGhg9BzV&2fZgvlkLq^Toag_2uqedKY=1&oKed;o&Er2ZzZHU?u zB|a7?tea!T!Fba?lx5K7i?UZHchjxVz{>nH3W9Psoz7uC zr4l-anPW>-3Bj>UNdUhn0RMHQQUd(aa|5380r+)k;4imn0zQ3E`>o8p8Oq~+V^-XF zudqPCX1xn#V@C3r#umNL^yNo1;Y7Hn_SvoaoDmI(P3I0MX+s}?mhQW~vOWL%AfDWU z&FXt~@bY%Y$X;-mFMvf?J*~MjToVsD&Z$ftPtLl6O{rN27Jbik_SDL{&Py>IUyK7` zhNBV|ovQWpbRRZz_n~1wdyMTVcUIYk|CZbVfNtTMD{d*>BF5u^&6N<=CcYdlK>NL) zQ5F02=G;&4C`v3b8A#wTw?6!*emS+O#$yxb0NCdnnf1t>?tR@JQeXqYD@_byBUpvF zh(t4sB~!BDL7|j!2K?-&zv3y1E*^6?^&#W!w(vGra5xI(O#eJk`|?bV+m zQYVarf&K9_>L2(%ilHvL_DgiTx(S`bfl+B!?3= z;D+`4!y-tkeY$awD+MoC=Jq{|Aba!CLzpL0q>v()s|AJilvo>dQ2SFCXwU6|(NKa; z41tBNLW)L&y^9Q=eS$y;XV!mCRQ9v9-k=IStK1$E!O%5(3`KNYDf?#wnDG-HSg^sK zl$U=8N`)R=Kx^|Pe^H^GOVl0lLlo>oQm+Nl-i`M7AYj#|`G-txdso$IW{O%=>OIQj zZe17Lp#8}wK5&pM`)!@%uFvajXwu;K;w5?aS*ox+9`?7w3hY&m*ovA{xG4ftT4RZ9 z^pY|EyKY*95t#19c#o0WFF7S`&*9L&$JSMb71=(7l9|pN*&>7$yBKcPt3-p7bKx%f zC5P*$K&gkY2gwsE*F<+rUdISt3I1e$_EE^}K1>th#7Ase^i#je^{ZOHV9IZMvMkWI z=5nk5fOg zz6a>HD*Iurnlm5P+WI)0^=lkvbO%vB<63C$@zUE*U3QYfE&$pV+qu4MWF0gjU-m>5 zWP8NVjlvWuYuPVr!k3G#Ft&;IQetn8ZspG_8PUUSW*(kl3 zR+R9NmAB2Eu?Z$^!qZpM8Ylw*ynht{@XmDQJ0ZJKdvA#+u~aJixvS7v7I^3R@D)uK zSk_ZmXQqfo>N|{!=0#)cim>pK{lxr%;WvIM!yoZyR7$Kjht~^iFNWZZTdI*%6SzCR zk$qSdPk?@5-j!MB!SL0!2$|$%v<-VxLMGP100d5}ePhlQY%JiJGA2PgLCDIuQ*uNW zQ$6Vw8;Erd2Laa*l^Th(@Hbp|>9-cF-!CEE!D=RA>T2ziXzp%$F0mDA_B*kBcoR4^ zQK|G@n=R>aGYa@@O4_QSEH~Irdg~_bv)qmhTufP>M19y7YVj0n^Cq9A5viU$LRMxyR2=tB z=x<-BK!@3a67b6G35`g*M5caB(TvMHB#&mPEp9^$ZGCi>w(3wVzhwnIIeG{q-JnC%MmHVv7asyQ{Mphy@Cyv^-j3XQqB87jzKB5&f`2WVc&1K9-AJA;(N>gck-^#TsF8rP`<+zE}+J5QWsq6 z;eSYEaUkB+I-jnX0ncEHtW63Cn(h83{Pe{S{pKrX@$d^UpW0t)P2ydr@*p+L_N&w} zN@a>N7GQCwc(m`3{y56F1m*-Z}!0G{l9GPr||u+ zz_$|V!IK_q_`_-NE}(%(obZ_gSzw32D;BtyT3=m^eU)^b8?Z;~Z!3kM|GO@Pd-kWw z29oJyb3ur{FgnjX1r%GvAN?ZXfCwr*ur@^m0mCfQ3Nx_-MSa2whcHISHF zwmSfS^6D%jIqmZt8Pwmd2W%3UYr|v(FD*i$E_te&zM?-Y&+gOR z*QcJ`@}<`E7-W~8GR^N@`I^1cN7A~e0%D*3Zyd&jWp3uq$y-2qUQQl$oR?HHz4MK2 zM|Zi+yB~Wb*ey=>;IrDg(Xx!Wr}&f^8rUk2Jp%m0cCbEPA6-~z&y2(`!*DdVt=pMR z&F{170!@Qrn>yH+&gS;cUNU42&#{Svn1H3WL3f?W`X66uJ6T1Af$jhgH-QE%ca5qN z7IiJo&KINR`!X9YvZ3CiEo2(0dDiWhVC_;*xP{+x)gbrSQ8u(mG9LUB+r$qESV2$Q z_z5kaU-!CE7x%$d`Y7^^%aW&PlR$-~JJgmHK=g+9*{ZQxNek?K0v=fTuz%t6!yG1? z?;DhK9I8jU$+Gr^hj2Gm0b#;rHq}xV2k{KJJ}UjKwJUVPWhD7t)S-@qTkQRSG$AI$ z7#O#O)xx}?jet_HVH!G(s>6p->a87U8GKKFN;@@?X*>Hc5-?VXkN0hL9ima86@;7A z6j{UQH&UPti;l0_sAqkMc_O*M4ik8Qj~}g1-mdFZM5AI4;-FL%g!a_k;$WA>+hp!3 zvmg5Vqs3Mg+Agxs37v^bxyqf6UGjXUBbs$phQeQsa9e}iSK<`E7i_r;2zqu;FE zH1>?Xb(i9$Jj9Xl7gsBbBefQX3d8@L@@1S?ZsAun;*KoM|CO`p81}`k9zF%y+ReZ@ zc*_)mf&&8(K!2qIw(J>kb{l*4DHvV*VQkU_-1wez|A$hz2k@Y^@zePRN5TjnycYH; zdsXjiAbm0VpL1c5_D@Ni&PU!b2~R%7aLTzypG4#Ezz@wA+2iCB5kMVadrxK3(2=qX z1FSC=dOaG(``m%4((Bq-%fH~u-`4so=5)DL4rlPKN-m*Nrt`zF0Pl=M&awnV2uu(G z@-yIs-4q#vn%#ew{HnM}C{6!8#ga(&WQl?5!_|HZ`>CwHZJ5o6nQSte(Z-W0g?mg; zxc@!m*hykY{Ys|%y@bfkhm^x!rj_*b3LlXs)qA9p{ZeCvMo0)um3gIsy~BvzH@4Y75h<^>Rc&BB%mz5}6|E5tGmrVP z&$WHmL$#vh;RU(g`u|wc*=ocR{rC-xqljNP%TZz5{3EC0c#6ophIJFWn;s#!TmOd# z5;($aJwmf5)oeF@Q*i6`xP-mVneQ}|JQ%gQJ8Ic3;zxZ#E$nLU!u#Lo%IT*E4*dv` z$4;vsT{9Fl00O@Z;w$~ez$Yrh^m~F-dDpqYAJTB~5ZEURs))%`&cvZP)s7RGMhb5U zlj17K_iW%3s36t0jxGqgnA#Q`-r+awGM(SPru6)nam=r(70QOXd6d`v@@i}?i$*H<@p~~+RC<-Jc6!qpY&&fqrUZTt+J&YaSlcM^UAN*-T^-f z03YLxpCUGIry%D=m{z5w)<<1Lfm9#1;zyyKcc8%?ZnCy*T(bq(#qb-H^ZPv?!rFU- zDl`KOvUoa6Vc|N9=|o!Cftyhw`rq$5 z7<_!x+<;WAlm3Brvh;+WsCs{PC-A?zswLXA&h%O5KS_Jqtax$hm^~;3M>hYk@ zipU1G4LuIX=y5+icFnbG)Ylj9&{s3tJXrxR$L?3dHmxfxcn#O@-N~51KK%6l^$UIg z5*gb0a`s4lQuAME)bRX(4#`2Hkj z7M>zzw$fu})4#y9D*C$h9IiFY76EM#IpR4FP-Q%z>E)1)Yi*Ra{zsl*liNZcb@L4y z%KsPZ$)3ygeG#-{2|%2*WRB}(tjoXy+#rcUOS}&GjTucR%rM=NsqtLXK8)wgZ-DT| zyD5SO(Ut?hlF|1Q81W<4T)>!&V2SJ$@rAeRz0#cxqV`t${d`|M;3#&xDZqZf z*M^MS*D>}88;k<4?L-fiHDq(ph9aAXHWan7hD^($BTz3e;(lv1_59~_{!e-g})`kE>RlkI>auhG!*zYR|3?&VORF^CRTY~fcrJ7Tp@ zPKXR&2M^fPyS0=dLCU0j8SWPe4hK}Bn++F)NE4hHLROB4YImDZt%H}5+MSeff~3l* z>GO0>B#sC4vtB-4#r7G3P70_D_z{|>Mn44pOWYBULFdq&F=XWO>?#*$_6c_~f88qP z`o^NvK9nydwsYmNU!xA|*Q^gcyl(YyMwalo#nL{T+rO%x3)vRwF)N%}Zf{$PD$0k7 zWDV=J_HWuj7lCW1s4352R4GEW;K5EABRoqZJpa4~IN%hb$&o8VrG0++NK=D{%C@mR zydkGF72 zH-^!`!CDPqkYgX%oy4bmYz0 z;t3SEznY(Vb)BEC;u6InE4}pngE_uw6&+lZ?YQ5~B*%8<*87`Wd!1Zizht<~WJ!}; zsSO!P{^DKH69ZE(UN?G}_KI!mQ!aBG+0#4ZtKXy;L+H4ImyMzeQ#QnTXR{%m`PdW- z=)Yl4i#kUa-jDo!|KiH1V^!1=;l{=A|6Kk% zJ->o6ljDGh?Yxd|Gt?>|_ZAO-VsMoW_7y>M8MC2)Vdq6}GEss?Fq*vkh#0sq_`{0e zPhfuQI5@DkoPk{zB5Quh7SOypYP^^WZ^gKO$BNT4x}3n94qaG_juW5;VYaJ6!3pe( zz|lgL94cFpQ_YbHCP0oor&u-_VPq9o>`-W$xI^*wf>oS@SaxO@Hu$!ZnlN!y}s(b z6lP%#qrbB56?$W~l~tVvSGPiAp5(M(ik;ZV_asD_6+unHlC>h) zoP(eWg4quCt|!@8P`DU&zmOBPG{{6~>T}Pw9l}RqqY3QPPcA|31NpCGR4;2EU8m^+ zA2<_5*AX7B{a8~X|H;u$c&od{Vly=%%Q)4&g4X~sqFv+jc9X1#*KoXw3@tUf{i=ZT zGtvF3_O7ax*(BwnNE42x;_UaP;tPt(?u}Y6j-tDxt2#JG$D&}J%Alw|2gq`yu=kaR zlq(b^=YoqAX*WbJQuNNA_9|SNs3A#?NA22UG!7A#|C5hcM0a=J2=L zb{%4VBV4KlBDdu()W9lsAP+NQbU!nuor8a(nH`vhLe?asU%&eQbS07UTJ5ojSZkPq$~;HhV5+`ar1@OT=2; z^#xpmm$JprxJHRkjh5}%2`wUu0S*JaVHh#RY*I+4S1>Afl~siU(^XIL>CGf9rA zB&WT4dA*~H{vY<<1HjAb*!$nz+21x;gas6lpeP!HA{rA*H1@`#v7~x$yj(<35(Gnu zCN~9^4i*qZR1`%8K`bbB0SiS?P!Xl5h^QbSBDh$<0{_o<&hz}r?ovce?*Dz?6!!T& z&na`}%$YMYXU>dP0vvXbpx{beecP`L_CSJBBy`$g(-^T7#8qcoTsK}Wfwo#LQclK2 z$LP~sMfGL*-p_+|po zlifrAN5~o=6R#A9y8Xl-ZQ)GaH5f8GI)Yw%rU-*vpQpqA*l%WrmRHOHLB7u@_sw9v z1=t%kd@0A612%(%H4^3TcAUKT6f=kjy=XqOUrB_XG%bkGPE04+ps%2~y%J46lL*TMzSc6dg z3VrrSsXCoUS>@J;bE;We;2!&N;oz1?r&#(4Iz@R>kaaCaU6L@EHed!%6(Fex$RGZ| zAl>7k=VCEoWmd(Pz z2{qX~8QM#vQEMQN;Kbw%zmIH-H5rRUA$|E`Jws$cKBw{sD+Q-oxtf5~=G>U0`zwi} zg2(%w$63V#;h?6mz;>(kl~!q@A59t$7@-IX1Cl4krrF}FM7H8E!dFX z1-j3e?YI4AIw4`{V8%Y2R21SRhQy(bdU4s{O*jqU;UQi)?BJ_9?;Nt zc5x5rc^{E2c9?Y!XwoRHnFd2dh&ZfAAo+{0~#*o1Iy{RSNDL1i#L#8ZQfqr1JV-3 z@*Pn(^+6-))lPOfAif85*Zt8wpc#AFaI{9@a8bjwz}|4Oy^`55t0}q%^vK?~tOdjs z=G21JJ)k*h4F@I}?g6b|%Vt{JKB#gJX!#k^P*eASWRFhhNgQh3vvJ~cYkeFm)e#i#T@GaL=dm;l-Qy&n-LiN zDAWa=M~CMiQ7s|(OyW|u#2=y3ONOycoN#Akp+JzjvNZQjB~rjAvgQSeT745GTPf2} z;X#yv0-g?5^6+Y)r&LA_83-1jIa9T^eFDI$!ufhN=`%2(5E5k{(t^*DpwE!fL)kL+F{Q_4i2{2Ay`Yh;<#;Y5rv_eCHttC9vivu!S@ygKe}p{pCO^XL zH7T|3Zg(W*#*qlx34$uH;5Yn+8!SH}kgEUXJjtg5bJ5e#Nk#|C(Q$g_J4CVgxTpL; zM83kJnL!pl7!}8^Vy>TU@B8mF2bK~t;CyV&n6NAC>GrNN@V39+HuJZ@Jau5k&&fK7 z&qp{@=8~&5^}5M?voL`E2C7`avkyV>X>AyKb2cOf5mN)sAA`G z+dutPmOawGT;km81kfgTzu8e+y+O408d2Ug$-*q%99b|APPucz1a zG(k^G^z^8n7VGJ8J-wu-C-k&PPm}cYf}W=6X@Q=m>FGH=mFsD)o@VN4ww|8S(;L{v zxbr-ct>235Sa*1v@;tKM721Q|mWORw?xi|jxD_IlFgHU+uwrhlwQ8k8_8>98k+hE| zMv>GYvt=Yg$&2&vOj6u+vT-XQc$V=?oYqbIYV8o4HaWYrFR#c~^8#W>Ke&F6id z-Tyo%ly6OO$2PRTJIKgEEp~soXNzNVZtOP<&O%_e>Dse6+;FxI`&u^zd$+eu$Z@gy z8ulK|s{ROpRm0W;R_-69!j;n#MeEszvJeCx5GLG@Rxbb@hughVopUqz zWt0Lm7`Bzbrju$Rgz?OgD{V$L&#tQh0@HO@+{sw0hz|aL#RVxmrlucOqf0WVVW8YzqV<8E8oL7C1=zQ!{%$qJ# z3)Mq5P(0tZ*TC76&^^HT^NP%*sr76E#w%N}0JUM7Fj^x|hLZWBOE}124-Ym&t|*El zNLpeoIbTz5nl83U+zr!FKIQ+DXcSIfTTZD6n%Qx&vl#6_H~P>Tf>iEEgbKXYL(^z$ORR^)E=2TnLet*~Z}qoZqb^pUIcc+50?4c5iJz?)mg$vZRnTI%cdtSE;;MCJ$Sc&@Q5#)#I z*+q(OZRMC4FTl{QkaegBsr239+rFgQ_VEE3+jWnb;*34!hI3RWVMbPEc-0MgZ{MZi zvvL)-+fMLPZk09%O+)cLyn+LoPw=5S0fGDW>_jfxzGg+K+^Uq-cPn?AYhZq7S-vUI z1Ow9K_n;E(VoYVhvGvO>3j_4E;IU=m0B!mWY@yabTD1VdgZP(w>&eceR)wp7meG7^ z{1-H`RS%hgP(h8x_QqWIHOK{i+UH1Lkfe8@7NT#9M6vo-EEA(Nvz1)AtE8IwHM}TD zgR)nYv%tZMcmm`w1JZ&aEI_>AQQVeiq|jpj66pILqzyYGwc{zHn!ecGFQU6AKb&H_ z_)ynIDMTQV#B4sSj=gG1cFqmi@Dy=NU;A4WTM=1| zr0%#$xb6IK_-whKde$hlXT=|JczbrLYp9B0R}c3?y+xsU7vTv~fn_Gn(hrGWGP0w6R+$;dO(^I-udWSH|G3B)rfTz&vMc39FZbM6h)R<#g5@p%a>FAn6{6g zW4rz;?r1>h2$qR}ll+2&XJhCy&;CpBaH2u_o_IG$%Ih-?)T)j|$4XM(ZIgmL_R9QN z%9}`OAJuDY9Ri0CL27Q67!k^f3NJx2<_BL((!Za!G&ZyNz^O=~#ZBi&yf@Dsq z>ZQEfC?g=}10+)3bp4E^ym?93X2r0v2k!wkHcLut3JPsy3bw;+j9_EslzGOSV9#R} zBu^h)$kTLIK9$ZC@epwD22xH(S)l<1er()xYfs6~HS7`Z$DTXZ!{QBh)Puf06c$py zFH!GK1}!|kFFZm!cM1101AoO_xV@n=g+PCgO>=o~?6G^2_iPNJswYHG6a3OeIf6Q7 zh<&syA#7IDU5I@z{inpfyT1F5XJ|+#+r;WScIhue_N&;F?Dx#sEP_e%VWYN4#91Q` ziQq|Lc~7!mys^TVU%FFEDV6}&(hf7EHjn_{*G!3>jLIPHN)n(-MH1kM`7Qyj5B1ok zC#LAU#9oQk;B8uiKedgNiX^~CQ^iiSS1IPbj@VtVn^L_F3B7Jk_BuY*93GBQuQ!KY zD^k6Vjf+X{944ROC9u0#=7f1wkvYN5gI!APO}u6Z8;efkvZwfd8S*CaOg%njQtGTo zlRDXKd^@cqbz&9Zr0kr)awAdmaoqA*F9@3mq)Uj+@ThLhRxabUoA%Y_D zivnK6CCXLe0AA#f?G)KGG!@l6UN!x#ORGA3txj4Epn)NdvlV~mbAqb}RZ0?UX;7+m zCBVvQ$i;>g)rbwx_`7ne7_R#pFKJqfq2q~8*DvcQURwHrtiVs_pKOn8VJVT|Fq?vr z1fs#vi87J;aLTSeRFV~<6_Ya;U_gDfBEU0eCq;lqv_KF6mQK_CI4V4>7ftlLG(6W! zdqyhwOq$=H?5QyF;qJo&SD>dV(k!i>-`A8 zG6wVAofj*Y09m07OPlyslt~m$XGL@6)$am~oaQ2ttr5V88TSA&LW@?=<@!;kXUC-U z3Z^&;+rSeV1XIs(+>O&Cwy<4Ad1d{)l~0~S%HU&}@uYcTdkt5Nzz_x`$$<}GBJ!-A zSVbgVA~-)>C?^27GA;eHE55^NLzuG7p@SNBtJ47%P;$tylie-|+>A76ezj(#d#48h zW3_V5qzM>Tu!lZHsO#D`mUHsPed+c%Tl{b|o+mpm4(XoYJi2IAi@Q|1r0{6 z${Ob8F@9rhL@JsNhi9z41to+18ZbG^7BVi^NM+HxLIpl@yisBmaQaBchOYT0IVyai z?r2cTcNd`GPr*!v1LZoPQbTtHM7usjOdN)T;e<8a-vh9k*5(ZDG-q#Rtfntq#~w;8aM*l6#XVJ2);4NLF+as7>?l3&87F#J3q%a z+6r)=V2e5gC#$LV05u9o z49mSKSc(%T*mfP9$Z09d-k;0Voo08=2vZ3oOfPzpC$z`%tWvBfcSdK4;hRpxOja1x z*z~!%$jevea*%PjJ(g^$XR;}d@wjkRjFYrYR28`;`x4#yf=nVS|5D0g)m+1C2fI0F zkp>g3V!uX62NY9*Nwk0^3y|~}h1BjL;ptqC`NsPUo?xVq<@cF>%0$p@yMy=oy^fJ2 zevvryJpRST$IOn(PITr@T%w%sr(1v8;Y~N|!OA%olITG{?aOk1mAD2oCs$m!*Ikhy zmV5g$67Zaw`%4MRfMI_keM_kqlaoz*hC^+{QjFc9F2~pBVt?8M8{;;dULwwd$M*b) ziiY}hgNquk6W8!{&;L^UaCM~G?P*dyAD-;z-fZn?Gl59~Q^`A~pU*N0HCp*9#l*_B zdHFfq3uINe2nTq=7#e`D?kX%KTBy>2nz)5iq_7~J6l0F@4^D$c8RqZ{S+98-lQR`lFdKiq)?cLBi@IpQf= z8{yRyvkl8pQ`~V%OYQf9yF|=V%6ZV*VT{K_hZ#pt2U^I?$=H zo}}E}l}ki=5=tfLL{HKkiJ&KGUqx15S)AidKhUKd(E=av2eNbimaT6#t)`;f=!3`T zl`3{kHC<#VYua=w!w?FD)*toYg=+oLs;!?BweDIU*Ur>XP=A`Ud*vAy#t~%zdIQz~ zG4?A;a}P&g>KgXH;tKAg>4mO}`FGxMAmN-QXqU1K#QNo_p*jz)gXd>ywLgrul!^is`e zS<}F0vR&rG*ao1I=*4zl8~ymDN8FQ5&$-Rnd2q#uco8SF<+_Ndim$TtRq-*`RbJtj z9&=93Ha#)>9rCbJ0J4OSz)NBM?JCUWIqUEuzpe|nvmr6fM z%c#m!G`94UG+q!@MWQMb#rbV%`d^)uEy~$fQpf|L>|7Z$8=VqYdh3L;{C!vD33K$X<;Aq=8(-bP0@J+d+>%;yt}&**)sHfxS!7pq)>SJH!dZJA6$Y zYRBSB=rDXKwxyv%ZF(csC2P0uI#$V%1*fp#j>Wdgm)Fz*(*7d?#$MIP(FwO|q{?%2 z2*A|`=0Pe3xqRlu2I|*wSRPcYA$kvfWn|N)eSM(SSH~*3Yc9@^MON{;(xV|8@d-=9 z1Ayx@7`f1{9m`r#Nn8CoB^nZrLk^_!{zP=bL)5)TsbaQj3@{2SJC;+@tn49nMV>uQ z$SwRpwI;U05Bv5_{Ge~*@VhkAeN7PdkDY926-q0RK!;wEJ zMZTF+r?)T9PGk?3UvTZzH0+yeXUvgdebXMoWF(3NtM9y-Ja8mbk{w^<@1_A!g@_bi`EgbCqoX2qltP-FRwXfbUl5M;w!v`x);~ zxT*P2WC)$M!kO7F&v>yO|Hg|u(v|7P9R`vefa=8&svp;~I7~lP7IAhAg~4SNkG}nE zB4qAY_8->t9BWH8Jr-R0#wCG#JqB{Zo`HlmC?0@RhMVXPO%tWLVGP_ui6f!TioOEb z#t=?D?VOiY!v5eul?O7Vaaq*nh>!Y zjO@%%A62n+x_9-Wf7A@kcu2B{znm9dLNE(?d5$uf z4B|2(=#WIgeO49|{(rawC;k7h-EtT#Sl(E#Wtny&3_r!a55%+gAh5%6TpB;v4_cJJ zVSo03SOUfn=8jpE!dZ|?5fCT|C)<5L(WPK9=x@>>Ei7jkDAbqQ&eQ*GqW}h|=VZHW zp9UesLVkXJqadnlqH{foftmL-T%TfQIn;xK5d%B~Y@*gI_T+_sE3;+XL(U6`t>c`a zKeNr)sv9f*Vjg06H|C8*Hx34F-Q-++grHxWU(_{|lHw*bQIL zb={r}3_3}a%Sq&|S8k`r$*xkNxT|{trwLm+1}0J0798gy*Die$OXYZo$XnI%5U0fd zT^}<&A%!fP^$;pkaB$<=M)D~>;TB65g~3F&Ve!LNY^jbSqk|=M`F-+(bcG7#EejJ7 zev2TPM;Z5#)exCswdq$%T;`F#V(d^D{|&`YXO^F30#I=97Y3 zOa6VM00!Rx*6-6GcC`Tnb{}r)L6&UfpBei&B-_m@NSwy~56M*+pvdK=6Ubff486|C z+!)@3--eB0Y|L*_TlU0n*%&Au_-(}-RYk<{>2my;XAlQE!6_6#T+1H}WN??-@wwk9_6!AfG{d(qeLTuhv$jbZV>Vq=J58K z>9JZ$U>&ntClQI_Qk(eiTNn?rIH9wXZT>#33|R9-TKK(|_k;hwQ2>K4?-~0vh-i6F zkZ8RN`7XJ-iH}yC=$&n&9@O&Q7}gF-@awrUiyvr{$qu&Lh5ooNbbET4>oiUR^%x5VHXG{p^NYOc3p)sLoV+dAEZ3x(s-T?MI`2PZCe4@v==EJ!UEfg`@vs&WT@-H$EFnB<~Ngr$c)s_AGDEY#B=Cb^PNoUuoQ!k$>1TGA2K}l)fVgv`mg? z#WpsyQ)nw_XDjC7IOC%qd)k^mR@q)bfwEq5g5_u3gsp4H!eB&%T-rnaJ9(W32UPG? zuY%!`h*PJOL=e(2$}ote6b(tx6-c9uWS-A?Z6m4+r5hNzvvjMrB@=KTudvE;UV@QO zFP{WMy1qXTGqe!iMrP_dg79dY`Xl-$jQ}YGe6p}cT&~%GI8y1=%H37a2eiBy`fgo2 z*!7r!zjjZn&zq_JhW5;FbQ8A+`sl%SFNfr{Z5f8phITWjQ24s(ur3sw4Ir``f68C~ zki32|2zm!?%V|-NKI(DkYuKwl^8OzBH3+s9d~~XN;n(g}Sn2NVJI$Q5M-hHKn%Lk{ zSjRp-B8c*nexr-*nOE`m!gi~nRI=SR!d*%V#(m62Dk1>LK=l~<&tMgn!S=hkieH?# z#0E8kwnGP#extS9&Vv>-Ga}^X_16b$?{8{a1KwPyAe5P53;=gP3~opQj6Hb|0SuU= zdZzPtPNL`o`df-()zn(c%F8JWo(9mG1}bkKO6OW1Ts{TOb7*7f8d#t$&I03k)_KS? zK3N%#j5wlhZU!|ENzJ2&n)fx}x_GxJN1)jqKcwJ`zrsetvB!w<**Oz%fL2J@^=O#7 zb{ItYlQ`Ls%anHfJev&zh9ijYf`BFD1c&Ayg`&^mhm#)*!|AV%y$t=G0sou;0dl&! zty#{nY?|oLPxkyTm=o*!Yxy4Y7^rU4<$gD{h7A;KD}Uu{T43{9Xn9bM`qikKl~3_- z{Mdsw%M$m)Jk3JtB+)m7j#|kVYr6!%$KmzyibxupRREm5AucPh)`E@zm-Cn~#|mvB z0)rdF$kB~ohXWHKBd>Qg)YZuFvq@VKdrM-)iHX_vC|0w?y`0bI9+UVbjQ|af1^XFh zlYEY>bg`j0@i~}xfc0gbRG)k{MP0NlPJEi<-^vnw$#u5tMq&?7Sj@t|Xm8pZH_G6s zii2u_afYT%Y6lJ_$)@C&DV`_4O!>d+S-!ApT&9GinA<0zdR*Oq?%B|MjCGP_@!Cg}5JIEd%Bg!AM^dB-(*AKXKuYrY#aVaOsy{EiN zevje!pJ8TrLq<*kmEMZzP8aEttw86=GPlSlXW+j0a}b< zH-b0KCGsxLwR1V-j2u>C-wvJ8X8LvrkClyGn##KNFYxVf)=_m9&E9a%1Eu-Ks|YVL z9i>lpdvm5~1OUS)U%U>b`NNC>8PJa0iiO z%V9#|Zz4`xirj=8S!5G_3%RTdTwUO;buq>jnl%9fR~NnrHP`9gPbQ2*3Yt+e1gzBr#hPJ*h0`O zN#}9!jHE*XsOSO((oLxibad0F?th?~#3ub3xIzTU$EN>BZ10C=8rT!kVl(yuSsa_}sL5yXP)yR4CcHp#?2{M$@G6m{RKd3r=|G)=%#^VJMCx+!&lIP^s&En>KNsT^y|W(PoauQ_^6eo7 zF&>NDLbr;GTHEG_PsCrD!)i@1LF;knW!@Uw@*lIMv}&G)^g-NkQdmWngYp*|irj)GMrkBg4w%|_!CAAfi&`T#T=ahaA^&U7`Q;J@f- z*?E_;`M0M5yn_(NX z?+m1Nrf)Ds!Eytgu!gWinNQOgf*-or3tJdx15N=;i%YrL3!dF8*(DY&Yr3>|C z;0mO>jtZA0*DnKpfTk(C@&ft$yd>cAi?$}twcg;)A$vmHUKSs>19_bQF# zJA4mcpo`y2PmJ`QxfeQQbP)2YfJ!oK(Nw|~i&X0N42e$4?co^!3x3`ZVr$yw12Tp{ z2hiOvhOky2?_vM~>4|m0PrOKua)`SD@u9); zy2$djni11WeH$z1z*NS)EPIt5?)u0Tq(VU%8glKFJ2;m%${!H%hT3e67L}S_5_Bc z`t}Fa+2327#C8;8BHCx@=l%aFSB8t1=*P$_%XsW1qRXd7c7=}&$F)YBl;T|}Fq->T zVLO2lX=LPacs*gHS@R1IWjObEcJ2BFr>Qf0^^!OM`$_hwEDzHzbYOa%b)*|d{%V19U!?a!W5Y}b`>PY35ud5qtAKE+YP2^dO7Y*GS*9!A2Ss`dcV zFpaDHX3EzPK8kx|H#(nY;Tm6^gcL`XRv^Hngbg_!SWQMh|2*!lo~%96c08bc1FF4` z6`HWAtJowTs8;6-Kzku1U8WIjVu6pSSDN^vN9J683-dH_i&*uBQl^n+#y=O5E%+3fthlJ)2A{2s=TxDl zSk*ZkS3wej77|wPLQ!Cxl$RS5XZu$4^r>vEPE_`k!mLc>cSgF5MU*Syt~Bp!1Qs^q ze38A09_b$6bEZ0y^o0a2+H5_QmTsaVL^4aybIxW`(V*tiN{Mx2F)mPN)zHTh6@T>X z3gdylzR|yX=Q#I)5$V`*Cf%^}z@)Ti<}}OZxC_WKHd4J&1dGAUM)wv!_3l zjFD2EdtEHo{6P7YXh(dIDE#uEJp?X!8oC8RXVI$8l$Wl(eVT)M-ANxRbQFyGc*jZ00~Kc`&(16drZ!7#pihT>mom*xD5%fSRI(o@ z`@?kK#4D(Qs6oGhDLXcp8A_uAl z;_lC00(v^xZn{V7m9ucEF>EqVoQ?ysQ(H2kq=d03#0yi6iV;p)(jMv4Y{V&ia4Mzs zn@C}EsXf1&{%<b9{V z8VvKiS%ZTV@8vg}$J3-Z5}zjV9lIIp+g1+K+GLaAMJ#=MxiJo;9Exhrb@E9I!F7V= zzEFx3F*C(L#s^ifqm38>9hxNgLhH9VY4mAq+Xn|Z$tpI&wxaorTLliX+Yh6?{N9N( z`|+B%{D8pwLYuTHs=4Ua=#9rDl(E{LHQ zQr$3qDtAu$H(-boq^ZRAlY@P^u`L?nI&g_i;tdo5(lfn9SWXLX1L5SHI=p3^*ZwA~ zWswg{D(dv)&{Uzlpr#<}jI9<$XOIvfP3O}Oka`J}v-o`)E+n3x(3O6x4{U#Uw`3a| z=6b(=WoZ2v3(7x|OQoDopBqARL4j3spVcV~6f=bhV|uggYf(&1TlO6B*wvNCjE-go z84)vmR2|yWH;@?i8hB3d)egXF+y17&%7>1ue8C+&ZVv9f31lF5e4q;{fb{g&SvrLz zyJ(5#u(nO=(+Om%i#wVnKC#O z*tS2@%Nsk;UVelmKaeeeqDwvvEPqT-EjD4NuovPfx8uwX_7Y=v0EOA>D$oRYDVFEu zh&HIy>Be@*j&&2rJIMO67Z5O9ln)QRb0?kg?X`itK9ZZ%l-8u3X6$|0Ze%{gXYuFY z>-2X|G4@Sgk3#4e#!|MCf3vn@=@@tg?t5An?K0$tkfGrK4CB?dUXwu!Rm~_ zCVUC)l5gV&Xr3WC+~eCZ(jf4@*4LA{DHxN8s9|1DOrrkH7WK_xQ*_!#EpKRl@+M^5 zW^?~RUhmzvgdJf*A1M7a%=vZ8te;?|KN=;&En!wfC=YHYbd~1$Mn-t76)NoggI_>z z$J(2Hn0x;vesHk#q~@O7Srf#ezRV$5w1b1m|H$Ln6-t zn@u=7`gCG73$z)CE)XZzT2&By-rgU4?xzI5LGKGzvc+HWb$7~`)Usj)P+YKv4M;Nk z%Ao2cY&xnQ2ax)tqAN=+I#9W$Hxp&8V0q87l^o`wXpG(At}nSaXKQ;?Y5%;OW9xAk z1Ap7!u2+I^o_WnPp6LE;)*aQvYv~FkHiUJ(SwhrdO~I(`XM3w0FVvm}s~0$R637DM%DKBT*w6qUH zIKqkm1<>#Nfp2TS+qu?I;l_g`Xn*5ktEPnqs`i%I+=! zFkz$Kkt@)KyRdiJ?V`&c%;Z)Wq)U$LK(@|Ad#!?k9qNYTG~L zWWx+C^52uTX&-@JRQg158s>psWp}1==;lQ0NKjMl^p5^xgnqM*6-??66?EX^9a#z| z+8mHx6f?p5ZKiXRy=E~sZ#!8k0}vubJc9ze25YV8x)8Wu(V(D=$yyp`oCQ2083teMoMcHbY6))LIkFlK$Ct>etk3Pok?(000Uy5N6^UN?V zn2K}B-SJI(Rv3V0X7tS|BPQHfwRf<+vR!F)e`b&AXLJ43Mq4c6-uu>|I`G6YjQCC1 zd{g|W(zb8g;cmy+aOmh@dkO$1@N0GefS+0`5de@oEK}lJ??m16Fh}cOvC*F)9fbi* z^7=nx@9_cfGi?C7s}BO0ynD7f(XkL`W0X#uCpwm``oEo-AEF5os{u#H+x;4%Jqx)v zv8M~P@Tc(XObQIZ*7QSsQqO_{B@FfjlK`t9 zoFkKpKd|cMCL0#LFJD+hMc@#Hc?FNeg~VR!WN-$(DYScIUO_|9cz@#F6erHbqR&R_ zEci{b%+W|q)6R>ENo-6B|KcptUrDV=1)#ga4N;2d#c#74L;Vtaj{Ro>uYPKG5z#0} zvvlQ~aIi{I`S%|9yX z4mGi8!`{AcTRYwmS~G0>C^{?)QTsjYuxZ3BI!>d+h>BrFqC>`A(0!k1EELo@^pA}g8w{b(YDk8`3#6+R9#B$V|1(v>|5LD~{gEE^!6RQpU>OgQU7ZdlF4 z?r+aQmrIup{)Lq06D<41zR&Pe5US7c{5{WbGfr#g3j*nHa!s@h6`;d7_Nku z;h|r`D#P5nrLKyR2pV4@n!iS7e!6nuOQq4#IjNlxBdIiLwgSMXJ|#JPqDhf8u0Rm; z)6j=VBbum7el>p9f^jN{S3YctHQo0z zz|B&!+~)$2=WS|_#g?f zhe?n>TAF73ZDDXFYXnN$;`Q~#JkDUz?i9XCxZ9;eY z*MxoaoG+8QHfg%g@S%3&9Hyl)Z5}E>ooJTMKr8^)ljh1&zGwz?asu`ne#r&21;U6LQX&)YnJ}|u4e?p@}8iitoqD%3iu=ZHx;zNuF!OII0AXm%S#9do_MCNcLD z+p!{&BRB1)HcVnfT)Stg_K$49>#W`bZQTIGZceX%ZzIHN_LJI!Sx8d>Dc&DTrW%VM z;2h>Bx7t322z~~?a5Tq4m)qpGn8z&ra!~z9GH}87fD>VH(N5`ERB*d|gaFh7Drm#! zZm6Go`qya82>+?Cj%oiIjR_M;T4!PlyFC<5vP(GN^KSu?KpCwpEn#4q0Q{fc%90_6 z$voHt@7kbUBDYkt_(j?*4%lT;pT)1@dANH_+AOYR9-Q#|?xr@d?~H5TnX0{?t=B9j z=d0K5=IcE{`nx=L4kWDwt!Tj2Z0cqU)oM*!vqPIon6czwF_Kp|C(M|}hv})huMzxt z)-!F!;D1#oEcGrx_dekRnXo%o1!8;uzRDB!`g{)rTvSwWI?ZcA=G)HszD!%eo(M#U zV~ZTSr92!`>9>qv#4AXCmq9ekKA#Hjg;UoIh9VqBH z-}=$7Ga$W5_sa!K_b*`I$g*`iyuW;D^i z+sk~WU5??Oo*r?)xz9x#!IR-l9eXvrDY1KI60Q=vX63_6OkvZ8qj1&EIl3jhHw>F|nu z?-u+FkjJkrlZ~!{{HzYwoq}B-zhNEGd75O9opj$sr*GfzFb-t85(fg5{h35EFgb7o z%iDnM<~;mL7SOb|x?f_5DNRVy=WQ^?zcZEYv2du!FL^3WkX(QaqcKZ=-RTgTAwU=w zDeJqz!z<~q_X{1o)xf1|zKmHVHs(I4LLd4m-7nJO63v5LV-;V#%qH9pfw0BAM)^}I z|L}bPa^TEFqM(cDx2J*xV$|at4`UeY!*dX0(Rl7d53ytSNUVyE8Sm|p{XHBrDvK*1 zK}j22N8j`5BIs^xQ`WK%9&5kwW!RUv+qzgZnjqg{?KiNkdY4o)5bAx6{a7<3{y7z+ zpdLk#OywhY`nmumX#oo8$kRS*y)W4S0%2Pm%)ImnTWBd$djX2W5`dS;k1&mOco?(6 zpOI39v+O;E4r3X;x`E7K67!w_CK~15nP!R3CJYBiZk{PP`5$z|_7Y%erB(_*@D?qo z{QZ>YGi}DHze{ZMT6U2}5>=&PpvK)soA89;IPZI}n>V;}mTyC#P;Y$OhQ9}w_<_Sw z*J^KNHGi>0PO_VB!&HhoQbB*rh=B23`v9RS<0d^Fa8m%)2B@mN9>6$@Z2VB~vCx*0 zmnNN|QT=XRE~sgTqDe^#Yy}eQm)e`_v0O2}i64NWQ|+W69gG~lYr*X@L~#`^u$M_z z1$R2OE(Zipye95++c(1nwQ&|Z&6d3?WDEfrwwa~_#>bOMM;WAp4+G4wT)iF(P5hKg zOgM{b3V!NSFiG8}vxG<*&_(^Y0hFPgq3zn%H)D9!`@UQn$}`OAX~SIL!_+bTH<>EuzZ}Le`zVyV6V@<>nFMkdW6;9zaU>YUZJ}yy+Y+u>N7D5!N1^hJ;{LQztnyK8 z*tb!Xc@Vs{8pU17QS4xcNln%+hLJWE566ReV>g4i%+_(oKGFC>mh`ZHrsg!#i%zwB z*v`OWZF@1J74RJtH+N!UBBw=g+B<-mto`u1NJM?6n%b9I&s(JJ%n*`bb>$ng(D1b^ z3vEf*P8-{!q5tp(?vEh}nT}hP5Um&wcvvFr6ZTPT3Y|8^v);|gIkLna9mW8Inh;-K zk%$_!hM-bZ_shR{zHZo_D-WSmcn-XxY}dRZ{VLJE6h^LDuh18|uav=#0)AjVY5BO4 z*a$obmL6R}%Fp{}wa+c``bFGHm}$rnTxEX6>!-!d(mq5*Sti^~s?hQIOB=FsCShK? zAXfXPhTVW7k_|beS*-2L@5yRg&_!9QT*DcaCmRcQWz#l*q~t1<3UA0QOf6Y+m_gB? z?!sx#lgVpk&lhce1J|IVQ4@ALY#d($BEqo#gdhGdVL1?AD1uCa#K%~kQHYuv_6$+) z#m8U#Dl4$?Z8%SVOK?EZyuY!{aa~uN1@}@yB6w)dg@_=?;31Xhk*LMRQ+rrmK80e= zM@uABJp0rz9+8BD(FypaGSmnX^M(Na?GgB&{p-NjQr5m+5xB2w_Q82-+WMeIKRQ%e zSyZeny_j<{&O~$LYtk7$-DY3RmM7?k({v>@G>|IFq!8?8Zs_90smU&a6pDzsArdir z-YV52NNTcyB^|*IlbZdhnLRmQ%$Li82bCFWy8zci_rsA`03RIYH{hxP+4BzXECgkMz zbWMD0 z?e@7cHNQL+JG@3W1X__;ZGBm69;wB~u8}i>$fL;SkK}D^)?|-bxkmF(It$-7&{c+y z0wWnNWC?D0_|oy49TW-4R}Z$YR)a{bj0?)Bf06j64Z2H9gEF*Bk0sV4)gC&Cg3cvs z^g5wO>-I=Tv_CSVU!eT>*}T zJvypyU&$>6FjuZl*PZc6ATUZ}F%=ZF>hu6i1N9l*fI28^!E;1J9-! zXog^lU4=oQG9G0&;p?y!;|s#rY|a;Sm3G$ON^K7AU$cnM7O`IKGMYa*gEXshj9W}HS(0gMoPgcaVWRpwTox9S4h z@(f4PVR9UcWr^!ZO}kK2?8~EhGVZ1_rNza?m6FAwBn}+3pujlHRmP13Sy%AYBp;h7 z#qL5-MIzu%%Kkd#>q}J8K+}>)C(A$w0k86aqoef;lIXn&bkwnfd_C8Zx5-odyek(z zBY(HXxEn#F&7AGjq(&rO-bgas#G#yuR)BaAJs*ctt*M7M!|7@S55a-Fs$n|LEVi@h zT5pT(KlF4&shzLJ$n~pPk`w(AxO#5(vO$0yJ~)6ocnfa(=Zgtpx;)Zk+R?qLvv8(D zN;hsU|IRL;tyawEi5y4rjbXLZd1h05gjA}I41Nsfhx&0e1rG4xG;zp>Yb2m$$H$u7 zGW}vVdb1)+nJ~h^?7i+y`<{k+f;~V|Isv_1{_F=^KfOJJrQ?ll{%^l_+AtY3;GM^{ zurX$_7icxZBF4WA#t%g7ijT?Z2x`z#cgzoKEK3 z-LEiv836*G9}k7bqHemd;}HU;F9i~_`7HeURtJY~Smx#ltOd4^$6sZbI&nz2%h67F zZT*5rK|s{rdU}r{Nh2~h>2zd2 zg{Hg$`#6Na>~_w}ISJoZ`1e>k!dtQoFHqgW6TKek2l>^zm#4c)2G%y?YvtZdO_^+u zex|*671$}UyRpA!T&}HjwKi<5nH$qNHdE(O=WF{`usK4yYM?vsm6#77~fS--}X^X*_pKuqr6{J zQ+bpls*G~;+wSxk&FcrF!Z1gyrt%5)9E5zREp4NDE7c{Q-i=e2d#au(Na$|NlJv_w zM;piU(MbYc**^O}q!l!1=)US@o`0aqu7*x;*OgDMG0cSU__HLt9Q_t!5eLNb4)p!H z2su9O@d|3d>alziLtw|gAZwteH6Y8@3kT4}JFBBZ$Wfz|{4$+1*7GSz8Xrq8gKUOq zqdvi2WOW~EFJGC&*}xxsZ#e78sGpVqc&DO6Jq`7Nv85au@Q~L^-m`x$#d)J!^an-9 z5p|Iewe0JCK~yghMue!%8aRl0^PLD$58hK5QLEqaLv2wPINEh6kyT&Gy8cZ=iF}y? zCQQ%G62Y~0AA8rS`ta(aiQJD!BIf@#@?l0i5x}pGVZa=?Fsd4ejM_0FU)^QB(ct%f|8_l~GTB)+LZf9*-7MIXfklS#ma~nj zkwy9nPyqY_mCIv`+$Q%JiHBtxt|Pa6kmQ{PMFs0PuKDEeW%k-21kLzKu}TIau)_UL z;piZ7DKW1;VOOeaD=DTs55+{{QS=VZAT4aPriBgV$RM`X#nKAf+ti(M_X`})2Wlf1 zxW(y&B70cooWqSMg;>h{mgg=u0!+NR)cH;K0nD~Dbt9B4;gTL7`;F7%ZQ}tQ-4iK? zL(QSzzlkPDTD|YW>!3RG%q`0V$j9UGhCo;XUL5OsNEr#{6M$S7f2@STv;&^bjm;AUjK zOKFn1?Br~D8|gyrj+=G6^fBP{o5?feYf-1jKDk+L98E#-8NtZ=vTPg>@)OH7u9qGH zoJ;frCcujQVIFrtT19qxHu=}bIjMfT6y^erLtMg`$dBJ-2*x(YI5gdBxol>q=`ZR^cC zqKRMFS1c>$eHKv?*im%$dAZHrC=Y9!BTf4d+tL*DbDf)Z7s~#H$H`Q;e^KpS9SJC9 z^F16Y_(b!@od;aoZY!Vp1~&)J8TFXrJg-I z1(tD^J^ef^i-?zm39yMn#8moG)tSmd>4-lmvQ?@eu6DNbpZitxBQN^ggHh3!RrK5< zyZcr@EUs;LFw3!JmjzzE!|I1`0PIgLjN6vqoUD94*l~dsRhf=BZiLws5qM48u3M87 zi=9B#C{9TareO^N&9KC$v5Sq%0=xJUn*)6K)dg&qO^a;Zts0nokuh+{7rB_5wCd%J z2Ldh6<)RXRmWa=Y6wa^}%O&bQ5q*F8O+hj70q3{;pf&jI5qY1uOhharWLb)av2y;D zk}c}moaMlDX^e=Ofw@#cgwv(e%wYB4`#??%S!SEO>!EZl0QFsGP>00<0V$|+6!x=^ zDClG8pX>q`FRj6O;Y*LA>#^9BR%=Cc!aeRIk4%f15 z(Y$c$q{voJi5$f5f1WlfJBTj~UlTUvd0!ND?ZYX4o_d0)wo_6Y5pb~y zevUB|Z$;)on@NApuIkCmCP==lKt6MeDDf~Tkg#cSyB~PFc00dy2A~PDyo=&J=^b3O zBjbtLsORJ+ncYi%+}Ec0alaKnJH;MQBPl=bWs_M|s1W^bLgYlL&{P20;Ln3#>Qj)5 z95-0sv+R*sP*qWp&HlTX>389CT7)eJWaTp~xv3rjH_o!BCc}VGE$6)euvu7&tmso6 zEH@y;A>z1=SJ1smClM#un*NS;p<0+0o7*L(C2GE`)@$3e**baKXE$#C;)!dC(LRK>_>%r2GstA))vAFj(aVMrp7+sN2d)r;`cTLCO#vlm8YmG69#YuoFS z*sAMZG&NiG9V@Ch%UD{UIFZrBB57I|e|TqlmKb zbU=f=G@7qJj7FoiUG6q)l)7q0GhnD@gw6WGM2$;1V&F>qS$X9OEW#~2dqI($&a#cY z5GGFan405hnD`9KsHPqMLpgbK<>ps5lq)eov7EzY_xQy0X-fn1mCy)&q1nz^GpyMk_=ld3<9e!fqJB z5~j-jcKf>2t5~W%+ZGWvi2e)hNr#XwbZbg7RC8OS6;fz#;HCmPQm%xg@!>S?BX6$6 zHV~gn5>07{6h_T@_VOS$(sS(Q-r%T?98QSR=Xg;?;|R~w7mME_&*}b%%MP3$9lTTeoJ;N46lr!hJ1hTG*Cgf#wcE;AH&CT zKIr1mjA0R-bfdgcutlU@2ul(ax#sbaKtL`fm?X!7icP@3q?aHJJ1QMEO`Yi#tD7Mr zC_K{x9TG4u#EGk813!qULvLj1K}ivXxq+f(+H-EP4W?|o+btc!wiE!9wTJPe#3YGB zZjSs4)aT4kBZ*>m5*!Xmajg2l^pTWP(?<;Ahhb2IJ%H3TT0wV%WgJtO;M_mtS@WDr z+zrjf48|cga>;pOi=yGn8^UGj4+ckm^bc(LyOt=&*1W;|n{89E)%^*+v3!$z*w?X7 z2j}4U+T=6LOdqL{8AIfvI`1Q7bFj97U!25#AfeE;;R%~C9%B?-dTV4!o%^wb<0RhV z)kob&h9J>r*&Wx(ep6DUP5O8QT5iOUu>sX)_~H*b*KG z>6FY&6yk;Uzz#%XkUWh>5~s~b6t`5%3wAJk==ohWtp+Dk3`FAV*HhMZMsrzmG{=U~ zEZx&+TBJs!MG}vO?uM#6&aZb0h??;x-*<0Eb4qeFeRn&W9%a#JZjVRPt4uVc;f$2x z|AOFPenwJ|C@**kVVcJE2I}MJS96wUr-;UqQ^qXfg^<_}uDgOFx_$C+nUo_aM8AK` z7Nf=(l(5_%J|B>rZ4$4u>{4JavPry;XyYXWQxV71O6cU3tTyWDgjZP;+UV#bSNHohMQSV&8+O~+}~yu=4{zyS^AG1rTjY$itOGT*q4(fnWk(s%jk?m zC%Xr~gyvA(P=@|noCmbL+OQbD&Lv|hy&Rl(Q4|lcC0}0zxcW0Zn_EA8+1v1H8@?h< zZ8FM>ntheGYF0-OYIZ!$DeKlJbVDkvT+g~i1}de&@(O|@WaUw6!Hgt_Ra5m;Xsi?1h4*W(4HIkjV825Iy9Uh%-8&!}IL_OBo=ZPq7+<@u|;QI7sqCB+Fr@8`pNZg6CFlw#N$3Kqnd4N`D z<088$!ETtD_pjY4QK8a|2J{OH@6cwyx zy&P!^aWVKYtOj1OSlej0KZES>nCw{}-r)JNVRWn6Y8v!TH2oye;DW$Wh)(11RJ&M5 zX0!d`;z1u+oscWy-JK6-BGV#swM-n@D)$N-9{^BJMC9)ke=W-;;cYINW+j$!Ng4Tq z?w98fALsb1K$fyhsqav((y`<^C#h4bq0(E87!ak*iDX%LxB-YVI#3-OR`?C)*Jr zWxd#2bitXtYGZkU(}lX&^3LUqpN*gQUJ~gN=-cxnDjMq34N^I;69fuqzvq9ceYiSO z?e;XOo)1s9PJFwj7tc#}*`yzY-Chp?Q(qvCs&nN98^qmGCzw`wLHF>;bMn z=fttKj(8rRhOg@RRM2wY72zLkGHoc3awDB5T$po+gePBvmu!#L;6&37dt{NlYv?pu zfb7Nd-S*f;(L`(&!GvOII4$Hlgx$(D10s6ooW2v7CdNQ#tK-G(pQ5TUwTG&F@SQ7SC^@ zpjVV%JoH3R2LwZSJqBNZtjBdKV`O{~o=N;1{x)pF#0Az_TR5F>q9<&gNDk zx;psfHMua6+e4HrlB)8e3FkAHVxo}$f4-el%5lhSHqirGg^@|5zU1p@WCv&G-iscH zH-SP~6wi>V!l3GsK%6^E`||9-vl#(=U0cLeT5+eA`i1!oa2sJ9-=Dv=@>=?*9^9o1 zdp1f6b5o6kU0DOJYaMmCp@wPX3W3__U)Csuv{6&yl(uWZ9-<*Le-mSp}VO;P2 zjFVK%ua1#Z`$5oJymN_l)FK9{-W1sCBJFRv)}uQznPkeIHA-n9HSH?&kx~}iioFt& z*jxjiGo)K759!SJnHYwM`QDIXzGo1b%N{n`Z%+F}rnE<3Sr?o9U254lxQY@%zm1%E zhBnu)aT57?Ukr!1h8$`=eLZpL(~)8qaaIAR4!lo{R4c6u?j46?mgySiwYY)^?|MPz z-}sH;^>V5+TC8$xJT7g(XoIkkv0!CS(uNcFvRe-8+s+~IB)7c%-!$@bA-f(H4SZoD z8&u-B`x>WJlF5ni{}{5!negrxbm4p*`|TN08y=3hV_$z!tZm*2&HrEdJ=wHj#I0p_noK`p$^k-gkQu5$`=SHwaI$3vU`y1(GS}scE zlw3y#v5vH@LxOOS%UQcRhlpOd2-wut_@b&-FT-583%$&Rg#x=x<`oG?N7}8q<+~80 zUFO?FfGQmc?%;wYGE!5HCqPW34I`7~*XdXTQqU~0Vo zhEjVgKhkNwK+j6)G-*2n!>xyCAn=a2UNGjS)*5j~=j$8+BI!0H0DKwJDf$W5?(St3 zcftk#ZjAevAstKyvkmQLT8BgD+ZR}SfKa-}WwNPGg-ScY@js;lFE9W_h%Z+5*NXHu zX=xc%lP&G9mZE|gE$nZ!02@&6tb)xbC`niYWb-&*WKac$GhpZwZAKueii4Cfn!WBh zUp=eWxKjnAZI_NJM@-axeGZS&DF?Zd!PKQoRY3Ps+XiYIUy%4A*`Si@QMc6ozNH`{ zgn#4y-lH&rA=>5E`~J=-k^3ibCQ3Ns+&i=NYbK(wW|bg&jeg-1&J|>-*7i2sUwgOB zXQsr)IYsiBdjMX<%$2EyW>ydO_DrJY1$c)fYF+4U{k}qIcIedohUQmy z>fYjHeNO%_s@tONQAf2n`CGM6wI^@0#g!epb^TTir!~{1-Bq1BcWu|=nsyzpYuDww zXtv!A-M$0hu4;E>_p3uYF+!`NLx^b6?Jw80i{RdU$ z>K4Zxdkp{0ocFl3b{(#6*Xj5c=ju;Z)>R$bx9xPyHKLVH?XJ(t$;xWet@E`V+P1#F zbC;`lk3!X%W5>>ITX*Zy2EfBtzIEtyb^Gg8mBQ`* z*q(=kx81spO4E85UO}tOTHDT@+IP5`pY+1d^a8v||4Cc^Gu0U_bnVu$^`G0d4J}ea zsEY~+x@+2Wy{226D?7GpeO>2{9oqgSfYiQwr?%ZXbneuqV`~)%FWYqNaCN74SGB&f zd;9k7BKXw$b!|H67j5fTTs6Gu-mOE&4&DBe(NpxL6S!*!DYm}0&2`}w_yeZ_JE;ac zbZgfoLP*p_{KgU9+G!ya2a~Nkc5ZXkF>TulpKY&c(9GG;a?wg^K_`--u!K!VgsqPt9Y5Qt;X~-L7F=9R;A!q2DU0zoFIEkc$ut5#7Mr zfk3@$kSUP(5Jsc*7Ao*sKlJ+S&RyDNu`5KYqZ>pM5m@(59XfUB)`9l^+Adn8Y0HL& zSXUXu8r5xk-E~fm8AO+rdl0))R!!RGKlQm|&}-|*2p*eqYe`Uf8-e^FPP%kIsNii0 zB)9-@m;EF@*R#6|_XQm@Og&)QIFY#hN=DsCQ~@o7S-5!sSv{g|ON_q<5>J|D;ZRoIZ}*ecK!^!sMo&uK-G0(%U#PoNOHgd)MU z=R8b$Ze{O{9Lb=v?KXtXS^}wissAQw2JU-*Rn^*^oB7y7+?LWZpnyk!ic{$28V0%s8A!MK zEdHmo+d~8sY6iG{8$aYgOO2S?3qzWFC~g59q$O`YLCp|Fa~;v^>j(?oM}&dy!-r;i zU)x^6dF}ukCHsx|giBQg2g%Cl9))->_^+bbByv}oJ;+G{&^%8->aezZszU|V$U z(zbRMEzourR-Z*V5jsl_kOz4#X{^aoKjmK>8B0g_432$1wDiSv9y|H#l0f>Myw5nwo# zbOhd{>j*SasZm+g#nTv!p>+jwJE&j7A{Mjy8XHU6%`7FXk;e zfNOwf1;q{#^rCj%+Jq11wCmKh-PxVnwQt`w?QNbv2c+F! zbiejju}VncmKTRgXCc1-kxs7Ze3gV=LuBA%c7=QbU?N9r7HIk>;*-jV(pNhlcoJWo0( zEQ6P99*&ssJ$;DbjUytn{BK<4O{;ZLyK6glk$TJUGPQSBNSgKz(ImBZhTqwh#5Nt{ zb#PU?KXup0D2C#g67=~k?X&A&uH_>uH>E&yY2C3y*KVpW7MvWv#svZbR<3Q=saq!e znYt^j$GT+ASQm`-L|(M%a&7BQ?K(?qECw#N)pqSWNLBCb#6j&$-L_VyZp+U|w*|b86f>Q(45snCY^L7@eb%1SnX#47lHK|@1@4VaZiOJm+shIY&F+D6(f z&?U873dUNb9)osE0l^j=^n03l+3B*Uq7kZ(>yDN(?T~sF`zQZ5xD0m+qm0aeXx> zjz2e-JcK?8$YFsZ*8MVnbZdt>*|KuhQpCP`mYl=aN1JyHT6d{ z9qy@aDCvGDr+8-V-1b0hH8|Tqfrinyr**lzYX7Dn&N!sDexA{hm?AO|zG-M$7&f=x z=epM?M&w7!xUyoZP^0I~pU)Dsir&7jVZ`w6>v3NYymOiis>|#l)kwXJY+v!>1y?XtGqUwalg;Vf-~bZNcBK zaKA5B9_Jk~4}KKg-vV9cP!}>|42VxfbTNsn#J@zhuYOlxJg4V}038*aa<@+6I`s>g zn<+K@9^8YvD8fsUPyBO-J>SjqSe$WR$9P%gQk+eS_QB{k#}K(CYQYo$JLE~&A)m-N zT7nt!q^ue8-rfxPP}v8oA_Mpaj{j8SP%17p74${P~z z9eG1y3NnVo3*}7FJ=j&=wWG!OZ1Pn408%5((ejtw;MXzon~- z-8@RtYT^DOd`Iot8+oaZzin?%QhKvG+k@6Ii^dNc2rQ6DWd|M(tKttRhb-iu+&+7C z<58RP@!E^4bk@g9rSkEj6Z7#>AM)`^BX5$AS1b3`yLrDUm*kA5ULQ&L(26cUDAa5M z83&TY__fb$Zo1%dqffk2FL_?|7>mXxBdu=p2PG$V3Psay6`_~|f|3hPnOUA@gR=m| zZYPhMm!L-uxVQ>CB;n$9ER=BWS%eheTps)P0ifNC4*~6%Is!+-g)%eu(ro@@JLtcg zGqE{w@02gZh|1K?;673B1gA$qZtc*sq30rA7xsxDY)&I`*r$CL%ZO-tpg^{%*)q=~ z9?k$a-ZArryp!UQX=gm^-JLM*%@wM)13kC``9nsS*!Tno7%2-~rA9wRZhtX4lE# ziVwg&m?loA(ncaem>T^C+4cf5qfv)~UEOc}5vk{>@C2G=TqNv%*{P|W+_xCmjsOf_ zMUp>3Kydp}90i8@Dx$;^9y(G-3jo*Q6YhwTjyE#)_Q#mVFZ0F9nD@+yXoN)6S6qKb zz8qiS_v9GSTfJ0?QC@vTw$BKNeL9Hw_rz=5FqOP`ebMP=xg;B6jTG_Rxs$!i;_rF(;KJSDv!CW*E9Zz?3Gb zsWXYG!dF+o0ayma$BxkvToMX!A|e_)1)ri~2Q`jx4=@;2xQ-d>Fef6AJrgtuE5b*P zDf)P!`w^|NsTiN_(Gquy6EmlMb`OadsJ}f$9if2no=Iagio_ptn~%dU;p<=xTm{4? zMIU#+XI1oh_L<|ExK(j2Yjlfl)k=7_^VU3|401P+!7o5gBihy7S0GA2%58S`(X97t zgk>>Aynm=Lnw>4AQOHo?xDeNL$ES-Sxh^qI1oBWhs?Lfc; zFu&MsR|Wqv3qDh5f$thk9O`~a)j2FL(s2aVC79^%3G$t%a74Tx;YiJ$Iv!osb7+_L zqLG)ymb&-Yv??8=4n|-km3*3)cpBo4h@UE_R0>1I&{oDx(M9C0Z(x97VP0KC@e??!sM ztO>|kf#OFo@jERE)2k3hK;%~ zVF7BsN5KU3_ye|AxeR;xp6zr#D;&IHaDO=fL{jn8)F&y$Ps=`ej9?=wJs_3F`QLs>R^g{y9mf%!gt!ulyiW!} z3TWltjjK{i3Q48$4k~Z)5qAIy3ife#0t(1Gt)w~CII3}4!L2n-(VjZC-{olA*mB(q zm>1d-L;PQd*9MXx8+OS?yZ&l7is2LhOnlOyE98KQA?xd$#`yP)M&ggaElmrdpm1de zM#HB?uhxhp6snM9F zxdrqq&m#`W8GM~Gt8RvZ=2xw4?k>+>e9&Qnyg-S&Sa|z=W*J|Lglh6-j;~EBm%~06 z8@ba<`)#~h?_bL`CR}W+)!x4r+tseFH+Kug{m70nzINqyzpDOeM7SQ1laB=U!UF#%wL9dZOy63;u#kByqW(%H!R zx(*s_2LQd?*0nI*Kkfr~xgUGjVWA862gbg~7Pa&CE~l`8oT%FR@j)wxz#zCuEFL># zKX(l~gnjFG$aC=y(e63OeHUEZOQ$2n^g(J~9rah52A$)!=-{YW-p8{5ZT8R|?FdsP z9)M4&y-mKenJv1HZUtA8`$SZ3+u{?z$dT@BEI)J%zfO7TEx@D1_f)XgMef434h^ig zK}Q=^`f-2H#?6RV0R|TODF}vdWn*^xCCUK$9zA9DKp$-;0g-mAK^-;mD%=hqZS7V- zz4sDqGCg(qo{(>}a!x!5h3L+eY>n<+faJ?!CBMnTy6Awuh)L+)^@vgRJ=}RgMzxLy zc5r)_xJhpBy^EVZjC;Rfih_6b0t=i$3>JR@{(=qu`jy7LNMNUeTcM^KT0qxth5q*(s?r!e*J@2el{k^l&?r!dCj+QhBwM5op-(|w2XI+yPaQBjNi|YLb zw215J`CRsnf7Wq61cpZBQPCf#a7^eoNvc-zsLv5WosLg?y)Ibm%pdm~c|MHoW^)|t zL3S$3qaCCe8k%o*NBL(&-uC|e5P|m_NV7h8S)}_rI0nv0p~7att6r!>1`4tN$VY_x z#DF*0yo^Xlwpm`H2EY0MaZJ`hHrsD_eAq~%6wN{!wt07?A#x{C4v6N!3t02@)|e2v zf`w@DVOw-%UEBG!&eS+_>AWh>MUsxU%6nl1DG0_Y^UZrLdoK_XU-vw>#+bDfOFbaI z?&r!}aJwXEK-sw3t_(k}#uBOnI@{JgYov8+;imBwi2HD`Ge?iws|XLk*LGUW~ji*Y}lef)auYOmK!q z1cL?!p%cUp3n8s8 z;fh0YR0u;mEI47?%`jZ5u?4Y&_(Huu zuPB?}fqOVg*S%$SPWY%K3*bjjp;_I=Z&N-4I7lYAb}@|CW|<7(T|1Aw3?aS}rD1Yb zfF-)85?W9<8&MX{_FuF06c2df@&6CHj3sd|Gqw`~Di1PST0w!;(Eu=dsdnxp_ z3^gz0>KMK?yiaP_^i_ZHJ_Z9^&Ci8uw}WKv=NHw>S6_<(7E9c{7qI*TbSCHx%)9L9|?pB_qqeOJF$QIcO=Y_Bsvq2KVZ)g(<12~ZTdn}*nf1XpQW*RmPkf>+89Z#a+006(wjKKXu zQPD{*_bFq+hZg_r{pYyhuTO=!M+G$+Ck#<0M@Y(|ZAVML*DgoZs?=~&&bZ4V%0pm{ z-a=c!0EgvG8?McRBlQdvqkvz;GdDK;mV8Q)&0taJ#r0&utxv zcZBC$4Ozc$8wfPcX6^(o(y_y7h1hSbyM@JDDmQV47fo0~j)T+zh({FKj^a|M3>PX8 z*|!2*E3DwHxIh;b)sXVYYA6BnSo~2~R-JG~a7^%yW8GzOS64B0eet3+X!gl>X+x6! zt2yBH=4QZdFJum*7evv^eQ_Btv~BOA*NtiXM(j@Xd_U5Q?#}|=Z6OSwzYE#Xx+|_K zYNSH)Z&MV0whArLTz}vCGpo8z%7tm(MgeZ&83^wHtP}EcdE%JXPhrq2pT}M`V3D-i zWWpYL@B?Iukw*krTP!hrp}QA=4Q3gxAjo)XSHOHWdM~d?LuBbLbm?0lAL`;k#ImQgaA`6KT2MkFI1uf3SB6MQJaTL>*2^S&^ zi^GL1ii7UKvRcqR)k_8op+g@lB=kr%#R^#zLWPJI43R<>iC@ScC`3F`Hc-fhfLb<8 zh?smuzts2?B_tOjacE1~6~!?^Fg!}c2vL0m^09y$#k~n$SndEjv8EOR6N@DuA>^ps z03k;1LV%DS@QeYq7{-SXhBVqsaFBRK)fq={FMWvz&xQuk+!YxlpDC41$a^>Kl|<7G z7`IxWOIVD6nm2jPhS`7Z1xn_LTdl#oA91VKX)v2Jm{ofR1J5-@y6$0bvH;HDD=615 zgpdT2lYH@~Fg6j&KWYph9P6KpigqrX8hvtFv>({BhxYeL?CJHN(eZnG3cCgY;yUW&Q!6F5#wU|ogQ$Rr4$>|Y zla5BbkxO^tA_>DfYmV0IV_h{8H$h|B6^^bqmc9GcM2j9rzwdL=6K0hDuoI|~G06>7 znV94Q0#zUS%^U>Oa;!U?HPtv8d4H#Bs^LsDa?z?K`-Kg8-(U;)|2VPZx(EDUPxCi| z%D!PJc_TVWp=VEWcj*WYT z!}*{j`Llbqbn)S$|NZP-IP3e07X4oUB3|rG?rZk}&YNrm>9z4*{;09*xFk??PgVEvH2#OQJ2OVvM7tT{|H=LItiM z(0hsNB%7#N&LHmj7$!E75D~=HEkfJw(2);vzdW`}n|h;4=-{ug48Yw4BfQ<+-S)ea z-x$y!>gI8TyM@Pev2670eKd`m`GT%!!Zc%oujX317bNia^qIo!0)sSNZwZrD?0$4~ z6+b$%?BSYtBF{3BRQhcsy7*6+Y_AJvkG&Y$-(YdEhKWw)h(#Px;s!GYCEdzp0>!-| zz4M*Drq0f$v)7WHH6M@zwbB*H9I-=2jCUte1KopuaEuo_3SgmthR)}%4n(`S_n6LK zkuY>Y@&y9}Z+dArsAkM7&PC)Vs3Hiw2YbJ*nX&+ya;N!0ZSS53qU!?W=E-5+9|Vxs z#GQH6{PzHIu>JC|?c9*CU2|X`u$7Q?Ln3hI&cF6lH{G{K_d8M|)y)zGB+oS6uM8!k zUCL0>7x%X|?(o0w*ByQcy8FyfqBDkcL3YL@nckjUxi|8oJ)fUMACg9BARqedB>Ir_ zLIe2_jbWU3C`VH8VI#L>HtUqeNvnc*4ELK}(l~`>q5WhQCjsAQaSG7y`5taVNt^Qrh; zeD*aZqz_TK)mklz93#Tk!ZdQUL1)s+4HnV)5m$k2xRY$EZTTJ(^AXVY zVIYctCgfKHw0%$&5CP3Jb5EBMQfgYz+p%!+w82mU_1kbYO~*El>#*2Ek%s{WT|-0` zcSgHR;mtcuD@NZvxHxqi+)7 zFP|0=IUIxkA0yDX=>Zf95zppGJJMcVC2gTy%kb6!u6>4xM`aB?@hPvg@3Dt^YLM4# z|I?gZ%bdc+BmM{}u(SySaWI9giT`osM2bOQ3iiIe-k%9A$CYX^8 ziupoS-D4uFnVPCY5l$A&A(4rQr#LB5_NRTesXDMJ<49lCs_$I4vgn?s49g7>A% zv_P$#S1~iUC>zloG0rx~9FW+YbS(2{3|POE2+k?@gW{0BSCpW9MxKRC#`;ezqb+LQ z{AJ0-ltm!x@CU33vWu6c?4I)5g1p5ME5kgp{n~=uz+oPo?`*)gvy_>o#eU;|sV``* zOhIJ*g0rk|14Q;gj%5`88*dqMIy7Dz&{G z)3G`Ce-jdr`u6-rCDI|YfkL601xtE(=hSx%wkmTA!!V;a% z65-LD#-O${Hl0I!w*%+{OM@qN)^={GH|6`5H)yPIXAS}rpKX+TllvYPcd6xQa2s{! zg1AYdh!^}NV2T_a_a?*jpegi}cK?7|G#^GacYs?)ZxfiE`8Se&o6kqO_h1TnTY}pI zB2zcN(+!mfwa8t-$K@;Ou?n_pIjube50>$Wl&OZ?^Z9gF_bd%7f&&DCIJ>Yhl(L^i z7XO4qIc1*lWNxDraIXWGI0<*S(B&b*emREl|xvH7z- z#|TS_vkv-rXqmhe%G^5whn#vd{Bcjd(keuI#ir2SU|J03?O^1?~}Qal8C6eAH0{*tF(A9-e)=1D2EaM(dJCy;7V8%ocoBQ1FJJx%nicR&9cDrPF+A4w;u1~|VHq#?l_4*5 z%%4f$jKB<7yk?YUHlER_+QMo_+{WbjK@ekGPzxV0-d?` z`+)~pW5G@afCB7$PM9ri=|AQU_bm73Iv4Z%F>vjfW@zI6f&cb^vEE*|XPKKRr%%09VQlpjg3;>+b!jaqnr6HhHhiduLScn&hs9R-X?h(;L6 zyCCLQWg94p0lymUHZ9A4F86IAnv}N|k+{S}65GHWaQG4U&wo#i$A3CYVc8D85)keG zAMvzevtFA?V(>r7BnI2=sU!xQ5jwhO5`&!NVLRoE%%3NHST@dm-?8vFRP=g9^v)y< zSjRB%&)!HYxSXI{nu#feKCf_o=oK(qNnJp9%W zFP})rK43n9x+lh|r?THRw71nN7BeMn^8w!6iLH#fcJ9PPH_iS{qT~olCK9Z?roBEJ z{kuADi|ytcQI4)SyP8F(Z=BQK(o)+vC&ZXf1X@<0Ye1e!h(LhsY#WS^&pkfuG@pe{ z+uSp$7kJq%IRYi!GcFJ&x?73``bef&=-CRND5&+qI1L*$^c=DrgeMZlX*%|GU2dYa z@cq1ymCe^u3qExkpX3WS4*YcbQoB{04$PmOT*67ld9D5bk*(<_kj4 zXf<;-r^euaWrEP#?$NtMS~bc-5PFTC4|)Wl_v5l4^n&aBmZnCFQ=f@JuTk|HgPu=% zi7>A@(jO?}huSk|nzoi5Bg|KU<>TMP@+Y-Jb;zoqjcj8Fi9_B5`{jWIjq$nIuuJnF zkRFg%;7ka<4#*N=2iIu_&ryiK%6&M|noR|;~TXv+%kab^fZ}uiW zHm#u-gXJ#6NAXO&N;k(v_w{0m_f`OMdx<3Ae1iXc#Jz~Zr%ZkPRq;Ft=ZlTN@m=l_ z6z);+2{Puqg5e?3EvS+!@a6XK1XAlm>GMF;MrDK%B&4ApClhA}=?cO8qG27;HdWDB zjbUi9`yZT<5WkEg$6G0G#8(nz!Tk}jQ@Lc~OC!n<*^p@qp~+zk?-rz78@t(6dQWER zE($kuKjuP1C`}a+>GA}t_!DIKam}=QyP)gD)C6uQ!@HDiOno!2>$r1FP(ObGBBQ)L zk4aqBD&b*~rdqRUf&&UvqugIDuO4onKxFu|Vq(&FrnZT5xJ@9)Q1={eWr+Fq)o6#i zpOg}rZyJ%nP#mT{i}Ay6n3KkQ9(t;sdY@q#-&SI4a#4T!+S~W_({=1?;LtQ%r~o^g z4c5}@yJRfsFs)v{m-PJ@gh!Esg|Najc@=Mi2%oHbU>VXqR$CS~RaW`}SU&+57KJTW z`osMt%Ip+8h+~(Mfy&R0VPCz->%$b2aF=yL;4(JA?Zi! zU`JOx1!;D$8;oI-vpQLlTV(?&6G8kVQd&W9DFez&1d|=+BYnyDen5sOYo&nzXdD3@ zMUA@{1zHM2pY`dn{Hl06E$^{E%1PG;nc(X}iZhFeh# zs`GahYcR&WG))GG|G;}TCWk(QDdvPL0pDmh&(lZT^Qke$V)W@qtn|m!xqTc{2G@bX zxmVJaL(K-ZQ*!of?<=y7SkUJV?Y1;!(fAplDKrt%0S1VfBh)tpeu%r+A>}8027HzK zBc5Dih<0@~{M?RqL`7pOqlrt+$`bAQW2lBkyDJysvo$r^dLq0owFdj=% z*nX~7at->28@Xg%2DrvZ>nJhixr!gMW_4$x{L?7@d<>N32e_bdw)EJ{IjA%6!32`- z4>dm$u;W$28vBDkd$a_m`gKKKdw&O$$mko>kKPv}2cgz^{@E_${Jg+_i7X+OaQg{d zgfahNTd|!8hM`2hMaux*cy3z+BG7Vq7U2C_sO&&vR=^L@ZX~CZ@kdv!g$mp%A8$en zER8-kh4|$#qPS~T!tjy0Lw7%d9;jwCxpW1)rX!jRTV}6{HkQ4}crKQ++r!23$Apz& zS7AnmHIU~A$7AEBFh05g-Wq#GZpKGT;*TEYBgi_bHHZ$8lbL!O+PF!K@Q=RMp*$z4 zFY5eM90$%;9U+kYFM{`DNQSv{tj)n@3~Pt`g)K>&AD8hU4>9!UA2ksM9@BDq!N-`uA-_ zr-r%v0c(+atE}ry?6Q7-bf;Y?l!@nmvCoHB`e9?2tS%lMDnda<0~Y3+gEj7QcMcY} zG8}U!4$;YuQA@q9LgpI4nE_%Ho7o}PYWLhGe7~xWf4&W3ZnQi#KKhiqkChecdvZ+P zjba9IgE#s&%snbh?w=So80ISXi1+D5YVaN>guK`;6Q zLTX!yW=@dh-*^t}r9h;-^aT!yD)%?MIQX1N04MI6#}YBk5;7_5X=fIX?^ygFhsTnB zU3_$y)+U9xv3w-$b}-RV8P4cJYtpjFz2zhBEU2^YpojU#9dy&qsiep6nW$?lfEE)( zjg8%1@Ih(TYhzs)zAAs6O}P_eO&MVovr?LHt(`o{)PCe1H>psCo_nX&Yzb^1hAvfN z2Ex{{V0O!>Vd)6xj;_B0v%VWC$;;d=?NrWmmH z09aM)2&{7hu%7)72G%GPKLG2Xu3Spxsg%4vMdg(fWU%`w;1E%Ni#w@KGntla<2~~q z44#qh3?zP=az%0nt`&1>Lr~ZSX6cz>DU=OLAb1MM=BE-^T6M`od^h0U#|7Wca zKq{A`9m>7_+otRX|F||;(|@}N%JzQ)KqZHeN4K_aA)2q&cIjCGNu zz$=pAm=G3-=uMQXw0I`8OUQD)s6_YY8E1t1^Ct?UA%uUE&T0hLQT|GDLYQfU&bm1N z&ZK>1?n?Y*^!!IOo|67uS%P(e)SncRHLjqls9XX>iOw#L+y2iHotcR9%zqC_%7znh zp7kF#p}o)k51Y`qZ~O;MNMxtrn_)tC78DZ8r9`n=C0;t`=uY=a)Fp8nV!Mrq!k~-D z2;^W0-6WS?77Y#-D+(U3JIcv&WWNRR-e9Q_PJ?cVJl)2JL!gD@)T%gjIw93MZETDn z@2$lhUNTzESgwu7vW*$(q}_7-u5~*S@5*K9OI4|AB!RC7$=(XZ)z9I-CqQ4%AIvCT zY$huZ$(6C~SU9BEFbRfl!QXI< zI|Di^!M+mHX@_H&7gfx(I6VqHO-2_wPw4rp0l^Oig3o1aMN9)9s#WWRIG5|3NhyCu z3TzGCD|x=ciJmoDZ-n$+M)U~AU_ zjkOrRcuj0vJTE_kd#tLT(N}oeH&mAap!q0qK}r7f!uBJE`zk>F(v z2MRG9uMorS*Y=Dld60Hxl{_c~Z<{EcSebjFrYb6_yj5epqoFg#43bl?lOd$Be_;8F zVczKPyoOw>KWv5Fl40J&?D`fBw$J&mjag2<&owqnQd%1nK=|=6fbcM?HI!mkNl*Cu z`YL_|Cq7Gw@ST7`-xyjL4Nbe}+hl8e5}wg0$Ic(>A%CXg{62bAmHPn(7x}f4T7sa^ zt8i}^4#m%=q6G5gZjBN;KHX^e*Fz0wHBJ~TOJ6L0p(P@H3We66mX}~vGs?Y49)VJ~ z49lDCfB-ndepx6IlYh+Ai4lj&-88957KxUBpuAlL*nK8}W zHIxILy>(k7CPX$exDUcdDfiVVg3u5|j^~tn9;=gL!h%y+dT8X z=^+|B754Ph%=(-5%LCGUTGz+naRazaW{12!1DPa$(Dj*4PgrhHuUGFF8oYB0np@_y z$x#y*uJ*<{ys`L=qg3mh`L*%SwwCreZPivH|JIrYs>lzlxqV`5ZScKnscmg)Z!zyk zT8jNG+2Dy6Jk71chf<%=Mdml<^X4?#DAcnY(83^m&%ry5F1@oDFYybjYsw6qV(*K} z=fT_58nSV>h2hG%)Z9sH)IWnv_(QUD@UlvHc;cN^*VGz2fCi7R;4aBij*Hj)0(&p# zwRwvKGakG7bW)OZ7-bmUT|DI@mhd6PH?5n;CnZUb&z^nILQQ>Lt`{d|nq|U^lkaj} zEh$iyjH76HPB_4IE6MeD<7IPGYrNh(&BJT0wx&U#_AZ?K=;6XiJ&JvwPU*Nqe0O1g0h zyS*DH4QAXpDUIDYL9dM0rpHU~wdp-B<*yw4Q0d%UD)B@0W22lQ2Ru*sHLIfeY1gWv z|K%&j{+@gj{5`3V-4nrMld|gSd8|dX+V^9!eH0o#GA{QnuT0HKG3w$ z)2-7QHVVT?JzdH;-%`R>iTkN*YN%afPTVl3N5hsz zL(POut}KNL{RO*8`&3#%0O;d8-EX;7Z>O8ft*}|6V8myMK_%q#6r>0%#hYG@0q`&a zB6o4EnL;45-4w&nyPc?MTPqduA8$cJ&)ctdNcKTn8w}wXs1L_r( zMY^WMu#^EENzk6R`+cwz8x52C4nni-sCpyfjIv_x-fFJOH>Xf=eKp5y$sx*R^~(U} zDvZJz>=5@eWwN>9s4g#FfD=vv$V-!$8}}s!=4UUjMS**rrys_;(5Hs&lEO{#O7eWfr3Sq^$-;Q(_*_8vMU`LKMy?%#l`2=^>qD}xcR_Ksl&^sXr zdeu@^&^sXrdPj59lLz)JuA;aygIvK2eG8tUMos}DDW zIDxon_oSV)Y_!XC*8ao>?>)g2f{E&kU;;GF6-;#7(So!vTeF^_Gu``Yhm z!UC9F=q4iwUhbTWygEwmXDd}lsnTPSw)R#r-Wp8y8Y5gx_MHedj!2qxT7pqp2k|(E zU<)>c64;FI3=&0I)1m{t#0e;v^~gy-HA34?Sz>%g^+x26?=!LYYo#lCgkTNS}i|gLt%Z0gN$K- zryCzHq=rONQSr&Sb!=o0LS}3kKCMqn_oBx);OLNs(?+=f@|S>n3ME~@2KNYbYP{+*;pfC(&lzV zJChT0I;0pSMlFC{1&Vy$-NB>@2&yQ{@OuadUxQPb$EuzX z8OFcOxxWdsI0YXr;C6}_J&xl)&}Xe6bTRN`Kx-J;NcvktUW{3UnqNxGb0HOTRDG1I zfY9LnMCA{inPWVKu1XwQ5saRcsnd;X{4hAH1cUUvX_?2T-5GXVosR!o?3WJj?2ja?cod0x~>A zK!k}xhx@@h!TF+gbynh@Nej?7wpQ_`gTI}sq37&2)|u>8;Y@=qT*!pw-D&&quST=* zR-8pR2PoE;sH#%}hKp=@MF;y}JF7p!X2e|r|{i=Lmcmlv=-thLj>Cf;$p`GRn) zh^FblF%>wb`B3FT=|=NIORCqYGNFUQAViJ(L2fn&Mw?3ZHZ-4 zkvSofT_up}U1L{=q}^k~*d;5D>~IgElhV=Su59QMaXZ0U31^w$bZ))f*1QG22K_j5 zJ&O>mPl#2f1~h-aQ13QD zJ?*yQQ1Saet5DZByVxDR#MH@edeVFrKz8_~twHzo?htLj z-mWWxfcX7#cN&VU3ilRna6K0yvqrnk@EjH;Y=eq^jN6rd#PtHvbCU^K*s(91E2*f}{CswyuVn-L|osB@dmJjRx|~ z!4U3Spu0=odRtU@TU2l>N!~Y!MolHL0-PQ(x>%Zu;!61wq9P{1j@L(yMkHkNAc=%l zOe&N+_P1t2_+!%v!8fY}Gg8L@u#cohnu4{{yUZJO3-Am=vC@VDw@U@3PgV@-`FW*OTjbHB<3v28bR%Oz8n zB{v5Fm^^>EH>IJ88_M%n!_IpCO0zEaWi6Z3`I@vcn{ioADrIM*{d<|qv_8)9{Po}K zMeO-Y3*PB z&t~4hM+Z3hkS%k`_K06(=_AUNW9dU(v-Hsb`mprjJoT5mc<&1TbbbjX@h0>l0xW&( z8ZrSX4hQromg*l^7eJTu8~ZRz-3W5GXgv2E(o+?HYR=};waeH?W9h@#CtiMU>=V`% z9;Jt|&nPf0*Vspkw_=kjcFfU1VtGDB3&|1XA0<=f?%20Ajh3r?WmvA>tZ6j0eAYC* zZxU}!le=lO1PN=Je5h?TWKE-%Wlhs_`}N*(K5H6A-p!h(+nB+ScxC9UFKe1nth20X zgtUEG(`b@?TGI%cS!>HI1J|hVb@AxJByL&6>t9U&5MZ z?HI)@64o^N5x+NUnjHbtS+@r;JzH3a_zg=n@xk6W_iV0E?D99baBY7A=2|?03V-7? z-*!qgdMZ~lBof8TITd(=b=*H8a3i=->+aa0R8rrB(@P-}>4f&)!)Kc zp;NJ3lmUn+!4zciaGCnzplI;2Xp>65A(kliX=$}V%+E>_F_s)04LdL@IY?iR zr9)`KVJHJO*&(G(|?~59A1Y;8zMv*ar zp=N9Xqo4LWH07U|KabAaL$yq3VnwE=_T>hn+gOC9D<-gd%r$|nKn{EZ3=3KAI+34tMNy|a`#6ORehuzq=VB+* zY@AioZo&F>a-(&!Ab%%A)Ct~X_@BT~eS+bZ-HuTI$EYYOqOILKB;2J)F`6oHO!=hd zQ{-MHiK-sIf%sK9*Iq5@XiwtP13iW68No+!-;{5t8;F>WAXNC8#&{1PFb|@`p@G8hQ%-eMDR zSeO%SnN5TD6e22g;lD#(Rpbt?N|kcU+t)Ac?U9=JjC)q|{f7bymU+zrj}od>2wo@1 zna}{XvR8mTrw0D+0d`^xuvZLVMeZ6*`pewI@U=p{j?^I3=Xdes!7Zkk2@Ya{#G}j> zzG8*r&G@MzIuMg7Kju}qZ)@7CHSLvtV7KHS7*2=JYhdsCft?%=>}4(&0@Cy_px%~p z7}$R~a#Ov39AVKgq^lLWV%P)F8I49iYt^ns@Q9e> zA+UT*Wi<96eTsIK2y9Xo(@7Wp5|SPO-9m-QN;rCx^0kRCa4r1=1I+ zLR1|;K&-tXsW`UeH6RLy=I8D4No#v)4_x6 z=r!_ORB*nXgN+ge?iJf$_8b*r1B1DZN5PkTQyA~i)Qh1h1y0ac{uwu7n%?9DD_R{I z`YuHyOZT+07wof%?%R}Yj*Veq@w903J?(lsQbq`4mPI3P(Z3r{i^`W7`7c-W z!b^?@5Kp5K8mVi%fW)O<-4A!Sa5di8J<0953@NqfWre$ffmR^G%_k*pakXiDGd~ELKZwD+3zx5)3c1%99;zCHMKuaB?;p-(deK}rC2sR z9t$KOLm6ahWjB$CQEB@m``zPp<&*Vt!;bYk5gjPXVF! z#UC={B~g*(B~is}UJ~sv%S%#$is_b=|KusMpvd1-FG)H=p9ZI-)H;mFYbj})I_!@s z4WsvQWxX@=k0$xvdvE$6*LDCd!Q?3#lrGv4;m^NNCC7M@V{Rba*u%8!S^+tkYkBYD z2&@1-?*k!*9(D#$r91gckxMCF$ zw;mG?cytyrq&PJynp$WWanrFnu%9$KG{{}V#*rLq8R=X2fo}Uu20UC;EgH03!;=Z+ zX6|li7cWoYNE>9*xuK5Ox{`wFTXr*H+;}$>K^_=>JH7W4kOG{%^#!wxw?5EKcsS5T>277t!tNdgnX$I|k6byDG6mECz)~CUh3GOYCIbyhKDQ;$pStYUO zGwoy%2}I4>bLgC6DKs(Wj!Fh4#*Q!(BV^&vuYn`@11O&b9f!ILq7Hu93_&-jm!D#G zHhHILJd~f}-o4E*28ZXrV7S~nEZ&Zez!VDQk8pEp2;MKrrkE_E$1*NL{tE-dM{E0K z(-ATLEwM7;lOQXb58&uaLBSsa z8^?+Y{2i`nDAx+;#0i!btJ0_h2>T9i201KH!BxLqAD3tB<;O@%@1CH6q07lxQ{^sU z13$&%FeuB|<+S-%Ym=1XNXhw<9k^Pr$+?wj{AFwWJXQHFRUnNoaRO?8p29V*f@NSDLFR6|-)_b1{&{w@dci1-F%9A*62@mePlIkmj3w3S5X?73wsabZTp=GYGKSW} zD#`LnYpq+L-ro$|!1W850teo&iom}QWC`Q@X}`D^+&w%mwL#eymS_!hHEVSN0IpZg ziIW#{Fuo5R0`TGP8%A?0+}p^1Od}ohMEUrnM43$WBsm#|<9O5=ja!+TOlvE|Z5gpa zhxHD}%W!ucXgHasABV+{U?V!1qj9kuxc1^v?o_E0MLpcpDXHalLW|GkAjx?pIhcI> zR`R{)a2VPM_w7^{?QIGdK4Mw4>CZ4gE$o6LAR%)BP9ApLO>bXXl zdK|3AtfvayAfs3tj5il%E6U4SF&l`n^ImL5!~%b-ur)<(g`Qo_1M<$EAZPwp3*hU; ztmbLgma@Z^(pKqr;!+cq9yvU7g%@zn=*Ui-er2)Ox}{IE{_ z#N+qpEN6(g!Rlyr7xd#`_1FCXLSfDa!nKAq<$7M3T}bcC22`>!Nn_0KCqymA-uo!q zsc`3rGPpPUq6;w>Gl(QO->3RPY|guts0(jnivEHMj8eO?yvm(9FVmsd0~7b?;Edx& z2O-aiUeq#3Y{&gDx26Ho=q@!5IEAdwNJ6k-55~tiM;b&>r=91|jPHsIGOkaa8yn^` zUh4j->~739&IGnz;v;_{G*~Hp=KIj7ZfYB3sO&okl&Ez8n)p0pYa>Dup^4iNz2sq0 z{33VnGv6wD>r}s9j4TPz4a4~63?%M@X@C!R5TU9_U{p726R1@ODvmA0kbVAJOgd^QuhPZK?0~+)bX$YmpWw|U5V?r?_q@4= zo2tn#w^GHd_)?+|U2(W>FDG}CT7L^}nhUCATwH3AS49&jMmk*lPPEySXyeLg$Q0}3 zS9GRMaWu>H32bqf1aLSk^>`^Fn-Hw(vtig)=M0F43PkoMPt9DK5oUu;-2Sl*Je%7U z`2QMkL7MwbhKH>jmUqLKL|Xv5tq89t>A}gexidH9A8B41p-%OlBlg=#qehARBUkid zVWCa`5vGrX;q4-5sb3N#qc~X8_v)e|LRF7TD{1(5&__HE%^O^Nuw)<_J}jE?p@YnY zNb`9JZUT-Sc}4{`>+(6jU7}pZ_#Q#g=ta^0(mfo}P5Iy*(MPf%@~90WQ}6C>ky;Tb z$kF{H?tbJ6J$&3N+;e2t$7GcZ^REbK zWlwP_5Gr;LB6QIOHoqB#5$MY!T~2#kc1eY)o8xbBN>BsqqkGV4bbd&w8IB`Xw9IVe z3&3eMmT9C$lzvjuboU0g){*YsV#$jle=#8Dh=hx;p-P|3Wq#@VbiX%%3|O-=-2F1u zCCma%rbkF`^>YhMK~YqLY%I#PCU&y9*xCFr_y4Q{hG`ZexHHM6tCoX9I39Yg%ItNZ zb@9n>M71*}sz6%Sz8w0Of;x5t^um7(q&+S_E zO1OPCY?*t*bz=0qwY!_^30G=IbQ10E|7A-??nJtt$Tq=c-SL5&O z-j$Su6@gq5?~rRb->Hd=YNXS4meQ-skVHNnYJ@z6G-Ad|l$W{F26HibpH+s0a1KPM zpD{E&qWX~ z#tjCvz>OMoyDPv2amu()h-0jftJ32Iu*(^*KA5lMYWNGQ4O$LYneRMbYs>Q!9WQ0@ z0nwl-Mg;DKX`m6gg$*kGxNU(~xgo<}xo=3VcMnJAfOMw$WnP*Jc}OF4&Pg6AhXL_> z-MW6ybk_L4F)T44;u8`K2z5qa0~Lhi%ixiuN_kHV9QS)sf$kA<65D;f8Izp-+)qU4 z#*zpezcUtVN6%w(0glBD5cJnkYip69`{KPgnWU2XIw~o+-Zyp6X1ce)+Ek#_x<@)D z_`O|=r(5|o2(mYbzJfj;;o4DwtIEAP6yY>3XJAQ_7j20@+0oIr0b!N9(-y1TU1PWH zb6L@HrrF_M9$e+lS|F+=2lajsv;T1~a&DnX1bs!=I{7FjY@Y4_s`rWP0E^*aCKc?A z{JNRUwzJEV;;4mvoZPB$SPOHczf|cX+*}Zg0`fR zRAi=cI`Cox6$!vqDX1Vt1(R2m0Z|IvNuPE_2YLB$cH9t_6CfA3f-{kk<_tb`>PaV_ z8jVCj%yt@z$@NG&BELKH{Sy(R&%`fypClb9S)kc z+#aa)cVwY`)rui1PHDX^2tI>V$SEbfll5JUhyA!Z3I%oYVigph1OumHY5>VOluwze znEpV?U|vbC+8d}OSEn4;raqw}Ch`;llYQW@=XU1Im=a=D^(%eIY8x+^@2)lA7s!F^OS{# z_3~qrp_I9ES+(v;cz|>7R7ngG~(H|X^X|D2dILe3obt5imrq`EpUG$)Hvfv zyYG~kdN3E|lB*%KVJm<%IBjLt#5Q(vfio+kk$9iPa<>$lY8|JS5@a36gv^Os^ijF1 zaU;Qu9qE?4=J?Fbsw*SXHFUV%{6Pn~M;CfJ@d)?5SmtZSE5cJ^RMXsW_rgNNF3TBJ z8SV$hF!veO8W9J4c&0VAM0X(RK#O~hxtB)#TAb|Xg38dWohAxAEDl$~VmG`qI+Q6+ zlg0KF`2CKEV_|r4C5u(=et{@iJRb@&Uf6I&F0T0+0{+aF^(bT))R=4}*3A&5cU_#2 z)6Q0@wz~DyZSX%RL3JbqOCk#>wz`N!a=mO_PLhOF5#`Y@xc7jaXQ5>CX@H95e?0^b zZH09EEy*(hOxm3)RiD&(z5DQ};=qhePBe`c`n{`?Dy?GV@mC(-;j{cYMzbm&%}F?c zgIa0#+r>abpqCduEX)9QNj1?VJ(FBDF(v)Tl3sbtEMfeont{)?aP%3^qJAQi~Z%fjy zl0nGc>MS&>6`S_8 zme6Hb^s%&iND<-3&E!K`fYnjZqSJv?2@3gPB5QxaL$r#1Fn(5?-b!5EA4iL;i}dA- z{qvJN4+8^MW9!zb7G#sIq6&8!vQstr9)d$g`lk7hf;?A%#FmRxqnbTD%zbUx$cWt% zg%ub#levv{OLav4%WOzI0lummo*9}74)lHULIs;}%k7F$PTaHHL(xu79g4Xqof_tz zDded5hFRrsRaqLozk=@*_#5|uAE778n%G$*!o+?LvhEEk|4$N?FOJ`yW2kI~Qh0=F zo0qsB085oH;)j60idH}Yu(snlB(+o*PsfcspPkj?Icri{;e z_h~b3?Y5M}c02#&Q}*TV?h@0r6uI2zlzR&D8MjoyXR9nYL7BS|WQ@J`wkEztXmS|$ zD{^?q{#nXnyF4;US(Myh2rOfB@}QNV}!x-j(6pbY_>Z3Ud7leV}H^2Q8{qC z2(!cx5BUB$(`E_!-lM`=D%e|T8a_@~a4Or>BY{ZdZ9pD&z+DwckZso%x689fc-KtW_)|-|6UTY(v7#eI?&Dhi5_hu;=eBxS64(A2?QERB zBPw2*n!*`!12%!>oIWGPLt)GaRozUC{W3$UU;AT2-q2VY{uYLaNO_i+TeNRY+-47U ztpJK|+%RWmE+bbSzu^STeKRh8lQ@O4M?^=KE0UqY186U^1DPFv`X?j8fuq#4o8vb< zK)xjTCI{qa#cz6m{Nngczd(L%Tzdn8eB5RMusuM&bNogiFDDZ9WL9+)^e1sx&4}v= z_^NY2&pOR<9hM>56L)WxiG)?U2J2!xC~D8Vo;NSUnfBa)L+C~QuM4H*hs>yr(I zEp?tkVQbI|g{@UoC~Qf06ZwfppfPp|CZ{ zK0{#(n(x92_(bTscq$aOwpGti*zwqUM{1)63=ZG%%Q%htOf0XSv!SrnvqE93XNAJ{ zkjcP&Adp#?P}n(`*F6+AR)9Vf_AuGk^_^H=v&x3T_Or+k-rfi|09(gU*nasEp|IDE zQ7lg)6n1{ZcfBN*H%2i&<^4@NAuW5}2?a z(^1v`LlUqN2?5x+aXFL9E5=w6#2637Vhpj^v*QnYu-MJXH#sc!lK4#z7W=IDO}|*| zi{siGki{+^-y4fPE`DVfuTLxyhWJy3dXw|eEN<_K7C32_G;crD7OAoNKQ!>22ImusF7=J*rF zKB7&bu zxapt8%b;rv_QSiocAfqc91f2PPfH7+xw4wMXnP-~G|u7}4W6oON@5+p=;LSb#eCiC zl$c7JwVQR$SZNbaCyUn5nu&(0Yxt#D?9p!ML? z7I=EA0L~s;U`_H(&K4-xI()+x01RkgUP9`lh-rID4OHSLdj<#{Uy{RTcqQ)Yq(Err zxS@XSn7!lL8*s;58@Jg*mT^b?Mk*I*UD};cEPpw)e9vv`8NKUgX708LMi1eDQA^xy zO$g2MKfw>t&&vv{^jm+kM7n&N08IoUzN3!f0dYol36^Z^yV%AQ|I~W=`f))MYh*R< z!EZ=5MsiauiQoQ`O|d6i24!Pn%fxSgVOz${@Lb{cs1|w%A#Cm04--Jidvwbw48XUIuQ@jz2w{v5&=S3GnXbc9Ti>mk1%^y3GEgOaa62GA0|a zlChdka{t1SCbH~?{c3)}v1wfI;cOIOhxNeDSem_ltC**EtHLE0^zwPL?K zZ1`2~o-=Ea{oMEDM$4Bi!aoZQQx<)~Rm%H3<$kXCb;{H0*VY7++Xc`jh#qPGdZl?u z8VFXuU|797&g0UtY>UmHSt{L!QO2(BCK+0|yNCc;#*CC}W~|~iN|$^+!yUwwe}VPR zbS{KMkmGp^M+~`W^g&kiima}#hN79j|F01a4MC>7ChFwvZti@1gOxZGdV=_+6rXdV z$cwK4csSwiplsrNnF$_G>tozoj`dgk_$y5Lly;A02xS@IxeZHnQU^=XB-vhfGI{Ox z0aQK6U3Ib?EG{3byr|BqceJjIUh9m1J4I|M-Vi)0t<7;0}Il5JQUx0%3NM|Bo$r7+x7QdzKF0ccpI2ug}ccNz+K_ZDV=yaJ8%NR#!II|=D; zCKm$ws<@?oE&J1P?G3c-5_8PhDa`-j!9?lBn240F_^`+e{*yRyJeiX)G1@6)XA|CF~gK6l(1y%fzgTMPZ zHOt+7n5ztPH$k7W4Hvk-LWZyjCH^T@R;gihSLAV`*Ab|(HlbZ;NgDC#84IM7z+Y%E zolIMaRGi*;eqFttNpG(Y4zSJ<=)4JgWy0w9p=Vd@v-_%K$|@&pvTvT7etrU3^FJ4J?Z50OxYUwP{iP|0(H~%o z$_NeeU7g|#*$TA`@|XQNU6{WtM{|k09j9!1x{ptx#}HRQuk!C52ToFo<@!ySiefE? z!A2y3>kTOCEm)^-g;SeA^MK+GtULy}yX^OE{8kVkf2yy${tN``B}~?2@%5`P`qf}p zOILIsbxJnZctg$xDI~BrLyLXec}4 z{04T!Pt6A!)a#~8WyU3LqSrSm_;-KxO+z_wXqfuDxr14cm)PZbTc4oT1U6)th>h{flcdYgU`~Ba;}PQ)*0!|PH8qagW#^svzlk4hKfJxMt$mkq z1?0|ZY-+8YG{3gKnL3kdkDOQCy11dbdGS#@DUsWxxixJylbV`q8=LFuo7xIyES}ah zx4pi0|Jr%gm88uoXga*QrFPz&#x|0PwYHK%tJ=zxX-n^vri+gbKK!e-bL@qxQ1IEB zmQdE#T-{jHP+P!XOH5}Kc&KZuZHRx*t+k|LWP0TX(X+x(`vtr}QMZF38&(A<(35=rh3r{BiIt83=YEg&yrJS0k5+YfJRsR5S!ZlLYD z=K96@-BR07Q`b1xe>S&nVMEhg6*o66qKH`}+i0vkqNc5GVXd#wO7b)RyXNrLruz0a zD?hxcslK4DaY1`si?v_Z2o71V^{w;k=Gm{7%&!`tLT^X0F#PfVk{VABEw!z+EemVy z{k;078Y`@8Y_6}FQ)~01PW+ghTwIo%WL%ar*|^Y8HPKpjpmCM#fa8)d@c1!IAb#`{ zVbo16)xflFu7QSZbhU}cxN`Suae0sGb8C+hU`U|XQg>9&BF3L|e>G$AbVG>*-hjES zwF}y78|Ty(v@WQwuWcmZVgY{)k0??8Mu5#Pu&Y+Tw42CZ7+25+D_Ep<7F4&^*ZFp8 zT3c=B`Pxl~f0YlKTbky?74<$-nJ(Hux>h#&SNVUdM`Q6UvLlE~!br3?{LphJM7GN2 zy2c|48k*zz@C%%1ozqg++@@mdK2zYkjYkM+^4}*KonO;BpRHJ}zYr$2^F(&SLrZPV+@?l0Wv0mBLYllBiU9L| zlcBb4oHGTK`N8u;gJ*5*D~=6Kq@h*>uGNb5D-<&VfGj|Z?9NzxU~StWwQb?0og{oa zw+`Z`zqO!+;I30)P76Qc0s1#;$$s%8^M-E|v)1{g+>bHv{2^oi#$PDQEdRxi^IB?a z3-nK1P}f?0gsqK+XKU5a(xlEC{4v|W&SOUUBNEd9320s{7-vrGeRUc)*ottJ=_GEj zwbNNd0SA0*f&R_;=nxe&WRZ_{4apj+4I0&7*yUsUeg4pc4xV0p*!05=Ibi?l&+ap` za>g#ZBsxA|;mj$ARu}ZB_K8HDaoc~2ZvBj^S^0f9#Sei(LJ#6v)zfPig(+u>sJXu| z0)Wid);q+~y;7Q6!a9Rf%@kJJkCs{7s%`D`PxTS?q%f^-EwG2f z+v_;VA*A+X?2!Fh&|XuYeVWt6`D5jCYvj6E(q;}htS8qmLZI?%*;F4dOZmS#Xi zMn0#>=W=b;FU`t+Wb)&-)f~0N7DT51+o1I?Dj9(O5+ z_Rnd8mDP96O|7E4$)Y0{buS?s@SGzJ^Z8<4T?^@CX}Yn=#^lG_T;J}87=}+paVw;? zuC1?MSOeKoNzQ{dLi{G%NM?@Nq9fUw_Wis%j%wkA+6sR&t4*0km4Qfd!2}HhXAW2l zNH!gzWo-;fnAVmWb)hd{wrZM<)vK=FXXea(K3{!E%`u+ zZdA6P|23x?Dle#O3or~nY6N7( zjwk2&sp{I6mTDU`=V^lmb^rxXpgBiYs^Eyadfv9xvQ*$R$DiFxs%fpD(U|q>HluIV zb#p~}U}xsSPEemkfOK$lBn#_lsimN)F;vR_@~beXsildu$c-#`OWhH5jRpX4^9brU zbCmnOkEm_*TSOc{PMJTUTEHxZdQ=U^;$q%iUR0-TlE~j4RVl+wtzf`Oy&NJ!4?u$ zB|fZl9#zA*Xk9afs&v3na{w=-by`gu+<~T~;{EJ6?d2T(nD!(W-CmE-@IL4Gr1PBP z^U(I@`dXcy^tkWhw%XR}$t_J`Z2L6MJ;dM14{NM5I+5?4->{mM8m5`bhGw>>U=Y{~ ze+b*$1(@XA!^bmWN%spZ>5RomDAAtSnQEGtL|T0&vO!(nfClT0G>nazQrtUVFJAPYFceW z^)%0h`f*KfqNs^0xPLcU{AYmObZwOwj(!EhAgop|__VNBL|WKXH`ilPa_kudjth;( zHfC`|EM&d@@k~VG7T`xy&>)5p2AHvi)eA3Tt_5LJlL5LFhTStZ{(#RswFykwmoPlS zw#@4z{Dr}o8;*kvbt~uv2D|QBEdf{ce%<((UO|(;x(8N3FaO75*wosEwe?|=9C#9X z*oND`sa-tIjKx!%AhiOae()T_cK=#!KnncF)d%_OYo0Cy%$jC|OGbufG=a*{V5poB zD{KjmTr)h{igv2}b9HU=XEe1Q45zeD3%AQmUm$s9>*R3x(7p*{*bj7!i(542{ev*h zBk1H>NEx-YiI8?7kb`c2VQ&45g#}0rTWTm6=T9ms9auTllg0*J>PA zVz4v)-JbEsYni2V9s%}g%`AU_EZg2+`1#8J0D>kIpuh`!s-aqX+l^)?y4k07pF{Sm ztjuiF&~|0(A>rQn|JZx?=D2O7Z&V+}e{JpVldU7pjBYN!sdDVe6TOyYt;R`qbLt!x zHA6{^XNI$Lv8An3`RwP{xDntLBmp|v_t}l@AqjLh8jS|f-Dse!)|31v-l@5Wbo!g< zz|6GNWIU=uZ`mIEa`%=m-DJ~93O;NXBr6&vqeou1t9=veGi_kZXpPRc8f>h* z-eoTYXD-<$S2a#)P0?7Tb0yJlxIIj9_HungCdl{FhANQ1-ia|OX9Wf5r_9_ew?7$g zvyU_p;e9xz5qZn^mY-u9MfCP6h6yMCR+9L7_v6R!&sA6QUPsf}!Xlfe*;L6om@P*Y z3-~mGmDn%qFRN_ytGbmr_UW@pcrzP? zN7<)W3#PfgJ;K5THp_p&WQ{-Xu$h4pUhm@YX|rWEh*u2!%a^>IsP@f^zXjjCz<G z@T&j`&Y2E@?FY+}jH=?x9)t#C4lWN~JokV+*`{B1VB&7SINIznyzjBM>jQ6|E(u=u zPMMGr00bovmg4n-Nt2L-;N&fd=$kZ#kH}i8NXVw6W3YtjneU!IV4JeNT(9Hp6eGFp zz1GlPIKj43oMrFb;5?ZVbEsYH#}QQJ0!|^=aX&snZA_P#93XZ4U9@~f9*u8aFgbj| zHN%TPeItH-i`oEo8}AR>HEAk0BnD@Uw0u7lUb?|HUlKFq`sL4maRXJd*$uShX_}Gv zfB!#jfKtQVKnk9Wq2FUf1kcVO{o5I&FB}q|YHqWY;vIi&7N23g&PP%9kN2`Bug7tKVW$A*J3ND6D5F|9u)3VzkOc-1p z!@R&ML=mZeJ7EE2eyKpK-$%@_ag`GNLbZaL-qHu?eC^=^lEx?}l(7|u3&P|oqjyipMMi%>VvW%skXT~$2Sh83t|KjQ zu>l%SrzM)O=dOwYEvUl&K#duoKR83RLgXDlR9du0zmD~Oyd`F>4HC61BiaL z9BIqv3{EdF7qCRnHt-`XrZ83qBOcgFqcH@F0eW_dxVHu-BNSrCU}Wt5=0zA%zVdGwdR{6*T_TJ%LmprTysmh9_M_LEzIyNR>LAI6Q7@CczB zi*)sRK1Ucw84aDgRKr#53(*xWfD zZD0WUv;pB@OE#g>kM4v7!457|nh8j+k~-0zdw?AQj2a+ZnLzCHm(GCq73nij#iSbU zBmS#9X#`7jt@za))&(GNeS=w4{U&%FmmtAevU`7+Kh9Qg=*HWRkI|ZXob*BALq>LR z`rk1uO356)YpfPvv4FGnEZ*#JrfLn!#IK`UgjO`vI$t1QZ@&wUQBCQOQux8i;;>ph zBknPt zujm@IUE*}dK%3iRn?st;=3#rZFN5FIDGA_DoQ2jJ6W$HpRQ zBL1@Bl@QYm=o+x=fd;SRmP!gDSC(g=|Rc)Dp^Z6o&4DgT=b;CiJv{dok9{< z5iJj~H#xuj04b!$BZ|l5zwMo5WCwao@i22h~5FFh_yM&_F>A2J@I)n7hi`{)Xr~upYQv5%h z*VzZzsvc}QVQQ_HV2{zbo&eUgB8k?|eHy~farC0&42&kr0f2~KM?B1sUcy+@M(rd1 zPFSmMIZ#vocT;K_fd*lAGZ7=HyZ%Bz&{A+m{OZFU_$JxP>kS9$ggY65ow%dBOWV$d zr()BCZEchBNm%$`$AwiUGeG5IH0$hp9GMHADY|LobrVVnqR-rTfrIJ@q{q1vGI6K} zY%s)YOI^+5UH``2aow78hLdr0=9`oN{{<@88*3UyeY{2*eu=l8-T`(tvP5kcQW8uA zD>4hY`J%h@oZQhtBlJ4@o&7xej$T;vnj)R)&ppoe#(ns%6T(So$Mzf{tP2<%3f}HK zxPl2z%-zB&0DBj*1F%?F^G%N_vkZ85O2?qM~xElFYyBLvSgA&h(yAJuPbDAy~lhp4Xy=MUIEm)i|DOmK>gET3v5@=`YaL9)u z@$q*DadIF{0)JOQQWQuz>b2+?WA_VYaAK_Ymh8k??`4>Qd)~s%%Fq|pbuUK1Gxo4T zvJ28#;-}d2w&RW1kaRTH=~VEIZ8tFy`+^y7lZ$=9gp%_>QZVc~woQZ3ZM!x>LNxOX zP1~)zgrK7PcoZnb`C0Bl3_E&o{GOfJw2u=EMvEkRNO3xp@f;zvqMSQB}aZV+jfAO=Q{JZdu#!HsK?@6ePnAtLRYaRKzd9*{zjn4^B%HAfZi z(;fg(XYrVZlZWwya%3i-CdRs;B!`zvTD7GJuBSJWb&mQ1mH_4-vuZMx{px)0Nkn^= zXWFp6s85nrM1z+8u@i7A*@wq!$<%?^f-L-$#9yS+EW|Xjj({7*pw@1A0i9AZ1`DIl zAA0M6KMc9+6mBsDC*4B&%~8jvxDJdKQjrb1+Lkhr=*(zI{v`yHLCLHw(vaLz>tmiJv7P~zqb3C-)+d*g1)4b{^hdjvu?*74 z71CoN$66(5aMUoa3*ILzjE@T*9(aqsW0|*W7N-a^$eN=vAhheOTxr%s&jI;8Hwc1d z(Gv@EVuJ8Kda`9%^z?rq%W&wL`Kl?!XU4TDJzDZ@j_lWJ@_6>uH0=JD|DW*#%`Ua z230+LC{ZL3OV%P;TCX0(=~daIs&)BS#JR3x;zIEaY*WAcKnzZD^wA(O8_}z)&!WYz zl++Ml#V@->2DBbG&1A|luL}`?FODp>QIRjcwcPa8EEl{Im($@rTKSr@-i+LlTH zZu&7}^)hRvtwIe>&(6+9!HMqRY;SfbC7~UoGeTVPTS3gT{p~aIx+im%%FXP8&XR^~ zjflbB#bj-vRU{or$=)0xC|7*66n&7~V^TT4T)-E_Pw!Z+7?Dqh)i9K^oe+UmiO=L_ z*EumGAKtVcY?vT>C-cbBzrsmr2&Et1kgs0k(}X+k1tvLqlQ|sW?@4lYrmmb4E$qXj z6JpLkpdi`5y&?TmK>BBINWTb3zx0Omvw-w7LFzHYqn%XT0GK@}rTg<1w;aU?+;3-k z>_yZ#+TFysjDuec!sybTkF?+2sp~48?DVZv4ImAtJmpiLJ~hE|715(t6P)-I+LE87 zlaD>6CCQ|P!@e5uS96gI{Gm)u1X6Bslw>GLiU)Hsa)et)m1O2R6SF%o5 zESv$H=RbPMMh2{hFr2W9i9isu7f1zYy{hS>n9ETQI5S+_BX!J8^7-n3_N(7V-;1|D zwpxgGmaAZdl`rL7k(B6pBGf#?}6i5<&BFWEd3{t`eEzmA0GV<4sm3%Vl>E)L3S zf&F#%)T>?N<&wbR@1v`$kCtu8ofT`pcbqI294-Dix_Ubt;$ZxU3$EhFbcqb@f8V0z z#&a)L28cu=ng1b&q2w)00{N1+mb~Y?#Lk0rbS(5jp31VGqaCB zY;ij;3xK2hSa8n~-H^-DXEc-mlWQRi!|))8>9z-Ukd{^`+LO4y;T1m{%!qxG*)wFo zDmIn0kwlh&42rqq?kozyNCy82w}AfGYb0F!8qL$YWcGP6{q;!wKKkGM?N4tlIseTI zW+f$pK5-OnTAx=8Ik|hFIaYq3!GS!;)owS{`Z7 zQn2`K0N=bAGa-T~(T|=h+u$)>r4Z;CT8^nt^>p+@_Qkq~ajaIW=1Q`IN99%_*Oc~T z>EHd=A>Aj~A!epA>EzA(FSP!^u=^lVlk|wtVbF^A30Wv72mZR+Q7nQTSfmh#B%(@af|b zl3P896oriA8g=oMMecrg!tz&uowN-yzf;(t@!kB)f<4*oBIbJ*n^=60uz=#r%@tnC zN$9^=o*o0(>Qejux03HvACw!Fkp8Fml1C*Rv#fz;J5NHopq)5C{~m=OH}G7uE_|i& zkLyqk&wT>}@x6|LqWbhcN4}_5@*XWH76t>0FTu5vmt`fvs$$71R^3k(t0aT&>1w?K zYZeWx!S_1Wi0V_8i$>$Ps8;eG6c-DFHN}@;P07o$l3-1-WEE=`Mb^k0yTo7=Y0+jF zx^nEZA=g#yPUh+EQ4HJ8Fm}nhFAN-1qeVdD1b7M0OP~DoRU7a`ON+i${*alXWKFm<(HywN{w3FSJXfwSfAewMDW0u#_ zwP_->6OJ1*wIGyJGai0A5t?x6S|nXWg}D_ zIxl~Ol^7jo{=n{>-tlvULNbi7IpI0h6AlF@T5y~F*}?UfDeg8`!q^c=1R!!%_5#;e z^4rZsPj-X3SWa;xZC}b35kXO;@q2AuQP-bwjJ*C}s1qG9YmIJn0EYD(ZRMPFo(n+4 zA6)6MM^xqh5t>@hkKS?IutqwDIl04x#Px@?*mWB_?f}uW=7ge5zxQj}3Cmz8a)7u2 z)mu)rYn$}Iq;7qu0VBftHBkemAF}T#^BT1Nq^XIo=iK88PB!cJmInpO86>(L;rKdz zgXHB8NFj`j3GzYxaG=u^-FbAq+flJp^8|Mo^7B~w5B+j3^=1;^KHxs1zVk5veV}`h z`obB%$G+kQdrbUGe_BPxu^>tjt1(0R+(rBfUW;Q2_J2d$FTj(R824I#aw4m*OIKI# z@V%t5JkKIM1NZ_!UMaomHHT1lr#ca1b+ zXOpIRrM#226)$u5icZ@~i-mxPHfeirk4UO-hVMU;Ot(zg_3L_8x%;tPNR`p0t5`++oKHY*J-zLeGKgNxx(~>#Q{}zGaElhfY z;58N%gJ8_hv%?@AY@!|O!T)9|Y!~L7>G?Wc(`BcoTiFAm3oej6BX(v=@qsB><7OR^ zdt2>dJRnjIx@_9?iAD2hc|gP6QfHbw$paDul~FJwA_iB{CC=I)>K_8Jb-6a>#%DfJ zd1%1}E`#LRuP{qxIiiF|iM(g(C%j?uaF|Li0_PJ87OU|?8P@aRT97-5;-npg96=ew zJfQR3^TDa=dU-@fGf8>qsB`8(rNhI^C5;-Ns!YQ*94gKc1OFuC-*Q01ro1gkK^#GOD60Ndf&|A zNc=L3;qc6?`vf;2`_@h@L6TDO-m#64*D2G7L#U&`L^*&;z|Bf~rWO3k2ca223@?C& z-wez>Kw@X>LCXb5SM~ldf1KfDF^;HzL|h|@ztG?w@t!BU*Be}0|MW4{M}mLE$H{I` zgr~`l38on4{#Xh`Of>x?dW?40(Y0^UynsZ0pJ1yfBJsU#>{eIaH9n4{dheD=jJzf2 z6t(pV(=|U=9`2tvoo+z$p>TqAyxV{G%ntj5+Ux8o+dn(mf_k+yRit?PKHbh^WV54V zhOg)Ic&BBxbJZwsF7_*vZBzl5Ae>#4G8IzKvc;(kQ5|?SA zApTl&zKWg(L3DagsZ;jQ!Pp(2Uw*(arN^V6aWt6!{v+w06PBOKw-k&q{rbnTHbeD1 zOgISQJg_W$UdPNC&gZdfYCel=W$6L;8O+U8!~N#~nH0*~EKt=FW!!ex27j6bseG0L zb%!1g<3W6@TH>@jJh$Og>}5S0p%fagW+;ip^CWzMj7H03PB-O(ZMX8lJ zKPvrcxT4-klti&99(upnAdix;PdB&8!{h!ms1418Dd{b21Y z#pkbiXLsp-pRNY&!b+U}nt95bIb=sxq4d_sGa4C`*Tb8Z97stP8sbSu8qM+6Ey1xE zV!Ug-?i-7^JT_~UEEda{OPrpC#D~^DE+F&Pu=6F;_J}a^HjZe5ri(Crhh!F7;%Oim z?eW$z7hAs0U_Ik?809f}Yf>QO`VD2t8ubcBa(}LX~6fIw| zNvrGvj;4+pjNBY?PP+e3`n=$!|JiL4wp~wGNBl8*eF#ebpdHTc`LNV-RMvZkV*=!p z>_7rew}4A8RIB?1xO#`i|69lBdFXO^fnfgqcCzA}wkPDBUG z1g^z=_HjX`Yx&2d+HW6ci#jhteLko7hSzs=dN&iAn&nD#w=*OfGPv8ze3(wAD(^GZ zg>3VvMWaXm8Lgi2Yf`Mbn(k8h4{0?bX>I#@hq76#rIEwO6zyHmgAtQ-acQkB1H@go z84v!L`w_0$-s5H=3YljD{~d19t=)?uVl``a)$M;Slw3}n78Bluvn(x#WHH)Q02H)BkWB$NbejLBW*gcoz2sP1$2r254lSW8sOo>53mWv=j6B zYExvoTB&6#St>XEyN}`j)#Tsf+ELGc;nTE)W1sA1vxT_A*Yl{J(6y?VJ3ONaj(7X$ zZW#~LsPnt!VIWi&kI$QQKTNZNW9lq^x$6L3hFndu%XFL`#~3dB5$)s6^N1=q$+gZu zL(ihcuPM|oFfm2$z#{28Uy6+hqGmUV>c1Wy5S^UONBQZ-a|?1ak!NhAMSaTbL`YCc ze6An!f%K|CWZw!0i?oQjSts)|1wQA~^RhNLH*2trr|L|tDk%YC^+%Ic~MfJHN``(WDOcr7!+Fn+d!=3Hqmw$ljW3lf|QE^NtDDJDfuq6gMazH zTu{2Fy_qQWnBVW?@=}cHxx&Pw!8}e9lOK@`K?I%oN8@?MJE6w>!~0^8q50=9Xnq+6 z&CeW-&zUtij&^c}12*~d=WVpvAZMd&z7D+jMf4?0%#X^>LfvKFI^D$U~vMqO0VG zMSFq9Lg&L$E*t4lRL|BaEE^GdN3T;PWQm+6Vo@g7Y(e3Dom-uq#UmT5k@}o|^js<) z8+VEvAh6*3pH2-#9vgHLZMP9Ed0*4Na#mA*CI@jG-le>}34g!^$HhIof;Y+MtAl^} z3P#waQAX{7@Qs!OH0n&av%x;$2Y0^%^{K>yU=bs-44!GqDLQf9?ecf~L{)!?0*a$3jaCjCYKi*H)V)SrIy=JQonah$7r#dH^e&lwUQB=W-L})a#e5J%!Q_Ai zd?qpjbXyP~ke2rK`e7N_ZN4SmmhwYkWXLTv?16cSbd^`93VLfLizMJo7 zdt^_ec@9xpQ+P9ysc5e(^M`FLZi?SM`d7b`U9uhk4bE*3uml*RF+;G72WsiCD1#32voFA=t#`B}k5K{_q3zPeB z@w|>!$y{58pUY6$;G(49PR15`YLI{$@7xd3#yEpGSA@jcj+~!Na^VW2_j6j?*|QW*3kQY&@7^T zf9?jShT1u<_hK?6r-e0HtD`w-#bek7K^J3(YCmJfxjZy~_yvQh$6?8gd^j`9#HberW+t9nkG7JjJT(a9? z8HCqJ54zeU%lKomijO`Vuzuj6%@6$DE8N|wr^t4Y*aY{?N4tHvPs0sgy|6o4rZ4%Gn4=fxN>0i>KT)EM!L1&Ra2Us zJ?JKRCRHvZ(1hqf5>0?kB+>-wLdMN|8_k<}I}YU>NGCAWU5Ne1Vg||$EOtSiOHln` zX?HEU1=b(hXcW#LAH$eKhpiCj5v|y6w)DeMZep_3J$g8P(>%r}-9S#d*{o<$ z@xu)Dvb9T7jp~I-bIshUgYQd@LY#4@^vCSS8?w0YS^E_?CMnmGx~u(Ywq*vche$ZHV&uL&$sVBhWK+F9u>h@cA1*g8XCa5b`->)?!#po zEy8HMKyIUlWQPSW-G;S43&Z)-QxF8BJ2Yb+?l7OCG4t6z27W+j{Wgxl!1*V!EceM~`HTXhtzZp~D6%TwV+>0|Is6%-(&KQ-te7Z-4p6B1r>i*n98-P% z=?xK$mQGijJ>i%>&11Ie4Z#p97TC{PFt7+4ODr z)9c&In{l{@P9dp0Dtvu~Z_LOl8-g7@FiOt7-u?LT`*XZ_AFsk&WX=MUh@kB@q(BP{ zj(^9BI)hU5u}-PtJeFn1Sc&yJV5SS|QncwB9K(xC1gIdj4PNk1c%|y$&mvp^v?p34R zGyjMwYX2PW*|^c)+&%AO(9QtxG6*8kFu!@0-dMf@X9WQYB%IAR9Mgn7(q94)|9-MQ ztTxZ#qUysv=F9}#D64e0g*v3YcG<`Ef<@AneWK71Xri)Dpax2(>8!)U7m|a8wf{yu2XA{9_{q-tdrQ2uvQvP;FYC-?>X%ikWu9>8* z!(I4#_U7_ZJmVW)ESKQ|q7Bx=k`Q7{L2H1E@}*vPw~G;biz7wbZ7MsT0r~E5e~*#K z=vt)lE?lSk5K$MTCuo*cKn~#>9r>FGxs2A!=Wvdx2h&0n-f>9#$7mlWax5_%C`(YI z9ZP-%YZ9BSSZ&6Y99$|ZpnicHmpRBd_dsS=76fs)G*3QpZK;hh9rJ!0t#_ndATM92<=F2Vzv;+UBtWa_$hn} zKjU8=0*!+b05m$V(+Jc1@D8_(E_Pw`1Ob=)V*>@tMJDS~caTD%akx7mfAm)MJIWrg zUWKnDS(>?gRj44At>~)$FT!(kzhYao^gq2<66c!LduSM*l>@d=x-sr!v zjzLheAuTt_{L?ZvvF*aYYqf6m-&mw=^k=E-NPce{xn?22W^i15Iq-I%;N_PZtg zu0W$EYr-MSe(%Eh5;L)0j-Erz7}U?kdtiiE)8<<2)iOo8*? zldG(mOwk*2Ygqwk`26%cPdCpxfpllG@odb8G(8%lCN~9P?Ih<&4T$zOj13JVx3mLz-?MAPvtyM@4*#3YP9>yqR&|+?&$biL|6x61OD#uuC(!l|} z`$3Xg>aj9A%`~h zx`bl;0v5`Ngov+O&(ODW((om}YT;8l;;#(oY@Vl=k`J6F7!j0gAHoOBhl_-k%e2S_ zmoS;^Xna60Xc4Y8nQd%oGfK24%pRbBrHR^jE?HiQ=_L7gwl8A9Xp9MMpc98Q%S=ji zbwuNN2h&DY4#bFe;c;#$66qt0@`Pywelk~Eh_%f2i9}S{@=v`BskY>6RvIR&oxVcL zjjR*#R=>hmgIX?u^3~nd10X@*dZ%U_G@@D~cX4 zx*kJSii?+q6Z%7c+L945qi91WH|>!vQS=vum3rCgJlfCoz9UI5U+mBqxoXw1;5GUm zjn2Ky4_B(6Q^D$My;Pj+-54MGdY{|{P-1`^J zW6%pb+Tk%fT1he5DQKus5_`eIi{hq_7lcwV%5n?1@yZ~-d^1$K0ouh&nDo>}rg{%l zy6?fue9y>N#kR1uzK$zXK{SAO*f8i{k!wMhf&w14OO{4G1^^3P13)StS?`e5Vu1lf zP6T5GQSp`bExENup=8zf^}{YbY>gfU`h&64-977lrZ+XWVcxGcpA~Bu2?w7s&sn_8C-e9X}|zpRfm!FzC1B3jLNl2mBss@5d58H|K?tbiVly zCxS}xC@YG`AXhq&TNm+tEQyiNx%y*Cl=wc8yDj-F8780Qv?!k?@$xxG?j%RwBuC#Q zN6#cj&q!KIeJcV^ql1AImyv;lB4HD@{3l>m=@7hl7j4wq#=7FsmR_)IO$=(#{ksMNG#svz;1q#On3daR{#szxD1$riuo|RC#@aA0bIfB1Y1~B+^ zPD?&88yGvYAYC`)Ho6)KN0I3?5%V}cPdKRTbGXu+M`d5hWwB$Ri(hGxkN@Z^{9m*J z_(bk7<(T>;E$6>nO^#)OX4^UF9I4Vd^SKVG*?|7bm0;>8GNJ2rn~mtX(hX+xlF~JX z^k1&ViXT;`^b&|Q#&kdw-oQ_F=JZU=KA9GE)EA;-e8|?`(pZjy!dI9tSXh>zA4`iW z(|RV5CM<4UufkNaA+4gmus=mX#dzJKtee?Em6960jM`SQ(NNklWo*|wPlr*qq9<@; zCGdJ_)8t-7yT0hGVg&le+^AOpqk_`*4n~y9M5eNYWC=JKtx!Rzv9nBjFW z&4ze@Q3~i%v&Ey8LTi13?Y!C=Z(`$1S7}=)+T+dAO%{1woTU9eXOq{tV3_4Wzi{Y( zDp=i>VP5ab%=pW#_tK)JDZ*=0e6P#w^ICCO==JtC+vv5rH&i!JBjqMro$4(%wy#?4 zzf)~B5^otSrQ>e-N)~X`c)rDA7SC!Val<{{C@IZs_u!cl?ON--M!`q3HJSxqXHc^Z z9~3EJ)y?=26xFRWC%#T(VPnZ+M(Ro^P3zpl%o zqTL^#Ge{H!lr#MsFs1chCx|-$wDw}7jqj>Mh2UFfjk$_jKx1=ut?-bXR zI{_~hlgWLc7g8Ps@J!V#U9)9kTe42e`W7Fv6^ClS?o9xC)yC{S7e6)J;6ornvyDiz zQ$cSg`4#Z2_#<5lc&CH~!-dRZs1)ABF!xN2$iHA}jBO zKxrjSE9rD~ZkN=$_(BipHG zj1ixNc2bOyk^ZbdH8@OlW*w2=hh`mN?maWX;XV(YZ6!O<42-$!%v2lRtM1HZ3;9<0 zKlC0DE)cv@Qp_E(#vA4cF{*K2NbVJR_3=tcIwOVx8w_B~DPq1MzX)2d7+vNWLEkHZ zE`B$CBY;&}R$riH{YB6+{|G2kVuLTtMS^##yP20nTe-4nGUFb1mFPgEw*(DPBd@_< zqN}NrqB)O=j!ZgDjCU+j(d-58I?>z3yeD9s(zm7qMQbsivsGI(FN#(OeiT4gBVD*s z@JhiaZwj83+;N8r-U#+%`Gw^nxyZ9pw9sF}or5<5G+XGy8N0mN8}-!%UCgO$+}7zO4*ekUKfnI(%>sg z==LP34&*n!63aJ(nRli<@CKcpYevqtbRv3$CWWw7;Q23CCqhny;k;dSW+bOgkM!mV zuM~SVk1*RUM1mrc2n^91Oi~n1$QQF{6}>>t;KL3H`S6lG&)BH`K8cr$@QAr7naZQq zJs@CZbA&aeJSIS5G=Yc`9FmJmcoW0*8irn)5BH%sGr>H7>~P3il^qG9{`T^}FF(%0 zAEy7{BFmn`o7b1OGaL{hnkV`z3OYn*h;}G+a-+pi(j1GV2FoQKN#X~oG#@K{BpduF}w91c)KYx|=sN`zCbseuF6aa2NmUfDkX?>}7R@B=PTv z6Wveu(ux50lJJkd6dR185nBf#S=z+q8B!sPE6WZ2gb zZgG#0K|0HXNa2Syh27#bV@Qr(aXa=s+NHD5yQ zg>yPWQZd9T$*p4Fgbou=3#}vgrF^R{UnXhi@e__7BY>=gf$~#jTk0xT^wx-_L&qs( zM2T_4;g>l2G`&p<9XK1|&^AA^Y!nsOl82F5oFZeGwr|1lud*UCYDKcGv`lfAQ-VxFlC3I(l;2xp>%bE$ zu;?xcA?Irhm3N&?_dLAqdkHhEFpK?}I((0W24FY^BU4f2Ws%{?fOecYIT@S_`4vP<2Pu7!p(7a+ z!#&UTLF+>7sCOK?6s3xC1nNZ4y26o$FgRh}{RPgnyl29|9)&rsV30nQ+dZn|Iq%N?;G)j0(}TcKpalhr6#qxNW$y)L94RU%FUe0hz z#(a6X`w1s()2;dTdv@INa)%6I@1tL_lH>Ve3$?NC%H;za1-Nb;X+3xz4zkIC;BLP|a1E;CdtyLZ|mWGSf<0x@k&n5O3Q>d)^wH3%`pxP{k(WM!k{Id)^ZEFZij{? z>u1@;UGoc~@0H9*Sk0O1-tKUvp%@lSLRR4p`S_5NFaMgd4PopM?+YSijF2GUk8fBS z{o4iI1fsn;0!oo95Lm=7Hg0GH(AR%#_(c;9gSw0oUz*?~tkMLyzX$2pn1MOZmf?xP zIvjeCl=1I|BBXx!eNj}r6GIK};X4eMOyzFQ_=>~?0q-m}b#MX7%@xBlC>UWvRjLR? z>5sn;4G@f=F?AC4$C9b)D=^W}$a*I7uPSZYq=0*JigWt#j2ewKn!bC+NsV~RR;Y9v zOvR_)2jR!K>4(K{AWfgT_f7T3+p;X@DQ2NcD?m^BTXfdJ&Hm#0678XVy zk63C=tc!l)XUmToRxNUA1}iYOCeiZc%UG_zBiaCx*9$sA9EOb|jAn-z``kB&egX6h|1_H(pdHzV#*6aAy@QE9FeOe4DB7iz(ff{TW%dEwR(F-qANGUpuA5HJ5N?osMoKVgw5g{&GWE09P@AbOWup@@~(o;)1yY46$WX{Vg?BiQ+ZohiCB@Ggff&mZXqv zb9XJoh8d7XbrZH51kH19uNIUUe0l*4;N8H*dnF4P7yOtn%^UrCkt*9x%EJY5$rE1y zyMRRvbwyY3WT>`YJPV#3!uq#ESYJ3SzSZs3#LTY8CIkl%afca=iQCv57Oubt0p+NU zZ`dNm85>4p4XQDmUD16(rgUy!bOn-P$OKF;B$Lm4^X!__qYS7Qs!w?cfHTo3xo^h7 zD5*4D^%~6=*iv&hinHcJZkGyVZuMZj2r(~8?A}DWr&wwinj4WC2e;5zlflU1t>A^y8tDoeHWl;*6%(7jjOx6 z_y2f0EzyX*SAh&{!Itj=tT7+B0GL;@PGGvxvSVf&5CmN?S!uD$o1VkD{|g;E%a=Ar5d_{-L|dn}Nclzc%3k?X^98Ev0GlvucT>~eO_3)IR?>3P$m zaUEirk*VwG)F>u`dkl;WQcpk^Fq+O_2#28*7dQqZ9_38ejfCJUfYW`4ZyGoYKf{i} z$awnA3yS84xB3o#x-k6npVu+6WFrePY{V@3{?DVo{N*n%_)*!xIzVeJYa1@l?$HSv zv?A{W>)e1RVEt&F&~zuPY+c1y!05v=4nngFv>)~peu-|cxk^g zzfQeCUw%(#R7AjESGBvk>Z>CbKS>CkSv#Rf2rxvgCUHk2Pvya8^H(jGl7H&Ae?!PN zeEHu!Ge$F&M8k~iLs64=lSIa z$lfa2Pmd@*ga2+Rd!1W!!oo*-_VXC}vNwpe>B(#_C~zO+?zf(FoWVUodnSP4VKMZ8 zJ!v~FiRc(T1g5pTR#9PVJdpT1iv@xPmM++U0Jk11q-iml$^|AFMT+iYx2W6r2F2;5r(|xBOQN z{G)zroD$q^)d#1b^NM03TJOYKcXCI^%F&nT&F|=E3r_L~!EavNN6TH@kE=y8+A_6B zOm_zF)6H%2@VI}I;w0o&m}fex+h9@(uQPdLfV+zCT~SvGt}}6Gcj+EU-dwV;5@cs0 zPdSkenOFs}D~V?$GU=BcJVsqdCC)+j9Fzqjx{gUjN>_FS$3m<)OZx1dilDj^wMrI? zWz73Y4Eu)30UzGS)qKDvG+<=}KB=VHq>X>WS+fVvVSS^b8N5%P$c?y6mM zn+B^ZSqK}aDAX>a9fA4|reK4BE+gF_qca<@MeD!@ab7_wn$A5s*73LHLY|7QOn@2u zfzmaQc=C;Ed$H)Z9;>3DEk|&Gq|ZWs@)#qbV?RBn!RXo_lRd6z?n{P%q09x=3vKfR z#WA;_wh61jf#4*1NO5wGjzk$Yl%NARq*eUPx6HV8s@A8UZZ_#Ifuk8G+muVWoe1@A z`~~p+dU&7>t0mQ{LO-$rW|8cXn>W(V>ZhZfMD2ZnnW2et<4Af;}qp zOIS6M%Ki>`-J6WBz~*EXS&v34+mFr4+UG_jC22**dqI!t~+dPgU}i! z!%x)CWYQ-AxpR|s!ApF!@yV$ZXA4qL+b|{vJvf`~zPb>5J}1-j>pP0^%zC0GFbqj7 z4H+<$XtOHQ*FjzAy^!>dS`a+?`V`OpwIz3n6^nN$`#Yc*7YA5VjItTUa{tp>0rwS- zV8o;Y7pw|%v=zG(UOb~8j)Z}wnvcTw35#dpLh@bGu$qILH6!_(EJm;$>A9vdhIx+; z?Y)W={ED7f#0Dd}nO{gqt0u4i!}x`xd(6X#Ys+{jogK^Ot4)z*Y9`Ir2vlzR_twMa zE6QH?*F9-7zcq6Fhh0$TES8TJB}BLH&PTD z<+yi;UoPO)K&EUABFlw8E>mDN3~k!N4Ae`BoGW^{pRl{APmp+=xpTN9$B-_6oH$m| zRxdCIRYk~jQHP>EnQx~HkP~9cKl)Dj49Y*9K>5W9l%F}29?CvAj&@Qn1DO2z^A`6& z;+U-=J(h#E4>ic}c@u9}2i(R1cLoU3p8C+#eK@hxRcdgu&5SExMnpgtsSa=oN0DY8 zdFcvH3PA3-NGEV-$?ivzqL14IciA0qD%TOztMrRws23m=8Uj8>Nn-a-K3k{Q4@6{j zzD{4$FY8%P?X37vBhPE!B}etCknSz4hS_86>xVqLlXkj_aO60b7_Ecn*?`lXoD+6! zEhK?$m8Ax2x2WjD(^B*UEA@+eoXEdPK3^TchwsJjAFank{}t&7%TGGbE@`;Q9tR|2 zw50a;vxS`rdp-aON5Ft=#1$_{iVV{{C0yv+lJRm$K(4MnTDKr~7^TaUG+8b<+PA~v z4aSctZc}?qm&n!ncS>X3PYwcvnvgjEkb{cgz}(wgYxedYXQN{=(DPJ@F|WTKkgPGg z+ja@r{jl9XrYtz=ZA`bgQos;jWg@){@+w!B7>?eB$Ai$ zQx@JN5|fCnmzngc!;}|{PzWXmtR^#g>p$Rw_<*zkuh$RDm_mv5IK?ik34+ITl~TrcXb@2M zL-y37hx&_L@TlzZ{!kEu zPXoW-I%Et|dIOnIOpp?$8FL-qrs@8xbkTU3Qj{at5?AR%gbd7&tFJ@K2ImvVs>6x7 zA*09FB*Yj~f+)Uldg?}b){owqPMH{ zVHRll!2*j)liinSgBvG#J*i=BD&jOqZa~`9!ahLMvS$asiXz^AhLQDid@J%r8h!^0 z)GE=WxfrpiIa%N~AFej+iI$c0-Y$eUuobaBZ=U4tYqY&PWc_7I7jBERl~&homR&)z zj+}s5ET=b2RSR}?ZPg-j1c&Hx!5>DD3qaIgPFO@e<^&MyGqKQe(QR%(5ua|~&Gra` z!By|+mvHYu%2`vLL!I1VN-!4}UFF^-sG^$gOjV}4LXGdFQp`_&qifH*EXYK5ZCm!otbO zFEn|D7ssYasjJrHbX8ySr}A#|ja^}lE-YQ_zP~Cm74;lO-A#Z*j^(PJu6Bc5o^qC4 z(j&X=&GNFqKOCl(R}MOApZ%?bju19oT<8i-VYz1BZRiS3_4S7?MwV%8ExRMpO*{Hs zqv(_d^jpL2#-&%pIHaL`dCn{uEDNZ*pVA@DZud1hBtTv4q&7Ex8!VYj>w$q#%G;p^ zLMLyK8VH@dWojsNX5LocV=}O~q|)JN2%7J)bcik6i5g}@zXP!1rnmtqXm??zLw3e z3^utS9tfLQ4-bT``SMnWBY~}kbAp&ff4EU;W^kfUOGo>AVqLMa{Z+CKF&j&dAvTF< zZGI*m3hjVXam~fHZaUBE?psHwtggp(g)3Pjg?^TIlq*g%LAE1QC7w&acr^E!7ew3x zcBTcpc|n6%H411%)L_MJzAjY19ysl#6-~DSyK96{Z$q{s7o_f}Erm=KmFZgCAoMN+ zZLTtQq;$^Tn719Pt&%+Bt=Ps=BnAcbm_}YfyEs^#G{zS6}-_X>&Wa zqb{|%K-(3n#yhqhA+ouK+Yzezo4Oq#X}HYW5tgR=zB?tc@v?BSx(nRRzETS=^3#;| zcZ$1fn8yuXW5y^i+-$hM+|@v7xZ&Ip8a+RjVNa8J6U=A0vuP}3FY&QLYqw(ba3 zn+w_94P2k%(0H-CBhEG4{q77)?e*}Eupkt*{swtRc&e^<_h7@7$+tYt5ml{G3k??o zMz+J}kg2+E-b=Ss-%RgH$l&{A7i@eM7evxSmi8UTZ!*t4rC#iK;KzGAeKzszF5U0b)xcd@iPdLQPkB>^ z?a(Tu9vgZ_LzD7UdDfowm#e#4*ybDKRd=c;dF-CxSPVJdMZUFW0h`yRt&+uJ8FT6L zKO-C$(0Od!`I5~9h>r8#upBCnjk?(KIeds#<#BmzRv;wf4JFE z+mZW&XVvw+qB9!eO|Kix@!2g%I_9feL^>8VJ^3^wjP-VS>6LtIJa!5qIv!TYdQ3{- zr+AM1qdeQRV{;|)aGC^&Rs9yNDTg@&l#SiAEsMexNbQBsO%r5 z_lKeN58Uy|DzesmRCa)lS7%`c6Lz}aR(g(bXLr0^N6VKlck>9>9EMDUw(-5ua;FPJ zX!;UWCs1Tc?yFO&WpZ?~kl>n)FSva5bwR#sxyU5kcVB1AKTnN5pOahv^&MR%kcm&` z<}ZkNbhk64+n8k?O=APhVi&UAqZSPx{pYlN#_wLS>TvXJM#~f}w5^dy7^olGv$+d6@ww^_cUsEV%;9{$WCd0IarPF_=78^rG z&BE;W(1zTK%|Fk48@z&vkff5xTwf*#>A!*Sz7?(6?P>^{}{m!@NW$j>#b9pC= z!`2iMD=E%-!l-9f@-7HVZ-Nk z$tp{m8A>KJQ*YdAj3K1`azS@z@6B|tethKT3Kx%D^SS_<{J2h7bd2x0N+6;|tJemd zP=o$4z|xT+`sYxHei;hU&m588**7?jc5)5`KKb+KZM50M+gBd+?jSmE9PMu6?dq_{ zoy{rPt+glbZSy*+SZ*t&m$U<5o>mtoJ|lwH7e-_ZQVk@7v;W;SFiOd1_CEg@&ywAb zG{Qb^6I{J{fUSBs#8>H;;Spb;!I%$Vla~$kI!w;iDeNQ>`Dd@w*YwNnN=KP>xuuz6 z00&qbSLcQC%FJrCekUhAhl|$+o~|Nt_zW@O8mPQB>Ll83BU&cErhnzEr#xIv;!6gQ z`SND`K^G<$_wY;JB%iMiL&#b%!ai@GM8jbmEeC1XnQ*RyiNY)IR=W?fMhzA*;^5#X zhZA}TX&5h;gW#Dg7sDV5#*gV?7eA)UMZEp{b_gB@2k5A~T1B5?ZAOsZ$J@p1oL!ROcYijHpEeK;z6G8>ZPGQF z=A-3pygzK$KasL_EBb@1%O-p?`2Ar$XVcrw_p?26)X^OHbh((qf09f^n`N0lbb}}J zboV%fQl9LR^&p6FoPCf*!Wa!2hH*UXoDZ}a3s1XE)BPV>?8eKKjz#e{U8N7vHrYR} z{@6|0An^cMta+nu$j%zqiN@hlGE#`%+sIkz`Hb}$LQDw7B_e{|M0H*z$J6Nq z2^>sCmYrNbavMEl54d7fH?oWSw@y_qq_Gb(M1;0e z0*<%g{&^EmZ*-5d6GTD4?^?xNztZ`TYd}BRXXUr(;&*0QwhnfU(`jnrtQPPH^%#Fz9TI-{SorqwbPA7y0 zyLkUbUCb(?d$_jhJciBd{+4t{r~@sd?z(f)?hKeKX!&a)J9Cdn#0tk(wb*4KAQ&G4YpQwKFoL(Vb5)@Q@!M{ zscWt$_!hk8q6%RW_{U;FZ_Z|nF=sLE31cNYp)FgCuTJ`Qy)w($;k zrzc0^XNx-T63P^VWuaITiYH_&iMR239uufK>>2T^n|I7nSywtZULe&I;{q0*$*Pgi z^A*l_?{Mr85^FU46;`lVTxEO;?_kgnZ^3TjEEm4;=r@Cz_B}xj;>`J+CJV)(`rb5} zNF6GgS%+3N^7b7n5L0SOkDV?@fi#aGf!eDs@Tm6~F_38vPQ5V*u7!O8Djwo}D49Z& z4Dr7BmcYELY;zTyx;kS*taJph8qY_+Nj4I5Ya0=OTmdJZVrs~qYO9S=Fh8s4Z)z)_ zq4FI0*q{r9lyJ=EJJk_#j``+ArDmM%Pd~GKze~vK#pH)BKvds8e%K=QA=BFk zi@UtLx`PQ&A2YIo?6=BF^UrtSy^P{{ahImcBNjg-1_gtrNF$_N+6^MF8puTy* zQ$W+-3Si%+!evn3EEM3)5<*)}J(VKrt0>QMiWdnc&4-veq~sI*!W5SNhKo9?9eAT?6AZJ?OyC^lnQH4#O6xm+wM@6QgzEN z`>$?%UtM-aze+k+ozTQbqVh&=IEtf%G{%d+ikXq?4SH2ERf^E2!sy8cX7kv4S2g(Z z1C7nEw5qfmZe@VkcxxUirB&@lSw&TwVOCbva-3CEwHjz;b=gSk$S2F8RfcvW(%?6Y z%Cf4qL#ni{<(Mj~s|Hnm-Vw);JB+8oa2jI^#8o^N{keHF`&RgLx|Q?emfygr=EPUZ z67}+BVLEK90;-fiSM=IAx7R};g4M%Xh+Q_Rnp(QpKwk4|j@EuWolBnbA8d6|;QVCH z;nP3mCC=umbHuOmawpisFjCpSJ;E9bwAA(LsgxaB;SX%eDS$iQq#F+H^O5{n3JMzvboGAPw3vk| z4#Fv{EfZmB&8fwfa4N`d38l^6r6uT9WlK-6&B3zHl3}GxZwF#_TF&x`vgwv1nJ?o= zoOdh8M{tf|c%Lk>ZBtv=Dc>s=-j_ljk=)34vMG%y;E=Pf@p^qI0jxYm#Q8&50`RM#YB@ zQ}`L?$jodyfKTB7Cb`u1F*%QKCmflRSmi(cFnehU4}IjquVD`l8x& zXfuz35T2JWb>VqMaw9f0nh3Gi2tCZXBB+Eok0;$Jh&W)Liv|=TToH2FiGkc8EJwG; z0U`noXw9VjPI6dvC4Opj|1G-z28xP_fLlD70APNQ>mip7X%Qa)^mzv6UH%Os(_SiV z;s-j3ADCGcba2LI98DpWgcx+kX~rdBC4h{RP~o1?HAXNDh*_Vl^L_-EEFM+HJa}tt zX-tG)YD9i$5EY_U*p|d)SLMT5N3L2H|j!0`@4gvoeppZR2?O72eSO+L7yJa0&7?(f}0Mi zIOEWVP6g7j1-R)vMIV~04`K9yT7Gh)4@B*_2SnA42$Y-+=|iGpaAl`ZT(w*sNO7d? z6g)Q_qn~?mM4=AS4UyUr8%H#15FL@29p-UGVg}I-iP|wC$68Z^{K2V1PCvKgOcz-n z{UJ~B89U|l+NG1x@{kI-HW_-iEN$KT0i2<&X~Jmn$bp>%1(H7&=oEPI{Gii8ZGX&A zcE7vHsXgx5cMhi~HUjk15frL6SlpsPBk*Uw}r=dx2SC(#Z=nV;W z^C;k~2+Z1Ig zWYZYAI!55fbsiahrUp(z6WrzEc0nCL2M6vBl;uw*4L4sLVMrJ3knHNuU<8FNXY8y6wvZR*K*TD@lA%vEC0MA^EMDH%HxMCBEcm7x zk_-r{Eztl&MZZ)7k=fg-OQ`6Qnj$h9q`HU<{i!Yy(6KFC5y6Cddc*RSXD^OI+-8;+ zqB>b7QGn`T(x~dO%K?}i2SV`ZAl2o9Pkf+2NF&Oz9gKduFOx=D%&1#9*7lo*K?p-> z#rlJHj;i1sFV9F#EK!p%A25_P+IY=Ioi+vJR%saST2c#fU4&(Eo`&9-VT;h)EY_Iv z*OO2~ZkpC>sFSU6^0yo4YE&_bCvng|u|*r;a7BfMjd3nkD@YoYfl-N1F#<|El?)UD zAx$q_9pzrt$q{Y5GDe6|gxRj}whjnwOcfCj3ZAn_e^XbRn{f2f(;K$lG-v?WCLq~S zAd*Z@g!!%x0yRRU5hp(GhzPc_Ghf$%pw2+e{Wg7OoYY|$@9Th2(t5U{qf1HnSW}Nu zC9#8?TwV(MHvU?Ldz>t2B3H_)IOAp<5}Bk0fTQ17O-`x_h08A=!?S(iTb4<>@CjmE zJh8P9iKNZa+Q}=ntIH#j-)lg^EM>wB3i_70ddxyb^miUY_R(B|s7ZwfAc?VzWs>pC z&nx9&WT1XKFTLoQ)K7l3qtc- zA@aujoQt6`Kbp}n<~MzkD3LA|PEt0o)JJhgSiaM%Vn$2~%s376n-~6)R8>Vf7_nMR(p8YUv;I6*Z4~p`P|FUk%$m%5=$da}tBI$FjaKihn3oL7FqV zqQkTjRUnWqQ>F{0e3|Tb89fCDwb_5tv01)Uez&;6TsBoXG&|HSr{4~33#~64O0~^c zRkTC6IBV;cvDT&@PPLX*m5$Bw$J_fXQQu1%sV?%;ol~z=Q)k+ST z8{m8_Cz%Wayf#BzEKZ>v^kUOJqoR9fXci$#TuociMu-JX*IC`i{KlQ6SGPw zTv~*yM3g-7bv0yyXcjJoNwlhBl<%?*Vo~HXpOE`{%5j#H@@jW-u3)8O*eo}qMu<$- zp|I-hDE%i_`Pg&Td@f@utiROpmztU_!*+j|q zQrsh-zezNhUM0u)v!)-&Ju|(=1yGj@@j|@Ko>0K_L{f&)-(YPA3TD|6qy*Zl7N~=I z)O?FgDbIg|DEtVPXNYU=e#I5%xX7F?$firqZ7->oTe7z7vuy)*gvwPyP87K-W?fGF z^w6RgYUjzf!!XFKPLv`$I+3e9;Lpj2?J=~jpOy09-o~2l9=j2LV3XU~JqfxQ zhgL7y%;a?tLnCFVv@Fn`#+1$XORss^;X16cv>Y0KZ&MVOM-^lcTm&RLOIeZ!jNo|Uwb0R z3~aK@jO~Y(Vw4lRF+IEZ+wcYt)@Mbsv`wB(6qF}!bq?q9Ll3r??E}O-lF};V%rOPKtpI z;u_iE7*TfG>}$|bIIzYy1ni8OPd!vP`Q{T@mOohpQ?{QC8%&I9)oyV_&u>e)TJzmb zZpD-d;Re8#T|YMfGN^&#K}U>E^QfaYA(Dq9^?Yl-TP<;I2Pk(lBZ+JHb1E=x4~(`7v+u-u8H~Pnr3{`!#tS<^U4% z`|7p-AZ;SgQ25sSr3dA`4f0{JRUGE`*SfOw0N$`wB^>aEusnr*5xil`BAm_h z%H9yF+zi948x%S%fxd6u(vV)l8*57wR(Qi!Oo8#AfT|%)hqorG^d18&UKB3>t6M$) z$N(+V(fMzjmLz3>wrSY>H_gb}GNkI%lgni3*?ntlEx*iwjn%LY*;JVwho7_XFH2P! zcf9G+x@0=A9kL$2fuCWjt|aj-U)B^2CkNIf)!HHbOOG|3tHFA+CeM)}Uc;<#ZK+Wg z(fAg2d6a!9pG0YPC~wN8D&Lem9qOCA@DI=6t$pH|o}tSILtLH{3lcw!oZIEu^4ISw zL6$f?IiydB<(koRe+@Nvm**3sa0%~nuJ~P(kc`wV{;(q@gZ76-s~n|0bWokDdF zjQ4)EO1+jNZAdjofiWuGT6GFHox))hAX5U0vZ_RI!_!rtVD9%!&u~J|gTC&g1MZZF zHXG_Z5%1-FyfvlR^EP8PC+!o=*qG~4iGh>P6Bv6y2b)X zMJmhmZa0sR`k61k%F{AkPp0p_p9R5(yIs8f9PN{Ioy$i#QjyoCce2@L!8DUxjvLQ` zSi{wh_wWnSYL54G0Q#t&)M+YSg-9%Q@XE5_H)@ zHV^h$*WyRhM&VEKd@q!|wW6h?D5DV9z@EwKbb>sjs|@%R-Rb6;Jxw*IGrsu1rC+8e zE%tp;)gQy|*$%J3E6&jOB$@6|6th7r%{zU0OuN?XVmaK*m`$iXsU?$?IDWT-Xh#o> zW=-}i=d;53G25{vLw(ha@h7ZiW4?JctS+GEq!!x7%XE&+_H;SM8Qnkou#J}ddeUgU zzr4G;L#ledQ5XoH+N^fQM|%9Qi*W~oXqyPp>bXStpA>CB|clPsMf65Ba*LIejd8#$!ZZ+~6LdM8Fa5Ux-Uqr+2s+&z{EJpAY} zo_`9L@p_5~(0M<7!y*t7iVc9|R_9PLTgyPr&OMYr?c5t6oj5QK(NR=Dzs6?=;A}_O z(D-KjmXhv^1tzU}Y$OFAcnr0nfoYA7!bFC0KJlJw6@a}CrdJ95VL$K}{Vx}SO<;8w zuU!a!8Ds~?1?s`dL9MM+yHlI7K}MlF0c!-J-#`no`PmJFb(4(kv4Q**Mr{rb6zk%| zSY@<-S>N?IJWvKMFT35250pYS`mN6af>P*N&uKGL|Din8A%eUha9grAUhIz%l(C0m zl-wUAsKn&*C_xpHVtBus!vyyD^f`=0Z#wNR+(9)9H`{a*Js|WoOxGcWdG|QCP}MM( zM+$0j$Z%fb8?}SSQ_EO6c8byFyiIHtDL9P1+p^` zLeQLOB@Lc+Ttbatw+(8m0o6Lt$~w-!HBdc;zd6Nd8vs{>)K3VU zGlW(_aHbiqm&vm(5H4FBFW{tJRK&Ys1!Sf$6NRnP<;j@Mb|7>obpwPpo@YsTmpWEH zVu`@Q@hgkwy}1jShqa35P1)cU>EUh}7i5ON{x)wrlw|aDn05nGaNbEUO|DH@uHdg+ zP;C4Nm(3vJ#yY`VFKCr*FujTzVdj!rAm`4$AQ$1Bef%)1{#Lq0S>!T<2~e7+ZBa^y zEYJpM<`gocW6QEqEs9EKK_Nu>d|O;zU)bf-DgkPlDy6JuF*3`tA)C$ACZ$OUPRleU z6s&Syj8VA0;(yQ+bqCwM@@ZQWd7HinL2oLWQaok?l?Dx8U3o z1GCK-dRIbc=^*0nEJ-Nxpf``tGT4@5skExyV5+EUGn&e(S`Md*s#fEvtghvNDywQc zqDt%94XLuKwqvTauH~RAt6M#)Op)y}wh9wWsn1>vyX;$`T2~*k9ByrCuhI-%>FCGF ziiKji=U6ba_G6WgSJo|c+=`Et-dORy!o?~ZEK5kc_*H2VzTVyFK^Xu0QxLqW&;tk>s97Tq^)}I>}lNtM`FbTd*z9rB;CLeEhT= zUZ+#0HK1A@CT%BwZTH~vP-#0XqLw&V+Olrh;nD)LT$~|o4OI8S$w@rt$E$|f#>eIx zik0uKng|PTUUlWXe-GZNat~iMh~`6?ZA4BCiR^fGo65z*nX~XxtZqq0X?Gg*^dc+vu5oAke08(-K<) zmu~M1!a6k%Cj{8&C;KE?A_*Y*t9zPu8a4mQg9q^jPX83qW>? z$qJB-W@-jxshX?+S?Q)`NS4Z}8IY}ZvVdf#o|*yK>L&|GmI|sFQniNaGUUFxp2{?G zQB7rG1R7iFiq!$@>hN!;!oDg$Ei`{uF8twSD<5f56r1w6itgpALNQ7pmPTb1%T)$w z6pL2GY7`5aJIdg2h)vJv{P>w~FVtkH;XxYcvNM6&nIiiF)FOJ?Y=3&2u9#~?vybP(gRUpj zci+!~;KLnmbom_ZlXN}RBZRon)FryF2S68`5D6_QXcH$?+5{tK|%OxR!64t>RL zMhg+wUcS`0hBGVqh@i4EJk@>~F7C>ao|B3!@?{l`*dH{sDSdt^41-_fCcMF5mHyvT z<%1Q8voGN}DP{XK;~18HQscB~Op72OfX@@g-D~RYt6~?}1p1UV4Xvq4XU|s@nuwPr z&M#v-gK38QKqv7KhK}HRNBmSaz6e>@rff^wmFCWIKb6FG3jL{v)++j^D0oO2U(^}f z_%2y5O2pKR)G4XSqj4sil%}t(9G5qxO$d%vu@qYz=on0O3%I@0b+mkSA1!zC72eWkyS~Q0whQ)CrVhJGII8l0!uc9MQlQ$3Ay!{CL4(Y1F@C2vA3XwpF1;v-01r)`&JR8EX0sT zQ3rCUMe}V;H$D+_cT+};Iu6yMVboCou-~T7eL+!XHMYMX-AM`|)44_2ELcejVyE&6 zoh)cQSg*E=OSFu~JV>-if>;e&fae26TA}SKWWk$u#xz)vXa+aB6=vG7sFMql zXj4P;OIuW{3Y)N~YQ{uZRM0{moR_W&g0MiO;vDRBw<>O>l=QF%JNSAHD->EJgdGO0 zf)xVT*bckL@P3=F_tTc*rB}_|loq|BMNYIssa0%=Fx`kYiWnvfDhmM{7IkElLYWBw zt9I7f8!S<$DmK9-&{jOLC$;~gOeDT&LoN2*NN6n`CO>Z_J=os57dg8WSh^h2}+0>;y>V2|YYFoONs-!Bc#D1`5 zfg)Nub-7KpX$0*iH_#Gy(fm^w9iF%`$4-aR{*mf3E!wuS3XEwOB+?SEN4D5BjBMr{ zG^4C)xO4?imN~h1rZ_t*Br5K~rUBG5I)-Ue69B!X1d}}?-okzqM*HwCen{4hNUXIA zd>k6^c)f53Itw^yVu>}i_8?pJAvYb}M+f+!qRoc5AiVT85>Od%Wl?!VE!xHuCK89j zo42EG=1U%XD&R*h2Sgg9MQcVh;K{Vvix?W!c_3{GAzPK?3^Qay_FJ}v$jE_c%U2eI z2Q%Jsna;_U$Bcn@)&k3hm*&wArgi~R7NXM)?c(bXe-J(1m0b7a;~GK)7=`&7FY80%#hWzC2A?dN$C*Se8a#Ukz2bcb6ctAIozkw_#G znTh!#8jSjJwr1x$QR&pF=ytM!|!>y%fvS6l+_F|F`Iqbns zB77RpLd-a*jgxtd>>*u#1b0ty)cO~Ee`gDjwH5pgSm+=5U~#qs5NZ%m(Q>G6KsZ$m zMyHeiHp9YQdt55k&Pw&%^>XE_$+oUPn?D75Tc;I!x&hgTRr?@7J(U4#ui5Taz>F>c zdRyYn)ftA1xlhUi^7u;TV9lCUnoLN5T((Ft)Q>srqxuQ$Ee#;UG;~Y1QZC6rb*ih; zO1GNA_{CAYSiwCoF~6#ytc0=%<~k@RtCvLCM^>Y5y!FxxhtjXy+EPT{D)mxWdj1qn zruirWx3`#u>hHyJIl76~A{*`0BnO;;= zgG)haUa2vCWqxLuj}q%Pemz}be=&z2=hpJZVy8p`7R3#)o!4K9LLY86!W!_F7RZir zrLIfC`cSgiMqvH*ox*H0EnYu_%U~UjSL}!V&K_;)_^GM1wex<-%{}u=ZXtqSbR!*3 zMN?9wfU1-qU69z^yezA=qF|2J+D(K=oNtc>Ni@FW&dQIbITv@M4UTO|WxctUKWHP9 z=b)bs1ZuR;Rovj3?Q_a~?$CqnpJS)o?nd{~^oJj?TYn?_c7El4{f$ZRtnbo$`Qk{v z{rKVtUv*K%)Nk>SLWf@8YDFi2k%HufqV8F?6FlJRD*g4>I4f=4!-%-e}7<>1icltszk+=^0paFptY z#x>8z%tafHAHye@pkQznx79)o-*@q_SZiFE7x;X@t^xL6j%xjD`95QEP1dmS&bR5o;;+UvQhj9tx1ob1_Y zbFi~X;`cLNJLZ}H9+0wU@+RTTevsOh?S4P4W)tS01z1_|j~h4ano8z~`L3`#(1@kd z_WOj(r0H*VFQ*L9d*w%Ev{3uBq7(Iov>h~cZT(^Q-6bym2&y#4=_A7A)1CrKHAjAXG}J9EZTAq|R{&RLUwH z2f?MB)^P|_%Bmd)!KI|$aR^+B6^}ivGrx27W6#=$OGUG9J;$}Q=PqqXOA`e5(-otC zkQMX~r5B!UX&*J7t{g_~tvgD8NC@Lk=*DW#6DpZRX|J2112&aT+_c|*B~m`^wW&<9 zsJ*t9N;9?Bwvq{|_S%$l#1s#*Jx{PyQmno9%(ewboP!+Y6eZ%?YcGqhKucOs8afC} zW(?bF&x$T$+e^Q^#AbW#)S=pu;KxNcy+;t%L*z17?6q??uiCyfY}?SD#g(7PZQp(J z+uC!tyzFuN?v>ZnzB?sOm$HcMy;H8KJ$K5>gmQBM&mVrEiSXOm_fRr>ZF3zB|M;Fmc%j zacfKFVBG8UF1(HNAX}57%!@kYZ@)dasSmxJjR)zqD8V{qB{IXs-EA`8hGj%OV9kt7o7K`SG;Z{1S`8F5Re z62SI8^bfFBAlm6xZ6qc8tIa)YB6s)8HR-IihiNsF(36oY2cWgf&AE;FjJWzPkwQMT z1K^dDY$^Qs&-OlYrBrF4 zOtzH50m`2fP2@`{Y_g;n*fC>D<>nJS*+|Zm$|yLl#0JG^K?f4T-ym;Fc_wcnb4uZ8 z6s!vjRua8XR=TB({sfIJC)Iw@+IaKOk zgJkH>^mmrG8rtId0TMz$8Mc zbN0Gpli#-ERl=f^zOUKrD}{u}w_&(t55|lJ@~@Phtj%O#X{5I$gQ5>Y`G&HvG((qW z@~||5OUbzCgN#vAxmX$@Ov%XTgAk@{X!K!_DHj`k5M0UzM;`{6lF`uzL8dr7x>WL% z^2<$)(CD(j_rF1{9Hv?*S~eTtswg5`gXarz*jW>)5Eol^43Em`BZuj9NrmJ<$TXCv zr4e?3delg!mPU{%sgoRLn93?8hry<#R&p3*%Bm#?!ls;Fau{UFDkcZQrle+a7;K7F zlfA4z&p<(O#)PEq2&E%+_j95A-K?Luyebu(taol}@7=1KALI`eIh!A3|BO+0wEmD9 zyw%;^5mzUtOU=1lFV)KLp|QG|UF!C&R&JM?jn&TXQnS69`CV$ZRxiU#&BmPDXvG{a zHQTe9R}OL{XIrZgv{$o(yJmW+*=+q>FEtyim+hryV|DYr)NHOsCYJBMrCqbW)a;;5 z$FhI*%Qm%lwcO9gvj2Yht?j*QUQ(9*_snZ-{~dFQSq{)K*Vx`W<|So0+$!faT0Q)_ zrYNbM3#Mj!l@o?k&lhqi%nmk2m1*{E{c9?tTO%h-%`vW;g5@CkbXBA(=Y^?Bth$+D zYBpCdH%!gO8p{q-v;Bth!_;iu2bCT4ri9CHw?s^*R<>kqYmpEj;uC*2S4Z_oJWY0^HwkK!Qu z8ZW|NFX@o#}EO1E8iCZk%?RE!uxQ+V3GG2_P_m_R_Dcb#qaG~!9z3g}4zuw2~ zp{)#{Rsw7gr`v`B`Ei6Lb&!71ekr1JJ{wKr?#-v$pxwT{Ln66#7>{PtZp*z**X*3k z7tvsZtN`J35Ul1f6-2>Z822A?;M}EapQ#Gnkv>RIpP#q8SEHBsU-MYE`{}k5Tn_Yu z9L{rk!T?knfJnWkpD(X&W1@BY`Qmf86(F%!JdZ(7ymQ~DbM>PYKh2}r-T$`kp5kb> z7(@$s5=>W;_qWvd@dqBx}Gr1fe3 zbg}yS4qt=!izwpzR)0L3M*f?(d?2s9;&FKIm1z;jhj978ku?pz^P9iE`(Gqzz=h9o zw3tSNR)02`hjk*9AdQ==mv~S;DUg~lfu9X$#6FswZ=XKyx}SS##$cAN_8>n*~xa zCx-y3okN4QYvsJK6)WYakb!-1Bp;Oe*;UMh!QJ$4OlHUQLf46Y15frL^YcM;##pU3 zygwKDw}`sP9SI<2BBYknGbQm@D8HGLAs0=&hP@2T#$N>mIilTOpG6BwFgeV|5{4|8 zw*~05JMj!#9clzvsz88I%YTsHaJ!8%SQkv4KI@p@MOC8TY!NoYaqu4H*E)`7!>&Gk zPmkw0SSa9o;;g^7g16|(XQ&uf#ZgiL3-#S>Hb$zU=`s$d@f+l8SuLYr5h=m{=fB{( z(O`gHK*STzR}lLA_}V_hw;@-Svy-n}3eXg!cRxgREZ%cyEXyU~#?Y52zn>)xrY>FPg4flRI!I{x0L$ zBQ%T29Y0&YE!iU0bS{LgC9c32w6L_tGyO4EzgGBsTE;*Tb>kVJ;0r%nTo#Yy52)4} zj|ZbQnhv_ec{~nLP@V~%8rawZ9edSR)1`F#h;Rgjq52rhJaLlw7)^A)eg)&)#>Z$N zYK8sT657dVidI7Pr_<_3qj76U1TcuRMQb=gpN0#pxUKO({?6{(FI#vzYz<~BP{)in zJ_+$b{RN%*V=N8e8Jc;(Gk)M1+QT#c<#^y@-0I(fqWm+Izj%Pz%D&kzc%dJSThU@T z0lvzENt@p%ZFw|lqlbghME(rrFCI)n{*RxyxtV{y${+dt zl@CBB{^5hsbliG)nuGh~?@)b=Tch#p{!aac2E`v3srzsO(CTBTKk;~s4F-prA9yUE z@_4oaFX1;oDo-&l`2-*G2A|+u%&NQb)O>6m7=bkdBp{EbGklK2 zdu#=Q*?17lhQnpV&f^O@7xY&PNV@TAg7WJ)~zCAnPH_(H7 zkN#SHe}t1|Als_|q9KAv4`iEQe+i^u9u7`h!D`^&4YA~B@Pd__vj2YwME zN{p7X{_EGl@DXePW{}aq+61w?P+}M&7PT;LqbVdMKIOr(CD2&X!dPk;E8I@Rme#|^ zxteSNw)Y@0ir!-xpUv@QZNA_MNunOGVcsJ z>+CCC>#>i%U}?ZofxVS{Oy=@2gXrheIW~~^Sk9;X9LA$b#4n@_KBl_Xw6Cg7b$Nlx zg=eWNa+Sib7}HZezNimrBc5T+!qczA1sAP&27D&bL_qSBDBzR2mV8nCr8{Xmvg|)_ zo4cIfEd)3gS@|uyUxHCTu?A~QR0r8OCpG4xs1foF`(P~m)GxfB>DRL9^xiA3B_Qsv z;?|1Od#K^q9|Fbx5*YTEh9JK^4BT&xf_tEGa1T5X4hv=c2%wK>okz)-kKTis+Ab@_ z{WMjyeVnMtL|x%vfPFgkKJ#5`hg<5lU!npuI?y*#we=5Hhi40REFM-sJk>T&Z7{b` z6_R00efZB)3?K^rrKP`c)MWp$1ypzowbbo@x0k+V;eRDaQLZI(zN_}yC3@Lk-zk;4 zMA^#RRwOV87)aw@JBQ^AK1igSC z@^G{a$26hwbN&$Gvp18Ku%xo)6e zL<8%H{Dl5O5x0n@A%v_2sUQLX7dU*Z)k3EmT&macWX{zX=<09$1e}&EMO=yWLbNuY zir!d!4eINm0_7g4-|OYnE@F0NQLiAZu?<;b#^D?0BEF1}K~N7ozNnFZR3n5}h6hw} z7B<}QXxQP=@Pk^kSjKR~qhX0hGxU#^DKskB8n1q zgf?*xWeAHzw7>=xe>r70y>CI60&~Q{h}*2I*RaE0etLV;ecw9|wEVV@Oo4aZOab+X z1v;4W(jc}t!Ezq;p_v3wV^`zIf`rUd#uUUS7Zv8tj7I{P7_&(r+zUYR$<68`uIYyD z8x6K!0>OXe;G~}kQaBeOQoX0k2`#R{#bEGJaJq?xVzMcI?b^s8%smV5bQ0g;ZGCrJwI9D{dhzqQToIn8T+RKV2$v7)*;x2*Pa-4y^i<+4M7JYOmcE z%aB?3U0bdUtP(f}8b~?VJ4Tu{U=`<~gBo9Q5n7mIz}`L?s|lET6k84g-{ia|Zs*{J z&;Q-)x}y34U$#5FCt?b75w3*si@2xKK~1P%qs3_W^j1)o9-2u3o)Ha?OqDLg9Xk4g zPGToC>dR>l+XiOR$}i#aeH6y4MT%e(Sdmf%u&78u;&iMh)>|wWadayOd!NI*i|ODJ zlu^HzX8bl5(!_%Vfw%~;e`-Zj?27OMf{{mt`s_z22Ez+G$u{0U z7S5R{0VCvU|2&@Eh2um|^&=@snR9uYWV96fyArI?!EuD8qwv#DYB!c>LUEdTBlR@7 zevV@O_!AcLbbpg?rJm*%86s&ffAo^Cq;F?n!_^$i$Zhv?aQV6W(Y7|GvYLLY>ZsoF zj1N2NPdFi#|7=ZE%>Ek@T)JXwxQ6WxlWPb&)fflct??A*Jx%~k3M>pGaAR;ULnLxR zHuZ-0i{1-aUa9s>nV7;rpwTRlhLC)#89WZ!(q&EH+bI53Oc2T8?-^M3eO?z-1By3` z5peGXh8DiPr!EeTG4h{h^T})(TjO)@IKYvjp=&`QA%-R>thIU%cMJQCRChB9=UZ~b zCES}VDP+*{q4#vHB=}pb&Z%LyxOhdReN94J7oE9?;{_yu4>|-&3PbhU$VxrCXcr$ zgS+1;Ps^pqjGX2-l$O3|q1%^b?fnAMjWR?HA+^Mpfz^QWir~5d|hO zdJZ+8qfdiM56bz#pea~jCU}!$sieI-lpGT9T9Og=cI1U)xg7spewifqG?&x zP;^@!MfIhY{YI_Z$D;T2j*c;4`b(U@6itm(83BM5XO4wdUm!^FqBZ(ak9v@!GB`QE zAWY_u0Z$OfxKN2$iU*e>ZVfP9JN;bhV1l#G-DpYW&O>3@>*%%Jp&^T(XajIFDXiF< zsGZ8OUQm^$;pVj+#<87XlwqYhwn)oNQ_W1Ds!MV4)10$6g#CW2UoKh?Aw;F zv_L2>31<{;KA;$4`N4jOB*F!SN-vOC7M92Ls$sPa65}+SXyYfirC@KQzABS7hDgiP z91MKG#dx;n@JoR>U3@^Cndb+mT#=!Q1_}QiRMKmOr+u z%&*|-8Mgl8alj*8N>@%p+w0zYj3WN^Xb_y>|1MSyerlw9PX!QKYaZI$rNZkQ+pzEf z$pK3h5=`|BDQqYB@@Rq8MixL?Q~n>}knMii`tr!BgU{$`3D>qryCCA^97eP03WpR< zlk<=k9ZWmzLpW$*;|eGS%Q8=*o=-KL$n)U;J*)@x)}lF{%$0h~8YjhSNbr`HKI$Z+ zyHy-vv6xwliq#{WK9W})?NS8BazH1Yx6J{ZTilWK2OHyMV#zWJhsAwE4FRoJE~Oe; ztxkh3TA(+SCQ#aNNx94A?dpzeTT;<=ENBY|QMGP4nogqy>J#&yN9$;s#;RjkFu~8; z>tUM>+Y<2Mk+}MXvpF!AR`EBqxtS8VXi60!ho7Wsev}Y?S zDk)1lf+c_+=Dc#PyO%AxB0}P*v(P)O_R7$F1{Jt1l-9I91*H;audwi}a5pb>T+YgY zZOV;WZaJL2!+J&ST0rWtg!K%DLe3~C6|qr-l275<08g9XpV49lk#LV|zSJ_OnFw30KycGdPSyDn zjN!26qmzKtqe)af=qZ~|whTb?;W}84qDT7!m3Snp-UuxFi%uKn4ZKI8FKQ_f;G9{> zi{My)<594N0R>Q5lXMaAyMBd}YeYMl=HlQ)zqxv8z5pCpQI90ObkMD(B9XOZB_Feb zTkW*-tr~v6ZXb)4aG`b3O_zaF!T`>|I7O$8NxaT*5VDxSr%BEz##lYcC_J%l4RE;8 zg6*1NTW~0a+sp%oQ!M(+mV5*(LEJ1`8r*0h8IV6O=&C&K;ZGL1WT6(EJCt()spGl; zG8|fj-Gta7 z{|#fnH^D!L|WTBZipJ+M+yQE40-9tl2xOhBN@&E=<`UG>Z>se#>(s$mw>Yz6a% z<+&K*aPaM?gjm#%1mH1B&~Th8#W)S`Ig6fwROE{JFo5&G09M{8IDd%7IKf^bb}0HX z43jYXnY&RBdV8L0`)RaCgDREz_UCKzCcHGP5idP zDc@p>RR~A(U)^(k>H!0Wdj{9pdz|{JMsRwJZMbO=3lS`Mbga}Embn+hl_S_Yy;-@Tt ztqRVYfDt@b^z-Ay&-oKdk;*hMum(Tj);gn&!FCtRO+pAGknY|r`<6wL$^n@gO_H7c z(&S6CZxe|NNP^_$RJLcVHnw_mUI}=Pf$|`{e8Psx&!IR)^P3U%aC3l-1ffl19Mhv! zI!$$Oq)gM2c+Osq5V$nzcHed2y%j%0=4YE{FEgG-HCuJIr+Z_|%K#$ul&dL1W zu2oy1bAm190MlrO+REt$7F1Tgyt->6gmn!VMMd85Xa^x4h8h;?aXYWd08WH(f(}>l z43yH)KO^R6OW`*vg5brGZ4SfO4&Ft-t&~6XrH&*OQp+fx4)`+pJYbLtq6aXDFsF|Y zf*?in!{~YlO!eac+cq@m3|2yhHQIo=OR!K*@hyRXtdWWYYzI9^SQD01+zurJ_m*^q zRFQR{M`7^_(SQJ!?p!(=Pz?p{sNh8)kbQFiE znBOqaREyEZ=-r+MdY*!*pjFPEz@%T_4B?_c_Qs(HLmY5IwBWF7w(0m~FC^c1)V8i6SYKGWfp-tW0hnZ@r16*dXh;8aZPj_Mot}k zBWuBdxGEqB!;jpRiZic*W_~GVtqhPp-vc=IV%MOtQ$Je&@>#GRa6S8dCap67SeZUo z;ZV*K$(}%64rIn;Wmph}#W7D}t>i=IhI4V2UoN{h+}D>atAbNE!F4OjL@y7UN+*^F z9VEUHZ9lhiqDv-RlL}BhUQptQnVw|nQ6rDT3$+MiCnKWqQsvP|rlw#-ZV&%=-*&iS zolv~-&>OfUSMj{coMx!%$@+qoF0XQO2|wPlw3dRfZB@?)k{HPwc>MHuSgC1{zjEgT zaw7~%s@V9#wLc$11$6-M?WE9g{%Li9`^+DH@Dh<|%|J(Uq__hick^(xxNItwNcRQ{ zMvsezVy#zTtt?wL-fCL(7mh&VEhicJddpSd}FV1fhqT^-FE3rO)p;@$+sV092J*KW_7~F8fvGIPz`eh zQ*t%W$Q7r!c^Z0-)-8FQlIxGss!zG>7_B-3UR}E9t0cXAETI=u>>9neE+DRHRCJGn ztfHF(6BJJi+8oIAv@l7n6 zC`ooH!Js*0N$k;!*)!7`H-||}ec7SNWh`I%W{ky#b(1gr{$>PrYTi{^L$GpF*-}e( z)eTX5V{S#WfFyCR+Q#PmjhJ4EL6yGmOM7&3YU4^)UBy1xOh+X{vXAX%Vk3Yc$ z!ZKxV!qZq?Kd+=f(vH!$;V`;UIdY0n$P{7yV>nrok%qx3{1)a?fhdnr;h_28IJM2ltTlPNYn8F z!w)CIOO;a^N2>Ub-)Z3OA-^4o(u3bTj1RZW^SsAK;ryT*wT(2;8wFAygH)kd&aS*1 z&FFn!VPvYdW69*TQ$(jquob1oDNR*l#H>xm_po25* z8e4hkI}w>zch%Dqre>?U_8Q(_bVs^6gBzbgBZ%AI<2OCw+hguWG5=Q?_>^60i--Z#^+y8X%^K*>HW0pe;P%aigCaKGyT z#cYQc1ehJi)3unr-67j3|INA_W7q!Ltm9*0*~U4Q+DA}c@V!s1sShov_As!|@PWr| z06d!ih^+kPHU9-)|E}eHfUZvm^ zoa%1X3znRTOo&^DR^V~Po)BN~=cy;YPO#cz@+yz-x&jQHXrOga;R;C^Yl1q{x6Rb; zLw(t6THXo&&P(l}Ul;$nV_+L5`X-^34TEQHf=@H}$=fvw?ews7%$8vN^SZ;==}<}0 zBoI@{!8OPn6l6r}Y6hJXrrlUhX0!OA?x0$#!)#T1fIU1kjCBCNx)DNkZP?rznHLum z+(r;G%M|8eZR6dUjeTjN)9APVuQm-FR+a=k`;9R=_QyZ%w;TISU7qE|q^#kB&Iq3e zNKg9n*Ju1=?6Pz`zs@Ce@Zh%`6r@XaS>PBu6|5=BbhvA$>WxX2R!J>{X!>o(QO~I;&stTPs$d|3tikH}@ zfJbz4CykP@ii`5)?k3fxoDzba4l34gI9{y$dG<4I*O=P?w*1$Eh&BReN_@iYYwL)H z%3>(4jDXUaJTjobSF{WdHUslZ<&emA?ZWU>F=Doe0Men<8N7Nb?L;vcU4TGNG@Y!< zf|SD_ZS4LnL-T{d67h??FUHCn6F^w1R*P3@h*6L?T(rWkNCm?*$xEg}XNEK_aE2j* zXUW#OU;lV})xAJY-|oj>FS~!wkI*-WB+IrQcq@mA#SQzoM`$VGbb1m)iw=;Wu*D); zyh+MEdVk->ol`^xYnf*t}2z=manqa=Eh|2X`2fcuy)a zF`0y)OM)-{`ZZjr(>@!SE{VZNaj0>s5hHXZ4o-$HHDg)X%UX=5*t1=)-gzhg>Vl zH3x^410`*B-Oy8j!P5ekRMId>D+x4ZxOrB9YuX& z&CQn-A|A(DWW0U4UU>J81(L|2d*!8eSA1Gjj<8H3Zgu1bTc8|hyMuAtA+Cg}LYgh0 z0Xwm_MhrAF|JZjxoUy71lhudWNEf2{(10UoD0A)8UztEI;w|FBc-+oszO*IQqqo0#u)J6b9qK_JIXdsu-#iMYm>W zs~O{4k%Id<66ho04Z!ZCgkH=sk>w;TCSsE9v^f zEUq$^;CNnT#Wv0{G13Xsp}c{y`bg~Dl+-;nMCvN*^siZIvD z=85bL@PN#`fwbnme4@P^+XY)`;@GIf*9#_O{QClbZX|6Pl|IWTPR;KVl7Kr6qi6uGOO{ zuFXl64(=k}$tTy=1q0|sxI}K6479I|G%uX8NHdT>i8wliJH8OvZ%@4vg;Pk^8ir!J z)f-m8yKu*Ha-`;ke^w?CGIWDL*q1Or;8Go_NVLEI7^CuqYweesha%>ZT#$>rNDXg>~dXXndZjlPS*ZFHD&s zX)_!i=yJNboT{o?y6TCmiW~)540D=$HPd~|G(y)e(;Z7w1vWo;DHHlohaI(>RyrW7 z7`8=iBbQbM>-ui^qAmoT;AMM~B-5m>P$nZxhAMW<%8gL6$$dF3LV&68V1-ok%_wiT zR5L{mco~`%yAXmr0LrLY96HJYJCx0Wgc+JWbgS*{>8n(;C`f%Q;jp?hFv*RiH>V6_ zI@8<8M9Qcn(O#A%8VcqSEkU(2Q0+{pb_41mT1Qh(l$q3=)`PZV`;>NUvE4zExG^r} zKz6nMmrISt4c-w2+)eMjb!2Xc;_!D-`qh5BNQWQXl_Cn6y8grTbN$JiBT&nDl#7Ma zD9D#gRdD+XWKzV)z-gQ!$loKjXy|cF4QbMz1@Kg#AoL)D3QvnT-@!Jma-+cr4Abd)1xO;hwwlM)VtvJEp4h^b6V%O;fW3K<9{?OP$bKj+K>Zv+$sr1hhTY? zL(eqncAVMd*{-78Pr>a)fa^&!gRb^@-#htK5@sF_3GsLfMz${ja`~lruK@z4Xec=! zkO9JSp+AL!@OQwD&2l%6q-1}KV=2Yh42wyQ4e!|v;OIY{A-`=j$Ei3n+bNx@p%n}+ zhI$cG+p0RX4aQdu(!RtCSr0m)O1X<_)h&x5;y2V;k}JvV{|hR3!6O5UND)RN>YF9vKuT5j{8BH^XqK{3u%_mu1G^G z@=HwikeCf@1uJ4;ceIe=6;{$^t#&u1nu%w?Ste_zKeiokreFf0t>s zDVyt3?GKfovNTex+yR!Sj#=n8@a*&Uv8-=&6?2rEr(0;;{LbW=nFlImwpiRV8j7|q z`PhSvU~pMP+E*|P+Lwa?oQ>nx(Nt$xxctX*aSV>810@0r?ndz=F4Z!1Sm^RIHs_~^ zI9TD{5h8G+oRdx9kV|xGY9R(7Xj`HxgnmQ}gKko87kP1{5fuxleFv{)nO;T6XsAE_ z@Pi zU1X?k%rR#>%K7OnTy5`h7a_!sIM~o?sg6X{f8_!q(jH)Dg3apEKy_th&iFIoY-|In$+R&b5~IVErc zW1EC^mF^O~4+C6N0~07_1)!)Xey@<}T0$OrvxDMysi-DRKz4YwJJQBBS(Z0CNCjlD z5-Y7w?jY8F_-T9}zNFligaju$tl!&$>#npVqNssy#Y_`xm|rR>|aTCC!hx0fzETen*c z?G*$EAb?(5O_PNJ30d1J3#25$PRjBK3g(>pyJa2c*4%1dQ0;(n%1NX%KWqIc*R&68ksqHKmi_)|2~5&e_pl#N!^SeIZIn*d~YJ5AM+pd?tB&{pIyg9F$_B2A1qU7-}!#sHCm6q@1s)4OO(&8B6L; z`cTa_o79NvqG0u&opqv`7<@~us1W7vQZFiPzOA#il?7f;H!2Igk~k_2bg%kRArIvr z=6(knQhB=7(6Gw_{~hzu{xqfLc}2MNGIb&?0Y}}tn-54x58Wmc#_^f#-d8{v=Eo0= z6j|`Ef6AE~4lCzcxyL$gjP#KZ^6l-8146VAUYL3_Ph8|}s>4RDv zbzbtI1qjKZoYKG91d?78raKM>!l{FKJKkj_ZtjJ64|Z%#?wQj zY&ChvHw0@-esCVv8jt68sfc5U8+8<~+@#yJqmHfIQh>G{Y$yrgH*IgV=)A&N>Of-l z5IBgyy89_2>*Ox?RXoE{366o~aCgEm*usML;2()QA~8HD%v?LiI+YL8t|1CAz(Mt5 zIG#Q7?05~}56HG6H@zp`y5nO*X$!G^Vz5QXBOFPPGd%ggjgGC;!DSKIPN@1g9G0#U znZiQuU^Lag_W5#xct&;H{1AqmR*~KYwav%BN_E@JM7v zcAeP7Vp{)YKzbb>%Tb>-D78f8b6K{Q-~5(kP1`=VaV}gC%xPYB$)lS=hAm!4biiR? z7q0=TImINq1Slzssz%i^QL=@tJ#dt~UG)DkUoe(62XC+@*ccZ^PnoK8xzs6Gaqq>f z+=WJ<&nNhwyjFDs)PhSD{#)OC4sJeR&A=asfZ|qMNYj>(c5D4DR}MMFqQx{E|L}uF z&9b^(>~kp6etBWZQ0hvjd=^Z8<9K@lG=cOYjzL*=yb4GD%#T-c9S;rQJ$_Jz6e z)6oq48NN+RM65?8QB5Rm*vR{IS-UV86ioQ`X=-#D925}*)_3vpAJcfb=$u-~Ncpmw zK+KRAke*B(HyT&UwRWUbqQZ@ANh(=xRo)hMs_Q+dz5Ljgb6l<3g6Oi9oP4mo(O#Nl zdUXVsmd~{b>#_Ep`wj-ZrlR>SLXv|BDd^2IR&%{NVcK=IKfR$NDGdp)MMnG-A~O*k zWm_y#atJwplqPs9NgDKzE|cXOOzm=bI%krmOL|_s$G7HfMVQ7;^OPUC$g$l~Vny+d>TiChk(u8wDjl!f`D~ZZ=1UUfa*&}i zBg;iKYpEhu>{TLnw#9P=F3vQm=RmsMxK6{0-+yY|0(1{q z;jsr>w$ja&9DJ*)ZDA4>bKp&|nyZr!ZZ6?6FS@N~mo5{FyNk!cN=zsIrmkE6Q zZV5?)kxt#57Yh5`;;k7VHz26?(vagRQ=R~2OHxCEB2<`Sv^29yCIYPn%hI;Z#iT5T z<+X{@C5>9x3Etsa+r{ijF5i$m{WyNcWlVgwbt0E0jXR3=_YK%2ebyO%b&H#)Zh3kg zSZZtLe`Scd55oCtqR7?`z@wF>_}D2F6Gxm zw_h=ezgiY$2==qB_S1$=M$o?Pd@?4Wlp`&ygB#qhv)7=)NQTW948g`J`#)8Vppv<8 zzOe;JSsT)6m~yD3T#Y$_lyMA;-)S~i5fUr;47=6Jm(uP_mlr!I-MgwaXVaIZ5;0|& zqFi^Ywf;>y%d|d8hjh*N`Qek-kZsCVTu{rx(h-l_D!>eVt^HjyRQBF^j)GOwQiCiIDcQr&b z$Cn*T*RIfC526yKeqzMTs4<0_8M16L`6@W?kU~v)l5BD$Rtak8vTCNTu2b7p{Td@g zBIo-MrxW6M4JYq=lNTlh8@9PN6aD5(;vmYryBTq94o|$gYkM7zJqUi&{qX+whab$L znauI+T#9^C+Ju`>A(&-O8&5F5pd)0GfAO)4oqSc*vnQ3hLsk9P{T!teExIhtjroe%9@nT4#R78K?2NG`zY(yG%Xd$S<9RJgumpE~ zr9CszGt9Bv{PFNy*UNpLW8{ZXZ)Ciwp#0L*q-ZI7EbH;8)@y*`nTvdAn0X$HTXndR z6T_N*K;NQ~^v4s&wkl3t8cCV*`XC99GUir1(+P3C?vzXlUxdHQ>aBRMQ1L~c1iGnu zisx2efe!_Z>aAkU%mVY-@rWGP6AC`KmF5oJ>H&^ zs`JPV70QoA`7J^dq5~>bHbzQs5Vpx!YI98RXV07#kq{&pAtTAcUMnSAxxCGg+3FOo z#aJsyHZ&-BO zi}a=uYIFByl(S*Pf-8s?@9;&%Lat;aK2n4+k$}E>`%ZQv5UqS-qI6an8{pHjhdnEc!zJ`Fv0aM0z zQX?+nqQu@vx&bQXZ5&A|vvGt&jrh-aVK^pK&L`D|En{yBIJ*JN!qahQ3V>+c8Xb;r zW7|^|e>9T7M$_$|=tG>`FIzlIoFh~mj4dG{6`|>&-C@I})nE#Cp?_E5mA`iy(I$ftd_#PDEgqR>;bro+re5&Esxm zSChz_sNg#4GAS*SL=(EmBcnboJm@)7ut_=;Pu`jX$<32ToozF|nZA_YH0If}t4I=L zKC6B{C%1iRswm$XOfQ6j1`{3C-3%49XwTD%YNE}tRCl)K7{84wrEKtxb|Fu)Y}-22 z>Y_9FV=GU4qRQB>qq_0vEzb%y4b)9-X6Py(0F}8=tUH( zkuR%2ekUZ{qL_XsSgI|lXV1Vf>vXn2>TY|)d|7WHwJsId9C2z(HXwB}uFeWvqr41c zM;`LpC~@HjZhSPcWw`L;I~fXlu<>q}pz9jzqc;_O1Eg|0zyX8}`QB_x_)f^EMOTGz z>)lA^FI?iNfxyK;58)pKvp!Nz9QXv|f=}m`cU6O~zY}IFulX9AUoAPO9n9()3e8ao z1FcUb(3-Qlrm^rlp}bnSHdtzMj&JHMGQ2WaZK;eF?i+VXlVj_a-qWxdR$Yrx+${4K z#Om?a$d`iyC$mQC`0I^5&@*Ab$}^ToWxciWoMF(eNh(Dkx(BMk#nSgG6Y&Y~<<)~S z^r?1ctNNQdji|*K<$C+=`wFGdj;)Q=t<_^34{NbmE}VD6=xvwsxwJAc68?_e2zR_Feb@9tzrSBo+((WU<(?D*e zg#=7ook5&1k|10x!lyuepAT`P&#$BCF&H4#GcHn^EuQ4(sVW77&_H`v1U;sKb^tI* zb*w>MfDm$59azmAOux1BK#74=BNiRjK7Ey}O-S3igm8>;G!2^RjsZqw&Qe_|gA77$ z0$fTpLh{!8Z`vcG?ygWo9e|2WQoUl*FTJWHu zWak#qVAYR;{!{#bJ6DQ@%(jYbISRPcJi-q2LaO>4-!sz%EU^+6@rPj*fav z0@37gqXZ^*45w(3u92Ki1-P5>Hq&t<5M6i;ZDZ8Og-0^B>tKa@0?ou?7w9bH3AtlS zAG_-KZ>7^1cK_MCXc(@>v8{-va$d9M2^NvL5?om-Wa;j&->(Qgb| zB+f+CQ;|B$@rY6uXSqFk?4;ges`c8C(8LjySVJo4q0WV4*+5s2hBXsYw%oxsAE;($ zi$S!=ZNRKWc@BCp;-qi@YFuIItlLJ;rvC{zdAQR$)Vxh5}gllts`!M zjd9&l;H%d zB{=BeB8ikbt6&Dv*BCb{E_2)O_14fZM-$ydQQg*Tg)x#F*7z-w>(#Cdg9zD|a!>9U zSGeRc2xhizBw4&AKile~(~?HoxS?jCzjuURv{s;5NUHGS9Guk0qx-xD`yOE}o4P7O zFuj&|q*s7R1&(`ePdvET(s^^n)Uug{&B?o%$^Ucbt_Wgn-*UHP!Q5 zu#s?5{ppyQYJ3gAz+$u8|t#LK&^j>;H!DSu@>|Ffpx&mOi2)eE=7BeXB zdNNLyA`Q;9BH=NXDp9EWwO@K=v545cc!3bkB2~8m4e9F43BQh;Y=$d*jGT^GLR854_--ZJ`n{$bT>;7DgizJ*;*|)j)3oQ*=~WY4(Dt zfi9TtHVx2eh*WJL$w$`C)7|ES-;$lnFi1cXTH4e%L%t2?!{LtL5Fc`diyQwgxez-D%Jb9}ZA=7GQZ;8!lVc`(4W!wPk%M`DAq zKh<(?ULpw?daC8zGLGC2MHtZy%zORFtD&FRYE-snvvF`Yn$Cd5Y--H`uZv#5(J@m6 znwQ=g+=QcL^a*f2&8T88cqd+$!Wn@}qOKMe;P`bgeq0))(C69gV>o^KmDaMQz~DN# z;WZ&}p|eFkMG@{tT|`A7a^4FTTC)}`{x%gI|7wQ2mj#L52dWdcjm-PjI>g=O%5=8l z3Iy%k+WNL}u`^J5B2O_wx#iApOmo=PsUgQaxjXUkGV2i5=-g%6D=W}6qujbJSaS0P zAS1g0OO!k3g5qi19%=PH3M|rPoS*0pIENYIY*gf(EtLS6*J7?}$BbG70X#3*#vPu(VC03@gxYGwnXR8JWan+ zAf!!g63MHOXI3g8MOwQk3yvt{DE>lxC>F@@UC>~bPrN#Iih+PuPhnGAt>K9sQTwyC zhHoQwz8SdynqaccB%ZE|b%a~}@+R>j0MfcMPnN*^gdyBbk|F_6@X>p}!UKXtXH@mw z2$F=6z@g{}J%PjN@*$izN|Yo-&BEurxB4r0qg>BmQHZAZ@q?hNb^mfC)4+G5SqccT zIMW+g%=Z$EbgnEY%O-g#4O0{Dl_nf|tSG0N7M%67a+I_1ccWbfj9{Xd{&Li7zqH$_ zMk$yFH$_FP1e%IwLnr80lVLvkyAd;iu>nPlI>4xhiPC$zjec82xH2~Q2Da#(+=$z3tL8@b=W5_IAN6nv`5U8!#9 zZ3(J*rQCER*T;S4{>T;(RgD;huKbfiJLWPl1@n(52+%YiU`t4E(K92qAg>`RH+ zv+3Pa95pHaT0<9~3{$je*!a65ogA%9+9yz{Dx1Dcch?#fmBf zfuK@7x5^3JyW)P&R3x01a(2HhTo)`JQ z&3Cv9w}z|nSh+!>0d^(|$aH6Wp)ZmCqKi508Vl4^jWi#o~V1WBvmY z-j%zS?fckbrqOZ*asjpaPeU|>!pQd)+>d8>2w;VYS$v&Zy{AjMJVjsNWbwpw>tBT& zX8Jt=@1PIoia4^(_S)^<(?=ly+;;$%SVAGQC1q$55TdV9-*3ahO4Lr55;$6M{JaSJ z5zMr!`Neeb7L@As+MV9hTlgO;vh;dq!Ek}`=p6^}k@(O@$ch>EOl8wY^2EhpAn)(O z{ufjmQA%mb`mdylK3$+!XZLGAnsfA2d$vbN2&{4f6LzAYbO-wrzEG_6ZWhNpU?49! z0JiyTApxNeD7<0+6g{dziQrQ?z@UsAG-S6i|8%dC6$K;)i&zNBq z&`{S~8;Yy=UG;Wg?)KXroDC9AoS5HWh z54k^{Emw=`{HN<}AaWn;b!8&6QUQ0cKLh1MT%8c6VgYQKq+4Nc9YhU*jTj$?)IffD zG?-K-jjLJ!pPg`pis5hThJzsuWmhAPL^z$!5Oe{hsQO@dbqiWxSG-d7`{DtSrn0LL zJ0o7HaMF%P)9NhiSN6N(2U*dr`!-&DnklakGXieiEH3P$-Frg);OEggnp&OoV;Eyw zwe%Nty7%ea08F$C#aSZ&!tWeEgVu04ny#f&cWF)z=~N@h#Uxtr`mjmjF0eP&$ki#J)1*0 zbk>Os1nFqTC_wHK+e7sROicnd@lRg+AhL8oSvErWz28qKa2wy&P_Fw=5in_6AGK_0 zJ6K{@K|NKQBD~^YC@}j5TIMyc;mP>v9kK_~)DRE2Xi(6qZE|C$H4JG9dP!=W;ju24 zl?k!o%B*HbQG>>T+(R`VfKWC|Dm9MGJ2k;B7lxlL&DkDe>ZK4b0L6w)NRo%8@H0=V z3woA?Z)-?bGEAcQGQaaZDy~U%RdMvTmnGpQP||n-v;qojZoQbI{!Gh^5b@x$pVuo( zsZA|s2&|g3b=iP9Glo6YSZ2>5f~PZBV$UC<@fWHU^(`&+0)T9;dLP zv7>-6Mc`u<91`-{V&vv$b&x>lliW3Y#(TD(Chyc8wMdw8I^a>}rFz?LU*F+Ugte$G za$g-Yhi3}k#wYV|w74vL>EkD$emS@r$@RW@cl??R9Hu2fHGzzNb9JVvies~F6m7S? zaSe_oni1~5zVYq@M6Pev-2teup0Scwg>%|4UJ9N+8!FT5ygyqzoe5Wi?M5j9M}$oL zL}i3tV>t_kqcIebARfUWV06TtaZ5uMH1%>?8O?T^8rfd(%z%~wHs_O7d9Hm-f~tLU zbF}oK3VK>us7}XI9C`r3Mf3>Wqd^1{a0NxZELTVIe2#^MmXgL;v28#Su~&7)N&B@% z3|quOu$m(dFADCs4Qde6!ZvoIX{Q~o?nOm!jHVVO5i{=4l?S_X%z3Sm69Lqqbj$%R zRIEFbBUBL zh?fy_S`W%QAiST%xKS79q1|!Bb9p|_1um`Y(-vJ%4zOX?VxT6#Z1u8@E*63S%qVq6?gT;C-WHb|2R{s*WYdSZ>teqlnx zj$8`JY_bSYs`)3x@>UwxLd=Mi&$IV3hIu2*cGKl_&kSQoYJjOk;TtL9MBiUwoV6H@ z$IP;)x?w)k@(ll(rWK0cGm_V2lgy4-tg>V(08J}T#kf5VXR|{oo zZo&hLitf&)_7a`bb1CRE<%CAokXH?~(7-Du1D3Ti`tvELJ9>yb-Z#@rpP-1nAwiaW zt1l>}4<7x(M#g2J2)1a#8%c*l+2M3G4DC3kbbpG2izS?)oL*+x$-NU4G--QJpH`DQ zY{~KZdU1t}6zP%6mXJ1$97Kwcam0{j$b^4tq7Lmt7A-H&AyF42F!*M9o@0PA?QUH$ zQY{cY6IN%exbT3(a<3#ibM3?fX42AA_@`63XVj+=2eMRMA)7g)p3l2qr||j0ahG)^ z@Sd@(-9Bz#sFJ3#_N&6}{W_=KyO&*5{U5Dzyuyr&5a&K_gBs$pJsJjBt7ebU;1XH6&prxgTN`S-do_BA z|1~Rj=`uAKAh++$=iuf8@>Jg-m5y~wcPAdHI(#wsq0n_m@}B4bEcF-i-NaC&Z)6^WeDIzcgC$C*ennGNZc0dV>m7! z`Z%}Wqj6o*4^YaLslzr*-Vx~)e5F-pmsIZ(Fa27}-_*HNk|vC!A`XeSK1B>XbXg7- z-BGNgNT!Sc&}!9W9$>mLCkZz`bDgftr>g^$Usj;m?XPA~EvI}q=n93LRaSM8g5Gcd zQNfVUA>s8#l@S2i=BQqR7uUG0~~RPO#*T4yO+|s*4;j;eiInzq2;v4XO7kKN)i(8b@vrn>3zw=Pt%1H zjm#1@kx@9FC?{S8HrZ?{o2bLCY*k`>qKyld<@`44@b~8W(xfI*Zj<$R-ETAx0-HV7 zTcSifjLabWt1Pw$vz>FFXIWw700{wqr;aH5f=9tOHp3Wn+fCjE3d zheyMf-ls}ySb`(BDXGMRT&}f2gD64L6qFR2X|D7z*5js?PVMTXb%2RD;HC(XS3z)e zV!^m@xMnQboOsF>5-1su7f7j;5YQA!j}X{Av1n%bNtf{3u|jksu1b`;B83>_YCWzV z`XVL#`bN2Nr7W@1`j0Cj0E`Y}XB)s{CKhT!uDV~4psXKZS{-s#EK=Yy{4>NYu0Xg* zoQUlDSS2iQLagL@j{|A&LvB<+`mvSzO?19w>w>NrNh2E9C{U76ZkQ zMO*Mr;kF{J^b2Gab=$OJ=qBw;r3P%JQZ#3BkqV??ae=GZvk-SKk+j%VfNiP>e68vf z!dJ;QDnM5iO3|bu-YhO~^~1qtmWZQXDJK&c2>5pLn9m#Z9cTm*wn+dK@}bw^d(buB1{!scmu z?7^_1g0Xq5790mJgI8Yn`Y@YLCR{mE1(h!ZSV&a?p;H9}QmT{rSr+tYCU%w{3ebd- zPQB%!uz4Cqh?+ePV_pdhUgMp3$y(-M)C*_xG8ufjzPS1M)&dbO@Xnn#RT8>ul=916 zSA=^lMAjpe5AyxR?dP`_S69J@?tlON`sUqj@Ui>(m+N;GTPgxW1gPhd%q0=nwdGdu z^VRiF7gyN0t?q(LKLNx4>Cfj(RH1@;MV*^Jse@O^Mu6)Zc%+A5Dlu}w$^7)#{N!>Uh?a>mJto^FEHfCX}HnPs7pByLQ z!3BD!54z%Ubbkzk*vjt<)_p&C440rKW8DTU z7x5&brIkJH$`^e#53tgT{mT4S1#CT)p#-e?-~R}Hx_HOwj&DC-U%zWfp2`6dT|5Bs zFVorMR6Sa&FgyQ83oDHj_ju|G)br_#5f?hcCcz{VhBwa4<3!=tmd1*O)=YA)>?gY7 zn#s{qPbPl8^ogGqT@3QJCa%>;)WpRJe(UQ%GJa8Su~jf9R`xa|me1?Usd=0OO|gRM zO}`a!VK6Ka@tfnQwQTb{ZgZC4>m{z1algRpIy=up zxO`~0__x#I%_nX7+rf#e zjCnBzj|X9_zc8tcz8QyIRma2VuF}giwV;axG;`R2!bsci!--3bFXT4l*SG1|g1C_> zHj)h^Ks@M_op^75$Qi2smCh(?44b^C2>82vM=+3B05)P!Qmpuo2Qr-{WzUyKkq(%3 zycKGSIgI>^7(Mj`=NA}cW;6%+)c5{ug29732>D95O%JE~uBfiYElrKUEy$puq5K^rl%ocDN zMcNy*2D1q=M` zaw5nDO0!`AYxF&SAOw^c=t}ZXf5)|6iFY2`Ekc>l!6bB-FAy{D!Td>C(}J6ka~v_x z{^_2@LFZUA55AsQKDu#C=s{QqH(nd-;GeFP2NTZ|r9ul;$fr7z$p#B~ic@}v3vLaP z=?S#Vg+lm>`vByr=^q%&YuS71VI2qUGYhP364m1=Qq}7w+PDSDwDuBTzk;`0ko|9G z<0U_DW{+lSn>K=;(QI_p?29br|0`Ygzp`b%7QwYIY@M{^K<+K+#o8ff%dUfL{dJIS z9~8}fSkzsVx36qth8B34ZPk03riWi%_vPv}7DQwiTf!V=MBx<{Nl^=MPZo6-Ph(I^ zx-vy*T5#1*JOHbS{4vBDj25(;(cWbVXm4$U7HcqR8=hQqi!0kc^9r{n<=$el4$KwK z3b91HqI@VTk!_dACJOO^H4Nz^-wi@IuB58TUj(@cbrMKTbY&Z>aZ6m*MSD$@m z<~w%Z<{6}jI>uZtTU`AigJq>`@x*cj=R>>7pnzF8s1!qkn`27i$`8peuGAZIA}Z?< zR@o`pMAlHnjL4qR{~~wCwWgGML#%ufPyK&&IQ9Q!F!dNW1OA_WzcmoyvL|J%F)2zNq0h-w~0ce6m@sxX4NQ!QICHG~&O z;0pTcefogtZWg*6b^BxZ`1AW4^YS(>LArL=fyfYzx!uSVb>KKM5lY^`y@AW3P{d+w z$sj$mt>W0?BN#|2DJ%@0M|UR^qt%JlsP+}$c~N_mCb^6-$p%zfyoXs}rF+>CM$17b zpW#ZnUnz^5KXe~4KUO3ubY`;j&V5q z@`!@xI0$;D5=p7?8wgW_Tra!b_Av*Of_F5 zN;!kF78BkRGp}`WFwWuc0_{_veYfg=flm*ldGu8<#~e#N{+=kELAeK4YAyuAF*HnE z-kt@*YhCHc^s8QK#A+ez&i>(QxkZRwQE-LDFu33jT5aR8d)4pWw9j4~y@JqH8*KB5 z0&2fQvcT|rKV30fEwl2-^vlBsmmwtNEdN-(f%0X!aPl%ur8IT)Eb*U;^7S^v~ z@OQ$KBv>h>pn>5?taAwwtuquEv7!e-#5ScPZas=sSNW|KybZC*aVxCW4=C+-!t%wD z2oH*Q!cq!kinNI0O)4XYRF*&rE=G~4LfzixmClt+v&XmW163pO?xFItp$j;3?P5Lg z3bPm9)cb~=AWLeI`Bre`kMD`dFM%K?3KmB_ZS;@thlJ435-29+*EbwnDwGdxC2Vj$ z^xg2B!|VGZm1L#^$zbgIUZ$szO7KFqiB`~66G6WJf)V|NcDa7;3SxJ_w4i8xs-{L{ zwXr-?k7zdBAd00XTQq0qu5~*LEoV#ZmM_?j&{6#Dv~am~2;T*>!&V)W-qElsS`wFK zWEJGm|4f;YZay%uvSl7tvnRcTJ;{f+i%lsPma~Qw+Ler@EztvO{@?jb4ZHJ{or2dC(vnx8P^l+(m>ct8H7gAL+f13UdI_oXEKV#9& zm4d&6ZcsQyzp3>_?ib9_X?|DT=u&b(CFgEGL|8H0P8K{nz(EUAnjl#zT{rN)QJLSq>ch(ww4)5XUJ|u`dywmg8l}a+Kc8VsjcQkEKG{#2l?>L5{_?K@kPh zMsI=Kp73tqVg`Q-oToiWn_GpKtO_G#Vr)h-eYmDG>5Roc4Hcik<|Cw45cY*Oi z1E~(f9SKi*AH)__9Y*`5jtWJna<>Om}B;?>(YjjGm3?cq>mR zrxm7r(cL~xfu^34oO=Zo+dxZjxcd_8gBD_hUnK!xPO~(l{LDhIRDjY?O9G@#a~fe4 zP>U1Jiq-j#dqhC#gN?h1CcO%DH3uGVxLJB}lsJRei?YhC?$`5ABdFFSjuC`m@}N~e zZcuGrGm_=r@0(=$yabWpQr(GCi`6Vg7v}Z zaK8}V^p^B|)^z1D{x_ni^h8g=OwvkJW9p@q5IYK+tVO{3wdhyhNL$TO_p-Q_QEBa7 zJfXNC2;*{!8x0^hHn|~u@49UloJhm<^nd9YMb%h#bc*3KkFm1YBB>ehTb1IcWE4OBzRyEwtB{>NcS^DLVwSxl`h{a}gtNQ~ZZCq{x54eZ01i^O z?}OW4g04N@g|`Eb<3NZ%c=sFdu0F&Ba~2z}6X(5~oFGqw+f&3`s7*!p+!^~{Z!`Aq z+{A}l)kfpJsB%?`k^|mOkBpPi#r~Ufen@Q0Sv_6&qK){o zdribr2vCGtI@m*7bTpr&~Rt_r)-?bXU3gc3fZ&x#C~Is*d&$N zMjGNW?T#yj0ywkGFgQYhQiD)~#>gI&X-vX%RD-$i_A=Hypi6anse7G$u{R7fqah?g z;?(pJVfv}zIOX1FV%o$VB(=F|WQch9>5;~u))Rj`9WNkLg7~OI&1`W*5Mw4?@Qm3P zCek$}HFPg$i@ggGt}!MQ5UyM1EB4S#eZ$`o&S^0S5pt)9@~K>RT!Dq}5yTQpMC^{u zuxb50rQoInyxi=8yHapS4m~Kf_So~Vl(VVtba`GBl6qbglllo7cK#_M+6TC;UQJyr zY9AQ|j@$x%hr8qj0LU-{Ns}%9??)efmir7jqJ7Nyf{CvdNwq+_-~Q>JDxqZObEE{9 zkhG|#IOG!j4ErmxAS>t#Wx>B6C5(5`GaP(~db@1OGO3-JRCv8!IK_(f3_DK+S#?@` zd~9!@}uFx0mo|Dn5F6wgRsjC6NB(*;2weonZo)HP7Z#5_JI2 z7ZIYf2D!?8ZNJj2|3|atCzZ?r`-9K(Hj?kS4(!$Zq)50|g4wP5AC~ijTh5PuM3XM& z{>K)BHsm1W*-8kNGUZZRDW9PZfDUpYe9i-iMLx$#3C4=nzntao*%H9Ggg@gkKDA2h zbJf)S9zIL${5YBpRHQ)mMEyA!9G`pt&ic=O4xaR%Igg&`cs%8`^9*&JQ{?H5pPsXr zX&)oWt=q^x=dSvW9nY3y&(sbJnK^F3ShfNV_UNb`BFD`}=oh6Fwf)>K_$(u=W;b$q^}^tm&v*-1a+IjMHi&$xr_ zHt%iGd0(EjE{p3%6F!9OZ1TyoT{+=8lI$s?f!;q~_3mVdQ*f)nK2L4o-=UAEYKQ%- zw<7Jf%Df{t5hPI?WSmFV5)se~V6*l`hm7Xn)B=58<+2A8bx@D>ohPibZGJ?Zt#;^LWW11i(#H|NR3Aa#2E=4%sKGC z7X_ZR4Dd!7f%sdw{r1E2HH)A2$5ANP@IF(?cBT$^o^b>?GQcodz1IFjH^z;?$SWy~ z{SZzEV_vq7Okd2sgZvP=`XGgR3XDn?V$@2Nf;p2FBq1Z4GzJ?>rPqtb{2dONhq_>vsSqzL5=pc2v=Xb zlTCYYwGz=OGC?O*@1q}~ zcde$g#UNVXdM+TY#mI5u;pM3Je%%}3b}RgYUGRjAhwF)vLDb;JU;Y(pxU(3y;;P8{ zpUlRvIjGmSdjJYyn-fEhgw`YqeW4n{zc7HSA^7PKxQ4){LI)dynhNo1j>>*Gb%TSq zC$PpNSkiDcM}%ZZazjJ57oc9`ZFAlC^yk>W%TBhHY18fNtm(EPf>|_fY-ZY~WQn=X zD{njXTG=vO&yzL{)n8s--mK6!DEVnZiwuZ9%{O%6ZOR<8Z`9%BtFo>)$BKq3*L#Cp zmEL>oWK~r5M-&WT@tWS;=vrI3n`~uRzS)VFgGBat#-DL}X})u{Xfh+1{j` zZ)$N*dqX!)lKcjm8_UsGxJfik6#%^+H9ND_?e>k6cTZr8(kL`EuXA%3G`s^&~e<6wt}w+=iHLFF;cs#=jV_2Ww^0Zu$M2S$|o!R`Wp^N4Uj9q=z*~n5!uIbSUF>1O+$e z-RirX)YU*XJBDYFx=gycz8>!WCTyVD<4x_~-&I5S-aQQ)> z5(t+XUhVQ;D&Ci;w;zo`+5r$ff#$Ju=V}K5JD{eX=|ww0oRa!y&M{8FbFSnYu^%2G zAC1bxz4dq}_sB=?&rDO$G>qm=+c9>$@K&Ej%T=E@*adfsun$oJBnG&Ido~TnZ-(J` z8NE1Cc-4=F%*XTSPYK9*$Q=EtRBvGCE8m&syMcb_^S>-PkN#Am3ueO(cBpmimQP<< z6q;e`)CAqZ-7Ftf6|CxsUVVL_L{kLoaJy%2Wup?%>B)^Q8M20F`Prod;1+~d5j@5Zh88& z_WPk7=6DLb?}{<0AwRU0K=p+4H)lB?ukVjwo$r)jf|o1}R?_Y2d!DawSdGoPb=l2t zfyQM@!8b-iDY7psVVm|~>2^A8gjZloowfpoh(~-mFA}Aq$2XK^=^WCm> zdKLLbt9#DEnB8HNQ2|~Yi6)TJ0}!EnsZ(KXKNV!(*Z5kRnjOzt{+dyMJ5i2XJhqX@!hqvsobdlM zS_I?KGH#sQW@MCZU?E*P~8b`B5GLA!G;8J zRhWvfn{{Z+9LxP1(?UCUT5A!sihmQn@Eu0IF8?9RzGGP?YZ+YXqWc9dx)M*ea2mhi zenoGOm744y(jq|rw-q#&_-TvZ?DxJq7E8G#A7y{20>|2CM|R2R-C2OlWC*Cay$IkN zar-WS`v$I~x&4JX3JewgVDRsl!L5nsL$M*#kDlG=w1s4K=3lp~_D$V$XB1W;%=>T1 z1WWI!M^#M9JCQDBaelqk;=EI9TMW|PIV6pT;xE|vUd$+u6sox<>w{w!^DX~e{rXUBf6FvlfaLd%WoSy5=0dr^NeDXbC zXoXMvSb~`VINkCJCXfR2ndZ`pgHms@tRX<}&lE?R_LFX1<#wnJq;W8EQV50>s9WKd zq_bmgOHwYOcUv+oCbw;@`KV-1MmLbMPDYKyya%q}94c{(QyQd0@+~h(T2`UQI@I3e z=$1+VLF)9|p5L_4z;nuJj$@8&sD7gVpOD^QN0_7{)oZoOR)J2u)4I$7^>$WVTDch#%qEF3ipIANb5;V!J@hm z4^uwh^J2DW6+e8orzWqxf+?51c3w_T8-#Py{F%M>5`2)?{+!tyF!s;6A!W~NOA0c0AW}Rt`RSt_PNLJf3-sDANu6IrF5d z?#s`WhU?lvKie~x_osfY$4wh%ThHAef4 z@!Xwf*|y=&^?l}vmgL312-1Ddip0yHU2c-|HrUVB!JQj6@LYLO#q@(`d)y-o2BVa= zSE29CAD@2`SmDHw+5Yjl>xFzc6jgwqv)Fk#ClzzKp1oC*pW_7w9zvU$d}jg!{ZyXw zOWx?#b2bCH8ilD$xh5*bye0#kT%LcSf}F7m`D*UNgjOg}ZH(m5Orb=SR>ooe!Lxo2 zQu;1M#uW@udG>Y(DPp>T14AP34UQ`aa6;1ZWt<%c9gwr<4*iVt6-a%a$65lCk~NmW zjlI30UZL{sKX;r&E=ljEwOTE3^6cw4u-76~3EQj4z4yX(%s4|$5!-Vn5v=KB&t@HX z|G!ia~pKD+!Kjr$lo)fyCU|}Rv5{b$T16-ktBw=oMPO$KCUN!U~ z!zM~q_U8nuUnn=EhHK;|>nJF+FUc@W`nURhl+r=8W&xS*+Jf%TmvYu;u5=L}Q07tE z#C#(SZrX^UEuZkSF2p?HQ$2UOtTlmu1U_DX7Dqb$usjcE{V-Y9nf}k5xwOZ{^Y03Q z4Us5WKt$yexC3_$1orb${Xxzxu-8i%pNM%|q(Ku^?CwKvvH$bGe))M3uCIM}|6gU} za>{=83yWvxv$e}cPUX}*h5GBhm=b9nu7faIxRJZC;ha;C4*!CVdi?+3yBs65Q!hUW zQl1$Gty+N5(+&jhxM8Y#?TeYVrGZPAj4^?R;K-se)~)m`mE~(ncgYt6DqTERP^on7 zT(O&K?91io%CA=I;yeYKx7bpO^=x7HQ(0Q7Usg>gLT#0sjaJ!2XCyZ!P9>legI2mZBm+Vhe=Ip;8+5~5 z6&*}57aLK^aC!eFs%$IQkgP*AC+wSbFi*TN5KZEo?y zL!ow~^4j0avyNi84 z3~oi$*!~xMJYv$-2nUhJ3NA?~9%`;Zi0w_(zsh${S377s>$0!Ud z<4z4R=Sc6?>ButN7~N3$QEYE4Im*JKOzIFVjUofpU!0mx^O-}{6djek4SFHkf`OhX zPOXPn%whtW80f7M?S91N!3W6SL2`Atup=k9b;)x8633r|ar(i%aUd6;{@sH7B@B0j zkbIR1_9V}Om0N@jAmW9#{#0+Kr1bFAUJ@nd*&ONeQ(;KrJ8++4uE=r^=ISJG^+jf!uJ?viiSr1*D&9*6PDp|GUszi*#xuK~ApxcdF^#~D z*K-VR*w>LW2R#E0v+&Sa<@j${Q#9#(Qea-OtSLF~{!g#=rM=6*-Tz4;Rv?Pf9x3@= z0DYhX@WHkzUfljq%22_bqCn=o-Z#lV=#w?%7;7PSx`#VusAk<_^@&T6_BF85wAEVe{dJ%5MB$VL)O9%;6gpzEh(lc60m4_A*(hrIkW`yUol ze2V8pB|HA%tiV$HjT|HM5?MX$Q?Q}2DFRRQX9-zP@jih0<<9X$F9a>;JBtT=pW;=> zCwR)2FnaQrKu$oUw%|mn9k$GD>D8DJrqY7X>=SN9%^p)`HHdu+F3TclCEiP}%fLuY zCwdeqB$}>72gHwOERLV)<@^X5k^Ni7cd~iO~gK`LSK30k!lK zDLzBPY*V~!Op~Vm-U-^@1fel;-D6vn3gw=r%H-wxvqXxdBhw~HCECEVJUD7VY0}<{ zxa;)DsBh3)WfAElTDzhhDt-eJB>fOF0@ZwKGMD4@hf(dc2bGv|=Fw;fKq}Te`XK`K`nY5i&f7Gg+^E*LHn(=?00& z5$KiHcejE;UVbYVpjhOj`pc!#Tw<+|eLIZgLtux2`vam>K8)Q0r?8SJ&)e!M8QU zPtnjJCT7t?|6&outEZt_8Du|^5_x;8zMCNXw8kX2tP?^?5SdTB4tMNw*UI1Wl5t+;S-b;iJii{c`4OSVa`?S6va+y=sT~Js8X0ylHO7Cj+(LD zkr8BSLW?5EBB`nhX{e%RCR|0X1-CFku3pjUyDuyR0^;<<3ljG>a(uJ{2@dg1P9ZD|*8A+eJ^Nt8z<8(=m`!acdVrBPv(MO) zm*Z^5H+FpE>GKVi*#!-js^g;&ut-&l%wSeUW5)GQVB{Kc(0LpNfeg`=v9DO7P^=Ah2b|i;!69ArUCvB z`5de2_B@bGkAUS8u$6HbBKJ@1nLUSL!YKAX4hyuj1^@v|W6kb$Xy3X1%8lOe8i3R{ zl6T7ug0?Gy;K$OT$O)!e?|TCI|4;;t{g4E{Xy92^fnhFOifW@!$uF{Zpim!9lcosP zCYPW9=i@_t14br<SoVY!mQ>`~*Y2$sP%UhS9@21gf_4W*%TA`HW$7@!=Ci#F??I-;*jIXT zG5ccIg*K^TzvD_M^ESd=`RLb|%B=7;LLnNs$KW->SJ3HXQEGDa>NDNvDM2cnqb!H0 zOMwk@Z_!M`U-x7*4GTgvM5$J+<}S+|%jx9^Q=MDoRV4}hI@=Rb*~W!5u{7O3)1kHo zijo4iVv3ott=V6-EuDgDIrbZOqQ0Mw0N_8Dh-GMbZ2P}rbrkWPCXXxZ{D6+5oqPfL zLc%L%&C%OnjOIa!N~cCw1esnEr6C|c@p-H-%@^CHEDRK#ex6+7{{!#h}k?`2gDgo z=l|~T1NbSQ>%2n^@EVp{bTvEKIiu2OVmj#h9GVvTqDe`UpPsp|Hwcw%=z`yTgM!DN zEg`wm^ZxqO`>w8|zHseJ`)=#PXA}KI8P3kVk-9f%-^LwA2uAYHINNb(_n5aIu3cmz zsvh%B;iU>MaaQhLv*d;1uDKmjB&1N++zurYN-WC{orQhl%%R)#&K;F;M;&2~66$yM zD)hZM^VaRu1)?rMWkn75D! zF_gzxG#f5*f?Joqq$kmDH(xb9#74V2e#Cs`o6uO9P24`sREa-I_U9B0%aUHf)N(fn z<*r^er&WrA9ncTlhY2lIr4DwI6N@Fdw1Xk$^6effd#F;S6Ga?K%bhVN8*|t&0QD=V zdAh-g@|a;gS?=(JuSv!ePNOGy${}c{cM-jdbj9%4L=n>5f!7u`@TwjDQv5|Osj$n| zX4c@3aIzf&DFSh<3nl}tBKO`4*D>Q{H9Z}6n4_4(7AWlLt^@C%H5URndl)LtOVx}W z>7`y9GEs;jaJlvqkCI*;_GZ8D++HaHvB=YnpkW4k}%A`b@)DeBItQS*>3xOJ>{PR1^aZErKH(_){vX1EhCNF`Xk;$!S#Pd(? zaK;U z`;Rc?p16K4fLunDao;(?!gr_8)ezjTq;qVQxio00W#5 z$8LrL+Qi2}dbhUGJGSPRyZ$aTqBl8lACd^N?OLOJXF3SeLEvs@JY*FWKPch8Q?Tf2V5Itz!n{9K+J`|O**94lf0MLjvNeY>i1H0oi~*8sZet9NT!Rpk)RJ#8XACEU0fd+1@h;@X zFp_QS_R_(SdUct6FT$>cCb(h{W|cc;QVc5^yG8-{m6+vaPDX*~jNK@KX7*)1{R#Ey zr})jLLLpX3;Dq;2HHK4uj7@2w_SnDWGQWm*T&NzTgIP^JM2`E50l~5<9SjPQn*u*1 z!~-E#YvU%VROAYz%`i6~Z^a|NG>tLREVUTuRFov8=7e$k-jn~Z6$*@LmX+WTe>To_V*PN1V z<;rCTa8czTnWSRx0aCTi-xYvy0p3^B5@6)OICO>%qc3_efK>HoHOBwznxdKms=O1a zF?iDUpXQ%-+N_Tjh#N!7U;yDBR$j|y3?tcIbT1u@T+20M=&0y(W)7YsY(rh>y=GEt zu?isFm{uL~S?tEH>jcMEM)%N6VJ{OdZ%Pc`Z zIpz}0A$ur&VUrUeA7`=P?Mn^p*~^w#y|hZwGB?Y%F$s(^EVzelafr!SG#BeFyt{PG zo@zDr|MhC0%DVl3{lX@}j`3hqC1*;2lR^sz;QH(N9eiP5L-sw004PLRc<6q0{5Pzp znpB(8KD(~7gvy?O|EE{`5*%fq@BgG2OAtA3kEFiyar5W_{IJB&;-&8Yq!cwgWB|{? z7(EbGrEm676sVdZ)kww)tlsERh<3o=dqO=JGY;jF-1 zoIZJT5!>DIx=@xP{8aA+7-a4&PxwKh8GmO{nJ7u(C-zk2Q#|#{7(I*2Ag3TwUbq}p z`(BxuWK3%pW}4`SB7C6iukOI*s`}Kze|qSpkxpQ+CC&45EDNvHrA_9mS}7!FQ%R?VkCXzbCtgFY!8nT#Qmp=^}c{( zBd<=6shVpIpI2*-5Dr}!7dhenvMHD5 zjTVE_JFJLMy%eE14BQ_OK=5G}IBA2c#z#6i!3eJ#qgwi&>R)~C`H5|+f6r5fI!HCT z{6u^~`uDUB7OvR#5{^m}74&Z`_bkYejbX<(3Wb!0iOAj*qGH#TTqKhQaizv6+efXW zb}H}SZE!8)nX0LRw`_VPOx2LmN#5Ysa8pFPOV=eoMOQ+utz`ZN*)K}IhP;nsr#B~y z*RLf6mFSQ~EVfXtrO=e@m>tRyls~$NjA)6vL@xL{p&FFL2?Wi#7trpHHry-pC+b@ylJ?YFIckB+581_ zL;ldgfenn2TpLNOv(pJ3829JaFXabipBoeh$QkClE5?pLkR)8vsRO)XdtLxJo{)C@ zA2+gnFHQ{KB|cHt= z{E#XIJtg%Wm5X`?VsA2>@66D+-uzY>%g?L$s;Hc)=fszjNv#>#S1y`hFEQK$;<$3| zIUKvBO;j?xYG{`DyNi(@r>{B;Hgg zKMmnT#GV)Ap2Qn;A~6RlbsET`3n~)+S%b-xJSwb$ehU6m!ehxGUOfK<90J*)Q4kgf zmmxGVf+mH~FCNm)p}pShlRZ1PXJ4>KJIC9Or|fvj^W`aNT5NTE7($t;N|G5l-#r`P z9j}<0$T8mjYVw6knY}@m z8+nf?#!C|xRDj$R2+ybzAnA2pmZ+EHJqvi#aKUd_nJmrLb+1GF&h=N&ZQ|TJz}^vs zeD>}f>21o9hz@aL&+PfF3tbOCiMcWZ0uR&}n?Of^OJnURuHGClbvWnARY6RfD%uT6 z7=rdH5(18;iU)F zigrHUWdb-dH8lqu>BKS=04=QA$pIJ-27LrN_7b2|!+QSRO=3QnT<}FB?*U{*25}s? zOH%g4%G}9I#;kpWIrnC%^cT;ZTYjSEZE$LWu=iOb10p6n8u~}9-PtL~K{WJ1L(i!I zA}tO=wNhOIPKM((ZSeIMu&u4~erO-68lvIvRF)>da*eeK6G8*)*p2NNdaprg0wsb8 z(f}+_AOhq_dDj3OcjE?DqFV{HXr|4qo)`X@TYpDq)OQbE`+(OV8=+bOPs`ikhvNr@ zSe2OAVToa>PGXgDE0W2db7a1FZY8NoT;daMwPWid9S-8O$gYU8W?#FvUO+Xr9g0#E zq0K^3vy*kump09%oWNYC&-OCB2U!=#(DM`KP+Zt`X#v#C+i`g=3pc`_w&C>9!uVjuh247u!!J^buGv>D~iysfnSfrk}U-xA64cP<8J>Y8YyUFRDUZ8LZaO=M+ zy_FZ5wI{kJAj;je>ef#W3GOA9Xew-Zwt3qUw{(*I9mGy3u4tEMju(lzhL_EXRcyo) zlsv9nlJB?Es(I}MYae~VytO+q&crx$)keil|dEnK)s_O zd{L5t!NyMQto9nb?BtV>Ph=+7j#zTUvcpPQ2Sh$dZbvRTa-pN#c4*0?C5Gx!k>9b? zeGxtI&yl-aC67D2OmpO79YXFEk8_25X30<>RJz=%MIIr(d7!99pH$2uQU!ho+alXfV?h57;~v+H5}!2Cw9% z&&L8%&%U~*CS@^*ZNmd{d*+?1F{4{#$CmH79I;3^*$z^>2X4K74JnP?$~|>H z@ST#JD#^PSUgz$kEsuA0xUj>iyKjeBm8pcK^;ZFHTl@GZpj3N)E?aoNd z8;MxUiW)4`huz@ddCVN2EO)pnnK%nA>=~|dNZRRdLVqJ2NIW*#CR3Byz`J%h%;GR| zNmXLDuC)e-gtP6Cm?9BJ3}FJ(Dsu0=a2+$wR?{nEhrJYg*lvbB<8|Quv*v;U$81-r zAUhJwdWOi9D~817+D|-6f^`_2UG3a!StMeCtQ%oZBY2*b&DwXKlsIoav_Kq`WA6}G zgE+?Q3XPR&UhpngBa^FfM4v9}eMOvhSr-H~V7c7cVXq2%(5E8f^4#IgxrPpCbfkTr z^)ag3@wNhQ+weWke&4AhS#{)S?z;|)rtjVvtcW0wFy& zhrX%_$>veIK_neNsTQjkblF|WfSTjeDA-Q22+2Ym${7x76JHAH!CN&h7lUGag{}GR zzoGl&PLMG{cH%yOu02m$qkU(}WlTANznxK1FiJ?jVU~*NtRE&zcz2baz8zg<=&C*L zcD)z#ZUPK_bGzm06GSgs_s4r4s;RM5rLsDje1TruW__Dph1h%O6@d9HLREu+QNy&? zOJ`*x21vzulO@*B+>u>DiqLGc#I`q?wq4AbQ0?io0Z`aM=+}qqAdD7n}ZI>*a#Ri!3Q^?p^t59Sr@|JxO2@kEEluEfC8ewq~G30+HVi@+l=C>vL%X9 zsPYYLi~=*xHW@MsORhnSY3j+h0yK)7K>?HLWM=xBvd!jy#exWq>qm#7+&i`XSi)ObH!qqyZq*_1A7 zk3P*M+z<1}P?<@G_?mv4{0=S#2G6E6F*t;7dVrx_01#%iW^bBmMP5Y8=$?u|DFMBh zEHpGJC^B^T+*GqNump!~u7CDv5EgtcC&j1;=6&F)Lty|0J9?$;n{_Zxyf8?+U>HSG zraPu-*2k;#=}R+6RO%0dQCYe2!`fN}xe-ys;FBL^E# z41{n71x!_MUZb+2t|6{jz{f9)D1_ccF`0|=TqnOF|8{C0H zgOs_pdPdP=mG`nU3)9ikd9VvT_DpL%RspP=A*dbs3IU^6cY-5VqkCv{v6o2$Xi9|G zG}(j>Cf)z}U%&jk2-i@swEwSH`~0h43V9P6T2Z%6zS#6+B8_J2T#Ze4tjDED?f7(N z+qc2m#;StD!2OX9FqvL{I-Gp^I5}|^3%LInwBSRck#F)VpV;p-?sCcy12lH|iHss@ z{1xjU9rr%DgpH`)(D-|Dm^*XgH>B2b9}d0$FUWHknZeo6v5y_@PCiE zy>guXA}hE{KRQVdiumM*1uj_oTbZ-sFJ8iSTp6hS&GfVYBE7(-%??ju*LUZM9R@a_ z1jfS#ZUkSg9`ReqR$5c<5M3~TSjrT{Pcvwv=|s{EjTx4CWnzjbfOTS>*fU#(W%Y=N z9uq{jU*!N+fuqDfoD~r9*q$A4w!jF%SViH=xpfkkVg+!)CZOkuwf;!Owd85)8?J>1 z%fLmBxY;7m_-O`|{=<2UZNmMi)2}^t@%Mu;xr@RdWHLPdK7BguQtJrf)qdv9v5C|r zKcg#Vh>3~mk^LvoY8a76%3dUp5xkEH5)k`KZ@KdAg_Ag>D-oe({0_-U_!+iY2{BIA z1;@k{A$^7D&PaP+hJ1^_Ks2XL&vnH-#CQd$S~!UN!9Lj z0>3wpTzp+IT%`lOEMY(CUge8tlCX}$%#!1KLKJy=IFpDqa($TUk<@p}pr=-{n#d@x zSPdW2I(8w)n!!aLa^+EgkJ*bb{WMAh%$Pi~Q9i&;HPi%DK(XbrO^34pT5+%}sC!=E zC7$EMw7tmoy*QCCn+@bH2bRiRDh{gfL`F3?egs8g9t^@l>hAxTNq{9V5ib180p*|E zYMV^znZ%b*aBg|Dl;+Y*FR9L!;sPlFcp=Er$pjkJ-S6=pu$(tbtQK`1Xo}cjhgDJ# z9-9KWTB%sV!;^G4$a2{k3Rr?b(FLF22KPIjWOYuL=mN&d?+nIr+8vCg*L{sKYVvru z`KKfE956abH31bN^4~Ow9;)6#Ot72_qz}1nclshb!cYZ5CPT6u%Jd^uiyTLEc+UME z^onyM5Luk7yb;Fa>({za+<;^Sz;(U>UNupU;Bn+a2Ye#jD@mozXSh$eVWoNVZYOhb zqqHqA=wT~(dw%E6zjLL%d_N2( z)^8|2QFXARn+W^^4YVwOsA?hL%K&ZzC8wXMT!z?m4a=mTsaoc2wT3JhvRxxpNuRxF z&;n0a;fk(WPxdUsxJiLQr4zgva#OnUi{?3|tru)M$i@q9rT1>U3u(h#r?B(9wFb>l zAXepCvoq!%EWab32v%>YWK-A5SF*5^;f?3RxJqGHL5J!l6J>PfB3RQf8z|NWzMfZ+BQTC$9$}m{n zcjm5*Mg1GETq!lE!wbcM?YjZG*XOlYiq1|VJqQ)h-vR33uHy=#L;D`%dqiM2e;ix& zlU|3mlh}Aq=n|*{D{ar&gc(jRYFC38Z{33A{$x+?1^St{_rZK7u2k+~u3Zd0FB@Ab zd-i|ZH>)tV6EKDN7tQ{?qC55dh)QiZYpsV*{3SYKTmDk|v2vnI|Gswb4-`a5y8C`Z zJg?w6yx)_)!HbndLU|bMj93L2`apNe{}2)fr^@~1SNp^2;_HFECq9t17^yWuf=cwu zpO{apKH?+qHzNC?Lwj;hf6Z}KE0*o1eE`sDB)0RFESj>6-7wE)l3$K_4H8z7Mp_YKr}z$JPv zyWToKAv`M}6QYRB68E3!JR^)O8~C+!iLenMX@2KKW7{S-cJ&Ev9)3<5 z*Fn;tG*%W}tbis9e_ezC0Wmy&Gnu`&_reuO3Wy5)-~amtKZlW70Rg+o>oD~3=eQrf zW)OxI8_x6F&2h8&WHM%EfecA9$?6yc@s?8R+PsZO+tp}8( z+vIMtq>2*6rMT(@KLrvCEd0-i0$MJYxWE~qjEUS^2x+(xeQ`wW@E^e%)&YLT55w>4 zRoy$Oyx|F1kuCu1&62LQ61PGm&HZq_@WWf%_27=Z83eu$?EmbgKgR1gns~QvaOwqs?ZEM^Q+jhSrU#;! z9&nxD7W$Uh$Df@f@*bv(b1#72Q1n0I3;59lB$a*m8M>T+pg;Ex@Y~}V{LaFi;RVFN^-m{`fBony`pZt~U6k1Mzzlwm0yD z1De;faG^%oepu0%IA8NUO4u)J-*=+N3$YVN*X!5u+=0KMDIQJ$*&izgvWmkSceo8vrvp7Hzj7?#lC4_JP&9znU-9bkJrUieuWV!qSO$e6@F4(>hC)fB6qrF_=@?vb z;N~#Sk1WeWRh>FE1^`Wn*26%cIRm3+D4>8DBS6U+czv3h==hR!yE6hx4_4;nGzf!# zyHS`k@O#_;j1nef&eKQ26zu*Ga7N#$0Dy|;{`TkDe?+x6wz-krY4HP1OX&OL;L*DJ zwAgzeE|<ighlP|z8~kT`)4?koSg|8w{M(8~|bqS6?6dHp);&*w-{ z8(@HIhk9fhq~JTG_h0}VGjwPji~E=cmzXssYf1g_-_!RPX@F=Ec)O4zq_LjfWS|6s zaR>|na0bz@8Dy(NzzYLwqZt(Px&hYI*>Euc6wFIBaWxWL1d6w&p(tW!5XeCw%;08> z+AH%^_bp4=-X;i>ZY}vr`s0}6i@=RdVVv%51mk3DGZ@DNb)v5tkWQ8ryNM8zhU9}a z0w7WuVUQQ+ATh`Ipv6f-c%KoH#NEw3h%?yz3T7#Xtjf7}V**+e#GlvmyBQR(`)>3V z1{~x2WHPXSa8AAW?Ft&HJbVr1r)mtI11}x|9LHWvo(SVwz26J$PacV}{h=B57w3y9 z*BZQyk66NG$h2FYo06G}Kl#qRlib+FvMwSMdf(f!Kr>9 zG+m@Wz1TX1>n3>8%7nVFmWq~@!FJ?3tow6h~d)4aUgN7=vVz7ePkwG4ElhPetFWd4ait} z_`YAe1ugB!;f>}i99=^R;s3P$h9IJpj!BwP-GJSsuy9Vy2YDFYyqDoFZ9 z$q7DPtSmPsOQ7q5K~YjTzadGI!9w3eU>z`KK?%WxlfDQ-|43MRi-qsf*C5x~_9#gY z3NZAIhEtzNP{@uq#t~4n!tQ2fl*=Ll46%d^8u})Kvxw@IgbqwFgggL!Bfw%$@jbRa z$+SV}pB+dr^o<7SeS=L04B44R8A0aghIoLCfZnejLMmpi9!?GaH>edJ%11YF^?3yJ zef5yrdAo$_3uJsWoMwapm{9<#4sU=CptGKdz{2>>br$gSO~`#|@4l&i3{xVr9d`N? z^?YxUCDW%KjXjE2x|G zaDb-NSh9DWSiKp9irG;Uq7M&b+15S`^@Cjnf%uXjDt;Q(P9G~?Ne57fV2uPu=ZNW8#GH=sg2a<6Fi+`zT?|# zEH7y#6`kui^ZwvP^qUuJP-kVR!Vx-caW#6;$eR5VVXMkk$co{!FB@4&&l}DJHt5Uj9|G$rhYMpY z;>1~e3qdxuwNYAxI7~MyZR5^^+F$14OXYGpkBtVgQemE#)rL=)6XS-VNmCGdcrElaX~~%7Ijh0RuFU;$cvvDZn!31OcO9&DAc4j~6lXDt-q|*g< zu1;7Z76V*D06-Jh`-fos2Q>Z5bO`QKZn53X=q*Qh^uJBn9c1_aHM;x1jqd&z-Q9#o z=)j4&RsulqFaL^g+JOKbn&u1UIIGIW}KHXzJ?3eQK{Fu9T+Zo3gp8o4NLXDb=tT5czVC)&5a&3~fCl zm`iOc_>|ed|KlGyQRJYF^%no+dWD?Vso67UOu;HYdGAgTW9L7+S^NH_cYnS%M*G$X zTpBo?$}AWo-y8}~SXLI?0ZZrVQ#=|YKFeCTFi95@tZ-zUDc*bN`{p(u`wN4+TZeby zI(F|uf8j>IN5-zef@(N?{=W?Zn$ZDcio*cs5N4<^S3bOyizvAZNsZ?R7k`HJlhi9< z$m+6OteJxu8EY6~X6pS~qYw-~CkZ2?c_U}voOyWd&F&YIZ-!Esj;|MUllxoaH5i&H zm6{_7%U#1HskgzcPp0e1_4mDcN36SW8Nw5Bfw2KLeoMdWQ@|UHdt26>NFc%~7VWY_ z|5=BL2Z5h7tE4KOmp0SrU0QHO}gxQ=DPO&r-431U_?2Q9fP3h-hna z?%}@&@GtvjGMS8_r(aHj=-UfCLw)Uaa)TOEh<-3gJBwZWVHMfe66s}H_fa%eD(8Hn zN?MxC;wkj^{$53r?tVu8j@RoQk$v#K8t;N#3*OE30bI@G1Uz}(eXexn$t-W368p!V zJ8@#`J&6Ts5HxPkyi4(^sJjc$VRKJI;o33nA}8pQbKfpcAZrmFkp_Kayko3@@{vhR zMhC!}roqB}c=vd*hSB<$2PUP1b0Q>=7c z9><|9Jay~?2?iNYq>eohVY<&@X&oDckT(8u)1y?I|Zjmh{)InJmQz~_y0(D9)e2NZ9;IUif=sBEBN<^04?FuqW=XM#v zuXCfkbkw?+cJX*9mt$lnMRf6no(5s?Z#T+CJJqd!MrkWQZ$aS(RJ{`$P@bZ0{o}|b zem>$c(6+di)oIY>h~%26h8(=Aq?28^Tsl+8XoK8zxPnN9DkvxHsJq8A(D;HF@nfJ1i$kZ~970B4e)I)Yv3C6VGq;Wm2i(>fLx$`h+3Q&QbEoW92p2qxeAK2m&n z)GHfCC@?=rD6oXIFjs45b~C?LwB?!4kfw zI-^ZH6#SZ+f`!@v;m#|g*x>Fhqd;&6m{}lN1YWh%1b3pD#YA)HRy!h6AF^Zslm^4K zgHqwDHxAck(P8~)+B$r!9kdPN%i3YtHUO<1u#F}S9{NG zi^ZD!uWgoS@S?U^qRJQAL^sWD%;w#@IU`%IzokpD<@(&?)aV#&x!!i}y_So&a?-V2 ziyyqn)z)&kHV(6vOSN%(wOp!=^Q!GqEnHA-muivX-*%~HcTmff+B?%MCVgcC=h^TbD)4s1R3tu9X1a@7ngSFm25L#kL(35%>r zHf}~$D+gYSWm>u6+N{&Unbu;NMwi$oYg9V6S}a1{Q-_sly)Bk#a56PL|LTm+7JJtx z;5=9Dn?HPhavF4Z?xsy4=%bXIb*>iqu}Hz_SvL>$B0 z_H-hxj%#&-bc|IjnHg{!V~#D+0rzwTDcxgp7%l?Rj<*XCbcxO@bUMb3=lj`NIvb;c zjIt8h_uUwPHHzINWdhwFMsC5*8B#d%Yo z*Ymp>42p+F(_inL011M<@~u}r_2RdyRTMsa4Q1Nsx-5(eQ@Gr*7n93mM7!-_VHt9r zU6;9Y;xEpZZr6DRxA@V6O0P`IhK(Qf^1LHgSp3Ns*cPi}7rOBSGK3aqqs+zz{X}GE zM<+I_a6eVoWwwy7mIdrSdG|;BZ4+w;{+PY{P0ML?4QJl!EY{Bo3X@K`_wtOB@d{Ap{4D_ci)yApoO2W00jqf z=Tg##g7c80%T&u6%Fq zfNlgxyW-!pJV79;FbWMAgy2zbvYGo zW0K3RvLz_i0lUu5;1pNd8lq7xkB3;AJ| zEzE!bCqEI}_m9Ad9>D>^Ebl@?r*K6k%(@xdcO%m2dUD9&4Zf{!(e`W!v-pKhK*K5v zGFsR1-w>OpY`|j^`jmi@+qltRp7GdkK^RIk$8%RGdPlLhbXvbb{A?!_ ziv$KG#PFx*{;1>^K=|qHVBRxc}Ny5enEI ztEqOr1*oTU^cKIpj@z{L~M-+T}%V+LvDp?kA6Ib9{m2jQZs#fpJ7@mW=Ig2 z-+2uh8^l0UfU8DkH|Y?$bCR9Ke8EcQPjEwr8}iYF?Kvu&W4-;;XUK9MHbIv2@G_AF zg=QoO2;*;Q8e2Q!nlD#He2F_wtq1(vT9C`R>f4hpWCD^o#EUPGBLIxG zlfWJa3Kp>rpeHa4oL2$R={2MtsaWXj?r{|+Dps-%5J{w^H|CtYjUwl0}?Rj4E$$&}ki?oSclTqmBxCDG(cC zA_YYma>bIJ8T0{^)4t~Wh}u1ATNU?N^il^!P8k>AL$ zr}qAwE+XhuKug1UTNC*B56J3fF~P2jbmD_Y2*}@50B#KkS>%6JEb?y^i~L0w*`A+T z2Tsg+AFRc{{3~)+E10*k5fAA6N)Mg*(v6nu#7VpmT^!PP9U$8JvPp@Mcn8EVP_$Mi zM81U(wxFOy0G6%a*m5;~^Td4bWC3Ai&L2oUUn9>6Zr8pOsaft1r zfLmYhNf3hO@1UFZO9diUpRz`;lM^&gw5SKA}N z8i7WKlfpOzm+7~?0WtFN?49`M33GhII?Q9<8wRa~3*&{shm8ZNIv(TD_i>H$^RI2e z&(&6JA;`x5f^Pbu&t0v+xs8-^`9TwB8FF2Y|piiuNQN=`MVGAXYF_H zO48PN4XR&CIh}9Ca@SCY{x-PvNrweFX?hDzW?6UPG6b4&feQd^zop-`zng3qtON6g1 za6ET(1&u~a=esL$P41e#TFl0z^V0SY>d<{y!Cg_aWAd;H1N0#|{*{}oqkvR`x22%& zZ;Wc^AJ@U0SoD`4X9-jvBG-PHE+*iH^Ck>Z{uu*cj^|-~*Y*96V=w5u2;_`+77vF2 zNcY3glo(1xGZG!W3d6*}3d$uqBg}!3c}EN+ zs_Z;;fQ%juT@ahG2xc*lNMiO3G!y66oi3mujx~}0b1<3Eh`l9sm$Taa*2QeoUmC|h zoYmxt{T^qiEp{t*yKe&{a1p3|k)4DswxWIi-RK@Xp7-t*n+2ZnxVKnE^bX9r6$p~Tl1RrJWJJl9a7nAl zo{R3QsX&@q;J9c@Bj;P5QrSYOZ0}AMVl8z`VcX7wFX4M=zjq4_&S;TgH*PDS%&*-Y z>I!vB*TOv=AioWHR^9HP98ulzBq!{4gAi7_n8{tLtu0^b;b*WCE{R>YaVIKp2(jqi z45E+=_YM5uAnP3J1Qi;aqB@isX9YzYwnSaqg2YAL;CxyrAT5e-bt?f-3ZYW46ncAC zkOF`m54R;O>sT9QWx?B!!g_;C3903ds^M-`kX{~26<}J>W%oT+{$U^&+YxtX-PwN0 zzM4fvUt$G^PS;YjSiaHqwh{&bqiZPuOzNMkcr^vfjYjtT&Ygd^6Bm5^&@{k?lniHy zMqAGNvyFeTv9&_cx!C4cxMz`Bf{njYG9s(}uV&}QG>P=RByzl@bt;)0mC82P&^pkz ze&j}%m|W}BsZ6BG{LwS9#J&(vNV~5nIOz!Jc>(U}R#%TjO99@dKAOGmjpG!Vq?v2ES;1zYQZ}de~bEclG!( z#szh`|IJg2srS7NA-!p+j#hHZnwO?zMQ-knNw%B=#UKk5hP4^G6y~#;?InYo0Kja$ z9+^Vbs3R&74Zu@1B*_>+`SD7o0BJLrNh=p^Gtx;f0FA?-v~J&KjFeUY>IYD1-MV3P zmDatRhF-OHyZ!jPlb)60N|;h)#0OS|0;WUu^5ps9`+xLR!}&}QK=qtIy>9@rv&&{A_DcYU4$mhB z%9%wyD!*cTBTt|2ZphKrFlezS&O_(xnc}@wa~^v-e9f>(y*wu>9NYxQt)5k>_4Mth zTxtcQIGVCwmS3D~*}wcR;=lwQ7BSJk8>W1mXa6^{!CX|=DYt3kT&m~_W5XWBUwItbJ9>v?!MQ{lgrdjVlg^4)aM=Av?}2n zj8)ePhsuHM&-}`?%!BU>XTZsO87kk?c@#E3X6jy3JvuZ#t{rc$^_7lsx;bF@OmC)IQ?DYt_$YD49`Ejv zjwFuf4$OhF$+L{yo3uAPw5{sX)&ymzL<-0dkmoq`L-dR^%JfZ;SK%Gj-VAw(hRG|n zAbNd>bpHC=YwWetN=jvObIdOUWQ{h!*64+!Yer`Rv?8t;KKs(q z1q}e(QdbP0P0__2p+R|Z867YrKQNr&+jJW+K>8Wf|F6U{~1Pp zV9Nw@*mp3#EqbicS7E+eim$5KJiXxUWl=c0E9YU8yK)|OcV$5FvCI=H8rvYor|^PwPf%Y4uq_R~s@sY0)^UPb(N>9ODKe)sSss z9Y7=6Yu`1Cgwtz(Z5V{JyT?_Sm_>tifW!d9s{aG+sm+nZaY_<0ECzT4%wl2qpy)6F zf_0R`hPjJ5aTeb~5L5sGQ30F0)8IDvw!Xzyzm*HSgoW!wL=!qy z7QES%b(4jHvS>38#ft?pSjTWvaPU`3Vg;t$tS4Ul2l9xokq6^A*N|{!8l3a+$56mI z1LS~Ih0rKRih&1w5`^IGbTCQhO9(Rp9WmRfC$~T*(HE2ajag$>Wt&w4_fidv35Fs! zKQ(}i<0UBpF{c4#05E`nBPWU+w7%ZrpIpz7lSH3yLP`1AUy{;!cC+^VOYi=CZSDnF zBk*}7o?{x0k#7(QCoH)Ou7PER8Swv@;QyAja1$_lAd!m%;tc7NhrW+tKtsEa{e{Wx zt;4%;9lLj-zi^}9BXfALpyUqOz;D9P| zF{gnc3briQyLE$m2l7r(<2MDyCp=JXC7XAv-`#5n<-ozUoYlH0kFnv zFhWyOHAohgyY}7aZE))Yb@~R~IM!Xb4B?@;z~KNNzop;xD(`bWzk7A~Th^V(Lc**p z;tgm_h{IR9?IbqqL_Tf5}aRJ!;)G8Rd$Zkg?QKz6r&g{oz# zn?|qqIvOpV@2(^&d1lJhVs>UMEA`NQSOJkytW6$PVSw>Q$G>uubrk%G@~YRDXE4Ap zroN7k>tIflh0Bk#1X}Q;M)5FROd$O1O&Fs1XI>tb#`7?~GbgFWu@@NJ9y)^=)ZPx^ z@Fr1Di~cC9n2}uet1wJn-Wxdd!&|{K&%;|M@{+sd3&g`JB#AkUDPCfL=fz?nBP$q2 z-c#XW8Zq?68g3>v&T4p5m@j|Ii=eDi))Rtga^UC!Efys11U_?2fuAnUy}+8V{~Yiy ztO@)xhGvC1uB>r0@WAx8*~ty+A|ZO5ve@G)8Assj*F^-TJxDTvKK5g(ieslmP>t~q z)Q!^=r);;yBVse)mF2GkuOxFD(luQl;O(5g4+E%Z0Ouu6(AK+yrVY;EP>^^yhawq3 zfi;@B|E#H&Y|~TCXjK^vPpLzlv@e-HenPASjk^?2hiRAE4~LuRIotT(ZWLxR2i4sU zTU!T3)1{@H9)(a}1jNOo1#G&uzNPhG7ltx~W z+ezQUg$Aq%dAnM!99Ji_s%7;vSpCWg7Gbu`R^1!6Ai3-FdVV*9(oJyNe!X)@%Lm3o zS(H-YcBfwacD0Jahp(Yb%G&lj@Zvu9Ird^gV(e8a#~Z9qh)mo1cTW7p`I7MnsJrzu zpskM{1Snj(fojgUJkRFdse^p+Ctq3lmGas4Y4}bZ*jDr4dFr~aR_A4HK2`8(EA@nse2#8XzoH%<89zB-p=Q4ERq|$pFuSxHYWV3!&bu#_bztUxM4(lm$l_2MD=e9 zBulpYfI57)nV;STF{jJs@#tOFZ$JIK`?FGhv5hm!yI`haBzd=`YbTC(S-Nqcc$dYi zhGoyu0mD11cA*m<6<5uGs{m($P6f!yiM!Qo?rxA*Po3^WCG``vhX^ts1ua*As*@37 zbsc^SzBn;7l@npZkm_!CN$0+5@d=+qg$c__-g?c%=uS_j2(Ch&T0Q5v3(W1uICt5l zIH6d{JyO!+y-)F7Dt|gf$Q52`5q{Movtkgjax_)!qx?9fbA;8OrgR(ShpC(Zto}fi zTPZ(O)c{}hXR6vs^^vlZc$J?cyS!@Pi!*eUAE3B}`a={3;A%KUVGq^EC=QTSDh2B& zVRjMUMZh%(K>@yMwCAVADkq)%2C5HGGU!$L8A|q0eT>YwRArP8zHC7`%CV9GSuxGa zfGbCJ$z0ZMRvti$+G@kN)h)U(H(fuwveN-er{8771j#vWYWl4c!l!Ycg}HP!_gOz5vg3V< z{6&>qy-2RLWB2N&I(9r>2@hhbSW2jdU=w3qIvufYv|=ZYQ=rgVG}TQ`>~ua^<5fwb zYUdpe@`#x!g)=A#ac{u zASqfryTS0>tZ9El`0V@8y}5}^aV)G3oQw{@Z8;4V?!&vsi#2pJn+71XSXmbH^;iRf z76|UiKnod#aKA&vr3Gnn0Nzu$_PIY)B=Rek@?eJZTD*seKS;pvJ_iYy^^mF98O~K& zY{4-Kc;pg|1Lz#B4%XJCvD8a^;T1$;RZelVT}GEuWC<)L@C=xGoJSjwMm%#=;4 z=^dyu`Vy$GXfUWcqbx)~RhACZJF1Q&m-y6(!8R<2h69o_gSG~UJ*_-vSHM92n& z#io9sz4MZWCZdMm8IBAXH?%A5A3^m!P7T2`pbKm2rrJA(TDM^BAF`6Ztpj3~CCy$3 z1YL87*xv86xvgyPAhqg6+dEWM4QwfSl~(`t4`Wr=+d%=DZPGwnKvqpR{~;i1XzEP$9D&}kWkJ)ZdpCk6DZ!-=b93b~M8ipC#lHW;5rM_A z0mI;{MVt+d_KTPsgp911o-mACtpIKqh$|h`Fc7?z!Zr-FRgQxg2ZD1w^oWM z8>)IM5H|=?%a2DH#>31*H3(FdOko)Ywn_jS1i~@{T872J$u+adEzzxE5IijavzOsn12}6Ab><Y84Uo;E%bZX~L#GYciRf(=TPVJuXa_s-fxn`Da6*X^~%-pHMXb zW>Gt~t8Vhz5D;4;1q;^jQ$C;=Z)G0Yb%W&kC*uNtsJ-R7>2u~WEBj20GYGYF?{>(| zStCEZ*nJBV^4eM>^;X0Vy(Q?K{S)C(g;uzU;j_cG^HN8Xan?ZRMb5n2pf!5ovnhIC z?cX?l?EX49-FHw7*c#1|NlXKh?A#X99{qTV>>ZYC4Gb#gK6?ReH;ov7=LJsmSYu}_ zy$mtaw#0+ObJ^?qviAM@vwFo?GS%d$rH=q7Ueo7IeE9maCWDt@E(S z-8v8H+j+IWyIXS2!@FCUO@nWB^3U3#&BlqCZ+yD*<*InS!njHsk>lqkzwh3(c+)iK zW?c1<=M=EOq;Z&_2P9BoR4m;NJ>hhjjKtg3(vU?15nrR_dc*M2a}`3`>6~? zrz}MlvCa1jajhCIQ13PFmU}`_R+x+>=rYY4j!5ybQG$B;oh10;g>0VxX{c>`f4 zCqW321t$hB{3U#gUk%0_5z*|l&~8vxeDx@ef!u91fJ0$?@-T~mAnkbRB$4+pENwFb z)Ibn*HmkmkEsd+f@th7h6a*#co(i? z_b&7oZuEOJEPPqeG631tZ^H#~bimmCfMGne=HYVX!#ll*lDm*(0DN%qXJPCyN7jH| ziDkLotsC4skPC>`-H<>Vh2T$ck}w)xGT_-aXC7XAv-`#5+mLW}e7%?t4k&B92B${) z90o>amb>=d=xuQ8!wc{S=8m-P!es~#)CH~#c>68=ZZJAhZl2Wu+{+f_>Z zvknsvLdnH)iF{QAO(PnXRR(uJtCFfK4Y#a?%A7M-5ykd|f++YZt(h5!=V3HjI^SJM zRp42ISBu$udq`aS(0y0|p;GKl9#&z1ISr0~>!+l%_bD~^b zew-yRpA9vzhv{MhDKy@MA(nq;ht&h#dZxmwGMQRWiA%X?${biw-kL3dWK{vD2?lYUO6=otWT0UHJ2)0c<-D!Fpe!fn2e87X}oner!Fr? zTVtjjhFQaVBkhr%Cics{^IgcBHYqx)bE$V(zJ0%;F1s|h4(hUc>n=cDHfh(;r^^m4 zd-HVJqIH{{PMd7hF{jH;?V8_o*Sd7b}U`!Fzt(wR#b9pvJ3tjnxZHNITKp%40y}-3tji2 zHne);NiS7ucA>xp0*MJNdV8q3TM2T7cbmfB%N2|5w0TPkeJ)PQ`doA&RBc2mN<(Yv zX*CY+U``b+^q5*}Lr4wkEyH9@XXL zUEZOHey8~Xb(P^=4p3b~t$_`k-h|QIg)02pz+JqZ&ml-zoAuS@V9ll1T~^N&ENkHV znf2A*M0vfg0;5Hn>Rk@8GGj#>+%4;TyU^kWCA(d=X{x^MvUYVLZ5KAG?NZy9vvxsB zV`XZW#hZ&vyR5!Ry=bR>HZJ|_vfCC_oL#o-R*>0c=k~RgopxzoCfQ}1mKBd(wrEql z*k%2V>JU3^v_VN>w|yF`1G_MOtm%@IArDeL8uJ@FLf&_cUPnv}y}Yi=ZPZoD9qS6~ zZ&38s zy-5%THt`|b36#`9l_5;li;}DG2mkVYC|ze-LdTRPsExE?iU(!&8&=JoUjxBYoR952 zBF(VYlCCE)9rc@*mWdV1w@S(mvUtXu6{TdYQ7#hrdOBFz7fi#3mKOwWG=qk^3pXR_ zbnF$bp@m{Ed!6!U0B4#(QKNGU)9n}TgI2Pno5F*mh@=8QJs!s%j*_{jFAiRMOuvGC zV`$CC^otl>G!E7NhrLus=< zPYL-Tt4AXLbd$>n+GVq?`aB@ii^H}(-QpmyRDXua#)tYE(D+w2Tf zHrY|2aVJpH#7@LiOqEXs+Aa4rYdQdU;8Ly+6$44+c!?Mg)>$jp2X%!A$&_BHX6t|~ zp+4$6nRFkhdgyP?&;Oe8k9k}+Wafj@9Y7I2Sbw`b7K-EzPZ^|Z_sm9IWWKtrb zbg9^6w}Ob$xLZcZYuqO<3w3U#TNob7S&e6eq`P~0CZ`Yu`?nkAdO|B({)|!;b$zAL z7rn-G7@FWA44leTw96*s$W~j;?&(vn;R*{2{=e`!Z0-0T{=?;r$EPlKvASX z;iK+M#o(TSUKhkL#t5CSX=4%=Gw7`5F^-~)Dk{M3SnDK$C4k~WJBAb~>UPm`mDaJi zOFk4s@|!5Tg46dH!@yZ}zRzZ9E2c?l2i+U!S^o^01J72@9O7XRh_psC_n$Q#{$T^w zV9(hpNx)W&H)&h433T8PW`eTomo_P$t&gMO9$HQ|MnTVF0E%yhEv?}?=*l|Y`S=3b zBWpqjU0Me^$jVyKapU=Zc7VIGH$~br2)3$+Ct0J|O;Wz3k3r-%()L_W;5_8T>bPxO zTpKB!!Qxj=un3pb5wBWFvY>Ir=k@$(WJ z`ZmWdj9S%$Y|FwS1@9ioyg1n6OZuHMlTtN0D*C2;EHpS#b^^sDSaARi4w}Pwtw{)s zmoBhPBmQDgJ49u?6=>@zd z{C4jzm>@>KR`!}yW9EnqqSix;haik}tsG>tgOsWJkOj5|_lcIbc>>|>A0F}M{Yhp) z;WrnnuH$Tkhm5xmP|R_w!0zscku1xwNF7-%tWm*16im0|LEEe=ih&;zqDorU!!V% zU4&cRZ5E+dezQrqy7F%ClJ{W*by&F4Sqnqj^_zb{mXuivAPUXyG}xVc_^Pk?hPwm!)o( z;1-l`g_H}PL6V`+3SaoyL0_mw0H4BLdP}D@Bf`(>x=Rq0RGMie)IUA<2bVlv08Lha z$-jOb&mG^1Y(fdxL@!*iu6HofwR4EcOzz6s;DeL*{kxXuC zgS_(sCwiGGxaj76kwv1DsUVTunR3D1YT5bBlnQda-Y81`?QWvPEJPFktS0xy;ccsb@)!9 z@8fpGZn{D}p!TdB$iznP94h2ktP340*iRI^UtQEWU0@@PB-?sTU4-vctWVQll&c2g zKXAl?-o?{m28Dd#2m$|Flfpz6|6iSp|6Awcf6>L&%PQ*tM{Ur+HtfN_{3~)+E9fbu zioI#$GKWrl=|;?J%>>KU`cNd!4-&!t9g%1;+?`5Y(eJ)agc1|0mZv; zIwh_iEj|Hkaq$Pffv=J01h;GOIqKc)Jp9qmW@m6P;I!aFU`yxs@_UHua~Rpl^^7I=|JD`+&~3&YEx!;<-i{~QRJY; z_ZI);azja!Ukh_8hj-}0`s@ZmH<#Z1`5G{-1uxbJEDUUjsdbl;uk8RQEOH14Vj)Kb zj8mKPWi4FDmVqE3_G;90rH8(+ZSAqY(6_jCco(i?_b&8d7}xKSF8o-KQ;FpMTOXT^ z4%id!Ww%2Z@&Q9RfyOSPm8D_pxbzct~v0U%g4M9Hmb->lc5j1QpERYEv-DLOFV`yAluP0hp`B?3lFVRc|~Tx(_S3cY5T>!zv7Dzu_x4Sw{hB z9;bkSwW%s&YMy*t2Xi7hEHtKK_IZxh>8UR=GHsM_D$ba`A+s+!!U{8Xoq^%*75Gbkf- zG;IStTIe>KNMei~-eHH_o8e5HJ{wkZDGd4p_7(UKu+0uP@uhA-6xuVf>gI0{9xWXw zD7{3n+?L?6SQ6=UK%$luOvW%aW)qA>9NKcrj+A?*6mdGgbLZb}Xzgs1h^!afwn7L% zbO`)%IyyGt$zgwf&CVR>ka(i z;8$M1lPB2@Xt2gve-WVXz_w0Vc`)$@(OM&LBTN8Y%CVB&o+F6M98st&K~gAGZg@)@ zVr_Gx#j>4iBpINijqv#e5Go`mDgMcb&epgl&zGaF0UMOFAa|jyf&`)Ixd_}yaJ3C@ zBClJp@+hWUz;}!yw|%9I#o`~(5l0}R1cBL4%DI_Jco8Ex!j1SL2|+35K%3KvAQN(C zFz^Eia)+yA4@x6fK1^t{6X46U1kgag-?L{nNF<<9thEgPqy-ZLqfI4-eLf zZBuW%?LmMQV?@(SrWm)m^5poQbY@5HJ#+BCKnM#QroxxAVUV9RY`ghF|3y=6G{d-J zp@&UwpCx^zO$7Hz3ukN!^yLIzJO0=i)Rqjg`#$YBq>6pou*lB)wB(U0_G!f=J8#sI zOLpF;Et~AVQ9C}_d7rk7vin9YIc4XKBvzR-dqXjrX~~k()n*7S)s#nQq-T>0!3A0H8qT>2p`{`Zn@ci5ICBhD<`6;H4Uc??@89 z^P7&hQ%l+`{}=xG@7i9%mY;(036UPusnB7j>~A@2O7UMqA|kHO!| z?2B@FG;DrjjpAsYJHgYs0*l&SbgHo2Gvdj-fy@C)RLWsf&E2C>2E!C-6%Y#vzMU13nvF7ty!JM&CJl_Sfh-NFUystgaBe>@_KdVaLG=?_0-6RDs?iI_{CJ%7@Hz#kY1XNN_=KVq-3glCYYY`oGc-Lak;dA z(B{Z{cTQ|$wFh)kC10;`HU|0Xnheg`V}HqiLAWDXu2A~oip6AU30D%WT~><3E0WTj zCGNNE>FgyAEzOd8Gg5-wCitg{lr-lx)W`&tr!Z_DD?N%?Ygy${%o)#0PhrfKR(T5J zrnS<;n76dm9>=udt@Jd;?Qo5!>EA3@d6;2Y=}J%5bDBj@dd=uyI5xb>>l&s>-;cqt zsWodfIU{T7m4IF_`G<+b{#*hb8iAyBVjI1+FW@a`=m$dDvm7qGdsfnxuPYm8>dJnr zsw>;P69i^K(T*YIN&gi|5FL=%)E%X^Hq9J3C5lD=z(`pe8&m>myetWz4bn(70<>jj ziB5<>Luf7@>hf|0*RQA?lp6KyUHc()))GP?|2=ojm8>L7nq0Rb-pEWW%a`eLDmf)4 zQ{|{ffFUE45GC)q<-8)xp5Ls(i6R6S}j~i5%O=>sGzx zAl6X@nqtRGS8#N=K{~^v!70%dCdDp-&fusu*t>$G$9(P#l_q1hJ6u{!%g$iwG4vFJ zrO52+3RMqAP-hT(&NeC+($$i%_q3r+0aUK8mjo2IYrwKiAD7`)>Wl?Y~=j<&nMLuY|zO|d1_~I!D-$e;~&*oEfN;Kj7DaJvIV!+LHclEWOZDj4c7z}J1E6 zC-4CQfLUSBNwPhRQneFri8EEn4QHf^n=O0 z9lP^A_yZLtt(^)cJIbJlam~dENQlxF zSp@%qe{dQs_FEC#)B&w+_w=|74L$56PD~K{Wjy)xab{T;*RdPjJBb$t1UFV&+|(^l zI9{6%=VIX%o)a>YUC9h60P^b7?1V(Lb9-keimBOhQnTOam^{GJL<}5!l^1T@%$EpT z%$utnS6|`~!1>W^fIUpHw_u7r@`6%Ocv1NV0v4bP>-^u-ijqp3P3BkdCAde!2=qaGJ>Vk;uEl(&sg(NrcqA;C4ED z4}$FoXYII?%lpYVd0e>@%Ii{^cp{_#s#xxs>Aeo=DGdcSA*o-1sP=G`lyd5NAhs2F^68pozcWkEU^Sh=DnCQGaw8ma z`+xNvM4A8*xj0}C-YvXOKm6e?lyVQ8p)2V$Ih_YooUbFiwgM38(HrstB<88&wqNbj zGFtv;8NbbHq+3(`glVBi&023W-SNc^%N9Fc`JuB|Ppw1S{s> zpd%fvgOxM??k08;IbIS^VQezz%k-DufZd$HU0lOZDBJ$|=fDjE`yK`qhmno^`{&Uw zzx=|GSB5kSLz0I9U->3*B%8oNa(qjIfZENOV~Wfvp00@W1KZ!DA9w>=c1OIb@a~qF zFlh-l<;PnN@3cl#pkET=0(@A76Cktq6P%)d0$)XQZg&|Xb(|}D_cC!9Wx>8I$QG-r?Dy4}h z!fl_bICYLSc|BsXmqrasccN+)bVSX!utUF%%w0>m$k{2gIxWsC!AyuY#vK||z7H`# zaGSkf$4R*SLMNzPtkOg}$;I4iP0M17OdeK{EHP^abuvL$cHxv?ZSZnWCI}zID5XXD z&7?|o5e0l?i;Tw_{mR9qqta`7J(miXpaE^!)3 znqY@)0vQ3qoa+bIjFqHhUdb`ask|Z6pupD49$_PSmmr?}j#fK(vs^31(wH9A&^=YL>;`rycuRr z2tAdkSTt{dvZY=FqOv+%YSk9(=YD9sL<6hTmQ(v0Dg%yeT1DVN1q5atO&3>-%LNNH zj>^(WELJ!S6$Uh_-pVzu@0O+AL%p<@`V;B%RqQ_i=O?o!`ZD;k_&IRqgLc2g>?+ ztPy#)f8Z3|i&fT*GiFOV*YSvHN$9}oaN8g>k0N)met?ZewpGL^d;ms2e6=A{4n9@s z0HU{4f|%saizisvw3KFq2v$`b!@E~Wsh?h#=a zFwA_WC6Wc9W)x#hZC1>p?X01tidpCy_@v1f%0ZKq4q=d*MVfUo58a!acaIm4-W^SY zz>Odpo41SU(OkwNPfVd~d3ejmbLyAOMXj|zp4s!%2CpNZdr*r-@i{E!RQ zy#NZe9!P;X1@M^uV2qz+QPq@Wt^c3BH*szwNAgDbr|64#F)`E8yDL(+!_yHy=x*Aw zq$jHT+izaHs3?&oiEUoZL$*6!^xyt|nK%ll6R0X4_D=7PMHW#&B9Tbs4Ss(Stsq#k z;CgiWIG){y<6si5o`Q$<6#4J7=`wg2jX_pO{SvwAcY#X!k~s$Oa3TwWdeeXyUF&BV zXgd`9neYY(AdO{+&is6*{9M-HidVDWrSwyHon!D7wWegBY?(eoYDus*)!`nHKL-XJ z8fhVltd@T)KO*w{M3?34gFPQ1S;r_S>}PRp{SA$bj%c`BPGPX%du^i zT?&gZ4cfHU#Rz0Uz<);Cn2y99QYyE+N|!U3$1{YFG@y0r?PSkQb)DLjtc-^2BvJIL zyU2(MCiNC^gq(8-JB4l<_iJH5cBz#Q)1RSNIhjcREvzc9cD85ygjm2U`UkaLU+EG7 zY6a?;6g0Z`a&a|uF)=jYJO37_A$yM(xZS^BBESy!C@N3~4+i(C)s1^8f^U%&iBVnn zL?OI`r^>aYK^?qnZn2lVEc2l1v@?%wmK&=0VQbJ6g@uYD*YQt<`wKRruj z2WM!N-EKkV2hHv<0I8C+T&b9VF|~v(Y6m=76a)1{V!hkqv%_jK>NPx@4tTwR|7Ren zb1bBBQNO`74;R*Qu!}jEuT?GVkYX8WlR?&krdZhX4Y|<|v%*@A=QvH$OiwZqGEh1xC~DI;O(_UE$MowxUnyG(hpy)fzVIU_AO1^{7Hqf7NN@>16gC1#CoF ztYIX^6^uP3x!~9Kx%yR59^KB!KWXt=*^Y1VLca%_A?EOMxf;HBk%(k^NmVspyfCV2 zLU>L-BAlil{vh&?6ozhYvhcAXG$7_J4-Fg+C$)?i4QE0BXNiW4nGmILx!6wdn<&?F zkBEZ2BCdQ6QDOvtz(1l&D=m8aOm!f<6yYj_^%U-xW_s7)QSS|Q9Cvjp$`w_Zy6Pic zr&axO5d@FZbujqy1!%$!SWMsr8L5!E8|m(mML^oA!Di6fs;n;)OgelFLEaW`ojTL6&`%*z2}D<<@R=d zjqoG$S0(;u*gI`=CxK)j=!ke06&o9HyrC&d_nP@9_ z39zj2>Vo>~>4wQDs3Vm7C`6TQTye5i~m0+hI;hACvWdWseVWc}H8s1_qwArx#;VOCTUt5exg_15sD zZT3`!e`g$<^*FdUyUc*VVmMV9X0lAC-n%7r8O6r*WSUu%ux63RHeJrVjLsWA^=w=L z13vuDe%XzUCplhvinV!OAMq;TBMu@KoRvBuWy($`xRwe>Fb}^{l}QodkX&fYI;%W`Rh=GnK;im{u_IY}(rS$e!xWi!(ex(Cjl$GvYQyPNR zM*>2EjWzTv9gkAkZfKQD6?a$|4aGgBh-GP+IjW~vn_QYp?JY?D_t%gnfwO4(h|M~b ztJ^%S(?IZ_5JG&$@S^SX7#>uLvK z0##b8Pw8sVtcA7~YifqJnY1bCY?$N^vVK3fTDB^g1&Jm9w1f8mg-=Z=jxfh*<=2*B z6DqdKS?r5tuh|iBbXgJ#&@~!KQPk2N`;Q?2pt)yYap(xGX98q({~Gr#k4Mi zDcH8Vqav3QC0XZ?)0X00=M(I64qo6I?6V{46Pz-^q}tWdXpoOb1(2!)V?ys_tISw? zSvQmqZaOO+?h8ptTQ>YAR562dtEH9!Ao%?TYNOd8YbNAChAOm0{AHCb>2^&7J)9)O zPqJz{Feu0macDzUAq!aZIr%6-zEyngPT;_~n{o28za`77%-0yCUCY@ZBa3(+ZXkeX zC~t~b4muhT=CJSg3Y6|oP3{ij3WbL$c~ai|m}LPV8zBkYupE61=IbT$niewz{)b4` zkA-oq$k{FAwV^3%K&%L~ahvFD{*@i#d>aK>SYUBF#YJMn8S>x<10=d>S0Y)my65Vh z-c78W$qPVP9;aY}04vTnD$4$aTrOOoT5@Bzx%O(w$H2*5r0-|HxnC~sNDM$)dsmwk$JONMQlh#mN0vm6Z z3VR=sM9Ow0H~$UxlL!o?h)1d#t45HFXe)aviw9)EN-HS10KynfV^}FPC{%lj%`Be0 z$a6V3LI%4fix-p`^3wAHVfMh&=-5zoz1jh27>`J8P*Z-(k(+9Hc*>fO=vWejG$mt6 z8dyjlB9N$zj|iWaagN~s=!z>D89tpLBCPqeA4!|+973Cvrz)f!#7;XND#-X? z?$IT$^hECHjIN3a_M1CAl%fv2WeE5zJaau%p+MwnIwH5SM#K>4UWU5aEc3# zxZnYAbKJ(M2-(}xA+>`K(mLGg9O}WF2cE~#oPs`(e!#bhU%~XzgMO$Vz~O%$T+{id zAuDinSYCDt({RSP-1*X=qyZL|%%m|gg#xPnScr7uA4J6MWSllVM4UFNxu)Z^`FQf6 zF^~Cb3tHpEB?5Q0?AA6z%uf-b&7xCgi1{XQDi50tuUK{rLgN%`$5NaCsZ6TMl}_Z! z=~(^MWF(WMC{8a`mRP4qwNHklhlgkpO_8O*n;l{_Bwa{rDgf(0w1HFjG7^bXh1m#M zF&J^Q14V&Y(GDrot}^a;M0mvAlW3py{AovtfQr~^_Fk3_cekaus=Kf){3P)pD*SmkLky!K;jVVid zq&Dk^(ak$#Hj;L!{+}zUasI&IFI=4)vPz_PNas}5BTAdbWsTKA8>Bc zsXn=(N>7KuFCiQrlwU|{qzL|O1?rs^|NI8Oip*{kxR>z2n0!oNi61`CM#F=@|L~8$ zOR9uX$L-TUU`t{`Q3!!ONzYIIq^3yYqxpKeup3FpR1vjV?H$vhSsFB390JZs`e2gASb>{3@9R|qqoXwYDOf-fh zCZhA+2f`97D3}O%e6dpt%ON2t)?7T%kT5y{QqW8SQpqC)<^Tt_BqC^$;x(E>kyuY@ zUydXKW#U)EFw%}7*1X*X;Q@~c>y;LNM2ibG3JilYs;Q%f@j^>NJTTs0MbtLn+X1q+ zS>~4PcJC3%r#9H%|IsMyv;jdhHt^FZn>ir1ypTV1seFY3^nd-6SeqX!P|=F@t`87d z5nWDICH8mI;MD|i--s_w^&JP>$l5>1QKj>f@|e>RCn>E;7ks1xEOqk)=u2p4)oz&( zkOPc{FPV@Sp<@Q;v30pk z3E4Qe87vo3;?8KecM za?KlU2w(9Ibqj|}ExxhvuqWBr+(49^Y2eZ3jvBa7BCPt$$5tYI%{N5c3r88jU8G8; zBYq3(j%An>o5z$irr{Ke76^`e@uJy?^15gvOtuRG&ACwNnPZ^&F0rTSI>z({0?_NC zJDW=V;?j4CWno>Yb?&uOsqzJky)cwHnIK<-qltNaNbs40MFd#520u4VZ`Rf&nytB*S`@7H-n>ULP(gLsq!S5VFphT z47CefYzJGy7*`?876GEY77ydu=a>J{&Xg0*i(W!0Ac&fLheHol0Lk%=7!r!y7NrU& z;TL41;^HV0$6-j9Hax1Tbo>NsUiaq1^91%sw(QYUvUs4#JVMdNNFQF2wQ?D$9O7Kt zBf5s6jOrb=+a2VNj|Krb;iiwh0S0Xkp2CGHk~1K$_W=rNz0fROm5hCBa6pabYU#l=xhK-yc7aOu3?<}h!Jr3+-MsxW!fi3 z@C=a%IY%L`@reXS6!wVGz*rtNTe&$hvlLQPExIyO8FG8f&m^E;hZ08KEM<8E3eh8^uT~4_$nMeW^0Zw>cb8>H!+Bf&v_qbj9sB;JmW%(NHKEW9AFyQ5^7W5 zfZHV(TJ`BTcdb&C?28%{Zabk0c!4ru8upV|`dNhS5trAUlq?l{a&qDLb#z zOua0=4NjLMGP6?Rbx}OBFL?%PCc~OiadTLJblI$|hg<@mLeo%Veinp7RrO965*HN> z1#Om^rPZ+xTfFeC2eJ-1LgGl3kvUrOw@O`Ow@h?zv2dQPiaSdrTIVpub&49`J5@d4 z&Y;-lkW$cj6KKimz6>#--7L+s)BupPGQ}Vqv)l+@2mYg6V5x(OWX}xM*1?M6EelBP z(e=Gr=ZIm9&k$^FuB+@>xoZ1%mL#z%WtM^eSu3QE#q!l;mqvl@2=OsV+tFqg*vx*t zVf&>pPQ7Epgl(MqpS7A9wkvn8Mn!Lw0<5w(Vyl)rcM-N=*Y<@KbJ`vibFu^)@Z>vO z`UV<-;{gG!+PW`G1shk$C}x%ECdj-d2IsPJ9TZf%Neewckk*qDg?=ciR*`*AO)&u4 zaGy0+5d_lxkUwX(1dA!N9o%aG!@WYeET6;0P?ZEB-;+F?@{1%HT!;o2jvCdIEVfcg zHufUl!#hk{=B+O6Pqufy&kI{4B+s`5#hgBGr-nr2)@#S8WDg>)<@ zSlpj1kW>ex%JkMgVjL-8dIiLupgg|IhAGGo52W5?)aWTC8>2oKeB6SyKmbInJnECG zrPkgH$&4+G%gR~ssURav7RiA@iEDhvl#=p0f@3I$MKPNw=~u6j?k&}^+Wn#@Mz{cw zz|(U}0wjG(@f7rGs?hA>ED@F*jJM%+%0;l)erg5+%OyLl7%d9ccw4E?lhZ8UK&~S> ztVDWWWUfiP3G$(aZCJ%<Oa61#g1>JJW^4Ce00{#mW<9L%mZ5 z>L#HVVo3uG%YXfoS0fXNuriE)_&>n_QI8DTF4vzC8(26%H-&G-|1#OC|0K)O@^J;5 zWYZ8J=@K^MK-X+~vjhMpwBZ5dNtGGQf+BssB>-ySR5Qj6&v{EoRmbUOu*k==AWS}< zzXzN(FG~31zAEbzqRD1g!AaoppK_f|n--upi-K)>GZS6Keecw}18-3($A+%guN zzXxgs+uUSKH#AmU<6J4O`yExEc$*j3{pLH3>!$b?rI77wj5iy-PRVxibpmf4NXR?% zU#gSx0_3w)nox%KOkALerot0%U4eWB85?Oj7jdzylwwM+_uqgPK~p38FAimrB|LC> zI4;gMt7NhZxn?kf$P9LK>}RDj!(*E^G75jLxVAo?hpUdR+_<6_RdH0s?dSB8u_Eby ze!jeZ{pu14BkTL17et>Pg5}rAe+~vMDm#vX9%HHrf*a_g)^a>Txu)eRT&(2h2z5u0 zrLu@VqsGRtHM?IzYeH$902OQKLK^jzUHte79{wOir&N6(UuWYXw^l#XrPB1a^<9jI zZt>$JoCo4&TlEz;Mo%WQ>3`t{`N#3>k>Gv~mvdyXtR7l_PW}i6t1r}+KQCv4Pti(z zj8^mwcM^(Lv*{Eyc3SJzh%>v6>BH$`w2G$B$hH|&*)J4u!2Mj{hPfeOGUDua|D6W} z%MJvvlI}g1@ta0$meN9X++aCuEL|m`-C(k{8`R%IUfFwM@w2aDtLrHQxxB! zZ>uMUPo=2pR`NN$L^na|hCFCM{UKF}UlmWN%`{w%U~{LMVE87UQ>2ED-Y}kpeTt9> zT7St|P<+P;e^$S6=!AH5OjA@>-HS)(tHoEIIUcKzVjS`N>3W)eseL3td_rv=tmt#g z`fh&{^Y{}q*dl6cFUil!Iu@y2h+h>W_Irq30n7HIwFGi=hY-A;TH>5yQQ`%&U`6T{3`0=dmkfa-aH ztf~7xcK`Ho3~J~r((Qwx%qAlg=`!YzFI0~!g~gWwhc8}eB-;5Xsxw&-L)FE={+p1# z2YLrnOLqc2jjl+1kd=mT$H)i}%F07nMj~LVG>sbPr`BIV@Hq-U!PLY>ie!kA@vK+4 z%3VR}oSh_R%RTij;dSVsvW5yC^6gRGz=>EYuUF$cIlbPbi&?XDKfn-q#l>f}Kz@B8gG7+b5DXJ?4=wuYf(|3(<37w3LCIgM zjgcg%DswjbNbM7~^DT17AtlWoVpi#W(nuZznH0<{?nja(HgWu{Qr~?0b0dJBETW}2 zNHl|~1KW{2l^W@6@O&R1pf!;O!A0$dMqsY(meGJ8^F1jB=D!W^?cJZ0bBW*lZq_JZrLWlo)#1EA^l@>Q+Hg9s(?1VQf@5$7?-HHE|yQ*(}7wpQvb>p_juqA z#o0hpf=kyYI3nF=C>1f6j!nglg|cEwKZRCHTAn=O9UD7ywD!^R30})jlnDJWik&IN z0JgQF9! z90AcS%MfwG{%ThY8;#34KBj0o$9|2rrQNb_z|vCbY8=OH%euXouW^wKgX~Pz#yi)J zNBjAFHW#Bf$$OAGK&7j$Y4FJ?a)r!5dF|pYQUslZ65ozpC+H1vEg{Eyw23Q%PND_; zn(l~qLAr0B9H&nTbupV%=4Lm^_XJf`L#f4<_1r#(5{S?a2rLMf5z;xAh;Wl*JEVOM zqla)kURgc3Ad49!kL@i#$FDk4x!OJMB08)W@zlckoDOlPlZ0J^8HZu%QjqgbOea`8 zhhuljbltg(HJqU15OGl9`iuVvrTkbJc(~v&O8ItS%|>KHIf1jCQj{F#uq}QUTv|C8 zinj+cBoR-c%-HU)odDs?1SqJB)|Yf`7jS9QxN#3fcbn;z^TZvnOO$0=LrF1iz>?t6 zDcKKX@eflWD$_s7V~wyXHaTXR;8plF!WjMI(h{y8+jI0<8^e%)ODSUP_2@M*kT7FV zec`xcc>@^x0Fb#wMXejD;cQ}C+E_%ARC5#I8m-gWG+M3)bW>k&k1Oq>B|;mgL!2oy zT(F_?=7o+K2eBL9H#TX?d$h($gQ_b#G>V#QQGp~qToz`wjT4m&ijc+B${qYoRBvr^ zb14x9RL}XA){1P9+zULvO-`?C_>C#Sw9s$7p@BbeYOCdrOL(0d9oWZb-RQuUkM{md_t`6*5_-Cn^;hz-p@AlPvrqe4L`N#XbUw_?ap;3yY;7 z-T*b_){D&o6l;vh1b{u+QYyR^*H&^SYJITMh7ZZA$@H;VYzx~zR6N19#M}hati`;t zr}Q!S6n%xDHz5&^_8=U1$CM6=$`$_plI~zkA=?OSMR_^uMZ(>fyMk6h9VQmwAIw=~ zv=D%71|$ONWAKC$22@+%Bkbjnf@Qw50!97Gjw;-|B_(X}n0=zGG>V{il6j2=h{ zHu)C$7QG#kYJS_~%zr#E?%32~c_q@(Iv=Pf;daB0gF3-ED(&T}2Xh(S(#k}N z#&mHjJ?e6(0maE*5&pIPh@?vq!f!v9#J;-`HwFD5ACsU^eXqG5bwb>J}Dda&`ToJe}0Nrf2C*V{1&=7fJ<*=(p`vExV{)^d+ z!(zoJf(wW7uIbnWj1I3|!-G&BVTGE^mJ(ZJlcH~Xg0U2Ydx19E7;LnQ@ut7-3*u5R z?gQpX%(62DcD)5Gh~Ci6z5%LPBe0%pO6>#A$iOCZ8u-JW5SRhhK41yg%#mRZbzKm= zog*K}7KFgv^Ilv%L+WB7xcGfPfTav_IvL=8$aEQyOG0=v_5rmqv_uM;!w6lHj2ioa zR3ceEHj1!n_=faEcBB&;@a{cc4OXDhwr}fiae%#rGU0vPg?5D-^k;@ueif$yUHlXWp68r%NH8#pF~#jOOv-FM*V)(F zNJ&N&`4cRibXtliXqN%uMb#nR;!ZTfugcL5X=A+u82%yK#lUjysWhw%TOBBUf~X51 zRI$;>cBu}{en=3whrpug=#Mp$;d2OH|F|cxt4c0%KR%(Th%C*>GvF(=lS zi8^CTC%TBe8}{q*b5%BgFhZ>DOm9>5OS91f!n(Shu~doOElg`Z7f~nM84A^MiEVCt zu_lwP%?d+dR*Kja?TJH$d6dEDHIj(!y4{?RFx#bMmO`0cR_K<^;V}H~M=lkPX?Hpq9xk2OR0x zs#v<~r809_*e1JcfRt-TNFlrDM4XEtYo4J1T$w3^6i?lHKZF&}8Q_N1{eWAPhJ1a( zwT>JRzYqFO66Q<~2M46F8Q8OD(nx4TKi>Rc8^ulbmv_C0avDILfeN^ zc;5gz;RHF2qCGhH+JhyP&X)Xr7%Z z!?Fa8GSTVKm96^-_eLvkw_O%&$0~Vp*>()h9xYxFEbar`#4>u|+auy{`yubc`h3m4 zuziq3Qz_^_JJf&PwUp%pw7#Ee=RhZGZQp_jC^oG4hO%!9?7hJ@0y(Hkf)NFw?$So_ zWzf$R#Wp{M)8QD7bkwbQ6;L^WOz$Jz>XzMCOLQX#SwyS#VwwoA-ubC+OjLr_SW%8` z*RGS}=?V`CR8vsI4rG>tpXliOH=19(*kHJ)K=M8um>o`5wipWwi#XF8;49qKeuya? zD`#_1BWS(UPT2@Li~;uqDO?u8T78C5kU*Kyyg8ig5uKbxUskx*VO2^I`>}!=TsB;+ zr{Usj@UWip{o7kUJrcK1GBwp1YfC*@`Lw=w! zgBx7Af+TJ=vn?+gVfRDy_4)w?F4xG;mgxsl7Wvj?s~w_MN_U$n)s`(fZZThl$mTYh zTYDwrUg0J;sqKKzy2ZH3(ahK^VgwtWoQ!vh@1~PCN5`3)Y!5pS0Y?pP%f$5nt-mJW zT%2r2_*5wn#V&i7EODn6iL}%+l)IBjy`l(zf3?L?uVv-`tqz(^N^hu!8pkAVYyLU) z@U}I4Vtegk*zGNQ9Lxw#vaPAcgKlrkI8t)E#B7bbz3JNVa@$(i-He*NW_)Y2wJt2* z)~Kng&$l&j;u7_(4QpICzC|8oi*(zXY$|qgTLa@pb-E~PyW$lFy@sr{-9hQfb~V*4 z(vvyt_KpEO#wsXn#7a`)eqo!HXRLTVF}1 z5cM5FrO*29?Qq96(t%0aI#E;}%(m@WCq~@(79}n-*LS-*fBTRNjq;r@NHmVW7$45Re7HHW9#K1A&S|-vI(r z0KjL`yzA8T(R}}IMYusu#f*>NFK5$Za>s+gU;TQC|9yPjy=}d|zP@a|y1jk%e_GeC z-*?~Kk%(`-bT(QB)Ae|a_vEKklMDV~av#yXo%(aC8TCX8jA%rkQcb9*kLi`EexNOa;-I=ZlU|DS+x7Zn9GrB@mPf?5;1FFxd zX6-|olx`S*Nw@5XnTfV4+wZw$K25*W<~dUq#$<^(8Q;=vJ7VghaXf(eH1!hfTjF9t zlW54&_5pT;Ga19z?x6PkXdsuVH-HzeZQP;W8_?}r18IJ+aDF^oPv+g*=K6}K1)?=! zKEc&>%cvsUxBb)Lsvlg?j=AA}U<5#St^VDstGBOi-?rXdfBe|Jy6d-e6GCMM05=~7 zm8P2*KGAu*&F}=1^>{U^I>|}iG)1?`2{kfi8nH=c6a7Kezz&1f4E2)2)ok(4f2OE( z411{6=4GnMl-Azt=6_{$lWg-c-R3bl6x&`bqJB(v^HaK;i>DB5?I{HF1z1G^5LNcZ z6()LoN1VM2e0ZeMynC-r~VU+ZaiA9jDV<(MnAlGLGV!Y^I!eX;p2Gr*k6S! zghc)8s@*Z49O0+#2-{?Yn&kNZs+=ZxTsAv}p{_WMz^sGAQsuj#Y(_90OZ*6uLSqxCK)hu!Ncd*<>U=_nMiOOwE^5q0(H%LYgJz{B*0 zUs^l`@h>Cg<)M^Cn~Re__!|n%KZN6DB<;nx8Q^X`A4j}ojJfxfP?y3RugV5G7wC#% zmMhcPNTSpmt$gz{Sbh#6>F|1Y$I&F3u9htW{hL{DxzHyoTIOEW)zxSL*UZ1CfyZcC zJp;}D;*KuVqv6fJ@_gi1|MMf&0bPXXM%+!SWiZzZvzhnUgJ`*yec zrXv*e-IrsCA=#FXBObAxyv#fPY1fIqZ}kFg3oUZQ%l5@GBKAysaXN^CXg(V}!Az2V zC{OWYkpB~W6+;O9>*=a@c@=Lh7oiQpwuhWtz!%i{=5#kPwPblHKCC;9?w&h!!2 zrB9(w4ToTU%XzpOJaunIxHKUDclD@Hocp zn3)~OUnMEjTv2Sl>;5sM!vHBo_L4$Gx+d!a>5_cP_HNVy83faXVsa5p!+VmsAA0}2 zT$~1sR3ww*({#29D6Jf`#8Ja1G!BYSQST11I|!m_5m&`oo`-~RFc9RI&k8FFv{B#v?qi$07Kvb9!OeWjSh;OG(m z2hol$HTx-ZY8RLqCd@se#h2%Sj;Awm^cMU4%0h9vl2@cRv{nZ?L*bUw@pl}qV8G@ zD3IS^*6aq?*|CVI^@vbJu(65EhT8Q!z}XpI`~$|g7pUdZ0jgLCpT6SS#~y0u6aG?1 z394!a%Wx722NLHF^1+ed{{71U|8HCc!VX?p@8qT6GQ7WPXis#6;A(Gq&IPNNDahnN z#u%mx=_T<2>|#2Ue!_wD;su{z)N2T7>J^&~se%WVs=peq@?B2%MdstX;O;QE!_Ajn zN)=ZAg_k_KWHJPZROb{>jGXv{U{EPxlZtx$9I>#sd$omSI!Qe}Q1vVLuYL|-@QZN= z-vFeBteXKrUOCr;^sj^KyWkdRGYF_5qR|!*$0TWWSQ|7{elD2ej_RO#8Z&yZI@AJ$ zOJ4GZ#0^wdiPxBR4DAzKV@37}Nf6>f^We|@V00iseJzo^*|rMB76zGvqSJIM2m3eq zO7TA?$bBN;MFb<+UR)?*anHe65NS8>f+f(KK2rYvkEV!>kHE#F#E7qgbw&~wOd%xf zupT?3vipJ!`1XYprq2=_^*4c%ufOdHTcHYi19*T}5wpPFdp-tn>gC+u^>$86X1~2(Xe~-O^3?Yb%_^Rz9(l;8uPSSkg&_O75u9GVouJ9pAM9o$7rhQ z8UaA>2{&wh?n+t+U=)*{I*JiEeV8pihYQ%iq;;nEzKW-rIDwk;A@ z%MO3Nw=;mT_IOr+2-#+Mhd7cYT$a`gdZEaoJXx=zFKm^C&dEWDm@hx%?>FJPM< zbjA3URGan*H5zij2P>0+Hu0o2h`?XRtsY{E-iE8t2oFh**>2O@&$IC=M1Yj&OMc61 zJXkLl@RQ5N@>@pZL+W`6&s#W-Clo)+c;kqErBEn%-5!_rOZqXrN4s9@dQuVWu~DOj z>7ER>-R`;U7pF0{KU>K$8eDy(&Z9lm8I=q6|n zpKK}-ykUb=JUUxK(?l@(Y)ZcURXCa=JfH49r?1EWB3J)xN@g3tl9WdUVd|&8bh;P2 zP3!}M{UU0IXVjR?O~(tc*M+&c4`m@nx43SeYQ`Lg)CAw| z(1%tYVE1a_wc*8DwaxoDHL+aN@1aGaxm0?=Pm(op>9^P*qsGO4f&AGrm5CkutST%~h z6Kl1jrD90tYj}GJlB~!VP?-?>c7v%CU}_k_#5Mc6w=mKrZbKMN_7yKLhfS8VO;B_u!%VT;;}VIR!Kdi!K7vM`1>$xrWN2A}k4)A^b|_@TpwWu% z7i>gs3u4WCh&Kba{Y0FxPxot8t$n&*pmE$j%9V^J>&YI{oDJUok)41q{Ib{RQ{e3% z`Z|=AA%brau)C6Jrzm?vAz!NSmfkRxE=bhw3MlLzIyfe$O23zn}r|! z1AgUEtDC2)uh2EDLsP@+1RN;j2VTRz%Kcjc@a(yh3qr> zE%3iB^o!67aoZXo*YvSX5>8x#wj(G`_P|qQ!muMW#P{CsiX37Hc7%e{g(8JTM49&} z=iwMP7XD9SQkbKi0N9q2kTcy2e$^%w;fcI@=s0}xJ77Gy;?hY9P@PL8=_&NkdB z2xgEhn=5yO2ys(}y5n^xK%i8M)JcMH{RN?!1?HRGYH^;B>MMJ9g4X0U%X^E}B%qm& zf!!{=yrX%?3R)6T#VfiG)CUb70U^zo`StKMn%7D1NWxNgDGQ(Lu7vshfI{E0yi*5s z^2X!cu1q#GJ0jNPWz4%qjcL)@G5>A1g{4_t(+t#by0a+h_+9vHRne^PVlunctKF#O zJ5Z{VH1i!yY1fp4TW{{E)a2+vYRWr03}BPK#?=x#^jERU#T842sCtP2t8PG{NqpTK zE_D;ZA0e)qy60-L-w33*{&bg+lH=N}0<+Ip^@4S`c!fSjmwOo@0W#(in`i|>zM|U! z#NB|Dc#5Rc>?>QK>k@r%bJ^J+Ivil2eezHyI4bw{xM;-@lieoLBN98-0h#ce&gv!`K1q?cOCE1f#Kn=B_aTc;;aRxDhZSK!;4>sj;#_ZAOUrAxTOJ)~h| ztIK*CF1`j2>nT^q{05I8tLk`uomgKPLu-n5iILio?SnCN9Z_JG!kDc3C5?3cfqUzRw% z$eSPPT2^7+{7BiG1UD3tTm{=tfa^Hqar~TbS4hE{QZ^U^hCmM4;(L$FilS zjSiIx9Np+>qc2cH)twxh9*OQC6b6rtj?@WPdQzJ{PRy}3%y+fDrqEO-WuI-qvL)hy zCPXDpa?HE9_Jc0{Nu}Ze7s?O2QG!#@l`TxR4Rc?h=PP}`!+@vz*=#JYn%fE$T=&KO zHyhr9G0|ly@!MeoF$@Kv$^b=>7UYku;iMRzEiI9ZDlcOTTR0Mvk>!~o_}ifw9csT7 zsl#yzbPUu+IfS~Zaw~QiGcJD9QcxnTc+b>Li?R$W_>!NBQ3# zu%~dLE<=d}qjboW@_@BFzl4k7=Wr2S;nML_Tv#H?@{127G}$fA=Tzos_V9q*WA!oJ zs(rk~4IuYiCKy+lFHw!pevt7BZWLVw!_jg+4!@#IBu44p^IO)lj2BO+_SJIvglgd7 z{WzlJ@Whj>muNKeB{7!qB>ht75JCA5qsL${Un4?wIz(vs^bt^IJMqCN#~K6e7RGWv#DIIAk;l z3N<~ameX(&6|`ydIt-)d(I5&|U+3}~k$AE^W}A9?o{d-GV?l$#dI9{(BASUF4ta5b z`fywTO-#wDd7C7h`Z0rY(`_#cp^(y)T7zdwj+9z}C;R<(brkmj*zk|O~3(?wQ(OaS)TKZNv zoXu(4gHOS#^%wtrT!YaN;Zh(@`~)VY6Mj*;PunnFek6ceaT{^ka4TtJ$nN1y2jb%) zSwAlkyO;ocJ*5sEW+)mKLHf2M7U=jUTs^fETHkBqg- z0roDqI}GmHu>GM9*GX_4M_J{(kUKjei1Wk*ah&So%DPH9Wq4Hn_k198$LwC6{=S?| z+wJ4`_yhZ8w;NwOciVqkc3by$VJW?_e8b>a7vd3iZV-AOUZo%91Qz=-h%+c*+Du})C;stGnpGYzk@t9k?_%XE`&*TMLJrG*A`+Rd3 zwB!?kANOE0h`@>2Nyfe#T8St2nkL4Z36nF=0ZwZ;_~FNc=h&JsboFlRy`5_S8OaCCh%k$=#4%ps@D%>Vm z8=@;un}=AvU95*ZdLS(Dj1f%EqZD9hYG`6l0#==L{WwS79lNIGTl zbhC$2U6f(5_T}Uuu~*Bz=3#<8A1q15>&mje+ydkRC(Uz4mkga=>`qqHAAF$2OP$EeBUi%LTSg`#L`1&hM^*Q8xp!jXo zlF*_r?P}(bynS^Vd>Gu`47dPG7m5r^xtkd11Oq{#${48W^`KkhDP~Zu2NGpSs-(?F zEGd~+#M(aS;(}CGWz=a@6uEr`H5F)dce#zz310ION>1=Jn%B`ab9d z5=s9#7_`PHkUyTTC#}iyF}PnpzzOvj{LcR_`PuKS)e@eq-&+q0xI=>xr1fCjT8$>r zY`tpDfke2yp2w}>jLt^-{Sp4Z89d>z<Z|%1VoGuA@B#5y^eaXjt(N#hZtqFB{6y~c z#dt)p)1Ls|TKvi%<&#PHg6H=Y%53Y%&KTk7&L|=#DSN=QW z$6uq6AAgpQzskR(<#4&8cIc4+z^6YE4bhr>qET-zdmnpu!JC_3)yH@J-oLu)%iC9X zuhi%M-K#er)R#Bcx1`j`*KhlM^~2TmyWXYollUszz3RvBT;1GWzlpzo?0&qwM*q4` z`erom_kO*#G(e{4e!t?$t3iVJ zt5{pC)DpNJMBpw#IG^*M6@R-Y<7J;snEik@2fo0BGKJR>PZ4%NYe*DMx45UC5d|gN z(c%U@ym>9(q!vghqd!c8eY2}&6w&gDNAy--JZQbW3x2)&aCQB^uju2u-n(o1`{tKh z`t!EOe_mgHpl`R`pXtx#6@Tj!^6~Y5|8mD8Bji0C&!0m2G6enM54^t-Pv!{@Y<#B* zdy8p^O$;0i7zfM22t+-481W0sr`cx`?WqBMp3m?~`~}+%&p(akpZU`o8ztAI&#F$OlUurd z_|V(TsOm1vjZ8`1NV}=d`R2=wbgnME+*Icb`DRuWd4=FCmN?fOk+;Q}dCX8gk0T9qEGQX?<}Cc-!#&&zkON~52xIm! z&K<~{6FSbwd<9+M9jV-=BqIe&$908| zU?T2cHa1UPv~_EG3!lniVB)OnGSCr3A2*O-!udiid(+h&1>)sl_T_rI96e5>;lUW1 z%1^D&vjubnI$y;(Ej~Vt9uOrGrJX}17+Ho00)?xV%e(Nx@vD3`nF3>%DL*xru~)a_1gp{r&bEl{!fp2xrc zL)hGMc;Yq@PoagdyA1|N3t=I{9-MwfFb5r7L7$Ev`)5HEFe5}lQ6e`q1SWXaq~?|t z%iKL132OuPjr=4QxJ|+q-c`zE*~@&g_^Nw|fI$2m)`(nQDiF`NlVh&i|E!eX*|JoX zW$EQY&TqENp4tL-FKFe!i~Q7*8aUwx(of0z$7BP*%k;;JVRX>V^Tbg(vPRIkm;%Y1 z(?`*7)?7rS{1F-ua|}dtA;kWb?m;YnwK3R1^SpxLgAS~UeY63k309eLA{SfM+A@%^k>kNddx4U6Jg9h_HE7ouj}!{DEF)<-nrzKujm%zPD)Q+@ zHs^kZ+>aVy23s3pv4r}qcceK=V!(y3@asH|6B~LE2uv>dgnyMnI*s5V4wpsz7yGr|NT2AAN`=S6S9XPyPdPDR)Bnwd zBIPjkb8jf^hVyR(-R)#4V>;d_&f;NqGE1(74@H&oumYoeyk7*n4rInQL16wpY`<{x zDNAq($!kdP#l#TzAi+^^KjUv4yC0axF3JwkMI$SPiReG4Lj88o-*#h zOzFn~Oh-I4H2Vp|B>$omIuzvKaXh*okUJ?_Jd=jc@`pZM9a)=MtDHp z?+2f%@?+$q&f!8)9YE~z9sU%4Y?6E?KrDX(KBtJHlOl%W!ANJ(Y`pB=yhD74VR0uWb($&JQP6CwR;fL^{V6LSdHoWueJNc6yOD1E0yC_y&mSlb7j z+QJPPARs|(xRN(cK97dcv^!|=-xlj>3c7dTj3g8@s?lSF@XQB#Mj5``l5$yZKOk0w z)gZHp&`yo+L;@PNf__sEO(RrV5gg3X3Py;Jfy}DW6iR)sp2(^n(8LHAyc2$>#-v!% zU&LNaR_%+6qqEjuWa*eqRNgZ+2X$KyO*32SCuQ%#{1U&N!8N>)k((L4#-^Xdd$?i_ z+NBD9wLzgQ39_rA1>p4ME!h0xb;e2(-ZotwqIfm>db10eyMWhg$6`wMj zUEoK=r#y$e3)JV#rtMSRR)Nobi`NZU((43X#$6lBWq!{bPDp*hk`K3iu^j;@dFGvy z*sy}v9!okKl9^ms$jJ~6bN4;|;(y&!aEov}pttw~@nV$3h^DjkBg-O#rv+*|1hY?A zrr9uQzF~VFEO&=L9*`AB{L8$JSf+&FghiDk2%OGHSR7EhK zi2diw>frGP6OB^{f?udQ21y!7=WIhR8r_@+y=#OFT~dTF(wT@SJ)sd2n5w-dhSTG` z#Lj?^_2BP6{NwLxq=O&+@#DcmI9>{qC)O~LXxi?+w?WH>%jYcv3+1ngvq#Ur`~|`q zVlL+rYjM_W&h+J$hG9V?it}sZ)krReNWlQAoL>>SAiDpT;7{=a6yqO>zA+?Ni9RK< zWs*h$HDxd6uR{Kt#K0w9KL+%LT)|Ip(;|mNo=VP8h`xNGC?&tqBt)8vo;4VyiyJRdlm-f1tp`u|K(W1WYaEC? zwK&Hy8>DMu8EJ^TU{Sg2*QHPEnX_j`r=`tr8<6jT2%9Vp4=LpDh92?_l#g3! zyl3D(fsbNb!tPE>u#N~pa!((|Pco2+4ZzeU6qVApZ&^R0*%vn*lH&+r=*T!5L*52J zNIZ)WvP~wkXbj(@F%ipWSKO}(R4j*pDr^ZMq7>LRS00O(T7EL)oJyvf>_JjU@mvPa zGM1#sZ z*IO-Ilnuak>p4jn5=ER|!wU0iC%8a>8k>(v)_$#scZ<~EQLYK#>2OIErp@QGekxO$ zlqG*V<(e3TCIdj@l25g=4$1$gcDNBueKd_e2O49r1{%&kuGvvE|xftt|?b*Bw4CN!TAq3Xy+RY|q7r-|K@LBY>4`@nEJF01jDBy$4~>?~@Bt0sxt&r=Qf%TU zakI8~$UUIlGiu^$>w$cMe@ngbFkUZFb0yiBAIFUkx%&}vHOJl2pC{*hdc>0$|uuJkxm;DvvEE64fT zt>R)-W9VM=0H;v!qv7<1Q z+eO)$_*>jWIZqMrfQVDo9WvI1&sRLw&Ch`rPTjA%eCmDOW4n!*+{J1MS2TRm)qJ)% zM-gJ9d(nMgAl15d$GQ*QZM!4f{mAm3uPghR%|3M3TzQ@tE6gIGg@8WlAKQn_a$$QK z4ZEGygzGS%Y!AL--{RY_MKueE7ov&)I4#8@;Yo|RBsC-~t=7m>T6_%&(xbAk9xX13p+Is9&_C0uNl$10h!! z8LuMS{89Y6dKw|63!SgN{+B3$EC2lGfb#SaMbSv*Z)ox7&_bSJi~PTItu8?Fyt*H= zl~}~`!I!4K>!Xksj7 zqBN8fcpFpc;Vxi1W==bH<&r1u(v@RYv}0FJInXYBIc7Y&bmf}g?9`WAHnU4tuDQ!j zeK}?-yY!{=lChIZsQ!aXf0?^gc-AWHS*IZ#H?3P=@=mlSPyr6$vTdE&$WYI(24jUzjaXkdi9=irAJa61%m-k15l+4{Wu?AkUQ?=ai+rxF#v;h{AW;(b#S0o)1^@`lLgSN3d*}s|V&fd&Lr`L-Yh;Q( zVF!&P;+krvrSY(B47de5G&_6cHU$Ex5LE(xAQ^Cnk@6+(t)8Vh})gn{qHbG ziT6v!LO0cHAFaO(HI#1><74h6QjDf+s+0fX1xl8QGR8PMSaD4jTBZo|HQz>p;>+~q za}<7p9hScRm2S)d6-fHc1Qv?LOh(gI>4bv#$+)7TW1!Qo zE=W0tUHAdj8LQ3DtVT_VU^L0N8Z|ws*fSF3?0%ql!!kenoE|~_QgI}Nf629%Wwpf! zObzl$?VgRWA32tMLOt_2;7b!Sts$o1%H$=&fDlcK%*WMNnN=^p2uFqdf-7MqA}$Ep zN%$#Jh0}4rMEOi+C ziAzvrE0oWjqOd5L39TmBJCqso)qXmS9%)yJU&P4bEitfMbEuVZ0sA22Y8kpF{y8zY zE6lpMBt8X2b6_;9+SIY+$n8UVxsQmv!3x+;oP6f5;}!oJH)ooZ-JJYJ#}jJO_XDoO zF4TZScmPn~Dt-l3kPJJY@4N8tkju$Vke!Yxu zDvOaP43^;OjS_@1gb;UWv}4J6Xs4&?*P1a+5h3;&XR-{o*D?1CR7ZYB;m|Lz$FEX- zNaZi*_6WzFB2`xeL4&G*lkBS~JUTO?ZR_=wsBTvivN&9pR=yr&IiP_YwH*h@=IM%92L^HOV4`d*Ntea9|QkPpJPN<2G zrHu24T3^$xDl8#oVdqCnEaIAifFpxn%`fW??rD!xTD^c?J6m1SU zjO}uYJXyMjZFt7|koR7Dkr-)&fDd3}8irG;#a;^0>5rHRiB8)S_Y zaX+LJi(2KNPIOWEuuk;jc3?|#1Y!lVguPO@>nt*lTS0G$kIlr0!irPj=vLi}YAlcy zOOETrxHXS#HM;Mqoq(ds$z9lmLBIK;L!t+RVcI;YN)JV+xI&ui!D+);^%y6ux%`l+ zFjlpLy7EB2hjo>KnmMp5jBL=L!=Wt+sqoxZ#FnS}W*^<^Eq$`5PH)}9@c=)h1N`l5 zeUIBHeb4W9cj$h8Q{(FAHxE_u{N{HXKEJPi{rI|j`{TioF=wCQ21<+Ek!_=0oh;0SZob8oF~{Bz?pR6Aw^g{R1zYr9;(X_RyS@UgxC-z5`=DK3lP?DmE{N7 zxwH6SjapNBkYjrb4;BoSWQT$t44N%C_^l2MuI(&2_hI{q7TF?ei_T%bBJ3BX+@h~KUv z55#X*mIdN2+~fd|dWjGqT38Z5JV@o!pL%sY`s3kh9{V(?@0lMDUgf;cd)uJH{IfoO z*^F^FG6>Z8fSl?V7#xF55_f{rR>D7&Bg75jHN{Foa zxuRL&PyM@FTw5&(uF29yWCxAo-bnHjbki<~dp0KD}6)~MVh%% ziE7|xS>X8OSCk^-EtVV`wSN#vBkA5Fb~>+v>VidHj|IASq2!g@U&FSFSGTvX{*R;; zk)&Yx%nPYV*Y;B~L%gJA$xpoQI{C@q$2l@Y+_On6?h=Igeiiw_e7~~vV0PjrJ209` zL86n3 zt9|JsHArgA6&hk{bv9;Pb7HJ{5I7k#P9QZ@zjYB}hPtT|C1q)=sPc?R_@{7Q{O6pz zwRupgOEQ~>t*T741;~VSMI{`v3@_KO-*?~K$t{8`&dnC=kmHc)sp)~JHb^4=KQ2&V zlky(i)MakVrx6(zMIXfXTQ5?D&|-w*Krp=?H;NKpmqj8 z)ki{Aq?s$Css^KFu$)JO5fsutaX}bYQ5ZdrR?GHb3%`w~tLQOW(8uUYI6#4ea5(zX zLQw^LpX25$6jLz2;4SJR{>}J;-=0G1Qr148FMq5@C_8c$Uhz*$B;j#AQ~gBLWZ)lV zd4}<9xn#(q!O6)5eY&So4S*dVaWCY0JVPp&FBUZTdfbyI8B&+4{T%6~|`eMV;=@w_vd^sA=raBop-K5i zat3ct*vOo+36jxlxMrDZQ6R7V618Q5`D{EIeC>9i#26`Er=rT!4u<}KYoTe{TN~O( zCTkes31RNEG_kqi@$;oX)(LX*S}iki?O;YN+MVi*WLcEB$EvnNzD$zBQRcWf!?tVP zb#+E)hXjLM+cj)sTLWQ}OW)sWG1Y%QxH}4Y7r8jz2K!C$yTifgwMc;40W4MOE z*6~5dJ{J>2kpL8*2cO$E2p;!(0l;`yKw5yjldNE{&27S*0_ej1*AlEKcwD2(R5aWq ztH6l3rBaQEQt_)r?=C=X1uo&Lo-0UpjG(^~kV* zEpAD}33Nz@J`=SX0d-4ycerboZiu4fXhG@tJ4cB+Qr_nBa?l{`;OQc|M?JVC+D%nW zrXfgmZYx5@j|bvjT@$#i3`{&rqSG8(a*df?9%%=NiQ!|>hbqvq&VjuPii&FxC2Q+h zbW})v>GFCT=-atcTLrkuR6)gb%8Rv$^~=ukbuZT@sX%h>?0Q)4({QWV=GR|o**1^v z+$y(ubf}I2*fc?CwbAELzs&{)hLq$c^E&*K2-|2L6RKn z_oj%ER=Z|z$5d=r7I7V+d86kOtse?NvgdB1Gyx82njav3OX)k&UB;XWy(AJVs+NUNC@^B%s6?F&A}@Cu zHhFEV@p>jmNjmhc-~OgUY&pkMl<2&I4XMy^Sct|&hvMai-rA+yvfM2Wb4TGd}ZFlHsdFA9JXm6nd7k5Ue`wZf@skO z7dU1Q$%4VoHg8Z-;c1ND5sjBAi5BmC?`b+XN#Z3Y4@n)5Sp8|c`NAwBDm}ubd|BTQ zW)16)*pgFk6H9AtqsIJS-gs!%_vJgh$6?*1->cSUU@ib5tA@wR7fl!~@PFiWL_bhaJ0ea3?wT@Df6sEdEYg(NHpSv~+q*hKP3p*O+3Cq-aH6g6OSa1}Yil*D{Zzzi2rZN!_Ks3y8x zTtco0^Kl1dJArcfC$q%b{Gzh=rwA@3f6;AGY=O}BM9b1keEr9RktuA|Vx*?ygG4Rp zr#T@)4h|o^!Y}gHWQo@Zw^DD2FY>8sGrH0TkeU`07*0z3U*}sWx%^0UYL>a z!tiaXr$TU7gTe#DkMr%t%EGSRNPAysOO$$FEWG7M{H8~%;&X{%O}<@XdCC|*VL0;e zwU|(tb{{uCi}ALH*~Zhyf>nv@t`@p|3~-Xp6<+^@bH(J;DOFL#AvWn%(a_cNsHD3Q z-W2eXLZwVNbwmNE;iCi?Pxl6(t@hw4T&NJE0fkl!AUNZ{TI!^= zNG>X6>V|}i zB5F0?n)dtK#^zh1EvspI>`QaYo0@~_s(IzX!c9E|BD*Un5o%Ux&!L)E$fE z+9=zL1FJN2GqGSEL&w2Fco;&K~EF$WL3sh7BR)R#mXeziO%uO z4WYjo`A|R|48DA6w_m(4HPDx&e8y*H&DseD=b-qrih8emwFNUeOrN)w%U3|;6SP)) z;i`tN)gIU@fNckeVfbRTIJvdbN}XOd2g+^IVpEZB8?@ILCXr17<82VB2F!NMAx=!r z%?{GkG##xVE|BMh6u7+V7H*I_GfOoA5NTBw?;NC1@v1n4FI>|-aWFxi3cg}akAAJP z#ME7RK!iC`Dk!4LurLLehEZ6DM}B?s_@pm%>f2LD#!AT0*cv^Q=xteR1|%fZE{}+d zKZi zbK)*OddecgSe=+clX8cgz-HtKpU%DI0@3+)&iT|bxSi>FAUdAW$x(C8<7BfC zjj{{%7>4Zd*=7JdrBu}fb>L)8IBnk`KY>HYqs3+E9S8flK+W0g)pZJPVO>7GshFDjpqUXS z`5|4-uqpFZQ67$SXAa?9&V4xsb2;~y3?8b#5>C-M&hR;earyM62re&1%DFFx5H9Dw zl50>KIH&L}XYkCe1@g!W-g54%S>k9QaI1jFmc(s2&$)8cRxxbKmR*viBly1+-cscX zR;^^zJVFdp997pl6|iujo#Xc?hr@odbH3=VUc{EMJTCECiRSsyTJk(KlpWL3Du2z7 z)iTF%!o{fvF0eauBeINv<9MvR1vutGX|u=kZmXZYrAxD zRWmlrnBI0HvnmYSOk9@pz)eSGIS*`EEt`tTavr^bh%EOlkfryPSe#v~0*T2w*aYIm zu3N9GnaR6ZKN9mS^}k3dp?=k_#K8UtF0totW|6Ip)mRi(1zeckg!(a9{s4G5BbtoB zs=YNDh`;hj7D=32h`wqDIq=}5p>?#S`lF_a$SeO*mEo$PxT{7GuLRt*%gep{$`W>M z=U8G5C=$z5C60rX-szftwy-htuGkE@f~jE z>K?-yrg}ofdx_yLmAAR>pO|4_@jCEt`YqL;%6j1X9_6uKad)XmuNa~$fE3S5vXs(@ zF7te@$~LBw8&OWljlYX4w{3Vl0=GgRo?J)l9Lqi(Gl(Mz$Q zdUFhK@aQq=TyFw}PF`#e z7#)Hf{CZOaNCcDRulMN9A<)62x8!Ox0H9N_g9nJ_hHC(QF6Br)plcxHp@<8Y#5{Na zS~=>W1UzL-DhYd#hlCaPFbU@}aXdc*>c<1qm?A5OjH9Kzj=V4zAXR6C6`^@JTD&ye z#06d0gTvQ@|0@Z+@K_PUCP3csBcKCu7yh+$=u#vpfUk}THNF1ZfF=FaF-^Aj0pI&w z5w}n;h{KwlOBhG$h5SGcB}T*%4pyq8`Z+(8!yapc*nOSA?(3lc#s|CLV!2@<)+Ch4 zsA=-JNKD`&=)V#ZAO;&RfKP~tViUZ_vSUoXFCG9?Wk$JJE68y!P3~-1M~Eu)&OQ(N zSj|ciGit>QUii&&Wb+g<4-7TOO_fg){Wo%>U9zjfz#TQO|1rC*ZtRe?D`^L9yRMU5 zUe}?Ui68QqbsSXEWL+nxSzBhYrecVErmjOAD&P0#vmbLEZu#}WT|!J!6ZQ{usZrOd zDFnF15~b$4y=bD;(EeyHF&%Gev8`>^SVU1JeCQ1a$+mt>Q56t8Y~W2s6*aI;8i*^Z zf-q8Awh&p=6oTr+7F9t{6VXLg##PqihT@AFLcbEn(-B5K1F&%WO{yfy8B((XfIt>2 zd?L)Lh9;@wq8w~QO$JPfIrv0O`H)DaELAmTs`kKMQBylWj7Q*<4c#}r32S@k3{&E_ zXr|p5_*=JwHjDjTTS33=O8o;$K^j! zR4K9{c5|KtDxg+GI&gh}pdXD96y9F0dgQ;>yb!uFxmn1i-9AzP1QgEQLm0&6eOq$H zo{ZAoHIU4N1&gk68rTR*B11cjPXbt6)w$4>7=UR{u2b+7g~MpUAeo28WgBP?SGe10 zx*m_a&n@Gdte9yA4k%za$XAp?5aH^g9;F!$&qEzrV;x1y!Rr&Q=iME&@TK(-j>gdt zgD%2V^!SxVlzkuo^XJR!*RL*v;3{Z~t#A`AmeJyvUaDRSwY2~CIeE_4lPLK7G+IT= zc{qrGnDj#@Xxk_1#ldVciKZ)~EBVB;pT}@bc{1*_SoXbN!b z2X4Kzqv>EajDq#*;k-M(trFkVGP-aZv@<6HkhhR2LV9kQPrW*tt|#}=0vHfIh_6mP zoJL>fU{T#_S5Im2swKK{8nS&TprkMe+;SX$X}!mj8{Qh!5sqD*>Oyz8cqP?5`}ClP zkr_2UFM~VC<|+e5ZTvXrgalpHF2z}N4h*8?=u|jFV`5&5RWP3|4UAr%kEX#QoMOj} z$7ACM9ti!L7fGvUl?yGW;jDa0)5Mfin<0MFgjxJf3^^1_Sd7+oC&IA_#)iDB!6#@? ztW@0M50&EyTIR1-xL#EYxLED-)Fdeen6geMcuy5I9m+{3;yNWQ7Yda~0!NmG$IJ_%_11Hv1Zc>n}aZKIvlmL-DM4W0N~3cNcKZmug{Q{on_}JBeMg z&(!<$I%TKH-~HaE*@_Nsv6b#XS$Q3$F>C^rm=oz+*&Qh=(j26KQN<`NMm@3wKL(44 zLllG26oSG^(e<-g{~UK(PG^frI1X^QL+qF>dN)7-1rBuu@u&K+u=x`t0Y1oshuM0{ zyRB5DV3DPF-|gN7l{gD6ElE8u?`N~|PpxRNz)V*LFDsFjAf?Mt;_4tE+mb;r!|()E zLjKOZ5j0;gxC=mNceKx_<~^bv5v2lANwP2Bn@3N@igzc7JfOT#It1E+0eE*6&gao| z*hO9L3Gce-kDN2~o&tCkRq}kgRK9;U7j*T{e_Di-3R|}@Nh;xMtS)7S0{rNYbvS z!NX{=Tw&l~9E!jEfPesdYfBiJyQK!lW}>l=d2FMl4A8g7%7p;q$k~-`;N;}>s$l2H z&^#O<6jDoIy)sZ@dK#0AAqQHvEmulzwNvsoKAbQ!7>8~a@5@JBhf&8zFT^Cdv9KoN zRki)_(sMfm%CWVsE6k1t+m1dL^fw*dOrKj|aUJg<9K#gO$)M zXTh_!4R$5(3$YzKKynTg^pB%RgAHx6RtRnbBGHYFbjEM~(Xk_zkO`AMv6qo_T{`u+2PtA&;wp;L%@ z-vJ^8rKLsP?ctS@D~V3u2|8ujXP?*~Nn-oJ{$74_`Myx6p#4K;TP~T$F*iIy4u6g$ zBi&4N8%#EHigWksuLv_pLsEl?JDV@z%&}n>wD~j9X8#vbrAZ{s7MU4*xk%aY*Jpm4 zX08e42^e|tB7qUIM*#gDH=STde56k%tX zz;t^S4u=Z}YhA|1F2-#pbK7;kaY&sCr!&mB8^p5}h1XQhw)3QQ{%GZdZ6c*YM+-GT z){<$M><8fLlhL4oOCRi+`lk?szv&t)ToP6C?d)A-+0&btIkBJeAZ>e+uuc{ig>CG@ z2YXz9?G1vppBhWf_6Ea>iLIZR?LEFnL~WC4*){isH0QO?^{$M9$91?EMnf+9 z?Y&nVXcn$j2$7NrM8g2}*SK7haFDC#3Jk#>G|Si;w-BDiELd5D@#P^7cxfUL+n;O^ z8cC5$_Im6R>G>JhZnQ2fB&Zr_^@P&YhJ29{zmR03TqZUS;W2p+>8#1bVtGIdHZgis` zLNCV1EJqh3HxrPOTNQcrT6q_a$Yu5A;-!)xbUJ?QMrI|8@N#;2TV{>tmlb#rWigh}lG%2%(gf!`qBW3nt3498{cy;4 zO`}V@O;#6*HjF}X6Yv(R=2aTI8RLu3yyMN2k%CG zLro;^kR--0W>y}EwkmY)e%F>Jk}T5u@qjb9+JJ&n6Ji1I?^VA3$-EQ6TfD)7gVV1Ho+1!?SQI=nKiV%rz>UQUH@s`{ACBCsoP8Ni>!_s1k!Fy-Y4ns*)~B%yOAX!(0=eZzAL5?N9UC$l?_~iWzv7$Td=bG>bCysbKyCz)kNGgX+Co_M#Vld zdcncytP0BD{J&VC+6LIp!z}uPWYmlxZwf~~B*$cbwOCWduPW(XEl#4QUgUPHI$4{n zJtu6Zo8Q-%i6lLfV-}a|>kX8@L22bHa32weMUCvR{XYdpaK6T;EL+-u&<}m@h zR(%R5vUZLrBta7q6`g7sVGqfP`*yazA4eQK?@s#2-yba>M$-`v-j@1g;6fH87}lT= z0as0GKcgA;P%^O=p^s`z1B2&A$%w@iaccP&-Rg^F9mE}8QSh13^pU4r>b)arr&CXV9h8&UmK z5{5k)#Jg0VOhVAm;%~O3T#*daaqGKeXR1^lo#`w%x8xH`yAxQE5o=y(j0eCz(;-9R zs207tZ2c;ApwwN{1(90{c`6k~K${0*kP`{}v69*UCi#LNSs^Zn{-tb>4 zCrJ09qpA#|m<0qp%C@UenKl?zxwCzqfs*R8H>=v+Q0YoB`8Poy#kkTV?E?lnut}yN z3&MsT~eDVo{{CiXXRJwB#TQ&mO5>$cW` zsQ8*ih3dqqtYsT)%u^WmW8;DxjO_^z`spoz`rGSP7K~dX4!leyf`6?uHLDM7bVdsv}6?jZtCux znviPYOMzN+jY!P7SaT*OXE82y`;MVkf783JST3}7oGs%@$*{?tRkSV{GUl$!I~H8; z0*c+E`&|Id4la1XsOpB7ov&0ocr_l+aD5DJ10l|+@v&>js2n^i9#;Sf<*H*aah%-1 z;Sg7HBiQ*~Azsc~s#-7JmHE`NVw(JxZ|jrE4%I7EsuF7Y0wghH^$rhIs3jG;D}`UT zj{V7O!KyRi)M_CN7k?<;`W%u2AfIWz(zbKUe4`1BISOr8<^zt)v?Fh+(IXXVZxB z2q>I+1uuo-6}pFibBqme43nrQqvYKuu}KUjD9HuD;>mHFVNw#;G_+5KqlbrRfh(w@ zfSkbO{e8uzBULl)KP=&t?n&U8Rk0M3qKZ9>;QU2|vl3UG1!2%m%|k#>nyIknz{GVN z+={xM=8Gx7ELC3t8uM`TXA!0VU|@}j`>Y5`BY?m@paGfP{|-we*@SH4W^8*V+wKj} zlSGSp(*nu1u@t5v%J7YHV}&rs7)-5@YdV=IWS2&twsiuvLUDoBNU#>%WHp>kf^aZU zrE94qVSoY&a(?*@0L<+xx=958a^XVazp`^G{B)ZCDqXKdk+vxC#+QMl?^7U)HO#NL z7xs(`(vsg#H}|{1AfUZTrT*xzdxgc+6%PawsyBmL%tDAly)^ek!5t{rwkR?Gp^BT* zCgCpEkQXJ?1q&h(Uhx{-6k}+;&PC*zy3Cyd0o<$;$b^Mw|37)}8&uo2llBUxn;d(I_ zBZ+h%N?L4DQL!b8HX2k+VHL5kW zb3U9k)?oa`zd6R7bN$(S51IXzJlrEQ|Gpb}^*u_gq5SP1IB@E7b9L@#+d}8eY+V1H zrGh`4mfj)!iJzMN7)OI`saK-*9(@_T$?xHkm2m{Ws*k zO4V=YMI2-7G0}u?E;Tfwdepxi)ms`E8Jes11Mzn~9*qKj_4g_1M%3t}TlU<`M2#Js z;@aOHn_P>&J;P<4nE72K-XHqW+?z!WjkTcWx8o$(gF96xvR8Gn&l_^iHFOMu&~@!^k3(Jo$Kt(HLA~$Bylqx~2&kU@##s6@ zQt4Cwx@*R*cYvGejQVHH4|D(YT>9(F z_Uh_8=1xh;-dZs)_N1zEuOgSyr|(%X-o5m%J0RWgrrkFL)8P4_(W42 zIyj?2XmH+*ILD|ehSd=dwM>Uv)Dic!q=W10i5l@f=fAkTj@>TICA?Z}lQ1!edULEn!L3PAw@LGJSaHI>Y`PB0M zMJH6O76BD=!b``&*OM}}$?OyXo=c!=5m1y-Wp*$e%`z;(`kKnM;P3RjsWe@e-*mza zP(sqFmN8osuhe1*9aJ0p8rpk4&a!PbSc4$P9qXYv`|Bf)MoJr;W}s((M<$tOkSF(! z*|fzI?pw1ld6vOiaBM2QCfW9ni^is{PMi$jXyn>|XZH8|AI{0~qAr?TTWO5glH{Gd6^R< z{ld5Zc87m0pqT&WVkHPI5fbTz-rNl5;t+ zdC;pk+UP;9VU4nmkmmYj#JGg@VXn4fqz7fudPQ<1C&sDXt!)X(vz!>|fype-X1B1> z#FH|Z#uJj9_^c(#R>DH-Cn?ZJiycZomB9p*0$qHE3Gk=?8dHycR@_JEtb2yp{Db^i}&Wdr{ zv^1GHWO<}H?8aYzdt}A@-I3*GO5FcX9j9ZAgVjx%V`CyB$*fy3(i{OJMv?9%Ab&_f12a8C*w4I0P@hWI8Id=x*3wsFh^OFr`~4P^1@-7S-^;`=B5q~9f!t3 zNxNa19zbt$7i-1tr?TNFvJGrRJMH9#jx>kRTyc@)HGp-MW5Px;^UYFIH%5b_(^Psv zk^^P294XgPFE|EVZkkF}t~Tr zBsL>_U*ZWT>QvI7so%OH;E1Mhjw!bYDU&DXa*=HAMDpYUOtaXKWV9)`XuNi)`mq~N za5TD^0mfy;7*-p0$d*UC*X^2zL2}z|w3We{6RGk%$RxLECOzji&5IzppEk<2!8#PF z@)5`+*SDnSz_Un@OSuJ(^rozX3CTrtuZ@%RhRm-C$x?2bB+c!eG0NWT&uzL$bB|`k zxHntNiILuOdoz-g-^m8r`bK&VJfm$5B1u$JyWV+oW+6?5r!?Ly$*~^}brJwV7JP zF3EaDdQ)~zV>=)Zg_V$elS7hz6tS^p)L4hBHIiKBt<7!x`N)Zpy!icD60F!A=>8vd zym8Q*Io=WI=0D)%x=)Zg_V$elS7hz6tS^p^iGHCA(Hvk za1(z%bYdijbJwDzXWg~v0?0LCmDfS?iq$5LbgOK6k`9nPjzw}CtaM~RA38CT$HE#r z1$iZ`gybz)sT-gloEXVwJg6|~ZUxyTtb}9_SXLS70VhUsI44HB?8Hb`a$=SYt;Z&xMtcd;rTvK)PitD?c+$kZc#$SSQF{VI?HXU|D6Pt4@sMys*X= zL9PiaA$bUvRYv;MiIKbz*4P!uJ7FaxJ3et8Mfw?dCQOoj!WtU@nFuQ(xd4{+jP!~V zBe^cDu}zTs!b(V9f@PJFzHwqC?}at?2(m4AhX!PS?nVyjVJAj%Tv%fhAm@aYkX!-F zdPaJ~i5-Ew&54n2b@zMxyFykQ?-0#8F_P|1(bzivx*<|y+aM2wm5{sw%jze6>%>St z2y3kL6Io5P<7n!D~vx+uS`elASp*($AdO1jxml80i%!MsibFWBVWv9P0?=xv&zF4`5kuNjJ;$sf1*k zu*Nz-_6RE>IRchdM!M|8NLGY3HVbk|SP97$u&grD>rRa1wy?%_K^_S!A$bdyRW^sK zgMr+hlyn(9b5mggs=#8l3Qsj zMtWj0>v6L+UTNaV0+&V-!95N+H|OUckx~AOp?W2!3y=ZE5N8@BY@Uoo{4}eH`Tv z+DQ8v(|aqvwv<^^)Ay9x?*7bPN8lRyvHI>2^KUIJm}q|k)!p>l)K*zVk}h$y?M3Iz+zx~rMo5pck#<8vRWlQp9 zOZm%|FI%2}*<>X6mkCJxgHGZfFn=by^0r={&Vt>NnKLREz*!9bLe47wVk~ux8Aq%a z2DkzCX6--6CVrypdjnam-69d&R1E%`Io9wywv@|O<9wPB6053vJJ!x77aN9ojC`yCy zAwbpL@vrd^K+{qN`e|A=pk>qfq8Y9OGW0t$rQPZSkV$poXtVz#8LJgX zGfimjEkNO_Q%r?}qFB|k9B4_XrAxG^#jyr0yUv#ppyx!3>dSVZC83r?w5Y!9LCcBr zWfABd(W3ft6lh7PWm&YSzMMkKwew{k=nK)J`f?d)NvP#Ow5YzkftE+-%Qeu=zdI|o zh^o5}v?SE>Cf=9QKam-1$1%ciTL4ib?gXSa-bzmZQLXd?k~k}E$Y)=CUWWrM3AMC~ z7S)$=Xqk1s3<6ydEo!}00xb!(42c%impN!zalXs}y)If*UzP$b3AN0N7S)$kXxVYT zYy*8FT2x;)11$-)?1&cCmtAN%a=vI&{b2x6ty}~0AXe0CtlI#hS|OyfCkr9wz9TUu zU?TP>Q4n4Tfc z&4t~ISXvm-Lwu{(0oj4}eX){|WJg7`I(>W+L~ZpEwD^&0_5V*FWFHmL>LEmJkA^_h zR&R)v!m&iPy6;+4FVz5jr1nw`Q1L3L*FAj~>AM%v>V)i~up?IWIw0fFJ}FiblI*C6 zR;Q0of~c+j2p?yAWmW$TeUN=rM5~7owLKaFQCqzsRtm=w)#|=$QN2_Hr1w${Q1L4G zaPCFi`eH<76m~?b*8ypU_BOGSkYqXsaJ-NifHu^qP9mv zAZn{O#7f~G)5j-4)K9@FRfb_0y6sWj+5v@+=hEUiMt9l)fJG9TEYju+BsEAgl zk57WAt-gp%+_+Z%vwExhsEAcPgsAP&5Qw^}H^fTeSfX0pcP*;bYk-OmXuX#7`Jo~1 zMYKBYT*S9}9grnxUll6}Np@63tJB9PLDW`n{ef&XU%=5kZ2MfV3?CKI>LEmJkA^_h zR&R)v!m&iPy6;+41J(fP7sE9`de=4zRNTFYR;P0n6n4a_UI(NN+B?NcLXsU7(dzW^ zNf5QwTl&!IIGR>p(_7s~MLhfnA!>Ux1fp)>8)Bt!EK#lQyB5{zH9+m^!?qeAz1159 z`rg9sMJz3Ju7bjjX!SZEZP4B+RuYm6!csqZK_8z4QCocz4z>KCT&w@8-s(OoBK09e zZI6aP)K$G9Rtm=w)#|=$QLSDBRD3||wWQAv4RJ4GRi~YM>A2`#C;-`p_C2wZkYqh$qR5Vh5>;N!^el2!dkuM8g*aR)wxsO`}Z zh`NDqh?T;zM76r_T2uqp0O_~5Yk>5wZ4{`udl9Wp=lW6D5v^VaG z)5j-4)K))3CI)^;TK(7bR`*d6tsX+uCTs{q{Txn1tQ3wVs?~khqFTKMNdNYc8X&#Z z8wD!vUPPt^{-<=;- zV!kH(8Gc_;%;)-jJ>Pwg=Kh&19ZNVyeA56S3j$F`g4$OFl8`(UmU=n12hk#se>My6 z7RQKrdk>fxhrzN)(p3>lNIv}YR5sm-`JoTTh}n#8QcK#^ z)H4h{QS*$i$-3<;ikWA8J@tFkjbt&Q5$U)_GMSDD$Ri*vKg@AR_&Y)yp9+g4e@)2z zz(n>p_rKqnT~OF3ipx$oqkKpkMB4?DkmT6=WMTJmZ01TjWD+a!c(F%aKL!}47;EZ@NhTgPzgM%f^7oL<7`FbQ%$s%`&4$6BW+OJebc?^L907TNTaV&inPl_t z$$X0HB7JZ!cx~1`9>=4AGcgrSew! znG5xUh$W!uq#0*wVM+|kcQB%(>6TM0zgg@QzX}zr9uL6dMB*OpMZEk$y@-w;1bRrc zs2yG7H@~&^T!!{Fv7+`OA-SJA96@-A3~L=)Mnf&?w6_AcSH*obNi}|!QA^SZw7-eB za#kGj0LY`WLbBOyJeQg@Z>gsjAUip5V>$dCH(_w{DDo>Q)J@0iBm#G7E}a^Ddnwa5 z7&nPP{WC;kCJ`#l)(X3@axAf^8+MBFHhI4SG|xGCEz6(THZ19EuTK!p4UQ2RAcPr+*q5DpNsHKVT@-hWF*M7frf$D(VWj|sqAq;(-cJi0DgdGA zq{O0b144+pD25Pqwe}%VyZdK|qFSFaw34huw`nR<&u`iev7kQ*5_%_Fc<0I~_l zIgWOk;m)jr{fg!BX~8mzFlIWU?o;SCOAA#G$W}-#1Zvq4Eo!$B!l2B|LBov6u>6oB z=9g_RTV{Tt;zS~vngHo+O@+49W@gr05c2!APVsc8SWW09g1D1}suh1#98&txY*FmP z(H6`C5_5o~<*}f)3ltW0_dvHPEUMvc=snC{MSj?KUH61FR4i&3~wSypzB%x|y?G}fe0aE${*=X4!>Oet_=L(Ajby=XW zeBGvssCrngUZ?p};k0I?d}9&iM_U(?Ep_8S$b*B>J^rG3#MS4ymq4>RQp=zOITZ#u z6$Yu+8a?G;8TUfPGofNN6|ETkZX6>nRN9I|`T(ioXlt#C9PQ+4jWxz!CAV_gT;l6C zB}3I4G7QuFy?I(QQogZ>TBEH2$(EX6LM9!A?k$RYs+N8)fu`1|Wlgk9g+We*L8`Sz zPdQko) zAIu7;1ILIpryHV!0#S?aS#b!pPly$@k%k~z05S>4f>=>ARw)iy1Y{%L%5rhYCLo9L zR(6U*jsWSz%o(#S_-Ad{x?&(T)QLid^d5r6^ky^!GfNya| z%m4>LL~1+N0XYt=s4Z{<2wze)dj`Iz+U?#~)h2~Lhz<%w9peFr4hv+IsjkZVdg@+_ zT82c6+FOJ;!%1jZ)l!DR*?7YX5M2|9nxqYg?g>P7> zoQf9JS3;cOBs8pQxq`vlc*746ZG-ZNYuOHn_6S6EtQQg^0#VzsuQ-I-D`G{RS`vsB zfSdwyC00PVslop=PAj^%3&)7dkt2wn$3r^t5v*PuBdjb!bS)lo1<|{B$iOFAY7!hH z9NUEGemvw6qHW`uwFoN{5S@#M>_GIiIOG}-du`GAM=~dSaE!U$py~a1(+9=9y$7WA z$D`9oNEaYBm_Y17gcg^+44z$yY;Di9#`^u(L)g=hh9`v9T0 z<~zK6XCuDWYYti##aA?ZRu=Yuf0}CuM4e3M1IJXz0w7BgiwfC>=s`TB^b=WX+Hs7S zfF>b29}n4u=&?Z5ad`sdNUW%Pr#*-kfLs7_BUaRL>HEW3lIL)YNHQVIfY|A&6_>Z& zIL6Gs)H4`wdZ@U!BY-T56*cqa;#LT8Ir&zNoP0}tG)6rIhJ%m-0j?sz4atdG^9_Nh z)wmWorb5;M*_2pR$Pq-(;~^a=njRb@+GG}@OYx9hh#tj5&LDad58;P^*W~L5)O%BP zK=_Hr4!Pu3@3hnbnTPgOv7(OtLUG6%AbasvHi|>`0Xd7ea#$R44oEMqzhh?V?-nNF z_SXf%d5BLMAiOL0gS zApP-Hx{E^w04c{?87dB$0AwNFN~Jht5s+iCqE1R7MD5BDqAnJMEQ@1mjZt(x942325Q;LUh|cYU zl>!io&H);cu>_*kcnGzhKLw)B451ZuTtbLC`tyikLt;@EH$q(a>NV&Bv^xkGuG0K| zSt{<>a&ZX5J^(c0ZOToE7JyK+K=_BSQUFrIVE5o?mQa#s7$MW!%`dZ@ci$NI1=Ri}^8<+t6kv(?gKwjuqNcn~t`+ z#MUPyyCq@MVO$ukcb79qq5}8q5=DAbT&^&RGsp6yh`HrSYik&Hiy^%(wJ^gPU_540 z=1@7GWNf&-CcD9NE;^T zbXMX?r_9=)_JB+ri)1+u<;kRzbH+2upE2I+0*y44zD<%QQdeV@JAa~6;vnihKZf8S z&o#$xy~H<_K5IkHIwW^LNzy6)OjArzR|Nd3XhHfTundC^qE=@ekZ|FD&4qthb{?<8 z^%;K??}L}VI?=HsIGSgmhruQg3|-5xXnA=C(2Z;*U)}|Z_2~lH-IZZg=j0uTp5SP= zQl#CsIw8sJb&Z|2MRKRLDPf@Y-kl6OaGP_0w6iutl0#d|n&mk|8RZus&2c2nZP?Ih zb-NpCnF_V2yYWzqTvE6MA}ubicSXb@GDC9?&?Sy$14HtSutxoq8X$w%knvMj=o2V( z=4%y;bHDbmgd?sN4lBWpq}sl9K&U;}t6D6CtVw&TT}Vi7UeT;{LHm$cQHP2U=a`!0 zZfJK9wKsZ-JJwqq!mwv0d^MH?qSbf^MGJ&ahnB^PnlXy9`_ zq%9}sHJd-hzSjjBG21GVG!eCLq;ltvI<6rkI*ZPVy4Bq965mvM&a|IO+9yal#p;HX zqR-q2bRcGT-%RZq-iR9)Em(=%VEW@oQCGHQmTj}t=x6O9JB6ihYvF@iw$<5)J`{i) z!U{KwX7_mm7Q={mDetHuTId5EFh6j27x==Clo9a<6EA2k+Fe zG%X7a(Lx{G-Nec<6zA@6YQC%jlGDOS3TSzT4jPo1Rc-JDqRRqFNUr>gnb+n9+B(Qb z$I>FA;w4c$O42Ew4i&3CPsNL(c#Pz-xK{}ks~a#XX8cX1Pe^WyEp`_9c4($3A%6a2YZtc}u5m(5Xw=TI0(tLP zT7K!#h2&Db1A7Y50uWZwjaX4T{tBW6AS?n`tLplG2P*|2tw?T{Bw3B64Wdf|QTwyq zgT&l0s0YJl?h)5&)SB87EaInWVcicoUuqP&R?+PDoR)bg%(aT9h3Ja-GDUQOQDg__ zv}lHRVDLx`tJ&Wz4yj|>JAswUc*p9PkFKHpKHf^{U&?aYj-$DSMDki#Q@0=&e>#(n zcMl1Gp|;<36nc#kdTv8ts9h6kK4B)5e%O>!43 zJ42D)cVZ+Db7JS9FPvByth&P*0-D+)9(@l3vMPqvd-`h-Ww_=pETcRSEvm0X6KZ_* z6BFS+b66l^=CxglNcEMX1?rBX6R=`yf%Lpsu8?F8#w==7-J4TQdQem+Bx%A76G>V# z^Mcl^q0efz>VPc4?M>%C$>TZBPL*?zZGTi)n){*RQ7YaSTk7S0sAY^=_C$+%10&S( z3AOBs7Pb3AE#uU(BU;okq86qyrtW-+;*c9a+9U~TUzFI80#VDi6{4L2QEQbB z6@c78`_l%L&CxG4kdV9)*3<*Y($8>KQY(du`$Wqq$%?QlBp1PoX%lMh5jA5ZSA?Z! z9HNZYtP>&#M5z$6Nw9p4SV74O6>bbb5=7nRE)1nOswLdMD7x3|E zTG~(nT~Y}N$su8>P1Oz20+0ldvRFw-R)jUCrE(6U+X6{Qo(XH}2IR;elgV%y($Fb;l zn>bmelU?Fbl};`>)^^~xx`Na14RLaeL%*l#_onzgO}{V1?`isdEKaKZw+^!% zqIjIPE*y*GDhBkU(ibfpTxQ1dNH2*4<0QAivSOr-{YLx%^#LHc>StZE*37!XQmawwgHl4%OCViUsnt*O&f{^KzjW2V9Vk{m zQ%J?RS(J)hTvLqe{qtiOm%54DrT+&S25ZHZ5I8-Exj7K#u|f|nWoKCNt(j|Z-&n+DIoHH%DUpPv8^#%$ zr%iLmpJbbiY|;*r@f)eoBlXS`&3DVjw0Dd2fJ|m(x>Q0&ViL=Uc0`Rj*|tD^n3tU_)e`X~@} z2Y8H0>(b3*B%dv0Lt(Dnw9yH*j8e-RQLN6qp_VafxfU(z7U&M5_X1Iq(EP7t0k+^6 z@$|I=qMh-O9*FkFLk1x_6b~7PXgMBIh3ITNWD%lE@sKr$uE#@mAi5h5IfUp@Jmd_b z=kbtBh~DCuejDoP0MCOwCqF6nKOI|^2)I^Uk*bp z8sr*~2WO@8XERV2juA8DO+&OiLQ97;+zs-XV`&jJLo}yFgY*D0Z~x=~$YUj)rLIg_a>4 z(>0tY3*wEs_Z^4mtU%OJEEk8I1Je1gX4x?lFv(S6O>Ka@aIDtF46uQtxof56m$o`Y z%P2`_s}kC(gtpW@KW(*(tuc}-!kVV7OUDXrsUt;Oy`trlA&}#awFq+8v93WrIF^>f z>kl|ykFeDv?v0b|2g`h-se`d5PK@M4PK@#II5Cp@IWgwH7j1N70g4Q6Ue|?jly3^07FC4i&JHAck>? zMXiB3h#ok|3CMHD(ngP34h1qwEfT!|L71{NW@A`o>zDY_jG*?_2vSgnE0 z;t)Diz{(x0lzuKtx4nM^vO`!?T_AfMOB)?3ZV|{RwRAg{riJKsfv6=)ALkup8RVK{ zZGzl&EX@}xUJ%GA6|XxM74JD#am8a)d>~rXLLPwVut3y8rs!lmqzqA)1htSSibLp7 z0V~I_aw4&)m2wTyH}Q}gh(5$aN=w=Jx8oRbhnAw<@sM7K4mt?QvaqHmK|VNE$@}L& z-=*SVfs9hioMWAVymYLR_s>^61krIEOaF1Ntv2I%x1d@1&Af4L~ z-4}?ukKcpni9pIF@1O5j=}%??9XOgKkz5wm)GEk5$MW zC?2Dh9mmqNbVHOrnU^C;_K6nNmjt5Kc*rC~7X_kLLZvu_4i&Jn4=cycF_M?Unz{zL z@Tam2M_jv8@u_GTrItI#8iB&HC{|bA6QD0dOG3rBjzz_ZC{`0rPjia3db)u@S~GcJ zBn49CYf0xhUr*HJ$IL#uM35YkM3jBi5tARaG&?O?ZdxJQEf94k>w@TjK-59&foLu~ z&9NmwHk=ib%|9>o-3qeDv0@ePiQ-X`PH`nvtWG%e_)HX!QA@YDr|xohfTmAo@*{a5 zidA3EA$k)JxrXSYK-6J1MYEX}<&h;9l* zHB3>4VcLacE+WlvW3=qUZI=Xfi+4~Qa#$QvTFw&Cj-%N~k}Ul~_9wF@wt^gSEG=(T z+#`xd2SFx|rD++4=$$|+p)VCp3k}YSmV~5JJQFHbKO`^-h13@D6-0#WiZ7L(AiHWr zz83qkysswa1$yc!5CBEzTmV}BDe7WYGrI}x`(h;;;)ZmZL(0@dyfu6PgJ)uRx)bB` zBrTOtOGV2YeK~f%XplpQ9tlL9XwD&eE0Af;N(VB+n9Qu9K@vc=aWs%akVlSHT+3*v zMO_)_%VNCYDn#c5qULo2qECxB)KX8x^kGNbPnh)+$I`NY4$IhT4=CUe6569R9|l3%e}Zir5P^4pv#-uE-irMeATQFQUx?-{{L=a zBJMvha)uKzcZU#lG~1A@UK}GF>nIMP_7Sn77Hc0w3qUC9GNy)~z)Atg93YDli(3C* zTgW_OSjN$|%qHmV9PbeHQI2;C`XNNMg<@rFRurIv;}ong&N9guctrxkomv1LoMMPP@xr!MQ=5bYI+nuIza&pa#9 z5fRuU?x_(`)J3F1`k{SMtR!b3&mBw4zOTi$AJwotV^%R=kGazK)fiS$Z%o@z%M)U% z&zAutaYB+=4t-HaX%OhL)1oDTkdb%@MGIK@FpvZ>Fo`jxWi_)UqzV{JjfVMhuL_4j<_aiLbm3a?i0yazrdLOy+0Wz|sM#F|`nC zQOkpK2cZ$y$`mb0`Fy(_q^qcJYwi=$<+OYSkPc|4mFR_vz)o>bozI>HNl@F$hs4YQ zJ|<$s`rz5P1oM+~Am<%ROMgE^lj4w}cnC!cSotuJVZ^{B#*CGZiFg#s0dcMLliI-S z!?RP#azb+R&tzb;FW&`u>R6iM6DYhB#m_@6>J)PibiWw>bROiIV`;wJ1X{+ZWl^-K z4=K+Y5)rk$c~V}e<j6a zid&%GmE32v>`G2uVcVglL!9m1BJDI!X#RHx&U~Ulh5@0|5qFm+1BiNig?-~vqV~@@ ztUTao79Wzgt65a$`?Q)r&&VAdBfesbS{|X;&aR}J|132pB)f&B-rk|+(?6GKv6|07 zKjLV9GmvB(!mwhbJ0!G(q)eVLE4c(Q8>yVu%tIK{5gA)`qcIH8L?G&_OUQ(SFe=tV#Cl0BoNUaEJZj-A z5^+;;9X@P}FKWb_5Zw`o8ZjXU4#G$|Ge<;BEqkJ6lv=u_S=9SU=Rmhgc~7(DSVj?> zEo!+FUtUm4S$uh+)!Sv@ORy|Oys|?d?wv0q@PRW&TKznkbPkeaFndDDP=Nemyk62Pk(TWXB`-rRJ0!_9IdD+ zjpMbK8=HO5R8(ZV>Wb+9Z2Af!YR*MOx(hsWy+D!JmynnJDXlHX+<18_iJj zTS|YT^bfWDquz!`obA7V)_~Yn%TajOA%xIp~^RorKx6kIS0QUkS=7bM>40@I7Ryfl8{^!mb&;4LexRj zxuX(5R4df}OomFevI#3Cfy`<{wF}4rj%My4`6#RxB%R_!Q+xz8p%EAK*8xPmH#3Y# zD-yAKbAtKo6Nq}-U_7v*K19C*r2Efji86U5+4FCaRb2)-@fU=(2y)f2?*3Bt*Y5o0*Ok9L?j3U67}amC3mO{U?uMbfb(ek$|V@ce9wEqWNyI zrLNQ+P}u1dJI6B0ckc<1Dy-PeJLwCt{Q8>Ce3@BpD!uLoIp|o!AV(Z)9ORi}U4U#^ z7hSC&I~}VV#%HIbKLqcZdMs-S4yvA2Zot7 z`^Y(D^qIsrJpgjYu^94&^v*OxUXmI!U{h=Nq)VqV`fJ!;DS)KBRJC#-wuU$=I|XK%tE7<|Z7{Zo;XM zoWx{dlS8^Hb4i8d0$Rq3k!GWqiw}}aixnfiBlS~Zg4$6(R*dw3Oy(6<6kEj@AUTdA zvq;h$b0bD_B_~Fjbr*51#Ht&}<&gBLgd^+F16bB6(r#@^NU{dZHF_9fjTJ26yx=@n z7d3j$iO{-4nlqwF0LeoHXf82GazQatB$uQfUXo`PUA%Hg=jaHMit3d4Ln??oP5NY9($4P7>$ zBMKdT9{QwqJI&9^aJ+1R`8FKQ%+nE=e@XKvlBbt6e=jMKDbcm=OV%;7Wz-kVQMz$p z)i6sblS5yIS1FUO?!d2<$rC#LjnX%NA+psD|8196(nsK#w7vn^mKzb$oicC<$q8Y} z#)4yMY;q_kB>B@MIUY6uKl_%)^zXR5awIrc8v`USoD@k8j8#UO6QDsBohh12E61f^ zm@=+EP#Kp)#XE)>myI!jOyRw&B-kh$f`tJ@yg zqrK(^vhZzEzi*6sP6=!p!_u-xC%MNo7rJ!vLbjWgGW=y<8>v{uyz%_iKrS&X&Wifr zh@v-uMmSang!#!6+EF$6X4F>^?a6i0=75yRqC%f-;J!g`S<#MO(sHiS;T zrjs>_+Bx}}PQJg+LnrGg>Pw`JPbJI;$k}Gjqw)rdnrZvE)b@Q_JYfRu5=weS_ITw} zkj!t2Aa{wQNohS7A#o#9BjGjdYyH%RDsb~}xfw&=C-ZNa zb;-TG35-`W++0R{|3DSC7H~B8U8-1)nWl(aF|(l-Eyxc8nF}0Km*o{e)+8ed$pf&= z>nklfD@CSrBp1Z3Y?)~rzb1t1@nmOHjMRa8+dDKl0RCq?5g^;D$j)cY$p@Z(NG zQ12TNlAH51UvHtEU19FPk#t&A!~F=0Gpt!^G{dWa>`F#dD;p5q5r}Gq5Ux0O8q+)@ zrVcY_;+Yx@wR4^`tH;l6`Kw3DrI zQ?D4WlB9C;{TROLi0?$DVyC4VYN=|0ZeuVQlX*)_gNz^&XSg2seJ%B8IMmcu=VZsq zbjeUFw2Wj_WOx&jEoV{#9qhB1}j#8Y5^d&7?Kg{~eo9ZXUqbf;S zG&>>Ro?$VqoUS7FOSI(_S3||sP_eonT88u7eVO}Ke67;Gls6T=Ag4ZbqQY&-j=Fdg zvK9~7fvDS?=qoWG<=p*P(sSTNd}nk8qE&%>s`Viu&Wh@+4>8r+w6zVB3_4{NH~yKg zr>Ug26mM*|%ZxD1TM_R0wR*3{*J8i*(pO`7T1?c#TkH{=3f_5tS^&2g0e7oj-OW7! z@-)M~7W+x$Fmw8+lYKoVbH190WKv6kH1KtbUROZcC=Wt3_XdUrIRnJau$e*>w67eAG^qtG7#rx{A*se~U6o3CRs%&G_C#T++Qq3&*U0mNn;#RuMG3 z91o%PT*R7{b!c}Gb%tjW3xrR|QG6_64XBRYK>PAv%%ZlNY0{hEMXZx+5M39Dx=s?} ztf;FGK-?GCt{uC1KUA7kTsJj@6NmT=hSu5*J9U1Uro$9Nj-dY z95J=?iSp9|=s@`H5%hDdh4|F^X@-3*cAX3}r>~Q~p8Cd-S_-6L7@6Z+gb_nF3kaVc zMNFh`0O5yjY>$uQDbga25tf@F+AfeOejJ3at3^By?*h6{w5Ttb4nUMXM_8fgoLEs; z!!kq*K-lDb6c>@i1RrGF#?ideOLFcnXI*3NZ?9rgyoaN`<-MK#wFO7RO8&i!HHTxw zjd7Y^6!W7bAI1C>&F_o(DU!#+s*-#otSLGm()>M=-$XT|u;m=RbWU2la`mPdL}9IcXMSXPWQ<1*twk|A2LMQC}G zvp~B0uawe%AC*3zBRv3~DG`z65E0#nu=W@-36XWEJ-G_c49wYsFm1bB=)js#j2l0WEN*piqJ>X0;QB>JHG1Nej$;mEZS)|0_tTweYum;sM427gc;FPr$94X z=9^-ug~>83KUWdoCquWKV!7Mm6wB_@rAm$a5gzmAL_|q+UQpd8n1BXtzX7KzJ9S^RHxii1-kAjeBw#*8T4%u^ZY4#EKeA zja#Zte@6LM!uw9@3=l%p{dfpbH`gIVy-=7$rsgDL>eW&OqDul%lUywhnJo^XL!085 znz3bw7JyKcH^Cx4slN>?hvJx8Fzo#cfg~g+1^Re0A zlxi-KfLlpK?^ZL0i1WYQKtBVoPlm5|YXGzxQtrdti1@P)?NN7ANqy^tCTT8ata!8U z2rfn}gds%jzYwC%iy=g9rV3)1msr$Et_sm*fvA%l@8lMM@P=;z2t{|qF*V665Z#W4 zP}GgSnq)du0CEh6a*xSe-Pc}wPl`jX0LeW*)~s9?htznMs#$r2l{UE;R%?v+RE`~l z5~mw8;9zQiIej@lP9!nuB%Bh2T{*T=*AV4 z+m+-RG!@0%o}nJ5?up@;2SR`SYc-C7{cq?iShWIY2lob!ORYw;--c@fp;=ewcLM@+Z z*}Z|5lG73kxtF}DRw!D)%7=kGcuBNfq{Z)J%(ug6kS=7`jrb=Tq&I+!X^<))OEQ+K zV;c}1mIXH9M7Zi$n;_2|>l|da%y|jtgJnz`5s$8}VV)DQxx=~y#V2BGT8o=n`UFy@ zmSx9c5Kgf=L%e}|cal)mmm7%Ye5u1QwTy`S&qFQh3~>)%+C|G}p%%4wAE2epY0(CR zkmh&@MGIK@Fpw6+z$C`Z5I!bihUkSEH{$9HF&IG98DbldLmVR>vz}d&-ChUDUEDT1Kg5Cw_Ez5$94pO&_?IHNNm7?pzeBL2kn> z?!zOpKM3v4mn8H>y*lPT*=d>5283a`;(GBFK)6fqmkaWQWb=QJ*)vsr0Yv-s2)I^v$-6Qo|haU6FOsFCjQI+ODP!G z%n*Ec4p+1i^c~LE*0Wq|^nhN;rHu5tr0f%hKo6|CqAnE4*)$C@O*M07?j`-rk7HA& zE}n6D>gQYkZN7KAr{tEA4dz5&~4 z)K68GrJwnLiFm#P#+g4ECWk z()4MjeNe;;A%s+=1l6V@BsW(TcT9a#fL2z-F%{AZ(Ly=%K@pdTA>^f&fDkfM9P&zo zw0jANc(ttz2-9rptV!)X9~6Rr;q;*g`_5IS@#j;R^D zfM@{-MGK7n9jp|9@Di1G79%D=-fHNVvQ)=~5NAcL3<5hV92t~&w zd^MH@3dnWG(iR>nZWD<5M2(PUfsB!KzD$L_ zsAa*3%21qM`B2Y7p2?F{aY6OkS8lIlse1)#ERVEPtv-kKRTuGFePT=HJvkpq4@vk5 z$+?^uX=ck54M|o=%=J7y7|E$7%?ujVB#WqK)pfc+NHRwA=^<)nJQ4fU8d|hY=!Fl= zWP}xFq3qn(tZYN{)Imt@{>SX?SNkB39c%qR$^P28FH*^Wnvsh*n$NVYf?Rj3Ove51 z-vJCg8l^|);-uQUge?6>nI&6Tr1!xy7o~?FFC2^HgRowboR{!llk7qotbV5CB*!D& zDrtI6ase#+?O9w!${$(|3d_i&vc?*ZvH@nAaiK))9l=Rq~jgX&l3 z!AzV7Gf(m03f*K!f%F^cunNihoEYgx5t|~}iQcf>=nuH{)!D?eF zcF|VmULwguVNH=_cUdIq#C6pI=@szI=fST)vbijjG@HwQAsT6Rjg=$KuCa2YS+k~F z9?*xbd}}q(LTm#uP1Xa_oTJUGOY$g}Y|`vE6E{gF+aQ^1*VXYo#UZv%k#?$IQZ?rx zD@K}GG)|FZ60I0%m%W!yDSTG3RZZGCIz>lWWLAu{^I*#NAmUj&XCJnf)l7OpO1To} zK&9f%z!CS@FVMGZSlg@vq<3V!OGuWae`mWvjyo1frp_v(>*u*8ko1*An2@{?)-1{U z9FqN;TPdqGR?2GRN?BzCb9J;HlV&NJj}DS#DOxeoEJf4jRnqKpE7yxb8J2abR->!; zRya`XqjU?;6DHg|NBf2IlH{CQjZ~H=%rsmSDrX(sANQFBByQGY-U_wRfhjAterHJq7fIGV5h(aZ#62lF5| zJCPocdFKVmVOiCCw@7oQFk5?)jHGt6zhH?jqG8i!2fZRq{95z<9y2SqLuNJDMXhmX z60txuMoT;L_e^GV^_75Th_(nMA<5asen6U`+)FEb(c+JF%m=BddlKfpD$D@%(@wqmwX1;4;~24a6SCqU91c$Q1+*-RmQiXsM!iOSKgul7bD~A9FzzXMEuGF& zJn4|`F4vsTDroh7)SY=S%4KNCvDoQs>D0s`{=V$wv|gsGx%&jZR}s&%8>3|x8Fs!r z4}DQz9yx)Q8yPS4)-xe@0#Tn;oCa1@$ORzIiaOI?7KgCRxQUGzy&8~P^au9{5n8%X z*Icq99_Z7@0uYLFLmu(%7ZY%dx3MB(Sp z7sVlTs96>!iox}j8)+yaLRKq%TTv8Ye{d8Ircdt&_sWFPafxpk$!a8&~| zR}ZMFf_f1OLyFkk5W;(W2IB8d3uqaF17<%&Eemo%FsjWreL(k%7ImWFE{9hx5tA}S zc?&aUBTY>14yYE)5`x%~V3Jq}J&Op24mpTAMXwfjj5m-9#6r_W5vgrWt) zKY^735MHhGu13W7p*{h!fo0y-CFxCB`qhr0WnOPaES(`lT{=UEI;%5=z4%zRA$lZ` zMC&2mg(?8yuoi$&^imvCm(F8|7JyLH4W*joD_AK2c>ttMCTcawkHsN19*1f}*#U=g zPf#^TFCe*F$r_}uIHU>)m$--pat)9J9L=_#WZ!?DxoEWXA7tbJj)pZ1vg%kT|79k1 zildRb0D0+HZ$RETR_QPUw&G}j&p`G%Rwm>A_n%0Ip^P$=V~I{J)KJS9wH%2SbuA<0 z5;;t7U+||7K~6nP&o1S)Ozv zg)qm{1+Y`u4V>&a*bERr0A)DJKH@9MMeT%VENk?dDVF68n``cfwOD#?6a`%p!5s2uARbIp`k9_a}Q zs7mrMmkQEXPK+eux7tWE7v_NgN!DhO^sMC4L%Lt$mL-tuomEYG)rpbZ%VqHn^fOea zg}yIkEH*1gn#E?j4Qb*0ZpBEm*m5iAKrXYSS#0KlVFG`i%ZZU*0MBS6xt|j|1kJ%Q zVk9{>);H1|93w`uo^d+OO(LYvWM!Tr*_<0r((O|13CSa2y&%a!x4x6+ZpS?LBU#Rk zFzG>=e`ZL=_6a8(8aw`&PHj7bBk}H$-fb_mBTr-?~>hYkph6j71xf&E3JL`ngGBSz9%vS)8UQNwPSt7-`01#F$VQ&J@F8rXrqf)BcTg zow^@BhbST6Q)*jUTIy2wY{XrPsj`-_3y8AAzqj;@r62viZ~ZpO2R94y2d3ZwgDihw zpLAhZ<@^~gWok~+VwWhdF~_R6SQ?|H13oxkp8J7D z{Cr>^w2Vtc>OD0=nCXaVt3R-!&U8b7I4f#i>ws`)w-X=!DntuFD9SBGL^mJ9O77xE zD^7~?A}L~A>VQ1LF)lF?R!W!!x@0!^M2n>(fQ)I7ML@R2O4Xl!Bi<46wb+%@S7Uj_ zy{Y(WA~HvBR$NS)VT$I`ph0+%;vnh*UI%0&7$5cB7COYMr-%m{$FOo4pE3V>%xo(s zux>BlXjt699Xi$(NDi!#(o!ATdJ)=^D}86{MQBUi5csxi+4{yT&yURVd~-1+PkWD& zdNmyn5bcr+r3yWqlRT?S1<|~qHjTxY_M8?!q=@#TLSDQ@3@}A`zbRs>UqbNPk_2^n z+z24*^vJzFub9lnZWbHd6}g&GKYK^?PVSFLKB>7#_yaRvBB4 zBWQWtKJ%g^rW%J}rz|e0b;LWKvku~0jwqT*pmSQZS>bCBS(l8IIc6PFG-WNk3eY(% zteIV>cpoGS#e5sYHCWBgRzu8xMlGG9Sp9198XnhhPfG>kJ(RfBugxcfJ=IkD_8XuX zMpH?3e*}^8=15E-12QK`Qs;Au7MM{ex+7N9K3#=q0muN>fkf5=b&JCVh!avo#y$*$ zyMj}RMcoQC1fpIThF0o;sG}cRiH2|s5V4NaN&(0q9zG7?81WV@AxZAJCF${aHIopX zcaUX}D~_ejP1Ld=kkL?!dLO3>^dgRSttL%%CNm@tb7G{A#R2sV4_c$o=?(&Ln#fsW zHmn%wZD)-n9f;Xy&;w%A`$#-F5Z&tjjC%F~v9?J&HR{fgYUsf`+);;-DY%dbl3S2> zj-{0pwOk5hG}IF9%av#u3$>^TJ_Wk%zskI}2`1eQo+%ZQLpd?hBTh_) zG)RK{j7w_OnTn9fTxv;I;?>MSblpKncKp|w+vduy7v$NIu(XhK4uGJtX2RK8FYOLypBt zS##_VqUSi;zGi?+l4A2UI-qw^H)g0hjzOPFEvbD=bGPE*6s;AgNMB3dX{w2t9DP0Z z&WBf$5l^{}ycDKW>?N2CG-Xox9*m^SQ_o_`)P~KsX`}T`=CeYJmggIc$&_#JyAfk* zlXc3xnrkm+bvK_?p0rDCs@DSS8rP#TLCr(8S!PJ?2uoc%>1(?{)Cu$+a5O@eCk zQ?!7UVZ<;I9}8=bQ->Kx{X3p(fb=hq_dzk0{RV;1yND+V7Xd`QnmqxeOUhBbV{!-x z+cn}_jtOzGsBbaTF~$^e0ZfMqKq$&&M?7x3MEC_D6uk#DVkmDQS^z@PXEKy(k_jm= z`h++uYK?^u^-h)#iD{S*h2hLSFL_qO2_b6I2q`c$ggD340wBaSrn(w+AnXANU%ikZ z#5tzk{$tnVYS&iM^Qe-KOJAIp zc;f2BeEA`2hK^b=tKw3s!d&x#X8ETIdBR?>VA5=gRFEgEDJ#gLx?H) z23d^@vfAh%IlbGQlIA>bmLZbkvZ(cLk!Avn7|Ey9^%W*9qt0JKtaDG9ff!irAZOx& zoM}XmjLck6lWf#9`;c2vNHa2Xmw+Tk&*p+OBQs(opE8n+%%~&Ts37T{^?nUCSsyU;)KqnOrCH}hXQ|D2b(MV z5T?Xb1y6>-G_t>JeBkM7UX~|Z`Hk$Rk>%+_UX~}1PVb*LvOFC;&2|8(4?GzH)976> zvOHbM%kpH^$^OP)H95oSd0v($7f$xx$ntanW19NFBI7`tZ|mW#!5t{l$W!izQ@FOD z;rOrQ=EC>YAjjU;n?LlH$01(L)g@^c!Y2%&$kvOlvO3fFc*0UOpa1^fOHZiO49_T7 znHiU7EX~vbp0F@8QJ%3fQ&FC&BV7@I+n-6GjQm&9+`R2^m=yL_Um+j3ff2(Jt{B50K`6Xajnnwe;@xmK1rT};^ zrqkVkA<26)=Igl5@K;`*85Tp~%w<^qQf0r#3rhn#)36u{d&TO)e5I$61z6a5Q(f&Ou%{Rwm>A_wN$iLiE8wn*X~@yamUI+h$!5?QxKP zkOPk8yvQiumvM+rI>;=@ImgnptUz?#LAF8eIF_d62%@JBasl$vu{14r5Pfuz7Bo?- zG?RL3vm2tl4#J{c!%iz=jCdc2tE0L3=P&Ap#Z`{=ZlzHAtarom=W@f+Qo+f?nST|U ze?{}0Ow3%s`NVnjD)i`8=#e^!EFqm|lGfMfAf1!1LnmK{PQDI3dL4SCeu3Ub;L+?A zSiGt+-*Y>FZJBd&Hgs|}baHkx7|7Ys$yse658%-$j%KR54V;`B51gC|otz4toZ1bX zoC=+s(wuyRM{RH;qCe_@v_QMF@?3MQ3`iBnk4kHU8s;3b*EmLebgCf`^#uw#bSI8g zTd?}K$}XU)h4)oyDTltO5iydM+-0@qe?6E<=;szLqCVFFar=~4;XXy3^w@FF@Yp40 z|L0@O#en_>3qfu2^h-^CD@5sAQ%QZHwljc?Ys1wYK-4#w=+H2rF-h|=QAs1H7ltB! z__qh5^erN30|7)$+E4&dlSYTuTrB6<1K-JBxZI09@Cc3(5mWIl6ld3_p6Zn8D^HnP zefa9_V+G%F%k!0|k10Im{tkBpF0V*Vp8KlJS5x?!BfhO7R9p@f*OTl7p3aHKpM{D) z3qAhK%S7;nJ>yU~>lDXACgUL#EnwxtKq`oVd5xJ;e2n=#v6iw`m|?F(%nq9YM4cU| z{Z0m^e20E)bA8PguR50IJ{5B%PaD`*oicspQLXN)HybNoxncRLBeq|ANW_gKMF@UIjPVI?o?#t|Nt^j8JW`FZGSHzM|#Z@RyyVqBpGJWMyeeSC_@89~$ z4a-*@@s=*Ha)u=#&qKw}L&a*Jhl(4N={9)UD;|Fqdi+`FvD)YDP}t)XYkf{gS3HEG z1+07+NH=0&USs;)$3*n`2+XiiBKmwHfT(>=?JI!B1mj~&W9k=)1kJ%v#8fd0QTi5< zfyDr#W?(shsMkAmXcy3!r1_Yrq!F|RLlH?^g(!WCNZMuqQIob4K-8qsp%Xx3lICNg zl19)z3`Hbu52ExfB56kfL`_-??sxL(aNL6Cfj%nzkopwQH}p~IhwH%nt~xNfZ#{@- z5XXpAcLxx)*b+c^vpy=-J}4&DAx2Mii1|S^)geYt^*oZW5})eX0HUV)2oS!V5S3~l z6qD)@qo+E=^r@*1F?y=6k%asBR9^-VHPy{{=FGP{qEhXHVp1Jq^i+qKA5c>rV)Rr$ zLlOpXjF>>W0*IRG5kUBuKPuHeC??e*Mo)E!`F=IkAx2O29FnjcpXzD=QB%DR2w$Iw zO0^G)Np*=&3$L63*gNy&pi-R1f1;-MrkDS2ryoM14|22wxM6c+1C! z#Ozo?jGks66IE-KAZu!(*8tg*L|3#+=0bc%NWa*K+s&eEe3h?Km?}K1m)5YYNXgOLva-7TTQf*~+^VH<#v)Ki;D5 zF2I{hKX14nQdb9z74yJHz2^Zj6VO?gAs_X1GQ^Y(A~G|0`}*M3hw6rnXE;XWp$POdmdIY9KP^Yg&%QAn1D1#l?vn{3>3=Uzi>9 zL927HE^ss~frE(9QWRneCl|yUz%y=9U3Gap%>>f+d%i`5-5F-@yQgItS$exFZon;8 z601i{*WH}pgKG>U%%3&X2MUrvD1Lzt4~Xhm#C)FPs^}_ z@JD|f{4$R3dBn}kJ^@k@EAM=niB_r*oyYN`(z_pRJ_WN5{X62?6ev0PIs5w*vi7&X zqB)F;{Z`WFFd_@hVebOHXNDl8mWS`3!-({!qxa5X?*i4~;d|#W+VR6GHv2SIOMy9z zh6_wc4S+<nKj=d`3ob;Y6Tpz+Z z_^9+pOQaW&&yPyW{B7aVWsV0@4y-L-cb8y(rbK!}ct0C41b}V*c;#lJ#=|;qe(0spW`L38}!kSCJ zaQN=WksN9|{WR2jZrp!xLkmd%x*G;ia_|d>kfjd-agH(Rs$*X*gki77hra>QLxHHV z5VHM2AkMLOUS+W|>DX5bVc2`|;d5HO6v#9vIrx=K$jJwRILFi^)3L7>!m!Wv@b`cH z?G0LoKoXM6!jd~J4C6g(`nwd{H-1X8(s8A?Pwz`xYp`^PW5&ga95~pt(2l=!;b@+< zQBg#dy+?~!1o1AzOjOaHjPKFps8Qz=QDbL<{Y0WhBLU;g26VMx=lMl&G6)g!gnIF70~G z`@SBp^Zvfioq3&m;WM3Vzn|p$z0dQyuixi&Ugx}jTm~ymd3y^xpE&;&bAoH%jR-O1 zGOzg+P)zgZ5y7D$oy@Z3SPLQ}qO&5ON%MavLJ7r5z)d+<6#9bf5C_Kum+X%}&te%& z$jsE_)5S9>U5~%nT@k#Lqlp#$pvf0? zcMHe8Qn=aOuX_HV>Ym8aRH=ZXZmR#GeE*S~-P4!y{f&HnVh6rq@#M?`M=&ZEKXfm&qK{c?t_r@8`=UEvn1lHZQO-9RkRt779^`vc+ z(ORCB!Rx@fd~cJ{R-To?o4~q#Z=c8%HVBay}qZf{~zaB8N3gy zTVHK5I?J;%_z+l+zS?9&DP*%H9QskLvp)G|NIrj141P6iNj8{%SL1&(7K3}3MqQLc zee`THm=vN*&v9v!(R`p@mo^zK2deu?52Lj}J#znuiHx=a^|DPTV>eLO?`<+V4AjGW zn~aVF_59u@qq9I=`)ZRB>%~R!iN{_a>z+TzQ8<}?B1e*W{rFfP%1y@E$DctK4c$)4 zO`-ZF;Ja}z!BD?Az#+^XgdYoOSUw$TTwo=Tssd|)v><(q*Z@>t+-AdL&G1X5LCEsz!jE(X$yz*m9v zTHtyhy%D$_NP7bJ1L>{6qd$$XS5y|fg6F*b$UkIff2Y97+v#c zv>zCO2Z7P;2aJvaBk)~dbXx?YlfVc(4UBHrV00cBffs?%Z6u6t0;3@P_`#(AVA4y2 zQVv7%>Dv22%HS0If3(mv?OpjkX8k*1=5DVtw7olxEn|Z0uKY}oxtNjIu&>p zNEZSx14)p66bpY)z8R9wzZrAD-H1nWm%v@g_Xz9@Bu$}!VkXh@@Uw^n$EvB0eYYZn zolBzSSPLRulH6`ha@n%df(Y81h@}M)v{P$t=~=O~Aj0jiVa-@|L?CzGKJi$A<33sj zgBHuzTZjb5K6*2^=-78FLfE+^TH&`KG9<};tVuQtq6HDOHxWwSqxNj+w=cW8bX^Vds))Wvm5}nk08llWZ1u3nFN5B9<0J&`zx- z6n7IMrSW=-&g4&^b^TZM>2Owneg8G2IpDgG?v=jn+ZWvaXO#`uB_z*w{^#mn_x<_$ zr>7nLw{?6hpPmLj5t{oK~WFLJ(7z^6hotO7*C$ag70q&+Vqb5b7B4Sfj6Y$}Bz7P^yH& zj5u9!DAhQWY8=W(kA+Op8wmkt-KjTrayoW$I(Bk8c5*s)ayoYMqpyMDWT!Z}`}6gg z@qf+xMDSIP2EG=Ws{!EoF9uO-dNFrjrY8HljSNVI`-iaq>c8K%$*?5TSN|K2GGMtm z-k){644LYTmjU^7yyuRWAvKWkG6*$3T9$Gr_ae@4Ly9^R-;x3AAtN$irbGcl7D~p; zfO!yJrlKY}7V;|@l6oPhW`97E=qGzn@R0VXzD;mQ#u&*UYA;IAl%1!s)QKZsPk8HT zsjgBRS&|q~8SdYs{!68_I;pcJl}VlTlT|_u)L9vkoAipP%YU*UnE5(uapLP#E1C54 zW+vcs$*f5O+R=t@HdaJ7(nVeiDReu4{`lXQpgkhDuBIwhvSG#4Cw_y9l`YX8 zc8VA56pwW~djT9#QVke3y%($vnxFfly~R>?BubVg>`28bbR-rwi`tQ_=-Kp|n9k25 zaunrwCeHCkAC@sw`;nGvti>$gSc{$vnB-5q>{9gQSbXwr6?`Ey|IecdENR)yb_fjh zHcJ$Pfy)~eEFN)>!L=`rst@FRp3u>HBQ4cfi#hADmg!iF z+0oE4q`6Ku+~2xLYDdGnV9M-hur?9U=Mfo@bd}}PcQo*vrtQR1Zznhttgbz(e6gZ{wGRWv2!j-xRK9< ze|YCC60uvFOk_nT)Z80~??S{}$T(D0$L4@sDEWJ`-0)b?`y$`=4gH1sV&Lk@^A&IM zcp5izxPJ09uA#z>5yvMt)B66Wx?az>DtO=*0&QL}_X0d$@lJrJSxc4BL!7QvNPHnq zcmF4fvu`tw)7>bPyIvvAPu~CvarSM-ak_(86ldRN9H)Kr=m&9@NClF#q4zzh96~w-yJ$%R+M(^uTp_v&g##-VmDmw>W^?%J%I5 zcrkZNp8M~=8dnur_9+6BarexIgp*N60(SlnVXnFaH_F=mv%m-L6q-{9>{ik=@KjI&P$<9T9525hz&XK}a9h(yM*A|n?2Rz@stxEYa?1)VD+GGOtz zCq%!z)7D@u&9ZQoq}>Q7LmE`3l>v)Pcp0+J9C`asv~5x~tR=W*Np;IfN4Sdzg3KT% zf>k*gWJCs!!b3418$(V>qIWxfR_2|nPha@|;-m3mN%(RrR)nV&3&PWi_26m6a`3cb zHF#RF7(A_53!YXi1y7?A9yi#--s*nUw|OM^weB!|o9r+T8}!d`W(^OAJ7gBU-Ot?_ zi*u7zMR9U6VsUmdVsUyhVsU;lVsU~pVsVBtVsVNxVsVZ#B9p`l&4>(GuI{0(^;t(BTctEvUya2{ z^R(ied0KJGJgqomp2mccdQaPuQ(dE#@wv_itb%;(cM<285YxnQeZGCJ!P`P>E4>7s z<=BqpWves!bZlhfo&0dgYXhGN&9MQ?ayjeSz!O4qY{0o38|!v5*KxrcLUW?P?Hn8U z>c6Xp>eztWxn2zpr{9+p;-y}0^lgGWe@?Xlt3vW&foT}dD2<=Z+q1EArq4~{Qt*R`(SR`!HZfQGe9cAtNv6|ILws?n3{06-GLm>yt-z4 zN54$6mjy5B#LoZ^a%@ceo)m-ggxw+3!VHb*eQuJ$AG8)`faAFxA3P~EX8<^#W2024 z6CVPb$Z_tl0KTu64Ku)eX>nFqIjhgJR|nn^n)3vhT7mh}dQ~{_c@v?i>gZ#o)t)OY z@Q`+tDIm?ps|HhU?n%_As%AX4cwKkqPAQj=+!0giQ-QG`C$4Tz$7JMZ%CkhIUudb z$3-u?)b=z-5gp}v5ts(#VgTMvblSUnyG|_)y!) zG>{@`Trkt0DwubN`U*l2^J2YL%&o(DP6xZ!&}O)9_uK)9_uK)9_uK)9_uK z)9_uK)9_uK)9_uK)9_uK)9_uK)9{^@)7Mh?p-#U!`u!izseacWr}|xkoa%QCa;o1o z$fXx?Ln|*-@vgh)s3;+YfW zO72SKJ1~7I-eTIl@Q&qWJ>Je*hS74ZnKeaV4Th&NOvnkDdn_3%>qVsb69hyigGhs$ zR#wDlsi>Awv>a*P%!(Wq=@HdpRwQn7lg{1iv3y+mmFPq_n=Fq5!$hRbm)m0Yg(tH_ikQWn-XDpFyu-_?jK#Vy{wL(9(Ip_kC+ z(yGL^?pE=E2Jtjj{51CXqks09H}b2Za77h=9V`AiR{XV<_L?YM4vJGn7ScsvZNkdu z5m}TN$g95{V8vgQX)8UmM7G3CsEaX6WH%BqueGm4q)*;dbvGdF*EfnnDKBl`jm%G& znQq0-LkYfDJ`-Nr?uN-P43TjTJwQ6`Rd6R(wa9UJ_3?)Z?#X zkH3yRHoNe$C|nPUt?VJPnl1us6IMQt$eP4JUQ@boQ6`}a?~550NWPPuOb9-Hg@OcY)R#a8wZxkwj*wFxVqN90msAg?Lw zyeN~f&L2vlu}~7$c~2x_uJbJs;r^6=*e>fkJa{oLdv-+2k$k!bFTkL98pW@*ft0Pf zDap-=@bt*^r85#S?}4p}$hv&GSIB|fCGo%UAR%mxo@NEGAu114bs30icS{7#*XfzL z5QW`(S!rH1-$Wwjy%_GEgg+e8%3t|96(29v*JoVh-2{@A%5k|g=7qb22ZA*bSn)!kkFYs}}R70B-XNVnUMkMf;IjF_VPIsfhR% zSbRpG(iV$)oVP_a2>~367kJ}#^H__y!J{Rl!4!ct7;eS=E_w5&C%l1Ul@}rdL8QT( zH>q0sRLdw@j(@H$oKU3QBK=6Um_>@)yl9kg`>rb5d37@3J~FHa>e$qfyy(cAB5t?q zkVn|OE8$31-eScsW5q9H#pbe#6;H>Cr(?zD28ZIckP0ivRbdU;tK!RozCl`zeKBte z??sCBJ=B^io{1HkdljDY4rIbi!g`^3G3V$?SUXNwA!ha;3G1SYRCv2~M(IT_U#9f{6L-4lB7AC{yR9 z36W!&!XRQg#_MTwKU?=Fs7i4tWAV}E!w*@W9C&jBEgEeU`nDrh?v`CyNER5SV!|BXdl$@%~-mHbs${? z)+WNop(aEY#35e&N_YbW)-8?2{2QOU!pa4#Ta~;)!8^wZ3-v&>oT=e5FerYB;x&D6 zWEN)wEmjBYlB=6Oy~;70MsFlyo)p(bWJ|4#0=dj`O|gR+I}V}<)j z!tBlcBEpjC5#Gh0C#bpJvpReupRTrc1eWxUcs$ue zl*r79jJr&ULwZ^8wN!K#Em%&t*jW&RubObS6`AFN9rrhHUNg2>8Q z-43gz2`v|@WfU!|qAlT;do4<^*41?bhXC9&uX`c_`Y06?69bMPyh$ z@0HeutAfM!wKh!4qTD^7m8S*Kll!5ZC4xyBuQx+GIG1*iVtPwVZ_B5fBGiPgVs42= zE$yXm-9HsuR8*&0krj3Qz@zXlXmjZt=crOlcEVdDUy_!6slOwwL$kXe@=ir&DcN&b z0SS9}QHv|mlhS5UQJrd)F1mgY#FsJ?p*Eftr!-;5W@9qP`Z)6g`VBWrqqf370~bB69yjUAtQ(z;Pv2 zUkQAzr1Fu#D!e3ne|l{I;4mpR>lHj$wXB6_3TX#;~=ew#>)CB~iE_pZ+!y#$Jh_8u37YcAf@XjZZrdZt{rM?mu&O>x;lpkq zSuL|yN@hSl-G+g+l4>af`;=rh!(w*bp9t@W@|F=T7w=9}MS`3N!CJ;!5TS@_YNcvf zsS4|NE3z(D*nwQR*+1wk3Z*RO+sGVh*1l(DZC6->h`DXH;@Ng&#w>m^e5%2;vd5$4 zeb8d11lFA4FGFNrI!D;e%~m9f=6fS(J1C8)Yd5Gw*m=U6}4ram}6T{uvJmTPk_rx`X1(Yl=KAi zH8pRpli2(i=I2!LSZr$yTa#+bT>8h7&VEts8yUuiMNLK%j0rdUz~vm9HH*w%u810x z$DC+vqC8OCmx}{TY|dwl_2hg86OUuVfmTAhpYs57?{YLS%fX*&hr}H+o^YzYC`?>- zO2QtYWW-`H8PS@kqIzEgMeUweRPJfb>i&*gr^dWX;0C1-=AmyBd|&3H#Zn-7ltLCD zgWy7ygkDK`WPA*mLwAZUCfSj!9N$QJbckwqg2mclAOSCxWHu)<$>M4&{k}MBzt3{- zZnX4>+r8?(xfiw|QW5R1$TMP|&}BEuUZ z>V8wqDrjO$L(A)+#YzdRIm2IuNME!um=(StB8%F?z6%j{#_eDQxO!gCook+l0u^y%9oLe;H-ThjAM>4RYZP18fwUqD*Hp22^h5C*jq3?;NflSI72>KA*SOlM z#&MZ#8}o;1ehhe`q-o%VlE#1`A=5ayp~;_)J({*M-7ZlF#WS(u85EQ8gq!j^;{1Ua z@EsD2g$5<$*~m2olhRxH4{b z*qc)g4jsmRd169TV=i0b3`n-?w*RH;_JmUrn;9}(9-HvmB-I#1%swBB%vg>gav~1;^#{Jv_@1*(bm-pjyi;KC z@402HT||PG@{o`o%cq+}OUnac?N$*pF%!bddBznSwZ{&eP=gK52lfSjQRrUjx0^S@ z?m{LZoh<9+0eS@XE2&%)_*zL*>jK*^ zf}p_RK(dMskB-%&QOpmjtx?P`2U3sN=vQ0jwPtMV3AP4Q@e|;rlD>!eRV6*a{9`qr zocs{#80JS*@mOqY3|oV0%dDqEN#_Gm?As5<9*G)H17pI^zI;8LW3y(Fka9)Tpgfw@ z;vGaIfj9??nmrpui1Usu)!L1u%Bw;3PA+ZW4@&#Cqf2r_`VyWWoEByz+pw{BA-Xdn zgOV6&L3uuw8}-}$bJc=_YO|7VmHKAqdB-V)W01Uy!fncV?lrKPw)?0vN;g#IX7#q>*>GgW%rqHZ(#dJ1X`^K!Xt7cPYtHbOA#y+JkmmWbEF!P8 z@0EdTvFtl(Z~xHIS?%U~Az2M2mTPKx9STdjdT8ztB=${=e(+Og`Ol zu|wRds(WTjz}AM^8Ur3FX&QK{q%mNZdNe&Da50c@@<^SWj-50Q|4a^weWw8Ls<9d1 z8wo$9p%U@%W)KuSdc!)l(F z!5bk8Z|W56N$UI*>oI z&%c>C@paZu&O6grXJtfi>62NPC+O;@=CaOe<>E|M(~b5dvyUKhkuLHbqV9IPsur?9U=Mi}&>DrP{ze2zVn#vc40*?dfL|~}87je~@ ziw64`Na)q?B45fFp44(T*V$?0zFA^jq8)2)&$chli$eEGKVj~9cOjE-(|btb8P}|t z7w4^bHV~P4V)Y_+(^d7%oX-|SRz!QSVm_eW5D^ak{$VsnT=soWi_f!b!^LC0=i~VH zMot5sW+mrTe88T&!Y-O~qyf3;=IG%_7@HGgj?}_+c+tG?7)AS@R&>DA@F0Y1AJso) z?``e^5X{AtTL8H5L2}_;0EfI(@v5eIsRCc=yxh*w_c=%L>L%wExLsWsZN-H%DUBQX z{HpZLq}gp+68g}JrJ_*6qu+~yodl6f5$Vfaa)QH}nW1K@GBxgfJYb{Q+R4op_?^(4 zD6_?a@}&k|(Mg>FHd9x`(HRK+^;i7Qi&6HZP85q6|9Jt!Y*O?)lfTF>3c0>SCb+eqx|ucA=O_1E3V*e^G=VrN%^e=DB}uSIT0B4z`o*IsI> z6G{i>8x=}eiC4l*vAPX|dVQ!p%JetZG8$_cwOV|vr5tN1TUrP|MAU+a=_|?UZDw(I z33Cuin4vonN@ycRI|(A)t;9p{;T(}r+jkRuk4``AnK2g!WV@p=rfJ35$HL759ol z329i2>?B0glF*7+T9eO&MP3w1nxj_*J1q$%oEwQ_UE?vIG!{kfm4?h~J=8Z?%c>q>Gm~1w%LWiwbYDx&^reeAip@cU4x$F@9 zdr5b~114BM=nN(FxmyXHwPL9$A()$r=}v?aYT%Bws z{z<2>29a^=#MB*$m=8jGA`$Z%wRm?s;h@lh$b~r8{!8_!6RL*W+~Mt{YVi%igvHKN z#YHik)c9{D#PgM=EHx!WET2zkDSg^*h@to!Epf-jWa&Hkz??CqfCUx`6i8Nk#G_;NXcY60)z&EHUj-7j zdezow^R}K~Ye*G80oIiCJgnMlRIFw_v%rSepB5F_`sao#moCXt!a}dopIkr^QHylPH6^SQ^j9DVBcvgS47k;2WqB?o{N^H zpv8(0)|}xlL!>?Gd1cG7ArYy`r&}k$k^iSI>|Y8Lxc66-bRuxzuPSL!U^S3Z%^$1z zQEct2`O(Lsu&j#BQv-2TRq+$xpen9nE5ubLt_NzX8pmb+_7C&RYJLp3uB2(;j*`ZJ zAtBQ^Iibm)jy*D8Remcrg5sH2@eGQ|c)}IwoG4zBwEEr!#zKP<@@(Xqf=Ow6nClR8 z*^b5ldv4?XBYW;wcfvC$nag;GWH6p5G9bsIfZ=+cm%*+O-N}MLNSlZ=B)-hPwIm4e zelDM#f*u6Y_UZ0Bg;5W*NCPyt@F=>MI~k2^+ubDQa@%M%$BlBJgc zzSmh9H8m5vQrSnkJg19#5`K$=mV=68h5pmkUS4l2ofmy5oT z3(|7$^N0}q2hE$gnYAEtD%yh;^LFBuh|qNW8~Q9prpeRd6=lE4&qB}by{O4;wAKWn zrJQRQ;7OsmmW<|p+3Hf3H>%l0z088Br0eGz;zh3MfJ2A*wirnC@0NAZ~z)n4EnWz2+b!^366(5#@FP6xf zu+n1_eq=y31`+d27K@nAt`S)m2Yq3J_cXreY!gR;bR30b{=E3Dhy*R=l1yHEm_#d= z??ua*`eG)gOSE&IaRo>1u>&X6V1x64{dQ-FLGo7Vz+enm-E?V$M0H6o+O0w4arN=nsor0zWduHB%ex-0PP zuPF(SH#CUqP85WBF-Q<44Pp#PFzy@)?9{l%fO|@szW@K#oeO?XE=uBLrGgQ)rUQJgl{5pq%&~#50~@d;J;+-CcW7TSx8e8FNg5SWGqsGK4q4XOaf<y7xasp^8nSa=+KhmPt6+w&XORPmtenE>l`)GNrc}q4t(7H%! z_r|+ms$$h9tW5;;c|-;!UE}iU7Y%q`Q~6>+;7TB^3Jg{EBCa}f(O@3~3ESFoLZ-?U72jhT+#{NqQv5f88TS>x+rrK=L2a$-`(jLg|m709I0~r_KZv)9{ zX*XgxXqk?+nA09>nTfTSEe$RA)%|3{rPf7KTN>U4Q)WwpwTXZ}k4U?ut4lt8O9KyR zDqjo=90{axfuUYr#4~NSH0)y_p`{H+zLYV%ukM*GtrEF!me_)bU@fVo6@^k-S}bF? zv{=UeBcHL1-O|=22|Jo#8`?!d#$!AiZDGH_ZnOMf|GqKE1n%8!*jNNAzCHPhOOnA|0 zJ`yqe%)W?lBRQcgZbT&9bFOjEc}Z_Dn|H)cA}!Og7PC^&!lO<16cvbj{&{0jbM_3f zuwshOkWhUkjwallMdUnP1lA_3d>)YtiJ@Jl)b}fJw@&lRM*{l;X;2^&&{ld`%)cWQ zvL8MD!9E5O3bQZrrHtWubK0Zp52Dc@X7ZY8({!IFPKEU>!~u!N>40 ztXh1gn&5t)Ji8u|Pv`!nz?(qoEwyD4jL4_sIu&>pNLG-stx;^XtCmr0Jq{#nod;6$ zww_?Cq*~nGQ;(}hN#DbKSxHYYe;r88n;*mc1JyDX+Zw~xW#F=GF?FXhU%n4kL>zUV zma1p5fu1?h=kF$bO!#GOMa&$^XLf{Qa3Vyfhfpw=@x2#2#Fupb!s2l* zKyWZPhQV!(uWu8K6Yi)}bRi|hctDun7c=wc-h}v%+H?lj#fyxU0k-R`j9N;@>s&Ix zTblhc5RY9;0pf4I-f+d!z_{g_hE;;(XHgu;f@Xj{_tq#=^g5p$2Em^BPsP^6&O!(n z)sv#yc@11sl6h!d7KLOqA@(;SLV6RLH|>i);?iZm%v=;osoUGgkbb_DJQl9hzm)+n~#tF2LNJy6A?*xC=I=50N}*0I`p0=!nz_b}hBww_@AD3F>r zKZf}aYHKXEHHNK2wPh~1E>XB6pT2qYh&bv}8VY)b8|WDneO?cEMQPu5tP9?f&xEr^ zkC<7L&um{|uq{NVhfpw=@x2i{#Fr7RNx|Y)E#U4gN=7x84Dh^WzYN4C|ZH2wJR^z?w7s zWr)0z7(&N4&l<-fvi_BxBHju-48Mru2&M zQunxIkX*UD>v4{z;~Y(sqdlE9^Y-imvBgBE#Ewk6(eg70ey;CcF#@CF8ZKmRKH$J3fAJ2xW{=$~iVliAcOCVc@T) z75%z(igCuBiw@d08Byimmu2!-XJv$U4YOHiEjpc)%pobJ32g!98bxFzU8F3mp~22x z3+YC+)PM`xRc6Ulzf7Y089i`7Ni`t(bX?>utSj?@1Z%j7RD2$hc}Y=dE;BS2QkL*% zmL?-D)mV!;`LPylbio(1g`s6peDdoH{8|g*Ipwk)NV`!K&*Lb}U-i5ZEkSV^Ef;Fb zJT~k_zL@EIB&8ine1;P5)p|DHJ!y}$==K}5n7+hXbb|_7%&A06moD05!=33Our^`k z^N2i<7<%Q?S2B25<9j|La3YYZ0z)Z0k4wRM{^O)yTldv!$@Qc{cug!z3jGk@+#_@9O&`k;7`u`CZkE%-okMAq#Lf|{~yBa%bZp=iF7QgULMPrY|>S=w2_&v>0iL=$UF(N! zn+!*OZGG)#ybQ`hbiD8Wv$jo!-9M7!W$;Ldj`uG*UWQkBUIy2J_ssD!q<>^SFgVwy zGFr@N#z$|Mkap5eEKxTG200OLdDX$YNnY4Y&iB%N!$$AY)}f3Dj8`Q3Dw(11g}-%7_xk zSQ$_Nbyh}HK*q{|#MN0DQ3M$)1LnHU%7{#6ti_qHvlbJav0544k%fAu8>+dzA+nz? zvMa2Jr2do;xji*y{*(|_OeI{b9fr zY*$hZxT2)lHv;zq33#BS8jxaf7O9ZXoy}XbYz|FK`sWe3l$i*-)(pEAGm>y?mau}B zYOKX9^H_`Spurb&BScHCwyY(I$h9QHH%jmWt;gqR>@_R+GZc}q6D-MUC> zcg4G4%IvPNHWAS05!sP+y_HYDXuxNh%Gw8kSAldRFjQSFt~&DvYuLv?!nSi6`BKL4 zvX;BK&Pu`>+&4>XSVR`oih1KW7BO!eBSK6GSNBDcd!^rH9uZ@i-_f*8(n+ZrWzD?f zv@0U*azWzuF3z5lfn@Cm>yegfti_!4Sj%**#cXJ3+1AoYHoVcgNNPjFyI{&}Xs|XB z(B~1^l639Mr*CNB_nOMuiNNzfx)d0yt`^U<+0d|$frN(kA@Ze+;c+c@v!Pu@?wcjn zDcZ4?w4RGX_eyr-h-K^s70cL9wqhCEw|+^&u%_B<(Y=v~+0s@-lYOKYa_E^hwti^0;Xj#&Tk`2$dE|S{P@Gh7#TN*jAiVWb}C7@)Kr@- z?R_L-wzPifTdzX@;>PrKAXyil4_sl-C7`boG`)d*5 zsZ3IzDGH_ZnOMf|GqH^Qx4vQ-yU*-P65eU5%|5dmiI{!nN0tW8+?JR*-IhC%tvT9e?4#`k0Sf-hwZZ>ukMYZBJrzB%tZBEnI0wpS8XGMW(kBM~9J32zdgiAY#=W=kSDyb6@?%#GK? z*7fDSaz|(VMY#v^>B4&~uo_4g0xtu}s>;~bD7Ly(%P6)c0ts8!fz-UMC)j$ZTAl!h zl=MB!*Oc@G^Bq6Ro5E&^#G#I1zE>5G#kR(<<^IG&7NYA#R;WzfwM?O3p7UY^bt(M| zJ#QQ6SrL6+5BQzZzIk{i_*^~{wum=k=0rZTWzK+D+)Isr?mutSaCSv~#>;>hh1W_K zcF%KRg0F<;vQ7pMHOjtCFp(!r4%P^)VU&(|FD=H5Gc`gcGPB8m%(~t{h&%bLG9ar7 zJ!DU^cBt7aqk2*6p$yzslDUdlo~#oWi2a98ib5%+e;b)x@31DOPeKnO=HhO}v!2L| znQ1ay(aCA06QQLXv{)&DHD~zC5IL3@LPs;V-%jb-OWM23+XD9kY2Y{1JNvwRy6yGw zZ>y8u%4foXBDOUe+Zv5+jbiJa+A@FPgRMRd;tBABlBTdVq>85|1#Scq=FbAjns3Yx ztF190A-m%gFl2fRk1jOR)!4jw(MG6SV&3LcT2Fr-B@ zIw|l_K1H12Szg>KuwvZ#89tO;z|neznPf*fKw@oKHwz7v$5e;G&*{Yb3PPf)>m0oUm@FNQIU49IFi0lt?R zJd;m%NJ4c@GgStzE6F_jc16`^p7e%Agf@}z&KnsCBId~>7BRPdM9R6c1J7yM)#!A~ zf%Ga0$$a}@NkoE{^1hG`RI!=MRbgFM5i>Ct!pgb8m6Uy5SQNTfvR}l!3z>w{?v!GE zq(y697q;SAM`Xra8)qWY{(#$2W#GZz0crMF;MU)%B&&O%xK|aA0)ygOtk^6{6!)m& zC%~h>9rvmz9#W61%K}3XW*uVdk=hyq?rU~tuoV=W&o@!rt%}EiZ#9T%6o(+D;~>nI zfvqmJ^?QJO8pIT~LJ;Qt_YP6mFQ0x3EDNrwu`+Nz#|BU!n;xfr`zvN66IaHUQ z$FpKSFYPQC_Rcm)cgK$Ky_3&`XO#~MsuM&WMk40FiP>8a@d1#<5p}iF-!kn$iR|#4wccNuowCt(j z*rDyc)utv-_i6^-hU?rTLr%T;?W{D7F6IMt&d-rAhl2)4{; zBa0%kr0z}KNN^=xM`n=UjTVi&=#hS5)p_h!rKl_6>Uc$Rv#vQZr|=dcYw1>Yg_YuV zu~6TkF;(KmRG~4QY8_X`Wwt~2G;4=^9H_@;p&+u;yvUn$k$1v+sv;9sr5r{gW=A{| zk&ykTarU3aseT%#+O%~M*{WizPv_9A%F9@bm6xkX#5^g}9C0w=A7zh4%t}Ig6XC-; zs2M9y2n@@m98Xx839D#FG?Nh9n!?tcnm2>&7uMjhDKZd=n3n@BI7SR1Z=-SEM#N$lyZaamBg|ppI+v*;Efz@OE9swqT9XkTU6~x zMa>EC1)qvD=kl3wH)C0HvaZuz2KII7Y1-;IXxUILqrhDynd=WNLBxE>h6vW&1ApL- z8aAKf#9GGDvaMRoPW@I`2mYRV-o7e*+hN`aM(CjkCA_)wPV8K$YZausR7<5tAl@XL znU+OlOSPDtt0Xnjn_eqJ!aA=aWnk?$X~nGwyy#YvRfH&>Q^lje`+qN5st*MA2hzO2 z9yMR>6F3n_cytg*?*v{4Qm6QPsD4+E1cp$|QX(Py5=!>s2ZM*|`3vB|Z=~dYw6w|K zG!WZ184y^ek-?z){{l$h86Tk!NhBGO!9*aoZ89MIjI)@4jA+f~BZ;z4qpbp&y01zr zZJP`p2R>j~NEsi4iNI&MfW2WAsf-8=TFetStks~!G7Rgyh`5CPwAo2u9+YW!SIZA% zUYTb{qCR`HKBtOv=D3P8mT={b`8UDm(&n}df=^?yPh&-&viiWQ1$A_6Q6RBjIM~310(yb+uGuC%?wYHTCFg%cCPP`#zWl;?Y;7f1_=a z!Fk{VUI{7VV^GpcFkQf25HT-rVC_&VrUm&q{$)NeMqQNw4|8nq1i#PG zz{kG@r>ds{gP+ydPcyUk#Yn$=X1fA|!9Z-=WPru zHVN}4@L5S65>^tKIm-aQzE3%M%QzXFNaiw5(s-enHQV^Lu#P-pGM)g-N}2`Mlw@9K z^$Y8uikQuQURXmF%*It zT~f8!Z}VNscj9-@G81bt8`6bn>G-Wg|FkA>HIS_0>=M>~6?umAejr&|kRDQzmsbMA z6u*pvG&kJAzrP;bxqSL9^ao_nR0(g(q%-axxA_+gHA{M+l_Km3WnR~1~#(G~=+=4k7JH*&Q8-%-~y zD4*V!_1{^i?aQa975^))iXDmXzQ)wI34SOv*EfKxN}2*L{KG`#ep)8@oqW1`1;EQ3 zTaP4zq&PNUx5nrizhH9W`~dFDS56YRubFUv;$852`E+c+%N!ecKoaKIfaKD5An<-* z1DPXfh{%rk8;@umo?R8;DVBBz$2|O_tR;??LStZk+xC|*e@g>4tPGW0pI4> z!0(i;47^ZM4S1Q81Yav#891PYQ3HNird&+{ zDI}LRV8>5}+6MOv&9MRB=Ged&fekp)AGCq1LUVoq7nM{4t}3Yvqycz0q@*9`N*i3$ z6;K1t<=DV1821Z2APdH44a|aZMuC&L6#!n)6;J~%DQO0{uA~}pLrLX*fhS6;0k4JR zJxg6-mD~yg)4Sab1R$;3s|HtPSvfXfqh{8q@+d8@4*XtQ*EEm`^lV@z&{+kx68E+A z_w1O!U`r#Kq3?EzR~a7zLUL6>FJ4jaX9#F3kXSba<^Z=UE#5=vq!}**`lsXl1;@*fs?K;B&|@9%A9K7!+$TxM zco{GwqL(2V$#}`dyi7($WUwGa34$SImGLq-4!qtmhLoPDU`SW1tB?*zTN8g7(%Ld! z1_M&8!prbP$Qdt#>+k2adKB~eHn$TpCpS4-Ns6&QSMURZ$%-%31If&BuF(@4<>vWP z{i4LO7#UD+?qALP^QE+MbF6=%lvZtZtx3gJ*V=lm)lGe})F`4lE2B@ARNX7GP7yV% zs5)y>LDgAP=WY1M!+8VzT4?SUKETTy+qRS&<>$);d@A2LQQ$?cI+-k1yBB4#zssF` zz^8hqnFCJd3Kq<%rLFXwgrDZv$Smg!Zd|kyxZ!yHw7Unni34-3=(GXXa%|u*annF1D?f3ox(uf`1nvY9 zjdDOMeHu8Dt90;sU<2;w*ud9;%~~U8a#FpLPj_`ozD_iSW#D}|ue6oSXHT5}OL`~7 ze0JD^$c?zog`%6Y;sv53G25@y{pn)*9G8_U?yU8Oh&YRI4=~|w?cHd>hY9s%YF&ck zeCe)c;vmf{7ZeW!#a3SMfg4@!mV+e%D|aTHua*d`r|Q@=2V3sm`UNXXiLD_TCN zmQl2H>a8~Oy8gXLpQsk|DH?8bD>WhFK{*->>kUw|b`hxrkp_1Xtt6qPtXf9V@-96| zLn8fHwU|l5ZEhqdB643_!Elk2Dl!s88eH3?YI&?$M$vMlmxkto?ic9+)ne8v zZgVY{@E+ijXy=mIT>@L-?TQFj*X|_F_Q6rxk>1PB!m-+s;;R|+?r3alHnuez+nSAS znX4`Olgwj?rUujzqku{CloTJ6&MRr9bcg4!(Dc7V48R5xAyIgx^N6aBP*>f3_ z5wB&Nf3&VB<9@#KL-A|92~k1um2L%<`=U75s>HU;ARdd2vf45?lwo1bxpz0dpm;}pc^WHz8V6~1 z!EsTzpo+ha6@MKoHs4;Zh{E}x_!e5KL5tOAV9go+GDK<;1F25ATq(-9KjLNuvnFOj zshEGlX)6*j@8dm^{tzC?n>Q`&>NaOW0jo5IK`rxP#$Z*MKygkdA8 zGB7Bvp}3r$glkcFql(QWbjWpUpI*P3Nmv(FE`43Z1kZUnAqj6p%Yhm$1B2q1D6Xa_ z;an76sA4k-*TUMZ8>;!%e}iYeR_!l|cAkDDTp}S79+a4|EJs#M5uVHhE9N7B7DPH_ z3VU=a&Bi_?tSp6uvKki=3MWCNCL&D~FV`A9`X*Ev*sG)|;KLzaYWTLhOYr4C9cWhJ zp!)hBughdtq2+&~KA8XAIU?Fe#7f4=U|ERnP7v@Y&vzw*zJD^OkwL!@-KEdrzwLgu zF2i^KRF0Ryu@D{apK!bk2|05rHRg&q<&O>%f>D%moVerMxwl#V^p9+|o<1l4Cx0X@ zdye%#_>tQsuYaIEJ3dk1A)&cvEx>gpy#)6DBS8{8AT%cl9L}+U#{(O1MM*E;4b~OE zmrw5+_*!Vr0I)12?{0Vkmxbgd!K@6=ChKBcJ{<{IQPKGN%kU zAtcYnvK!77E11>if&x-LSp*{TT0WhHJ%KDv&&Jwh-FX^#T-Ktq09+PQW;-V- z9}RU39v50$=>>2ySB>DRR^tnbwli0HV9L^EA6Uz=ffu!q%fJmKy#P|jKCKiorRr(m zWi8t>a64DF;Jv^GyjIc+U@2G0;QLzeWnfuJFFsZ86t~MRFw}OrSlf<^(w@uJESNfW z$puooP7+A%`V4_Pw2sTbE+xGHQsPcOa5-=_D)vkHnxgkM*JJ^_mQSZ`SKwYC9SeLP zNU6(YNzN4B74aBZ+snSSl_z zbjCStc~ewMqn08(B%cpThe_)3KME4lrxRs{_yHat{vK z`1WDyd{ErpeK6hKO+T=b>$zYO&tHlYcr6sHuC#;s1uo?*)&y^UMEV&4P zca<;>vpy5x$KfaeWZC)OMT1G4+l+wZ&}$=!EJeo#B$-+IrRDT%Px-b3d|xY3cU`jS zMZtT*=A8pmik|OEz9)B?tfZN3&dY*7o!f6aQdjSBt{B0mx+OgavNgE`0jX2>I2t&S zTjOBT?bygRsdXeE>)MA64w-#U$@YX~14*z`1|+{;8JJuQul0N((koN_CK9z zd*6B`+1%2snvZ#2Mg~A!mtsN_GEr?u5#7$UvB&Wn4JuRA!aVLUPWx`!MSh+?_2!BN! zT35%+3sqRJRAe?@@@BopT3*Cj%p}EHZsW^#h{!4%3^yUNA=*#WO65%8MIc#*_k{JG zikL|{j6}@YK?DaADhZKXcvdWk1S_Uvgx!P)4&6$`Y+y{`wa!a}3w!gC9nx&?33)He zv5Xsve#-%KspKxwF67n?cM<)oE?|ys*$yTLuesbc-=g5991XlGw698wZJP|Xh3I|? z@>;h3T|Gxkb3fuDcc$eMX+v){OkWmmE4U!yiza(}B|j5-e60XO+}~6<7KO{eZz}js zW4c%Rrm`2E5WlJ5X}FgA#;lhw)GaD!RkJnyT41i2NK9^0(3<{hNq*el8Lc+(#}O@m8fa=1S!Z|Cntb<*=giJE9_?z)nv0+EJ_#bg zGbK$>o4fi+3k#DN*(bTK{RDpv^D#u=%8zG8^RZA5u z7lCvs@H&ug1h)TU^`{)}{i0%I39lSAcrMc58HiP@zxuRnOLm){11nWb?xfCS8MvV{ zIeRSdB#`3CHP4XPx_$Y_nq1#0dgOYY-Hdi5?kkOdib}@KgbTo$NH3_CGB9X)QFJij zkck%N--+Bp%PVzHwe;y$ZeGsd%Tmx{RTlT&;sfTe}!;~V0FfB3T}_-&5HVVPUYp6^T0y^!-U)t_c$YNCH#KHU#= zNY7y)S(cZDbyYr7vWHC0a;lm9WLh$~)Qk)+-9{$imriGrts70Wxgv}A3=-aALF7U1 zxkRJueJhdZ;TA;`rrX7I!e5j{J2wK{R{hiZK$trq8IeJ_voTf-E8|;}7Jez88PN)s zDIsYt*rM`;_>m?U_gVorHSpe%aPZDw%)oq)roWLbD-~$z4q7acK4A@US0?5DQ;55A zT$q@I>fq_iocdDZp%ri5B>dPi)}rrc1TE&7bwzyGP+!b*(pzB-j|0t}{76L3)r$G6 zk+Vp|{ME>fh?H`-6Rk;xx4Q`$9)9wC**#(8wUk%-;+FXoFz;>TAD}$FEbvcPuYpEUaN@NQ+V-_H+~ahft9y660SB|5b2c#9jusz z1M5KU6%#N|0o;aZ75*Km;S~&C6ii4HtW7jCSl?*>GpBr2Sep=m^-!&tKcLzc)+R(? zJyk2_F8Wqjn-GEZTCJGB9Xb=%CPa7*KKK5oRd+3jEXp%DUM)?iFDli1A3oJVbE79(c@s-ZJn)Ni#kFO#Ryp`E;j)Z4I)KNJXG?;|A>p|dIjtv|-QyEB(T+aax~_ z$ybu6jaA{CfCMDB&(?kHUu7&_C zZ($8FKQB6)khwK6csE*h)P3_vR5a}G78L#WG%F27Juc>=nuIjGj?yp{Yca1{wjwR9 z_!4Wm3t#S)ezHM+f6~lv>`f~%T}WowBNCV4pTG3LIjNG-B21h#cmQB$Y-&Tu>Nolo3J+0+;AkCm%#6o_NsIu_%uhm z`WNeZ9*hKiyqBI8wKK?+m?WM*H#(@z7eM!*G|DtN5ai(ao3SL#Jl_Q z=}0(U38bn(VsTulp}f*io&fRR{k8&#|L$fX@KQsW9{v~VX+2iIr_Tjm1QOAe)bDAc z>kK5Kn+T*hI`b|e6SbnzjR6VCwG1F3xqr187^15Z-8&7XN_3ZjM0D-yca`XMpCe-XMCc!e58Ib{DyTSnWNFW&>(NTs;_eF8zRC4Lh zN@s$*MZ2dx5{&Yc>sEBP5~5D>-G#_}dDp=^I)`Q8{BV6axl0Nl0eDHKXi`?4V*~CB z$+LmqDq9)&TFdr1@F3Vvk9ci-7PdA8FO5e#A0qH!RtbEY`|6~cTO_s zg9aaKR_A~f$*N}qlU}#80YBu}z!y3pWnhPPzvsY4bF`G35b#Qv5a5=QW`Nr{N${Ss zm4PQpngcSWK2Y#(m`Y}sDRqD44#<>xNicKj*nmv0XJdY=I+tZ2)9l&6%(K%5Y-P&n zc3w4jU1ww#*ox{?QR7vEA8C?jSbPhC1Y|N@IRi<*+mC_kIup- zenaPP`mKH4zp=CX(Qh^{O}3;%oNK3;rM?NkJ#HvE>qwSkD5jgca!3`y7oU=%GoDuT z#?w-DH{lMfyCF4}6IG}LmtR~&#{Ek!-81%Q?ifcaL!he80Z0~GyFXbMyTX-E(mmW%}vbA`vJ2XlpQ ziHgyDzx&Ij&8oC^7PgR!?NG?pA}ktl$M3etL`Ezc$cW9VcaIl~{yS1pwIf-I zcM8dIZ(+xZE3snprwaR`_?>*ZKSyBy3mZkDlyx7=*h{S_^F=vF#;8~KQxc|RPEUGI z<0&!w^`%TjyPnp}*3d7k<0@jV&^cjURFS7Z&NuFdTRZaYfpUEfJXO*xC!M!?aGT`_ z&2_PVFG0TL5R`CGSP&b*qi3;4&klv_oqF^Pc%q~lF!=opzk`#t*hzD3lC~wa^)-sC zdIX;32z=)`!feRV1UU+!nm=tvdP9RSD`-zxgO#WEWr`nYA(;PA+=Xc2(lBK|lB||B zyK_}BxDX7l2wV#!tIINNDE_MShaYYhRcAz$zZT^gv03%*Vae4jSh`f?XYr@J~5g}Rb%Gk;XtRJ*Q%p|rTaw^(`74s!uSTE8Y zYe8f{W`9UN-Hj(86wG`K}zIo5*6aC9TW zyhy*q1Tn?l)fv*E;PvFwOqJql; zR|4r+;8`GblWH4deU-v=5>^+MphI$4dKG@t*dldAX$ zY1;}UY^|xSC)j$V2{C_CfvvJeZ;Ffv>!kWJO?FlS36I|f5*{z8$J2NmrqF!$R}u4b z>ap3TCWZBtiacuytX<8Ebf$~I+Ju$QBl19EAc-kOP?SmNH;=?jpQg<0H;;vN zL`BNLIVG8|s<1{V@`QujfoMNcD`ulZg!=PYBVp}mcvFW0j{=FM!%;qA z@%G8}$%tO3lz|&cn%Wk)tE39>P)Soq0Jm;{7b0?_`898@;pBaF*6d-_ zI)&~Wqt@4NrNvy5q8)1q8KKrE)v@W<0)wy9Z-jKa6)`7T7K1G-qPsDCMnq3&c;#Jz z17k|Ed}$Yve%119Qs7n~q4+Y8EXCL2-iCtD~8 zga`V5L*-Bp{m;GSqXl+T3I z86rnPge07Vh^%@*%ln|^Okhc~JB8xw<`svks>E8%`=A7ubI*$Cow$Fj5j_Q>CFQ{+ zykx`6T#HI7#?va2l6CoPO?TfWy2+P6p>)d(?8~R89SIITxEJXoAM6*O;`kc-fIrxC z?>!gIIg&LgWHDD$C*t(Ad?u7UT0ZF1PPL$gh{&$H7`NPiBuVd+&xH4iZXv>SJ1fj~ zNs~0YSeWbtUwR7e%SpS+TV^KG;x5n0uQR5k?e1(M}{MOYVA#C#oWLRf3* zB9oEGsO1>in{bSbtgBC*GM+Nyje^kAIqQ74}O*DE+#J^$D0 zu^ z?S_lu+`1~B!q)qjL}ymW<5)5Ca6845qIg;7!#w3yn-{5x$it`gh_fHFGGMaXOF#NY zdp8+%$~!_9X8aD}&NZ-F}@_M}hihdpFxfK~S4Q8wiHUg^)meF}$D+3DFY5nWJZIjVeEgu3SR$ykUCZ)EdB{xdRQQjFJ z0}8z!DI>~0V`Z=`YoX4%B_j&CPPO_J#n3Iq;LpR41T*WN#-y|IJ&o1RoO>EG&UAVj zlej1;@HB8p%NS`P0MC}{KINO`hXK{=GVur7Zdc1rp2#TQ%oGDEvTlmeM81+3P?2?3 zMoW2C1{i0WY zK6mBmL@v=_+;fKqU?Wc{d&dT(kbVBZ)Ujg&QpBDO%%Q-s0hy^rv*y@H1@)buv{P-g z)4*2dvFQU4{o%_w08x^6ao{Xw+)qN`zh9C6xFLag3do(m$kCF{Q7h-Kh3L#<`hv)w zh$gttA?%A2S(O;bt1tdyV)F}v=Im+3*6eA8X)G1z5qn#5EO7Ux*jYLCIT8m04h4>c zQ_FIQb0l^~+JPg{1vpbV601Ly$;^RN44aeVD(*;*WQEc$S5RDcxf?wbLgFIJk@ket zrMu27uvH(kb_xzR|t4E4%ocBe<1$$so&<6>#(qn z2NB}BkSoE2>tC`G+Gve(V8?Jjpd|&N9BNE7@hAMu7F+Y`v3b9x1(BL)4_3_IGr_u; z?pO;VqCNtq_o>6(jPrVo08r8q>tH`gOLK0WS*8{i8gA&)1zE9fhnN|)#O#5i^zko>xJkt2yB$0ZMj9}Maj@ZDJ)Mb7MZ7!wWD15fGH#A z9WXVyt8$CVn>Z9qJMy$*1$i0?pO9Nho(7)N8?e*N!8^Hi>e;|tawQzJXV(b!OB12lfaitgi~>{V{X?!6z-Lv; zXa?AsD-SRwjOXY?C}qBO`QB!ax~V$vACVd3Z}?C z?Ne1w`FcL;m%{WkDw8VoG|KS1D7nA#V^PVuYjz@~#6DJUuYN4K-nM@%x!(TFk0saJ z=8q@Wn~StTy&e7d?dq+Z+jp!Qg}0iMVY&9_YRb}65&2(jdL|^UCHZtO>x|0*ubMmj zfnVw2@8zn%w}JFtAm>7N`2HZIi@l>iaB<>tq~b}-k*uOylu22U zPv4j3}GmR;%XmAQ(o#B!wAGAKzWQA{URY}uCMwj&3HYKRCT$cacA=!6capi`v~#jy8t z{=dDSv!5gF{T#iFuBW@|-e>Kl^C4t9=qiW{)P94E=J3SeDJ<}rRYoaow;3UdFN^r{k9hnx^2P@ zht~xw(Hjm2f_N*@xV8Y{G>gq@!cQLeYLu3M+!uuXM?xP#l&wliifRS3DA(AfC!BOH z39_lHc|RuT@P#{~8wE)8(?N%Va292DnunU2{L10+nwAOdEfP-8ii&GR#kHd1=m{{M zcDS`p6mqOeb~;FO3hb6BGlXd{HY?1r32lg$JI-*_*ItSCJ4p1QdVFN!O6kN8r9O{2 z7LUWlGJ2+jwU}1);749hth-+oW0JI66^Do-&g6X{WB|+51r^&N3>pj=GLvz z?_D%;E2w)hWvT|bnzR6UtNeJ9J5z^dt#_mHy({dg?y8!WHzayE$Ag{}&wLQ}pI)JG zf2_V&`Bb7hs@T8H+{XTr{lka?vji}-@7uXwxca=eW7VrRU;PlS86Dh;t68`QSy;l+BVtm_7u08F<&|~F1vEO zKam5vnuiHGVrserOv0+@wjlkwnk`?<3LcFLaFmpkZg{YgLhtJS%3Jyfr6C z%7n5eS+>(RD_#HkO0PE1HC+w!dsis1PRS(0GmebO&YB%l#thFUGA5@JY{2Wx;Cv!u z#_Ik;_1Jaciq7L4CcJi#Xyd*MqGdiCA9Jh-i8^*5D?rVc^S>VLLV$cjezCIhNDcVb zHKbt{o5wI?)hMbr{iLYgFpKI9Gp3%Z;=Q?vG$Wsvbu}!=b;tU5AU7QA$xD%2o)t4s z?QkPu$$@)w&dOIY{K~UphWjO2b&zQ9;B@PugG9S6?S#+SxdsIvIadK6x#${zy6!q} zqEDT1AGFt<$vqwvIpkTf$RWxtRI^9o&gpczmgf>Z&^3!pF{zmWLjGFPjmb=s!m^m= zzSHr)<{oJ2^anp?)Tz+p4u~Fb7UZ*E!axi?wn;v8*z)if*DQ~8ds{wa*n(eQ4*jxX zvE~TfI)5PlzzydwvCEWF@PYg&bU2eM>#=#ZE{vmLg<&)-qDZqPJe0Q>bThM#DB7x` z_*lKkNKvz4*K4AKeNDD@bWJ!s0J7;I(JZts(QOC$K1gpkss#wcFYAz6)X(P@_e-L= zm6FmUL)|8)6Z2)MOGxt@$<{EjCea0~l(z zyij>cps!N*%}Rey!SRe4dY&<3y%*PMinhuq4YBGv^ys?CEzb(A8DOfd3s-!*&~>_M zO=4u2q1R@F*P@GyChD6tL03;R^*yE4Uu4guS?{`r`xtV_v3_?=Pg zoR(-lW5{L4s;-ON@~l{=MKLa#K!gq^#HQolt)JqN#}Xj; zy6Js|#Fy;77X2B`DetwQ8a=Ity{O5If-pX2ki|zqXCXq-uTId4J3c~?)XePKLvIW# z*5+qup&?6XIdJYJ8-AS*L3^&ovFaU4yN5(?923M6)dzB%UYBAYh&tA*Zu3f4n>?Wp z#7j6Pdo9sD2Z`n`Al^#U*$`sJUE4~hPW>6c88g;|p(gXK?@*6n#k6o^g1b2hOSce` z^7EZwxc8A@W>`Tf;n`>a$&%WRnA|SOnBlFGj9J_|e6dovdyz@TqKYHfv|TbZX?dYV z%Nx&&o%88fV5#tf^Nv`i(YzCV10rmg74mmTFIiM;tWxX>@d3cWI{ z(5Hlqfk(Hz`P(9UJ?k8br`2^6KEThtLLZ&zelmpIsQk`oM+-3t;}}SZ%FGmotXZOm z&6us*!-mY5VZ@VG_)To~G_%=L7_`~irisn?f+w_j*=b@!aXoVVD*Edp?+Q&}a$>P5 z471o2h8as-sBd@Up|g^EkgtmV~rl^KyS^>c+*`&zNpq7QA7=m%T}u0r~Td{XRZg*Vg^ zb`xhPrVEzPGUPmt?ny9wHywiZTo7UnGA!*L65ak0*AmqSGM!$RVo!NWPkE?!suB*u zS7q>)99{P@WX3>G>{M%Zw$aM>T+o_3eU4VGY(O`!VGu+!&hGcS7*NmC!uQ&eH zP*1|vg{PTbxmu5hNBRlNlTgcz%J-~gm9Y8H+!fo;iP?@L{nX=}B0#y%3t`GqRO-%ybA!Y5F22-tEBg?y;uJz&s1=Bpg!V(tHWmUQ5=$ zA{hOy<$yZ#sO!|xtXYIa+Y<<%TTNIOgpeDRc#ke(;=MD(Bn{DOA!^b7`CO3P2i{{n zt;rXYTKGB=Z$Z6wkNd~ZrFSF?CZWF`>e#z`k{8sgkkkJ@tnpcqJHN-VVo^ZxEvNVa z_% zrZG=eLel)1T&x$Pd|o{(OEYUK+;RQ*5z1eB)~3jc>w%BjMRt1@{WRxQ{1}(slLP&; z(KSF5P~6fTwdQ@-s^2#%(zn|86}wCHK%`e%?s>)M&@$k)#99>5oZ;&M8B`qzb;>3! z#3Uqqns3^LESew|CA#b&Pc}tvJJuK^L(iE)!3g!e{zlqm;Y#*8Mh*Aji>AXUiu zDb~XyCn7t(-?6$y-uA3mdt+{i5AWBcFBK!VB$4XT^;uJ^gU-ac8e0k`!M6+B`%a_qoby}hw z3N0nv$I2sFu~RgG8&LpL)-#u-r~Yh|9KoTa$Dr_NP~fa*g;mR#s9lic=PFZ>_Kqmr4WrAG3O6G0HAN$-T)M!4}ZJ^g(hpj?(s7doHL5#MrITB_F8e=-=I`pP<{W0YGoLE`kaoD`q2f3E(0?;p96(2*s%!yIQ zPUSHhF=)DB!kdHCo8(~CKtFf&u0m3Ob8-lIR+E`+IxR+34HEKo>FPuu%A-2@_JPJx z6P2ng6Kh**Xo79TAoFp5D=0Cx(AWf0(yKD6X_y7I)pu8BEB{p2KmRZG_xy8RJ$L?v zsB6o@t-H34&PqUb9OOx{<3$gPLM_euZ%S;@Q=$ThzVH=@wIHIt&e1S!NP7#AE$3MD z;4!q4@)T-_Nl1@)#8|Q|!!XW|jw6i@Iz&nfhPsVAq3T>tM{^0MeG5dxi7)Sb3*Za+ zAt9;05}Ih`avs4ltT0xF73+q$?S~{JU=qTwa zZ-p6U%2|oVtpy0$7o3%75LUOrM)s`&I3_IwCdbgz^E5tH%t7l zuTVgxIe>$tvYA{=`G_1{)-~HdP*@YwyvFcO3$0t;n$}{op zeV!TftzE*HNjPMDF35teDYHNk6MqaM#N4b*4MtZyA?R8;x2lNIvCING);>KN4}ET2 zv;c{Y^rDsMxhW34NO!DXqHF1p#R4RHYjZ=8x8BO$vwG${(lsIOXxVpK9zZVr$K>JK zs>p56+7Y?yS?&Kx9nh_-S=`{!iSwwo@B?yES0nZ4_tsg@bxl|m;rE{N`y#R#Oq*ILG>vPZkTi!C zi=`?m)TE!`yjcK+P8n9{lVOGS6IM=`zlh;^F=G*reC@|*x$blI{GLK@i?7558P>J6 z?1EuBWww%`KvFSBsXy||l@*HH8tj?uD;0M0ObWzF3WyawTWpH+>eZQE3N)ON{e#8_ zij06vmO{I0g9r3Lx_c%U>+b~PC^vxLi>A_c+=O+uJnB}F583zZE*gd+sfozoxn3V@)vJN@YZ%hy z^L>JPTOPH3lI88e23OUxREMYhIE z!wP&Xd}(@F0a$hUXyQO5%O&&H>K!@R@BE&qie#!ZQcNlICc`Rv6n%PdNQyCF7KsF8 zS=lOK-N@wU!}|EW6r;_|WeglVH!Q-5=Ls|3b17ce)wow|)#!GCZnEvPj2C^0wkP%V zm2`6*eJJ6EdZ;BoEKrk@14BJovLNU^`H6$V9WhO^`G+@FDD~wEkOFD z{jRf8oe=rlv%>C?kQXKkTB3W3ML`%+Sqpb)B4Cm*%=pKrSEY%Sh{@04nkyk?pGZr^ z4T^7=^B5I6bxk-wLJv{2uSUkEi>lO<;#%79i1soozwhIV;hZRf>?PV?d6amFRE|At_B$#KglKVv_pWK_P0CzjHy19;6enPI;JMr3Fa4w0kSjHyjWp#FrfHE_ry*#o-|hIp

  • )mcZ*M!|eRie*yy-}H}K)?J!dhu*!Q}kYrcPRQ@j<+^j$Gp?^hIyK3@DJ8` zcXhSAAj2Ps57a#MvYt@&S7(XEA^(TXboOhAvUx8j1 z&xk?3%85aDDquzol33bWLC%^*%ovvd{K=$T326WAdjYHCp zY=b}_I!Ip6j49KnAn8aZ9*_ra#F{t_!qmEUDBmr1A)TO&~T^stY8vzrL_i|#;3>dQ&g=E0kNImy~xwwA?n%r%U`yff(RyFjX z8%~cQn<(o@C*dYhI zoTJf$HSBF@rn2^+--u^si)L8|(?raOLFO9}dd~$Rdei-df^eX|oV67NdaF5M{LPjqczy4EgE}hb=Gg%7cSR*@UWT|m`zQ0hQMWmM^5y|uti~DMfj7ecg zOjUv+-71r%u;yj0V-)FnQbCcdR#%}6NLrJ>6iIEFEQLCN?La_qJOQD z*4ye@lR8^nYwLZjZtBdgMklI^QaZCs)x9F>bfTs`sxF$;q3WWk?RNVQ`1J<#gm~t| z(vYumV$apZ=zg}FKyT=81`4^I>zy7!1QQef=c2j)fj{G5Z)Ywc?ApibGRd^EF<`Ry=)?^A!5M^YjTMt(R{} zyf>c|IIGoIkY+8ZigYOU1`5gY#EL=tR(k@;Sg>Nyw4Tuh$r{p%LDRTK43ajsV$hRr zDt!VuFP0U9e&NL+cXMK?qpLR;f9L}j|8dB(<3D~@{MT~Z3TXBcW@QE0lj~#9v`v!* zm<>g-na0zaX*{i&#?zXquo7(EOylQirmfrt8JcyFSzFUQEO!ixCSg@$Sj@7snr#g$ zoN%n`q`SA8fGrQ2y`q6a)^hC&?HlefB#o7CxKTF@A5V##@hlQ$r|apDA$xK?9eUD> zLC)vIpm)7kY>aGZrTR)&v%4i;FI)(#kcW;Hy>G+%|Fu&befq8i$gZ@rQ8aB9ZV(NN z)_$bcHmopwh7}9dTiH7CH5!sa&Hxi0J-!$%_|WIhnZ_pN3+qd>n<-W@x^qEshgTen z3qEkrWsV$T5JVrPTS0WgK_0WP<@DCHVK@>Knl)5xR(^g{hU$zND$kg)s!qt?1zkHT zT|Y82GqZ4G1r9a3QTgU*SS2qV8n@Ch+v~E41v9uqHHH<_(x<%4kxD{L*96&c#~0Bq z0c6`lnw;asd_~Kq)A9fZF#W(hq_HYL)C^AYAz9tEgy}TFNmHUz?hbHEtk98vN`&bCO~>Tq{+T2)o{1d z@&GN%Zd)4ds~tjjIxW$@irefX6Mk#4D(!67&GtK1y;(un*_&Mei%6FFhPAE*BTIV2 zD(vyzYusok<_lpTE4t@yM80(E z^|7LR(G}HJ!PZmi&GCpiF)1pJKKV$WVgG7+MXb9a%8`TFrpF+NauYBiOCicV!t5-K z!hLr(H9`+(6O_q?`_YUUb27A;utaGA(k<7iO2U^ZhXkp)T1VSxxIAQ5klb#Wtug!I zgotq0WM6kpvgPe9t(w?EWz1bovm8-p%vc+R>do=|TXQ!cG$3|pLhQ0e%!Vv9U|6B@ zgl*fFg0km=GaG-+Is~Qs%w-W1f9^NL+^k$9=UxYqGtWNLBt33PK2mIw=nQ>JhY_4t zm<=xzWT#sPj=d0x0V5UbL@1tcryV0G-f>gG$e~DYYour^T8VDixZ`X^-McN(oO>7J z3yNo)FJCDt{z|cu(MQpGrEth8{%TS2SBr|HKRw$gh4;PUb7&d#T4G%U(VXGy0lBL> z5bBieN{C7LtW%xC-eNe~jY6^dM|W;kHv84Z^NO-#bY3K%vQf=2*_HYL4d4OTrcj$c&rmqjh;$ zuo8ug3gWFqZ$GpEc_S+)t}fBvFt}Ad!So73$4TgkcLgcYc@G7t{4fu7Rv~XYR`eDV zkmEnh0~g<@bk5i5SGwM)d?V~vg%`8iWpYnfJIzABk#5u3P<_j(?qBH_J(c4@FNv4X zPw@b2**-b6moYKk=ai4&!!xlmISO-PnnzfE^j}(`glm~-7@zQ2_0TyR9(=na^_BvHc(A$#Q=1Cq3B zrQ$W&vD;(lXU_J>lE`Jxisf)LPYP1Xol>BOvH+;95^cms0VK&e;^OT@&vZjbk{$H> z_(yN^PN+T}5)Aw@UKAW4liD`8@1 zKAS@LUO3ay+pR?{)uNW@l!4>kmnZ}ux1F!i$Zkj!NK%+C1eEaYzR*qrCy+QS$+a4*Vh{+ShgpRxT5=FKY>niDM-oMCz&`(Hw9gjzz6d?KcW? zQrZYX3AZpp$Yt4~9`DQ4=UkwpRxFhQAzZ3X7XnH+N4P3G%R20Sp=(kHIu~fY6-%W+ z2$!nUg@6(o_Nweq`Av5>BYHo$1qj-=oRw&5Yyr~#&H9rQw{=Yj^Pohl>5xf@&Za|F zCAygo*^}tIbV$d4Uax+St_jt@E76DPkSU4Ir9;*vx|I&um*`PCQ~S5tk+ zyFUW!$>blele@Z_S58J(>Z~PQ4eRJdoz?kg9PqZtnr9vTYW=V6zviT32LPdyH!2JF z@N)FW>uL;dXhwAPuXtXn?g1Bo2arAhkBb3#TnxbDVgMc&1Ms*Qfav`g0?_ZA{0Q>M zv1&ypYdHDbwNkBUK6>zs`95ds%aE@eYYg(_$Li5Hv)z7WT}^^-8I!`U>rP|uL=LUy zz_0#vz0jrJlYzsCX3UXas7r3>nlYdKVx76BYsTDBVe^-AhTi{5y>P5+CfWX~&g{@N zV|J@>JI`EHmnO8CB!&0-qgil{sLManHItiGVJ6Q^?X`@8w#q}uM~b*nzFi4NM8-^2 z-s{@-cR}{MoG@N&#Bq9?&k5tjAu&z^-gh}+oLKps5It`0k#o; zAb4n=av6;}_!$8)#_cfzbjMPCyqM?cAv?t~-R^DW@Q>F2p6j4*T?ZvkWReuf57r7a zi6RrEP*v8jf|H_mbTtnPKz9EL=i$Ads*}^Y8Y#$^j`bLFUo2yEsqKvl9cxY-iHd2? z`T;%Tx_J$9-mxA-E;?2XvTLiZKdUK)yJDIkABZIPWpWfqgw~TICB+e+2j5o0;o&bk=GzK|c`=ROkT1R5Qrm$FN57H-hiTcGCPi0# z0)AVeK*~0)2}$<0Sm@3?wo3&vdsb-*qm-pr%7Rd|(W-cri%cB%g{1b5mfJa?mdgdsfS#_LG$PuF`-zpfedp$e6C*R^)qPE_dqla4vp zM&Xrb?zB-@{!=+g3L{#fWQHh^4YC?iARX9HKr{F=!CM;6lYZFGwN0tOSkEMzjqzr~ zx!K5N6f=S|$9pw$bHjPAZC=c6T{F`RXNGIWWXv*LGo2I|uUSvjAYp7~XbKEYE64z4 z7-oVL7>8DnVaJHeOg9@=mo->AjT4`C@LxD=K3Dl!P96W97Y0# z1E~?jkb0!i(^>cHlb%mICO_?fThm{^Q2Dgu2YO7k%-`TK{yHjSpLS$_fivw;<}cC+ zZ}-2dkC{e$aQF1r@3cC9NCsi<=l_T|Fo!gH8}-7S&|km9*AmujQy|>=A`sSIQy|>K zA`sSX<&s8M;gWH3uEH8>3WQtLUvofMlTCqepA~_ymYM?Lt`>o?wweOrl0b8=!rE3& zZ43_F9sM;2g!Q&55N?;Uat;V`Wz6}Oj97-xuQi_>rH`hSvce@!kW?2zp;*R*)8ONuvmmN0^zbM z$pK-pHfaRHWyR9iB5>Jidf(mH@5i=;+t za9K9xtid{wBaPPJwrl&61Hxj5(+Gsiz9$ES#d56?2$%g(V@2SyOUkJY_e!}xg^R#O zoi%N)CUkA|2QE9ToLX3%;5Dj+%b~OyDs@-JA+%lXLJzxBxF?XSjx`3^u~?rW%*j0D zpks|ew!2fCCy=>K-%PVj-%PVj-;CSzP5yCb7m`J*tpxNtiJ2w)OdADG5S!d!uviWj zU%KP$G00br^#t;@V~s(+(=1*$ssd+}O>SXWqnuYVWm_IJGgPLJiHT_qBefqZ1-AjveD90d}LIevyDM`UsoNDW3GBttNhqrg$Ek%MF~+Q2|F zFf(j8Br|3>7>zx%Wrvz0>I4Y@=`>rg>!>vht%jISNa9YXhugSNP$~?R`9IxLGRDN6zKmZijef`OpXHm+Q>oD3o|(i?=&eHIY_!@ z-D&-uzIjSN-E3>pPdD4bewwLl(o;9JNR0* z*@ii!KYmyJk3Za9-=)K5HuysQ&lwcnYjx-by)d7t7w3WS=JdC0n~p`8^ZH}p5bQ&T z%~b{_L#M;l6b>_xnJaA!7(uW9SUtvKQ=D*jydHnr!NB4a+CYi-M31_z%4CX<>8k~0JqlUV{ zBx!kTaJrR=8elN{^hXbaGt>+QbEE)+GpWC*zfjy2yK(%%eb)%0cu$Lo2G3!VKfUL0 z$fAw5;P$Q7J9L9mm>eK@rErGyphW`==7|32VQ^NP!C-C{U~tI!4c1^X5j55>oDv%U z%HrwhWxe*^Q#dF3iyDq%-_M2sIPd>bLuR0OEVj1*hhr2{i4Izhe?GJThvO3gDBk^r z5CDfm3;`%k3eXTum{SF9aAupqV7@NE;2h~Ma)Kf=v5yO!rC+Sqr@=j#%+~o?0v_vE zuM*DtW-4K}|56w~I2-y)gC{V#*XXUmd9Py#)tKUm*d73fV+a8#cKzkhF*yDDivSc^ zwRj6~SiI!J2G1?i-5lsR+K4yQpCvrIe{T#9>v?%cku`mTHkh}yK=Rt)4C*h^Mv;}5 z2f*18AYWH_2aU=ozHI`5$2zXTZJ4a*8nX*rb|BtII4tv2DT>@&^?-2c*Wg9C1oSYr zFVA$4&;WzUu|Pgh@N!25cKMTAQf6ehuDl;S3S%BL8H(QZz2>0dpibuTo~0j*R_eDp ziv6YC!9cTCHv5vpX3y9hHhaeA&^?&Pvd5}~X3dkSq;N-fDy$%Mzj)>gMfXKk{#-q8 z8ditM9?yd8b*xFq8ONG{oY_FvB;=lBO+X%tm3d3y)}IGD0eMHPOm0hs_g)UN{b%aX zx|~)b?{qak2LQ=pC6i-4!3`K2CDsVs>99O#RtXuHwZVpFYb(f9%`FXM7;;1tsug42 zW*W9UXeQvy1_kCxE67~Ok-6nTGuvfg4$hgitRVD>p4hQJl%Oe#S;~rqr`VPk&Q+O> zaHg_?;nOvyQ@xT64wkLhf@Tm>zvV%b^o@IAqBpEC!&@YYeM0Hm@<{1qXv>SGWs(sC z)ncF-w8jNCx6|5W8dkW6H7s_p3{k5Lnh|QmAQ_-m4B8LYNe1hp8^4o~6*mmWHZ-ty z+?bn$eCJqWjHE3;LRhbNYQ1h8gRE(xZJK<)vZ(@tCu35`k0fXo<3=H5Wy_7${mNM* zu0w;%9E9Ey+2>h|M}}hN3WfZ*OdW*H#v5agMQLUvT!&`Nl#ywIz}oYjAA`+?Dnpd< zX^@a*hpK@#8>p-#H#ItqSaIx*H5{@rl{vX0!Qm>TG^o!QEwzR%-@&T|CnSMxzQZ+^`;j zWTaKb32S@^+&bfkcG`gU?X?T$OFn^ zhuK(c`p2&Nf>#fRSPMXrb%O_-D8`&-_`kpzP$vDHc{IzM2vfZ44@7JQ%wOQ#*Izzg z8OivRhw}W7KkcC0u9K3_+v8Hhr`+WZRx&olTRFC|O7Tu!i{Vp#)F@7IA`qv{@r`Or zk+T~g9yljbbko+B0v%4_r^x&w{iU#0(=n%rVRu9sq}FLl!8$)@$UOi~pWF9m zU6Dfszu#tDhAG~wVok>Q_kV$t+cVpt5L=u*RK}nEiF)R@Nd|gNJo7FbciL|0^w)}w zh@Q|hXqE>(Bc6fsi13{5GFvg|dGX9AJ|I~qTd^?Gmd6a6UzMg-^0{trT0PL*`ZPDq zAi4Ev#h|(KX~ZCpe$0oABzP|uMrdMZZ{O+9WJYU&bjV4$5rd@uR?KxTx3U-~6m%df z7Iqz@jXuNL-HN3~Z0o=9b%gHtw9YfCA@7N0Rr8EREf;L)Nq>L≀}>>uRCUGvb+- zBp{b^!49V_;|THJa+`;7Zd&!|-iTjCk9onYcIEG8YE#k5Fh zjuea-Br}l}gJv2sVvx*8R*bo*+2I1u23k4jmzs)PgKhOSzl^ zy)T|Q*nsTG*TNe0#{Xx6i48NK5k$J$Y9u!3jhhCU?%;|jSUKXOUehq;jp zJ)n`B*`+WgrnSqfIxjVLEf1POoPno)x<1a?pdRwFcz(Hp~%JRonypn3M)h_OU?ms?5jp!%>| zB76+Vqv)9@+zXz|9m_&*xMQ6$$agt0XwGNtqhUJr;m9X5LE*Iydu%PB58VM!74p76 zU)^b=uqUR)LUX`s>_W1Ov|`YQemiR3*HU5bFZdRRUKG#hgCrqm^`LN8cFqLJ&waW4 z49zYe6C@pzZ>`(V94?t9AmqR=)Sb?-VLr~7WaJG=T7_if6OZ1nP-vE>Irp_-XpW&W zD-=lBRuGzuoe5GPWt(U7AW7Mo90d||76;|>c9(?5$kq47vSQFA=u97lKAmS-L1@mn zGC>NQcG;&9h2dPW`Yz3#muTK zdNap6i8*SEw?&`e(6@nPa)r(xjKHz>X<3e{6sG^AkS#oDnk3!@l$3%R=)-b z$rDf(3GG+HPkGX*FL!JR&Fa`_n{2W;W{TZf^)Z5eBc9nBK=L-bbp-mMW@lpoax^z# zL$7LXHe!&~pYlebN5nHmA$b$t8inSCc%u!H#kv)PW}-J@kau$PEfX_u<{B|b=11cP z(<9TLVL^^)DQ|5;^O%xR2FcS$Rt%aK^Nlv%$!)d^n9uD3pqX5Z1<14J86(ClGn<=b zpqXWi7;_Bo1zUfi?{3u_%lOMKV9K$cLM}Ph<1LX)QU(agd}Q@QGaVT>Ae-$K?&=Yp z3@ZA$t_BLZpA&=T{bREVg6!3f!fJzNw_(!LQX2){Og1JUw}s8*!YR$jg%g^!5zc5< zo#rm)vrHX@X1kAvxfu}Lt;mFQ)|_IY zOeRbumIuwGV%2HdU~aKu&`d3+UXa{ewPN9nVtMD8P`Yvx3iODZP{tscM65YzW)U;9 zL!LcTj4@M?drjS>HRnW?k}=~r`4Sk3vBTj5)H)(!Fk$D5{7kUZ*b#h`g- z&4}@?+FUN9KySK?QiEhIWwk-Gm@;*T-1=$X%FvzeT%-osmpeXz9`$07&5l=}D`y#_ z9G<+)r7>vEMvNFFpDD0afc9r1HOQUZnFzFB2i8~z4(9Hza6a-r$AczOnvg?|x})D3 z-@x43Yur#%(D=XQ#mo{W%t0%BqR^9S#8ify=JsQazJ9m zI3MZEWp!v$xv2u=*;&0tRv*bNQK5ZSuaVVRgIY(RSza2WkQ{?pv10PCot6AgbOvH- z54rSS0<2k~0s3gzU_%N1<8D8YJYfTglcSnPiL6_i43AZeSh%dUVs6INS&1>gIZKaY)ykf-Fy~qe(9E!=rjQ(%STRojIr+Cd z=p#2zH+>g2ToIe9o@eSl&@F500d(%`pPibr2i4ml3=$oRNaaS zWWG$2oVVa5x7#R?2s1bZvR($KkUv|7=5!zv43lBT4AWu8yj@4%T6Uv_* z6puyN24}m^fV8}K8l23{mdDiG{YFJZx26b9j!&(%%4wED&qJx!Gibm6dcy3@L~X^Ohkv170i%tnyVmcPB!a- zvi;>Sx9^7TP#-eq>X0CP-mFw;hLm;}&y|!yb}h&*~#|j7*S1 z*@@n5SkrWCP*Pa(L&Q0nIOY^L2F5?5t`LwCP*Q5 zfaj;~a3yGs#0LGeW;nhtlP#UXQExn3ce`T_d^1T_eM}x1li7nq$&AUdBu8^~Loe&? z?PFyYjl}A;Rw|h!1-_~Gxyl!hH``Vy4!JeDQ9xl zq1g3nbqDKJP~onwM(>Xry%cG(Og2o)88ghv88fwocoyBZYWNJg<+cB4-BlXT@<`hZ z8_Nrai{*{{bREm90+yHRSFGo}cl(9w(R11>U;OdJj$=fBDzV=f(La*dZH(woURkfn z_XcQsg}J|eRx)n3_~WfB+d-gtfy$_3g*W4tb&nz6JJ!dLyrX25b!mym%x_Z8afJd? zzZHaL<~LR$ndPk*G;6|4U&@Sc^tC$Q8)&oH{;Y|e#AjV5@3HK&yvv-N=au@|_M2C3 zNayU^4J(!gKyyOyg~~VIKG)lX^e)uq|HdT2mOuZuaOa=@8&P77x|*8> zmjKx;Sc(3g^*cdwHv(dgaif4lX_CfOjZBilp_t~EmLWOf&%hM8>6(G*MI7;GObVRbXK)H6(i@dex}e`HF=v7l zj@^cQ1d`lpvCtfsXIKhkS1SlTr7d~pB83gl+-^HkfqR@54b3OYGcy!8dbfg{ymRL> zGed!UpH>i>Q~6Ag!k%{bnHdTscZ-JRP(Bl+z=^pPgyz6J6Qsc1!pt@WPSGtInnUyq zO@W(;8JYrH5{rgr=E=|`6%GV5G=)ufV)#kdwrEb#tw!i>x2`tbnF5;}D+tXVCo@ff ze4d#mk#SCL(cv+<<%LNt1C!0z8f9j}y-_Banh$pMz>JyTnbQ1gg&*_a^wE#k7tuzF z=cc>eBQziLqTzsN@hJ7MXYrolf@krx-KJ;paP@o7;&GgIchdfGpU45vB5n1#4E6D( z$R%BGR{DF~<2Yn0Qzgind%Wcd&m|wbgW4zT^2lc9$O>}T<*<(-Nn4ps3VrTLlaF~G zWzn;E_+;C&iVvTBOde!$kr^oFLsQc*9~y_rhW@KCPa*j_jOlyb(0lIQ=Tk^t53*v= zd>_U)7KKMmH)_$o@F6wHK zWb7lydcv?(UPwzoloCfQpz z^e70a-uMs6Qz8}#P4+hiAj$nk86=tCD1#*NTV>Ep0tOjQ0R|aP0LEmP{|zfl|3(+P z781TS2~EB?VvsL2aTt@FyD%FVR+G7)yUAS89nJ*?8qNg9W;hQRsn{&Q=cn)c$47c} z)-vTLh8o{>=CyRQ4kmN&xHMfObDww?cL;B}G+iTe-}9{ScdE==xX*NG)34uyGOV{E zd9Bm1c(`ythn|MTvxOs`#cP>!p2b_4>z>8A=nI$d$9Vv8-?NwldR)REFOKdSW0ZFs zj9)b)<3n)+@)V(YJVRDPgBlZ2Ga+df}KOICGD8UcI5u z^@g#2kprH^#~<$h1gWb^JKuHfJVrZ@Xv1KheZE6G>uM~%5!vaQeymI6Ezf#i=nZ4E z^P+3iG1~d1XK^V0*0HLz^BdRBW3+RhYv-|IJC7CHd5m@@&6zsVsPA2)j?t(ct_8uGAeZn-zR zqM_)Ls1N(&qI-`C#e~}@JmzR<)w7BoKaP1kSTH}1;w7ipfAGnjvP8QR_2KQ)gkFIt zFT*7y6-4=Hg53oN|H20rS5;%aLS|-c`uB4;wnx~ut-1yK2uEr?ZowWM&g(^6O%w+X z7alDwYKh+LcqzmCy0%rm`o7@HS7U~^1ljXiQXxC(5JXE@xf;l>>Oc@vCdLrcR{6eI z$chaUh43CIKTVjlX1}8q(KQA2%Dn-%aElJFdlF^MXL1Y&f^Xe{;21xX!rN*InP^ms z=bbM#6dyUo(V6F2(Y+RY!3ST-T2V{XmlyJd*MLnBIAHH_Nj*AQZ56cCidv$+>`Dtu zD)Yo5ZR1}XjLux|q@~*>?FqEpcjvs(^qK^d^kQOH+)e zJS>+~O@z-^C(w6vT9~jz=a|_;qGN49+V43l(OoByArC1YX1Ac_0a_N_nku@58k7%r zoiEWzVM3xa4iX(Q%M#^dSqZDiEkRy6E72i!H4y6H9jkE)yOch4T_-KngkRunt3=Od zf!tP4yHWWaE7YFbh?W=LPO!XOe#^)($+b%-x)VhXB=oNkViJ??0Ob4&T?6Fr zGDN#R5bs(PLdChKVWz2^PfcTX0g#l%H}&QxSIx`xt%9^Z-d2Ga)8n$`2t)4Htqw>vm|K zn(Hjl)CXk5L82`RAkj&w zXr%>6bQ4sxQW|2ytS80JXq$?@iog&^0-Xr7{YQBYB<`FbUFnc+i4HhOG&$Xu=x90w z(Gqp3N&8&76(HV9bT>LF?H&>xom1r3MPzlJP9P0dI z^`30HzrF)-#+Z34PMS;xMwn9Up9h{m^hak!?1)AP)7@8^E>cXWBU!OP#3;P0@uXC)&zs}JbYD+e@ zT_B=)v;_#-PkfCMzBjTX=>zB6*rCX`o)xx1*wkntnhATTb3kw`?TacH0+n!w_-Y^o zD;N4$oUaCgLv)0MXGdCq9I1Pq=$h7=7lTUZpYL08FGO7@Lj=0>$K6!B5uKJ=0=3IR zx2~pX6MkO)DpACsoQFu?aS{CHQ1tMwCD3hIC}k-GC5+piR_uhJYh;Ib-SaIpx)T1x z?9IwIN2ATwD-8p>nvsm2WzUKw>?T^S0FqTO^tQ!X*FrrB^JlTv-#RV*YOH&@W?@)W zfj2ReVsm+#Oy3GUN|-q4nRoLwi}kJ$bdBs#k73m(;pR4tI&`TJv_EuKqBpOo!{tKe zL%PO-chjLxS-W;>D^SmiIUL$E=J4lh4|8=AK>ZJ zHQ~-6kO2>A@{@?MVN%rc04;|&&SF zB>FB3klFH9fTTQERWuXzjCx}xA!IwM#Gb26^jv6Gug_Z-S6?~NYxHmvYR zybWt>tL^}wd@-z8e2eCv7R^5`ntxg}|Fmd6+7*lDYen<5qWN0Ue646cdb1w$_tbI; z0lOH$`yFwwCF)C;w6I<@zlXt38&0}PPRxm1@+{h!ugMu;tiAhXtEQ`| zB(|P8#nH)qxajf4xQAOl6k{k}^X?Vv9rbul9~=IDU>|>Zjds=VN7@4kYy9OH+)e{0=};H4#2voj^}3GTD-n z0-v}ua}nh8yj<86VR{Zh32X6r>0fd!72U`KS@jS;#K$Mt65g3AYI%T`Blk_W=nIq! z@?p{W5?z{ZOLX5sqMt;3FHwFjIbpGVONX{S?(jAmS0KF}LOfYJC&aa=yZoSo=-4iM}l3}Y(JH#x5clCmkK-o7%?B@mDv7qT(PSFZE)uR!mMceCqgs^vQPLc-g1HHvnz9f@8pq+JKqcie$>^!4A)0wntSZ@)eSo%@yE zSnCaxhcx*O!WJcG7$5STDL-+;BM|xHz+hkLia1XFVXS+R#@+B_g z?bI*S$119K*x3c%LuEMYmbiO>G@s&Zt-!w6Dd}CO7tDxi_x-lA-+(PZD~u&GcP54E>J?a(SP8= z9o=%Y0NIsxZzVcS91B8HOV~If%Fj-jpS*dayw|TO!mvnn{Irx|-BOCaz|Io+YQ{veL zKjLDv%wC8u)MUfeD7pY>0kSUb-b!?mdMn6#=U8+H3*?eAHtPE?XF>?oXSYc-d-B_c zmRC&b@sEw7`$WM^O5nGc;B`$HAAJ(NpAS(iVFDU*cA__FfY8zjD;OZSmhhwukQwJ# zbZFBz?v)8Z2ug4*gd{a+2x`Gj%AFP>>>DTgXg83mi}W~TO)P5}dcui4hV;gwci!k{ z56iUCg@6(sD+ui*K*C5R++{98qFa+9B-*M)$hVahy5_X&t*CWK*M zqK6Jrh2)So+ct8*;m>jtdh3alcDb{Y=uN&m676*-^2QDYj_VWdwp4}ZgxX|_G6(9h z#ayV~Jfl)PvaS`6tfRAbs5r}Vq3VnoDo@IXP1Jt~OQjNq<+IkD6K=F5e3olO!ZlqJ z=0qSf4st==9mOs9vV76L-~+)-c<$^RkV|ua$;D+X%p0bq!>p0e_{8J6Q+z>k z7?ki!UE9rPzi+Jc|K+->0bT3dhp+0~5nb!t#;R8euhZR?=GvuOn7woh!?KXDXrbCA zAc$5Q>Jf|Y`B0Y^GyKAWiCNgK3@hwY36Ui{m)D^}3m;rJJ5+T_qHY&{VS8F$*q|v3 z#A)eXa>FZ{?11>*RT^UQ<7yjtZ#p`eVH!xvk^v0n5)P2g0l~9`U#7#M#q`hvnRAe6 z$bfvXl4bLRW6@;=cj~{c&$(u<-MO*Cd_3sqWy2lTe9X|R%f{x7HCcG6>s6rMG}yX~ z+F-$?>`=X75vi&omN46F$mLyKFHP~qw=k|>T1-%U@vhS;cP_2NgcdHWT|>o}ADl~b z-Ok4SZJd#;Jk^>ba+GF zPFWm)X?JFtg(kHI7o+9SrMnSGU!_laV$QrPwl=}M?`wHAS_lZ;t<|QzC_Tdp0P!@( zq49TR0PP8!fmjCI)p8(X-q+m5AkCNyVlM02l1-DzHg2qhM(fimO3jNFKGdQ3 z#7{9w7u^mI)obWWW}Ox`Xu{HML|UHdY9KSGD_&M#Oi)~tmRYBG95g*T;hD*c(K1!= zrB?JMy8e72EnB*pGxXzdI2NA#>e86*X&BobKVKi|eY%<%JYj5KrY^I-!KpiPDq+bJ zdeoX0V$<(pWXB2z`uAP_OUX{nb%o6oKAhMq%g>z$pDf&1p`Z5sip$G}TUOWS?XS;& zsjHw3ep!8{uYB;$#4{GRKDFhvt|n)N4VsX~=#y2iW#n|lC+Yd|uCzRIipN3I-xBiU z#b_BS_);tS63vfu(z2v$y`z%iMtrJE7(|z;%OokBdYGQ-LXTS0LTp~R7}=yoiW@GK z>YD3{4U1J-uKY!p)Q;O$=yLNu)fsMCUG~d>JqL5`8-gExWEpxvD& z9$B7o9(;1xw!(;c=hL#`meo~Hzk>yB@XP8mY59Y1UmA?IL$BI$T37Q8q_9B~K8r-3 z94Knpa%nmGv8X|zN1T=?py^x*$^Bxq+%NbtUi2k8^3gKvYBWA6(g*yCv=G%2hUew$ zlCJeZMLJ&dX*prQU#2dTP;qKCJuQbGwWfvGyl^qHX_<8Vs8m{Rt}B-MUdr-Lg9liy zmGYpuu9yd}0uNFisksPD_MPyUb8qBaKc?kL%N!|cJuj{I-)+bOTMu_1A(@BeOjv}9-VBuHd~L!CPXDn79qqq z{lSpwgDr(F<(Zr?;3=sh#9Uz`wNj&e8R^YVux&ElpAQ&n60nD;yi-cc>nUI-s;rr~M=u6*S`LxUCuunVeycX|P)NoCq zyjdBEgQkOE+BPGwOZr<|<*TtSjhaE%jNcc7U}ZktN(&I`P{J`FCAuV#oRw)sVm>`0 zK%QSW2tD$aU+yNXw0^6i+7$(&VV2(ODNFCp0GIIPfG$Dq>uMk;`he-fU#>5&OK6#p z7IPHvx@{#?ROiMH4|K4_ChD&dR8YG^5zD)}Iz^R@Zu;+5EYBSA4B&T2H!6UFO%IaB5dh8CKcawWfvG zY$-6(j5!&qH$P4mDmSc9b;3`Wg^Dl9@5OusQY%{uG$#w2 zx|$_rF+yJ{Mkx9-9(eJ>DUSXw+^R%@BsDQ0dQfZaiI!X#TBtKx@FlB2s3)mbgrGrF ztOMZuxj+ef3iQ)a62?on5=%{26NLEVdLbxfiv;G5H?-YG;hsxx(e8_$Uau$aFv6v3 z*)I#{0wvtV5AEEj{LbhBXoyK_wt-eE6oSk>idc6KAvY=m(F%o_qzc__r9vSn;pSop zxl#F7q7@1;NflxoJXFOJ#{6(AF#vQ9J2xu-YBUCzDK&!d2~a`|Mq7zN2x`I3jY|CX zc4#K4A5iysRm^~P!ckXvh#KKd57MuF=b+&;y>BJ_&V#nwC>)7tzCs4cPknomEzaW115`A@WT6fi!bxp9cCQ+V$O@QnP!gHVrkaj(d z(C3~?h}LC5qCAzAV5KGqPf{d676suUg9OMcLHx53(Yid+$4F+}M@gbj%mSGx55bDr z%WcG;NxuL?2|o^n6@0rK$f$zFcXiStK!~T)Lwz-nNjX%)u_7eeIj727DMGG^mD!d$ zz{Q{v7QJ&Vxfi0Ylc7b`Xj#{^5w~<9sDxa-Dnl>4dkL>Yw}x74$ySI;sMLB(hC6*~8EkMw|>1&kmc-w-cmz{65RgvqS72D*Xg=i*BROf);m}#>T zH3XHg0L8bG;Ugi4h#h?=U=SEBJg{bRfh(PbCX6E=p zzXF--cH!|wOQ3C8*wfVvRPzLI&Pqmxrmhl249a5-m+ubVHkQ#f|rw%V`C4!G`b!?SiozV ze6t(+ofm`bl$TZv&wHHb4+ccu^Q`if`H0H&JNq9EiS+gRXk9E{zmImrI`BZ8>~|i0 zgp*azN_CRHU^*Y%e!j6R`*=v;bK zW+dt%Q7iL;Y&t8C8Gm<|08(;lsQ`S_Msr2ekTvrHnm~(ZB z<_RD(4ib&nv_!8RWJ8XTd=kFQ24vG!zY6KKM3c^e(8pfOY18G*`QTu|bdWFF z>%24E54GHPS{^`-I@XhAkqbBKgn1WpL^hr~Tc>{630wE1Wmwk)_kgT9D>Z@Lg+o28 z+}B^cm8fH*f=uaZ9>JUz`P{Qaxl3qxRDa$6D#zs zjr53ZN_5*nPJNe)h!r8x>K7rOT`L54R`bJI?<<5M1CucL37LmPql{-;YRk`6es5*q zx35t2noj+675=`K1`mlEFG8YCT!ehEqQL7CruQ&n<|gCm-?urfF;hBhXeeQRFG5Op zfR?J$l51Dd(XOsGmmBDg`q85Kh)%MdYX{j2657qm)6+i$!N7SVkgrX&+gw}7+aLg6 zuwT;XFrUyEkH-OQuV%b6zoJ3#05OH6WF0U)ZtHdGjvO<`K^s{!wAXFdaZmkNN2q4Y zK~DWx2N0}uIY`t>3lQp1!Z9Evq6j2syei8E7 zx5CLs%IKy3U=rqwB4m7~y*{GnbWNDv(ZY$%=PEy7*S!?IKhdLrHFXdViMDzX5^eP& z)&axajx*jK zC%NqgZDh?HhobeHi5c15e^1fWwv&*&O9jm4~RsvF7M8XZS5|HXY zQle31XLW6>Jb;{VhZ5s^A`czw0pu;0!cT3V(AJ!@RfW{2InDXt7`FDEttz(Kovl;5 zdT49L+4>0bjblCGu;`sA` znl;m!Os?yC#xe>m&n0@|ARiZfIrWovXyFdEHyrKbK+fkreSn&uaf=*ZL&yzt3rUrC zm$1b`%oUkAYw1jN2)R!}H5%~9C83(DnTW80XzB3~$VXyXXP`%&*a)OgxK9@J*KH^D z|;3D~VpXFPEm6%6X3`i=moSwcI5PRZ+{+qLygDi(0OaFE-hPRZ7W* zof>+62u4>sMaYB;yofOVK)T&Pe~=2nv6KZ0X26`W;bTMqIfrK-tbAz8#t4Mnzo#(B zYIIS*3Sd?3RGp^9L!wh7hCL*@uqi^KJ3S!O$=t?+thxbz>V0`eB3it!*Q|QpvFKLg zLtV07>?3xW-OgKywhP_zq3f2>Q3s?%PX@x`KVkE84#>5w%hfpc!AdsN5>77YW0xDT zQ4Os{H^idHJ3wX~Bs%2)X~Bw57vJVqq6>Y3>?8Ksg;0k%*Tv92M$v>e71ZAK%RS z7XP~~!rbG6eBoGQ9B%D<7C^3SNKp*>WjX}I0}gWPK@e7e^g2it^1fr$ID*0_^U)Y; z)Zv;v8YtfRHd^~RhOgwCAt z4De^cmv3!+AE{5$(a-o@LxR}?1ntXiNPLa4_S&=D@DLG>k_qvjd&srXVo%OPXU;lJ zCzy2RHCLx-diwy$Vs);FoqC9Kdb@mpsEg_nj?O*tk90lb42vKGDY1e;^i8^ztAQNI zp%RW2Ayp}HmoUhO<*gJU-(o8>JnO8w?CN^f18k>4PR*8B>6Z5GbSp*32P=x6E_BP& zgM3XQ)+>j%b-h{n{;tzs>QOKIR)VHlaqqG~Y$$Tk>xoA1TM3$K#l6b{4Hx^~>A$|m zNcvWSrdo0DvOrTo^x7-me|Y-W9|_-Q5jE9Py{;Q-zSv&J@%H*GqNZA^*L6d!7Tas# z^iQ%fzCMensg~+>-B7R8Uc0&`td>has{f?%=FH^?yl((MbK;<^eC{@ zUirrM>1%UL6;ZP-piJgFeOq~&shgGARzSZMEnQY1M%5?SF`xBnrj~V+#cs3{??y$` zYyt|mW@IzLz4@YhXY8!$dZ1nlZN|o>qgWNRS7uwXb@`|TMWfT)*8H@C|KM)uuisI5 z{Aox1&#taxi?dAe6 zB8>lf;Hi0{f~s!nPv%v@Es?K0OO(5urr1MHeTap2#g}tIPJf6{sjO(_G9XQY=t3nT zjM&vcXjPi@jKc)lr3DC0_*!*6<3Sy)AbLy31SUhCaoTnSOthmSR~3g`*}LC)nCkjmx2k*LhJXJ?m}3!>dCz_7XYbE@9$$ zr@#1T7o!;s2!S-?6Y@mb>>J`5ieB;Q&%rCZqS!-{eesa!OmQ_39F8bQy(X`oaRN^c|5l(T)U{J`IR4!hrg3z_9n@cQIULqK{i#$A z$10whyjmibt)Xx<%@(i0mqQV+)==eoR-XcYl_=`f*h_-EQ3(@AzdU`U>lvS4W!M10 zpc$W#UQ6u~4SOrmgpIEr5}g)`kf@d6LJ*_XzZyujykkH{T!*N}n(|?JD?qND6*>xe z?2O6h^>5y6h)lOiW>$n;bF8rqk^7z{%3T`o!-IvJuSBl6y~%o+Ps;?OVYySkbh-4i+FS)$w} zj0;)@%R{hI&fRkuO31WS2j4CSLLG9UcL5d=#`$U>ICRgoW;Nzm3y@*y9MLtc16&L$ zVcb&Xa_)tw>tu+U%=&T9*f#47w;f(Vcx={;|XR70@u4x_MVo(X=_IXS0g{bRfh(NEY zW@kR%K*P2Knv;cjT@yM`3lOyD>T~+zIMk;l(1Pl*m|mY2AZX9k=ky28s836vCDmg& zy*@2K&`y2Mc;uDZv;bLE9X8VI(gI{l+IO9mnkaV(bM@6gwq?JBV?cHUO&Fc8%3A?) zZLDnkfAw>gF4biqUi~9MBv}D!A_jTeX&FO`D;=Vz(he)TQaU5<{Q;y~3e4wBARju` z<3}RNp=T^tLdCb7mM=qA9jjJUT+<)jg-V8sd!3dlfgbcM6pwnAD0ewcai4=cC@OwX zRD9~|oS$8fZz}}3P_$6*i`7C~*e^$f&Ybl%30i^9F{HYkbz|!^%o!8R>5yoT4n0d4 zT}8;L$>Ce$m>=U~qYC&lT@!*x$fnXE6B4}~$aXwkE_q)!L~@7bj2fdD^s3h)%3a7; zK)Uspeg`=<6NQjF4pN2mT560Cd@@@MYUFQ&&_t)YcVB;*cD5$a((7*7&}ye@!I!Gn zav-uJUCTp3Mw}M(iQ#{Ui%_)yLHm@qLXBT~7H)Ss_oKed2tB9k=PJ)C-*ab$;(}BD zktlZw`^={PLJZGXArOc+g5Y-oguBWEu8L!WBDn#ZFeK1YViX~oGwebkB8BuB7ILeb(I{N&+U9ryzUgAn(0p0@)26-y=J2=eeOcDhFWfyH(UbJ zCGAZD-tP=Y<94xH4rKVOJsMHM@`Q7?HYE}@XPl9vg@84Q!c}xT%zInssRUYV_`+DE zgp?qlr}==}DnvQjONxqJHJ5$!6&2%%Wc+HK=DRY*`H6c2jEqTD5P|E~UWPuDZ15L&hc2-;aO87ow8JKZqo zM{!8yVSRTq_v`iRfv)Y9PZruweQo)CsHK){g{YgAPu^;0rfQlCt%ifkEtzT!wJKYc z->kcJv+~WQsDn*F3$1|WS^>?p0y_5578M4)Nu7?8LAefibTirkG1VGsOD$$cnaIVz zT91i2$b=mHZ|W@5;kMfzsj&Fp<(L%q#WY~ZzW+HV_wG09h1-8C$GoS)#6Qk4CsnwA zl4DXB64RK0T+7RCsWAFaa^SE5PHVJH7n28&L#ne$tW>}Azpbk_EGpmg-#gZQk*l7y zDRSGhw*Pt^u&b-lH6YIiT@7pZL{>d3wJI-NRX&2;RSTH5+;5{f{D3vgROK5^`IjMm zoSqP;d#*=385TL>Sv8RZE+|h3-GXN=irnxlqWRK=?g`Nx+M^ks42zuhtmh)-*FZPME3k|j@2u2z_ad&ocZ6K)SSp$nthDLZjt?- zbysB7vqnS?{XM6vDstbm4n^Mm`%Y>|&jI(8LO#*<>octU<8H5y>*K!5S;c=Ql**d@fL4D=nB5TB9|``mba%BWuVEQavL zUq}5@hH!1qv5E=tX|Z;v{$4GsAZE#RSC!ud>2uZuRe9lRH$hdpoZk~gk0$Vl$>@yV zK@B}xa~}PhkZ&Dp3^JFscU{(|Nlhx>ZKGW${FJv_4`QyFPn+_X``ar27UcY2r3uC% zbIX9OX3K!BHloGcZ{G8Q%q;`9Tn$KxrUqMWB*ok^V5_akGGME%xC|I4^0}C7xtQdZ z0b8YGa-*_vkD$EOrOiT4j0Iq76V=NxfJr5V@*IF{9p8pCy+fyuqGgP|L;1>>W4lN&*UD+EoD6` z22Cb3VvtkHfL3fl^oGxhkav{|tr#?8(`bX7$caHuif6DqX$7H~O*26X)0)bx zAoPrz>AnIvD^`Z3u$XIV=vDDDK?)=QYXq9Eo(WQ*1*~A|(2GQV<_6=DXj|pbxyaAl zpzuQLC@Z)t`ngsomIpoO7B63cWD#R(HFJXkEoHILG*l)?ftIp@&@@ygNP%cuL1==V z2~r^1RuGzCXMz-3iTsIH%U1dA|FPa%Bdsx)+8T4NHF|Tc0o^B_`DIW@7Qd!eb2lgu zZR;U4!OjFJ5N#_6O|UaT3PjrqLKEyvkOI-Rg3tsz6Qock^4nTSu*9*-!!?fOvEEtJ zioq;jAYY4R#h~~9TD|d%7-Y8=e^v~7)-4DpAQy6C(6!f28zdV=s|}i+qA?1|n#_tp zv(7YPkk7SrvtrOQemTeHlI5sDLe6SsYLU<^QH>ZRyUfg8tz6j}8ZpSX>ho3%`sM%R zDi6sH(uzTEX}U1lnx!W)(V;eq77G2wZ5}7sJhB%w+8}TJ-MSwZ3Ela>I^Q7KA6hYJ zHi$+W%3ECx>saI?w^Esy6#2rl zHbt_CF+dh7`);8!5#|9S6^?krV!SigSzp-+4rq^Oc`R|ZHSZZHOB}!Nn<%buCc=H6 zRTggiERQ7)>tV}-_6JB4#Z}KlYyu^jyjN1WS@~jRg#rtIld9ghUBHeGcQQ!|yYBF( z3YlB@ym1Sk+(Q11Tgc}&H*e~lGv{@<*xr$&2hQPy zFaN2w6^i76dWeEdAXyT_EB!f>r9g_1EX6&giABcp^>#= zr`Ye=wr&)C&N6Y}K!%-TrZ<-kGBV6rVNS5=J4^|d7iI*@BO!F>))}m`J9DdIR=Ybn z-md6pf8VbI*pEzTL|7Y4qm|r-v0e0NZf{7B^M@nx9a>oTEMQ^fGiF%(j7jy&=fn2O z7ynkJkPhqIFdNpnNy)G-8s!L|Xur3P zB1?&!mx)p!;~7!Yy(p3J4A(eIiHw&ipg_K>+oE(q*{^OtDft;u6YVhf8Lp|;#iu^@ zI*nf#gS)H4vd>pO?Xq8Cru93!co0REZd5!QobgQRPBivE_HIIbHoY;tj%Y2we!lPd_BH=PS z=8^C?pJ+tFWdTpTDKk&xHKxv$oFO$@gi8m(BIWz8!+g{9iF&Vqx92*{IDdjg2SFWW zx<;cDaOoUhsCZ-W*0sKEM8bWczkX+B#D8`i=7xh>wS1Hu?o0jkw`E2R9LBc(@EzG7 zKG~^!+5wA1`(6G|RxNC9ls5VbmwX(6VUvOz!EnjN0T?z(xe*MPJRE>wlVuyha7m~E z81{h{n2lh#C;BV>fii(%8 z+X#ls;x_=pW;xslhD&}3z_3XZM47Tr8-83}ZrT`DYWPm`bl?q=1I&GwH=gh(SmX(6 zK$#5D7#6tXhz4sgpSjV`$hTLx&-K@a!~t_gfBdd`Ex^N`)t@`+e>SND&Z7SEh5BDU zd2MnBJd(tB=l+&Y9xt>{Xsjw+vP6i6Po8K*!zE3GX!sEZH+GbX3-i!hEN28wQ%k`y3RK$NMrUG#d-98QU~(3b$sUYkF&@2FdN1Od2$q z>7+sOR9@B$ntfT<4Dw9seAW#5qwE8@W{})3$(liPS?`)bva^{rgJ!mH%^oEYX->; zlB^jtH%nZzaFfun((1=lTK$-!ey|gl*#S+_a7rPm8Cf%EiiT?j$to{vc3J&k`z&im zEum&)JZOqW;c+#qFr+RpctST*2fd_EUp$9o63?1JQw>@w&mnn`K5GWeqYkbaWUVmW zLXYZn`y7&DkV%8~)9v%irrYkqbPLTK>kNTpip?}YQw>}*$i2eohQ2R1n_V-=dw<<8 zXP|kO-8F;UDGW5|KAlI$A-4(xjS)n;X7)mpu1*7FG5-!_%HtX#gED_H@nk$`W*+y7 zC}j2Td%sfiYT$qN80d$ZS1%yRrOX0olBuQg0&=DB&-*R?!Vbjb%9SPO&ZEe5ysy7^ju1C)m%5nKFQ_yR-mZ(*q@ z{*ARPIa2%^$wIdk{}%RN@o!eAH1Kiz&tB}K{;h$J`nLu?>fajpsDEqVqyDXdkNP*u z#}ASPg?>Ewk1zI7|JJ}q{aXVc^=}P))W0?GQUBJ!NBx`SW9$D=uW#PRZ#G*m^wIw< z_R;?>_R;?>_R;?>_R;?>_R;^%^6_rufbCMYvSXa9Nl8lg6vDvbA?>^ zds$R(D)ei4z|l<{vcfDV3!kQXFOB!**y>9D56ziv_gg@X$z%5AEcB?9PgM|wGx0B* z<)Pd3$^VgVA@6%uA;dWu#u>>UHO^)1DTg`~9Uhg^r}zoVy-;U46++U!2Z910&?lCn z^T?x==zS0riqbL%6lT^@boql)S%?fQxa61Y8O0S*;2~yoLP(mQC}=O`5v@BFmC_S; zr8QA>Yf%E(D}PE@p2kv!Vku_Q#!{-Wl&Y1H`0qVx0%F=qa0WHnDI@uzwDzc!KDr)M zLWYNm5+Hp|d4&Id4oHdK^`KI&4{uIWRpLh^5<(tA(u&G(py(!0HPKm4S2+}c`!-OQ zd_;^%<9f_XQ1n`2&AX58msFbk_>bz7+G>1A79p!Y<`mRJH zs}s=oh37`+ppaG1vf_;7E`g-Qxj9su=F36=d`V6=PX+sdsFlIABiJt*Z7t@{*}(i6SXnkc&E zB!L{2KP9X%V<|(i6noVc*;0+An9D`{_Z~F?F>NI{(;DrRtQ(Wo9+lEZ*MmyP@K8|# zq}G&2`0wYol;~X#DrJRvbDCx(encW6k6?yZWlpJEh_?fUtSB4l)4tHF)hPy)FgCon>_w^SB~zHCaYtB-1iWk2;_<0 zrlbrZ<&`{Zn2=X@#D;dY#muV*(v+ti6KtIm2+umZr!}o0(Uixc-R*b29Lh5(j>Q8# zJeH7flRg$a84K30iFmeQ}1M$OF%^ z()nF1_zF_G)x0OM6!SuDTWmSfxO^Q;`P%a6y`T@hlvK!GI)tVrwA>72Uwj~lDKk=t zX{mf=h3uoK@jd?7g0xC?P zzZpSHE$>A7u4*yI%R_lgdceQ1WQ`XfV;*ux9);#H=!C9{r3@kEo_;#c+-d0(8~W82 zb2&CCO&1kncEyG?-Ib$z2xP6k?_P*i_;A8@07{4nkmF|b07@yWp`rxa@EtV?kZyV2 z`GJ4#xe%|M41)$_&_j6KnfGxL);_V6A*7t@2kgz{?6R|B5u`Lr;^zO^sC0?+;33lLL4vPhwWgUUMvy#x0H07<*gwaaVb$v<3j=nVQ z`d@i0euVeidgYxqw`Dmd5-;`=@6Qh=$EQUpGnsO#A`99=@F6cA?9>6THdg+@(|o! zRQF9^UP;pu5So^7e@V2Ifb0r{FV?w%%!eg-q~EbtKGetT(%-Eg^N$5`!aHxS9d8`* z#D79rz<>{8h`X|yzZHtkndXu~B%Bo`Ss)sB$_JF3rrBE-2wU%#0nwOWU~!rxss(l7 z)evU&dQCP64X*{1us8K>L0%So&&e%qq>Q#Egt^k=) zE#?e&Gg@$aUJWzTZcdsmDa3rW2QrTjSrs}g7ghBEbS@8tD)AL(p3&c z>vDcw4=UkNkQ-Bk|L=Xw6MonDYN+j|bd^KVx}0CvgG%V%8&h;Dv1Y-Tu+Hd`pOt&4 zKQCt%`~hjoy@7<=*fRpzRxReG=G*dGknRmLwT#GpjcvWZVP4X_iXf(zcG=-($2(y| z`Jq7Ob#vU@(5RKyf^=_~spXFBo6h+CQ)|h1KZ2NA?#jmGechmJ{BvEF>YCtRs~q$8 z+o?4Dpb&F67)ZPSLKxrg;x~^Hx;&OLgp^VJ#a;6j$(fjauI8J!NIJyqK5xDi*D-1O zT8{48X{CN8T0n-E4$}cBAtpeUn$ZI&Wt%Qklwcdaqb31zAZ{GXG2ylWkdGe1N2d4y zP*YNdkn-@av;Al0)}h#Nq_&v3)hgdL;$v9}whjw~Pa`GVv7;$pQF2ofKON0?jU0>H zZhY(~Vd9DfPsM_#V!>v~hy~YT!L?YhIoBX~UcWJA&S-Pe)JJb3wq+u=#k^!cj0Eea zr@H?JS@$9qY)%hY%8$_{^dwFBCS$^ArRk`C(b0~+G~H9k2p`m1QjbTrggo}FLfOp8 zuy)SHg0CRugPQjwmSWz1TNLz$O8GjLV%|$z67;&4Vg&)nN;-t5CA8cOWL111h$)j) zh)KBpwkv9UkDIsO_9KXS`;9M{4$3#L-Gv7vU#`pcam^LNtl(MqBy3l&3*>{UHf!&G zc`ZoyhM8KHWX<+b*KTI@co#uTEn_G3pfZ~$OqL4*Ign$*l>Dx|7NmQ_%zHAUvJ!c( zD-v@ecpX7ZEt67o=e77Y{tafU7;OvwK;@X177zbsy|WJGn6|$bqf%bJ12w3+J|C)2 zbd=LY>nTBJ6%cw(cN>D&aMk5R&E;3VcA# z>3ur#DCMQs89|{a?Hxi;m{~{B)>oMK<>+z`lAlJ%9&@SiEpEQMoiq9JHg7}bOg78- zGIq}7+t@r_lrwq8h|gZ<%<#L{IWzpCbIJ9kE&Ro) z+&F2J8z+r&go48E zqv@`PKo+`ht))R}U2ADDw4D*seLH?=ueBVSG?b1S4W*+nTG0@=BwQbS*ljuOf2-cZcjf5D@k$FP z9l~@=4#<1OcA=Hw_yW}Bgab-$L%#G0_)`Bv|RZ2RBw zVxmh(ege<|yM@IMm^s$4utq&_O2{S8S`l*bOvT4P96AyINa#ekm~tB9-w2&xc{KU= zRDAr~eG?C5Y057uIa%>fqD{oVw`o56K-ZV(yqkfHO0Rmu%!hdRT}aZ#{UD)L$4EAx zVUuyF%_mc?M+#V5P)pxn0m$!Wp3&?Fhdzj8A8fCm16F0uZRt+YKz(J zo6?l=pTA_r36;Pt_wa?EE6m%4qbO%uS%XF@k9)2M;ruRQ!lORdBV|jx_qIHZZ86^{ zIS?ryH05JyMup{H$Wety=~|2}r*{ z{6uBCM^itMy&&)RbTqz*XBzWShFI`aEO;swY<6ob_?j(dZco^s#+DM0F^TG;M)ye^ zmnU&t%qtdbm{Y-KC|^la4>7wHh|ia1`Vc9FAT;4IQoJqABr47qq*!$wv#$g(I~3{6 zjww}AI`pIFfccOXO}lj2YSxU3G%W$4DJx<(w(k62^@S`eV#kVC!Y|m$IFbDg*NTw{~6?=vL+$#{U7-9408Sdgf$82WBiO5-<4Rq)kYZO%!)Y3&j>P?8(FhB z%9C-FpAqGn27VHf`)h8k83%qc4*Vp6Uy;iiXFq}8_N>&vk4i*uSAINV?y=BYUnuCF z_=0(98yC%??nk=5Ik;^G@XJR%6u;KxnB_P$qtIm>D$8sv;5fIi>8LwrT0NhoSGWoWrO93)bg zuAOUdWm=*-xmJuTYLjD)%EgGEc530Ma;?Ha9b^3W6 z2lI^@;;p(Sc8<9F5Vs682iF6M!wZstf<`mM8KB*v9 zt#~i3K_wIhAiEkg)3%*Ri}|s#5R#T=dx4^qrAUZrPE$+8bm<^4uCC~<49V3}HU8#g ztzDyC^ zX3L;RIhLavW}81WF9jQ*+ycxhpP)v(uFr<5ijH!+Xgwq7tRh0s3(q~WuqNcXXIZ`@ z`L#gO;@li+Omq}xy6D?LCA_73J?14SI+Iwl1yqlDxIiExK+hIm38<*Y$poTqV7ozX?OBBAXiRa&%9|LEaPAt;&z5q3>(6 zkzpZgo@J$YEX7=&g^+qLT8g^GCd_RPl`tQpphpy@DFRj1(3x?FA!b2|AvdGNd{(ws z-0n|zKZcm@lb=(iy5?%A5@P{HB_Jc>NjZ;bJ*&|+H{GYD>6IYn)$mN9C2j09hr*Ku z4T5Q23^Dh$L&&X4pShM<6^qL42wx8>VQG0|irz^a-fIt;yU&|nDr74%%*?h!ft;%Q zW*NN}i2a1RJhQ>`3+^dS9+2YYd&jaSk^LGidC!OenY|i3Wfb457oAvub{-r3UM@fD-1Tqh^c?L0^y_f_yH1xz8TE zcWL;EQ@;C9=UT-fl$Cw(B$Sl$5tLBQb=q{DvVPIs{Qk>rf4MFDKlHQsx3Y1&ijDN+ zoxj6-c;IKSMGtnGgk{ga+WYz{NxLEJ+XOvIgCb~8wRA#wfZ`Y$xot& zPDzyea!m6a6lvyAXANWPxD8_KxK?Z%Xt?IyyVsQGAu8ed|L#~(LI8RM)h|bP!vu0f zSZ-ms`9n@>+HM4LQd!Rygx{^HrEs(BrTan#U{*d4wbMsO+2PVVVWXP3mQ5z z4l%@BjK`3h(PCbK&xqTz>F&o6(|z)DvsBky4OL<+pr{07Njxd%(VC#vHQMGl1+uLW z^T$;}h#LrR?2-)XXSNaQa&ZHd@Q@p!{=ATPL5e0A7D9e5%bZ_sH>dMmQMIp0`h@l9 zu&ztZXB4jWjW_VK?(5)rF_>d8i`|M7N{^rZl?a$q#R5BoogPN z<^%bl5VO995SJB4x6CmD>SwkQ>T+=dl`w1x_2-40O2(XN=9m>Ogt+>8bSt60;>g(l zQ{O6Zk=wboJS?SkM2>atyqqn5!nNvUt4MDDM8oGr^?su3b9i%KG-O|54T9xZVWb?( za`=u2?Ec(>ufK;e{j}`Oi!h$xcxNt>41!zbzc!TZY{GA z81+-XAK zbe$X8oz}yc{@G&k`MQ&&ocU}C6Kc4&gb4*-f4_zrKAY*;L?0$(#tYLiWkE0}J-MXg z$XpPF5ck}En>AcxjQx`-Atqs-4k68$_A@m<>(7J;yp;h{SP8tbXZNe2j(yp6x>#+D z`BjJGzLGPFfva;R>_UTkbRiV)SfT8M2OL(!8*SWjm(7`8eS_NlK z^zO>>+8hc6mv<=D^lR@6Oh@qbo6cZ(|Jf2X)NpP68VdgW!TD^aXY+nI!ZKbszEai) z2hx+|Ov*)Hh)MV?LkuyW=ZqoddowZQku?}&$mcMuSE}QyPpYJ4+e2wRAV-%_!$OXD zRufWEA(Nt|K2}mu1#?p&C`!06Bq*O3(nOrUOOP??cpqf*QIsn{YMRXEwaLwBnG%D_ z4cF^Ixj}A?n(3y@3sGN^A_6@pp1FdPuqoCY>b2-7rz=DyTt&_{r6@#wNs0*BqVFbm zyVOe8=1}vZqnxe~l@Ps!rWA#!FG&$0Tk+lG9s;(y>1wFAP3bC!qIEgHt_PLSzc;1` z|92$j?(WW>`LhxVzgutWG;Nq58uxk78xut1NddJ~%pX3a>9p6g*uu%8 z$}!gzOS18>D#wIx>;PFQ57{cU&2bHi66SfdVB6<`yb;gY@JYL>AjBnl=eq=1m!NH= zXWF$u%u#bQTDF_Ynd?C%)PeU+nHQqIBt?7TQMujN{cAxb%&~`}=tPcb7Yfaxj+)XH zq7s}sZc0&z`jQmUJ?Flg5-t>)L!F9_a=JoPLiEm>QWT=TBt;rB{aR!8uBUaOa5Yq= zDP84I+Pajk>p>;-?~N%M7XQaI4k=&byc&w%XifVH7rM%!@aHB`HHl$D|6a|!5{ll7 zO$WYz6TaDVHPn7ny2_zwUCyuTK_&F>jVZ$a_P<}hes-&!1G_#SN)MgLG2v4iK#p$& zQfbN^Pze{Oxbt}-1gk`xze|ua$(8f;oVgZ=d1ZPtT3RKE%Z<(JK_!gnwx-MrQD2fG z0?p5nCVk)Qu7sgWjtLF{=`0WF6-X)5uAnEO6ygo0eI5utlnC>83DPb7em^~Bt_5P2 z!kf|ZP~0vxGOq=cFr53EF)jpsL3$>|pT+cC`?etF^IEZC$&eX!|0U!rWtmS<{FFmx zB~o+g5xW+MS+8zJ3qxl~-G6x~(t? z)lhp)=_-e!^?oT`*Mmyv-y2gzed>`q$KNi8YXl|ij5&*)(aM;=58XqOya;ezZd#2R|QH=}z9N+zv|YCtcM z@tGKC%CQ>-kd#oDavji2WEm8iP&g=LP0Q&w9nj=PZoK@RQtP0Q_?l^j#&6dQlDe2R z3qz6dtjr&XM!)%q>q&tW=66dAO$ndd1?d#m35R3t3TsY#d^~j1wF zb-U8jr4ysKX@Uf%Tk>|CP$JyRMzNt2v7zR-DlnAPD`ept9kzC-(so@i`P!*V2Je9! z>kBFgHM4lmWaRbBACs0|-=@wr@zbqP+QqwdEmaK`Ee%#E4VEJf)*j}Q#0{fhjSfI7 z>W2AEL?EB^@MqA2{H+q%*9>Mu!)bxcm(c@gK|t=OUjxf3p=m(q>4aZ?1A=J@ zzq$;>YcX#x5UaT|0SG|}riGBC$vOlzp(k6uTAf3LceFpv#U+p>4}n}0R;C$xU7Jlo z?kdZya^%??fh5K5T0jYz9qLJdgpo>^MPrEh%ZV|>?9~|ZQ>A5H@@rF5({w+CB&Fs? zpr%H8xh|Oqnfy|gcxMgdShee>Fz11733KaRxlZQV)mC6Jy zu`CDgiAicedfappn>M;jDPG$ zC*}C{N!k<7KC$Uon5Aq&(t&nZ6*;G#W%VI;5SD~oZvt{629+?Z1Z1qW^%FPQt#!UY zw$`t}DsGqau8FM?h2O!q~Q%Ql@Z z!Ze}gi-p{n|7Ph7bD*h^nRPPO@-v7|2RRYW2{#ilc1mZ&7`I^97m~^Rk~^i0)L2S2 zmQwxH-+0+U6)MnXAvuo&NQ(d0fpM1}qFE1NnuTh92GLLn5k~Ap z`1HR~HDT<&A)IL6!RNMv248-$oQ%6C}?AP2>v~zIa3iupV-uyf0`k#Z2T_%F|einNOr`!4~mR58_Klpp*DlTdzQ$i%d0e5HMr9QcO<`CjEuXBCN4dOc^`6^Z7f z=>`B9QHa^|Kt8XQIGE;C4dk`@V#fbwATweRiE+E~qc(GTp>YXszDtlfiP^k%rdcaX zK-z!4^^;kI>lL@_0J)-yC-#IqRMv$XQla1}QR9}tkXtHc9Krj_y3ol`a7_h2f_$%1 zo*~#5j(t!UvE-i0^AUNo2(iqQ&&TK+OG$4mBGFbs(I<-#X$Lx|U68b&A0r5hGQ zzECZfttSW>q1x7rxo}nuA^RG#r;sc)GR+S~BGoD5L3?c%&UfE1EqDl|pAc-MnA&w!n*w&hA6v9?)&Ns2*pV=BMI^!UH zxp6&~+&GnEOT`@3G(Ag)oJ-S>>5z(yxw~>qDFopVPAQ%&gI0Bnn;Feedvg_tc`@)a zEqSu|Ae#}ROjosEejxd#hp+?=N>dNvg6cxZut26%iwPMEASt=LAQ=2FlgsOBnz?c& z{XN8-HW(=$Vrq#Y-?EmowpQ)njOdUv_j}-w!^)bVgSkMvm7LiTzVg2y~dC_OL~Lc#YHG879QiUnV|sTB(T$+5UoLQn`r6MkQ>6#62o z9icIo)f0MwTa^YeR zNWVx=m=@RQ$ubmYkXJ8hqw7{gbODz1S6%(OOX+*2iE5y*;(teILSL}(zQCsp(}ZO~ryP%PU1t%U}nE3xQD4Mc}V>kUD| z+9THXtMg{(^)?UbQ!N)>k73wDX*#12O*DGtlKOR#lx#aP4wL=$&g-#eIQA**pfIaO zn}_(MGlM-XS{5|e7giu5`>H%-Q6TH-THch0Abm@Jz6!~A}F1?!Wh!wRWFjw!1) zDdd7@EeZM7v#cD5bq&S3#$#RMu`V+dBVyK!nrCLhiZtEwkoQ9FdluxwR%VF{Z)THX z2tHOR7v9jh7;@ob!Xac&wLFIOw$`jZ!q#1tG7RaZn9<)6w1-^yFe~O0^@_wbt8nc? z4;Ofr1IY2gzVN1YsJaBCQ!MJ1qgzo}hS9V)9Wo|OCqF9$=~L-int)7;^jWV3azk0Q z9U*r;%Ze+4=M*voIj=0UcWAogA&}VQrfEoTo+%h91t%?!Xo|Lk^+60VNBWU?+V(vP zS#?mzs%KfYBIR7;HU!zDQpORy;904HzfkjV@}YQ?|0ES|jun}lObgTf_SIkd!xuhq zN=-sO=&T&pM8cvRFS{ol%4y2ZzuA&(XJ^4CXrBO8NX&34O|Y8r=1xHybieT2C(;l- zTxbT3x=X&Kc2VrIc;kTAb|pu!rkSq1Msq&M=xx;)nsp7x)y8KmWr)tJsx9Vf>7$rm zQHXh^&?8Oh&xCYfC{C*uv&J?7AtTJ_?Ej&8B>K*(OtvI;7K*H!QkBnq-1 zh`=@#JcOv z2-D5pf7_lFL;1x{MPkMq3{1~>);JDjm$Ln@+AEI@>49w>yXIT~R;IF+Vk!zB+eu{5A*p(I=VMwRQ5K6lT-S`bo&#he)5N>d-QuTVU!ioYT} zE1ngH;wwTiuc5f`9TtWN>ffuyPpnSfk*0+l!@PYpZyfWkmQd*O(HTOQ55*9=8f1kJ zg;|r(byu9o$~<(ZI#xyhexX@tKnBH_KJAPu{X<@+Oe9!!lMy)7WJnHL3CO-k_YgDX zXnLG(SQ8LJd`COm9PkX)LUAQ8&Q*$81CT;tbdM52l5JV>3ngbfYp^1^zq~abk{kvg zKVNB|b^k8@N(<#@Sj?JI^Qw?|?$-D?e&AbKeveAinjEuOLC>fd(=o(gRKf))sZg-r zGB$>oDYGg*tgA0oNTQWs>z1Ie0C9m0-HUGf9*LTBHP&2Ig%$O7j|Q#m1X8ezcdA!5bwbVVs`Y3Kz7uy>VsdXuhn|xm~dMIDeqLu z5adT?)$WPF0Tpbnn-Khknun8j#iRT(EOfJe2`Mc`U3rb>Y)XjV>yR}s`hi?+e8y6S=)7L-VsovyC1!7{`DTsXlcsH| zrBNbTQvg!P_(G=RMndsM%AuNXR!5qiE5xk#F(g^bNxGIJX?m;>vn%KVhE~GJq$-a1 z-m|)@3COHS-%u@8$dzAY8>F@&f2P; zP^{j}7u2t*`bUsn{Y0#O0`={x{!y&n+@nQ35qE15NU#29!Ozp4h`S9!$g2f^QTm)n z=L;FS`dkt{XL5pGx4QXHetns<`;r2AQ%?FcFU-Oo+L29pnDJ1=WISju`ofP9bAcF& zF6H8X+mh;{c|Ecsq2AVEcHvvDn7$`Xj}%fRD4SY@s@p>Dd)9%FN1nyVq;nFM{9B^- zP>wEgKV0VISZx}?rajS?x8vkcO&AGH$lF=vyif20UXBGh7t`7l@}ynJPS5HQa?-Ob z!5z}HOCk20CrvS+rDASX^$Vn?TFe<_SeklY%w^rQKvv|K4-1ABlUGs?y%q^?k;G!W&IZFyHwXB)c1Q!Ip0i#J{OP6Vf1 zK7n~7m^`yNL6BqKGOx{%1nAndyUFuE?={uagM`xAY+t8`pcI?0f+?hzl{hETAs%A( ze>0XHMQY5snFzQ0%xofAk<#X+SRtWlLGhOXsfrI<>Pz)R$Pb>?{SVe_=9nDaqN4h{ z>a1ZoCag1JT|=?1p;*@tx<*x(xzI${v^wz!@_|YjNAR>~S>1x*c@_K^5@*~F0i=)N zWBfYQ7}jF-<_Z8OjzoPn>_cT44{iIRE#sjXZ&OOfhUh_uyCOj};u4->cr8-OXa;jA z*u1>sHs-hj`}caI0OU;xJ?7S%azV~(HT<_%QhHfY)VZRS4YhH?_cwL$vDrAJ9_#!*9DP6oJ zNB5at$Q@;w*CveNf|HhcHv`!c=NZij8-?MhPRU>}cO+zaW^h8(9kbP3sUZo_wP|-1 z=fC(PrutrSfV4=s0>e@dF{hXqV(#q$=@SF9xIm9;qE3?8)1LJza%s}a%_)I+Db+P$ zt*c=3qVcsfomYq%m_unw`Ee;@uhT=&WgijbviUkN31g`uv%y_IL0GYG#=;}XG#s>{4fvMWuo$z9h#Ud_A{5!|XCnW=MD9)k3OtybK+ z#h^Yl%nZ_)G_5Jb^yLbWY0;969O#+ynt?VcW>z#Vq-zGUq>v%Vx5_e?Z%FYFvwqH( zw-xDYYM9xj+tPH;Lm-coWxBU>EmHPHN~N6=Vw!&_kW;nQ+_FC@uLbEP3~Lu3`n@lZ z^S^|9<8Osr^(@FWWtl-h*R<*ynh|o*vk<(Yg3ZYl!F?*_5#*vunTVa3K-admGSmIO z=;&2lrg=byJp{!ioJ7jDNXf4(I5`uhTigFP50^P>7q{}Jcje?>k;%z@Vb<}SO%|JS zGAm5?IB*!zIvU^J7tz+lfOm)DNLDzHgvO1GhZo%Rs{#+&Tl+Y)D}$z*MVv1R z`o^uR1>NECf;i`@IKg%oVb_$iQW1VA(FC00KA3s!^IF*F30oF}qPdX&R@`p}GA)Kt zh1~jUQ&@DkV= zn}t-xu&gdY50^I^bMB}{I3|ad}SmI7VPAjXrD&(HBCiaCq_pA>>&itb)>qN-; ze@s~`LLPh8sgMu;ac$KnCz-+I=nkei;hCFHSZ zwf+-zSxa(svfc{02sNYoeX3dDzKSuq$3Vs~xdW^0O)nyiT!ifUcIX|U2X(b?$+L8p!st5FdcFQ=V z59m_@%E-=;(EE28tmBYNI`E%D?kH=VT0jACOF_sJtp!gZsR^zXrz$YyoFg3_0g&;%wh}MYcdx>5aQ3~6rT3(~Dt$J2yQ-(}6 z3Ij3>7A#87WISkk&5b2`>y30x)(o0%bIl-$R2i$53Za5t(IQ!eBvrHClfQl_AffMS zCRZWJ=$6V0$VQPk@JN#TZXr0(U7E^ONaE%cKoY_%5XA6aA%@UBn(|dh!t10#9u$z! z3s;3CDm_A|GdaY1vM_F-XZ*Np zaAjqs1cJRS=G738BMs~jwtUp7!<2Fyc~q;&lyX+;HL;CBNCqSye|TKRj~OmV}InNxr06^kb?PE^noxZrBsJ+3zINi;W_TO z=drB_#1J$8h9%B3>Ag8x9)k2m)nfYcN}85{&~!t!nC>r0(-M$QS@`$q1)jM&X5*w+ zA?8!g_ob$Fs?zjo zibE;c9po?yDR-4aIn9LuDJ8-%9ED*L`}=j@#e8I*-3~6(-F1&uw?art%7qxWrgU*piim(4~|z5nI!YPxBI)6*(r<^bnFV7(p2&6=i;vJM` zwq{}}&1^OyrCs-g%(#BBkT&t5Lyp;G(IfPO0&h_0YJoQ@G+TEWHr&=qnS8JTeF@7x z%)o?%U7c;Q_Ee79;|xM}b@FIYtyjot&$5PDEO-dP{r@C_N2-xvbBT%IBenPuoH_iSrb^a{k!pgBDTo9n&}gPUhvac@KXd6 z-h^$`6A33>oRXqoFebl0%n4?>S42Mk(Phq7#QVJIs+?>VnVb-(I-awS#ikYMQQyf! zWGbH5(VXF2uHDLDyc?B}XAv0_8aFZ?USLJW!;As3FynZN z5JpO;WV&O`2>D7`laM4v!rlowP~c_qDb<>= zCRMN*{$6R?uMjgZv(l95-t`#uj!7(`6SqZ5VI5;XXA*)^_CBuzli<&>`13&nX%4Vv zEIW+Un1hmq$%f1vu53fj|5LgI-}tBNIY7vf-=nQ&gbF(>P^`X&`a@M;8}6zbHzUV{nR{L=SrT1&CFTS}zE}CBzw)29EOWY7Y|9B2y0#0h zEvLjQmy5|nEN61EDSkKs|CJNKX`A?xx8>xHFvT!V+dVrIF({{mBNt(H5dm2dC$qY> zDm12MyfrZw-5C%4D9m`N`iOaMBqv1NF@IND_+868R|tNt=+e;RW8U&g5k8iT&!Pl9 zCXsg6rjY2!nn9E3t{G%AF=xnUqM=*Wf{D9A(i`qFgiN4g91D_6&xD1Ep7BVYZplgq zjomRP9MW^F5IpD=Eg?@KcM8p*U#W*R$eJW`(e{M`51PzyafduFH2Wwt!_?Iu$UEY7 zrXhAas$5yK)RFVPa1{W3tOfQdWWTtbiH4@{+^Pw(z2Hx$(2cql$1-uyIO)Ve-f!S{ zGpSlM0h(TOGcpNRMl>@IF>}4OFEJtr2@^;tC5uNWCZ#t+Ij+7`B0)LR%8Le){CtFG zPLjRE3MF0Dw|APA<}Ns@*U}*@WJ+kc8OWyi;1kWfdT0W&D_V{;V&;OM(r~5_vtNLG z^bo4VJ*gH6g9e4)9VzD$k9M7dM&h`b+xY#0rWm_X`oraZiR*wIb0!6k`kFHbrP#72 z$eC8TxFb5z?dD~AvQK+-0_D_R*D6(Thla#_p9Nd)dkD5XP+NwurRrIhE!fbbg4Ls8 zm125?l!AHR5nJy0xLBd=l%`z@G1HoO`4p?tcRruYYDM1_q*%7nv@o73x;QNiol3MO zb3>_;f}T++X6|A(R}=|%4QX1~(%2Lm57kz4rbP;uE!qASV*EwN zubD|2%E>c36qJ+}ZdLX))j6X_fx-TFm*V2}r+aVNWZ;{ekijq_eA&FdSZsmcka7wWgpc zYl?(^ITS5id?y$N`)BLqT{*h6xhLd|XUz#Y?^#yXqiaoc zx|`ULQ>xzVcBHJR6m!+TAWe@&OFpY`g1hcM$Y1;Wm1RzGHE)ZvtKw|VwA@Y7>K>z7 zY5NRH2gTBCyA68OcNHWKrR*-^57-O?O|)FDgt1By{e~>mJ{{?ozVex2F0*4PPhu(N zG`lJ`?5HhY$5OtwI)7cz@4b{%$Ywf(rX{r83}j1uAc!eR5Mo*?Us)kL5;b&?OTY3E zv*H{_TFg`ga-x0t1k&4Tx`z}GF|)S`Eg!_ju3~k3C?}{+s(46h6L3pq)as5VAa_Oj zJ=O9jEG+}lbW9;;>|aaMw26@tn~;DAK2}?vFz0k>fqrsNNH5sz`dJb9UImZDQq0Va zr8Hy9g4nRGwtOAiViwUwL9cl!R!;+Yn+~CA2`x7RSrH!yVoDJWF$qO#v zh#=;}Nfk+Ga=r2D!K}sIBBoD=iaC-QLSqUsCy55j8Y}UTURViPkPR{DP>#1M(-r8s z-&bFR->Uq%%7V~6zu)t!LXZ6c&+EEhr>B11^LqYJov!_c=S}~Mb$UjQnT~m(R|>q^ zzf^BGC&#Q^`0sb*AMcUl(~Zp z;OC_J`J)PczEYolq<$_GcuPXRDe#j0yjQo?J?-BuF5Q=-V=V}|>RIdJ@P-^+t5jWU zD&;ZZ^HLrYy^d}yGRGvH)u)1oA+h{c<(p1uuYVZ*c#}1Q_BIV;(~4&EH=WR{!fUAv zL*CT{|E4qU_-{Jt_$}@DZ#wDtMeX=+I^$&irqc>CN!szxlYBkP(CBloDMO+*D`U`@ z;F>|UYf8CST!hBD3<}M#b5O`t9d-6&JQ%+r9htAzIH9lH1@7Pdi!IBXVp`solRmN0 zJr0Ap*pajX#E|ZS-_Q?K_Tx}?%FKpn+-m5fyPW<@znJP`Ei@y^#Z#$lZNJPo8@VH7 zhq4|)b}DNGa#mU9$UhNXBLd0d1U;!@%#|Txurm__jiK&67f1}vnn6#iHgg4uwkG`a z5OW6^ExssypUn0J==&6)S2CrvRK9N&g3l)SEKVHDmbjB1(IGxmW)_7~@-#=zed*Yo z*)J!#k`nl0y6zC)Jx2% z99`sFmV0{Y%)MW$AL~q6<}vT&Oe?!yNpwq9cm>JAC(njeIoZB7F8Lg=7OY|u?zOba5^7MZ#uQ{#SKm6fx zHE=LzTA>6qsge>xNeJiF;>VEh^or*x(=rQwcRMUx?>knw+;^;a=sb;wj(M{&Hu4ch zQpr9kYt$&WI)^mM)g5I+T&^bLa%F!11VfvS<_DQKTr?qDwKi4TguLrnNijFK zRIY3{S6oP}etn2%+F1-lwG5mh4%e)APb!mUGL*n`?7TiSVXu!PS zYmSZ=+)OBrBz4bqm^^~?+5FqRlCoacZ^zO3ZEMO&(lr|E8jW?Ccb-CBdBy)IPIeYo zqxS>f@|K~-oN4)25lKF9|GowJAQrU>w52i@s&*_(3f4?UxcL6ie4-fn-a&J~#t`$qZwxWJEQXj%?si$&K9FOc zV4Te8s@HT7IUZupi7~{yZj22x9egN045}|?Holgotb^T#GMDLGT_=15A(rwqmSP48 zDQjX=wyz28?fV+Z8?t22nn54wGXCphA0XaLBPBeSesdT!;m4iLJZdW+HUrSyqII%z{E*a&5?kVN2yDH#@m7 zbS$n4h99sS|8i8wY0qL??2X(c%4Esih)KOG@iJc5zl=AJUY2*|dF;yb*p=tF!u3}6 z<9%Xpr5Ep>-xIRevv7s`oDR4mUahHj&+o}T7`uH5-%+Pmwxrv$yoEl}+^RzQ&a1^9 z*J6)rvBxz$-uxqYT!TCoR%Qh*(`D{yXh{Nxs1O52kY)+Jm?s=9yJfdGYXMhZpW#}Uv z0TXS1xNcK#A+FF5HT)AbA>S05L9c4FDkQz+yb60HGnX!z)x@kq&M9j`dr4RsGR)tM zS9UDsGjrH?IWx@8oEhe4&Lq0+Vp|<9CuCaAR4-)Y<;=1sXKscTXS~qhj2GIQ@j`QR zY+!B13ysZqWo^wJ42`YFCm0(!Gc-46hW6Isfx$U5v^Zy4Ccl%iHLMfOQ%FC)zv&E} z$ewSABmPZi=t9;G4;TqKRvchRWISkwgxlDHB#p9WxcOd0WV~acsbU$=@_a`;Ki0x+ z-Wc1LrWE*ucTRw?@0pTDV6LDh;W4*R%k4`0FE69g_kH=%)?cXYRiTFqJm@*$-LB04 z@-io^TfXO*zx;E{oU(@bUga-lY))CyNNY}+1Ee*lObODOykrrSbq(~2Oba4`(^X~X z)^WO}?A$s|nOj63r{~hz`TeWQ6`6D%$T4U3$qCDxdP`a0w94^zGbJLvZ@@_jrx;Nvd*Q-0m?@A4|ki4c(B&X zTM`cjUCsVlvicJscXB@j}}&UT9jz3oXldp5i5u$&o2EN6xx z%b8)!a%LE`oS7Om6434El76$gOc|qpyW}BB*9wwLWVZ}x4;{#Oq5T;zG(Y2o)+cN% zlZg!sz2^;WLhuI}m87^U3AF}Y=9rx#yp z)7cdb!kpQ_x-N4VhSp_6m-O+ua`WYZ1n*ZWK34eE zn2?j6RaT$t2Hq8Uty0WN5L)dVjis2rH*xO)2sa$^MCN2$>(c0skcXaiEaZu2S-}E* zq>!&qg)DL7ho&D@ig`mPhL}$lHvz#Qk~`r|-6kMNf2gk{nRh3z0GZMxHnotk9`YE{ zKf0SN#Y4O>_tlmJ#kQWjxcojAt6N zr{7B#9LUj?PWOE^c`&`O`msN{_DaUshK{vrY+@A?ceU%QsBRUl2`|boiH>zS<^>;Z zXL50wGh2hS&6yZ+^v~6AbLGqra#C>G{*+i~$hEC<8VC;8ug+@s__jFfhh;NsD&n|V zj3+1LoLe;htzR$~rHBHRvXBLX#=Ji`L6BRn|Bb(3r{Ozs;Y5xJkCGfnQ#9p)wZ=X2 z@90*B`9y3*nzqR?3k~m)l647}uT4N^f_rT4y6Sqaz6cp<=<=UTWRN))y4dn`EUxs} z@N_II;-RiQOG0fqGt`$eLybAJyw0od+gLhZMV+Ou7W)9|Ys5Z)_P&SYU5}=071HN)GiVx%ISYb31E^02(MShl$(yvaKR}?7jO@|=85ErZ421L4tn7<7?Ba`5~PKM?x zaXNzhre#<-1-hZe*z}6c(RW9(vPX{j@IekM!JNs7U+_JN7kuU-2|XjK&po|nxf(B0 zzrvaUjd3&9FepkSDv+8ukdWK)$bS(Jy%+J&GZSr5Y@olgnFq-`vi+9vppSG*?n$UE zWj>#irPQt*6K=u3mZtM^%rl7-FUL$97wYgt(i3f6SZ-H^iiOMSr&CPP=3`(^m~Z8n zG%%3lm7CobLR`1~aXUA~sMDfx=W=pK>S&V1Na)bwYu?G-5Ir7ZIvGNeoUDpT3u>A< z!2%f;hE0_q@&Silt1%Qq0TZw_?Mp9B)_L{lpzP*)1|T@m7zZ@1Z`y>A?MR zGN7)E3<^2ySyqgY;vr`7#T9ShBMhv`3lZ*#%2=@Zm5nsPmPbrR#}d?pDHO=5Ld;cc z6A(V-Fs#>mW|4{^W85q}p;%yuh2LKnVpY)YDQiOGOMZe{?&BnAL?32@wGI zK_M$OY08H|6Ru=|%%&$z3^6kR$ZOSNewl%$YXWioZ{IHnK?(g2WI;_chX9Z{g_r}4 zrlq_IK?&Z(5HmGnh&kEB5HkRTmjEO@ul-KKyX7;WvdqUN`}9G0ci)VYF<~a$blexA z2ik|`ViSnpPcth;2+5Q9uDl<@{(n+thmzcTy`h|hZ`1J#%aWLo&*I430>E!uL{3_#DBL+2(=|F9MI*ZyojZk z)eb2O>D@OcO}&%m>>EOERes$ZP9Y|tAOR`i3~7C={+n~knKUKv`M3*1pEMYe)TX&H z4vBELeh5V;EGZD|rHsc?%=v#t%(|KsUX1rrn(-)>(#)6%r8M7lu_X6gLKtH=k=Zrl zRTSk(HA^=T?e{9U@j$*LVhG%vH%%WTavZ(r$dlF znhvQ-Qx7pWs%TomeIR4$hQ(>|jIMgCUGz z#3c9+q=Yjx_0GI_C82n$A$hSOB%fw*BTGNbAm2D}EPa1pcVEo(3)SaqCk#Ma&J6YC z%ur*_wE8d9>Fzw?eN|n40y(CvQOFr#aka|%Yi(*?tzrW%W)orPVa5v`OqnomQg(h- z8ycQ7L(6k!YS+BgNSfE0p||-yPi&Ff5sEEx%v6i$sC@O^Kzvst@%B1BwElDC0Uud$ zd9H@b=TICgj7q|NSjNGk_L8~KphJBa-CmPgqu)$%%+Q{sA&vNVYS9bG9c4Y;6A~lb zyp0K`8jz=aGUkJ4@u8Srt#waBGZWST80po&K)o0IA{J~90kO0o#Y*dMITW$_Yno3& z!Ph)>#Nyqxc-V<~i3qzf>8ia?I+9Nrx$AMVk#81dm*|p(9h!~iI|7H2`6oIUs*pY# zCqhTuC3xsY!VQ&61V7XvWv+ga@oU;xZ&Qi+$rONK;%rTTSH0i z5Ua5|)MpC+A@Qw<81o=@}PxnN}nd&m1mBH^Bf#ho$3`9=OLv+Us+YcjhzXX4u@jinI@E(mOwUCaSijlVzaoM1d3DA;W{u$y9J@5gg~}RG&(dY z<}hrJAm(HiLrg7wqJ^|d@MT0GWMIP9?Seqo9X<{nd3L-+PuNrAwN2{VRoUMQ~CTrmIf><datq^hNRB5q7urwU72o=MCHtzlSC*+(nB&JO@ZWd4vzhKk!fsptADA!lD9wFyFYgNd1o@Lce)bFUSp2hi*93lTdRD4>@5JNS3G*``M8``Rj-?Ejx8*luDdzV@Vq1PI zmhxMvwj64=d>;~NZrKXis{#K$2#7y_LXd86D>VFA2t1R;#Kse5_sRzjfBjX_we^REXJu%~hnp6EK zd&)uV9)uX|Ri zlV>XUHzB>?S}fR{eNRQ;q}uWvDVv^UnMZ2SlUZ5~2z*eE84uBPZ^m1bzi$`XrRwum zzX(Mqyy1t{UxF08KaeQ6*&g!bUuBSup9|UjuPMt46;h5=uvrp;Tut$bD4Z6XU9qb` z&!|i0z-%Ck%S>lR0%!8ec`MOx4n&M!t4C(6Ytpm{h|f+lZm&ekk{V_v^lW*^ z8-ct_*RoO`vMG@LbS>NEAxJ+~EoN6%r1o~C*Wey$I;@Z?Wal5Fl21$vIqz8uLaun$ zs*szWwJqd(&)OAo&$F!YGZ-0ZZV+4nQqxcj;rA=G)vV@KL64{ub8Has5z&&@6jbjQ znVg)dJrj5O>%G(^#~j=*C$%EeiZW&#iSVrG9t(}2ltPT0X54vt{qD3E+=2F~U4_J2 zcN?3~lc|~0(0dyBYG|rMhH+20Cr-2$BwsRR(8roX&aEe2z!%|eCKlLe=t*VO46|=g&tF*v@4n!bfj}3jptSJ#Db7FQM7Tk87~M* z7H8-y253fdXx68fRSnFD>OQLRCKEHs1e_0B;K6k-59tj(&BgvX6A!ZKGtLa!;Z2Klbg z4EoSFgFI4JwNv6v+!H1Z!oFQ_8oEOzk3)79Y=XY8&8m>z>2aKXTR=i@D{>t2y|St} zc&@DR*g*NUX@4a`Hi#^`@b9c~h&pVc(vJ%93+m z=+gr4OlbPHnK6~_yQ{G{PWW?hQ!dU+ZY}9pGiOU6S1Wq4lp%V4R>Ij*F&8EaV)mk% zZ!S#Mr0F|_n3D;R_a3q+Hc}80hBH#ORLT%i-lTiHF6a%FVtS0(6ww4*k45^KYB2{h zkc#>;PH?t8%NlY>`Jjr2kg}mt%(OTW^r=cQgM`^s(}eXZ6?ISz8)sl1c~&?qn-HAU zlTdQT3q_~Yo!IDFDB9&mC^;cz5d6TqZgniZCc{C+brd4ruR>(QeS`zY&XRQgj z?paoHY)jL94}o0xH`sinvB}Mvkls8~Fj5LmS{~69Z3)wL3^8j)kA!$sLtTX&{kOD3 zYC_)mx0Tf)ShYwLC>joRY(Smd*u$2v6C4JJ*?yDDdecK zs*se3Y&gqbUumnSkPFJHLar(6DQUT=WA7>CTV+)t54FrZrOfPWnRz-Y>0Hy{^AwVF zbEY!#NOTtp>eC0UPfu%6eKKEbWE6CWcUeH839Qo(NffhY(1fuNQ9Q_+L6f5eZ(7Cl ztQj=J#WjO$CX-3kOf)pf;~p!8#ILLwG&$g!L7o(%1I@(Znn6;NGilHtwfA4p`^Vb* zFXG_5i0kQ#I5scn{bTL@7bL<*&k7SFGc2_Z6Sc+>98Zhjcv=LShVsmr8=t3Z@NMucO9 z{peU>1RcvtL3F**x!`j^79)=y;n9)S`bT&)sD=Fz9?j}9(0l?KPgc`CVlLiOh`Fut zPMUg%`DwE4Cl^F*}x_3Jp*)=L?uWcnqo>2a4Vh^aRF1bQKb|>xB&+hr^<&1nBbBLBju~%VXsTDn zgJv$sl~9uIN@C?qYp^s3L8Va$D$5N*P+4veg35A(5LA}if)Kcc{+O_~{=Iqx91C(= zShp+gty@m+NTjlB1R*<=^}HLFR`+M!LiTx9zmS8TH7w+)XVrw9@~jylXFY3P$VJb3 zBjk!_(SIAtdfuS>D$DfcskVD|F62kgYW=NxtnSFs#p14zot|}1$oro4K*)!l)i30v zXEn&7$}$PnrxnZma##7Zy6Xp#(%#~F{+JqwqN zhqE}4@ygntI~_WZGx30K%9)(dXYS(nfB9bISl*NZfoD0B6I{$jx%3LXl(*xAK5}{% ze(uZaF=~Gn^|0<`JPO~6P6zH&z(ViH(f!B{WbePr4AHX;-6uTP405Z`4EoeJgIv*S z`y7%2>x4nJ%k1R77Yq4NSyjkUVP#H1ztU#UA(slxpm(%cbyrA=c_xi&{y+=-OUNl@ zJ%^l8RuytqSeY>Bd2RL_a{MG}&U!)?St zGI6+8kW3t|6(n;+CLfwA?vRkapudDp zWIT!r^&{h5Ru*5&g;)uKa&}=Now*~&Oab)1=0O#5R%g$r zklo++0~Wehc&;}g-z)1W8BujiJ3$oX@g7j5?G9Fix@wl2~Tv0Eacu1}c zvVcMR+F^dP;&aswYJX-H^pe*68YH#fec_7?*wKFcDxM{4alCXh%-13FW@PBK+X4;? zrelTEp<{)!p<}U8jwfI0>vyx)@A7Wg6u^=QGJCTjYR#_>nl^?JC*=RLZ=UTGX z#PJh3=GWe>vT2K%IWsI?InxrqE@F}7zP=vHN%$Z;QZ_`IgFt%0Umx17J47IMb3 zEQ@2oPY~?OpE*urDc5A)ri5TeL-7Ng^ydA*a`Jkl?28SjYRjJ>RM^x~`4g5c^dNiv zZcJE^htiz`+O1VcZtA<&2-vUZuDiP=vjjJgVnIg520VB3a7`{+CiU{|#jKFrXLGIM zyN%|3m{^zI*+hYRuqqa8-XYl$Cr;#;@*}+6vcc4&8%@>0YW;$ESdK2@gG0iSqhsBZ zeV}gL8XAEd6PEjgQ17(RYXu(kJB2=h*-hVnv>iAf2)X z7}T|Zc~@^*nv#xgnqYojQ7Puku_a9#tfbf#Nfh-Cp_m?^{inby=VlJCvDNkZ4rY*Z-%c(~9>sX4pAlei3iI-xP0w9O!5So_Iax;)4@qr+wEQmr( z!h)zx^2H~lIi5Nqi21d?5rIr=cADdj++R|NIV;iBU!+aM7ikk*q@C$@+yvWk?YaYN zz8~^d%-U4*%*o>l5IoA4eB9|6@tazZ-1l}rQP0-bp0=8TWWUR8FhH{3<$#df+HkEP z@9Bp96!#6f^+J9MvR7HU^+h*0@sQO1+$B!f3vlh?-H<7IjvbI3%8B0&nX<|R9nmUl zg4^y+zuw71PR=YVskQRW-mOSfoomTji!#bAv-S@26B7Mw^uL^GZD^!%$a4yyM6HkapA5S`7$2% zFH;3mecY(!R_c8fto5Wp@wlV?tHr}-+!S5euU%=5>_PF%*THJL)GTg#x-}+hxwGh4 ztV+Fl^HQZIx?XEKn9pQ20YUnL*Fx$(&|zmPo)vUKiq*L{1DT5qGuNoxz#-M#{ABsk z1Y|=DE1`u!b*f!uj-VzW$0FTpF{cTdo~Iku1cX}BsYBmfL^Xg+$;Ir9UerE06LL{5 zYHwG**{N{yMz3@ywuL+^w&P?`FMlT>-ze+Jdm+!2H33Q8a9X!352ct?<(QkoNljNr z6Odd0=ioj0d)sjRiaZB%(kV>$02Sn*u(B)VDWMmNSWebGc2~&LVmnT#drrr&RNk5# zb6Yr>*0MY?BP4Y(cZ8d9tx}kCFemL=tb;hvWXM@M zgrWuG&xXnhcu zTXn`aD+Q3d9zyA!bw0W#y_25-GA7c!7PAD=bUNLz zCLpUKoxV=!P&$$YZ~}y;lrpzYY_Kq93>Zi7k?+clV)X*rX?U_5yY+x0+~)X41-EQ zRz*5}ozS6lf~fBPtwwCP=CbDROW z>mk^~-DfwCW6gZ}07fuxW4PxS5X@T;313L8h*_;_o;iTI173I*xB)RtW;ZgrO4$! zf)~@nKPP6*t9fSld9-9lA?DOWj0;brSnjQe4{Pd66>?8m<_^iGG`#{O=`!d*^c<;a zRmfJITTN@v1lWJj^%YZ z*(x$aQDON+(x`x1Do-G5${IoRhO*3M1*R<&t=W~6!y?l%5lOFA`2^&gvPKYnpe!@F zFm1hP&8eJxEHW()h5eceA;@marQ=Ap01jy60`y zr%7qbD{Ki`XgViQm&peePTs0&^Y^_Mr0J4E%rF5tP{;^x&>ibbb!Hh~5%ji7`6`xT zJ`l7j=q)eBN*^E_=@6Qh&~h`7cj5y^@vKDkdmI z(NrQ2nDBr}CGx-n8e&K+6CQXViV2C8Ty9c{r6Fm@oa^`d#;h?|>lMpEXe*ninuMW!~M`Lc#lD%X44wbKglddE*ecD1yK81%KrWR^P>(fWQSS zSSut#X2T&InnBCMK<3~B;~FyeTui{bm>W=I>q338@|6csU*F`+K9j_#bv1@xM%&l( zrujQ(PFOSD*&kSPhQVRmX3+95kVW{wxP~+Z z7ZcDFcA&=Ah1wMMJ&4*AIJ51Kmem`tcLGu8o3BNM@Ylmn<<~#zJE+|lIv5V&&D@B9wM@^|89BGhcNKgIvNrUir)~QdK-UFl?9lb|7yIQHM7;0CUFWI|Z zixmB00z(Nk6On7wX}FX%yn(qZZ(z^2V~7|880A5RS%(63AK0ng_XHSxX>SENczqx@B#E?41znw?Xb$)+>-# zmZen?<9Q_U93eR_@qEE}UJ7f3!Fw+;c;Uz31uZ%ji`4I{(V{nE(J09?QU8(_y%pAI zGcvp)Nq@tVZCJ1k1dNyk0dKE>F`s_V$$aq+Ok-y3u<3r3Fus z92eFLlANeUBgxd9CCP>z+lAK4hHZ=>$*MA=SX5lc42xuHNh5hBtDJhnUMjEZD#zeG z&i^Q4ZN>ANw5_vAhN?qqW0GVqSTWKqj+p0H$0VzR+qrm{UmlZwc}%+H5hMNjP`^&V z`gn!O6^kKly)Mz~Aq!Re3==B0iS(6BvI5DXG_C0!kPNSJkR&4=3+qOR2c?k}80k_f`lQ*> z%>6f#%t9=UG&5p`u{60Ijfauue$>37Lh?WgeVSX-_m)MHg>0N6$%Gq~er~7T+!~Ec z?K`y0*f7%XWd~b`ka=4HFZ^^D+;kf&-02a^4_$m(Q}cr~yMy_GDamvqIcHdwu{s)h zmD*6$V#1h|*A&UyOjt@44rx}42|P&_i-{FU)=g|Y3x|n~d2Ck9UCbkGb2i-$e>qjt zv0$c*R+7wAJdE^}OnCJ+5$7mFk^GvR>7Zu`lP7f3diu18Fd-YbsHHHqzY`v|O-qJVS`Cz7qRtD5{ zBj())X+s{N{^0YHmkP<=}C)?o)!dl=stm{8=(#iwGef0{REIy zS~bHsl+D^)4cr5y745#=ZXq-+6YyotMvQaWN||K0;(8wNX@zA^aNz_jc8=5~krk}I zZsYEq%+7=Rq#5zMM1kCHm{D3NXcqks_!atFcyuGtQ>(fMHm0_DnqjX1VLvt9fcI<9 zWrlgXoPeG|!8a1OA_Z@X;Nm_=tE=d*&FX{MUFbLvU21>Y!_bs@cVi0$w@b@a*GwRF#FOO@T9;d$fSLO9(etA^zvV6yXgo0?f|t$6MUBaxWQR?-}I0$1&t{ zh%M+mseOc&Vs5gzVg*=s04=A|^3-RI^nX}(GwMF04?{CRICMs|sB2gOLo+}))aFv% z0L?;62FNuao&P2uFcwG_gf%$^a>BBfr^|p>I0kGzsH;PyjF7w()>ID!mPGIrb?sPI z|BJHvB97(;tyY3mPyft?HpwTVUac2GE+@+dBv(|$Qu$%aRJd89`W9%ilkjfHio28l8_-A&FfXgb*b!H|u zfV5pL3M9E|n5BW_Y%1lX_a)^el1Hgwq!%TZlO#DoV>?K1+hHU*SL0!%Z5e#cGGOyI z=Jp`y0}}ia$r4zxFw)GGnMou$x#D5WQNK))Ns>ijl}OqYP5LPcUY?lMSbykze3yzk z={7sjIzaXbYlh^k1bvF64e$&Dd?k}*iX;PVijO3Nnhr20h#5wbfi@k0BH7N{5ZBl4A6CB_&htAnta4y_P2bp|=ie}Lp!N*{+ zngeuE$8svXq&X2AqM|z)3`+~&3M6ie7wUECx(89`5+S>yC6BF?VmnFfX1WzXX~waM*>z}|Mf}E&ItLla(lp%yvdyyCux&$}_M5bN_ck!5 zFZ`Ik@MHRd;bm-192&NGG9!V0;RpH!1KlEle!)O<4{fe^s|I>TLil19q}^7(@MHgi zu|Kmw#=cns{erP?w=6&QFZ|f6&yL*K$IBec+1Bn$#(7-g_mc7B#b)Xv^S!LBFB!jW z3F%8We(9Cf7UfF@=2Qanl7YFgEC!}k0`t-j%u7Eo`uoe6%M3<9gFp2lEnXW?SK%sB zx}3zYeKUBHM75LS-jri4G9C}go-5lU$Y?WwT)cs zcSsJu_H+2PpF{O~_wBIT#!X#H84wFmL;Wxi-e+KX0&XudsWy}9$Fg%kXix?%tfx7t z=cy%-%a)}r#djlR1`4e$&wX3e$9XjSOw2EF$r+OwA{W#PQt0ZY%NP987c4E$3Re4@ zFL=rqJjHov1*_MYuHX;WUj`##y22Btmi13t{2J=R*2&8@)JMD2iJCh~*|F8;OHoT} z1L%|#E%*-uIe=lO;+|S`guD@mdV&1f)1pSqhp2}65H-6#L^bRXzGQI!43KMy*ra<~ zIbh2}DVJ7?RznknCI@VVxE>udTe`_TBpOCk*2f z6|lkbA*wHgJdti+AZZor+ceMCV91bFOp=Nlqi+_qjC0?=C}JkL@87X3P0A|_-4%%1 zu2(RW+RW93rsWKfOVOgXYZnqE$X!l`xbjtQ`Gk3Ew>{j zOtvT6X`Z>ACK>0pnuO{0nuMvvc@DjFMeZ)BS95H+7NX7*LUvM}TeHl?1U$GTWFy=e zIzh_Wm}=MwhQ1Yux4N1I_Xdj~A5aF|aA)xs zvG$r&aCz;JYdf{nTq%vwceh+IF;6Q$%Hb{{pfI?3sLg>sxNm!an#F!VYE$e=iC+=) zBlo*%rD zdMR}$5Op>8wWts-m2c%vw%W`tG1NlT$;OwbI5pxQ@}WI(=WkeA;XO(zN67ukFLyR8 z((%<$E@7yJs5$JyE0lXL%kP}U3H!QCcHkJ0LrOUiDI>lV^>5Zt%DzY$^`)qr+$I)$b&CbPngzph6iI~?2B1N65ml$fNk7{cR4Ei9?8(=aINt@E9SUW(y;-adYN}2b7jp{a} z?~4|7Q%x_9YJsSG-&06`YqgNvnPp3!+y{9mtim_ddgkkTMqOi~OTCJ? zKscGgxFeCKQd6}g2Ov2fMw(j9Fp?9gVVbv0D7Bi0uAP9VDkiIx*g#iI1*7jubXGY@ zBX?~~m{}!NayF}+{1)Ayj8>#R3u_?PEsM@}NqwrlEdsi_V9n71NGaf$I68ro#WYis zL-n4Ns!R~|1?-tApA*SA*`VrKg&)jTzzTH)$hD1|uEzz%C9B1{ z7EG!sYiiEnhlQwJGmm9&JT>Z#B1X7b=1ZOyPboJrpdnKIg5h;-D z`FCV{F#vK%ScL_Uhr*gX26<&!nv+z&BsbKV7iOwn~SqWVm6J}OPm7L8gC%;9jD5Ey1yg~=a zPRpXRuPjS5aVCW!h1HX)SH ziDdlIHwW$TgV_q$gbV}11{9>n1;r(+Wvv!Wswrz~O7O=*)I~avW#gV2brZq}uL5ee z5A3k#mZkYeDa+vy4oxZ6v^)&t8a}lCkUNe7$@jvVY?&+nYdemnsGow|5Z2^2$V1E0 zoTU0T(KSL{og!s~y2dSwx^^uqyRK2{>JTZTBnO4{eX5@k)+p7#wyf;xpHY2}NO|V# zdPZIQc9fhq!&XiM4i2PEbI2vsQrf#E{ZdG7A;CCSSebHIW(oXJ|J8@&&8Jl$&)|g zPHXZURDU7rN2u#sbd69~uLvHYt|iOLu4|OK-ioeK zlIA9|9i{0yML3zlxH(YS9KJjEj$H0RUTQT#0I)zDi|Fq`WShR#gMi}7pSd}@||=MJQE_4^evVaY5}z+ zD;D)pV8Y}Hr3WliZv4}cn@RaX+KN^ivnx7_-RidLEy}crv@}QG?ERSoSrC7!4wkn5~8`#(l_maF8a6)SnrdHXML{LDz z=74m;v;j%Sgl5=V4DG-SFy83fDi;(ow`;+)OIuO5Rm~V`A?obSW7!SDX4R#1c?SIM%n>l&r5NTiIC>=xGdslFhrQL3M}tnBKaQGL5edFJbSMqRUZl%|WRyF|W1 zIsq}qz$6WnClq9ujp`ytNd(=QcJm_T_Wz;3NXZm3mO;(a1%()03no=xS~fe7cneXR zXCBMiJT+?bWP}H8Y38U_O6j*!w2*LUN^yNamf*u%@uko)U+$FMIL4h4+<6^R!Nd$eO;Q;=Vbl#%|1}9E5p-wTP0RUj z|4)6hI0Fx^Bw*@C0%)p*sLPBGQGW_T$Q%rd14DXMjGbX=Z(G(Ykk&r+!y21_SSf`w zu+BxWx*^%c&;x;}fw`p_={GuDP{=1g?gA5Vx2_k=~n4i z>MF(P^`(p=&0;o}oJ`gUB9@LGV-WCn7pUzO#56~L?=ae;a0)7OL(7b^8loS#f(%QO z!a2ifVw_+UX-18xmbVFpNq8N@6G*xCz7^N+Y_7M_9}vMepslyW0ec!W|4B1OGH zMJZz|b$%0aEfBSf5Rya7!$97OFRJ@X7+U-f z%H27x7}68qnI=CAaz8apD=doM|5GdaHRvZPIi#u9^f#(o7Yimy=COd1W9KM3kDTU| zC!{yQGgi~N^VF~l$6+(f^*3!5y^MLJX{mvRhI|QHlj{Bp0r2x7Cs@X z0(nl-DpoftlwuXD>tzlt>#*@Pj!A4UaYAc@vQ0_WUiG&UIUxHm?G#7z1w1W-?WldW zG&2cV#_Xzwm7{S|@Qh5ZA_ZSs)(uFjtLW=eYpR1%M6lY|J25n6-rd+j!8V}JeZkLt zC)N7xhQ&kTtW|SWJecr8fekLw2cZ5PL9`2AHLud#*W= zqOR+Go)pzqDolB-xpxRHXW@qV5cOiphp6u7fSkaG3moG)Li$Slo4f|uwrDR|v@kt@ z=<}4-q^npRP`Y%m8;+VfBsnas$W-bVxG;Cix_7GNxRA0$!_Q2zygzk{+;TlC)-)Tr-VHw9=YX@=a2o zcF-j1iYtM1D`Jug6Du!I!Q7$fAq0zgH-ALi_g#HVU+|>N_)^qYTZ)h}E(x42d4ltp zHv=iNB3NDC<}q|vAf+RaZ!F7qQY{l-@RTn&&y?^5-?7EZ)^Dv-(v}R61xSA-TAnj5 zrWuI?L$(N#fMCYwXDuia& z1X10ibe2cJa&e7>vL6RLG3`O64N2=(-OmAe3h8#~QEP+-Wq|BK%c=NMAo)&MlShA6 z-e{iSXjaBckXOP|uW_jBOazZm@Eeh$ZbvDFW*S>a-kZf#aG$!45S3koBH6SuJ{M^w zPnZI8fBi4cqAi~G{J5N~M8Ggk=F?2AN7IxDpk!0w2nyMpP)>H2%x?C7YQ6`LIuOU$ zdeX~Mds8G=Q^QDa$gl!Q`epWRNBGybDJ1E47U`xVpg}Q+oHeoOq%UPA6-Zi}O0?-R zWfN)IW-6LwH!^HGpl_zy;bD+sz-F*dZa>Vc1;k~JxXVJ1S}yNNa(KAfa=Q;WiVZ+jgP0*CC z(wiuif6~q1nPF`p>8Np#q;;_5JE-;^I!KdZ2T31DZp6&(w3$wAyT4PR=sXyjaEIm` zB3-OTbBooFm%9Bt@}$i8Qq=7yo8%iQq3Lr^a31q6Amvg7tJ}}F82UuAT^ay6Y+1gO zYH9g`r+mSACZ#XjNDXK?w-g=}$Xm(8y)jdjQc?2w2Ge{_xpMYDetAMOa z*{H8=tzqbfK-3$Ogm4W^t$lC9r5s~u4#=r!QMb1odM1zp$w<~@wMJ-TO%OG%T`*`M z+^`&wen_{Q4RwaopbU_0XxS5A)YXfSeSxUiB_xNI43J$I^cu%_Cqw#3jGa6I`8GAo z*;hsG#_9n?AEeA7UBzlMnKh%YAu;-od9AAEmXKzFsJSI1hn5VG8~D-+!{XeMZWm)G zJ3$VlhG}7X0MRWeb4XXQIv}@$kT`*(xjG@aEUd{3knb%^iv|T31)^2}AvEC5ZMk#7 zbj}J^CsPfOIUC9gkXM$aC1e~!O9D~%3Uq7yC#gqenjV7M0E%Z=J7@}ud7*MnU~h8o zhJH7vE#gT(nC7;~8~tNEv~wNuW1C2CONC0h?7?kQPn)Oe~P-QgRYqCzkHA zO3`^RG$GbQx<+%h;SGZs5F8Gr1pygl*>_3Fsr%X-kO@fN5G{pGkO!7Ua&?(ogsJx+ zyMHPyCyU2@W?o%%!puh8KIPiwD=)(Eg~vA2u0Em8RZs4IbrgoS3<9T1Hu)a zbQvh>fS8y^`iY2Ee?H-g&SJNEQ;)*mBRGlOpd+c70?AHcl}L7j6(dRa$*=;+VPU-_ zd6q)Dc`*Io%|fg|n*nrZBPE*jrdTjZk`|ani3V`GCGH?ewhq)wKN@hJiYMu7@Ju@+ z$+()YX^|WkGfN~nd1ISMThmK4{YH>8BpE}al8#wt)OJT_c2drercK+<|VNsp~B>b{Y_P)Zz2(wCx4%7BtXitd(>xS0!Bj*bvy zLK~v5eK*zbpdEWse&9<{Kl{UsUP#4$&5UyL<};5)-YF4R9~k6-G(&m@Ev!!Ko?1~k zAe_8Q;=Zb74nvm(qHc^ihc*Qw4UcPI!0l8{yVq8V-$GRLsW2r)>){;A*%`3=JA{oH zAe`VsvJe+Y-Uw^5TfzoTdNDc=x;hS(K8UaD9)?pI+q`^AX?P>0`nNUhhuZ} zlkJ8r*TphdbJCS%-qQWa{}Xw_z|Jbo>@|JE5@uFOX6CpK223W`yLdTv#e^);uAF?< zFvV-(sb0lULYkt5esvd1&^Ev!->mg9eZhL_(l|Q5YlF?qk4ZN!&N$sH;6r4bb*Ca& zZ3_n&nge2cnA#Rjpyf&oQ|e%XE?%a#Tf1hPZ6PmTd`TVGrcK zWgUS$wyZOdR+n1N9Qqc}O>ifMQrevf z?t$Q<*rEoj4?~{{M4c&v*|ku52E#aX723)>EH~O=`z}{jvMF*!1?`kvNoK3|zy2=` zTdpjywL%z&Z?h77b={e9AVGT+f))V|*`xRveUCy6{i!SC==_QeHq*9mS;rvlbXHUH z3Xmg_qRzU#><}7sX|;5%lp9nJj;4={gIu(%6_BfzrPZacYlOP`M9K(t&07|Aty@-h zU8B_1D^f;D7KQbFs$UY;DAn&+R(AEzsQ#%)dFJbSMqQhBl%|WRYX>CcVu+acNPDuF z@q~g5Q~&FIltj>-X*bR8zxsdmKghxqGL}L8)&+$aT?-~vUs^VYkVOkopAO}*Y|vAq zevpe1p0lNyqgp9t#!Asb!l5a}^#R#~51qf@^Vz}>$f9MffIPIUy+1Dl_Hi^VR`bZ$ zHR9_U@pX+**K5(GKK`YyQ_0aN$#s!3Nx`R<73##52!2MA&X`-hBy9|z(XRo~Rr1xV zTTD7Jh)l%O-c=U!sI3p$VjeZq+mM#g20heaZn;x5#Rc4jKS!{#XeMR=79{M^h7s*1SYb-K*!Ztmvsx_v&oo(chDusaEKO zycK6gNbZZ2sUwiBs}!u(wl8>;f^S5ZT06d!XO!|@q^Psmmoi2v??j6FrXL~A2u3_x zNxza?;R z7`iHu?=!sbEK93#N|_Z%(U+pyLK{-4))eP}v|)xdf5Vwp=mj}!S(;*B%7`yTy&$BN zr!wnDNiO}8=1ngCCuQ;sN7F&azb&(7a5Svl^)hQ8$M`w?e_CcO;b>SJAP+1n)YSzs z@)=3GZ1$ogZ4950ypph%y8ohVQJ;8MqIXB)UCFn*H^2C0p#hwy<8V8HPvB%B&EyGF3jsVmNRQ>o8JHNWl`i8s4!`3Z zOn`oadW(6at$WYt-X5k?Jd9I|z9r%u*J2*$8?B9bp{6q1x2E1O0~4Q&WZId%L?%z@ zYci7F(z9eFvqm=(rsfCx7eOJu6VsPU(-7z^a&|D~4y9A6O@ffUaL6kRCFDEF^4z6n zn7Cb0rLKq^N>u@`;Os-XUEW@fqyLtq55FM!Mp!S|Pj=CJ%&X=nUblYfb_X+xGoIyQ zSTmRuoCt=c)eXCKhTJ_273>8qzxw z$``Ld9$3~PNLzI;Samkj>a{WTQ$fg5;Mr23;vOkfb)Fr0=Bp)k1qihzTMVr$xS+=9 z_tYizE->bzNHeV!(dv?@srRGuSk~;RQSV2M17a8L7u@u9V*?fNSGJ#eQcAuQHS4~V zDPM}((I{n1VjZk_C_f~$qtQC6O6_PIn!%xmfea&DB^=|9MtVs?`Smi$b<5fWX{+vQ zKhx^(>8PIy0y^57XG?*KJEh#!j<)TYua?*uAk-Gr(OghSN4p!$ch%0BN6!s{&?cc) z+u%D7qPDa_NayVdb8m^4><4S*yGMrA{rAh{GLD8-zzvBpxhGcQZL(R*+5x#Px5-Ky zAYWM)uk^1hs}I*SyxcJwSHRl9(Xb9c^0L*iwAF=<(#v=r(s172i+LYQPE*v|w(za&ha6u~t2cXrkrws>2jA4vn7nVthX5y6ucKi9l9nv8Q(n=qN@ z_sBOCxj9e9@}id6$5@`S7?QDWIV8-`uyv&FP<4Xl^>2l0-J&t+r z;3%s(!8+v}^IQjFUa0-q({94^YvLA@o-hMb{({q+{wD!<1CTJ?lqYI}5}u5_`*hD^ zmc$_@eJ$;6n&fR2KyPCxouw-=k2JGwZdkC2S+4Q0T9W+)y*ZXcdR6-MB+2#EFw)yH ztU&TaSd%2*rI73)#Z<^huS>`#cR;ecn5{nN(E{d^VR0I<-VBTFmpvtRij}pOnr)=H zf*2^tZCN=AB$*{Mib;BnQLzHj$AX+ZcV?+Ux_L9KTGE!jGfsL&*7pL*O<_%wd<9l) zI_VP`Rvrwq)LFa&3B0;7naysCcG_`Nz&cm znKwrZAXyA%(vak`Y(|l^%g(f0DP|N4g{2UiLE4r@fn~uGh=;KT*so$9>932bI)w^ZwGAzxa zRanA>$b^a(_1X17ld=yfr{b4-C+84DPXwYqDZGg>biZWV?};swz^rqc^E=SNeeL z_=2Z>^VB|4MT#|V+BZ)XJb|d$=uI6WYW=dgoSFf-YFX5^D)+vo)ADqC5IPSC*i?3!_d?n8 zSc}JGO&;OS|3Jz}eM6E`3L-__u@GVv%XO7itV$Vz!eLRY?hnQ>bRWlLjo`_tmE&H~ zCF9(kdC&qwjdLPgZW-_rF`&}#M#>Cqu(mvR9S!(vGs}>&BOa+Oj1WfJT#;$Dx#DS2 zA?tuxE$YgY1M&u1uEX6w%MN)52(OF-YNQhv)V-+-Yc0xoFx`%xfRdp}>03OSX?;*L zhNJoUq6QiEAnK#66+rmPrJ2+E?{ZvF$Wz0+!Thdzm6}J-E`o3v9_k$rqK3L1o0e|b z@~Iu3L+yQEwF&U@Hg&U4E1MjUGx%_cW4t#Y{Wjb`iXkKxLpqWbxbOsIzp&IFx=}Kv zB%2q&+eFMQl3#My$gN_)4G1cu;8+>y&T7hDxXNNA74u$QfB}Ah)R(n#Kp6gEap@(= zg0R$@=FpNrW=L`mAK>wOpj+%lz6T_?DFGLmyuUXgQYIHb^2T()!gB%0JCRZ#+3}z8 zb%0_o$T7>B09mrES&++?^%~^4Woa|IibXeKq`Fz86I7hcAxE|Qt=PN31YNPvkCyPL zAL#3iGC0D&0_Ir8_0Ic(wv}_b%7N9=oA^93p+{^d;{}nOL9f-<|1Lb`VywA zF=2-4><}|=n|jn&+dQLxR@ZZSHzDeuQ`e?txt;}FqfwWw>gOb>(^NIdl==mzwb_;0 zug#)C2&T?}R?ng15{hRG#T(1gQcNjh;Sdf@Db}<+4CDenJl&9$q5yKvvX(%uTGlqm zUCTNKd16_blT`miAR|2>hb)U0Em#&UTDL4(v~O9o=#6ECTGTI)QL3M}EUI6#EUMqL zEULe>tWfnfAkV0tI?XhruGb>?8FigomZt0KRO`q$M72~s zT$-r`%9Rw~p>YL;+_iD#m}WsS8S31Z@{Ce!4%CMjl#&7BPYU(c1;e~2X)7FpJh3b- z{*6-dco zD3=k%r+Ny0M zTALFC24TiHjtx=ej##gd>$b8la3SJZ758g^P7ZgFOsk;4U_o$=5hmdn*@Z)$OfR^x3 zdg%NGV%`v`8~hp|=h?MnfSf{l1_*~{aQ{vq>c;9}w9xHqL@sP8&4+pm9XC<~g#lbu z4$9S~8W*CQEo2r%In9r%#JmqS2Ka12|J>K}Cqf6j3XYQ(uf)NqkS)180OL4X-xD@A(h`30HhPrdqhj+D+NHhFw{nP$_+!cXJU>NMm6QJ6+Gz+ zE<(E;+)zH6R}PJ-mmJY!ItCG6^HLhgF|gt<2#{t2G1((IYmsXpcZ8*8kJU$M0afoq z$bnkFt@-AwJ-sNzLWx`tV&!}k9{dqzLd&uv0B1+iy01AZ-F?Ci)}?n#w%m zUJ>M5fU0=x3T9VsjQ%Jhy(XK_<%pseprSEajy6EIL0!yq|D*4&z9I%TMt>ZU9v0cF zqK~dLMqH?@hDx%zkTphsBA=!o64`%#i|jwQLP1rMJuG(5N2IOnUx;kp3U7>l5k-hk zv&88a5$`?Y?T#oO$2hj9#<_-7vTFzf8=~)#b*Hv+4b!)N*x*DUk!3og)Qa5Wu)MjgPjj_gPyGx|( zKK#oVj%JffauY1G7j9uWumobB$OPf0{!ug{!dOorP|T0HImH%cW9dfm7SIZcITL6p z4~XkcCQa9NG$_}nS@2n5=C8N91y2S=$ zKg+>&^br4&vgWQtUqLh{cysiV!^(fZhcmAJQT&PG0J>dM^ye)VUn8VjE~p`@_-B0y zaeqG86#YWiSKP-d^F^2i>sgsJfS}7%8N=ZwpFQuMr`P@8;?>)Ims&+rh zEoGbQddkwHE%7X?rK1YaAK2MKx*;+A-Ex&*BCvs;L(M6EHro^xzf~`G-U7rp$F`Af zlOINZr4=~E6b1672BDT_fv8$?KThWnH{P@FYA#QQunYctD8AU7O_z%bxcAZtXR;}B zQT3#Vo;-nP<~C78x(7USi(YGKcO<488m(sazF!W=0JO}De-+>8Vm0T03`2TBw5U<6 z0WvFER9~oNTp$&HR!R3KFqB%FqPEIE(5?guxWoRj^aPl;fDkN7)YQ_<0ipDL(Nghc z8-{raLstb-(q=0mE7>7C0tq&(CN1i-O8R0AyAKF`$Pnbu39^o?Z%Fn_T8-TaM4e&} zqvaLcwzE=ofA>KkH0S`@%O4qAdoX?IhT;AhUI`B64mJATLEp>ol_S_`-wwZYutR43N?AKf;T>*UB z~?k&R$!VufF2i1yIxv;;BecEhgkfATNBy6?ctPOed{k)m9Fj z6U8N8afu3ebOY{7$&)r;N}eG2Qa+w7LkO6SZXR2FDS6`JOQ|1Q;`@4T*;Ts_$vR|V zGQM9#KZ}0%cPc(`t^}*{2)7cX>SwqCa;?jurfwk*=D*rH?N);}{S`4m|)Q zq(u<31I!oZ&H8`_P8BC&9jgrt`%W_%KBUNh;?Yfx5BYqwge2!<`LFJCFOadfI0h8w zr2`4^|1L1q{z?r@a@9OS5EwbQ6Z6VRW?&?`~C11!~#dT*uaZxa@zf1;6 zwuzJ(U+@fpJi3nd;~$>l7+?z_R&mK!T%tlAUBxutDpqYRLKbD4A5gD?wT5H0KlFhi zw@AUi$icPsP9T#@kiU&%K&XAiFMKI#Gpi>l<6aP^SUi1F$T>E?lRZFNDLMA_)4r67 z4>;h6y!^zySwLD@=@wEaT5?RM&k3^O6{nh)8X%j{R^>$i*4V>n*@n7(F-)C8uQBvU zAZo;Xh&tVU$fv7?!M#MpLT*CQe_{ewIUk}%nU)dyMf9i9@BhvgPnqI`{oCptFb+SL z%1{j;X`vJa&Wf{?;S|U)qsns@;(Cf`jEc(?(C6a}JYo{;<1;s;Y*stH*XU)1rLR?PzA-$6bV=MR zwjCETgGe+*FTQPYLy<5;?aiS)2jr<_^SfKFxz+YeuHTenelzNd3HTW)4eyqKSNubT zRQ#}z48=pk9tOgCi}w+3;H&K|+%P_jwGX3(F){ljHzZZIPHsdVrIc5I&o?du=r*=@ zsck+7gwkiEx2am{7BU1MI5$E%jEf0a4hZR&#WdiTghkqhV{98^z9_L*e*{M{hXPT5 zmq9Ia0#UW(fY65wh7rPa1%#fEl$K^>p%ce|pMnz78V;GoP;MowycfleM97?InbI~_ zgk1bud1SI9Tf+`>567Tw8YR)*rf6CJq=^g4;N-qIIqljTu&6Oav^GHTBP1yiR!ZDX z+`xylzt1s@jEU(dZb$-J3?uR=<--lu=NA`tnzSJ$`06wrMg>-gewy~E8*cZKqnmyTm1Z-?i0AieD z+elwa?A4D~P)xs=tL{>%G48LQhCa%OWDN9v%@wmct>J82VNqr9Esk zPjL*`jeY)7;=7G*U_$OdzC&C)5X=~J4Vt&a^T;ttam57WiPp@+f@U*Wzin{^mATrI z z91vC`XLZP|b1?zU!-X_OQ~DRQx)6aLJ7cs6)Gg!*d>F$qB+kSzHvxA;D843$dPR{z zi<_`cFyaTkAeV$Sxdw8_vOvj!(}av}5KnPziN0+!ThHf}%Zo_rC(^tfQ29PrB~ZXS zxwl#P<+m+g=@ve5d@~mIs;|enpd1!f{Qwsu;ksq?+(G*CN$GI{RqgM#W9S%;MI5Vq z#sVXv8XzUnQt_TUwakE+$FVW`eKqHKFzb-NgJVFQ{E9->{y`IBR6ekA)ZD`;*qusx z4sGezbGK45^e`&U(2(u` z641k_#qUQ06?<4Mm<$bxYJNo_e6q;<2EFo1U4i7OuqH1-URl-$9nhR`A4b9b7&?Zd z`5xzKL&c<5K^=ypwymxJ)F4I=;b@*~wrmw~GLEBpGoEBg#{FFXdlR<`*J4HxHO1dB z)xCF7P0`PE`{?vGoC;G#)ErRp!elPoN|m>+Of2I{*Mh$2=z_wGbWsneD$KxnL@yQl z?M8KKxTq>W=3>xuK$acb^sNV#Ejh?I7P?nNvDvgnrkG4gO@G@Gzg7yFZ*cteDD{tI zp5Y(Ah`#MG7;Tcd9tM4t*#&)QrlxY$360r{RKBugJa+)v!?7tcZD$`R2RNF)6hrb* z#s&PP9tyXhfS%@qR`f>m3T9E0DT_6|Ea)dujZx(d0|S-^^E#Jx4~e>lg`NLsxys^; z43I;@Dvg1h5msRx`o zQu;;k6w%f^^?}sgNO|JfA`M|f%&YiI9!}Ch47CAQ%|8U>Sl4no*!)4Rcx%A4IFj2K zU>+&#g50yLLy#Ai1xgNV0j{ntfsByc7S^P%Yw{5PdSOR_l0zk3bmn%y4uQYGvC7jE z*9j|lgygnJ`PHzPH@p_b?-z$4FDwg`9NbLtzE5vBqz^;;1yXS~F>N^@ls;^=9D+Qu zEKqWA-CM=K@LtCk(L(flPquiIJWbTmB~XKjjz`r-&t1MUn!4j$I*=H z1=(j=+0~Eu>PM*lM%0f`eW&Oeq51*K%C3IYS3gSits;1o>U%7U>W3{$Q(r*vHzkMP z-J)cQ3wg2SuH>vb_B2H5J7+l{bDoxp&w@Dp>J~BvUy3*;d-MsM%%quGE!@4NTC0i{ zSvjV|ptx;yR(=r6wLc*J&hiFHQ?&V(#2;v~X)aAoLJHGb#caKS(nVq# zBGs)Nkh`*$R`Mz!j+DC*4vAhDB1Ac+6P#er&gmV{99$`JnYdy?w#BZTM{EA_FS#jW zhBlC%kk;X1n$0&{^yf}Q^`kbLBJ;-I08VDo%s$vMh+{HRo3NBba7ba)f+@n{#;9N2 zjZu%q{B916zUv!;O*RI4gCgb#*oJ6a3v~fQOA-QI4HJAOYSc^0aYs$SRj3OIspdya z6frx?lAUpq+rs)gT3xu1kmwV$nq5r}2%WiS%N|%wQ}i49eZm?7O?QIytRRtVIGXLk zzor!q$5K%UhGR1{luoQCS=!@6VU}TAmUZ}{Fa_KaDajqp!VJh+%hHleDTIW4iH;bm zGlelodLF6`Z;14gPwl@U=J}Qt_Dw_g8OV(YXYwMDj{lnWe-&yJF(lXg>Sa zymZ9`gu#{482vnQ#Wb2f{^I`UK1}iD{OlGvf8vVqUbXb)tlT1JKC>M2BSzP)hUj~) z7}u*yr1c$+&Cxg8KUTMU4~e>gWv%~s*_Y;MIp8%*7xkSO^;`PR?{-|98j%iI_cW80 zMD^B$3iYiATByyug4bexY{gTWZk{(TnBN9#mD3Grl-d--G|((S^Eg)dX#jiD=LA`X z+ow2&%{CwP%M1ObJRcP@vwc*(=~_eVUf~%2&MOhenUVWI*t~^A#Ycr?;Kb2oo>%B? z>l~oww(<=8PV~+3pZ!+%*5N-{K0m^dd~Kfos>?GI^Z3ua=#{xz?3jaglK-?fH(*Cg^o?dpderVzRj`aVg)3s-AExzJ$>ZjR!18qWxiTG>3`mm0YP`dM4yiQ8~CZgf5`wKU%Z{Y-0tm0fo)6+E4>hs0FRI zsVD=4o=k|AmztJ`fegbS8Wt96qSzwKD0dxrcv%H_Gb>@{Z*L{q?ghIG2{W4Ex{Clj z%G$$zC|~T8ujjb67xYOTMt%k5QcD@TvKpcp*CxY~G6dmPqbntTj_HaCdA3P8oCw(> zn+>&u=zSPP&C`4+>e&4tW16n|N3Fsi_LGoDR4yiMkBV}HE}#lOTC@XfW2voV zn!2^27NN`hNJ}d@D#`$%Cu}2OTTT}h@afnMxRFiKEhy7LwK$wZ*YZD69vL=aZ$Sk- zV7djB&%#Gt(PO^idcCEh9&4kHYoo2b+-3T447kvF7|0dc;DWTlxi!6cw!@8rxTF5y z>0uz9FsLMksjnkH41|f_5yR9U#nvsP4?diTFY0e!>J~BpA6|910_xWIRG&}r7Ctuul&a@QZoZsk(tI`8j&8=jhWx?ZCf)eI1>uJIJP= zqkuabpAPD^}Yf zrHTRPmZCiO^t(Uph(?#~3{ODzSe918l+u|ULM>Shu0d76%%?-N?tUQjAr*Wr(hmcn zK`e!UW|0HZi)tCbF|-8k3KuYg`*ND-;_6G)JiJ=QF~GWqfh=SQ2isd^yF@-0BW^cPt<396GM8u8_Bi9uRerOII^~jlG6r*o8My{Xmtw*PyyRZ^8I( z90QgXLfW!Js3og)HK+=Blamh7y8D69htBY@Jq)BB24yhJhp26?BfAzKQYTt^;7iuY zc2~H7N!pv!L>E_Isu=JRyesz+{U*c!#t-3Wycz~MW?9;9mr|Z)hfqsagKJO~(8cHw zt-BuxeMkjgi}b@lXb?*w;JP9Qq=;%M;TT#1cZCa>!Q(kibaC~iiUD8yAn^K4h#8EZ z$I*DT0CLH)v=XM2x$F>XDOXCk!8ND~nE7;w*4+<;KBR)LMfzbNG>D}T&@6I5mQgKh zIEI$MUEu;|@Jdb-U0i*s+J;w0IGXg5?EkCf3N!`}gIu>PtvV_A5Q5_`q@IEvf|&SA zsuaDG;)TklyoRVq@>2ZJpN?Ya{X!_c^`9<#Wxn@mF4tQ+%4eN8mbseWl-2x!ta?U; zyi0vIUWI77M#dRG^QF;?#(=M=5_coTrT#92>F%?s3i!+`QQbA6LO-DT1X`#q{($P2 z-?s3SrhgIrX~+juyC98Hn_`$&o76FG9S*peMbvOjsL<>WK?}9vJF^9_X?jyMqJPKZ zDL|AN^p#m^S_C-YMlm5JfsD+9v{FX2>`VZXl9C;w_Ti7EMZKxw8>T`S+(Sez?CZ{J z7`^w&pqipK{T}PxxD}*o(}`ec3ncCp@B!~q?qg`XUAouw&lev9b&8`YjC(^-$NNmW zJ|?O$8c>&tyRk1s(>dbC_?co_3)v(L*)D}~~Hi4+#noyy0qz784jo(=Z zyAQ|E@2q1ur3S5l{Qwnk49$p(3!8OBm7pyQHSE~PZ35WiIGQjO13vgQgyEDL6s9pp zmjM;kc|}kW;DE2E5VG^nl(z#-(Ti_eW^nxGx zOF8CNkSiwO?hp-UMFeH(5%inQNijVJ!U+T?Vf=MJw;DsfW5|F~j+y_in1Gh>D5c!$ z+#kPxesNhu6SYlH{a|1Y2&M0YuS#_bS%wdsVIi~9#RRM?gv`sT9Po|Mb=rnwY#U>K zAhB0J978cT0#WafQOmACR4q9m^dW;`gfLwJp(iAzWe`~?;uvr-K*&%ygf_kbBy6in z)a#m1p_}jnXrVT2jCp#3e-7Lj?_)Tn25pQF0irGgno&2#1RVh!PzQwc$sRcVyB#>; zs@fD8rnWJrq+Ax~0=4|JWt+@m?^+zN{xe9KR6l~SmwOC^69`VAcsX*bF=Y8)TkQ+KD%Fos)5eSNbtwnr9i-ocYsmqLu;|!` zs9*HX0ipC>S>jYJbqi^Q5A19q-H@1f;{S7P|Ivn_&9ajTxR~eyh;fc>BmGo#f2HZB zm{oy%sX?fvUm&WM91!}D!7xHHgr1O;mQ%QOCGM#aA>>Sl?EOLc)*6G{3BtS!L~^~M z%rlRkUx7TbECPAtO%PY`mQUUvY_^@aTF( z^Q~gl);Y*p6kDe^K^|BZC^@)_Z;>KnLEH;u(zjI&wQuVSUrNR0jtQ$LDf0-iP1sZ~ z3V1*Yx#HSFk5~aKkY*-TpC?6)t}kWUms0W89Bo;G4Jli|k%L=LKBP{xyn@L#JE~z1 z1KG`P7$N(BR(b7~socx1g^;?_!W5p0`|5l+!_Z5Cs1wnLs0HIgK3y#gZZn!swXGzJ zjQ$f-_C33B(hg++2tScMairc5-mCq^&_;XAnHqFAjd6h0%XauWILI+^u!J$eF~oW>xU#)5vy1l<996a8)f{iEbA@E zR&j8q2jsA@UXUz;70YLs8Czop$ycdiWxMVF-Edu?Vp}C#>K}E!b|6jBFFGntS=M1Y z0f})T=DolU z^E(o4t3z13ET#cZru*m;jMkj+v+HPEL=5X!WsK!hv_Zo~uT-yHsvl^*iU!Su zH|!jcMMz%`*OCLW0_oO$b)%XCLg@$LzSJ#b9X_!5Ls|?mOIWW1eq^)3#K;mKuzh?5 z5aS%%M*2izufB3fF&$#Ax)-FD!*DG*AoL-FVT5D|Js~MALF#&7bBP0ngqkKORyFxD8yUMu?&_W0e3%VvF=somh(31l~Z$j>1 z(K2Gp!_RUk?El>-hwq%Ah26^ri0*t&AX^F{&ruMFM^K(Xv|*y!a#i=SIUtnY4{ZU{ zwQeCD@PYLfvRt{CfTlo53s%LZC}1DkP1|scZDY)bCHCs3lw#Hd@;q|>b9)%I3<^Zm zk^@2?G8je((-jbULQ-1Zz^%99o*EHC&ch)C$n_wO0k#sdhc~8zR!@SKMUOh^X%h8> zRK1G{aOV*c#s4wN_Y<)pq`iQn**fU2^wb1mq20fxhw~|yCMGshARa*|)J%aGcB(vJ zF4X{Gg$F#cVd0F!zyQN?K;|HQAzVui$Rea$_tmSN91u$14fmyPAuI5KwH&gL5;G^S zMXS4yRj65#eL=wXaT6fMIkt`Tp~POj4N5UBVy?Ouq?Y|~Ejb|cA%kIrWC%SWDJ{c@ zL@7KXgp7qlPB8R6jzM=kPcish^h{oWyt1rhSCaalyZxt>v+NLR$z*K}dIJ7F2fd+b z_XD91smP}yoRDsq9|l5$SO-;po60w;azNgqRNmtll>a*c1-xo}oyRyAR7ZMvKffps zLw?!6rBz!lP%kv}$xl@({s4-_lLJEO)}L?m@73o5^}~;WaDQ?@W*~iDv`lN+nR6gb z(Q>z%(q(}5MbAtde&;hIKmD1R1-WWj{56$*)T3_nsOto}%mg3YaRinMq4Yhgg*Fa~tp(P=oMma|zlOjg9L*Odqu+b7 z#Z%T@Lo}*MI)j9B9OK`6k-h-W{1GaWH>qKvqKOH4APVvG_!(bQ^vkX-PEW=uVe$bi z=Ssrl?-%)F#e}Ju`4&3gi?@@Zke1raJhxh6o?9+4 zPpg+!bc0?T8={e6r%@Qzqm<7lE*+BTuRB4qL76+be)84#@mWHTf}_V!{3Wk&Sq*j_ z%u`#BQp&B@y(@M%apC;$K_B=c`s3*LerJoPwk^CEcGd)p)Yb(mprrV1vO$QN$1&z{ zgTwuM$XjRkDVw(K!bWo;KBF$Bw}1+HK=-6+1-@)spLFvGS_LRzFF?qn9y2>?i<@2v zA2HavaqG8L+#Z+*S<3M4C2dGS7iiJGWodnl_S7bYXggEPO%GaeB=Ip!&7OLcbN~l3 zIg$(1f%|8?#TM}J<|!b&v~|vWtlZW@1MCqbI>%8V}NlvAY5zLpe5+u%)^0J zU{)sca)GFUpEoms&>s}#00a~CAlN4$vu$#&~uf#uOzrRnpn+D^(jfACm-hj z6fUs5!UB4qvP>=0_nW^N6Ns&sVvM|Wu3{XpnLD)cmfM>oz71EE2KFr&)efrjRQ z3YBBYZ z!Q2`Y1$8h-^b`2;p?6@)!7V2jRZoiONfFkYT~fC?F?%t107v7{Ajl!h0wo7G zER@op9YQUctgS&$l`A5a2ECza_XD91smM!wLAYUl7zhm-lw=k(!*W1|A+v~MQ2y@( z6fkG$a3TNWrexHU^DrR)%D$z*K}dIIJ- zy`gFM1ECM8$V+@dxM6-62n}K#RM~*DigG{};Nx<5$t*qyWD{C;!wq{F$aZ$a2ze#G zuz!IOMQ)AlWYBwKonrp954lS~{d$yu z%Ku2_GXBy0#g(=ye{qGDP-DvD-ikZcN}vFbsfRuUK-@G|eJ_uuxu6_+J`6g-DF@C- zD(uIu9JMa>O`TaXbB0dlBh5kUb_ z^YyIgdM022^)yDmuiEBf0&H_352U7wW&APFHQqbw_!r8NFg=fC@n0lsat7pqWgUS$ zwyg4S`+p|Y)zvP#Mo8|W0h#?Ib)AV|mYqm;1=Hd_2#)VcG;Gb`Y~ceg&lbf97EVR+ zK1BW5Wf!D(ixzITD{9FBS%dUV(V`lb1JVQOjHg+HTDBNIs!o_p-9A#6Fx^5)m=XmL zZbn_5rir;44a?PMSgy7z-H&DI>iWq3tw=I&^Dk@QK5&Mj6Q&!yTJu8Tx98>2?p*Qi zb>^P=V8;?z%Tg!PuIPZzdazX%tdyd!i-Oms7f)-69E6l{5j;gS+d`EKWX{REkuv1j zQlKpx;*r|^OI};Q7=ge=>^1G zl3p}!@yrTR&1L*LMRzcyM_N<*nrwtWv&~X8}1$C{X zmZ4)C$EK)lP*s%+v<3~EI0pP7$sG(mz|pjmfIx8c8&RY-f{z0+pNrKOJJ+-z&}+DU zC?QbWXATIZX9#o-$Ps)v4)-Mogg!LO6|!119|sbYf7i4i&=~@J9v z_;4BSOAg2tq|=wiXh7|qc`)xBJ*E$CH>#S5iln5~KUvXKH;n+g>C9ts+xwLwarff&OZaz)2HO?C_LPpq851<*7x(dP(qpV@Q( z(}$yZprHRHuUw!`M^oGd^bKA<6r)mv&bX*6zuV5~Llk2XfAEzwB~^JB&=q4L72h>+ zk`r};VM>tXS#z0Z9t*z(+4_aBTmek4%O3>8d~l8=-y3L%UTolBUp1Bq!&-)}SEBv} z2FbzIHGqF%?N)h^O&Nroik6b^WQn7BbQKTcAFN{4RyxmD2+YHmIY?Q+vC8upjEE>@ z=0PCVFtwg&n1uvK;N*pi2gL{`<*SGTIDaPgh#iHoZufUL{;uX)D-)WM=i`q`KaY3 zr1n0cD1Z9tKS%xoCOGp_caT%~@IKrZAEKs`5Vn}6=lRA+KPD7~|xtS(@4U$>AOM2s~P(*9gbKw?~o`6)n$`S}3z#-rPu z2^+x1ped^IXJaX(6=`95VwXtwO3Et!4OmyqsX!{;l_G>%o(M$Mk^@2?G8je(vmB5y zLQ+~8+A)me$-pmQ<6!f2%fHmBQOz+}`&c58( z2@d=Y>h6o^NAbR$r`8@`-E#`d&)dj2fCLLsmHQAi>ptXB3o}qYx=Vu_v5<0fF#!v= z4|$kee){P@mX;qJvATo2h7XtFzW5L|m4vXxG(|7xDdx36)LkmIvu;iKdBKRB&s*aIt;Rp z5+~V2cyxCP8xAC-hq;)53noH#BxKKM5s#W>_p8MkR-i#VRx&ID#NVW=i6P`jBBt)f z3CVCNPy^&Z44Zxp(%P!7PXv zas+5|v=Hzr_UDRX6pj&%hN$9BgE6lGawb|TF8HpN9FY6UIJSy#d7hcCTft3+?3zjtMiXB=aN4PDf6_?;>4$YLgPdfLJj|+SCwz zMUrlsQ6#$s_?71OH6q6d{*~xw(Qmf>_22I8`fF`nPyU7%O!wbEw)}UF{Q*g8@nWgg z*_}Yt4%O-zHm-%&hp1X|6iE*Z8^f_F`g!Hg4zb_n0`>Zu^!ICXf%+Ux0dK12fb>HP zw>%9|#Y-l}EeC|snV%{TA*kgk3|qjlIr@3PE5AfhQG5e~G$mEJ#H*yd%0)jROR#gz z+I!ff{wN|JY8g5BH-6}wB^$g zyn-C9B7(qHN`7LUWo-XtsD?apNE0*?W93m zpH0Yh+IQ92=gaB6MNZ`}A9C*BpPbLjufV@0H|zzewTOEJCS7bVnk9=wu(+*%KJ zkC5eX2(Rd(@a4pZs9oKMsIAP0)QOfAL~2zcR`Fpm3qA*A8`Af}wGgr|5cNyPlwK30 zqWfJ>n?Gn%m~@eOWJz)p1I&8y3gn?>fszAn-&YnqLc#qarDEAoN*9KX38dogj*wmq z9S}&x3;d4*;cEg_mTnrx^lghT(@e#wWr31|n+gVRTOd=u6g93in`L2M2&nwcBRW8k zRbBBZH6cr|GNq^TWvL5V5f>}oD<@uZyqH%pPlWVgD7#LwSq6_5 zR4Zv$&VZ<Q8htUwQB7)d`;=8ys%LZL9ZlG6&E%_E->`1Kq}9(ztxOE<--$!6h7da z6Um?h=@N)66aB)c`ofj#ss1kCT*maYTxCfnk<-Wr|9Tas?i-;Yu|u86IPZ* z&DCYYaQBNEbukv~lvT1sNFSVIhs(OCxpD#)wT}b2CD-&h+oDGEYg^PPg{eA`BFnO< zQ3^d_^;TWfT#!{=aZw{=8&;izjRx z$w;1z0p1+_>>}FY*+g0>PfB*^O2Zb<=F&rXGH-|OHEi*0DLs@Y%Xa8l!xqoh(nEQ& zZig;4Zt-k8J(MRqcId0dEuQVAhw^0K4n1w$;@M$(C{K>;(D#j7JUdMf<;fd6bh~Mb zXBX+AJh`+(kDIo5#!^VKg%NUa>#P_5GKk}2F~qZB8`0Ro(bV{_VlkLoU4w`~0Y_6G z-CI1F0Mmr$G}_|XoaMfcws^K=x#k1XJX^Ee6qh1h$I6lV6UYk^j5&wzDN_{AmjEnGO)P@T9 zJO#6U?~3{mAa26U7UwBgLpU1N7|5b!l|XW*Zbr?6wO~grgIuw!b&wmDwFB~%W$lAJ zu&g7H$CmX50v8v|bt@3it|4FuJkBf)==ssUv>_O>#ejhV1q=jOhGm-u7${J{K!E}Vgsnh<0tE^b z2v}El|9)S!zEYj~>hxiYSC;=b>C2Jygmy?}V+yN)5A_^!7Q-}x>`(&)sW#5+@H ze~vNW-3b4irpsfvVZfgVHC)`2Wf;)Yg?Pi7GPe-)6w|QNh0yJ;Af^nf0O4=Rj!2Lj zDJ>NsWY6%W0)*_$HMjIqzEptlcG!$Wta$?>@4S^f_d;m zRaYNGX>?`a8zT_9KbgBPeZLWIUh7;eenY6Vnw!}_j1iGf=5Ed7eV&Xn?lSUn$Q|A( zPJzt@mI*WCySNfr%-pCsyh}3-Gcpdygb;rb^$gfR@pl>b<9kCHE|VCYQ&+T(@bCC( zfFzC1NkTUI0`Z117D>ZS7ecr1+1Vv za8@PpI25?UKSfV`DCbZ>LoKKN0Pq|u2+Cl@{BCqg_W7B?VC6LZo-k|{I|vN^Pdr^7!3 z*#P>Uu&hwrL)XRPcY~Cfqy}X-0MD@R0U%yWGH?|P`v@%q_WDRjMoHz+3@u+15qzEihC5yqvL zQ^TS}_k5?8P$cU|I0xrDb>VidWZ=$s>UNTyx${6R8)EVbGt`nym=IE@mbIAyEc#9} z>PrB{9qDTBLVV%7C>}{y<1Iv5UUK(Es~-`TS&H|iYk3zUb-FE{;wu?78>)}qFwyF- z3XA*-i1&UeRKG;^yr6SG9}=pM&KK1)(vzY-X>kb2)^fS{6|cYkZ4vzmcG@@%+q&XW z!BetyO=`%Jbe=5UmS)J(gu&9#S?!UxCW(FS-o%^IXp27+iqMv%-yzFV$ddG^UKR$U^)Y}prtG5u z#&;Ys^YLv+6d~wfR)9=^iXnFQ&b6^6x6^4WS*E~dfJ|fPj6jm^Re+Fv!D~5$_}q6v zl19gsXdk4gt!w}BfY7vr5xjDRf+Df*=x~g8Ph=ETpu>N8F-|-?g2A46IV6s6JZX!^ zy?G&VFBW^^pR2_(d0nB9xre}XG^9WV%P`nS(AJirqagIQG|(fB_9%ozKl5e~SQfd$ z%MRkm@E#zO5~S!Zq7AD6@xCNiYv@b-G#7P031MCLh9%t(AxU2tsi!{3M-W+VN;VY6 zoh;tgWM!Iymd9Q(Bx!V}PT?JniZfEs)uBty$I*mp$B_m3cY_r6DuG}^rz zc*nD>P$b)hBFQobmJPH9k3+}`z|v@2Lr5|?Lr7A~0`za7y;N+)|EeRWyeAM%GHK%A zEb}UX)>I%2nNP@FK;0)9kfhO*s!cPL^(~Oy7cIZ0_(;0Q8&zB{i&vbivG-t7Pmp=> z3xbX-*`MHj!z$j#&?A9FwKV>d0SxLi!vc|q{aB1$+N|PT&QeJxY2qtFED!rFO4kyJ zIhQ4MM-xv7%jX_oCovPcv(4atzoJ%Afgt+Rna21<{wMf(sPKfd>15XXg)iL_SHT* zJA}}N>*y$1NgBd+>8c_{E_D~T6%40Mu8STG%9A6}IixO{H6!MI&kT6vyEvMyj!Ve0 zyp6G*CAwV5dO9qv3ZjiEt172!joXv8F(updPr;Ti8{Y+lh>3oo_-h7@txnbo5VAi2 zr_;ij@V1Q{SIx(MGlDw$v8o9=xe){{y>glP=;Y4q`}Cr)j>YV*Aha$u$Fhxi}J=W z-0ON$=?czb{Jo))w9>?rU~@-Cirk3YnPC&}9?2;AtjDMDa;QFf45Ru95Kaqm^pL9| z9|dwdR2+TSk1TZ3D^A+Vp=+YJ87gk#O=*~wR2;G_g)GS+ge+Bp5VCwZTV@b3AKfap zge+C!60)2fTUrMtoiJsGC*~a!lkxqg`1|6||J~?gRWVq}MRW{Ob^#Q_R8VtfA${{d zSv7PHR0>(LPKH{}A+jB`1-&QqCt|$MdI!e1(*X~a$G+=ROZ`nluGEmF5wbK=EUZFZ zw&X+3h?Y%QzJu0q>f+F+fLKZdF?+y#bbdHx6?z8**Abcdm(T8&4EID`h zPnV@tCbpGJWu@bEt;zfB_iIK|Y5_u-bx-*h{?q4sFSal*v!X zD?5ZkU!OI|F$~HuEQB;bB8?96Nxqg4@`bgG{AUB=UrS(FcZYt8lk)J%@(YM3zKh~p z>5A4&t&4X#+_{(HQ(;*ObuCfXYZ(=dp4Qcbm+rf{6i0;RcBtz%b$P#{U(wUL=uDSi z>!Q9FC(4PTLK>#4HjlQn&N|x5va=+4W}tyQCBJ_}$QmFA67rQW%ut0DWM_-{hRe3TC+U!^P_&lNro(3 z?iY$*lcj4>bfV$^*Kr}sxh+T3Jwr83?xs>4kRUEMA+AYR z^wy~+-Vovj#fGpfk$6SA8W=APPZ*k*H-6lGQi>l%*KHDei=#J1H8IU}H$^FK3UMzM zlkM}wP$5msZ`#tj0jj+$yD3UHZ$JYBU2-Ww2#-w*GE32WY#QR{I-2kr!ab|x&pHso zTZ}%k(e zRXLC}C?5JC9zh(x*cn#x08pHGmc$F9Yxy0BuL^NAU*p7L@pU1NPCHpfFqDu>#oxt$ zz%vFa*(NoFw@e(Qg3q+JZkDCcmSp5c!^jOqzx2&8XpkXtW6(2=_R~M!p$-4^T|lJa z$(`nCZg&HRO)9y?y1~SnFw;!adng$uF8X?~Arna}_ zHxyViXyu}hUdq89Al}yH(AMOBO&eG3wpM^_fPKrZr2^z0*nLEj+hqj^*`L{cIkS-a z@PR9|?9M;4o0tvR5u>+A33&iD+kjju=6@VSpEP;{e2jM(=ay}hkMQ1w;$H|JLX2iu z%>Bz0gjx>mS}H*3Lxy35WQ3lOE-n0E?2bJmgf#6Cp49xcLn9UUQCwz>$>m0!kp1rl zJ~7~q%x;6?bLm=Q++Ipo;~1j9c@ZryTGyJe%u@8a*ShG8 z`w*JqT~Tkgn9xhb+R#J3AkU@ZH}UN^W{+bU{~XhJ^zwvERL^2va^Q|Z%04$IhV*{f zC!koEdHsBd9u-+|0qen;Ve%Y6)X_JF!|__R ztcXPr(uSP|gtN8_D=rjC_Zi#`fh6apKM)$k#BmD&CQ74&TmiBTvR$->wA|?nge!Yr z47>FV;(_lvg!saDL6SxX=`+MK7D5`bL|eS#=oZ3-R*T|hsJNML{+DCnbkYsCLXTko zYqW+%OZ356gU}%6rD4%#Ku-Q*01kJWVZ3r$C^8w`Id~24Zp)}>ipGg&NjxenRDllv zWMaK6W8l9gilaBIsF;u$fk+V6eHSEYxY{*K1;q$(+u8%99$P)j za_Dh#!szL=_c&xpW^Kswwb|0T+R}k3y8>e>&mpdUmXeFN0%TrkDZ8MiWg6oig|9k-aoo3h@MsY*BmhM4(?7JXI z!`X`y%WlLaU-F4dy(}!WlXmlafUJ8hj2lngB{#U}F%^53<&Y&>o5?Z(8y0)Ag)H6{ z$%G7#$l`73#UpP^6&4;YSW{bdSckW)HZ#7O$K7erG$o%(##ySw_bl16ihT346y38J zgbI*5N=wYAg$Q5<5d`-pU z0*S^|Lq-MCpy*keT-CJ6UEtB9dGV-8PPW>-X}rPgcVF5j%b2jN5Y1Mz(3S=UIF@6G zgLalVK<0&oeCY5uP}xxdLiRPUg&sfgT{Qc$n4h#|1L!TZ-xTY`pN~G|%WWZ#u6T?n zoL@35W`>yVg}?$ zov5$CSy!DXay7cs7}Io7Mn$KB#6;h)L#TL6AkpeXErg5+q(O09x|&lEX_Ko?^oR?h z*L)WwX_!2kWzi1d&@RP74?%0`4}=CW3?(T__cI`i^8=r_IfYkF z3q`JXm!gyQYN3g*3bA}+%6rt@z`M_6R5R2?w=l-<4O-Wzu-v4`a^gG#pgl{p3{Y_h`B`fz zyTXWvtRGQM{Ou|l$K%OMq(bY$SLb8d&Dt1GwK}1#aR*9mOv%p+#clcWEUXmOJUYbe z9HVs)IYW|$`x1ljlYv;4&^WHDmfSvas@}PE>AtG^|RRcupX*6g_d1#0P$qFhYnC)66c57lkFdl(l(eX@7x( zFUV6mxg|{F4?n{cpFT1Xv}SihL(0|{)sWs#Lo!-DKsdvfilM3KH#llAt&$#s%FaEs zZ4y4}3f2faY_UP-=1fBIv0VE}_V&6GfT{B&LuUlro|@3m-MqoS+Fdo3iM0O6Jp z=X^R(mPw$i-D@Gs3RpJ8mYh%L$-+I^v&7FdNRbfIgbC8f?h=K3Jz7dnF<;dG#8m=Q zU>no+5^e6imKaaoy_Psj&Yg*~%)%2~-ly~Q=n%7WjJD)*{wD{qEFtb?K8n$ME%g6L zh0M4fP5|?o;s-mdZw|Fw83OViT0CSPJ<{kZ`Za5@q(FcD=L8wE<|C%9>r?ZRqacz% zgG%nTFsZZdwP=vxUdzc}eR>eQ3%}f*3yNGGEq+)SE3POZ$!tUy!HtcANH{;P#I&@qeutqS&{`%l2LoDZh9Px*1#C{bmKPvy`7TJ(Fig?`;R@Od#dj1L zFSkR4#L-#S#A8C-xDIi`caeC}cR`XSX7M$F%!b6XA#wEbPc%XJ=~#Rf7I%fBg5UMB za4uRUN*hyFwm1t+ju~{6?GG_b$^IXQBr{rDR`MeqaV^n;8i$;wVSbG-Ey99zw1yzk zvNbzo1w&640wu+$7~(PgeQ!vd-43%xAepCR5AT~)p*JPq_6VLAU^ZQ;)G z{C=vx8sLgTp#0+t?AU;?h4%b=wFrdX==rTSekavXkop6mL8tS*+IRoO00Po!M)1mI z8%5@rJDDBh-4hwbqKpoofN|p45e)Xk%OP>}i-d7vv3T5@7ZUeku_ykyS}c>-6$+Vq z2wYn6nX1CVU1mfkSLVART~#u46lm`e`S3=V)FC9g3o{5jsq&;*awn_?$fQIhdIZ#3 zDnPt1$<-RVAHBP+4f9%(kO{c$AxZZ`NYWQZ>ZuR%5k!`olHG&uk;U7ZtV~nT^4Kee zB#mBsQ+S6dU2+*g!w7i-sKFOPGPF#CeMhu>{|KUYFZvB`+Ik~kSs@|WE)+?YIk0S? zHFz9CRsfbpPelkxCT9pqYFU8(4YZevt@z(9Wf*$`(Ik^54$d;K5@<~Y!jSod+y%7c zBS=P0n`S8MTVTI0T7FIOk#vz49pM&KFN;^4tg-iCQcsY1@e6`pEM$Lz_YJFfA487> z64i3_Uk+eUrx_8*XU-JSh{RcDNyz$Cl6-NNn`B|FEJ?07%Xeg15htT{N3$#nWRBv7 zbVZLmWSPNGE~nNFIm)EDSp0T)3*(qstv<@nL>+4(I{b>DI#NCsNJGX#V3rZGgMMlm zD1N*Bx6#M%z66SuffimUl1aU*oH9Vj{v6Ow98U1+^(Vb}A&rjd0p9tPONK+Rp-wP5 z&w{r=eMD=URifODmiE8XL{Z1Ie5~7e{7pyg6SQvD7Jt#{+Cb~JqrqQxx-O%2m+74j z|G$oGsB5+v5Z@&66(LS8?~wTBNkY)WzH4i+W63?V?qsbn^44e_qY7!=}4lMd5M z$3<5b#g!&qnGn01-r|m=?ViS8S#Ed;MNho)(qAw3+NlC>D%~a6bsipd^+;8z}y^=g%rKLK$Zod*U(-ne)YEx z@8ZRFcV}vfHIv&@G>_qMPy?jxLdx0=)czcTE9Ol>*{uvA=$dC{4OPP^6A^uY3B~= zI#h<+P4n=1RRZPCDy06<-I+>W&EyUyn#XWfxd)Yx(OL>{9T-!E(~3?Hw4=gc(o_lb zpo%69G8AA=D09Lst|us%uj~a_v$WSWc?NOkrQONG%d1{f1<>^8M!EvrQzQ?NUZ(Ir z!C-<61-J%?sQ}X?pT13!T0q~p3kt)1ss{3a1{&(j93U%_LawCT!Hcc#&eQ_ZOs+y` z9z)Tn0b*LD>&ivLO{oWfJV9$X-Drr(H1a<9qw(( zQma|o)@mM;3q0Bl%Ms5|YI_1*siG+h#KBoU)dDh<+J5Pw^P3WGcj8P{pjtr2Qab{} zXrQ6gjsh|vKDkmmjTiIXohe5(ldG$m$53i(fS4BPjB?RXYF7c-L~AIu8e%eyAI={^ zPuW+?c-+(&(=~V{&=Xii>)ekt{VKT#o(3R8Nvs5VRz;Hr8D{oS=_&gzA16s;Op|mB zMGM_GXZh3sF9l48zSCnudD2!HtJZ7fp{rV&$xz7NfaN3F_EH-}(5_1G4A-Wb$yF`Q zV<==bKup!*vU1T-$i@MgMth;S9R@skVA3pYYc-F_g)P{zgVwYzdIH_AqA3eRU-}O+ z9GGe`&Y|BWzBlxF6rb_g!Q(&u=hC_DmQCtRq#>r|aENHJxEqQMhw^&G zV48-QOgn~YUQhBWkVAQI+hCf8m`r;Q)4ZOfX?(zL{g<72G}WD+KzFNX$^y}s{(}tl zpcdl{dgweK88jV_Y5^IKJe$Y^8fZA*Yyt9EQpj+W(I7)9*;RTfKuqg(FVK^`(eoS- zAGPIF0oD+cX?&#igM`{}wbB#lV--zVAo|jOkYT;nVw^z_onOQm!c-S(0U7JU01Tsn zhPp5a$TjiFP!}}Fu*gT0o(d4t;u{V0BE5M(jM?*|{1_C|F zlQ6#vG6|^ZB-|5dqKc+05C>=ZR13(k6ZK0Eo#)qLY*)=wn4BAE^H6!Z-a`k!rDLdB zgnX17+Dv~nqZZIN#ir$}87naC4O)Xws~Ea1J{h)g4KftfO{J#-#8iZ~0zJt({1}iU zwC(LOCp67v{WF3AB2$QvyIQZ7up#Sz7MZaWjr2<7lE}5SWF`ac5 zQ>@@Oq19LzHO@sVdg`D424O9bWf1tX0ukg?t zoE<`2atYEO2%mX)hXru`4?31P!zgaS*bBw2M-Yd9#Zk9bAg=nZb%-y0*W@2}08?lk z*F3~s-}UTII-?HJx>0W-zVltXS30Bi(7I8b4*$R2=IGru@otu)_imZqoruHBp?Ayl z?tyr>9D27*?^eXS<(H8ie=`EcsED!@jvK5+$XUo5QqLyx(?vzU2)|$?e+^JxtTGzbE5t)tQHe; zvG`XS5*#xpK;J;ydQ^_G=lSi*0^VPgalc)mypBG1%xcnine626KvBz@ur##QdTLHE zbmMYofA5??F5Ww)T(!Z0?6X<#sOvCzCyfD%%?FVJZa|b-Or)OZtxjmgKqc1@j=_j({4c}yZguw(EDsBxB(=T4o zBtPG`b>0}BJ3oMfFC{AO10M2>O8yx>_0df3Vn*{Au5aiKq3%i`wP|RG>E!+z{_+ym znf4J~UUl+nj6)eHgM%7kvi1rl!s|(XY&8MM0$M{LHN<3EBVUh(nDopAdXlrl^0^79 zsjT+|+Nh!_3&g=$KGgy;l)irHq4QV&s8btE`(rI2AmX@>o*H)!e6e z@uIskRSz|jD@vNjP^W5unAY_(<)Yzk(Fq^}nEngJU#DWCAtuv44P!{6Wt zxmushgj}uO)apB{T&sxF+9&Z!c|+9ZC#WzomMD{}jv1?yYaPDPN5h7(4TyKek{S=^sXHUot02Y_}e>?YO_XWLeHKhKrQv(KZdSwJrq@hNZnD9q3K`SG{u zd`zYpFn!~0`?`-(H5a;5KAtYyFWa`c4>7fM@ke|7%W$@P36?i#+oyu} zcrhqbVz|iGOm4Yo9>WT%0b)AXd{8bLmfclEV;rsfg9Bl}zfVn@W@%fic}yZHA zPD*`GpasbX!{;f~lm%))Ll%gGvjR~I$Z*2ym!7+b+!or-QHmdMY-AmdRawN7Kpy|A7se-T8uO3q4O)qZ`19TT0q9z zEyu_M8fbVB`VAnL#V5n=t3igXwg5l%RDhV)>p-9HLHJ`TXR~U<~}_} zTEvGn`I_IEux(IH6-QShFRSnws^%J4cF?xhENurgkIAd&p*?H)_Gp&2YRzM^ z=S5)8{GGs_WbJ1~;dLfbxNpWp?*d1pF$pE6VGsPS3#DbS10d7lDRicU|U z*D%wNWBt2rd z$+VF`Px8Dn4af>w!{J0jOr|a5>(LOCp2a{<@-V@K*#*?LFnUAnRMM4)+JcTe6i4Sp zqc_xjSZb)2r>9ju&Qi!yC4M2xxh<`U zV@Awj7Trn<=P0=>&RII)(<|USE@wY3%=|@J0S!pf=xO~-$&|4WG-MI|n`ldp6fAtT zK%yVN#I+>%_|UK;3u&q4OWZde9n@m~#yu`PjTfu0X-apIgq zTbw25&_))X2fUNfeM3W7Crci3B!ui9lGH+o;q0Wf>|*-zwnegx0G*+j=M?W=pAK!b znFe^za}G*zmYicnoaNk>R!T8BxOG*_&U2Q|^5ibUtUHg(*^dh|f3ag~QF5H(v@T$% zhs>i#8l4Fox``16EwwDNyAKxL%0HxkP(cyRLuT3$QReq`HNQP z%^wH(nkN0CXtw(?Od4$$`4||tLMW2T5RiIV45uxIm5MVUV~7PKcA=Q1_y%v4e8NM; zWMQzn;^tYR2itmCW?=RWw3mv%A9?r~FKA7>6MfR?Y|u5CSt{7l3|X3D1ca0=-xNO%-uiLyK88O) zi*CMrj_zL+jrMT9rui6-QPQN8yBpg)HIS*~Ubmjwu5gAdRl*svn8V4k;7ZgBxPOGU zJ}0L5O~mLoH-q6~ks_rXc7E+eJU;+u+M%Kn~CveA!nJQyC@bh3J`w zB#rjw3EuIL=qK!q86EeKWXwWH^j0agJPQoFDNaDpzVrZLVw%ECJz1bb7)_8N2VMf= z>p(J}2XUAjwjU}9F`Ppe*9ShCgKK!@mHq*4%(7a2je`4p`Xe36=6wcGKa1Sggxj8)0Qr8VuUHTxI73l zBoZNvP1y|~tjjH!sFAA~1DT;+hESuPcSH}X(h)9!>CY4qf4CYQ*X z$B^5ajdG#bHmK+;xLAC?}2ts3Hf zU1B}@i*gL32K|im9Q^A6NtKpx6|dZhh2oxc$%p%#-jWNmIC0LSD{+>bM_0%)3{U8p z!F)odB?!^0dTJrNheUT^4Y?*-q8q7(>i#8l4Fox``1bHyWs=7D)6uJgy~Kkwe3hkX5+7Zg+nRLw5y|4DwDsgx5YVL`!n^ zGa&pezWpm5`m6u2)0WJB91^|Ah(n^s|2QQ2=!=FN!lw(x9L3ktHUB>FIQdsm#}S-O zdyqm%GDsmL8Ke-B3{nW0LxM@e3crx+LDVV z5|ibI5H}%7L-TupOoGg7i5}UhWh#I~kL+I>lJteU$Q=Fv%|P+1*TqBrB{j}gr&q!b zK}UZB{rAwi-*p&|UQIJHl|a<6m!qjC&~6n?S)d(g$O3V2Rv>BtmFymz+J5QbbsYCZ zXBtI+FDQCCptVHLh|~dEQ?673J+7ijgGwG$<%B*_dM+0Ke)9OIF%{HQfS6*fP3s@X5;&&K=*3Q@ zFr3E-nG?tl{JWF7#f`9{wRq4G@#H1A%GL#|UWJ7$B2q z-4P}Xc=Gh5S=!cW9+L~4_$KTz)wP~Li&ZpbfjBtJr&>UUy4x>3bpEX*+7GPj*YIZ^ z4W;XJSX`0~KGfEsevEAL73YBJZdz|JmYtvjZN0Z$&&HA~xC&0}(b6MrJJ zWcW0#C(v;fO<5og&hn`ikfHAOOAno28Q^*52iElkdwoA07PqGjKGfE@bp4}yf;5XcWK-*@a~oGd>-#V;_ohFekx80sO( z*{K0yI;PVkp9Re@3!16T>J=P(i?&^GKj6h>B$%lRYbLkHX&%G2R|CXk?MLOJVcQ!) zG_K3CyB!8Rc}&+VZEH1;$pudQg3OZPnBEg;zKW(S5C>=ZR13&(Oz)Q-I{#V{?FZKN zd-nQ%IxKEa8+@p(X?Lb7O%vXDubP_2a7@k&_obzn@@RVz9@&^;9flO}>50Bky@?^Mx54V)#Dc^YImrtc}^ zEZLwjCfn%9l|k0z-X@UH}^8M0Y#>w*YQ+$ZIHQY^qilH8ooShmVreiuy@>$Rf zvmkj)KZ1j=(Y6cjJG>Y`f|;tYW^#L+<}qx0H9$<(zE>_9w!L9Q)c=pK1Xaj_LimPQp`p+d@>C!{@K;_o@!Kzkvm;r4eu^i2 z+)`Ee8ismE@_=0f#B{)>Nj?jjVHPA0*wb)u9&Ni+Ht}M;yE7Fk&E$3`&12ZGYJixk z{fctYuwmT;WEZWw4;}_QdBD~zZEH1;$pudQbD1T>0lO#AVHHhTAP&y*sTPo-?)FO$ zop1bpXU(}{&bt154APz&QyIkLh^X8nwrOOz&-}cJ4r=%!2XCALkO5@ z`Di9roHUQ2Uey3GSzEw0x@f3Zqkv3E8r=#5o;+Y{mbSH;$K=8t*zo}E#p0hP&xmzk zOvf;-==4B$RTxZ~HmiW{)d4b`l{ulsAFy5}4@rcK3*-luwkP%yN0y(T;(bi5;hevR zp&pW)of;sfBP>nwSOl?t`$<=?&W7raEfSBs(iE`1f zB@AG>4a>5-9R@skgw-r@n5Co@TP z)c`Rq_I2f=pI|iwkUcx?k`c=9+LoR+A#4Xc3{&F;=r zs5Fz?oivYO!>R#ds`hirMZ<=*4#+*UZo>)#p4_lBOWRt_V{(BL|3vIb{wQb_^o`qdz8!q1twMLou4hOedgw}%W-?T( z=U_QT+g>Mc@Zw{4XUZPUAf~1MR=H@XRzt{|QMB$}Ul{P@kw~+&t<^jx z7dY{AKAY2jb)+Xyql%_1&@?n;fjBrT5Ve2|hnIfoSw-YF(YnuDQ!7?OOj)-U=t=(G zJxzKbrX}}u4KbOv1%9t5X&Q&}`qmIN4KbOv3)8%wq-h+=lZ-nYr6yEEOr|}BXq(l%p?Acz zWYjdoWZEM5y`H3L9C}YoOGZsYOs1`a-|I=5#-V#+S~6-HVlr(T{9aGeG!A_xrX{1M zAtuuvf#2&%n#Q3o#k6G9G{j`u0rdvEKOM;`qF=p;UHd%aRxnfeih+1+`p~?;wE)4`FzkIO!B5B4@Xx3nULgh zcQaGxPz^F%_g_hGf5spMbIF_^4?c^DnLxj?n$60SrJ|V z;-i+V2pVEC?E~}-3}x)xJ%I+RXvzZ7m;QqcE43Em40`DN9faFZ5o&;#D#8#<@}?y# z!c{<~BzX)KL4yp-`?}Io0b*Kq6M>#&MOXmDM=eEJriw5O zle}rkiZBYuj3ketB506dc~2@m6(FW%Hx=kfR)i)XK5EH|pdlvHHlb%5ts!xGfb8UJ z$$-#@enT3mTU@mmmefMG$NpF@07sH{-)aFFA3}P7*{6Yq@4r0)OO7I4d%a~TfQwJJiGOYlAh8_(u=@|(0BtQPR4#*T*)3K!|&~z0|Ss?n- ze~{rgQHyZ~J#>B_;Wq3(H9$)lE-jt(I7+RSyOr{Kujz3PM{}Q ztnLHiqn13jXo$(Qr_ghV)>ILC0zI#yDGNkj`VTU!)LM))=%Mr1|DF;s*aAf}3N zgbeVeB`d-)AO*ZJ<+cVHmiK$5rvk)e+J`_-vLalC>pp79il8AT({`ZektEJi>{#CT z?*=}33pZa1m!1^IF~B_(KLL^F?~>=_NjwI~HDMtb9YyhP@vlFSUFGprZy3cr=~{XM z@ulyABn{1v6VH;^2O+*(qUPNs3qxA=C19`&!%9L+CXD72GA$m*lN4IW?jg~9qZUFk zB0|Wn7$&px)OSIWM$gU&-pNpW9T4x{Es6_x>tgZSVaki>bA@LM;;!#vLebX-yn6Vh*$DR$4em$z^fQ(g~kl0q1c!`*C6BFUkst z?)2ORK2tIQmPTg+**EQ4YJtR`e?@r>wIuiW3XoN}y^gl*G6IHuW)lKf8Xe>vyt9k8 z>VdgK&3W#poEJ+I(>LK&! zkw&jG4&B6vl2Z${)B=ef+TvQ06*)943CTFL(Xfm|TMv*5C$J32;`RXMyVLN*(et4# zPMmXSi?ie$+Q^b|XwwkZgOWoVAq=61L=SBmVmLc#$S$TY?_LI3Mu5&x%yWu&uTO_I z+Drqy=Q)SAI7`m4BF=JdODm6dXL)j~X4aj@31r{2YpDeiJ+#FQi=M!GfMguns3qgj)&r!%2`mFL_1_Oj614=LIC?&`#fftc zZE=>ILmOE#4s9C3I$3gPBZMLJkm#XJLkwpp4cW!?riCH`@kOsvm>5>%L@m-LlIb+0P7X)qI74*|tcRfRK18=!A z$u`7{rNL~O5|##8eDoT4QyOhv6Yty+7WUK$A^Tm?61@^(B36Jr0Q;U@O9o^gwT{1>6}5>O?r9) zO;^#B1>)c=pK1Y>d~nQM?Ux=pzk+aIEdImj54O;@5R+bebzn-qh+U^?8ET#(Y6b{* zH3s@Z5j|tknf^d%koP6J&(SbK{LW8P5fA@G4-MInh$XeGVrWm0=$FH3*jk_^=}QF& zeb|OJcYJ~*4No~VEQI`}jD?^fTjP$$&fpJAJX7yokvN*}hU^aE2CTI8zIx z0aK;XbJ-s)FQNZ6T0_LnEaa8lmxG;w_Ta04OnUc+E_CE8XiFlZS=M`E83DRCTSAs* z=us1@q+#;Wqfxwb4eh03=-Y>UF@w(5&mmCuuK!xAEBn<1t6gyH8+gp!K{Y9XX6NHA3zoelGNrzc2si=<%-N=rNE#3l&ZG=ee$Pyy0Z zrj?vt=uIt<=!PHHl7w&)x8RduUG)Ij%-50u;m{0UYJqT3!#RKD!g=YB7P@^5J4$b` z&@>GyJBksr4F!*6HfP0k2zp`eqo1~2EUrgS?^IIJZyctVy69#v5+ z0fUf^TR*g1EdFt{rk2cw)tRoqTOrIFi)9=;2lA4S@aW78hGsyRGA{uAWwAN(?Z~%- z4_~8$c`a|CUm88vn(>=9W59=Qp@GmJHad05*_KQZI@A-WOH&r;2pY0L9Gn%1 zo|;6F<&{u;BX z15iAvXNJ{|@2@--SWaF#1~8H6f1f z$Qt6E{Ep(Nurx&@gtX#0D}>tI3Z}R%ilZs2&Hsse%(7B)VX8f5u)5;bcb0KX)P_u0 zv~bh>>lo^7T|tjDI=LnTNK#8JkYv_}TFj7b_*Am_Gh)>8H9&Y_;%7e@u`>_Jm>2re z6C`>An+X$YNkTXuTv!*1=<~qT!l8?j$w|lphI&YH_A5Zhz9NQELWjQ)r!N{(_6RXC zB;61-j7U_?D&FysWXSFWkffG%Kr)g{L&~1@p#Q{pXOfn2=nXm1EK&65o?8^3`BASR z?p^HoR&p1Z=G{jWo}m3jaqGvy+dmHS^)dP{wfgzuy&BBdH0hh7&B2$nu+2dm-@(>) zC-|h%TiXM?^9Zfm|7i=A7>)!X%Pq3d19v||jDV1~sXg!oCAZ=B0Y#7$c4iJPIt$qE=+{8J-t-xX&t_GEdu55ROdO7EXD z!*oDSnZEsT;ow7UKf1LC=uWM*eGKsVy{r|ub+5?{rQjKekI=SnU6Z;gu`l_@m2&q1R+RCa(es`6yohX5=AXTo#_>S|bltUn>4h{8L)GND%e8 zC#ues7ez+c-(uQ)1Px&)$luUOoV|78S{Jl?_N{huBnG|aS0s3!|VKL~R7I>r!{YqF}7(H+82LJemjvQOHzR49%b zQu;X~(`ybUv6z>9wnxZ1Aos+Z@58O-d*&cpourzjZLQ`pxxh0(*TINN*=prIK=#G! zWc{a>36KF@So|6lKdio7XUKrA_UGXIe`Kac{a0DF$`!%$t)X^Zr z>3BrxsQ@vVHX7(j9(-m1Sw&m&^QtTb8e%eSF<*~{nDjIQJ;{a51)Z@7dVp+8pp&bU zS~4IU>U~LWQxza&&sd!`KrGwTDXTg9p9i=-wA<@=X(5`%j_hxdjdl_J0)8!ePQvQ6D`r(5^)Ggz~Mg@BV-EiaHlk-O)Vh9bZR{% zSM}PT4fth%Fu;ofY21al;kzJ7qn9jGz(b-}FSIp;L_d0oLz0Do2JOOhxANXY9Fc7& zS!+Xc%o^PYRu+~pWU0kBLDP6Zdb9F9^5Ok0xfSwbU zq%BmuE|6q;ekn+@deX3Y@nxk6(Yu$NP_oPbYFbJJQO_9zHQ0F67~VPY6c-2xzl8ZO|;z6q$|Qk3@t9}8rO;%n); z&HI7=wq3G@?g4!uEXg87#fJh}IfCeINiJNnct|q+z7!-`%4paVgrW4I2yS=;F#u-_ z^bEfE#7GvQ5RxoH`_STZDVYU?c*Bwvr3VNNGtCb5WP#`hL9XVU1j{KI$mf6%T2fPn z{+EGIjwYjc%%Phqa*i>>2K^7{W088s*ok_?uU41toZ+G?WK)w!j zr5_2w_p88AuX~VY3|%zAbs*n~Z$H%+vOXPL>Z4(*#^!RQ#d z)e*8ZW$qxvrjYSDTP)v)9z}0@$7bA>qg6P+hPLE57H5e+BZ6Ac06Vpn+`pg}y0<8X zB_~WnOsjyb-n8f@Ow$PQF^k^nBxE57Ky*i~0Ybw}0ibDFAP(M?*-0i}2>EM(rO_*J z5AW=YmgqT=QG14=tf-}zDKU^?H~m`m93g(DxE)|HL58>yatx@U5*%Wvha`9UR{GzD0pi_HmJVvkfbe!AeKE~H`QJzY8Ur{Y4a!j|8OFCjdq{MZ zH~!ZF4DK{TUhyaW?gb}HL#_y9mg1;%H7W9>>K<#c5?8S0bRkz^`M7s)0^)-2f+UTO zTgVdK?HTINK&beJDDD%>2o(AWZHlW9w8tT&kqYEhoQ$ERw=%cuBA5+-}^2|(s0T(@pXa7bA_I`84^c}1Bq##Vahb*Gq&uBdA-=; zS*nEUGmBfo3PDFVghUq!k(y>(AK1u5W=3Q7W%M( z5hYjd^d*EOlRtzc-47uZv_!9{>B|b-zGHVkgd`1Pj_rw-M0p1XMC4cfAu0jjq#^pQZ~b*^{Fv0cj!hI+_6 zdZf|rhmh#~B2Ly*kTFp&6x_t3S}H(_;A13tB6L!2mn7rPkNmC)q`{BnCVZFJ4M7K~ zfuU<2LUBX7;+Hqb0S>(f$S;cDZD0C!C|*M%xPcZfiFyPrFU7z{%FXaI+oi^(4rmT- z$%AuD56#m0{Vq*Y_M2WY9;aH z+Ke>lVjx~(3XHk(M5UO!a7>>HLXcs-RRXb15m@o zC5KXrE$S;!a7Pp^rOtOfKM?nR34Zgg)$x zFAa(Zzv$?5k652Tyz@)xO4;%pgl~m-Ls>cpp|j)%ba-P-N5MgK3|yCvKn5}WHxp~m4Z7YVH|V!1 zSOjtYTelIl>#aWRyXAJH=58CL$=jWpJud_ON9>Z$JZrdAfY7QFXX$TdLn6!nI>Q2b5GysI#aiVQPV0Ydi4tRN6|U80@* zOov1B6lqk+&;PP`QNgs>mJGFql>I>zsv-S?s7YQo&0uI9`L4MPfw=+o85Ykei(6$* zuTM+qBTt5E2I&|kxEeV4kUKC7WV?(XJ%KJ1t0_GzFp7E% z{;UO%?}^^QTdhCjO8Ei$+_M6Q5IHlhOUJY9Prz~k(Ev|VWm+^#^)%5;)zU<>d_DGr znUE}a8e&?m_mN)AxJsb1M_Ta75czkZ&!mT-16dBqAcT-k6Nb<%A?}t{4~TF-<8@k$viBOWUMMcK4M0w#T4EGCJ|)V&I!3J-bDY{9v3r* zdM!x^Bi|Dw8D_Hk`AuG3T!Gt!n8HjD^|e9Fqy`vGOk|*XLs7V@EH)hAHN<2ZO}duj z4+l>GWJthq3}yV>y#|JGURa`Em1ItaERB#Qxf#-IZ%Y!wq10CLvj()4Zms4-b^(J4 zGDNl(Nb)9fs3i$m%=d+EbAvLaa4jIqWoq9Pts!y@gP~q%h$(V+lpfQ`qbJZNG-hea z0x@R&2N~|b)nc4M51rqUa2rl-J%P5XXvzX{aF$QCfD8femmWI5hj80&O817^t)wdt z#nE|w)q^rjZ{HNr|EIE?+y{)QOO>8L`&Be$fgV9a7Knqh0?`xb3CuL4L%;M~!3Vh` z{sZ0gBXvE2MyqJb0@0WLgA5Z}i*W`$bpE=8+ps_P1RAfRDGS8GSw7VQG6cL|dg%N# z!fo51dqYiC(v^qe=sdsbK^dmEZ;I&uyeucf{@fF&QAJZ0h=a3y>IpOlpA0kGFFgw| zX-!OvKJcfHV>9S*-ZUZd9;WN!S7A^5C`i)q+n&+^VH~Y{P@Uon>1vYrjdaaY{2*O4 z2p#^1wxk2Xb%D%NoRY3D9}3#!?u1Z$>dgy75xqGDP;mtU*)A6A1!V@g_3dp<-5SR* z58;cDW#96qzG0=W%aJL(Rq_=E&Eg@q`4(H9Ojq&7HMAvbjuayhe1w;E7)tJcY8FPd z%VSTx6cQ(=?%cdih+V!^h#se73iITiu%$SMF86rGFl81HH+vNMxQRn<1FA{rJOiyu za*Ce#CW+trQ8a_Cj_;`ve}G2*0YRHg zc$c$K;;|+k6XIEl!}3EQP5z$DyzjzzX*jJU9>qH}(_jmSPKYf_6zOE^m;X-ic7~T^ zCQY?i)x$Cl^XJ9O6>f=((zQ%+Rk~KzAU^V4ClGxoR?s7jo)@a`EfgWkZ4&a37RSlfTDL|nNGZh&F-%`QS^RAw@2n%sD5=FgkBe;8I4ZJ(&Sd{S(*Zepku6AE)`oN z4>eD_GndJ2VVbApXHR3X`FibX)dwA*R$qRc8{5F_pe;GoG0t-s$|Uc~_Z4ADW-^Da z34}f9@Yf<#OqVw?!jxNF9t0T@i4exdU9yQy5cFEuLcb4V^gK;(2=Q7PDJ>fq;33fm zy{M%J2z@bynS&p}#F8&l(6kT|y}~1e>?fi{e%bh~@8a#GtFn(Thg*9xLH9xEbyYba zXqHRG-;F%f*0ejJP8ywJn#m=y<}u{9X8HQ;d5#Dgg7E}H2{FwBK`%v5vN}A)P!EYd zXv<7L0OU}#B$qlNCxDo|sRTNL2JcVwCll#U2x)*s8lCWT{RATn6H16TEEzQp^;#MY z)D3?fkhGQ6ho#40tA@A-4cDVjs4$Eg^fS`K$ALHS!O~;-fT=-oez21&7mDOJY{>FR zSY|2S5SAt~Pa3AEwq;LPZc_9t(Opfm>9blpy|>|^K? zwC)Fpi-#}p;<&r>4PKDEJu*dq2+$E)cibe;Ti->I)Fpo(kTD!UphhKN(G8vu4xP3` z7BO^PAPtIp(v{2_vfL5KEJe?f%$hBr9|=p+<9!T$DUb%mYrof-x{^OK%(#)|NLXem zjtNWj_^Vl72+K{1SA``R1lsakSiYk;DlEwfVGxeN(z@SB*&CA#FClNln3V!Xc$Ssa z5}5*|A@(;Y-j%LoU=}dcLy}S02IR45X;6GEUCAJj<&i*UDV|7|*_J(l+@$DPl0i5C z+MAzD%XffW{(Y{8#xTSY-<6uf{y=EZb#K@v#2w$2vh^B<-VjJKu7psVyU|F6Pdv*D zh)2FFWy?5*X4n!!k|{bBXlYX6BHn6!v7Yj(*gyXWqW5xMdujPfJ`Jcnem_0pX+)Hv zXn&tYCsVsq2io+_m#>4K*?AUR4p&98T!fJ56*ErKZK3Pum$&^O*F|Dg5Uh>Ejr+-61Ocrw%8Mczo;;82y^ms@zGi!k) zlX+ViR`v-vozWPB{~FRKH5Du~K*G&A8Rl9b$&?ATBq5J6|4+~w+&{w5j{=F_wPMD6 zz|f&T;9>WN)CrA{LLkvwf7CL9p-q7_HX!c$uJ;f>_^y;KB%TwKwXQ8GGo9Rr(~Q`zNA5%9$}0H?n^i{>o7SBM8P>x(OrrxPJsM>2=dRM@ z;>kcg_JK<6F(Hd2sAoxDB7`irLR*serb3o4XUjH1_&`FLG(UtS3<;+7 z7$8p&EiOxwKQ90}Mtl08S5-7+fjBtJr&>UU3e_(?JXj9lfN7f8N+4>ulB1~>kRjat z(lY|*r_i?k&M4*PKj>@(t#6>+g}l+#_W<&4S6^!DpuS1ybKgFsNOf*cqBb&@e4@{t znnvFc;^c)1hc5I2NnYvIq9y4IeOUFr=;<+BF0TQ7*R!N1v;yQU*guMv2E`$y(uLx? zlwv}z3M3gM4YAzWAtuAJ5mLhi1563nY1Gr$1UI5V0AV zmtnamSlcBi0Kh-2A8>$r`WcThZhqfjsIb^BgamaFRORKDHAZd0ad6HF|kZpm?QhX#` z$rPl*J%J<@-^b7l$N?ZP?OF&q0_0+`Jw^Gw@0&?&3RHRGRlkP##&@MyUSVh#OA1o_ zQD?*mTDPZBd?sDXn?s#ZTWAfp>Pb8%EVC3naWf=NJ`6Dl!WAJ-*1;(Zy&;g~Z?(@T zEtiUaJsf?GpO^3&WcXF`3Xnz>(+HZghhQE<{dC<5rz;tI&2p(28h@yH+MTIXT~zk; z&h$uvv7#+9{Ia;V$3ZHvtiXl`J=vmJTx>=@7v+&;4zI$FHL>S*=+*7iToLWP%7(OE zNa@*!mCRAg4H1rg3GD9`|756jNdKdMCm9?KH5`Qwp@rHm7XKuvMq><*@4rxL41c{l zgd`X9YiN0g)^u;1gEz2woE~Tx8m^%=|Mlt-0BEA|FA@`0Szl$~cvTOxfi&^U0SzBE z)MlhX7Xy)*D>pD>t7uJsy_z8EGA*4-pr%>@*1ul;7`UNdbxO6#!b+fL&~${>ytogQ ziN?iESY>^cfiJ6im<^n#+Y)4j&Md#AG9v^h6=3F%b#rCV|YbETTQtR6pslu)D56`s4!KF`at^hQeAx|CW4xX zf?;E+09gb31FwbRu5>kz{-jf`UZTBJZ2s-T_jvIEt>Ga#QXhia{k+c9!~H8A@+WB9 zovHFjrg5>TD$^cp>D?yHYZ?H=-0>Dh&5r=sgqHq^T#+B+Sgx zlm+78ET3ut8BUV@(nIHGq%QoB+GOT2bPa9m{siS+p-EnDEn?_nwC-=&ZT(rY?DmGD znTGogRFnbX&9iYLMZ4q#-6fOjsIcD08Fm zBLi{+kcFHO^aPr(qA3f+!C5}l0y5-6zx3Qgn0d)=SPr{@@ao>BY5L;!jDw!Sr$e-c zRdi+{&*8&Mw5Bpr2}BLAax~QfGOVC}={bS(1OKqIUpvz%j!0MY8pKK8mD=7*h==Sf z?_u7cKxR{lX+E`FD#p{#h?D<{=xI=-@9z8W6sP^Dlr?1O3Z@l8ZI){*gha9;!D!~BMg0q)_ssVmb^Py3G_1GxC)S0 zRs7K)!>8BBN{^+UX^bh>8f38TEo^&__M76z!N!k+e0ltjI-6Cid+EnPzI@x&?MCzE zDA$3fGtlep4n(1ch3&`+w zs0kQFW6c_MT>t`1!H__)FOS}h>0dieBJeEHOKm$lqJa8R=a0p-=39t7hZ-Kn)huptjXl&n?atI0fJ`sEJt@cmhV}$W z-jF#|T1?(l0@07IDM^JOge1R-a0Gucw1kjk)X4tUKAo>I)I*Y5YJnubllev&X1N~K z7{gl9kUpuYV3`5JNqjH!pPWn$xmZjk@0O6BCCjupKfoq}4DN)Gq&ow+lBO2RbZU&r zok69@1fo?}{q=tOFwhfdxQeDM5C>=ZR13(kulGyO6vBMNhkG!&jCuk!s%Xjr(U<;% z3=><6aRxo}2y@eiJH28nfv906M^h~zLm2v{=PsPzM0>GVFDP$I-){=aJJRko>*Tj})$Wp@S49Um9_gjx4`?P5W zZ)eWK=cG!!9q9W!)fbT{ND#) zOsC;_$Q^1Z@+4F8FhZO~4p@x~9R+S(Hz7XqU7y(CUT|~P#MdzJLUGdyp&RajI*Oyh z5pErbh+@ublI17vG3!}LIoF~7Ox*g;GLCui6UNdKov`b8$J@$f z9)(N>kffGcAjzx`wU{A3Vm~X$OfZ#6_s={eV=C!OPmt(^AS*3J|idh+&k_5$>BBQuYxB{U@oPOGYHBhDRq4iT)f7wXA{6Ly}t7 z14uH;8dCO|2QAZ>l1DlS*-(~UD*oHG=$(LCK^Kbep<5b#9?`}bAe&YE(I88#iJ6h3 z;1W-V_kEYR20?rH0R8XK{-U`3uo9~y0F^*bt7yssad4J-wSY>leHpuc>7nx(8P@~kxh#cbl2S_sghRbA4d|0bSI-I% zvcD2vlFPaVNZIXm=1iZ|(DBz2fTqM3f(|o>j>*1ehI{~}`}+(d5BXwHc#?UfRbMLp zK3%y8qP}zG?ODhO`x{J~kDwv!1P#da&Vxo8omp@3j)z2_x#Kb^!0sW@FT%wk$;$E` zhJ8faP9eU?2qbyDwaL4GJwRxfX_Zh<7KnZjUvh-^E_S{t%7Ll!y&`Y_whHp}hMqvV8y9<78d73Sy`S+2?)Mepx3IcUp$#NV*O zG{m(0HOQc68z$|DY01hILX!0_G|U{cT^QC50AtVfkrkD*#KdsZCU@m^1^F~Ad6k?A zq8}kfhQ0eShBA_d6!}t+Wa*<}2k@!%ju6)(K@7kd1MR~X`ec|NLS6t`@_{&m@B~9W zBzjAdkmms;x#~kmGNbvC%8~ez+`1}24#7?>rW~LiAG7FPPR6VPgzPlU6^6I4mKj@e zmxhX80zzoXN5O=U-It%_78^p6`{@T5=C$yAi#Nif32Xh7)Ws!=yi4NFlApOc7e)yB z{51i>IU!EkLdEL>Nv7wQf+VXa4VxEVR+ z$P&fZ(si5n1O08gWDVT|`aoEcMTm+I1+sDk(c6+-xMcB=Wcqz6NV1gCuqOz^rQ+Yj zKS1Y(M-T&W#z4>Di%*PX5egy6)w2&RK9`bNK!`UiSy6g`&@j{NP)`s@eXKJHd8VuH z2ITFoz8%Qdp|0#BA?mvd4E0_pem#aRn&7%_#fMs9V4EKQj^2(c+-e9jij_n}A8o8GY*cjagm&aa^@x$=y&M4xvcqyctn zE4hC`2;Ey0!;%xGA*NM8R&QE#6Q*f|_?Sg+brP}=1R%Pj)&QYlrU1~iED#58%IqYQ zFN8$@@DxL^2ljo@5+QA;mVVj#nA`nBpgLi|i|JHTLq3~?jm7*IncIK)s7 zN$&Ko0!VUEhmZzHq|qD13%qlJ*5G~*5bu7nbWlqMgtrsvi)sGJ|3(7P7{C!}P>xE; zFun!aL!zsE`~Moi;7&8`6)!+s^<8%$uKO;E`_g6Bbxk0%6rV{~6OuH{6>Tw(!0zkw z6g^9HA0^8O__-uX?t~CRTdxCJa-Ud3xU7F!47J?(qv-ePY6q5magE9*;E>OOdGtu5 zCt(WjFjq>BlGH+W4~g#egxm;3=IhCRXP1GMhi8j>`eBAPUX zIP>;@*_W{~MQecgDVnGFAU$iv|MTfY^Hs^LX~>Yc7v1+Yq=J^yh0up<;!A_#hIB14 zIbQlMNYZdZ>G3$;;c_k65qf}3DJ||=B>tnL)N=zMR`Qb5At4+}Z!Q(TiZ6p0$e?FU z`BMR6GVLAo_}fnnii@&#mR2D0cDP{h&0=U4smB*nmmYQvqU{_9N(dEg@)7 z#$Lx`<@~c#xi~|~)~XDUkIFg&gwGCS#Igqn!)8bpYB_U|DNKDszFE+qxFcQ7R6>L- zvt*eUmSi1Tz|aS1t?8(7hD50VSy9#*wA=$EBa%Hp7&b#XQp=fx>>^?ZXkCygj$GBA4T1MSWf(`UkYHXw`!C$+kZ z^)b5H0r z;_?v_;iok@A%v_W6YvLu`Em>0)>AF%rhqe?HwmFC1LP{$GyFWWkTLi&BN2=KI3hPA zLK=WvD%OUhcW(*0hQU6}$-~&0hh)q@ed#G?|37=r9Co+R{-1LhbbDR`w%}g&7tgYNk!Y7eY({CRQuOVm#87=g=FG#Q1jqs)9BZbqNl?*UExJQYf^D4H1LT30I4wXJ0mG!eiJ(34 z8Bk^M+*dt#k7D*o(`vVK=|k~esM0(l*Hf?fK8qKqy6t{uo@CTquhUdh&wKw~zUk$kjJA61Qk4%!4XIO38uvmby6+?;hf3osOU*~ zIwLU!&ynRpIz&^!bU)^&{VI!dzUsjOii@F2%f?voeJY;xT0Wabu^Os0#iJ4AC$V|z z2|#bTEm$QWv&hYwPiHj|OF)*O zea*8}Sv>Jo>arATxlb*RycTr={ivmxMsnNHp15qFBSN>T9YV+{pw^9z#2KzNN!s5X9nsY+^b~TE_p-NkJ zV#W8VxW{Yx>@JFZp-NNy4weSUPh#`b^{TyEE_sw{eq&c59WZU2t_i0`-W>>|!5%8_ zV*51FmP<*k1*-(4A89=3(^*Z#5|9ySpYSYI7SDW@y28d3JAGI{oNN$|k z6PIapMCewvLkKwq6!-A>=Q*ma`zfkh_bE|*hT>7E(uNYXklnB=TZHxm*KaH&j+lCX zW)tocdMlgLg1nj@vF<|H`=;lsXj=C{hR3C(aW@81B5erS^TSz9&L`=~`5cfiX{aom zvce3Yu4yemm}iEmiA~@6h*h<*d1E2j-)NfN18H#o#zOkw!#%q%Hx^QX4}*4JZY*R3 zK8)IZxv`K5_%Lbr<;Fs)@L|U8%Z-K1!-tyP7ebaiM12R7kPVoQ*26=QMFS3THA@kOZ8)@>?Y@enmg%V^pXMD0Clf8-6TZlL%$ zRMF#uP^EdC{hQ4e6-XD#K@>+r)f9@;p~|W_Xt_@4^Ic z7|q&U=s)nLRat!Jt7<)XVZRsBa6>#+e4mP+d&TNTmykCeq82wz_N-mkK_{cklB&@dZO%emL0&Wwb-_mJGLdE(u#0T?u7H;hfk zJVcGihk=;hFdTsw^rk2K#bKsCrQb~yEt~T3R)XCrDq@`Flc zA>_Xvy4O}8LTBSC@; zBjJ(YDFHE=wh{5D+w6TnUO^W8E*P(YB*bLeQ96%=n0Q`BJnGp_*4JDoh9KQek;QFa zReOoz+fdc}D^1|5ztxoPYPjcbH;d2i`Kl8XhyISQnnH0aR2`sr{&#(=o`0uVoclFj zHCbsEdj@^ga}>vZ(^u`G_%u}Y|5o$U0Z3=+Fp49g>II6gL)FS}H-X2H4mdZ|teS^( zRm&)@gsKe`w?fs-?=*q4kPg_a2>;8sFxWR$ANBj}h*zPC#dBZvkbSd+K62~ga}=k1 zcRk!iaT49;TJ52@?tAbdd+=STVh_&w9(>3iJPlQY=*+w5NvFPs;%2CN-{17V_wO~O zYjyYUH;Y4%u4?w*ZC1@gx~kz{Z&po0x~gVH_+Q3z3=x`zbXS!62_r#UDWLH(OcG@9 zXaYP_khin{bcf|-U-$JC%XGpp2U9g6reJjsG!O6AAq~6N5|Bk`PYMD-47wrMY`WpS zsfILemSi#$l4RP7@TZe=Srk`8)jEot znO&>JN)xyZ>8kcn?Dv!OS1bRH_NRn?yFH$R<# zbgf=ulW^?!4PTw1*yA?|U)@EqFI0`7I2x)>usPWBJA$v8eBpmNP^ZzE?A)I0>)oHK zqweOT7T^~*8I}X*7^8pdTRSkem`kRQsCrhje+@@zY+q+apoZ%E( zQW+peFt+A*#-DR%{5(|g+Gf~qmOtm7_sH*gKj)rz$Y02O9wvrnNlp)>zven>#BB!HAHO_;*ex|Dpp~y+l>3WPw@1>voYF6)F zBFKhiodHRJyoL4)&+?gOn1s0NYkexZ2J}bjOnw(hGyv(CN`drC70G1yBHd9KHIZW6 zH6YzM2{ITr38OeN8+)iDk%Xp=6*X;pH{F$ADNVe7ZrvuS$zASAiwswQ)9`4M%QaxWPvT zsxpkn&S)v0^EHg1RJ;P3|fy)?~QpCN;TzxYT3Vnt%7SY@&lXuuY@16o?FaKKs;fykepTh?=mwWfHa& zh(^8e{#1Ezw&d?dtCwLXK%YaJ;@>^cYhj+@d6pjBSGo&n*#yQIeG}LUhWEZ2(dNw} z-uE|k0ogxlD&7QkE>3R8CwtDY31n8X->}=0noxb!xA-?;q&BxLl9~)VrOs$6pW79T z+)00jxQth0Kr_lhza4;W!Ux1#~y1eD}X$Oyq%4zXWZ?;nD#f4 zsB@q-5e5@eOQ1(!bkoi~HR5c{UNV^{L5ACITOtgWY>*g}ZFJ-WgzhDR(`<)NML+(v zX4*DuwG{58F85NzY5g5DX&LJ^+YaC#{dAi{smiclJQP|QPt8-$0)l0FlwN9bv%J(} zSSwCpPcI%3xt;xin!@eCm{Lm;bq;hU!eC-LF9W)02goq~2hgE>6y6QM^K9oaGVFC2 zmabMy{Z8s~!|%L4ETv_v*K8XUe!4LzRT+lmh|tm)fzd?smYB&smCxZtFUJo zvOatBy^$xs*^G&0M(>oK#`us1nFfut=q6~I711tlQ~Nc|!#30Af{mFr9f; z+b{{$L}1INvD8!EuSc+mcca}Cw3|QOd5sZ1P-zaWX00~$bW+#%>UOzlQCh}&&9+V9 zr<((%D#Nt+SZHa?fYfuAGA&9?ZVr@s4AbIE*mDkPd;XayKKt54@ln*fc)zPzJB-Pd z50y4+5AaCeGe{fnaVcvh%5bsBciI>hH!@l5!E?Uu*VOx1zU!a;oqdBl3k-tm0~vuj zQp+|P(CrBSvhkiFqZsGL7rn_uZdA%%Y*flLHhoXrFB>OE&W#ODJdD-5f)Zkzzk2z8 zEMz&9VOr;e)R#m=6bFO5Gs2;8YQJIHDJ>6UTOMlDsI;Y#f>MtuFWaZ7AANEu%9Z=cu$FReHDMDa< zEK%YNx23xSc_kb&81^2J9=~d+j|JUWNH2UCf^1wV^G!K!3LBN$EKW^xEo+1L?H&Fxipu({Ml3S~ZYv|{EN>){k7~;I$xYNWf`HLG!wW2J zfvB5a$zsa-ap6rVkYUR^5%IVj)P|%48RoVUkg71v;7uDKra(&`6KECw>_WQj=#(02 zg1Gx`fcT2?8D3RxRQBS;=q{v5{aP8DB*<_wv?+Mp?8q=2gmCQslz%)&rR(!UI7w$+ z)iti}{!~j^n$V$0e!JCgBi@&Sv$%6jnl0{J6Z=Iqi@zJ{nXztUeQ=lKfugQM5@MPl zo*^+fAWMM^GdJ}ghS@-$90_99x^;*-``mwvgBq7kX?YmiqMp1+TNM~@rq&Gm$5Hj8YX~p|vh_a8S5FjMvs0Z z(kVUdjZu4iYlls>E4Kn=&ovpezPk`Pa4Y-lW1|P9)mw6APn(XN~j4M0myP4jiyOF)K8FshfOEEY3hP1A(o#zq56bmn}kJ#n39d4 zS?`W|-Zv$940$sxASTl!=yvwUJM!DG>UG+b66+bcMvuONNIeZFq(MoZtspF|dPY61 zTXX`8%4@2MuD0AqkQhTot%7FD8*F${nV=(p5_m#j3_NRPjFX^S*_T>oKN36!e@Z|Y z;=Pnm6ZF`JTAf$eG>J!o3^O?OKlP@mftC=<3{Le4$+i!Rl9G*}m);#U(g$doVA^wG znq^oMlR!f!k|NL&=rtTO9iNgZ2}EDI4>HULZ86TkL+9W6a2pPuTLPVxVM+qAagtAM z0T}|`Egm}m9^tlK8Qy%<;NNSmzH^W^za+{ut4L4>sYc*UHOVW9x|QA6wk8r{3WNmN z0wGb|vhE{KR;pL;WPj1CUbKygME%75`iFZ3KubFbGjVZB zTmWRl`{aHnPm7)e8IFwC1WyTw=~c4zi06lzH%|b033)49NQIb8J51-15EIXfh-X&w zXY}tkTZ}q-D$SNpAsdy=s_?)37Qzmz--Xru*$cPp;V)l|`(MCNZ>>o! z%|(TZ)}hF@)JR<)EsDRlhcP-p@7W^z1g(iO>~PxvabJ|DuPHPsq~TXGd))7qgi+Eg z$+7ZWBy(fPQ_mo>&@>NF(;+k(rd*o7_Ya!JIeU*$qzSHyPwia#Q5DUrerTa$w{-UH zNIi|pbWQF7hgg&0sR!CL2HTS8TLRt6eyq7!fl-0S;L(r(-OB!)_-TCPp1tg4c?NYZ zF;-Dz|F|j{(>hYKng&pfTOCSvPOPbH!o-?B+EnjHIq}3NTl-KY zB#nrzx&Jf_2MIB4SqHGc4Lm>8M$i->i;!;5lL|4JHlNNTAts($#G_uluLClGUvIP} zPkT`AyES&}-?^d1d_&l1xDwg|BjrqH(Ci7YXP5N9=x2E0Vx#nkM zulae_xAs4>S4$ceC6*QHWqoQx=|^Wo3;b7dUt6Ut9O;LdRM8URUnaZVeydoGT_x5YLGzn|V5y=xEBZzG4o{tGl z^@9!>Ld)SttY_pJJ^JBBr}UIxQEt9P<$aq*?}yY=U-0P;WDbU{LOK^mcI5A7H!8K! zMNNDGvb?7Gw%H^#xtD#UZ-)1OYOrU~$EfdjclgH!D&3B6ie-ktJ!38D>dmxBl8!bt%D`V@GSmT#N%>M` zhCo70Jg3kfc+?Q|RGM480Z7AZClX>ZZ4&yYJ&$UdgjiNos$T?+Y09pm@vPmp88i(% zhTo505Fo?X6}JVV9v{$)Z6AQI_+!oozn(Szxo1A!pg8awzUmCOgLxWkcrxTEIG#aT zb_p>?{|@R_F#Yhfkv%=%Z@SwLX-X-wf7H|r9{-mQE_W_YZg9z-GmJN8CHoD(V=Xlq zf8JVZbDJQk$*?c#jF$4b{SqVh9P*M^_b^5bUcCXDkuGn~cU#k0+v4=?(ByuUT8ikx@)qiv#S_I?dRF4@X z#5R<-k@6e`85hE60!pe4{695W4UG9`iNOZP#B`JgSv8F=VCcR#k}r!~|D zx;Bj~4aL@Jezk_$gkOfRca7*NY&uREP6Y9owJ`=KaL;GO-yd}=`w?yo^QBGGXx%Sk zlLQ&gYz_sFTe%sAH~6T2h{Ez))VXbPRru3Tp7Oh)p84v=)dzPu9w+JrvV@qXhchGw$73mw;aZpa&%tNnA&6P)=6dGrwEd=d zr?fnbZBh5o(w0W5Nj;59?Lwh_nl8lLU|3NzM4ugFvbYzZg!_mifG|Rh=NU$Rvl*LF zNYk@Jqt|KDVtg&A6un&IOzGbikYQ{}9s^_s;k>dx(ZV?=K)16$Q&*N4qn}*017qr- zt`nUgf+p)~BHV^!tL{KnVc3@U#_(1fnn92N~vrwisvNq4RHjxDB@%S^}MwVM+qAagtAM z0T}|`Egm}0-{Q2L5uT%Sp8Bt?d!X(72v9Dh_VSEg!mS2$9S;i9Jv5Yua26T(HqzNiMs3Z(lD z)O8fMLzNaLsik49)MIi%f(*aODj_DGN0F22OMv@;JcqPREbT!V9!EVWWu8RcB%)XF z=oHd)@!ArIPj4nMC4uNm_dstDJ;U~)CF2r!-oYe(rvU_ z5jFr}&l=We2{D5s zCxWL0#AMp*h)2z!3_Z%8HDr*4m`oc5&*P9mrAo|ih&^~-JTrjp|TmsKCm~;ebn|*FR>J|K%8*0wR#$P9w zFwq5z;gj-*C_heA)0m86FE+MdL?hKuJtnV3_)y=44`z(Ilz^B_JC1nNb>ST#{XPd4LcE$K88rzpnRXZY6L=)V#M2k?sO!Q6AZe3Sdr*dX zYO<7h5_OY^=Hbycq}$cAxINs=Id{+R0L2%fO3O@Yx$uhBrwj<$_mIz@qZqWP-w_pS znT@rmi5P29iD~0|Z~p8O;`PYKO(l-Cd>(5lVatOB*s$eoQ9C5I{<$XnTu z<|D;F(vpKAqG#n&j9O?@{rN+dY2WSa2Rke?0`+z>qb<)a_Wi@AU-uvl-{>@erZbT4 zQml995CP+8YE)_=qo&ceYjV?(w8$_+Rba=Ux5xcZ4F8xwrTZ146_yzSx8O>;dNa*` z@=;CsNZv$E;|SOl@3fE*#0VRmR|2w& z031R#qV@~}|2d>7l%3P$M!B@eF!1-_(NphP-w$^92i>iY=to#0w*68uE9oo)pL|qZ zK9V<46TP~NAT_*WesG>NpZU74S6J=| zX(HJyX+pZz19=lQy+OdPc&Duo1Tn&f^?^;vV^|*~#FVUWg+GQL-);k>o`PD?Vj6XM zC;>T#|Cf?pGpq#&d(+f4?sZSh+ke^P+*vn2G$` zpvg_=(l^5lKabcf_!zmJ0RLd%>T|c$ZJE!hoO&9umWoUra1%B0!Z#cYsF(D|*fgF& zx~ZAPr~kM)c^LYPTF$+e`z((9F14tKwHH7q5ck5yd)`)+r3J`tI!l0jp-si~VGu0! ziHqf7&pbPgV)arpmRCZvR5o`lB{dr^ucXc8v<$)Q;N|D^Xw7@1rZUl^9-`&~n@)I$ z+Dl_-%3$5fKBbN8UdyLi^kXgeV=ed7wNzs*>PCak2aifXR9o4h3qD9{sAGuAG6U^_ zMa_ZP2%;KB$h`MOJ)30HV3^7hLsXU;3|jVvsqPaJ40}lQnq3Rggc>di79(5L5gtQS z_g28N>V27IF}SDRL*vNa_F7cpM`#)#YKON4qTULKSyaeIx-WEl*B-GpKrDOxF3~)O z;~@ZQn4bXh%E#;{XDGf8RobFJEzdkey(2@&FAwoPf;>KXmPjCZ|z7ujY=(Nq$W3gQ_qD@BQ<|d(3DVv3lh=@`8()Y!KFi^aut7U zUar*qlIm||Kat8^l~nDjKA7TD5yQqK5$uDz-uGYm=}tfX7`|Mo*)7$(j+V+@l~iq5 z&DrPFmH^@0X3EqOrb$R6q*|Z`M05>rwNC&t1L+>Xj5AB!H%KiFYo#8O3ld~_AXGw3 zJZtcmBeSUM|K=xG0?#LriVlR^2f33i6+C1Ho_-j(4e3tx_E3Bls!;O6KS2d8c-J@^ zLyJZrC-KMZgfxrCT_o>5$Jf$eSp7>c;rSLe3&zs&COz?|p~m z4;u9GJv5#65H%t(#?n?|&&zE9|>V6DS-H##NG3+DD)m)ZyqU@JD z*~Vnfp`&?n%wS7>M7cgAuHMdDc)s(XH~dZv>^jz7mx$UTiHS!aPHiF zwB%TkS{l|$Jth|<$l2prQIO;kV&ciLhY4dv-H>tH!#$5Fp(V(0+)x5C4sU2$(KZ$x zKLJP$(iAlbGUWcO;3)wynKl>ks0aOPfb2mUW)=xCnYNwIBOxZ9#}SX3(=P#e7Em#)#G4cZv;ASPD#PO%ns8yrIxVq$g9xk*~scXY#b*b4e?!`_EPFWhv< zo$N35eb^b2IC!Jpkb4VA9|B++auQ^i-Fl#(JS89|(|RKwbwV5lqzY+xq*6jmrcI{v zNQjAND&kQm#7#h+_z+ZCT=+dsh_&qZo5cl4ck^Qz#fwliGumvm2#6c6wIdGQg9zdlYl2DR>^4*Gb4bAL?r8 zmu5-!4h_3;kY1!_=ukCcgMdszx-Ydm)W6iOJt)I0Dv8|1+o9~9=m>tOlur_6*gy}L zB9bUW7)At<JFp^!&V{P*A309Zvqj-$Q0fB#<`4yn0UA~O)^e`4AaMw z2!g?%5)gW^krHZx)&Vk{eX?m1j|3TbsDI0wrmm(EV)9`)w^d*q;gj!RU6(f+Y=G8tmP78 z=m_SDsb=nI7GIR%HLLS4!5JS`e zPJ zUdMVyuF<1!=B1v76Vjk0&&CmsJkR8DO^UbFoo}Voo@6=)as#vsKlU$o@3oOB#W?}B zvyisy9HMBcTc~K~E)*HoE~%x-O+|FrW)V-a()^Gp!)5Ta2$;do5)it<0Na8<)V%Kl zb??WfX+#obSWQX5?loM`u<5FIM?KJ$5X;V->UTYjI_IvTX$Utu^N>y1r3Mcr#O5J);`dT6?t9RfAj8E#TOewr zV-^+Co9+wUPC5{23&=9Fb&aSWkz*JPm$(vQy7U|nJe>y(gE5II3B;InA7t29x5YRE z51k)FxNS4m%}33^pRh#CX!Csx`79M;nHwZc8H`~mk~FrCm8cFGw}9SRgES3tf(`&O zWVeKvcoxeTCqb4=K*3}1XE`0h5N`r%3IRcn05V+7v1t;I1Q~d!f7_d;?#(5{a^Xz% z3CZ>t77=2KG(k_jJL<8djwTH;7x1e6Z z7eY({Ac%Yo5c{|P8Nz-) zT+~}ov6gDAMLpZ3*})bS!lq<1EbMe^I3-gC(3l`YWZME!FV15Y6;es}g>G{RFlA#~ zK$exGYeXZ69K&FkFC@eixlzH>dC(*nlbDh~j9K?VhK)p9j5F}i`5A=UaHZG+q?*o> z0AbSvU)lmu*M#n{(Cr$6Y`lU;>vE|1Qe0^$wobFKJt)Hn>KYOK=K~L>=O}JCXc767 zBe1R8_lPf5= zPGWJ*S3P`$;(n+?$qU|$m5Td4KnJIC4pMHe`9Mq&!CKJy_p%^6y>;QQ(U`)VsxrEBp+CTLM}GPcF%P0*72a0!DDYiWl^ z^&XRfvGihWO)Eal+Pj1uy4(t+rgePGqCz;;?b!`00ipIMo~5e!k^tH4`{atY9-U=Z zKsbvO>>+}ptU z5H8rD4HI=9q-eb5VG6!9Hy_dsXA0ie&NnRg37>f}-iCc&R#{}Y3+8#Lg{#V~>^_U! z2)G^hJ~)m%SMEiKR7{&11C@W!z&qJ`{`Xc%O|+}+CSId>KHbspjuy@i3_|_K-VqNk zxYJ@M5i^Mvb<8x%>zC>_QGRo&4n;4d?g@O7lr`N0(dDpKKBUKcu)N?6CkBvO0wj0E zC1f7jmmqIvzqhl6GS$@UQ00Y;?>s)C9yj2nnu4qDJZoChaw(Wh8M6wSrQ1U{WPsl`9AT+G-H>DU8 znnqB;;c9mwBZw7y#^enb&)|*PHy;L4yoW=k%^(E9o7}5b_6=A2ML-+hZn=U#HZE79 z?1ju(smVRMBJ~tJ%|d(H04e-}PV%e@7YiO(BxDzm14#D;;fE-`3RNh1A;YwbPpG9~ z?I9|u$K-+p6?|biU62qH&kJFkp%>o*asg=?i){fFU5sIroR=|9f^GoM(%(*A9@hk< zAE9ukNJA(Nhbol3U@A*3ToNu_GIBC@RUVE)o)+3tc-E9hU3dZ{LEU5OgU=?PdeE5R zH2E|D5WBBv+r~H$QvtSMKuZW|3XUBmq&qCZu-vmYX;=b;KA5^@UkozCh{}iL4xc73r=zjLk!8ijZX+oTJg4h=u(B5mK~d%K!vS!Qp**)7T|X?A}O-C1^25AEXjvm^ley zZl;($KJQ5_V^DRL7ac{)3PD@{dy_ls?h44D9a2HlArF~F$qQcekfnl8Is-Wsz6^lP?NeDC z@l_ATP#h0cD0xBi4T^(DWfWIH8MNef7;Wh+r1E#KW)kCfDU|!L+2!LIijVZWkyK2D zbAZ-I&l=$Ce&FUW75RF8aE+e)QPyrf96$8yd)YU=BRk*pO5a!y_q|}s(Jt!a&?-2q zyzvm`G-Km3M~0Yc;O;Q?QGCd;Lj|$y^vcx z@+3eGg+GQ6ybusm2neESma$6ArC8_x!W)O`4F|nN@VH(5#4XU@&wmYpUP+i~U4JLI z3Z7jiPlgMoLCC@S@eygz1fbu$$bEikjH@V9HkNa=cqh}G@um|T#cg14mTf`piO zdLt(}2jx0hVkAn4$+U5p#+k#=i}Qdi`!0JJ&tvMaky;woNLvkkgvNX%12gV)mTs4otc=jSCkIi8c?&GNc>EalpB~ z^3js>gVfTnR_ZaiAg9fOGj8ULgqV1C;V(ynp%>Ydei=-Y5R+-oU|Qf&msmCpV?^yT z2{D;=4ATNnu4&bOaP?@f2gy@#akeBNcLBluZl8T9FbN4GL$94lLW-W^=n~DE2tt4G zhQ)bbmHYg=)H3NIxo=t$!l;wYy+6~p!#_w}xCf!83P=s)=fZ1tOhL9}1IY>2mky~2 z2z_#fjl#V#$O2pQwcMvdYP+O(!Yj`0w2zAY*R5*aj(KP?&1|F-+y<`dta41d3rbsgC269#Zg~XV{yz^eaT|rs^LQ~*sZJ> zMqwP%-TR$JF=)xX_nWWfL99jfo3_vmcUc{4DdABWVtPiY$E_PIMGH7BWfVh?-W1Dd z5hsa)(@#1RuPv$KS}-E8nl*;Cq7#=C%KTWR$Y6rN&Ph8Y6wErWVTXXroi^ zE>|V@QCylthgt#^Jg4@dc?^jqLtyZRY0JcNM_DqZ3Qo5elUWoNAsa_XEBIsMawW=M z$V8Hw+!jdcDL9~`+BQH6Pr=BuiUM6MIA$ee7li{zcY7`l_ySu~$}sKX18QklEA^OM zV8;_|8fz_qUc>ezrX}P_qHOq;?M*-qA?xpjy+U~&lV#DnVw`KG9!D+Jl(5Ea zjbkn9Qn3g7pFkRjTYxZfmpq>K%bGftNF200q{l%^?t>$YK0SSQsTWxenrGkP&Nh$b0m;Hq{(K%S*_jD+HKN2z#sOdPhJK zSg8HAH%!eaHa+tYHGNLel)dPFOpC!A@j=Wz8f6m3TB@-YbqS-{!4?(54)61}svZ-P zd5F4#zekV)i`o^`9w4e=g!I}CW77nd7^1p=7X}S@!&LVP35NZIXeNeXY9^Xc!$7+i z*{aR}F+_Eb1_fW#o%aX~o3saUG=iu()E0=k3dAfbWGvkmMk*|ZYQMArV%hO@iDn8h z3jt8W97EKY&46Vd(l9PtfGni5BtYmxcOW(Ii@Hv=U|0gn5)9f4hOxN%N6n3pJEYz~ zann~-pQ1SQ$G(-eZz9*0=ep10>oID1NUm+qbwB1(XEk!|g6nqnUuG=7_jNzdDj=SK zyq*0#qXkc3K^;pIp82|;XFYJe7qX6(|K$156L3HCF;HE3iKeHJcd}m;+&RJSQG#w~ zf4CF-@Q3PUb*yLP8a?^%Kyte$^)#H21|@m+4&li2Ebbk z`LEqDW-+MXT^)khCsRJv)Tl|w?JWPxwn#(uoc#==Z5kF4VjDUVWyt8NATroCDd@!U>-?`m0qqG8HcfE9Ef95m>kbRu zo=4(^(QAC+WV>?F5zT=2vT|%-{J{JGW~@ycIhD+e~wPDNr96l9<@Il44$4K!zE(TRbCheiqW1#^RE% zQXh^YWW|T_>#3a!{89P$n^&3cx@k(i#oazlbD$44{mM_hP2=7sS2>M8vhk*&^`9+3 zaSXEY&JF*V4DDEadbu6{c=1oYJ{Dj3ss$Eb`>HQl9R6pFn6r+5>`er1C{F%!U$uhb zt5EgyUo<~`4cYKv=09v!9zixL&+y0AWb?yD_NJAES_9$ z$3H56(geG9EUuuc!OK53Lc47gABQRy4=zLb$6;u9g5v8?^%ljRKlO(6p?EJ;H9rgg z%j4MjD80(2ywr3n`>`B4t}0m4EJ=H6!k+rEi&SGdijjI6qgE<14P~jRoL>vVFL!rM zTH~rFFoZdj4fo(yq4+VRTcwY(ox8{YW<;}A3qExnw?Wrh8|{+1+)1%?&~SLX4vRJ* z?__Q(>+#Hz;z?`C>mIy| z&;kR@_X1>t@k9GGf-+SVRJbx@5E@i zm3>Z+I4E3|=FuQ_GDDE{ZTy(J})YYTlOIZ^tBY3{m?qhNvu?Fla9r z#>d`d0h;zNBVNou*BjqXS_^}1~s#w(Y49e0_$?x@#k2|~W@w)h^j zl<}SM--j)>$y4UD>1v`S(15=@HylCqM8oY%txx&@N#a=mh{pw{Fi6ntY)s7g)6Y{|wxRknXDL4T^6=RUb6=L%LSuC{Bhd5!mQEU?i72k@=$?$=0Zpe2q%U*r+VQ zIdUE6$j&vKBRkh{>Tkd-BP0htGz-sAj_F-3t!?WK4mLASF% zR{Ka|N?Dgew3^~k4UHKFLmw>xlEkwucuY~CQD-S0Nzm&>(P4^5PtcfQ zF!a#@AW1y01&=8TG>Z3rN`Y=?f28(N*NJ-mS;A8J7O`U(41II~ND@y4Mv=!9?l%Bs z6HSk7*FLSG&cT_+m4-S4M;eN)-z8bt9+cs1wrfOpkqsk|?rX4k__O7YwH`DxCj2ii zaHN(-LP|ZRETyJOuqV(qOL^q|fVf*W8OuS9db?r(a6(MxmI9ICQp`0U2^oTshHs`} z(*%|nq8^4(JI`m`)dBP7rO%&*XE;lG?hm^bPEZUty7RwS6kkg)4d<62-Sav6`>O=e zzy?T~*r=37HY%l=B{{!d+=)3|Wz6X+V@_A8Wk|J5a3siZ_Bt`2Aa@g&ow$yV z+}C@qu)Kjfm*sm%qL56pGG=vTCjQAef(CRm3x0VyT}E^`+vC`NH#y@Gp*}7tA*LDY z5k?$GUMY}aQKJ4$@R@iB;^1}rC#Kh~Ut`p`bV|#^*p`Q4Hj0idr7do+5rzzXYE*Vl z(>A)~Qj|6FT>&v!O#M#*wp|;r^)sLhE7d-lzVMJwd4KrLzsMT@+*|$4Lik^<9I=*a ztVK;enjLIWAx9HUqs}0kapEI`Tm)^=qpkrAmsWJWY@=OLm)jRe2My1A9mAp%$i_1^ z{No)e>ko3V-0x?NSxIMk-iv(gh~`bzb&jyThcvu>+yaD=v|Jg(AVO>dAVZIrLtV<3 zO#GA6MUNmdJ?|w!hA@mJ*Zq^?Rbx++O$c;0IWz71dTQDkAX!DtQDdOY9bNqSp6X)Sr(;vUEIi#VQNFrK6{ z>7ovz z4e4GJMjP@;LTrB0CVFJpC9>%nY&7g>B*gONC{)j@LenwwI&31S=y%$17#c&=v)V_3 zr9P)=3yH*-+}RLBCeWq;8Qvi(0oen~OUT9nM10_CI9TqSCc{9J1oeIv0o3`HdjP#c=5* zAts(zWsH*`!}A2M1&_g>5)g*?A|=!WodaZ8fY~&OM}iDI)SvltLG_tl39;-As6HXt zdSDSDreq_i-@Bu3H+uz-A#d&qh{-ews;?7#d13ocn!6Fp+7as+xkit^c1S%9C!|41 zo{b?at$Id1ty{DXi^^;26J2fDIZBKnqsBoq18KV!Ac}4#5D{V{nkZ$SL>VqsrUa3} zqY@BCxt0`dqUL}y%&u&jMkG-NA`&cm+tfR85@MOgseawls5f(#(3B8c!by}N1j~ZR zkUA@XJcVr9#xLC9cWpFl`HdSqo@>_f`!%MMPW>cr{S+0iiIUV+Nk&&C=?tf+t0F9x z2~1)Pq1*(`)|F6d*VwJ0TJN^uq;8|NEs zl5OLwU+T?RKJ;G)qn?jQw)(SdKvP=@o6Bi=0*`~2pVJ18J;UJ|(XXM+*&@GC$5nB( zReY!x_|oStwqyps-+P#oDv*Y=*0w;@^odzi$bj(0(xnn(@Lxi@L{q}D5)fO~$PnB-)F5(U z6w-9)-V$h}3{w(_jgx$83&^n9>lV)v!o20fZ8+B?h+DJ9wZB~G8(T4*R!{g+!mTIg;9h5XX*rGz@dT1IdZ2=j^vE(s8-lIFXzMK5%!3hUJ zx3hn#-XV@L`dy`VU`jfaZd?-4A|hx4-4)?BJSxx~$RG?GhqO%^L@@@2RYF2+L_?*_ zlPJTDrV&A8@TdfYQJzkUHc^v68E$^CX&RA48Hh+Q<84#dXbG|0XrlT>PoqxrvuH|) zE#V}}5P~^DWJsNPKzOL$wCxPFTn3x9d?J}ocsFbL1?)8(OWVAYyzYLHBz0Ai(N#%0 z!;Pkz2#e*YOkxb7Tmj80q%9Dwp<3^@$)s+hwd8eAKgHb^eRscW#cm^=;jt;kaRc$J zcN@!rf0jA&1RK73GnSA2CQv=Lm2A#HskwyB<+NcH7uAfhC5h5qJuNoB(`DM{NBXD8sSjD>OaxkWV>SPW?3Ssdl{^YpKRs)D@p*2U}DKo1Q1diLKvz zr`3lf-=Qhjc6Wiy$$7}%Sytl|YpKRsRHtcnutkONx_%ISYRkfVXib!1E^G@#U3Ov? z71E#X3*F{p9=4#h2W8o9b&qKX!DA#0Q>BF1f;SGLX-ET640)hUS0x}5!Z1t!NQ~i@ zu7q@nri5h%$fSswEd^RbRl%9Ym4;$+eh8G|imE;48HnirJYsG-Noxr-SB5DG#KuWJ zwFP7dc(-`y{89+F{`GV>9K;vIH{g?DZ%oLlhp1OID`-j<+cZQ1q71eXvTnDHO%qsR zh#G-MFlZan76GDYTN6bcdr7*egJ{DZVpAAxxUQ2Bo1e6a9vM!ypTM?5NW*ywA^RSp zcH2|IVsnQC3APdP%x)W-Ca}a1H3H9J&`U^L1c;(-O%!#UBDG*z)u)4r6$% zVjzkk>IGy8NS`pw(mxVoxaN|OF42^*%mBG3VrEN$n~&m&;W+%W`8ABzL>V>$ZGosW zW6YvLM$&zu+q@TM3tD?nmQmC_rU?X(kuc105@HM942Wuw2BH|EPNpRwv%)Y-|458s z{*jO_(Uh>v0GSgpv!y_5s0DDQaiyV{oF4*ZIJ0Swc?Kf-zk-;XPUCJkXb-*|r1*5h zK`-FTaf(kZflkUWC4uNm_du`UlVM=AWLyHzYnb#lgj+u~z2Tq>_|o&I&3kILiTviH z`r*$Yq$GT^xuAsia|)4S+v0tO~>%JgRn>^>+k8E;^PD_X#~}ji&cBH zjKF+e;<;x+=1?^c=?=A7T=Z27ODH}GRi`M1P%NOv3)wHEZ!HwDmM^Jr2Gq_87U|z5 zSA!D|PXT!2fnTy1{CbEFy^wyz^ouKK9Jm>cjdy;Meho@zSnNwfj(b>J^vSAV@8D zvcIhCNNXCEpz%U>zSLB1!y>hO_v|?e{pDkcf(+>a>IpIR13|Am5BE5pPVzj%CjpXw zn;A_HAzwfiy=f~Tr}*3C%^?~mfsO$R{@h267cvAfr0UzEAR%=96rUSrZbE`#>IBKA zfu&lFt^-tCIs0(xG1w|0?%HxC|Jo8Ukf2{C9{di#2(FN4Al;6I#m%W^m|RqjP(1mU zz6v4q!snY%T=k0YvpD!?)RMnMLCYM_dtOT?A!~M)T4Y%M5(r-w0ZCwa9I>eG9{_R$ zS#%8z!#)%we^Zxhmljbj;1cc1;S=iOKPWg?x0kiep5atn}c?~9tr zWJ!Qbrn|ocNP_#z5#+~OTE-AH$T6f7EUS?(s$py8A>4QvRxz@)1X6e z$68v(5H-j#q!TR5kuR!YE8iZ7I$OrRs1T0EkTCh9Ql!NI{=SvnXK~0^sZz^R zujS!u6nWa@?wOq9;OQb9Tnm-aJrRCB>=mmgUWCvl_a$X44tg#53qIkHfp|uIl4~p3 z+{q1#o1WO*M}hcT=`oKK4Y$e|R|e}++`6u11jelS4pUFRN6|Fcn!h}t>39TDS=s_o zvp!}qLpFWHeyJc+QCF(&-*`wuSJIc3Ao(jjf*Z4_5ROI;tfE%}!NR8V_}c)PL(>3J zd%pyP+84ZGETJNPmOw%Zznu_TsB{f~8=ebTMAHEI95r6}<2}?YL#{y@SXR(9A;~19 z@SO#yCnmu%Hl6l6ng=X~ea{yxJ`b%rb(Y<4ITWG7B+Oy#&g)(sDwT*WcNPCCr=>V`cGR(V%QSITE3tbdQkKd zEx2PXUs6l3jOpiVxy^V_%k1T%*N7aV@r3 zodIKuzio=|Wb2h324l|;4_7I}(P*h|KdPk%sMdVgM}v^x4`qPd zxR=TeQ^9j6K8C!L{mM_h?KK~JSE-pOHMy0CCQ^@KF`|QKpfk9@ro(V-fTZo_`>;(1t?wy4iFXY;Ej!yza zee$XY+5<#=xG9EIy+tTU!!FnWY>gDk@JB)*sV7*go`$plp<$*`LY^cL{UFGlbqpaY z!;r3u!K0MX?L$*S4SOMKAGfoVm>eafFe94{^T$JDSy zYH3(2^_X1PgB_PPM)a0adfftK-+Qgj|71ykuxao`&BqcDYQMDkWuz!&#M%J4o&7*v z{klXW^Xyip=BtF5Qu8&E<=iLDECWm_1N{z7*Ku)b+yY9NY46(-Xv<$cs{?^N-G-IqrPn*R(C26)~>s;eljg({T1kVBR!5FqN+OAJwOy~L0OZxIU8FdDRr z&)vv-hhoJqJL+5;YpKOrXdTqY*>MPBc1Y~eLae1kAALbB1HO;c$IxiYHsWs> zVG?2*{t{&1*@Q`3-ZXV)iXrO!7aL}d*)9xg1c0&U_(+P%P13}0(b&kqGrXHOb7>wQ_Mp%~m#JCs_c05uIIg2;2jKvnn>5<{KpVu(7`O@bxFU(KZ! zAi)=P)*?#+WLo%Q>QL$r0jMrR4->;M)y)AysNn*h+SdU!T#E8M@TrG9VDXKw`jY2? z;n+@{L-&9_^jg$Oh{P{EWZ@XaV2e6%sU<+v^!rc{bt+|h4LuqEVqOPfFbX#?1w|B zq6w~w7EIzJw~eJSoF!c=7B@mGn)l3Csn<88rH77-ig&%12YV>q^`U*xhvL0Zg+^XP zJ5PL4%*Cq*5*Sj7PB3td^AWnS4p!5l$+tn18y(U&!+?>VxzQ18srkM`A+HM=>6@kH z$FWE1p?4gY>LQ$9f;4Q$VlC=3B2{Q7o8kO|?#+9{)DDvn(=e79cdt6aexhf!KK6_l}x;G2|h*?d$ z;c+5;G4((7pZNe(d$2|7^;;!1jBkMsklayz{;Qv$aZ`*3Viu{bpfjjt5a?ij?m{LZ z6P~z}5c+f{Tk7?Dbz18lXwCmA6KO9&1slxnLWU8*Yh7d?np~Vt@5K)TajUW3VKb38 z>R{luXA#iG^O`I8W8-oq%3g3nW7kVfZgQ4-3g&BSX#=G2kyG-l3K!jVqW261>EJHv z40#g5an(8;b-Vqe&4`F0rLj#k96y0Cx63wm%LVt)G zi}SuJH{Ya|Ne{_AkRgOoC!4zn?%UxXq;>x!n-jh<3VE2ROBh;16D)d&zvPrg-2$Wr-M6xzSXtIO3gHAF49lMm zkY9u_+C^W8#%v-cAk*`F8iw7(^N@Js2dC{CTO9nyPjB$QVWofzN7imBRYdL z+v%1OV(C9gb31FRX=}f6b>{B%-Y^SL5so@`1*AuZ9Hv7~1%&IGvYQ}`Mj8CcgB0y1 z@-PLfS01E@=3E4!KZKgad0&+~Fr=1A56N9O31QU9mcE;yrV2<6(-Be8{liK`&`bm|5<#c;OY- zsQA*uk|VfN5V)A@fL+=p2q!9D@nWXGedF}GZYMHeKRH16mGC!V65i{*XYUr z$|(l5U3zBV@ulea7@)v;lhijB!l`5#hPzuMD=4mqDwMpC?lH#_B0>nCtGJbY#dHpD zC+9v$#khX=v~W}WnDLWli0?l6^@ZhiN(gnP7K#&OAgmxdj}xZDIS zOBm;GA?p`(55DQ;pY-l~u6ktWn_m9SVTox8($jN)miLdgpm@hyB3w5Y>1hE%^b!pV?$0xDF+?3=F(mit=C-nMuJuun5!=Tn&+YEV5Y_z>2~z^XN#er$ zqK*OXUPrKXEjn&t$4HD}rjU>})13ci^0i9#TUQ}{K4w)G@A;}(l)PXTQHzA!$yW03 zAbpoX{Rq(@l=?u+<+;82k9YY{e7jx7;30G34G*qm$yhi=S_1jvZUp}Bg$O7Z?AVp(257TCv2@wRQlcQmA-aD8(CrT}o9+GRT?l2^T zrUjPVQ^daCzPkPg2=mlOoY^TMG_c?S3ke}hVeU#0c?x?+g1W~P@}OWq&^&IG0;pg> zNYF64r05w>bSw960h0R|KUo;D0Ljg_e2AJn+(ZNxHAP#1B&7~{l0a;yLLKRA0$Z5G zR>8#@wNyaJ-YIkj^v~*Zz~{NA6XLa}?i) zs^(|mf9?jP;&re1K8vrsmItxo+(ng&7ohOMD}ETPXqKccOK3_13PuT87=%sFq8diX zdqD1FeZP@=aVdESN-&L(PVqd2ALKEZb`U{wZ!0hWF+>e?4Cw^R^T-#~u)_#aTflC3 z8M5HLBSu7OsXrFNK3MicXOYDfU-gj1RbRCj53ogTw2-UvA2(YXOpYO)V4*=1-Y~UC z+5owo{hm6CNi&*m86iav|1dKoO@~aIf)@*RZ`uH{I76Dbbjt{_#97jG$h1fBVh{3; zySuHX8bJrGfDBW4w|F*15Dcaf!Vp-xRALfnp1?x4HDZy>x3b*RB92)S6IxCS314|z z)Tyrx5KG>Z<|y4VLM;6!X*y&Ym`}5*f+Aw;RGq?6@iL8B7~P(*SwM;v7D@oqfH+GDp69&}jo7KlWs^D0v}sjb!YX1p5dn-<7|- zKZdC8b56K2T79rkkYR2KlrZ~{Cjqhvlau_}2IvCPl%52=1*qUuo?S{vr+J=6 zK`8iQZyHAs{V9A7MS_w%BGa>!aF+s+;mG$rpKunP<1)@>M zU^Gm<5^_76$UP5Y45&V-S6{=XH+I`j(bSZ3OTTmVd9)$Vle;CAkcx*?S>)@%?n;Dj zE06iDc<=j-{wHG1;D-lN@mrVyxWqQiGc3wG$V=DVk5264%dj(pD_e=>vkwE+B^ zF=KOTf#jsfxRE7{g9lPm!HU@#Ev;n&J>o9QU_O@)2EnZi{W~%YjY<*COoo%10=YV_ z32Du1YPshpuP>zo1wVJoe*Erf;e5S{o-5zA?boyjn+m?`f*nKh1PGfl6;1iu5~%eU zlb)JfWa2Dd&;}trzKL4uE3|aUvT85GY5G(?kK3nd12(<&d0f@HhLGKKNMOmmIN)d@ zOMq}<^Y+P!TSAInahEhDoJoMN=~LK#EBnza6oY?1LX8*Fzg>JnE$(L>ZtX}tjY_Wq z1znSS3G@XT)1tz60vW$ufPzi#y`5N7!OJ{(n%o7~b74`zHCVouYOF;~ap~1ZTbdVy zH#;un1`u-03prMf@d*c-8@s+O3KGKYKKG)A?JF->c{OO6yCmkr(;WW8s|N=?2vEU+ z>al=~2MCLtkP7aI;)HrJWXy7A@vmOXQ-tOkiuX8BG0ODvET)esGPRf}1;S)-wga4j_x}!c7s;{&(+i&dq+!cwy5=Fdb9#3nb1*36U+%-~ zG>ni}-j^E!nTJ8^-Y~T*2?_3Z5)u+dT@7eh0%QSh2Z-uR3u(z9-^sr2&wUVsDMOxw zFcY!{uL`y&WLZH|vY1ShAj1SqNP=l>O4AJ95V8rc5+Ljw2YCc^(8AdZAB5juVHh9d zlRZzYLSCThiHE3D^&2#O2U)b2q-7Fgn0O_m%`|KO`06gV#|NN_k{4XwHU(s`JfyLu z^#mwrJl_RS1-=eJ7F;DV+?|CSi%#XmhjPhB7}KWL`;(hKd61&S&chT;DS410no|*k z{@@LZ^S&zgQbKB(^pM<3K0+9EvZY`0QBwt^2J-6fUY!C+?t;tWk$2(235uNd3Jxps z75ks)qnU2eszLFR=lXIP#p6(gk{6sT^0_{x6T?BvJc@y<#v(c0`Oqp_9YPiy8RgUa z%f~R(bC;HUExsqFy)C)j|S0n#6xmNl!PQi ze+t?|($|>u;YXI3t!NuIAta`j&|xZs`S!%Sr}l9S$-R`JVKGF_M?xNX!&H`aGz}27 zt73?1*cMnq#MB(x2ILU3V7rVKUi5iL)z_iGQ6uZ`dB}Yh2YpqI#UWpn8ziZ?ge{$g z48Xz>?@MhA#ko+0k{2>=v6kE+KpodWNF2sqm$X!1ROrwe&7_nb#}GBSVn`=g=tJmG zHHh7Tj3bm&kVQK>G|9?fi0wz=(thZ~S3NjG@m;7w$qU)#{9x2W?z0#a*J8!$Y?#4XnH(Uy9I*~1eEw_E*LoJCdr=K)!s^UY@0QQQhuD0v|hf_WFTs558`VNEVe zY^%x=Ls*l`LLb)9qTtG#I%0^L{4qpzKZcZG$=x;5mjx7-?e51A)iCDRo@Y_JvIR&& zCX*!r@(4a8__7JeD@b>5yOMh{k2cwd1g)1buT!9H5k2=zSEb;YI>s-C{mcSmx9&qv z!2u?j*feyndqABZQp!10f($%I&_$jS5ci}{zG?ISnIKo}#GfxlTK*h0UdTR(wbT|OEws+87fuG$q934?!4Y5fXe+hja@N8fNMl@+5)i2SIK0e=@$gq{yQ7U$-SR7^8nx3IY86}MtBwOy|m6kf2urFpcaewr=4EIQ$)o@p>FKo+drgw)V< z)%Oy?_#iC95)%5FN>s=rZ`cnvQQQhu9*%+x6ZbHO9`a)i!i`B_$z3t&9wDvSx(3VW zX2F(_#1c|Jgw*_#m@d&2J)}-|81faLS-B@{60!%k-N`JAYna69%q)kA?aw)}t$VWE z{g)&=^kiyk(4_#$z0&;9EF}!<1Y{e*WyIWOI{&3S#%y1JTpAG1t}obMODzGS<{yaz zL|u0Yp@DAC!(!0FMJ(e#IkQnqfOOKOz&O|XpO&CJng3T}< zV#r4pj>o2yqw-r5u{+tn(r48ZILnl|lWmj%8JNz%#35i}lAv3enw~cn!Voh6w=#93 zdXAX!>B7c)#{9B4evL=r%g0>zq$YO}AoUoo3)%oNS<7#-ql*P^mD53fo948?uKjWr z#l=vCczPiRx75)X1BA1~X3t@=E9H1V8yg6~8iW8wq3zO8+uvY3Z zxgbG?ZMlS)ct#>8)r}fg;+l_(dKei))YF_fXis2?As?8f^824$$(Tv}bt{{>Qt$rY zG9e)o9#Um-0@>{*GhS9yLlxS4k*9drE56U-sIU5x#b9ynoi=GPq3(tli!1gW`v=Vl@=hvH`_z7hKtqdK#5z;Dz)(*5n@ajx`lL{Y_`7Y3i~~o)?8Y`T$B` z8cksuLgN53FtKqk&&65usZF3#<{3Z}uzwP=;Q3K@Z4Aj>0SRFc0!!`_FN842OzKZu zQh#3$cMNkc5ZGbM2t!Zymxr0!w}!w(+h>lA z7^2RPu`g=GXwXJ5>?w+2xK!h=;4nnncxY2$(4uBi3{lf&GqQEoTZDq_a2mvIlKTmi z$__V5+>|vc(>1wQxT%Q~Xz?o;*g4XsH=sy)Q%nD2e@2WF@y9YXn%qzH{rFq>0 zF=`>TmK z|L3s(6jJi%;m>mH9r>@Cah!ylft-b$gPez~L9RfqLOy|%_ALI_P5tj6dsoqK|4mbF zebbaLAm2c~gS6^<1HGyGHelB#!z4|xh)Pfq;C5%(#`X~-&MA8?~N_*t~8K`uZpLQViz z%fT;I?w`n`rkKau;%se*^a-2mb=?);F5@HH~q|adjldX)p3}6Y?Cg z4{<&R&$}GHlmD*Ca|Zbqvijd&pWmaXAA=l+%xk}i&$l5TL+(L7fxP>(>-o;{`8&u9 zrTql-OhHaV&OpvWK8KX!Zx{7@kWZBM=lJ{r@;zkFdefg?$VEuWS4I5{-`-^{RHGBWM2CkK3{}ff?S4NgLT*D!|5s7J2Dz@ZKgQ=Lkgp-% zK%PNP|Bu)EJA(RA$T7&g_J{cV2=XQ5E65Yb@qcwaUj_ApkVBAp?Wgd06>m!@AN2>2&y@BV*3n+byO8%F`yp2$CEq;iYmf^{`we`41o;Z`1XAjMjQU;3 z7m&ou_Nc59}Q;=)WyO*PX1NB>w+mMfQ+CM}6Ipi|zScg1?JcFG6e-S@OY43aJ>Dz9$ zy8tfxKbwEc_A6+&2YCSb0#dfWK>f)7+SK=czbWtjUrpH$S%K_*)~p|dl={Y@rwTa& z+!&;6zm9fWkke>a&1wG(?Os40LB4^M`Y%vF^1s3E|GOziAtxZGAnDgco`29&g`5R$ z9#ZlzqumO8fKL59YL=K>ZZtG-NfW{Q~O$fA;P;-u?ft=l`h=P8>|8MkgIQ7_AJ$ zVziiAOr|D_m0__m3{xw^XmQG9aefS|riN9+WEhSbhG8)*hG94u4y~MW(kho<&)egB zxqKeq_v5nd^M3Dr&b#mXuj}RYeBGaq=i~W&y|(jyzdxVP`%}S7_U$)54^wh8oZ}sC zc;6pU??=x4`pew@^?JMJ-!QLe#~p zO5L_mKSP}?=CFwq>MU`Kr<|wMy*28Or4CN<p+%1l9ignJtVVu95d#&U8mG$J@Wq!+;-|4z}eH`E|>is^*_*c7mr+9|v=s`XI zlJNirF=XUrJk0$#CNPZ|)a!-5*7X_17{*cOm;Bsc;T>*_Uk?oax~qToH=Hqyqpm+= ze1X@0)6J`Wz4H;{-{7v-7#q23T`w$oOkfIizH{s9_|&>BBY#JJjrVxUd|m(0{E&60 zxWQ0UNb;cz>;o8dk{+4^b0nA|@b^jL! z=7Z#8Si&;u`k@2!XDToKTlJ+6ovRrAH2$_bpEh=}kGg*=H#71<#={svD}TZLEA-<6 zw;1?4FaG?e7*AscORp$Dq)u(@*6-s0XXyF6FYd3#_#Hl?=kL8Zf5ZJQPH>9)`7{sA zTXknfeHq`k|2cK`%?~(-H4gs1JD2*zIl<^Zbk|iJp+1kvp7Yzr{OCV$>%=gQ3DoOl z7%!moXVu@b&vW|Bs(tDDF>-NC$UM|}sh{P(oa2ad+_m1~AG!T+@Bw{OH?G%9GM>d6 zUK{z?fqAQL!>He4yoWQK8+oa-Z{Er+jrwcGAMxTF-8o*OK2NE$Z{EuJjrt+RW0=Q+ zk(WCA=B-@Gs9#~cfdd>G`RajrS$E(1R&HeUGi7`!_y4hbzNe_4uhiK$Z{^O7`aZ_} z*u<8Rmpc3A^K-YqF)r{C^?ujiTi8dv-hlBbN?)>$&PT~@@SHyMzO4S52MQBlVZm*_A(~j*?-9JY?zd`N>TiC}7=J}2J z`G4=~7qNtWtT3-(%pbGP6lZwO{5bRS#{3!ME4-K7e{_B6{dyU{z)SRF>OZ-8CDijn zMf0WI(0v-}7JG`d++1 zKkE7s#$%Ykq><16S69D``Hj22MqU5Ve4TY$7@}^z}pw7#9<-famxqD|5hj{lt zU%cKa^RCd30Ssak6PUy-=1}){Xg?+TEn@}sex{7;^{n}IBcI}2(wN0O-e41_IKw$E zaEaD=uera)Gv1SP)cdh=9wUFncmRVKGV)QzV;IMbk#F+8x3PmG)cwnNjrX_CdouhV zFMc2A)Oo;1+)91wc<=%*F^D15{UjLQx1S98Ear^)ZR7p7=9j3W`}1=y0SsXT^H{(( zcCd>*?4xzwx7?rM5?84EvvPMv{!zyH{GH;N@p<$z?!yZV8uF9xgr<9AV%?J^BwApasF+t-^{na`1x(gosv7l zbJYFFdnE7e3G;8MulK*}d>5S8#iQ%5fHlBbUd5%)=J*y2kwB*43Zj_`A49z22PM2Iu6?zuV2zc^NN%kGns{HR^o) z{oG%%n8XyOQRnlFS8@0OZvGf`zDcf)9qgjc4;dff7$-))^8Rl98m7OWyRM+FA3SyU z6IlHIu<>UKhWLJkS}5fd$>fYtLp`RpsN$Y z!VhxS*QoPJa%s$97Nzg7(f{y=xcX}>{7`p2^*HrfiUn+`h6tXB`)K_9NYRb#5xxF5!-k(co-_X}7u@-lwI{Wf-uyo^t{KgXq!m+>w4&pz1g*MoY$ zG9Kicx2;RI*6z!mEE&Chrc!x+UlCNYg!%wrMDSjB5>U=!Qe#Xb&kgcF?M0#~T_6JR`u z5sYF2lbFFQ7O;pFtYRG-*upmUu#dMm!YR&hi7R}&ANPHbhS@|^Y!HV}F$@+5cQR#!{BhRV# z)7<_R=wsam%5#x@=6|NkU*j6}^D5C#1#4JG>8D0tdcK~g_oMSQ{@-dh*upOA{I2?E zKgsPgfKuP8*JdA6l=E9~j(Yv(N4WX}lz9u|Jl5nk_<&o~^&5Uye}oU}dFp)Z%H=aC z^QO$#`7XH?MtHB1n86&%`%^dG_ayJ_Ez0{T&q1%BCfC9h>zwesbiV)5Zhsq;K1N1A zb8<^utNFTqo^`7z>ui~)^Ua^^`kA2gab|p;E&=L&d4V}%GFO{8gr=Y%XoqNCA>EBGTz{R6MIHp#s}QL z#hHs_UaGQg>q1KX!gdA5)Y*)uLzy4XSpC%@Lw!1E%?r%k%5c#2+S7ct*nE%N9Gd2H_YrWovI;RoWSMBFIJE-#` zaub|m{O7oNI{(1^GwyrPi$08@oPkOV=3nCt?%Gd}x-nI6-}y;3&&Rn{ zjPuKrFQeqsR{mq%xt7r%b=Ps!=QX2_mwZ#r)A=>|N0j`6c{+dcac=!H^kM;ZKE!w& zlbFIZ=26ctF-Jcg=jAzh!)e3tZv~_4-+3{Wi~Sf-Cfrm;TFK zSAV|S&jimt-dzVUhB?&zm#AOIhOu66$9h)%m72Gv&%2oGGyDsj(szMATSmW9?~b|~ zd_=v!Q`YmLtXE*&B9>6kk1n~le7AHRr!F? zPoD82mauE&i=W`0cNH(=?mCM4JZHQI7v$S&p3bkyKceJU%+vWk>y9z@i(EfB)cNWs zy8G97gJ-|cjqCh?`xBhu92atGJb*!rVG`ST{zt8T_iB}lL7~bFt*Qoom>IIE_j`1>9v4+>E*S}+2 zufJjZ0Uz=Fm$>KP!#ob~7Wb`pYUIO=CoqL+%%EO>$hcmA&iFk(Vm#^g)5lxX^L>m5 zFoa=@psqJyT-TF+bbe;!7mPp1{a@<(PGAWusMot>JcJR9Vhp98o-gameZ5|l`3=Zs*q=O)CiVKC?Djjuvrlo?e$?x2nHMAi!b!bBSqkb0eQ4S5o<=k>CC@*U$NZ5=*JRXeww=iuqbt{&=ojrHDbed%LC zKU*vt{badcRQZUJU;RqAzcoH!EaS$nv4ML3UdH_x#1Mv2*Q+zG>opl~VH*cHLeHnW z{wi3*ee3n8qw_1qA8;!<>Yt)sziO;sXS{(o*u?>!eumpm64R*rv+A{}qw{md*SNt4 zd_=u|%2+?kcnU{Xux%*K};0SfTz<3p}v5pPA zMLj>R`YUqXM(O8{`MdfL$~=sq>|g2+B}d(T>+5-0&Qbc(`pzbLETXROXFP~uY#8~|&vx~Fc!8Iw z>yM~2!zG4{e3|hEhItNA<9Q4jpWr<{82KsVbG$>Dr~3~S+u`%N#d-z3+=J`Pa#bI-W+Eqw%K9W_D5Bizqm!N|+_HTN5MgDq@hihY%g z{q0+)Lp|00iGEJ9-vRkKTI*l^7I*GBeEexTI)cc>%#~Jk-ijw5K9w69`IFCg_0BO_ao2g&^|#bn@0r*8tg;XP?{Mn`(Z_nx9qTWD zmz#HoYrMw|KH%&NUEcfqoO(aI>fHQpH*blaD)lh(MeaI=x_*Fp5o~_3%MVfKSM+)I z`&}+fE@9+n^sz>n=ViXG-(q}>Qa5YVkNh6jM+#-$%&5O4caO5qg;BqG?dp$E`Y0Ls z;O}+$ILf>!^YwoFZ+cefMk}FFdtN32)e*ybLKks7@bv}JyK1!V) zZsGKTN-FO6} zm_nVeFkZzPHjRAY54!qAY+)PwnD`QxOJSzrt~Y;_`G3r*`_Xw1xuTITP``*J?Bctf zUsLmg#`-sEz2uI5CEsM;uKYDQnJ0b7JbixIKjh9ehb63F9dB@eBYeayhInpaj9?UF z7{>%AF@^H{b-y|8w{U$yEgI}#&eiQnWyVl zny#N3USk7w{*LiA-b?O}zxerHFz&}L_Av1$+`J^}^=`;Dv4v76#yqK`=gT^`%#(Fe z#(Ib5Q-9L+U&0F3QTNkkyo)^?V7cw;HBry+w%q+W=E&)J9bt z)*GO%zcKPRM*f!Zdz{h7z0ptNPrH35F@<^5{d5=~;20OLC_nhKuAe!s@DYb!?e0IK z?oZ~AReoXQb$!WM^(B8t{ayKR*Yz96Ij*owUrnPwnIARg>;0dR^Pm@pIKdOvOYc}e z{WY%t4CXM8MNIxRm#bpsZ@TMSoPUG6*8P^4U&U*zqt2i7T%8LHUbb6OUGAQ9&3?VRZlm?S%la|;h-1PyzdGY>EYV+8`cwx#A~(S)&QQfqe1F09 z?MLZ<#6EOBMXreV_<)ai(&rpiftQ_MrhXM`crELy^{iZ9^7L6W`rYzgo(NK&9 zU7X_r&p8(ldeMg$DCej56XAXw6PQGu&oG|Fs^tHw+kX+WLw7CDscby22J<`E#SxBi ziVIxg9j;OLdqF=*qd%PwkPBkSm|tUj-}x~kf6w>>UT|)g7{>%AF@AzTLm$ zoS?4nBe!qfPd>b7eaUC{%vb)F>$iqYY-0z{{tz3J4s#j}6x zt}|FcJ^zyVLEM!O{UcX5iA~mPqpqKzZW||A{wgmd=&6St2Vc2M_sK6AMk=CO-9-}|R7Kfod0;t0psS-AWfb-i76 z^8d`u@8cb=(X({-eW>ei>EoPy;orJ^9d&;2uiX75o|C&Y@|}O~^0z4S*38%Si~ri? zn<#ZdMt#rR<^3r0I?UJg`{YI_`|KI@3;)K|zd`9EZsbqD$>lFl=Czrx`>Bx|qdcb& z&#Q}lOtNmlSU*NCA$d&Ud#(R3*dK2HrMo^g-p9a!c`tRUIHnJIZ{*yk#(plCm&LX0 zgZ!@f0p>+;-@L51D?i}8X6WU;4&#hI=f?gXW&Gc9?&v}NysZ4$E6Sf3eRvtaz)NF2 zox37;gDo6maOL)0M7>|DUX1zs<^x7P&UhZBzc$y>U()DL<`v18Q1;v5x{FfB+OJiw z#(cfsCF3i+!|1;J>q{2=%D)pk&?_p#4_)ZyjQyaW9Or5_g>%N`44yRcLa4m)|2BOO zQPv4CU-y6ZUtQl(e9t=MD;syehEvwvSnE^gjB_bS9c=PB8R5mZus-VkHhd31$oKL8 zc6l%Ae1&yRdB3C7eMG5u$^0Z{jd~&K#PL1f!^Y?R;okN4h+91SpKe_DE8`yS`!HnW zWjwVEu;2UWiHMEMZwO8?S_)xYP#?e_vN@e1{RlZ@xF_kZ2| z^>;cKe2(vo&-2U9A0D`#-~kk-JM4fWt{=} z?bh8t{VwM%>n@G;=hTUEo+IkaWPR#g;h4I2sQb(C>#Hmlu!=e_>!iQK^(%E--|eoY zUY+?p?Bf8(sO#6M+eZ1`doaEaynIgm_?{g5*Y!`{-@U)5*vAp>$`20A-|omuA7|wJ zAK>~6;SwvSZoGy!xcOmje2cpOwK4zt!1;ka^Ko(sOkxgof6px+Z-^$hZ+>g{fG+#Zie(6a0d!G9SAMu3Gkv=c~_jm6{5X0ES z4t6p4!7d-dUG<{OOQ6ondOBAoU%@KwT3^7Mlm>Bm-{KApuH}_n>sMeSFO!lw)Jv5&@FY;jVtuNoHPTd1G!q4`UmqaUN} zGiK~pauxEj&%lSc_d@q`?0kSeGJEzDBo|ist+C&TsxLWfzlY|t)X!r9OQ_HD(0r3R zZH%+egt1@Ao%}%eJY}DCd6V z&HH#xmzdg z9-41br;TZzYsPrK19G>RC6_bucjWFdPfmVL>i*Avko#WnU;u;oviS^ka+t^M`HO$P z)VP0*b!?#Sr@(j-OV~8>kBp~Szl3G1;x+bgjT?MG-H+4{a6g8}S}#of2u9VqxL{Uy+mglC$=EXg*H;B&INf`uq>g*Qj%gOI+ie zKi7LO{(P@ZZm?%w)>)9h#|PB=S^X&YK5g*qL)~=H2OJq{+e}%cyZz0pEyqN^uye^exD?FO)f+(W#kuX z9WObVr|b8rJHR1IUpn7?aDDdi7RRXb*Wc#yb!^}b>U@#$5|*)L94AE|%J{R=$SdLHU~(Wlnc{T08%o$m;*zSCU?QRlbhPX4dU zonjGXUg!;*e@_2;zcPNs{U~Pk+^?71tDYa*bA6v$f7kOlH1DT=K>9&_P6fvG`M#a+ zK1WY=ejPriUF_okhv?h7KEoJ6{XCCd?}T-wpIz&}&A;=6gQNPd6Eq`M4?PL4`uZ;b?>GQ39MvVPFxBQYmS9pgHM*lju zC3pGV?)}y8tCjaYQC|A=vwi@>Mn96j+B2`~Mwyp0>Rb8r6Xm7P0_zvCV)P^V{GNGT zx5m7oQQykR;#EJN6qtIsM)v$YUKF zsLv>uPEhaH%eWuqeDpl)yk2&G=KbAs z8Q=`#AK=Dyzt1h7qu-l7`_Gdr;uihJeoNfHMmZln&pNM{o!_FbJKSLA^u^DoW8^Q$ zN6?zzXZ~ERx9|L0HGkK7hvpj}=DzP+IK~<3_jP3C7DisiH{8GZac;dC>iY8!clXaO zodFD?&U+d6t6bQ~OHS&>$)%2*PZ;$d7!Ujyx8EeDQSUd*ctYheMqYAKw?M9Z3GTX$dcS8M!Fzz&pXjbDsPjE?-Yb{${Um1?)0oA{FLw7I@V)9$$Its( zW8MOFen9>ahva5PK1W^oTu9w5dGF6~{e@7k7x_qcKa1x-&0YIZ=lub9KY{a*yWXJA zPsxQo%H`@m-Pyw#E>O<#@{?Tdz3NdX{?YEf?CaXt-<-UUe4bp@$QQ_!@BuwP*{yf| zbDa&;{RPQ|FpM$Oc^OY|KZQjjFXLtISFvT}WxT`v9!`wBjL*2gzy~8Q<6G{Z2Hp8w zqTa8J`?(*)gpt4hDX!kdPv!i1ZavKN9OSv^_3p`eex{or``OMc>imM-7O#Ge%STb? zD`9v44p)++uS@jH^(VP}0^h6N$GH2CDDT-F^L4&PZh~WSOCulsS+0H=rLN~=-FPzY ztf5{nL9T{f?4!;%81Jauz{pEZ>W<0Hj+~zu^|v4A&g1mwIb#^dB<4`>|7GXFy2+UTO%(ysXHZS z_5Z5!GozmY=eWQupOYr)^L)4Y3H7Hq#{%orcdYkR^EaHEoQwW`(C72`%<|q}=sq7E z^#2lf9YWo||C!~d^fO24J7x5L?EIEKV!z0pV*-;XeWi{5PRWJ#%%8u@ynoO79&%Sl z%Ezgz&*_Ho7Pe8&En}RYu9uQ|sNd)JJQtO#$u;X(>sj+N2d-!3WqjX$BwyaM|17!E zk@D7ad|*8}*DU8e!-esDNNuq*S`hM!yho<6sD$#aSt z&+E|qE$_(`S1CT{M*TzcW9m$Ci7TW2q4~*y^`(!w>f^!a=g|C&I#U0RYpZ^he;#>_ zH`qe;dY*I`pJ3_xxql8?Mk_xgKf>{z^Sk7pYQD9u>|gKqZQi{P*7;0%o^uTG-b8l1 zKX>GVD!=RfJ0*XP9`va?QLgp#l+Q0?7b zJ^C0J{fx;;zug`A9QO-Y#1iWL%6T@pFZIuVz>EL=3qRupT%EbxJ?i=`a&uhb9lq|o z)koCm|GDKKIJYzUJx4EIp|zhkeSV7l<*|SztY8=Q`}L;Jud%OdtmBQb-$V0qe%3sF zo@XEEKL379U=nryobjt8<%iUr;T^_)pzAY_CDi@B>iG{Zx&BklAJMm;bCUD3&THTN zBlSE#$UToMtYH@isMmYd^FuGW{!`6Aq3^uv-#V{-^N~+=zduaj6iQ5LC|4P@#4NlRMVH|aTGXHeP{2=oSJL<`LI$tr?*L~0F;{kQQ8OBRk#)^@*ayLdk z#<<*{bGG#|*h^N(TYGu`zV_4%d9mGBxz zxIr)TFYwB!C+q6@R=)G=U4H{?{YH0vi@M+XuXFcvWH~ z9M>rI$9Y%(l)6^^Q*!-1^Imcnc!{w+=kMA_iu1@|7IUc2yZ6~{p9{P#xa%3}e1SSe zEMe8Cf5!9jpcj33iC3uC3ostU5XO!CIemxKKJJYDt;3EpFWyUeQO|=*LGcfN^rkSCp4N z;?z%I7OSjNH`Xgi4r_RgP3Cos`E7C&9Flu5@*~E_IN6b(bAN%$9r-nVZ14deQNRDq zl6#&jO#F6tokN|kFn)(;pX2fg)cGp8F$T!RjQpJOJ6vP=bKN?+evI)HrZH>ed!O&> z)P9H4`@5V;%>Hh7eOYymf1fk>Mb6F_J3U|G>|*B+xoh3uob{Ht!aIDxN7VB-M()u5 z1Ha$(m!r>`(eD}O;>Q3+Fp6MDJ3mSto!?3w z-iI^v;DYyKiC)gxhZlH>S7_}o#{DFwFpavu65|!DV$I0w+%>t2YxjO!;iY=t7rgg+ z{Tt?Yv4>-v;0%|z!ZqHbu77AhA^Hzv1WTyvTlu(=Uow7&=bV!VN1W3bCpg6!TIcz| z{gXf7p2sPkq3%B-xjN4eLx0d+>wJ`a3e#A`5?1gU>v)4r)b(eKpYGYuiu@g}jrkGk z>GiDn57g254t07s#|2(+ZkKq4ehi>>z7g&xF@ssu{aCr2kuNh|#X2^Oe2eimc5rCq zmu2_f)IZNTz%h3CUhf&-?=nBSXI^sFdiuPU)Lr2PKOalR&rcbzaKBF9Z9J{GeeU|X ze{i@2i?~_Jz(n)boAhBtIv&H1ca%2QOK#h`RnY<8|z#^r`a+`blCLJE-#`#>cou zpV5DV@f&R71Vj8>NXhrQT5!&SauQ5;Wze{d}4RS3be@AYMU2+2>f5o^T0~p2&_F?TOK`x0Y zl=IO0iTz1;E@`Y_6?Hy-VBV^GZPafwKENT~8u>@Yw{pMb_Txj{f0FUmpL4kh*8aka z-;X-^1&+Sl<<{u?3U{5r9CfUEOX_&O%+0%?jvsZuK62;W&tVyLA0_(8u&?t!@79sN zbo~tV+bHup)Y177&>};kN!XF`i!8?ZzT6sE;qtC>U@y#0ye2T!9>^9 zDPRw$sOwqzTOsk4&vA-?rdj5>7C;KWH z`-_pwpyaNNe3je{N>1KW-G7f<9|t%^oxk}S*Y^U)U+b=ysPl2g2Uy_y^%}c4#3`;& z*Gp382CeyXWB#G}RL|{igh}ekJ{nxNQSU?dpP^10t@$IP|3mW`^>Z-C&$%j|vX1=R z)BX1OIWp_Jb2$Br&f37)#WlX_`5V@cu>S1p+`8ev^v?As#`-zt)l~oI>_hk4B{#)5 zxulh6+)H0g`dXs&Wu6c7AMloW^F8N}m^Z^+>q%bL+m*lh%bYWY|AxCxqdvbPxxt?K z8My^+@#L?#bmW}=Pm^Z*7-lFc;TF<-ZdKcs_@d~A1 zy2b6nt^kq>^o+i&iWLF=j!{hgg2=3E7qOXH$3Ik9xnEf8_3$@PwSq)A>2M zCEnpy=Bo(_>NT*11B`v6TR(?t`bmad;lRACx2t}Yb<_XE^-;h9>VDpB{*iTV|FK(V zg}T0%@v6#Q(a+6}{w|o8#Z&SZd(ICqFM_+)lf10AD<7i|Iqz%Lmp+d}^Hb`raD$$i zJ9l0G(7c~Ir~lN|yTTso`iJIA)bHUKXIS5{UV~g`&%9n|&b%e+{j3?k#|_GP==@mv z{b%mH##s92FMb|}<}aw1!UC3MoOP`A!sHTr=Jh%i=G9Q|zrpwoHnC^qZ|Ju_cjq&~ z_BXxwybjIZQ~!#(5sYJ%b*%Ny$X)E2*XtyhmqLABS;lji$EuOPX1tCK?BN7YjPtwW z{u=Lh-1EM`2c#yZnh!`l3}FIw|A*$KPLg_gEE@IOjNhW4eOmi1alem| zf9=kth`Rq{=hO5t*|VSYzj6K6v4u0#{b!agU%+eZqRwv_KmWIGUjN@YXQ=bnVHPP1ul*H>33Owx^m|?#}x+ugBwp^3ibJ( zFz&?*yu>Ti^^%P1dKt#En8PyGaE|`}==u!ezV(XC*ZB_PLmc54C#csC80&`_k6;v2 zn8hCY{*&9!CF=gHdI{$1e3kJVY+)NasMo(R*3TI4$BJ{2=MiFl<-fT7j4|@x+;tY4 zI7HolkoCeC!6c?oub;I8$~ z?p*zI^xzfh^$yKPsT0FE=CIHCG}o>Vy`D8ctLBfWqvu~x_Y$u#Y^--^zE2+m9O4vp zKQW$T8VB@oYxGklSH&7$qpn}%b0VLcFz1pq&gam4@V~p~RKQzYqV8wS_ycay_di^n zIF_-A103NBb$ywi-ZQ@@_kdgU-MfC0Sj9Hp;sn>I`;qzCJ@b#`PXDJ{{|wL3hgTTK z9P0JUjMuP^O&sA8_5736`+e`w{71k4_qxK=hq?Z;_@2L??o-|PntB^t{Vz8z*1p+Y zH!!qu*GU}W2)p0n?)S0$t?s&tYusSvf%_Qy4(em>JKc2=%Ukl8_%8A|`)+qF%KvY$ z|2=N}4marK|J!$o0Sw|0N9g1Kk9LV={y$(gsYmcK_${=U8{e}9+!eOey={wDeR zvNrs^J!SsBl`0PSds0UDz~A!`{ABmM3#i|R+PV9CRhn4(!R~s9Ixo2l_p_K&^Tx*f zTh@{Jvd*sj>7Mm3$z7ozBdGWD-12wyxy9TM;d!9$e?#sOYviu6iLLLW^Uv6q2QM*h z>^H!85JNliy8gwEygWZyf7kO1{80CNgBZdv>gRoEzCxWU*6`Y>e`wzO!(9Ijyumgu zagBOEmyExu^E33H!#vhe@AuHWbuJU?%eg)n>sj+VMqb8;d)7bU`@DcfTzlMmvB48r z4?Q2`?icyF)H8lQg~>%QF7vRA6|7Z~A(AKi0XG*uOrvYsTf=-q-8N zdnD(g-y?lK$Idr@xcl6+u#KJ{;l{7Ai@LwJ^Pl$o0?-93nY2-_cH?W6&9O4L9xW!Z6%QNHsJa&EeyP=a4OMO08PR0+-%RKQ- zn}2A(Z}aX1#>+|$|i2J?|U=YhbH@^B&&XW&CRp9OXr#-(* zsN8} zBi(av^Z6Lb=R`I5cD_5Or#e4*USpoyuIDAW3Hhmd-s^iIpYglN{;tQ z=TnRqv5pOFVjD-e#5-K$>#qOEx?7ab$;$Y=Jh!~`eL}ydSd;$wxp-;(e0)2fUpG9n z^Yicd{PeGv^|k&y>HGTn`&z!kKd zLIrDhZG2xyKEeGIre9Iss=IH0lB?2>>|??813nu4>iKnYjaQVHeso>wPrr{={>JF% z(7fluegEaLjAPXO96Rr0-T0pU1XRAmwblQj`MW5;KKwXm1N*4Y=g|BE^%Hy6KP7i@ zqwVYxAo&n3)#u}N=OgqH6X{3xqx(s7KZ`l6;0?C0jU9Z`>K%GM zHO}!G8`#7awy}df)aUc6>%DA08~XI|JOdcQFvd{t=c(rp`MER339j)TA5r)Js^{Ms z>pvLl`+to4{tRFU!>Ic`G;h_78uf1&Z(byQn%0j0S=A) zgmK-6wV!+P54gqiAM2izejaan-p{_m7{R!VU%7q9Q1Aa`=Z9n+wSJ6iz22Lix6V1i ze&w7K#(BT&{EVD8_1izeJ>L=P^FB0RJh1+A%{SS{uJgGiH^MPaP@iXq@hdJaeu4TOi z-@_~8`#5o6{+|2;K4R_1xzCAyKi}rvxl|84pMCSE)IHm?{;SS!dHyG=4=>j~yud5; zqkdnWdp+5woTJ|7rLoTd;}MJ+`+w8x%RYnbFKp~P#&{ePn8XxjFpK(qdApwbetA{r zxvNgvcrH1{^H?yR*W3E;d0FQp@4cL}b*@$8eBbo>*X-*CTi7=CduZOO+oAph&wl)i ze?24P7u>%>KL#*@Nu1#v7pT9_-qv^L{#57V<+&W|`M%rw(>>pxUG+oM2^;U{ETQ?Dp* z)y*39?-_r@t>ldT%DG&U3t&*@sSO{Rx9WzC`tn>t^c%*g(SMxr1g0?kit<+7tWjUa zbKKA4;3M68SNSMs3)S(Syq)jP=c&$5o>znCw(EHf$PMupN2s4~i}5ygaAM?ryf-0C zVhS^u!y2}+i#^o+9J{`}_e0hn;n?Ws(7aW5YSfqU8TaQHtomRlH3LPOO)rWpKny|V;mEx^M1wy7{rv3?=n8d72e@JKA@NPF^FM|pzi0` z^{;-OJNE!4Fps*QW9OxhFzespz0uD(qmhg4w=O5?# ziR{_W9q-j6Zsk4uXjez~Z{@s3KE`+g)7Zx$-s1dcxOG>!{h99iBK+chD$J{53)|Si zF6#YQeT>OZaJggtK;@@g&v5Zf=S$!EImrI4eOTx5zE&^wlihon#tddrzi$!7qZq@y zksmTX#|=K<7Egn&k1LE~922PfId=UN>!vY-v!C+f&-2^7I~VJG+MHhpyF1Qv!u_e_ zaE|(Y=rcaRAuf%4i07EZ0v551Rczxej&XvzpJUfwvhE5KKi!>w5;K@Z-Cu$6B9^fH zit<+7ic$a2e3Lp$yyWL?87tUAz5nMjfBcgDx7GZFvEL54AxduF^Lp9&8`izz*GGQL zqwYgLFPZ;HofGDrqt077ANfnv{RA10VFq{gCw;uG`iJ)Os`D3|i=3lAw=DN_sGrZ< z`R@Drsm`y)bGgALcCe4PsGr}<&TmjxuirM-d(-oJpVm2#js3sue7)X?b*%M{otIy~ ztoijzgzxn^eXUS_epmQ?^w9YI^oBYQc=A)-=j#gf`x|FGfk{jm`5@yV3}eQ~_ZXkx z9jt=NQEdW-*T?Y+w%uI7HpgvFq!V70wRk*w{lcbMb{XCbvoTEG^>APc`=b`yF=c4O3jQY)601wsDLrT;n~y?)uj;_xZlTCbm%b(`LMjJscSM-Y;8`k9YYv>h+&{y}&29{(~687{)PyW1OJg?{lxW@6YMyn$zd~T>IR&uebYgC$R5% zz3$xG=kxaY{QoELy576D@7vq=?fcUEcIf;3-17Q!e`tU2>+=siuS4_i>*xEj`#6jj{U=fPe`sFncB$XPKI-}%#*dZ1rTz$~c#pcDL-PyjEOE7?{-dnRd7t6AasG$q zw+GfAs{AQ^_>6w?j5qNXM@GKP_|1{>`upwBYyJEWov-tU)_a?GC!o(!u8(~_vW|G{ z^qp2pK(?B<`Lm5-B8VrtL%VRBD3-&$ApulM^l@7@RNd@?-G z9FB2{`aI=*D{+6M^1I%@8}cn|V^`Igajn;v&&NIYcdZxWa}dWQrZ9~|T;LM*`p2%< zR{iW+|84%ACnV1^$2k_UWIRtR*CM~`eUQ3`<{Nv~FO#bsDIfVH_x(`8IyUem>F%H7 zJ5T%M#F}>_^VNhN<9!_B==*5i+GpgKxO06#IcIfTCvW=v70>k!*SNtg2IL&n0lb~> z-jjEGei_a+i#aS{8M~;C|K#m_cmD78{QP`xma+6pUA-#m^X`)y;1I_+#W}v6|IQPz z&gslJ@8_0p)8`b6pW@z^7QS=0CnsHU<300IH%h%E$~wCKbIZ@zr}vZHx$Np+az64G zDErs@jmUkBVH|b-ig7;%FlppFjE``MD_r9SJv^TPhA@n}pJUfgrT9L?JQh&*)BI&F z-^L!^;_J>!A05@l+~`N=N93&hhWn4W#nVr9=WvGSsQ16`yb$w~n0lA>4qad8Wgq+Y zBYFRx{d>q=94X(X?h3bf^2^=x();bc%lvH5`a^Q#BjuCqtARc28~aVa%Y1du`gwAt zBjx4Ki7oZ>wQ@54zLuALi-+!C=81ZK;?vycEQu*h<8#k%(tJ0!ZzytJoWr5 z`qF(zjDDY6e#QCAd$jAk6Tg!84O5s#{d}HVe)B7M-{{wm0c>F#^?sgu{uO=cz9UAz z&n>^={N=sab>5MTdtOnDVGi~4d8&MzeiE2Gu)o(e-&)5y&tvE7pYEP-18=a2`uRS$ ze2_k)n8yMxafNz6Pdz_JU%Ky#(eHE1U(%<%7rV~8`5Eqg>tGjqsGpDgy36uy-krdk zaz47xL!aNS`JP|p-mgoX;tchAhvucOpLzid8uhOjKUO|M{U|1|fO@}&=F`;4V0K6S zGWV-^jdj%h9Gb5jSU;@tHLjaRKb{YA@6YywohKi{`}Cpjba~;fS2*}6cRj)f`TP4m z#*KF)&OXlg@1OPiyz9F0%^&c+M;O{TrB0v!uYf53e*;~w&)<7h=I@QF^7lG<`R{La z{*v*HvcP|DTNL^4ZHsu18jP_mY2pCieOBaPf{mkKUmCdF_fnk1g`&YvKie z{&a~`)cwvFPxJfEEXwci#Vo&15ast{Vl(63=Qhf(uf%(Pp6m7X^@f~$KleY`CGJsw zU(~a1-6r;NfG?YG{%ZDx9h{-AfB9=%zKcDaqm^%S|MrRVe%9Z&p8)wNCNPb9za_@6 zQT97A^3sPsPnoCdADZ|4TKBx-IKZiL&1+5gMVzk12_{mhS`od1Yx zecnsPH`wL542@fsp3eihv(I#&YcF2nd%X{gUt=8`uPATTy)o+d7!R<&2Fm9^_kZmC;J|)v z$xm^Ccc}Y6VSiq=-xk+8pJ%*;*}QwsIegiC@U!@NfMcAYu0K3-{_L||KTT|57j-|4 zBj@wK-Stz%GFDLc)Bg=FzbQETztOouD<3AG#Kjvjf5?8N|MY?V%lr{_#<;*c+@RFY zvQ8e$Si=VD^PZ^sdcMx<^>@`jXWdKe;Rxk@xaEDA;M{mWJgQz_)zkeRT3?=i6x~`RalF9Gb5kSYPsW<~6W`a$fgb>+{NRjycR@1+Vc2_55DZJ%<4f zafvz~{LL<3#tL3z`nS0I8GNquqx2iY)SmrI&f34;ujKR8FW|oOtz1L;=A7l+_4+S6 zU)BloK9sRxydRSHJ(GNsbK18b$+wx;#UYMyhWfnkWnAsQW}H`o@iZoQo=M~Lb7($K zog$X7Y1H@sR`>b6#X07Fn;X~rJ$62%`dRMiNAeMJQOTpszvKEI&yD@XxSv+}6C*FV z9C^uE^{eDM=%;SNs9z)3!~nUdk(Zp*mz-7KdhT_j{=3aj=wIHe;*R=bl`j~1$w__5 zS@mbsmG`_#U2DI`&flt+^_K-AMw5Vd1m?R&vpF| zag6@*i@(owezj-5PVW8{=eN{5q2Dt+H~Mcf-p4tfecp@rd+hv*_3v&GC5jDF^f$3NelcLLL>_xte7@WdD;0R>dLwcu9vvN zHR|=>^!f4M;oh4hrZ9~e?4#cQnDMRLuef^Wc={#o`V61z{005*>UXtczj}X%=B;z| za-Jugqx7lQd)fIx)`?*Pld`^A@O>?xUnc8&8r{hjXo>nP7*`b7Ej1N)J@mw7%6U>IYl&nwG#31$ByWBTnez$ub@*K8Ll)pZ(AIUeEcY|FV;0X13 zEg9dS?0;kIKg8!Pf>F$&t}mZkIbV4ma=sVLYZ~(dJeLT@Fphe?W9QSXdyldY?-#xJ z`{&sC!h!v~u6&8UDp}b7A@D@`Q~KDqAIYCH&x2PO z#0cv1N;6(S+5e@n|Na-da~k3;u29#P&#ml7o`;-olX+g_^V_AbA&zj2dc9-k=d7Fm zJ?&-4rL!D&h4CtAsUdU<>v08!|pcIp4f-z7OOoU*JB!@*L___rt=2ftPE$pH`uQB5bl>G;d{YSpgy|*)zb4oo?K5<|_hvt(9)|Y&mc^NEX z1+P&*j}GHQl=F=n=er`8|9$Sc$a5$>QGR`3Ka$@t?*Y%)j~6ddpI3zOB+CA?#{O&M zZm@-I)b)>@@3U^~_q*pO&#h+kf9(9|z*4t#|mEK4eImiGd@Pyf5X^+gn#Z4!#Eah=O4P?m(B0{9NNZt9&3KxSnvFgy7%6P0bHU!54qpt{`iUWA=clwpD_6ZrZIQ1&}B^5=}pd0udBo#*u*bLZc{8{DAoC){-T2&OQNuRCw`(J=Zsc0OvHi`CDo z%2!yoigjcEJ;wWZkLf?|o~wR-LzT;to8nsL{fWcokKf1V4_epYFY_nV znc@oNeJaR%q+Y;l##`#V9*n$v&h-0vYP_H4jC;|C5hK54-2W%t`yRpss`gKgo%gV= z7kzkvmw1J`za-;%9OK;+=Toeo#tddLhk8HxmU}KmEMoQJ;T-KFfHGJ){2#%ctlwgITN@{mb7A zc>CFIzauP_+;tVRzujGn^7qeF8Bcu<_c8Rj?mCK@GWSvb`>E0Ax$&FNceYXf{3*$w z-?Wt_{=BD(sRs2i^rh}Pirzo$t}pQcPxy0^9`;fGykx|mkIeb~;|e$YzD7Lf*ApHb z^K*KJ=e(aDjPc$iQQpTs*Ydt?_TXnleKMkJC7$-P0p4afeyj6E@)R#V&^t-~f z(f^F`ee+iC!KfeWxbK-Hw(#^%yYa@Kakfx>U7YCo6E$DwrM~2L)$dSmh`aK#j}&3MsNA7#M@54(YFLm?Ouaj%w4PF`NwQIiauSLB%KH`Z{f5rU=l{+)?l9ReVa#sJZ zDt}@0Bj;M+d{gA|N6x2>`tnnIU-k3bcb??lwE2hjduU$HMLcx=%jSoF)qVfX@B#fp zH?Hd+JAcBur+9`Qqn{w-X&mC>iSjYljbjp1MnB81cIO=W8fOf1sLy{z{tnl;L7kWJ zed`}Pf5EjrtqLgJ0{;Ka2(JU?27QZr||v=RLRY3rzeucb!DN z-znp3y!i7j??;`VJ+u5BeXenXXMe%%L-#M^S?-7WE*D0f_mDd@pWd^+k6dEU`~|to zJ@ajHXYB7By~ciT$xm^HTh!+>W_+UZt0U*fGW2mqz_0eYUWT1FQdMmM_sy73)TS9me(fKJ|P#=MDWO2kyPeqV8AnBl2UM{y+B4 z2R@FX{QpZ^AV>;nDKtQU00HCIQj#=n16E9J3N4g!v=Jf{FKO=D#OBYDTp)$2hg6MP zHE7kS6@$N`QOlPA6{A!PSRiP@2vGwR$XAL+DRN-NAOU{Q%=3BfcIS3zuC&rB_kwBjq3?Q`$oeCI<8pmU(6|8(uk;b$4N80}hOY2QlN zg`hRi2-J+nW?#3L?AO6h2Xq6p3%V6L3N_<h@BEDS?+MTn=tij7pCryMe7+UhXR)7i7yGY)MxpDVrvH6yA3(X~ z&XeBfRHREds?}AR)!u898zFqd~5l;tn1GE#m5o*TQg}A$+Jtw_GKA|G%Wyoa zgl3?BWgbo*t9s}foVjacHXvDmeO$Dr%> z)9p7QuC37gt=ztCP_un^!fqFI1e#;9&%BTQO@Zb>TcM`^x68i95>Fm@K6Dz?X1@ua z?|?e@bN#cRW_=HI`^~85R%oADf1|=1k%vvt&Co5-t!3qW zGhc6)eZM81D0nM$4fO4@m-5#kj`rQevlgG5_C4Tc{`iyG!L2&eXI6u@RQZg<>W!{sor$hrsKg5$Jl0eaUY*uXWG}v<=z6H>Kd_(KhY(L4 zGy+`%mHM>fy;+~PdwUt5Ixs$MfObMRLS_6iIMl4qJNA4$*_LL0 z_O-pOy$T-ZcuSyjpbMa8`yS}_oBzo5-2q+y48NbSgS8a83~JVYQ=0bOu-^>rf%Za8 z|H8)_&%Uu6+!C)n#4$wO@qur7h42=+~J~aC>+BAL~YFHu}Xh z=ve#9PQ*Ka`SLJy8_uhi{e{ah+dBt#1<*Or1yIvI1l|f=3vIX9FTnZRMrax8SqC-! z+w7OYzVe;zb;@k{3s~|!*8G)Y`wD0!v<@1DwnEoH&Gvn#Jnq?hE1%_-{iO!^m-dnN zh=H%Qw9i=m$@XpVWA3lgPnH>RL@f4ib^n%rHUR(Tx|5uzZL^)9U>+>%M!U0*!G0~Y z4cZPh^C5h!{`a;07Q|`Bv&E91bnP>K$H$cjRE}F^IDVP=`ERq&Ofx@Ou%80Wf#yRC zpvBM<=vedrj(_g2w*Hxid`iCOq?zCSZTr$Rzt#Oe z8}sB`=peLhyZ?OFw9kf})gGVcKy#t_P&0msBhQFqqs3n4X)@23erL|>9n1OHGUR=% z_LZ;?L2IB9s97K3WA(qU?KdD!GoH95{&em0kmr2pG-!b(|LNLy8vQi;N$#g>p=SQ~ zwS9M*@uX|NIZgj!zXjX%TDH%#E;&{~X-Mv;Zo3+HUc` zukG{Fj7RLJVY>p$_Fb0xY{q`G1=tOc2y_&>XeaY! z(8}ley;+{Qz1X*6JJVi1uf*pe=-XxA`5f14BeVMc*>r(;NQ&a-m>4GrvD+segy9`5q~x`&r+XK@N(!HXq&}8`^ba!E|Uw* zgO)(cpaH14f7OA!7XBwNSHtJHaUFZt(ZU)xI@gGLDq4;KfAb`8fX+c0?qk{e}22M{SdUy*xrn9r%|5xcP#!T9`Tz6 zJ6k+^%YKR_o++rGlp}d+2Ve6t=cx^9)?c=tlcs(C80|}U6Q3DR8SEE87eNEiw`$)F zKhnpg%Xb#jY&jH_8_GR$D02+XnL(O=EFT>{{Xyk3OUx#u#pc|kY zp_w+()_ zAII&o3u?B{zV_F-m*d+Ae?3sC?^;WHbb@a-@-b}5hvaRMk+)3C{*B~zUEc#9}#Hj zD8Da*n(=Ia-9~5^v>Vz3?S<}d+xH=^5$MK)_;|V%S~iZ~w?em%=l2;CSk3zM!_Ode z`yTptEdGZKe-d9E;)@vZn(=iT^^^MSK)p_?;=BOu9pCd$u(PJ!k? zbD_rO&RgAncjcPp+3d3|@g3;)n_t861v&)X0nL1!KhJ`eK<7Zs{K$!`w{N|bUSn!;vRzTE7XK5ZU7=afDNr-Nb>LBGD|C&;ei(U*Lw7+(pr-##7&l~GE60A;2OWk^ zIM{#uj-+WHg?%e@4RkHkj8FJj#>Dq_jXFYTn znsErX??&h#G#C5*BFp|?hwY=#R%p8Z%Pjua82%)_ZHTYmh}Y~tyRf~~PwJCzDbMs< z0y|rLd&_=~B_7FpIX+(ot=UWVJKx~r%P!~$bQEglGZ#D`It^N2u@8aQK_k$p#l8!? z8@d_VW3kV~{Hy>f^Un2{*O~E)oy=RsuG?b22!6+EAAo&1v;tZQHRBOJR{#6jejVa8 z?QkQ?7wm7F6bz90`{{^%l`IuZ$AZb$$7f;1DU5p zkSCc3$UJ3&W&h5BzdUIE9{L}(w9hodpTySz`wd3CDg7D!UFs+G8M2gT`i;ZR7T?~o z-(`tM@}7zOPl3uj%dBs@_93j_nCF9e7zgBhB{ReS{KQ=UH{YA_nV*~Q-?8Tmn0b-+ zW`35TT`Hj=XbrRu+6pzd-wfUZ?S=MP><7RHq1&N(hjIUy1}%V^8&^UA# z)GR*-ag8-zsmB~_R|;JNT?=i4n&s`S?Tg{R1S;_?!23m(@}uBmjaTZi4%@Xu*F!s? z8=z)=w}JOV2cY@y@*h9ms{MBO-vJ$l?u450NgM@;rvw^>wnEoH_to~(;9tt0gZHJ- zGE4b&;A4$f#toaA^|RRtf5)CPAo(yg-Tb`O?f>27z14W%+1}fK{@dCw-TMBw*}v8O zV}Hxne_DO^xBR{n4`;yaXY&4?{G^wktP^>jo(;``jzGUp`Vqb6)=cgE20-Xabg=XaXpYPc0N3fll-+gUggL2nE+o0<$@pOZ4h4w?Y zTkNMH4-23b&}EkVl2Ms~Z{Ac8`-2!L@Gz2y6bM~=)9{iU;cNb4T z>@rW|dSpS@LA#+_pk{rBu>DTxu6O+D6s;L!{zi~52lf-7W_yg)->Ai3hNb6IQA<3PhjY0hXbrRu8ilq&&G>r3w?Zo?!XMPM9{}G8jYD@? z>_-j1QP@R~;Bw;7QK(s-#J6UQ_G{1%BhY2<;c{xArvHxp%wFOyK)l7!66hRgDb%db z1n>-KCUj5zbzu8m=vHXte>kt}pzTmIo-WvTLwlhA?fxpqn7=;cD_#3-*lqy29cs3Z z&2A^`9`Fq>mmX~Fg{b66*XQA92=rpJ;p8egvIL-J= z)3h(!jeR@%Pb=(p*MH)$8-b2O2j9!%rMds@ve@^$P4@XHcMfy`wA>O;1bi*D9lF6{ z-!YBzuoc<|Ek46PKVA5|8`=Z?Puo7vQvY6~zT5DA2)YCM@7{h8<(mE37O%~|1NH8K z_CmK>^0BY&J5laNXg74M@x9gUYo_yl&<0%xZHKOhc0kSi%k~j`z6KhD?r!^SunNq;o(El`hYdwoN4`zM$H~RqEr4kx~)>zu>K)1Kn)6!lCx_t!g zxE9(D-C$|o9`J3@LFf*PeID{w3@w4qvE=hWx3|@Ez*64>-M$R z5zpW6mgn)~dA)IHK?cV!T6{RaFNG%7tB+*f2knQ(vY3mm#rt+>2ecDfItl)v@_gD# zyf2%~p9i27&`N0JDE?fu74KuvZbK`lu)XNoqxpS1v;*1+mFJlb;e8IChnNeUgXf)< zLgo2>rFhO&88iSbhgL#E&; zh|2u~mEa+01R90LplhM+&<)T|Xa?>J$bx1=bD`zXO6YoMCsghqh~PegR%i^m4%!Y~ z5AB3*gmyzWLwliHq5aSS=n!-#G!Cse75fvk1{#5Gf_6i9LgP@mzafI_wJ}56@V;HH z=R!N71Gv6B1l<9RLw7+PTo0WFEr8B}mO{Ir-OwIrFEk6+BSq`*J_2op#-MG`cIW_f z2%3rOa9PlDXeG1`>#z}M7uHR?p_`$-(5=vZ=uWIh#-XE72kTfh(1^Upx=#ceg~p(3 zq3uvvujf9bi6apiTm>L&S0j?5Pyz$CO8!r`tgIEkpVw`h*R;nA3xOTc*2io zI2A{y1~lF|%;`DHkH5?5_vME>1xx(wGabJyj&~+Hy*}9;?;PQDc5*AYqaE)Y=|pbz z<5^Dc-~9L_r*+byZWsFR@y=wY)0ZFRboufrPVVu3evWnmC;0JWoZ*xF_*5r%njg=0 z+RFU+u_>`DFy1-N!jHG`91B0e!cVmDlTx^9?Fr6{Z9e`=oEe_qpks?%!ZZM^O_$2tr3=gEH#)BH$h*cbHw}+E_mGFr;GhAul+Rez$;!}1RiiT}gA_8Y)^-{s}s1vigtUEu96c>Ui3UK;oE+ra|{ z{|R`n!MA{Szv%UIkLFpkWPyc%Q+~ z0*@Q~Lhxz3y#A}eYYg53p8vAf{_y2+4V(>e_*Ua_W{}Q}em;+ zvp&FiI0XDV;GaZ3Wp>vMUW9y#AGNrq`ok=6$=f5~eTMxr;1_+6%N0NB$IXh}!hao=^@H4>0&nLkj zG5C7$rKp$Ke-AtiF8+JK*BJJ{0>94S+rftnKWaBud6Z}BR*ywN9fX_ny#m^VO>kQrrewV@T z0N;lEi=X?!i;y4TkAXKBd?)x7$dA~+p?S8`f%#r8>NS~m5S7pGUBUTz5d3uT0n}Ia zqqD(JL;S+k@S^;5gVW4Uzm|iKL%qcQD)2uT{Bz)sqF!QuBluqoemnR~)K~292cKi` z$2FhoEI5ZPOA+S_^j7zuuk(1QjvwlE3=IgXUU|raj1TVxpNRSjF9nYxPT?QYJlkDHZ$Ta=qTKg^XCn{NA1($z7o6Ve*GljTaPjjo@Y@lm?2qfg zr=eWoKLVd)@O#03WAMkoGf}QA1I58hz>h$jhf+Z*&;4QUAR+J)aOY=wg6EWB$Ey(g zA#Rs!^s6huW6!XCh(C6|F8pEiL;l$50q=g80re#PdRq8)aM&MA3D{a5&>!QTLvcDxb%ROItW#DAyeQ=O7h?*B3H zhl#8BvvB^n75RA$-1#AcfunhYGpXTpeSgWk0(rQcxSr1#`&~2ahyKEe8AZ8Y1rPMH zgH7=BOYq7Hwx_rH^(_6N{0|%RtJgK3>I{E?>lJ|gR7!}-|C0A{{>4uL_&BtS@P*)i zHTZJyRcJ4hf;@B?Gi_QrGK6bz6i$=@$)|7s$KcYuEfykHwUXhoa@;Qddr{T%o|brP2wyNvl1*k1tNxr)I6cocl-W(GCza}#mZ zA4ZJ*=;xYGbdFOKV0uwn^y@M3i_wn4{{eoY(Tf>-vi;Re`GI12sb0j{sK<3-?|%Q&7vl-mkEg#D-+{3h`3 z|6|8n;lH1_%3Gh2x97o!4E`<(SoL!U{fC-WzupbL&fsO>e>Qj(_|eF}`1v^aQ^-H1 zMZdm9T;;#?Qm*eZ@U7t84|0CCVFL83_LJ@8V|*xueKw8v+E0Y-H^Dvto`wBR&i6k9 z-i!9CfS+FQ+~0B{%fZJTgMM-^^EJrxH1O`GQuA_SAutf2jKrp z;FaK|;J0X=?PM6^;jh8_jduKt*c;>Ip;I}Yf)8>$GESbRInB>;+@ak>zvdBF`Rx1_ zw@WVgN5LZ<%rP7|H-LA4iMcHAZUN7_fq4M=c|q(ukvI6yq6v&Dw--DDel~HH&w{xe zKfTef3b99=a(s!wz5>T1>4!IJp6%2a`P>3Om0#vKBk=#6`2QHkxdrh|rAt97PG^7( z^T00#k3Yh^6#VnxG4!hi;P-(SJj(X%;2E@Jul)DJz7_le@ZMjsy~O!d;wnFV)4k); zX3evmETg`Uf)5(~=OxW2I$LpGAp7Ygy0oCihiS&~rGU7Kv*2r-w_^133h=;-$OGoR zU)O%7I;ChAO0Rz13H#n}vY$clr@-S;c02%nbPkuB6=M6%T#Qo&UWsv=h70|w2X{Wt ze&U$8+(=y2>m1aJhDZIn8@%4&Pl10L^Hmxy^y_u_FP+H#rQDfx2}k88_gl=@^5M$4 zUijS{e<$MaA+E;l81~;1I^R&QLCtAA!F)i*jS=|i$Naw!e%?!$h*Y^lE4kcWF2<<^ zFSv=hj7#4Fk2Sy^eqJN4^0NWsgVgIpx^$#?KKhC94}hP6`KRzo;wqlr^&E&C-#@4A zr#jsw-hTTd*bia9kbW{Oe!#{5X}RbR_aSh|6~t9O<3>OKgys{SEoes?j`ZuMT=rA2 zf#WPkhxiS6|1X%!_&NS$wy(U0c^k@|4c`7?<~y`^$Eg7yx`Yj5Rs6wMz)R8pW3c}f zakXD(&-UhLC+s6@xV`wgl;cb~h2!bx1$?Ii``rcL5gZ2tI6i(1eCRojQ;uJ^gBM_Y z>q9(o@Bqd)$^Z0Ixm<@Yd^nq6-vS?W81oJ1 zH11bf#&I@J^NG%1FfXOyUB4E9zl!}x>Qx7R4e}to9sCx9Zw8-){fmZc{Td{$^3Z)1 z=V2ETboA-me|qO}|EYxiS>PGSgXHrH;>u4X!hYm(;CHosw$p7KNA8DxH`-nL$szA% zKe68*q)U|ka1n9UjxVEqX?WMKDEMZyuhi=s@Dn&hxfJK*qy2V4w8_ z$KT8Doip+|o`OGcJf+|b;1O^+{`PPlS%N&XILE#Rd3%UK8HekfPh8cv z3hgNUAp-l(2id+2_IH5C-{5jLBF<6mht?<6LMy!_o>TsZ%XJ3Xei4fk0*^n=U<>%y ziL3Fj*BB4)hJ6I*eUi_(wx8(CM!%Kzn)+TYH~uU;uAr%qdVK`E{Z_75#lg(igBLu; zycF?l1t0n=a|%wsUKjogPRuYqZl1>Z45RV((bHZSHr%O zN>{I)=vO}nFWAQA7Nfq$6te$FkolnA%5gqKT>1YUuKUafzaIQO7`JKI*RR{aF9M$p z{xtZf!D$%OuZczMe-rro!QTfy4tbslUJE`4{e*^b{rWoi)8MCq-v@pK`oHwszk^>7 zehTbQp26|l3{KrZzb*owhkhvWe++yJxU|=gz(0%rDfxK}{2a6wz16Qni@DtIflE9y z!H>kcnUq^iT=lE=L%4mr4q-ocfXCE@YLRW5m@w zYUuque%7$L(+&GrlBPFkX4uaMA9|7vcfkJB;8~*_&mg;Vo&c}Jc|j%o zyq7wXinH^6HkAI^2p+-xLangh4BiVr>%fmFVLz2C*v~Sqp0gCZ7xPu5$N4gN>;bly zd=7$_!p{`=&pwO&_tvw0H|iS%@5ga=5cXZ*Swn2!cNl;0cku4*-g3`5oBhXkGLON} z=ZNd`S*%ayg5L)|Ji~h&Jm`JwC-7SiaBU`UPy-(OIP)0zL*V^c%qJYd_NUE3KY1S# ziTZ|!tM=;U8*H3jj59sp5zJ4P!G1jL_{u&$n}HlhDu}Ck<)6X+rCuArGYtNJ@KbpL z=ckkUy?TB79QI$jfc?vL$$x+sEM+e1GZ%gU`85206+C0QH=ZYntN4d5V?Ui4T<+{r z@DrJ59LxL$@IWbZb-i4@c9ybz|0T?2K6&0;j;F>b_XhA`qurkXZ!_XQ{e$dhf#K&$ z;wt{`bGckOUwat#U520I=dpe4eQYoJyav4c9Og3bdYrgw#|4I;_mrVt2478F#p8U4 z{Ybk!0UoPnz7GBB{d8c`{luu(m%!T${(r=k|Ew_k>1T1~pUZx_4Et|rp6&GDx<8uN zxfwj$IIp=4JlEhqC$7qkKf?u9;sE)P^O#32VBUk>=>g)ZUc*Lyau+B*(bq~1YT?KCh)5b9s|D>T;lv9_`eMM4d72< z{v+}H5d6b94hru9zue&WYo5Gsxkm3@j`LT|llM8J`#7(FJI4J0MGIA)X+7EC5%6B4 zKimr52Tr@Qe*H=FsZKBU(+u!a&S(Ea7juIP|0H_U#7$E_jE*3zo8dg~5LTK4S1C@|Df3Q)Pp@F!ZSZj)X5MS?--GuX{D+sZeVf6ryPSE4!7p3JyvyJ-u3+9{ z@XU`e?=$$b;DZLgJIMBx2CuJV-fOJGyt@ki4gL)Hpuuli&i2Cw4^}fDG584~<{3u2 zKLOrv*l!54{gAeqBA=M+~0dz}zwTli(Q!U*E{~*#^Hb!aU#Lhg`|L z#NfXG&ocP6O>CcQ@Uxnk7a07X;H3ti-s1ngo*zfmf#Y~*NhS^;kh?TL&bb5geEIZ; z`j3;GctDPH{K-AqKK1)44``nH{gj6^&vA~Ei8%^*RP!t+_n!w#ky-~er+EmDoATk4 znoo4DjCt+NHLo#@ZKi8xwU^Ki$>oRF|pf4r#eY2KCP zap6z4mv5cQ5twt>E!;FaH(z(1*OdA3So2m;W9-_fjw44&HC@KY~|Q zc{C|1loC{uQ z@N)1q244x@W$mt9L_+$MH)wpXfxs>aEum;FShnt~uSGiS-JV74@ot z{cT_K`f1R7lG9<#2fFoEsq=w5H9yh$?O|E^FZpMS{^NM3)Y#-+&5v__vUQ@EYVFhi zp5$~Nsv9Wr*?|5lbw2R4=0`g1o4oNqt9g!d=^U>gnGf^_z2l+G2LkGga;{e{#?MZJ zM|FPad)Z&|+ROZ*vfayN{!n^@m&^Pi_sd=`^9ScEUM};8ZiCDGp?AI4K7jZuTfF>3 z;6q>aa`~Qh{A*q=-?Pr@@N)T{b^kZLT)tMCdzII}93M-s_HsEsR}mE#{Qxz0|c_C*xGLRIjJWkKglHZq}b>IWePO@p{Wd=XT@x_-FFtIL1MZ z2(P!C=zL`IWbIM@;q{i|oxIb9u=0A#an2DRInwjN^V#y?qk>g;u`U1G?CC9aVctWIe+OexSYTA8T{ZiDv4Q6#yD?0 za^8_=a2c1({wCv6kI@fhT*@%Y&8BkI{@(v1&QA*p0lJW(D0L}z@5cig^K z^P`+$V;=ZP*njg|Ui;6&zUwIO`d&NiA2IB|4*Ooi{zlESogri1do%0@4f{>-U%tT` z&mG`h2LBoOc7xvo|5;PK@%Mq}8vHllB?kXJc);LKYCh39{M+6*cYvR0@aN#C-|+Ji z_^`oWfuD;FKhDQg|D^K;gCD9nE!G|Ft?v=Aj~Vty!@k6@&jAk@{8acEH2nMz_zMOv zgr9!HPYL+2!9M`*9OI4uT=1B|FBJQ!Ui)&*Cpt&n=xvwFVP9g{F9#18ycT{wYWRtO z#|(Zo{PY`sJ`O%?@K1p|+1~iq!T(0X|5spNV%UEZJYevf;OC!)pDysjzT?f$t?<)t z__-5&*x)}0caHVOzZL$^F#P`-_9ce>Bj5ppKL$T*4L?KR-!%B2;iup5^EdEegZ~5E zInEpZD0s}^<3G;(-HS%K@6!Azr^m3L1m17(Z1_31)0_X3V4q<;_wRJgPf&$>UT0{2 zqO)+OcY(fG^W&XKXL`(?_i28dbL{85=k*`d{3NFn-~W=W7HXb4KM81lBps)`@n5QW zj&t@mz4H@U#~3x{T{3Txr#?%$iFpg2rY!s;+CSYtiKlc54};6oJcZYR%TqmtH-pR5 zJ%wKbE>H0kejT_x%~N7K%KalR=}g%R|)+OYr(!yn3LY^)yT-GJzDbvE`xp4BdY2mUiAy1taF6$EV z^l9O;E+J2$7B1@&@-%AUvMwP{r54_d`pVO(h0D5xJf&KAVqM~RZ-18SFHVk^%k`Hm zgUfT?at$umWhxCW*JUCGm+LYygUfZ9c7w}xnNEWzuFDu)uFJ^NuO$z1U8dj!Z++#u zOu*o>ZsQ#3wU_HP5ySr5=;!?gm+Lt4^lXVouBXHe`~L?&^7L!5m-82Ss=M$Xz+Rq? zEnKe4$WyX~%XJxfTDI_8;YXgDE&Rve^7L%scY(`Ow1wXTE>F`I{s6c{lfC(u^EG*zz1Tkn`^YI?`=`NU27ea3-Qdqjxdwj`yxZXa1ed3EOFXZE_Z#-( zKcOt>I-0=`1CJa0Nbt&2z4emwQ+bNNlzTMn7v zr;7`}0$iRlF1#9Co;EJL7F?b>F1!(3o<1(T1zes&F8o?>c^bL!>%iry9;H zF6$5S>kY!c0DF0Qx$v)m%TvsSe*;{eW-k0Y;PO;+;WvZJ)6Iqd2wa|WF8nrddD^+~ zpMc9#&xQY7xG^vKCAd5VUF>BY+gvwzP}^rYJ;r*%cJS6iyz3#dzP;73kHfyhu%8f9 z5o9@=4W13&XYgs@+YMd{9yfS7c;2DjIAuMj--uJzpSK%au2T;iT-K!{2CqT6y9|CU zc=mX2JYNK_oZ#hh9eJ(6Z-RZ7!8c2}2AAuw6At$Jm+P?E2AAuw(+vIq{4X%LtY5Vm z^?e-n9R}YC9y0xaw;Fu%bq>9?1hdakP$eCvoqU8ZO{L%_;s9*fIo^acKj3-|q1;apSN0K{*GRp-ukB&vl7ABStM4IS@UQQD;>v#k&ZDQm*Y(6t zrt1i@PJSu)Q^fuJzhL2`@Gt8RneY?-qJKQ=iK}?zevbjzzee1z++)7PdF$@vye)wJ z9OA0~$aR?*_)_A^znsU-0sk1d+y^Vqf%z@`XW`f824Vj!ald$8vhX*wA8hQBoOX^! z)*mFE|3_Tyrv(piy?U|DF*hjt)YnYne*O7V7T%%#(EY&ZS2b`s@ylFpKdu+cczY&s zzxrON?Nj4fWwF1SxE^P4y(WfD@38pE_=ONK+hpx&*jQ`rnJ{Q;;OykU2Iu~qC&(~edTw2WE_iW`_yR0{qa|&@4kAwTBDzWVczEG#_=4*`lIK&2`}Ole;wm2b{gF2Kxl8+*=*acc3h=4lV0&3t?*_k( zxQbKm!$jJgUu#a|6|Q^6VE-rhk#$bV^QqtTkF%J#ic@~4qYr)-6ZdPEI@rrPe;xw* zm&O0F&-nW}{99bEgY{%-uL|ONzrZ*qxsAYH?kAMnH_zVSU#|-+{4(Oof25E5v-sbr zIV$gxJBh3O%k|kjeD)M^l{fj_7HQw;xBcU}&ceT8;kOZ2{$-t$qotM18~yzsM|={U zhsyoH(ofz)T=|i8QStKy;yTa9aq7Dk|F?;s*LlJ_h&((%T}CC5@_diQ{$UG$ zlDOZv{RVNr`cA&dpXU*mzU{bPGc0_8g;!a4199Dda=50l|K4D+|DLvY1%f|&E&MqP zpZi@d*Fm{k;pfBP@_nwIXn^znpMQQTh)<&Z`mwL`3C$Gvi4gb8+s7?_Zm`&YkGSfG zavwrW>T9uon7Hac@_n4G2k{0kTkMbA$oBI6piJ0bM%*v{I^wFm+F#(y&kvN zKSx~US-vmU3;!qmz`wp{6Zb23skW!{SsXV@;pdmc)p1Jh&ylg>F^iwS6Ibn(Ya9nB z|IokO6D@o;aaFH?aX#1#o{Qg8t3dyJinuD*JU@C#b5zD9NBzh@o>Pgd_LBSDB>!g< zm%6*$I2FWo{&D^y?cPk>uOHrG@$(RIzjk>_{2$HZiOeU%oBZutiK}?zdx-Q_zdGp; zm7mUS9APW?Pc_FImpn_{FP>K{Jo6TR`xA((e9G@I=A(?Wi2LQUN^@G5_?0)#Zj1lB zE&SIOzEk^mRTO`|=YRd%>vG~MZ|1sFBY5SnIZm3k=~pjtm4CSpnXmUd&V#r5*Z0_N ze?E`6U;Zy4uKdgQQrl7P2I2T!zm4Dz63@clZh0K`@;i?;`0#?;{OzlVt9jshe4mSJ z?Kta+tMQ?H1NYBz_}NKZ<*m1yEtg?Gop3wHFZaoapCEC+{t$(|Tt^oBM~Lfj756L3 zxO&DN%;o+)*?-%Jt9S~GajBcQUw(Qmd>e6+{rR{;JHxZH;(F(3P5|Gd4|!p|Wt+rqV$B^DkeuIelIU1VaT>n--*wD4}?y1qfQ zAo|0v!E=pu&VN|^IP}Fozxa1Bws30%HkumRiT;oQ`_nbY8<$iO zSN`Su&O`X@tMC)Sb0Ny%e-rHGdcDk}oF4Wg-$R$@WG*7E=8ex|-gpfBuOP1SmU}zr zEi#Tj_zZEsJZyk{{C#XsZ}sa=`a{Jp[Ye{b>gC+!CtyX0RM`y+qqAI}NIRk?B> zpyauWxT;s_FFDR-C}Rt_W9+9-!jIfH)eZY;KVv`bTiMSd@D}2#T)FRJ8u)KvUuhg) zo+B=J%1;dQH;L!B#Qo~^XN#X#E%t}q&3O*o!k!0Fm5Yh{<>yM`Djxa0-MHid zT<*gOfWK_V_9N{(^?v4ZKemhybHL@f zC_9n=UlLdIG5J1@wBysn{rdlN7XGq@XFQG`@{JMZ7Bzs z?l_NG{5(%w<);(RGbu%VYx}q#mg0KlGUW4m;wlgF{R`Reo&uNOk(d1Zi@5SH-yfIp z_B#*y$G@4lnt#goabhUe0|_U*>}-8|$~<2k(E7`)51+4_N#>ZQ(CyKiJqM z8QZwMj|<48X_?ze2;iTl#G!v0!t`QFV0^tbXy{PR#xT$Ninf%|7R z>_2C*?|^-`v0n6&#eV#w++MvOW&fKG<3I~FN6;>rPh7<#_xJKvj&l=nX(N}pa~JI8 zdktd$2aEsbVP9#CR|nICN0lr0!)Kz9TJXg4$B>`@B|h052>$++g}(ql@_i8L4>`Z% z{Fv+WU!?i7pZ|CLp63ZQm?ub1P9d)LF9#=Z68}u%x?k<$eudKv=UVM2wF2MJep2}@ z@Z(J449mDZYVlL}2QF9cx0mD5pTOmN0dr8)|!pxj(bm|BASZr~3ttXFKM-MNj(spGREzm*?UzZ<@+Ww4n&FjmHR0R|0?_hUg2?L3i9Us(ce!Nan&waom|rnhhOIq z_dCD7oVd=9aU6*fSNn^6zgzZ~4cb4Py5wi@Bi|#FJZC@SpSS-ZuG<&Sp_2agWpMdE zX&=hS+u>i|?tl9GFC=@N2VmTQt#Fc+}9;U40t+CjDmbhPk+hE~$!oPfU%EH|7sD z;FE^^{hVguCB&6~`M#3ek94EO{(p)4wadL0`$ynko-Z0f|GE4x=nwDVdX-4O0+;8Q zNj$6m%J%Y{w*cyU9eCtb9v|dB&qJT{kMnHes=o5Quqp8KIpTi#@3im$ok02J;ir~z zf1^1aUyk5*&mYGHpR$wtgLxl*32_ytJikuHhhA-upk4ATaliOqCa(5(dH#m%?~|VQ zw?CP&QgeH(2a9TKxZ*xE@!H`}DH@<{!`L#8n=$4&}UUM?d+g#eRUe znqSFt8$N_M&v=2$mFH%}z~>QH{^fh(HQ+xb?w5zd;%qO^{gZZyfXnyXN6@~XA+GC- z=R%ag{~uv5&+nDLoNDfT!@@TaSM4azpP7nnAF$ZJ zf0uu~77^F|2lu5cgP*%B_K(6|zCYUu`_ulx`83D>dd*?vlFt%X<;wFSLg=^u5I@Fs zy4sih<8L9Z@*vOuk+$o!*l!~4m*e3HTGRj~Lel;>7*p%pCRSXAt*`e?D>559K*U zOHu9yi=Q7^_)p+Ro}+aX{5(ut^+S2Cf{Zh>Uh|JS-czr6ig>`9p;XkX3;}5|8T^T#eOSszkdEWaTUKj&r`1RmL10ZS)M~U1OBfiuKLxGaUb}N z#B)=_ac&{*SKps&KdBpRx7a^VT;($h*TG}h^w4+tmwPgCRWEstsEn(35m)_0p3^Ap za@67eapqZgDRJdro)4Co=M&e***VyM(a+yY3lz#;p4UygiGH0=T*V{Lb(DCnBd-16 zdv?OVqd6+?l5W@+;5yDUeD<37Ddl)_!7rW2{>}Tlt|PAEl;6>i{qaHKe&f%$BiLS^ zZ?*yBRU>h~c0c-Q|Ksnc#ZRtx-uO4-e*N~GBmMnfM%>SS6>&8_%X3FRi9EbW+^=5m zrxPW=_%9`{$5q@PSOz~EE%tX<_^-7eZ0wRaag~30?h3b><1C)!AJ1~)e)VVj8?t5yY9H0&kM4a#$9dZGTONc}rwhW@u$|2tFvJ4^pNTmM_4|2<3nt4)dv z^q<;6v35|b9TfAY+Ci~)P^=vklY`djv{CEyLjIRFrN3z-`j0e3iFQz=9TaH?McP4;c2J}p6ln+AaE5j;LpzwE9q4WJCVC6K z!CB6E^X3J^t<~X3G#IT~UKcJbnC-(#e3;L+g+-}$RPmHDsCKEW(1-c>qYR{OJJW~x z#79X<*_KjdvYDywX3k2nnw1*Jtkex>l{mrk7G3ngxr>6q=9cBbg~9Nu6~X4!^})#M z*6G!eh!ebQQDH$)y$!AkE~)jt4;C5kXBh8i8}HBZzF%4GeP0{$zHczfzXs)3H#S6T zSGF{^G;909!0Ne8O;xLda{~(*1cLzzcu7@lb2uLGPZuaQEM`(--J4V`=c*<)scPW5Ccw(ZsCScwss;muul53} zmlrgJjk+|iHo#R?b$XK`smqeu;BqgiYFfz~C2T(0Sj(X#$f{a|pCI*BrcHfgDD3qd zsj6P(CC%Zw6$XifIa3MG&CxJ-0~cvDNHpBc*-O~8L|1SVB*-<%nzl5A>*{JF&9y65 zC%OlBtr?P+xl89Q-PTy6qY*HtxhvXZE=rGaBfpm0-DW0S6C0!p4S8RShdSt%(hrqg72tiPxB+)`z1tjUf)TxNPBh3(JFnxeJ#p4bo9S zb<|?1cXi`c&FB#c7H&{uuh*`&KGKL%6LxitD_0`k1dG&GuQIo7jyAPabHoX|Xno`= zw0wfKG$eXVl0`yQQI2IM@8$J$9B*!HK-VXz_Sz~v9yElnPPA`bpn7Rxkp9#4fZ3{G zRkJqr!cc8-f)Xd^imbcW_MQa;^7`H&HspAK$tEy|lbf8tqP31hoq;ei; zz*kg7tLk*$30zQpjoZ_z;C$}C+@P>u6TRLxP5C>j`3~P0*F$ zsII5CG?mfl>WJaDDZH|lc24e~2@lO~53{9PmDASq6T3kIhZ|bz!%fnlN!%Q*ttZOW zOJEw!bx-7xGl5lf$)FRsDI9944%75O*9ABl2~wvB&Zlw%G@z?W@zEjCPnH&O4=Lf^ zH8&J0Z>p*eFQ>7KnxVFqjv?A1KA#tf%x`Td3aqBuUFH7Z!f?~d@FjZI((EnDZ53F( zupt_p+Z?QIh$cet8eFJ%-QZ$ZUv?eG5Jq6N%5ZQ=xGJ>TUK+JcOC-pNNhysFb_>-g zlx!(-&-{|Ax)xUpCV03t+Ehim8%DDPZ)j|)4_?_)73DTeaOI5-Q!RD8|9kjVI$KhE zWr<-+x0jnoR@2cXSltw+PLiky)jP2I!p2ZbUAQdFhZVR-tLr`8o1MhQu4Y#StBz6I zu%a@uwJkhpwjSVXk1-UJP=Y^y5_4Ky3u^})c z7;O$D?3T_5(tl#D%Hc6B7_197PysTnaa+iElsrgKC~8x+Tho8u7}WJK&4>chzSH1$fD*VXCyp0eV$lQBFPZqlQ0@{`(z+GuT6UF|is4J*Yn zZ=?RDLsRvt=9YTzCs&1=nyHCsC|c3z{-j>F_f@qtZn_VswY4cbhTe*1v_=M+!jYyx z5hh~E%v_|WbCh8+qHQq_6zb|iD zu_D}*$X(#9!0I5ggey*np2MjKb{_laHu>g~GIU&{&g#8u8qQNq zzqIz6a8Pfe>kF&EYHkrVDye2jxRa_T?4)csG^mRD_ZKo& z*_N@(J+qNMvx<(8&0$)IX>3T0F3Hc5haj2dBtNUKQiq$XX>Scy@w{0+bG3?hY>u9^r0u9}YtWx}gE3cGruc1AOGqm6M0maWWvB9T$|=6V{kR2{+R zHiYI;e+mQ&Y2Go9W}Dn@fxxWbil(aiFds>%50nJCJrIBz6jZNPyK-|~ZFM*x1BR=s z({zY-Y&vkNkln@!S1K{Qn+4TwQx&C=F?l?a&Vthum!TeqcVkHYq|iX2XD&~1Nj6jf z(p^*^OZEvADj#~LmqqxH=KN}3)RTEVM!4OsqVYU&tP0|+J-Mapc$FA)6K+FM)%dl| zSa0yURWTdKM{!G?3~6jM4pT-h$xuyRla2M}a~biE`AKp!9U0~{A8c81ZhbV!!$P!) z4i~ypsK%F%Xt9NMF`E3kw@Y?e8Qk7{$U`jHFn$uesHNTPs8J|+-$(#Mt z#HqP>mj3IVjGLc&r{w0R!62Wa2lX6MKBc7ViC}7HP%(REgS01H<%v1D4UKTAlTazb zV@9X?uCc+LAD0=;UV^k|xtoIr8zh=c^>C%e;)do(BQ5Ir4N!)6Jz?QarX~rl{;R4= zKD7aNCKx0l@Ve6NZ@t_XsO<%lZR+^3aed|b0r5F6? zx6%?ajq#S_m@XZwRg^h32&mN{s->PDdFCf_T<|sbO9~8E=;Y( zAy+q4*V1}JV^d=btts-_S5e~gYPwuWlZys52J&i@yCSP(U1DoJo`>Lb?m*30_;mFkTJY0@VRC>|b7o#lOO#3t%>U_HW0OD?P4_Q~ zsI!f#I*g<45tOzF1hD0dV4WOTWNSH#QfIKL$TBrbB}Nk3uAcsPm#5CRr~}j4DoyO^ zpkAw1xLxO~$&Jm0C^{|HBadqrSQ@2;%K3FTlf|m1cPMZzxD@#sMCkN{f|eN7P_!zz zxG_pIC~{0|HQ`Wl$_)?H4sw#4Z0AJeZdZDi%;R6uQXAl;!#l5{0idzDrD?Z^2>*?_ z-!$9DXFk4QV||6ciB7Sau%882&?*j}PRY5Iw4_9=vLhq0&si#Y=KRS)TUMHEp4By=8fGbyIC5ntFmFof(Dj z%51nbT^rEq19EL~360E+O}e99l&q>+QA!L8 zsl}+N87(bU(W?1wyR!e*YN6)M=Q_M2q;9PzTDvV<_6nSG`McSD5UFl>=W#7k(;AOj z0mcR2A}WbZ7B^3+o(>) zL$y0*xzuopT6%6=5o~g;tcagvHfcPgb0yWrbcAa5o2D!cVjVfTF`wGKS>m|uWQLk7 z&K)RSsMeQ0^co@ENkg^KNeRdj@P)~NO4T9Jq1;a79MCtI)J1hQCak)8jHAMg)a_M} zW7*!jODadazfqOwDp0a%s-nSy)}X%Fnlv)@IQMZ+jFK7Ub9{B|!~8Vm6oW0W5-1M1 zff6&oq(7Zp#7jneB4K9N+Z41G9iW}jHD0S|^iENwFJJ9uA|VUzE(a>lV{%|58lkus z<>%5$E1l3UZq&1{MC40(I;qN5O+z`S1?y;#Zl|Cl4WES2j$vM47IUg#q^U7NlMc0U zGJC=DL;*ag%Ld-bBwdK33i1-WPB@})Inw*38r--y1TOH~H`T&KJzwRKf?O`B3_Tyx z0~1c|jBwq%)l$BOFOFO@hNMs3mvqFmfa}xfYFZ`dV!LZ~c+fWi1kbCzD%_B`s(WEo zl&-cVPamYQuxczbN6YMb2F$#T#B1tQ6?O7zwi32j6)dA`rw#go9!)r#gKAt)o*0Vb zWIptMr;{9^YmRjB)pCBAC{J>y+rgYBCjBPtspdxIX{VHP23N=9r)f!0-@&4SQ+AYw#5~xV2Xi(&1B0WtXC%|kL#SjCd+_eIp=;X7RoF3Z z(@fVA6V>-_;~go~GLpU{r+PIVb@dH}QVFl28gh;6|Ne$*@G zy3^C0eB@%4zCA!yg07&_d@sn+B^MH;Xjf|aFhoG@f81UDhO|1mN2@kas|6z)7A>re zrYEmvHgSe+-Kb&tYMKsPw(_P{&rNtm#nlSFivX$>uu`CJ!_X7j841%CeJ7S$l1^Mr z<6(&wFRJuj08>}qczIBrP}Z(&2sYD6P*sy&$yO`a=sGybvsRW*qf=^&&HUEEg4C#< zi3jHG)*{p(=+~S5(!~4FHr8UHjCN13511F_!X12P`^5 z+eTTv$Th>y3l+_q@}ZskpZ{8(?^xvyFLE`G`&>Y|j;d+xh?a5zRbfeMUgZj^-G;8&&bS}!TJ{8m3>n@n$TOAPL`Rb-xed`%UUkcFITAd5(%TKOR zTAw9(t=%U`SW469n=Sg*Rlb8X8Tb79NR%$|=(AS3wqF-EMj@~7g$>n>^%0tj(iN@5 zZ9L6-<{hLPclG_IN#At*;hU6PO{A*b+!9fD@9K*UZfib+rdwImZIir;PHRhQ5~)sv zy^&nxIjYfZLpZ&ys#fbMK|KZ}eSau1T=?$>Uf*;tJar(oBC5I)U3^w&bn2Ymw^ubZ z%HjxhX7t}+Fw_!Oqf-MPX_Aq+cHS1cC#5Es*l+oQsW%dzVUC+hE#uKxgGIQo*7RRNQaBbs`?C+RDi$`Oi zph>1GUf&Uo1Ey`LzXU{m)_1{>(+MV|HqXL4JtsB5f>&MFS-1?S?_^9OY#;_!7U zla;g8!S7(K6PxP0DZHXu-LQ`#Rd+HTQPmYzIxg`@fJwFVU3Czmj;X_;;kY>(Qdf`k z5Z18rgEOmJTj_>B$)qkhc_o`pn)UeS*D!KS^dHSBoZUF(EJ>8+fyRD19neRcVg#9J z>tv>bV?HuaA;!s+YpQCvmS6S@UDPgrYWw1aDb9Y1F$qk>;7W5E`xU(S1>vrgH40465>dD} zN+S%+P!evEmEq1f)}+qF&_#|4XI{b+geYz`)^G8-XQ?gGww~)9E?4HF2FEn^>dnOH z1fzgOQ)kWMym<#;+gYnSB4vA(Fz9Pg`q{Y4TbaZPvQ?k z^XKaj$6O57rFK({Dxn}*912NZ^i}IgX=LKf@06RFI9K8I;4~boy3fLNnELMSwk#}k z&kkp+TdcgjMXoN0PuCjB?tHsECw%JglDpRKTzJEq$&1)>AoJ{Gv*cK+dUJYib**(^ z?mZ$s9~_!?B1f%s!w3eeamR=3nRL9^ZB_h|Omn3`(Tr%-N_-FXB7J5@OB3O`Q1jB_ zApNJ-nDk8%`i}n)W>+-n(Nm$cJ5J$joLD3p+S@pL>bIy6r~DSb*#GnpmR^G;BGzrT z=YA3qy8Wb`zoOZRtB7x2)3iO$NL~`NcupR8)6C!unlj=l*BGt9Yix{)t!kFb(ijEuSCi-uhXVY4jJ`11C zE8O}DQHjjl(w*BBmiR3^s!Nf9J)G=>lJ_ywS{w zMXA&$E*$7L?&}0Ny3kEA>Z8QF#h!N;dENy)@0NJpm3!Xl<{;dhPu_0ZWhqr{T$PV^1ULxp?=OmC`c>EEowQLiiO+V+z2>do{FHqu|}8L^}|BO zzB%#}4VLIqXV58_sw`b=ucnJYv^q!Y9UFK-VW^99@A$ z9QRU4>PTt1r^lYpedu2=`0uqEym`a!rD|9UL0$e0>lL=X_iriMw%5H~h5tL#?o;=m zdK3z+aE*ESXpdK^=39H-+aJNdu@S6UNV_HWa3Sxl?|pk*uuuO>v+eh0(P=mOUM)P` z{ccYSxAwPxQ|7JZ|J%}UkAT}imU<)U&hlsJ<>Nh^(A##yS$lfUQOv8wdpn%uktQp$VkctXqb#)Iz+UpU$&1>NQdG)a!VG=9->F(oidkgv02qWizR-G^w z@9Dn1U$#?`KF0oMwbP9Mz&aHl*mbf_aQ;K9b)b)b*7m|F-~l^e*eiB`kA(J$9pJ;E zyalI(*bEBeJ$t(POINMHKb>j;j?tiTl*F6r`b=$z6hHJkCh3-$0t11U_^q4RopwZ)iaDYaSQGfrB-a5V?C_ApT0te3CYp=oqvkTj+aKP-x z_9|d!miq$JT_Gwga@`lWr*j9H9@rN>_cXksV%NQeZ#6ucgIOmqIKrksQ=|+xoa@p$O;S0y9W0#G;7ZG zbZM}tDD{TE{UtVa-;8-H;NFgHPiHAJs4Jx2ptpz7?e+vHaVuNe9q-?8ubr(=?&m@K zob>2<-+>o4W_t%<;5^4W00ZZl-Toc8by9Z#baQL$2Si`DM}Hu6czg8vH$2r(bJDMZ z>RtFIzKgt8tpm z>DB5+^z$ycjK5c^Cogq%SIwV6w*aYr?T1xF`iDnn>Tu~dDizW3&C~(X4SyA=dr}QuXt$z@7hW7KHhf>KMQyqZ>&_g(c{w)DHbdS~U|vi19+ z*_3i39}+b%Ug8W2)8Osy;ZTCZu9nn|Bux-CjA(C0U8>1TaS@2T6-o%!D1mTkVe ziXQU0GBLg^Dx66VcWwz0qb~r|*EcrQs>cAT=Uh}TxnOB@20e9i;o_xHT6)lr)F>>X z=a$!2<2f4(tCvO#3#;kDzUuL5wbAB<)$^BD(LeL&FP`;L`bEgX!s7Eu<}ZyF*U=+s z7Shk*C^9!44T-#rw(Nl;0C^Pf}*v(OTJo)r$hklI|zxf!9 z)~g3|tH;#m(N~q|X-@cNYA{3(outSAw9xNm)02wo=*t&$U@9!3U;gzoqObWi)bhjD zg7j3HrqvFAA0*ULU%#3*alNCjZqUyc@q?<^l%A7chrLq$fHfT@^`S=nP&MtLdbji& zlxYXQY;m#LST(tRwp5vZOp^LlyFKY{A9c99=^sp1Vc^J3`?G$>vEe|DBRL<+3lXvU zg>AK+j=YdVFI2y;O;G*7wi5QDeqvj_(+AkXB7KA{RKK#VAba7lsgTE|LLQh3)yPC9 z{PW_4>KLouu@`leRqxn~I?k$h97{0=!M`nD$UiP#$iFULsE)Q|$-ggN$UiV%s1CRa z^5!(it9R=7tAvB#nL;5?6$*K-P{@;oLY^%Y@^qn)=L>~AVJMu%UU=eA$TNpRHFY4@ z^yAiAxGJ-_D)jT#8geYNIhNV%Wj4n$8y$ze%w{jM*~@J9GMl}W@a84Fc?oS!zl>f$ zPzgaL|G&CxiE(5*%MRh42y%G_q9`GXA{L?5c0Y}Ta(lX~XFSs{wS6CCQ*pPeyPfeX zw!5b%3lyP9Jj4QJl^qv>P{alnARz=&mRTUgf<**E2#LiN3t)x9CgJ=3|NK>_%2n;M zyXW38(sbG7I#s96`QJ}>68Gdc+=U0+g$LY)2h0TrZNARMg`gs*xKg(wMBy)HgTI&z z{>ojrEch(<;G*2Fa82-6?!XnnXL+oOQd|z4k+ED1e3r4BGL|cGyTXOQUm43~z-M_b z7XhDTESCVEW$c!Wy}O&r|}n;Y!167R#^5Sm<;fzNRNbmuS# zgQGn*QVSm+y%7da+{q_?V zNv9%0OeNg=^`o7`1`>dC@57 zPzri?B1+&~(&n@-b`R9Jk&3)>oeZG z?7X!aQn`8W)vzrnA$LA{>DDi-QL4{^`v%*K3&3h+$N+U3lcvdp;o~vN(6-rvF98bE z{0b_Y&6FHFg1h;yx@YoE8_*z;%YGP+t|wQ31b{h|pT<*=A83|0d!yr4h`F(gB)Zu0 zVBa{+rc|Du;#A0vQ+=S|ey`1z&8;^L9R01p>-f6uZWX{d-PGK?2EdZYw~7bjhAk;3 z3t(%q)hkXQt(^_x+59xSpqpC2KVa2~ayY+5_&|Tma{J2XrRH73qlozEYW6&}(?`dS zxHk4M2vAlJPtTy>M@;8u4`3;!JC4u|tUW*@v=bNsw&P0%oru`5EN+~7%y9A(bHfRI%Qa0 zJ%U^W6uv&620Ls1waEBlBZCMd_TMC_g{Yv&A~A#3o^7CNGzN$S1f4aT4GIN!BDsRo6zjmY z0q8v#l7U9mqq5Z+>MOFnEFci%RiwVfja=YQAnNPr@|}WmavD^^2wUUpNWo2(eb}4G z`)5Vh_C`%2_Ch$>;f=5M8wc!Iv&1s1OSkPUw&8+#BEF5ZcSEV~9+=QH z5TY1!pluR+5-_ERj#L^8D4=G7?W|;cJ)q?dm2$z{IuImBFB=DEtKga_P@});N#LV# zvJSAd69mFT@h+{f3DUDEVsDC#RI&cH>m;`L@^}}WPbO{DN5_j&=rKupb|2iW@}YVI z)MI%fT1|*(Jwrt6(isyQwYRF!lX)XB^yQyhhIo%$o3j2j`g%*VG6$itthG2;LV%zo z6ZFqh&`xRuJVCSQ*+yD`dS^CD??J4b_=A+qJUh`wGqs1c0=3*nGZ`LqfxhMxj8uy3_5(3|0+2Qfc5*$x{J zR2v7}uohfOxgw%&W~?FdQ7P<@vG(MAKp}6HXS94?u^n@96uJU_ftTkoax65xVX0@T zCQ4OcA2Ky&02iA1;HHuJ-@XVrPYRFuMuysYQO&jh1~!x>^ObFuhr^U(AcrF5Xu6sQ z0&oTZEtL@fo(T2A8GNe&&_MM(_UIY6;aF;%JR`cSQ3!=RQw{rI4UfndTFtu`at_8V zO>yn18CRndIAd4i200k!3=9LXY$gnm442X>tUwUwpzJ(r?(uzaRmyxLD>VZ?v1I1M zZM8Pk0>o?pFfn@s5&MlnSFEB((F<hFhUaJm76q~+)Zz)C zi|F9NY*{k_=^5hEmxpN7Q(SitT@#4jRfsM{@fMd~=WqS1mwgIlMv~G|7hQy2bYb$R zrCW4n0#PiER#WfH*SS-YD*|L8{g576RKGE4UY`-Lc{c&;6gg8a0aGS=5WxdJfRPrp zG<`+<`(jbmTn;J%us)RHkW|sBs?VQZj+x>Pr7or&Liaq9@ct|Kuo$WB)7guzPzI8E z2F$`RKuLAsq+I4Bn)99@>H#Oj;?azz4Nz5oIb{X9x62v{ zM&t8oFC$RRV`kL=$`R*~Fj!waC>th2!bL0P(yZ9H8d&j$5UzbwJKt)L(E}5!W-MoC zveVpcKvH7o9GrJ{A!uuji8&u=eZ+e_v|=D~oRiOYCSn$?92`FmTaCk@+1fcgX}+50 zs-2)K9m8@py}bbz;z(^lV#eS+g!shX1}C0U#GJn@X}ZYWo$rT9b_m8?@N6+k+a{?A znbJbMVL$*iO~S^sk5+#@F}>_x4`5Rk`WTCJ(d~I8KBo+sOgM4A$XgA%0B$+~`lA$H zbb5%wOPwhRF1~P7PAkZmct8zA1rjAGJc!yi5y=A~d7&vRV%~DxNsRZZiJ3tM!aE|B z@MKXuYMr4JwvFhSNs0Q@yr;u7Z5h!dm0m+^`8UT5LUn zg>@QN5>CJuCf^u%%_q5WnJ(ilx}{G=9We;m5t5dDdeG8yqXPgIB=us#ig1a3ZStZ} zbJOoC`>>SWEZr#8mYTYySW?q&R_!`6EBnF?vkd)p0_NJGggI`_h_upgC*5j?O>vIE zpf{1B_ah^L5w+1ow9D00H#YBBu0HEnp zA`#TD+UR@FwvL=uuFmJQ!=*q63c9+N0thVIVi_&NBD~!y#UDx-)yh29cYln*GpaH0yoLT~3LOpsYJbcfZV)Ai&hRW%(h)@E=q7nSHB&cj45ErN{$fD90F zjeph?tSmrlF%WR1;3r0Mv}ZJVj2qIblJL*iJ}PGcW9viIaYsAF7fK{k01-o+KOrq3h&s8d9 zs+u{qOqlq>wh;w?A-iUCPH3A0ntU>bMYE^`71&_R7S~LMP{(p9Y%k~0A^RMUdXze1 zGM5h|IeMf6fMw_$Av?D0*c2`%=5SJ9Y zTAdnqgrGazB#~;cD~VL&-6Q`UX_YOsVBj?u@_LmvGf`E$%Na)FJ*Ezy7sC}q4&Q@= zEKLPeh=dTQ3K-Wnj(tc>^iGz)yl#(ir!&B9Mu<1`@d>+!Le*vb%%VQ%Bgb&#!_Jp_ zC_o-r2ymO9>W_R^huHbM^y;lxPDamSw(df)qyi(bN-7?p39v?A;t%lMO5{r{_)cC< zU~^EK-c4;M0?7f!PL~!N7Gek|6P(L($K*1~LZH3ec|`XWJ1&N_qo@s~(WjI#Y^4Kg zkZo0|yotc7;aH-RY3`ZAy8|}C4nk-cPj@i_Uc?e%{b@t% zPaAseX^Cp30)i4|R7z3duBfASb&O!_VIMdU7QO;)PGl zf8OFEq{m*%-hL5#6E~)umC;wxOYe;lMit6x6H(bzEb~2-;*5cO+(q+L5LDQvl3;XT zT^izZ95p752M%a=4OE?!j2k|>?)EwosTopVY$cGht;vAsh&2{i??w~wW1sSrwXA

    (3w?L;#@sNThC-zhgPspdNT1h~}J`Un_`27@S^!i@=G3%RZE8b*!&L4U0l9P~G9 z>-f7?-{N1G7W%b~&8_wAwaw}VzMu>9L4UngU$1X&)#^OM>uQ^8oAuiE<~rJ9_vO0v z)mm+9ZFOsdx2$f~|EQJBi@Nh_q( zAYwFjqXdtIaN^?kFUCUvuLSTz(D5yPRaRxvV>FLZTGdT>;Yw#TD(-&yCO9*`@$ol!27Hnggx0!Sxbrf`={@_f*E zzw{^1Z=6AH;oC-B9M71Enr==a}iFo!H^p@pl0T<9O>t}z7q1{ z)O%Z$1f8K@^s%?*X(bEAB&ggahJYEg6}h{4cV5?`GLg-YItxOIr*P*$his2jJ}usl z;zAB4(>{YI;$;7ZA;BQ?kB~9Pl!_$UA8N$5M4%&+QoI%z2>bh$eCD-?`X6>e;O8aO z8T&TDpmyYfBO`rVKH*$`g#dW=yk2V9Vbc zvO~l&4~B*yg3D;iaMKi$0#a-@^D&Tqeh){mXN!bWFSX!Q{?y2{6Ecv*F$YK4I?)Ys ziAXIO0-NCmE2v^1mzNMvQxQC+gh*kpDw6CVUiYdWA&XdrlJN7L-bsctsqp|?2rYmO zRaH6I#5P2O8%D`4vpPg8$jIQIFtE`u(Cy41mLC%*l; zE0U5=rE}^Cb{Bvxp*$7Msr&lASR(Gu*8#XzzTE#31H}fA*`3X3mkFLa=Q7-%hAx-S z5q1#MK>kmY#RiB2)$7DyQAJi+HDusvpix5N&fbf978G=k*nQ&~!tL;QF)&Mj4)J3q zk`z>*Ru+9rSJ7q}m`*=d^GUXtPtr}NlTiLC!!&%$muX}313go$7ZD(QEu)Q&{SR}4 zT5(-0;@Kh<$fPqaywVnsYIz8OIDuVZJXFBIWWpvi0cvl97Z$vtIl&Ci7-VByNMLM7 zQY-oJ`%F`_5_pwfYeE6S;q`QM4H~eN-pg6)-CVf*3y^AL+A(c06*E6Wj?GZB0E6@O zh1^i_vT%?{+g{iMHH_m5u7yvB>@ed!(F#mnBplo<-z2*rK#3Or$`c)WVc`-xo$A1 zyy<$l$1#PT(>Bpv6TLw>C+t!a2&gCzk$^XRD^xE9n^Qsp^A=Ek4blC9LoOFEQ7s!V zfeWdP&V()@(_SJaI_OqULOp9hz)1uzX+#ojRkK+4UT^}+zHVcgx6*Hqg1+RsDA`+; zEFm$k1>OFMCO;TK&lmES6#r;zc*zxJYa- z2-^i&lQ^BCum~`n5yKi#nGjFkswj3A6AAKHQrz+y1HTNN5O8OKfUT?OmbWnr&dIYY ziTExh{w$%{nBMFNc!HrRODd?Ae}Tk)n9cF-bty`KxQ_)nnT@~%m`!0JisNQD86eGa zFumXsr$oJ4fFS5BJr?79aTb%v+-lyXZ5go)&c5XWkdf8eO@|#4Q|!4jFa=Nbf@u^Jp%O{kNxCbwt^bD|#S6@tiM zTNMF>n!%c~L&fIl#Kr4ED#Vab4G$$#yiCqsI#M2T1ef15f@zzrU|zs@v!r^VI=2gV z0p6R|Z5x!&7M5hNiQz3F9{CT@j0J%+#7(e{59@w~qxMUd({|R+bY2IlACNir5wOYV z_wMBY^t0xGb-s#_QVmNf31HYTa`?$8cQ2Zl9`DCXA2M{ssP|$52r*i-iV@Qe9NiIl zoYVn+qJr`-a0xtv{+>(x5Nzr+s=Wx|k5@>eO_Nk334(I01bG9O3(`cll0ZWwl&rzWw&Fr~mcO$h3$P^q@t@aJT5a5VhWQPKta>BFJ4HcaIS8T!V@pk~Ko(kW z+F0r}Y-JqZI>QDzOTIXv16mb{wqA5&$rz(8mRE-9|6=jftDr z8-p_xI_(?)JT$Wv=bgL>EvM3do@;fwFUIH-gl{Uw+{cXsSWsw-T}XTIMffhHJsPut zV2k0H0q#TKfmAK4OVu)XNwSWn7@g%kdUQrWP~mPiyQop5OA9mVNHdrSJ3K&CAP^AO@7>qSSm&q{Q*PJ4Idpn#4eUH zBtA$q`oWxNbSW4KDpVAWj^E8D?^N1Vac@cSVulpZ&DE9A&%4F2SD%__x5wLXj7d0*Bglz5;lh0q4}OukD5>5;IkXqers z=VB(-Tb}p8j8FLcOcV(=A2v=2*3&Ye8~RyLt%&qKAWx>qjYMjw7W)hX1+EY@kyP03 zq_SIuLuDK=<-}A|Ldu~J5%X?#LGxl_j6})CC&M&v|arh=hMJ6DJYXCI0KJsQvsjx|mchKqn_ze&8%L;LPTeA7U3J8Uln6Dk8?ragM>NlhHng*@%T*wqTv-+#TM9#w zRMJB9dG`eDq7UO5^|!=k9`vEXO0Cp%EnSQKRa%VD2iO_s*T9|^90YP>YhBwK@{Ci6mNPM8)%cznPJrc5{C{9+ zXnhGQfM9!EKX{#{>X~$AKf7p`6)`aTL;_7KCkcmaOxPemUvyEIvyicIB)Q?RK4QVr zfvq`(v)0dtHw>yn&lX6$sZDi|f#{#u29r!bUw~fHp-U(X0~#T-S%;oNqT=ad?M6vm zLBR^BD}O0LU0p3jQ(RhJ!8w_8QgE(Z9Cn7n&ecf?HgOrQScFvwnXfj+F1K<*FBr$X z{zOYy#MuLDd;^PkhMdtBj(vS#gx&^1cV2f#o zr%{B|g(l&IN{GpWk(|pgL02*gaoM@Wu>o-KKlc!tc|N=xw?|i97`_;eLLX+>Mff0U z``iAjcL2eAo;bV_qMgnJ;d3-;;zlUV17UKkrkpLBav+#HcW_Fi(@FtLgS&*txLm9| z`eBJG?W`zdHn|b|;PJ?6K<87uj0W%%#P%c9M8NXRHjT`hMIM}oZGeY?G8b_%Awwd; zJC-m{GAjbURPeSD#+g1?BPpnop$ak9C6k#=)u3UnTGjO4Xtofp5Rmy)cTpiGZN)bl zHxLn=Wd1$KWy;g_V-2xTE!1qLxfD$dkN1rMOozr=ux>#BR5=5y%1Mh@y-7AD+9{RR z3R0(@WduYs(G&dy!(G&WfE7pz36e+5BtBD*pTlGTis#7EvE=Y`%EaV3Ib!J|FYHAL zEGErAD8EXfvWJre)>Wh9;jaZfgsxf)(ZH?j*%BGWjOHwKc@7%vzqvyzKrM^<`d*>Fp2 zPl{S~H>OdqcbSomMIc#RS5uocO$Pb#VNhNjTZDEz=Wi_SXJYP<|vEr8l+~^HL*f8d(gAbP--3_ zg2AhX`r%LLRnvlXP9iFYLB6-AEEZ`&hMMo?N|9NCPhTFCYAIo(#gu<5L4+pUJ(R$2 zxvqhpBI1RO1(gd4_sGg8e&U}vRv8KccXdpnwh=QH(nYr<+o-@*@dAzs_$b--9nat0 zMN{cjEV9!-#j3`{7pH@kBe{zznM!~j&LohQ_GhdE5{{EDf`C(+H{s>^NJUEiP!!M~ z$LzfNIsu~V#+sY6XG#eG*apCZgo5W*Tow7+6GOC1iLVpqGjT?A3rF@roGRQs6#P;e zkG#sFmSY-rbnAlCe8MltRA&slMpfOd%@+w;SZL7*&}R(+GF>442M;l zHRreK_r6p!Q*>$x-I%Y9s_V>}E;5&UwU689U%EyC!mRF>nw%tmy1Gxy?rTbgU?`JA z3$RsTN6%odeDK(i*uf=mI@gqw)oSYYuhP=h8QC~ zHxof5Hh1Ua)~gTG6U>dtlCK*91L!G9rI^oCzTdO?)+1}}LxPuPw@Co0^XDnitF6NW zdVzi)FzQa3hX!{n`pY1F3bm!rdlLTr{ZKS92>Pe&D8Oa{)m0!$yDx>FxKqjcdz=$Y zIF5S{29s-P73PBXT$xNnp}8m<^UlG494}#Z`P^8<{c3muOr^Q5P|%^}ZCa3U@2D>% z9;>9jP$CZH<4I0ZfB?3iUR1SS(=^^mVGmeT!^{3~z;Y63iy(nm*GM9^rt(f78(~Gm zo9=ju_Tnj$=mXjSh>}9+lqaPk(q4hAhh=;?iDnTehk3vXY9lBIdvKc-z*VcDqU>Er ze=<(c2Kg8zSkbV}b?mY#t-|Ez&mpzi)C%UBCrbGLeCXM{9-%H*6m%a-|4Z~3M|4T0 z)=%2gEA;u*hR9)ebneI0CD^|p7SKwe;1AmZ1shQX7-n!b6BFlhrR%Vw-#by7Z{!zm z*#adA(f4B94#!ZJP>yy<5rAto!z z()2Vv0e{w}U>11omkT$x(aPoEdgYA8+<&FpsmM20YOSnvUJfu) zk0`V(zo3XYi=U;wg!m1OX4)L!K8c%&Bc&x$->pLK>dE-Ubl zQfv%iwJDKsLKhyDcJo#LDyzQTz{nO0&Z~mu_x8v_+)<66F zzrlD;(N_8PHBy60<@Pm&h+md($sc>Z9lwR2eiHv}{5x*^J8ryPXLqpgb|kuS$8G#K z-1u*}@wY!_BlT$G?Cihc17~XEKlw48|0h4D^IvrvYwvC2Z6E&wWBuo!d|bz$d|bzW z-2lTq(8k;GzcSXXNynos8AH>V^{a3wf_|e8c&79}8{Ab4xyYYH9`TO_o`QQGFpH5DC zfo82_!cUzAJ!`a`xd`QvMDeD?i+^K&1U0e{?h z%^oF3d%hiit>F2e`5kh`N~QPa&&$#N*f{(Cq+tBl{xy(GKJux%=g<3PKvc$k;{y#j zzWaxAsQeNRKLsSP{Wq{8dZnMB*Z=+>>G;2WjZaAarN31wT%Ek}hkvP%^JZp1=4<8u E05apxdjJ3c diff --git a/rednose/helpers/kalmanfilter.py b/rednose/helpers/kalmanfilter.py index d541faa..fc9fd2b 100644 --- a/rednose/helpers/kalmanfilter.py +++ b/rednose/helpers/kalmanfilter.py @@ -1,4 +1,4 @@ -from typing import Any, Dict +from typing import Any import numpy as np @@ -8,10 +8,10 @@ class KalmanFilter: initial_x = np.zeros((0, 0)) initial_P_diag = np.zeros((0, 0)) Q = np.zeros((0, 0)) - obs_noise: Dict[int, Any] = {} + obs_noise: dict[int, Any] = {} # Should be initialized when initializating a KalmanFilter implementation - filter = None # noqa: A003 + filter = None @property def x(self): diff --git a/rednose/logger/logger.h b/rednose/logger/logger.h new file mode 100644 index 0000000..8f541a2 --- /dev/null +++ b/rednose/logger/logger.h @@ -0,0 +1,20 @@ +#pragma once + +#ifdef SWAGLOG +#include SWAGLOG +#else + +#define CLOUDLOG_DEBUG 10 +#define CLOUDLOG_INFO 20 +#define CLOUDLOG_WARNING 30 +#define CLOUDLOG_ERROR 40 +#define CLOUDLOG_CRITICAL 50 + +#define cloudlog(lvl, fmt, ...) printf(fmt "\n", ## __VA_ARGS__) + +#define LOGD(fmt, ...) cloudlog(CLOUDLOG_DEBUG, fmt, ## __VA_ARGS__) +#define LOG(fmt, ...) cloudlog(CLOUDLOG_INFO, fmt, ## __VA_ARGS__) +#define LOGW(fmt, ...) cloudlog(CLOUDLOG_WARNING, fmt, ## __VA_ARGS__) +#define LOGE(fmt, ...) cloudlog(CLOUDLOG_ERROR, fmt, ## __VA_ARGS__) + +#endif