From f9d3744670362583fc7f80d3d4d062b2883211d0 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Wed, 13 May 2020 13:43:32 -0700 Subject: [PATCH] initial commit --- .dockerignore | 1 + .editorconfig | 11 + .github/workflows/tests.yml | 13 + .gitignore | 141 ++++++ .pylintrc | 585 +++++++++++++++++++++++++ Dockerfile | 18 + LICENSE | 21 + README.md | 52 +++ SConscript | 29 ++ SConstruct | 26 ++ examples/__init__.py | 0 examples/live_kf.py | 338 +++++++++++++++ rednose/__init__.py | 0 rednose/helpers/__init__.py | 26 ++ rednose/helpers/chi2_lookup.py | 22 + rednose/helpers/chi2_lookup_table.npy | Bin 0 -> 156928 bytes rednose/helpers/ekf_sym.py | 600 ++++++++++++++++++++++++++ rednose/helpers/feature_handler.py | 166 +++++++ rednose/helpers/lst_sq_computer.py | 173 ++++++++ rednose/helpers/sympy_helpers.py | 90 ++++ rednose/templates/compute_pos.c | 54 +++ rednose/templates/ekf_c.c | 123 ++++++ rednose/templates/feature_handler.c | 58 +++ setup.py | 26 ++ 24 files changed, 2573 insertions(+) create mode 100644 .dockerignore create mode 100644 .editorconfig create mode 100644 .github/workflows/tests.yml create mode 100644 .gitignore create mode 100644 .pylintrc create mode 100644 Dockerfile create mode 100644 LICENSE create mode 100644 README.md create mode 100644 SConscript create mode 100644 SConstruct create mode 100644 examples/__init__.py create mode 100755 examples/live_kf.py create mode 100644 rednose/__init__.py create mode 100644 rednose/helpers/__init__.py create mode 100644 rednose/helpers/chi2_lookup.py create mode 100644 rednose/helpers/chi2_lookup_table.npy create mode 100644 rednose/helpers/ekf_sym.py create mode 100755 rednose/helpers/feature_handler.py create mode 100755 rednose/helpers/lst_sq_computer.py create mode 100644 rednose/helpers/sympy_helpers.py create mode 100644 rednose/templates/compute_pos.c create mode 100644 rednose/templates/ekf_c.c create mode 100644 rednose/templates/feature_handler.c create mode 100644 setup.py diff --git a/.dockerignore b/.dockerignore new file mode 100644 index 0000000..5b2d462 --- /dev/null +++ b/.dockerignore @@ -0,0 +1 @@ +.sconsign.dblite diff --git a/.editorconfig b/.editorconfig new file mode 100644 index 0000000..e0da061 --- /dev/null +++ b/.editorconfig @@ -0,0 +1,11 @@ +root = true + +[*] +end_of_line = lf +insert_final_newline = true +trim_trailing_whitespace = true + +[{*.py, *.pyx, *pxd}] +charset = utf-8 +indent_style = space +indent_size = 2 diff --git a/.github/workflows/tests.yml b/.github/workflows/tests.yml new file mode 100644 index 0000000..e79558f --- /dev/null +++ b/.github/workflows/tests.yml @@ -0,0 +1,13 @@ +name: Tests + +on: [push, pull_request] + +jobs: + test: + + runs-on: ubuntu-16.04 + + steps: + - uses: actions/checkout@v2 + - name: Build docker image + run: docker build -t rednose . diff --git a/.gitignore b/.gitignore new file mode 100644 index 0000000..60263b2 --- /dev/null +++ b/.gitignore @@ -0,0 +1,141 @@ +generated/ +.sconsign.dblite + +# Byte-compiled / optimized / DLL files +__pycache__/ +*.py[cod] +*$py.class + +# C extensions +*.so + +# Distribution / packaging +.Python +build/ +develop-eggs/ +dist/ +downloads/ +eggs/ +.eggs/ +lib/ +lib64/ +parts/ +sdist/ +var/ +wheels/ +share/python-wheels/ +*.egg-info/ +.installed.cfg +*.egg +MANIFEST + +# PyInstaller +# Usually these files are written by a python script from a template +# before PyInstaller builds the exe, so as to inject date/other infos into it. +*.manifest +*.spec + +# Installer logs +pip-log.txt +pip-delete-this-directory.txt + +# Unit test / coverage reports +htmlcov/ +.tox/ +.nox/ +.coverage +.coverage.* +.cache +nosetests.xml +coverage.xml +*.cover +*.py,cover +.hypothesis/ +.pytest_cache/ +cover/ + +# Translations +*.mo +*.pot + +# Django stuff: +*.log +local_settings.py +db.sqlite3 +db.sqlite3-journal + +# Flask stuff: +instance/ +.webassets-cache + +# Scrapy stuff: +.scrapy + +# Sphinx documentation +docs/_build/ + +# PyBuilder +.pybuilder/ +target/ + +# Jupyter Notebook +.ipynb_checkpoints + +# IPython +profile_default/ +ipython_config.py + +# pyenv +# For a library or package, you might want to ignore these files since the code is +# intended to run in multiple environments; otherwise, check them in: +# .python-version + +# pipenv +# According to pypa/pipenv#598, it is recommended to include Pipfile.lock in version control. +# However, in case of collaboration, if having platform-specific dependencies or dependencies +# having no cross-platform support, pipenv may install dependencies that don't work, or not +# install all needed dependencies. +#Pipfile.lock + +# PEP 582; used by e.g. github.com/David-OConnor/pyflow +__pypackages__/ + +# Celery stuff +celerybeat-schedule +celerybeat.pid + +# SageMath parsed files +*.sage.py + +# Environments +.env +.venv +env/ +venv/ +ENV/ +env.bak/ +venv.bak/ + +# Spyder project settings +.spyderproject +.spyproject + +# Rope project settings +.ropeproject + +# mkdocs documentation +/site + +# mypy +.mypy_cache/ +.dmypy.json +dmypy.json + +# Pyre type checker +.pyre/ + +# pytype static type analyzer +.pytype/ + +# Cython debug symbols +cython_debug/ diff --git a/.pylintrc b/.pylintrc new file mode 100644 index 0000000..64a55da --- /dev/null +++ b/.pylintrc @@ -0,0 +1,585 @@ +[MASTER] + +# A comma-separated list of package or module names from where C extensions may +# be loaded. Extensions are loading into the active Python interpreter and may +# run arbitrary code +extension-pkg-whitelist=scipy + +# Add files or directories to the blacklist. They should be base names, not +# paths. +ignore=CVS + +# Add files or directories matching the regex patterns to the blacklist. The +# regex matches against base names, not paths. +ignore-patterns= + +# Python code to execute, usually for sys.path manipulation such as +# pygtk.require(). +#init-hook= + +# Use multiple processes to speed up Pylint. +jobs=4 + +# List of plugins (as comma separated values of python modules names) to load, +# usually to register additional checkers. +load-plugins= + +# Pickle collected data for later comparisons. +persistent=yes + +# Specify a configuration file. +#rcfile= + +# When enabled, pylint would attempt to guess common misconfiguration and emit +# user-friendly hints instead of false-positive error messages +suggestion-mode=yes + +# Allow loading of arbitrary C extensions. Extensions are imported into the +# active Python interpreter and may run arbitrary code. +unsafe-load-any-extension=no + + +[MESSAGES CONTROL] + +# Only show warnings with the listed confidence levels. Leave empty to show +# all. Valid levels: HIGH, INFERENCE, INFERENCE_FAILURE, UNDEFINED +confidence= + +# Disable the message, report, category or checker with the given id(s). You +# can either give multiple identifiers separated by comma (,) or put this +# option multiple times (only on the command line, not in the configuration +# file where it should appear only once).You can also use "--disable=all" to +# disable everything first and then reenable specific checks. For example, if +# you want to run only the similarities checker, you can use "--disable=all +# --enable=similarities". If you want to run only the classes checker, but have +# no Warning level messages displayed, use"--disable=all --enable=classes +# --disable=W" +disable=print-statement, + parameter-unpacking, + unpacking-in-except, + old-raise-syntax, + backtick, + long-suffix, + old-ne-operator, + old-octal-literal, + import-star-module-level, + non-ascii-bytes-literal, + raw-checker-failed, + bad-inline-option, + locally-disabled, + locally-enabled, + file-ignored, + suppressed-message, + useless-suppression, + deprecated-pragma, + apply-builtin, + basestring-builtin, + buffer-builtin, + cmp-builtin, + coerce-builtin, + execfile-builtin, + file-builtin, + long-builtin, + raw_input-builtin, + reduce-builtin, + standarderror-builtin, + unicode-builtin, + xrange-builtin, + coerce-method, + delslice-method, + getslice-method, + setslice-method, + no-absolute-import, + old-division, + dict-iter-method, + dict-view-method, + next-method-called, + metaclass-assignment, + indexing-exception, + raising-string, + reload-builtin, + oct-method, + hex-method, + nonzero-method, + cmp-method, + input-builtin, + round-builtin, + intern-builtin, + unichr-builtin, + map-builtin-not-iterating, + zip-builtin-not-iterating, + range-builtin-not-iterating, + filter-builtin-not-iterating, + using-cmp-argument, + eq-without-hash, + div-method, + idiv-method, + rdiv-method, + exception-message-attribute, + invalid-str-codec, + sys-max-int, + bad-python3-import, + deprecated-string-function, + deprecated-str-translate-call, + deprecated-itertools-function, + deprecated-types-field, + next-method-defined, + dict-items-not-iterating, + dict-keys-not-iterating, + dict-values-not-iterating, + bad-indentation, + line-too-long, + missing-docstring, + multiple-statements, + bad-continuation, + invalid-name, + too-many-arguments, + too-many-locals, + superfluous-parens, + bad-whitespace, + too-many-instance-attributes, + wrong-import-position, + ungrouped-imports, + wrong-import-order, + protected-access, + trailing-whitespace, + too-many-branches, + too-few-public-methods, + too-many-statements, + trailing-newlines, + attribute-defined-outside-init, + too-many-return-statements, + too-many-public-methods, + unused-argument, + old-style-class, + no-init, + len-as-condition, + unneeded-not, + no-self-use, + multiple-imports, + no-else-return, + logging-not-lazy, + fixme, + redefined-outer-name, + unused-variable, + unsubscriptable-object, + expression-not-assigned, + too-many-boolean-expressions, + consider-using-ternary, + invalid-unary-operand-type, + relative-import, + deprecated-lambda + + +# Enable the message, report, category or checker with the given id(s). You can +# either give multiple identifier separated by comma (,) or put this option +# multiple time (only on the command line, not in the configuration file where +# it should appear only once). See also the "--disable" option for examples. +enable=c-extension-no-member + + +[REPORTS] + +# Python expression which should return a note less than 10 (10 is the highest +# note). You have access to the variables errors warning, statement which +# respectively contain the number of errors / warnings messages and the total +# number of statements analyzed. This is used by the global evaluation report +# (RP0004). +evaluation=10.0 - ((float(5 * error + warning + refactor + convention) / statement) * 10) + +# Template used to display messages. This is a python new-style format string +# used to format the message information. See doc for all details +#msg-template= + +# Set the output format. Available formats are text, parseable, colorized, json +# and msvs (visual studio).You can also give a reporter class, eg +# mypackage.mymodule.MyReporterClass. +output-format=text + +# Tells whether to display a full report or only the messages +reports=no + +# Activate the evaluation score. +score=yes + + +[REFACTORING] + +# Maximum number of nested blocks for function / method body +max-nested-blocks=5 + +# Complete name of functions that never returns. When checking for +# inconsistent-return-statements if a never returning function is called then +# it will be considered as an explicit return statement and no message will be +# printed. +never-returning-functions=optparse.Values,sys.exit + + +[LOGGING] + +# Logging modules to check that the string format arguments are in logging +# function parameter format +logging-modules=logging + + +[SPELLING] + +# Limits count of emitted suggestions for spelling mistakes +max-spelling-suggestions=4 + +# Spelling dictionary name. Available dictionaries: none. To make it working +# install python-enchant package. +spelling-dict= + +# List of comma separated words that should not be checked. +spelling-ignore-words= + +# A path to a file that contains private dictionary; one word per line. +spelling-private-dict-file= + +# Tells whether to store unknown words to indicated private dictionary in +# --spelling-private-dict-file option instead of raising a message. +spelling-store-unknown-words=no + + +[MISCELLANEOUS] + +# List of note tags to take in consideration, separated by a comma. +notes=FIXME, + XXX, + TODO + + +[SIMILARITIES] + +# Ignore comments when computing similarities. +ignore-comments=yes + +# Ignore docstrings when computing similarities. +ignore-docstrings=yes + +# Ignore imports when computing similarities. +ignore-imports=no + +# Minimum lines number of a similarity. +min-similarity-lines=4 + + +[TYPECHECK] + +# List of decorators that produce context managers, such as +# contextlib.contextmanager. Add to this list to register other decorators that +# produce valid context managers. +contextmanager-decorators=contextlib.contextmanager + +# List of members which are set dynamically and missed by pylint inference +# system, and so shouldn't trigger E1101 when accessed. Python regular +# expressions are accepted. +generated-members=capnp.* cereal.* pygame.* zmq.* setproctitle.* smbus2.* usb1.* serial.* cv2.* + +# Tells whether missing members accessed in mixin class should be ignored. A +# mixin class is detected if its name ends with "mixin" (case insensitive). +ignore-mixin-members=yes + +# This flag controls whether pylint should warn about no-member and similar +# checks whenever an opaque object is returned when inferring. The inference +# can return multiple potential results while evaluating a Python object, but +# some branches might not be evaluated, which results in partial inference. In +# that case, it might be useful to still emit no-member and other checks for +# the rest of the inferred objects. +ignore-on-opaque-inference=yes + +# List of class names for which member attributes should not be checked (useful +# for classes with dynamically set attributes). This supports the use of +# qualified names. +ignored-classes=optparse.Values,thread._local,_thread._local + +# List of module names for which member attributes should not be checked +# (useful for modules/projects where namespaces are manipulated during runtime +# and thus existing member attributes cannot be deduced by static analysis. It +# supports qualified module names, as well as Unix pattern matching. +ignored-modules=flask setproctitle usb1 flask.ext.socketio smbus2 usb1.* + +# Show a hint with possible names when a member name was not found. The aspect +# of finding the hint is based on edit distance. +missing-member-hint=yes + +# The minimum edit distance a name should have in order to be considered a +# similar match for a missing member name. +missing-member-hint-distance=1 + +# The total number of similar names that should be taken in consideration when +# showing a hint for a missing member. +missing-member-max-choices=1 + + +[VARIABLES] + +# List of additional names supposed to be defined in builtins. Remember that +# you should avoid to define new builtins when possible. +additional-builtins= + +# Tells whether unused global variables should be treated as a violation. +allow-global-unused-variables=yes + +# List of strings which can identify a callback function by name. A callback +# name must start or end with one of those strings. +callbacks=cb_, + _cb + +# A regular expression matching the name of dummy variables (i.e. expectedly +# not used). +dummy-variables-rgx=_+$|(_[a-zA-Z0-9_]*[a-zA-Z0-9]+?$)|dummy|^ignored_|^unused_ + +# Argument names that match this expression will be ignored. Default to name +# with leading underscore +ignored-argument-names=_.*|^ignored_|^unused_ + +# Tells whether we should check for unused import in __init__ files. +init-import=no + +# List of qualified module names which can have objects that can redefine +# builtins. +redefining-builtins-modules=six.moves,past.builtins,future.builtins + + +[FORMAT] + +# Expected format of line ending, e.g. empty (any line ending), LF or CRLF. +expected-line-ending-format= + +# Regexp for a line that is allowed to be longer than the limit. +ignore-long-lines=^\s*(# )??$ + +# Number of spaces of indent required inside a hanging or continued line. +indent-after-paren=4 + +# String used as indentation unit. This is usually " " (4 spaces) or "\t" (1 +# tab). +indent-string=' ' + +# Maximum number of characters on a single line. +max-line-length=100 + +# Maximum number of lines in a module +max-module-lines=1000 + +# List of optional constructs for which whitespace checking is disabled. `dict- +# separator` is used to allow tabulation in dicts, etc.: {1 : 1,\n222: 2}. +# `trailing-comma` allows a space between comma and closing bracket: (a, ). +# `empty-line` allows space-only lines. +no-space-check=trailing-comma, + dict-separator + +# Allow the body of a class to be on the same line as the declaration if body +# contains single statement. +single-line-class-stmt=no + +# Allow the body of an if to be on the same line as the test if there is no +# else. +single-line-if-stmt=no + + +[BASIC] + +# Naming style matching correct argument names +argument-naming-style=snake_case + +# Regular expression matching correct argument names. Overrides argument- +# naming-style +#argument-rgx= + +# Naming style matching correct attribute names +attr-naming-style=snake_case + +# Regular expression matching correct attribute names. Overrides attr-naming- +# style +#attr-rgx= + +# Bad variable names which should always be refused, separated by a comma +bad-names=foo, + bar, + baz, + toto, + tutu, + tata + +# Naming style matching correct class attribute names +class-attribute-naming-style=any + +# Regular expression matching correct class attribute names. Overrides class- +# attribute-naming-style +#class-attribute-rgx= + +# Naming style matching correct class names +class-naming-style=PascalCase + +# Regular expression matching correct class names. Overrides class-naming-style +#class-rgx= + +# Naming style matching correct constant names +const-naming-style=UPPER_CASE + +# Regular expression matching correct constant names. Overrides const-naming- +# style +#const-rgx= + +# Minimum line length for functions/classes that require docstrings, shorter +# ones are exempt. +docstring-min-length=-1 + +# Naming style matching correct function names +function-naming-style=snake_case + +# Regular expression matching correct function names. Overrides function- +# naming-style +#function-rgx= + +# Good variable names which should always be accepted, separated by a comma +good-names=i, + j, + k, + ex, + Run, + _ + +# Include a hint for the correct naming format with invalid-name +include-naming-hint=no + +# Naming style matching correct inline iteration names +inlinevar-naming-style=any + +# Regular expression matching correct inline iteration names. Overrides +# inlinevar-naming-style +#inlinevar-rgx= + +# Naming style matching correct method names +method-naming-style=snake_case + +# Regular expression matching correct method names. Overrides method-naming- +# style +#method-rgx= + +# Naming style matching correct module names +module-naming-style=snake_case + +# Regular expression matching correct module names. Overrides module-naming- +# style +#module-rgx= + +# Colon-delimited sets of names that determine each other's naming style when +# the name regexes allow several styles. +name-group= + +# Regular expression which should only match function or class names that do +# not require a docstring. +no-docstring-rgx=^_ + +# List of decorators that produce properties, such as abc.abstractproperty. Add +# to this list to register other decorators that produce valid properties. +property-classes=abc.abstractproperty + +# Naming style matching correct variable names +variable-naming-style=snake_case + +# Regular expression matching correct variable names. Overrides variable- +# naming-style +#variable-rgx= + + +[DESIGN] + +# Maximum number of arguments for function / method +max-args=5 + +# Maximum number of attributes for a class (see R0902). +max-attributes=7 + +# Maximum number of boolean expressions in a if statement +max-bool-expr=5 + +# Maximum number of branch for function / method body +max-branches=12 + +# Maximum number of locals for function / method body +max-locals=15 + +# Maximum number of parents for a class (see R0901). +max-parents=7 + +# Maximum number of public methods for a class (see R0904). +max-public-methods=20 + +# Maximum number of return / yield for function / method body +max-returns=6 + +# Maximum number of statements in function / method body +max-statements=50 + +# Minimum number of public methods for a class (see R0903). +min-public-methods=2 + + +[CLASSES] + +# List of method names used to declare (i.e. assign) instance attributes. +defining-attr-methods=__init__, + __new__, + setUp + +# List of member names, which should be excluded from the protected access +# warning. +exclude-protected=_asdict, + _fields, + _replace, + _source, + _make + +# List of valid names for the first argument in a class method. +valid-classmethod-first-arg=cls + +# List of valid names for the first argument in a metaclass class method. +valid-metaclass-classmethod-first-arg=mcs + + +[IMPORTS] + +# Allow wildcard imports from modules that define __all__. +allow-wildcard-with-all=no + +# Analyse import fallback blocks. This can be used to support both Python 2 and +# 3 compatible code, which means that the block might have code that exists +# only in one or another interpreter, leading to false positives when analysed. +analyse-fallback-blocks=no + +# Deprecated modules which should not be used, separated by a comma +deprecated-modules=regsub, + TERMIOS, + Bastion, + rexec + +# Create a graph of external dependencies in the given file (report RP0402 must +# not be disabled) +ext-import-graph= + +# Create a graph of every (i.e. internal and external) dependencies in the +# given file (report RP0402 must not be disabled) +import-graph= + +# Create a graph of internal dependencies in the given file (report RP0402 must +# not be disabled) +int-import-graph= + +# Force import order to recognize a module as part of the standard +# compatibility libraries. +known-standard-library= + +# Force import order to recognize a module as part of a third party library. +known-third-party=enchant + + +[EXCEPTIONS] + +# Exceptions that will emit a warning when being caught. Defaults to +# "Exception" +overgeneral-exceptions=Exception diff --git a/Dockerfile b/Dockerfile new file mode 100644 index 0000000..5e3934d --- /dev/null +++ b/Dockerfile @@ -0,0 +1,18 @@ +from ubuntu:16.04 + +RUN apt-get update && apt-get install -y libzmq3-dev capnproto libcapnp-dev clang wget git autoconf libtool curl make build-essential libssl-dev zlib1g-dev libbz2-dev libreadline-dev libsqlite3-dev llvm libncurses5-dev libncursesw5-dev xz-utils tk-dev libffi-dev liblzma-dev python-openssl libeigen3-dev + +RUN curl -L https://github.com/pyenv/pyenv-installer/raw/master/bin/pyenv-installer | bash +ENV PATH="/root/.pyenv/bin:/root/.pyenv/shims:${PATH}" +RUN pyenv install 3.7.3 +RUN pyenv global 3.7.3 +RUN pyenv rehash +RUN pip3 install scons==3.1.1 + +WORKDIR /project/rednose + +ENV PYTHONPATH=/project + +COPY . . +RUN python3 setup.py install +RUN scons -c && scons -j$(nproc) diff --git a/LICENSE b/LICENSE new file mode 100644 index 0000000..6f1774f --- /dev/null +++ b/LICENSE @@ -0,0 +1,21 @@ +MIT License + +Copyright (c) 2020 comma.ai + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. diff --git a/README.md b/README.md new file mode 100644 index 0000000..4c4ebd5 --- /dev/null +++ b/README.md @@ -0,0 +1,52 @@ +# Kalman filter library + +## Introduction +The kalman filter framework described here is an incredibly powerful tool for any optimization problem, +but particularly for visual odometry, sensor fusion localization or SLAM. It is designed to provide very +accurate results, work online or offline, be fairly computationally efficient, be easy to design filters with in +python. + +## Feature walkthrough + +### Extended Kalman Filter with symbolic Jacobian computation +Most dynamic systems can be described as a Hidden Markov Process. To estimate the state of such a system with noisy +measurements one can use a Recursive Bayesian estimator. For a linear Markov Process a regular linear Kalman filter is optimal. +Unfortunately, a lot of systems are non-linear. Extended Kalman Filters can model systems by linearizing the non-linear +system at every step, this provides a close to optimal estimator when the linearization is good enough. If the linearization +introduces too much noise, one can use an Iterated Extended Kalman Filter, Unscented Kalman Filter or a Particle Filter. For +most applications those estimators are overkill and introduce too much complexity and require a lot of additional compute. + +Conventionally Extended Kalman Filters are implemented by writing the system's dynamic equations and then manually symbolically +calculating the Jacobians for the linearization. For complex systems this is time consuming and very prone to calculation errors. +This library symbolically computes the Jacobians using sympy to simplify the system's definition and remove the possiblity of introducing calculation errors. + +### Error State Kalman Filter +3D localization algorithms ussually also require estimating orientation of an object in 3D. Orientation is generally represented +with euler angles or quaternions. + +Euler angles have several problems, there are mulitple ways to represent the same orientation, +gimbal lock can cause the loss of a degree of freedom and lastly their behaviour is very non-linear when errors are large. +Quaternions with one strictly positive dimension don't suffer from these issues, but have another set of problems. +Quaternions need to be normalized otherwise they will grow unbounded, this is cannot be cleanly enforced in a kalman filter. +Most importantly though a quaternion has 4 dimensions, but only represents 3 degrees of freedom, so there is one redundant dimension. + +Kalman filters are designed to minimize the error of the system's state. It is possible to have a kalman filter where state and the error of the state are represented in a different space. As long as there is an error function that can compute the error based on the true state and estimated state. It is problematic to have redundant dimensions in the error of the kalman filter, but not in the state. A good compromise then, is to use the quaternion to represent the system's attitude state and use euler angles to describe the error in attitude. This library supports and defining an arbitrary error that is in a different space than the state. [Joan Solà](https://arxiv.org/abs/1711.02508) has written a comprehensive description of using ESKFs for robust 3D orientation estimation. + +### Multi-State Constraint Kalman Filter +How do you integrate feature-based visual odometry with a Kalman filter? The problem is that one cannot write an observation equation for 2D feature observations in image space for a localization kalman filter. One needs to give the feature observation a depth so it has a 3D position, then one can write an obvervation equation in the kalman filter. This is possible by tracking the feature across frames and then estimating the depth. However, the solution is not that simple, the depth estimated by tracking the feature across frames depends on the location of the camera at those frames, and thus the state of the kalman filter. This creates a positive feedback loop where the kalman filter wrongly gains confidence in it's position because the feature position updates reinforce it. + +The solution is to use an [MSCKF](http://citeseerx.ist.psu.edu/viewdoc/download?doi=10.1.1.437.1085&rep=rep1&type=pdf), which this library fully supports. + +### Rauch–Tung–Striebel smoothing +When doing offline estimation with a kalman filter there can be an initialization period where states are badly estimated. +Global estimators don't suffer from this, to make our kalman filter competitive with global optimizers we can run the filter +backwards using an RTS smoother. Those combined with potentially multiple forward and backwards passes of the data should make +performance very close to global optimization. + +### Mahalanobis distance outlier rejector +A lot of measurements do not come from a Gaussian distribution and as such have outliers that do not fit the statistical model +of the Kalman filter. This can cause a lot of performance issues if not dealt with. This library allows the use of a mahalanobis +distance statistical test on the incoming measurements to deal with this. Note that good initialization is critical to prevent +good measurements from being rejected. + + diff --git a/SConscript b/SConscript new file mode 100644 index 0000000..55800e8 --- /dev/null +++ b/SConscript @@ -0,0 +1,29 @@ +Import('env', 'arch') + +templates = Glob('#rednose/templates/*') + +# TODO: get dependencies based on installation +sympy_helpers = "#rednose/helpers/sympy_helpers.py" +ekf_sym = "#rednose/helpers/ekf_sym.py" + +to_build = { + 'live': ('examples/live_kf.py', 'examples/generated'), +} + + +found = {} + +for target, (command, generated_folder) in to_build.items(): + if File(command).exists(): + found[target] = (command, generated_folder) + +for target, (command, generated_folder) in found.items(): + target_files = File([f'{generated_folder}/{target}.cpp', f'{generated_folder}/{target}.h']) + command_file = File(command) + + env.Command(target_files, + [templates, command_file, sympy_helpers, ekf_sym], + command_file.get_abspath()+" "+target + ) + + env.SharedLibrary(f'{generated_folder}/' + target, target_files[0]) diff --git a/SConstruct b/SConstruct new file mode 100644 index 0000000..3adcd01 --- /dev/null +++ b/SConstruct @@ -0,0 +1,26 @@ +import os +import subprocess + +arch = subprocess.check_output(["uname", "-m"], encoding='utf8').rstrip() + +env = Environment( + ENV=os.environ, + CC='clang', + CXX='clang++', + CCFLAGS=[ + "-g", + "-fPIC", + "-O2", + "-Werror=implicit-function-declaration", + "-Werror=incompatible-pointer-types", + "-Werror=int-conversion", + "-Werror=return-type", + "-Werror=format-extra-args", + ], + CFLAGS="-std=gnu11", + CXXFLAGS="-std=c++14", +) + + +Export('env', 'arch') +SConscript(['SConscript']) diff --git a/examples/__init__.py b/examples/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/examples/live_kf.py b/examples/live_kf.py new file mode 100755 index 0000000..46c6ee0 --- /dev/null +++ b/examples/live_kf.py @@ -0,0 +1,338 @@ +#!/usr/bin/env python3 +import os +import numpy as np +import sympy as sp + +from rednose.helpers import KalmanError +from rednose.helpers.ekf_sym import EKF_sym, gen_code +from rednose.helpers.sympy_helpers import (euler_rotate, quat_matrix_r, quat_rotate) + +GENERATED_DIR = os.path.abspath(os.path.join(os.path.dirname(__file__), 'generated')) +EARTH_GM = 3.986005e14 # m^3/s^2 (gravitational constant * mass of earth) + + +class ObservationKind(): + UNKNOWN = 0 + NO_OBSERVATION = 1 + GPS_NED = 2 + ODOMETRIC_SPEED = 3 + PHONE_GYRO = 4 + GPS_VEL = 5 + PSEUDORANGE_GPS = 6 + PSEUDORANGE_RATE_GPS = 7 + SPEED = 8 + NO_ROT = 9 + PHONE_ACCEL = 10 + ORB_POINT = 11 + ECEF_POS = 12 + CAMERA_ODO_TRANSLATION = 13 + CAMERA_ODO_ROTATION = 14 + ORB_FEATURES = 15 + MSCKF_TEST = 16 + FEATURE_TRACK_TEST = 17 + LANE_PT = 18 + IMU_FRAME = 19 + PSEUDORANGE_GLONASS = 20 + PSEUDORANGE_RATE_GLONASS = 21 + PSEUDORANGE = 22 + PSEUDORANGE_RATE = 23 + + names = [ + 'Unknown', + 'No observation', + 'GPS NED', + 'Odometric speed', + 'Phone gyro', + 'GPS velocity', + 'GPS pseudorange', + 'GPS pseudorange rate', + 'Speed', + 'No rotation', + 'Phone acceleration', + 'ORB point', + 'ECEF pos', + 'camera odometric translation', + 'camera odometric rotation', + 'ORB features', + 'MSCKF test', + 'Feature track test', + 'Lane ecef point', + 'imu frame eulers', + 'GLONASS pseudorange', + 'GLONASS pseudorange rate', + ] + + @classmethod + def to_string(cls, kind): + return cls.names[kind] + + +class States(): + ECEF_POS = slice(0, 3) # x, y and z in ECEF in meters + ECEF_ORIENTATION = slice(3, 7) # quat for pose of phone in ecef + ECEF_VELOCITY = slice(7, 10) # ecef velocity in m/s + ANGULAR_VELOCITY = slice(10, 13) # roll, pitch and yaw rates in device frame in radians/s + GYRO_BIAS = slice(13, 16) # roll, pitch and yaw biases + ODO_SCALE = slice(16, 17) # odometer scale + ACCELERATION = slice(17, 20) # Acceleration in device frame in m/s**2 + IMU_OFFSET = slice(20, 23) # imu offset angles in radians + + # Error-state has different slices because it is an ESKF + ECEF_POS_ERR = slice(0, 3) + ECEF_ORIENTATION_ERR = slice(3, 6) # euler angles for orientation error + ECEF_VELOCITY_ERR = slice(6, 9) + ANGULAR_VELOCITY_ERR = slice(9, 12) + GYRO_BIAS_ERR = slice(12, 15) + ODO_SCALE_ERR = slice(15, 16) + ACCELERATION_ERR = slice(16, 19) + IMU_OFFSET_ERR = slice(19, 22) + + +class LiveKalman(): + name = 'live' + + initial_x = np.array([-2.7e6, 4.2e6, 3.8e6, + 1, 0, 0, 0, + 0, 0, 0, + 0, 0, 0, + 0, 0, 0, + 1, + 0, 0, 0, + 0, 0, 0]) + + # state covariance + initial_P_diag = np.array([10000**2, 10000**2, 10000**2, + 10**2, 10**2, 10**2, + 10**2, 10**2, 10**2, + 1**2, 1**2, 1**2, + 0.05**2, 0.05**2, 0.05**2, + 0.02**2, + 1**2, 1**2, 1**2, + (0.01)**2, (0.01)**2, (0.01)**2]) + + # process noise + Q = np.diag([0.03**2, 0.03**2, 0.03**2, + 0.0**2, 0.0**2, 0.0**2, + 0.0**2, 0.0**2, 0.0**2, + 0.1**2, 0.1**2, 0.1**2, + (0.005 / 100)**2, (0.005 / 100)**2, (0.005 / 100)**2, + (0.02 / 100)**2, + 3**2, 3**2, 3**2, + (0.05 / 60)**2, (0.05 / 60)**2, (0.05 / 60)**2]) + + @staticmethod + def generate_code(): + name = LiveKalman.name + dim_state = LiveKalman.initial_x.shape[0] + dim_state_err = LiveKalman.initial_P_diag.shape[0] + + state_sym = sp.MatrixSymbol('state', dim_state, 1) + state = sp.Matrix(state_sym) + x, y, z = state[States.ECEF_POS, :] + q = state[States.ECEF_ORIENTATION, :] + v = state[States.ECEF_VELOCITY, :] + vx, vy, vz = v + omega = state[States.ANGULAR_VELOCITY, :] + vroll, vpitch, vyaw = omega + roll_bias, pitch_bias, yaw_bias = state[States.GYRO_BIAS, :] + odo_scale = state[States.ODO_SCALE, :][0,:] + acceleration = state[States.ACCELERATION, :] + imu_angles = state[States.IMU_OFFSET, :] + + dt = sp.Symbol('dt') + + # calibration and attitude rotation matrices + quat_rot = quat_rotate(*q) + + # Got the quat predict equations from here + # A New Quaternion-Based Kalman Filter for + # Real-Time Attitude Estimation Using the Two-Step + # Geometrically-Intuitive Correction Algorithm + A = 0.5 * sp.Matrix([[0, -vroll, -vpitch, -vyaw], + [vroll, 0, vyaw, -vpitch], + [vpitch, -vyaw, 0, vroll], + [vyaw, vpitch, -vroll, 0]]) + q_dot = A * q + + # Time derivative of the state as a function of state + state_dot = sp.Matrix(np.zeros((dim_state, 1))) + state_dot[States.ECEF_POS, :] = v + state_dot[States.ECEF_ORIENTATION, :] = q_dot + state_dot[States.ECEF_VELOCITY, 0] = quat_rot * acceleration + + # Basic descretization, 1st order intergrator + # Can be pretty bad if dt is big + f_sym = state + dt * state_dot + + state_err_sym = sp.MatrixSymbol('state_err', dim_state_err, 1) + state_err = sp.Matrix(state_err_sym) + quat_err = state_err[States.ECEF_ORIENTATION_ERR, :] + v_err = state_err[States.ECEF_VELOCITY_ERR, :] + omega_err = state_err[States.ANGULAR_VELOCITY_ERR, :] + acceleration_err = state_err[States.ACCELERATION_ERR, :] + + # Time derivative of the state error as a function of state error and state + quat_err_matrix = euler_rotate(quat_err[0], quat_err[1], quat_err[2]) + q_err_dot = quat_err_matrix * quat_rot * (omega + omega_err) + state_err_dot = sp.Matrix(np.zeros((dim_state_err, 1))) + state_err_dot[States.ECEF_POS_ERR, :] = v_err + state_err_dot[States.ECEF_ORIENTATION_ERR, :] = q_err_dot + state_err_dot[States.ECEF_VELOCITY_ERR, :] = quat_err_matrix * quat_rot * (acceleration + acceleration_err) + f_err_sym = state_err + dt * state_err_dot + + # Observation matrix modifier + H_mod_sym = sp.Matrix(np.zeros((dim_state, dim_state_err))) + H_mod_sym[States.ECEF_POS, States.ECEF_POS_ERR] = np.eye(States.ECEF_POS.stop - States.ECEF_POS.start) + H_mod_sym[States.ECEF_ORIENTATION, States.ECEF_ORIENTATION_ERR] = 0.5 * quat_matrix_r(state[3:7])[:, 1:] + H_mod_sym[States.ECEF_ORIENTATION.stop:, States.ECEF_ORIENTATION_ERR.stop:] = np.eye(dim_state - States.ECEF_ORIENTATION.stop) + + # these error functions are defined so that say there + # is a nominal x and true x: + # true x = err_function(nominal x, delta x) + # delta x = inv_err_function(nominal x, true x) + nom_x = sp.MatrixSymbol('nom_x', dim_state, 1) + true_x = sp.MatrixSymbol('true_x', dim_state, 1) + delta_x = sp.MatrixSymbol('delta_x', dim_state_err, 1) + + err_function_sym = sp.Matrix(np.zeros((dim_state, 1))) + delta_quat = sp.Matrix(np.ones((4))) + delta_quat[1:, :] = sp.Matrix(0.5 * delta_x[States.ECEF_ORIENTATION_ERR, :]) + err_function_sym[States.ECEF_POS, :] = sp.Matrix(nom_x[States.ECEF_POS, :] + delta_x[States.ECEF_POS_ERR, :]) + err_function_sym[States.ECEF_ORIENTATION, 0] = quat_matrix_r(nom_x[States.ECEF_ORIENTATION, 0]) * delta_quat + err_function_sym[States.ECEF_ORIENTATION.stop:, :] = sp.Matrix(nom_x[States.ECEF_ORIENTATION.stop:, :] + delta_x[States.ECEF_ORIENTATION_ERR.stop:, :]) + + inv_err_function_sym = sp.Matrix(np.zeros((dim_state_err, 1))) + inv_err_function_sym[States.ECEF_POS_ERR, 0] = sp.Matrix(-nom_x[States.ECEF_POS, 0] + true_x[States.ECEF_POS, 0]) + delta_quat = quat_matrix_r(nom_x[States.ECEF_ORIENTATION, 0]).T * true_x[States.ECEF_ORIENTATION, 0] + inv_err_function_sym[States.ECEF_ORIENTATION_ERR, 0] = sp.Matrix(2 * delta_quat[1:]) + inv_err_function_sym[States.ECEF_ORIENTATION_ERR.stop:, 0] = sp.Matrix(-nom_x[States.ECEF_ORIENTATION.stop:, 0] + true_x[States.ECEF_ORIENTATION.stop:, 0]) + + eskf_params = [[err_function_sym, nom_x, delta_x], + [inv_err_function_sym, nom_x, true_x], + H_mod_sym, f_err_sym, state_err_sym] + # + # Observation functions + # + imu_rot = euler_rotate(*imu_angles) + h_gyro_sym = imu_rot * sp.Matrix([vroll + roll_bias, + vpitch + pitch_bias, + vyaw + yaw_bias]) + + pos = sp.Matrix([x, y, z]) + gravity = quat_rot.T * ((EARTH_GM / ((x**2 + y**2 + z**2)**(3.0 / 2.0))) * pos) + h_acc_sym = imu_rot * (gravity + acceleration) + h_phone_rot_sym = sp.Matrix([vroll, vpitch, vyaw]) + + speed = sp.sqrt(vx**2 + vy**2 + vz**2) + h_speed_sym = sp.Matrix([speed * odo_scale]) + + h_pos_sym = sp.Matrix([x, y, z]) + h_imu_frame_sym = sp.Matrix(imu_angles) + + h_relative_motion = sp.Matrix(quat_rot.T * v) + + obs_eqs = [[h_speed_sym, ObservationKind.ODOMETRIC_SPEED, None], + [h_gyro_sym, ObservationKind.PHONE_GYRO, None], + [h_phone_rot_sym, ObservationKind.NO_ROT, None], + [h_acc_sym, ObservationKind.PHONE_ACCEL, None], + [h_pos_sym, ObservationKind.ECEF_POS, None], + [h_relative_motion, ObservationKind.CAMERA_ODO_TRANSLATION, None], + [h_phone_rot_sym, ObservationKind.CAMERA_ODO_ROTATION, None], + [h_imu_frame_sym, ObservationKind.IMU_FRAME, None]] + + gen_code(GENERATED_DIR, name, f_sym, dt, state_sym, obs_eqs, dim_state, dim_state_err, eskf_params) + + def __init__(self): + self.dim_state = self.initial_x.shape[0] + self.dim_state_err = self.initial_P_diag.shape[0] + + self.obs_noise = {ObservationKind.ODOMETRIC_SPEED: np.atleast_2d(0.2**2), + ObservationKind.PHONE_GYRO: np.diag([0.025**2, 0.025**2, 0.025**2]), + ObservationKind.PHONE_ACCEL: np.diag([.5**2, .5**2, .5**2]), + ObservationKind.CAMERA_ODO_ROTATION: np.diag([0.05**2, 0.05**2, 0.05**2]), + ObservationKind.IMU_FRAME: np.diag([0.05**2, 0.05**2, 0.05**2]), + ObservationKind.NO_ROT: np.diag([0.00025**2, 0.00025**2, 0.00025**2]), + ObservationKind.ECEF_POS: np.diag([5**2, 5**2, 5**2])} + + # init filter + self.filter = EKF_sym(GENERATED_DIR, self.name, self.Q, self.initial_x, np.diag(self.initial_P_diag), self.dim_state, self.dim_state_err) + + @property + def x(self): + return self.filter.state() + + @property + def t(self): + return self.filter.filter_time + + @property + def P(self): + return self.filter.covs() + + def rts_smooth(self, estimates): + return self.filter.rts_smooth(estimates, norm_quats=True) + + def init_state(self, state, covs_diag=None, covs=None, filter_time=None): + if covs_diag is not None: + P = np.diag(covs_diag) + elif covs is not None: + P = covs + else: + P = self.filter.covs() + self.filter.init_state(state, P, filter_time) + + def predict_and_observe(self, t, kind, data): + if len(data) > 0: + data = np.atleast_2d(data) + if kind == ObservationKind.CAMERA_ODO_TRANSLATION: + r = self.predict_and_update_odo_trans(data, t, kind) + elif kind == ObservationKind.CAMERA_ODO_ROTATION: + r = self.predict_and_update_odo_rot(data, t, kind) + elif kind == ObservationKind.ODOMETRIC_SPEED: + r = self.predict_and_update_odo_speed(data, t, kind) + else: + r = self.filter.predict_and_update_batch(t, kind, data, self.get_R(kind, len(data))) + + # Normalize quats + quat_norm = np.linalg.norm(self.filter.x[3:7, 0]) + + # Should not continue if the quats behave this weirdly + if not (0.1 < quat_norm < 10): + raise KalmanError("Kalman filter quaternions unstable") + + self.filter.x[States.ECEF_ORIENTATION, 0] = self.filter.x[States.ECEF_ORIENTATION, 0] / quat_norm + + return r + + def get_R(self, kind, n): + obs_noise = self.obs_noise[kind] + dim = obs_noise.shape[0] + R = np.zeros((n, dim, dim)) + for i in range(n): + R[i, :, :] = obs_noise + return R + + def predict_and_update_odo_speed(self, speed, t, kind): + z = np.array(speed) + R = np.zeros((len(speed), 1, 1)) + for i, _ in enumerate(z): + R[i, :, :] = np.diag([0.2**2]) + return self.filter.predict_and_update_batch(t, kind, z, R) + + def predict_and_update_odo_trans(self, trans, t, kind): + z = trans[:, :3] + R = np.zeros((len(trans), 3, 3)) + for i, _ in enumerate(z): + R[i, :, :] = np.diag(trans[i, 3:]**2) + return self.filter.predict_and_update_batch(t, kind, z, R) + + def predict_and_update_odo_rot(self, rot, t, kind): + z = rot[:, :3] + R = np.zeros((len(rot), 3, 3)) + for i, _ in enumerate(z): + R[i, :, :] = np.diag(rot[i, 3:]**2) + return self.filter.predict_and_update_batch(t, kind, z, R) + + +if __name__ == "__main__": + LiveKalman.generate_code() diff --git a/rednose/__init__.py b/rednose/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/rednose/helpers/__init__.py b/rednose/helpers/__init__.py new file mode 100644 index 0000000..0634321 --- /dev/null +++ b/rednose/helpers/__init__.py @@ -0,0 +1,26 @@ +import os +from cffi import FFI + +TEMPLATE_DIR = os.path.abspath(os.path.join(os.path.dirname(__file__), '..', 'templates')) + + +def write_code(folder, name, code, header): + if not os.path.exists(folder): + os.mkdir(folder) + + open(os.path.join(folder, f"{name}.cpp"), 'w').write(code) + open(os.path.join(folder, f"{name}.h"), 'w').write(header) + + +def load_code(folder, name): + shared_fn = os.path.join(folder, f"lib{name}.so") + header_fn = os.path.join(folder, f"{name}.h") + header = open(header_fn).read() + + ffi = FFI() + ffi.cdef(header) + return (ffi, ffi.dlopen(shared_fn)) + + +class KalmanError(Exception): + pass diff --git a/rednose/helpers/chi2_lookup.py b/rednose/helpers/chi2_lookup.py new file mode 100644 index 0000000..e22cc97 --- /dev/null +++ b/rednose/helpers/chi2_lookup.py @@ -0,0 +1,22 @@ +import os + +import numpy as np + + +def gen_chi2_ppf_lookup(max_dim=200): + from scipy.stats import chi2 + table = np.zeros((max_dim, 98)) + for dim in range(1, max_dim): + table[dim] = chi2.ppf(np.arange(.01, .99, .01), dim) + + np.save('chi2_lookup_table', table) + + +def chi2_ppf(p, dim): + table = np.load(os.path.dirname(os.path.realpath(__file__)) + '/chi2_lookup_table.npy') + result = np.interp(p, np.arange(.01, .99, .01), table[dim]) + return result + + +if __name__ == "__main__": + gen_chi2_ppf_lookup() diff --git a/rednose/helpers/chi2_lookup_table.npy b/rednose/helpers/chi2_lookup_table.npy new file mode 100644 index 0000000000000000000000000000000000000000..6f1bd959c194cbc2f955d8658ac913c088ffcab6 GIT binary patch literal 156928 zcmeFY`8$;VAO0eEnijpEkqLLO$qScb3LS#uoLMch2 zMM`#&r6OzMzP_L1KJGu@{`ot<%yG>Rj5*FZugCN8d`WV0S-Wn_5{|YU{G+7N5Ia&pxs{o=XD2*AM!5?DrzCbyy6BzM8q2uD;q) zwf}z)0gnIs_`jdP|NR91zfa)$hLXJtmnlSK;`akBDfUFxU$^M3`ffzk$6LEKuk9u- z^Dlc%RoqXwM8!(fvO|dG40n;lYf%I}_nYdWoLFKcZgQWIUOb^pSPup3B@*3^0W)ha zClUXcc{@s6Q;5ee*m0}&T_ZLX4Y4cQ(}T!>+(cri--s6WpZXcB}ABC>HD(Y zM}+&)9NS<29ur(Q_eIz;D~R_j!OQZIRYag1=Xg+1HK9L}rYTzVj3_ZZLZ~gNB`&(f zR1a>iBlP~h8p(h0obaP9@K@T@6R|3Wi5|~i60j87|8r{t@r7GqRn_8aBCpB0oL2mX zc(Wqo*5%N*M2Sqyv*J6=MBU4GyW_6BBdBlosB$E?5Ix)7jJI5AC2p>^KJos}d*WGZ zN_}bN2V!dx&wIyjABn1veh^!5sWxlt+6SiSz1XAt}61%J?Q*S;R zA|y7*MDjHMAgrV(c5j~;Cd@Q%_CRBl5Qu-swR6W9aZx)!_TcTGM30kl&+VhXh^tH) zivh#m#NicBq-TbH6T6Z#0{7&O6O;GO7rzdfAeb$yl;5xUL&W}ej)MLq5zD?&I3zPg zNUK!buM?go{>uMI{4PF2FpP?Z5-76-Z-KBEZN(g+y;}e3_VB;N3HR+m;h6CmN&|ZdFlU67I_c)CXr8h~`rdm*{?YLp(h^ zFVMEVnb@D>+2`8&j_92YlBYSf65-1(r})2lPv{PIn3}BrNJL3EHQfIEiBO&TsQzis zXJYIBeoi}~cJ*rgbi!9+U2rk9^uG}a9T>m#rjxjCaM8i2yo)ezc1YNn*i9sTVT*hE z_7E4-;#WH@?kT_}cK4)*n5HT)OB-51ggWxNdI6i)1n4tXc_m2?SZ#516T^J?q9sd-nnL0+q zC(;GZW&R{KNJY=(Z~jH}Z$BXF-t&vFJskSLJK#6b`@y=oYyLOEba0F9JU32A6}E_m zt4|OS+cOtlKbjyoOVzDM*8L&kxqh*xNB$6nS$n#co}DDd&F2q0antSbk|WFKhND0M zQM4e!o1jbfhc-gq4u5nER+@wJIvlKKy;dtCARtTFAYSQ%^*U z%KzKF^DWVd{?+-$t;ChidA~cc9|_Mv9iGm;JXH{96c z*iEdhGU{a(^$_gu`F)$^`Ut(v34A|8`w3s)kFM`O3=pM)c0DzQg9Pi-$2qrCL&Sp% zoplNwKL~R|k1LuvLRiMGyEh&?N>mRPr#5~XBXpC`ZDvaUBAQpuRUfPRMX-~@UQc`f zCa7am_K(EJ30^I!-yKiJ3G48xfw(;rMBVM$j#lwM#O}ho`#)FyA;$cTT#EcAiJ|F` zb768*M1!AT(u(>i;_PmpqpXl=;*DqQmMM9E}fqxE)4~}=(C$6 zjK%IRzM7jOIITvawio>+LKli>iucVEA5V#Zrtm$DpSkFU?!8qNWUNAmeNV;jP6`j+ z#5MnQz0L!R$IG_}$nZj(b|_BvA}{=2RP){xmrXh#VpAYfu zT_TT}e6B)F%R|ui!=nLyMVuC1xmaVZ1a7%7-P`HP_~j$Q?`W$E_c7Y*^=WEIWlnc+ z_N!x6*Q=rGTur=eKN2H}}i^ogh*<`k&2={vnR4uQQkJm?UZrx0`Uinj&)Yh;fsL(}caja~q{AGlX@~ z+gGBIv&31!bt(UO%n`YtK$E4nI|5H@Z8(V{f{s@8Drnj`;Um(YMuYO zW`PJ_T;p;+W0822ps`gI91!U}?-lca1I3%P?D$ldpqpJMSap60EOa8&%NLfQS0#GA za3Ckf)>@Ch?Bqn+n+*&9)^XwDQ$>Ty8ZIRLr@d6xm>b8gEAuGjaKq-SXTn!S9_(G; zK=DoFfkf+7&lVnDZ0^#O(~aOoe7VBr$O&E~ex5kp>(2+1vwq=z{e1Yb(L0E`iytdI z4iVa4`SBuXW?jsdrFdiFTEDh!Dg4Y=#$VekfD+G?oyXe+@SEk&CGRc>fA?hDkX}I) zxN*yt`Uyem&&wA-CxqZJBEX9%VJP?RP^uFWfsezC@U`nAD0TOE)lV0NaJ${s`dU%& zM#)}yXdni?O8K)BVPaSkVa{LiN(@sWr>?io-JhPb#xo9EblVd=rzA zz!I0@xP^TZD5rgVrSwt)$yA@IM2aM;{3FINT*$K;@A*7N(UggjDti`JaTmB+3^-tvAY1x)3?&ZwDFfECAoqP~TSIP*Py zPhhYT9wlwAZCtL5?fY$x&S|UQ`mSf!s4A*REc4T{mQh2ruzJthTs3%lc1fAIsH4)t z_uwNL4LrTjc=OS$2HJgS9b&>1eBE0;c62Wl4{k|a{OO{N49VH`Z!5Y93lmMxBcg-E zOps6RhyD?wDu5$)&9PsEUZhm_w~gb3#MvJH?8ON}>8;{Jo%55#quo8~RNiUAYIh?y z_RbJS?e$JAwX;O-i@R>_qJN2mdb^|V*Ub|l1DQNkr~eVoW}1{OPZo%lpPDoG2Nnro z%eWtoCpo}lnda3avjjVyIc*BMy#(Hlqlz{xPW-A}m42MOPn*2(Y(BJt3(dKL-&Qnp z;U&jX6Ut_8WVL@MRsPeU+MX!a6Xh=D=Q^{F{;+!yDI{SzPmPK zR#gyPO(y@{x+4g``33J@10fju_rH8oB80*a)ys!%gfZc9Z}fM)Fn;>`if`H=0x!L` zh{6sLXg*JxQ}Gi;+UB{(h0~(on?L`MuoJ_|#aoKbXT%^#r^ZXX7sGa&z~*FSain?E z=>6W}*yJ*{L%2vB@0NeQrMM`LMJ(@7UL%1<#_J0jS0!M5`4x}(kObsk-FG@*E{QmI zQ{S)gl34T7aKqUSNwmGsRlmfPg8x8*F8?Vh6boOLUFeWP%-(B?=S-wgzVfL=Q=&9j zmgZ$&Mx>!=)%LYzl?)DhxZY{GCj;GUL!ah_WO29e1@-U&SyYzgCGTmI#k`Z?&)H>i zh_CIm-jy$h9SoPfP0I2($TKq?nJAAX;*BpK@+#o^T?5v`V+ttpEYNORP(aEDR*^@v zB1*GDDqH!LpnQpmE6GZr^jLG4=_sSA>c#BJXUfR=RQD*_Lj@m2ZNEQQN;VpQO=?5A zDmLhL`u(*~gMIPR>Qy(@aMOzjrSYqS^Y%hx))94Z`*h^;|53-+h!fAbj%YyV!4ZoF z0ZpuX?@{PN_Pu-MtWT2%1)TrsY+BBw0!%RnIf@qe_84~buhd5J)TV_uPj&F@OQX{B z7c@M4-an^1I7~cp>uCW+!h5<^eArU`MgS)8KH5oQuOVN_;rLr8tsfH(B9g&0C`R`AfKgof&z;D3YR32)4 zPEFaV@+kiK-@?7W@;D;8Vd~s21>AT+@d~V0z`b+wd-pRG(bcUmTzpLtN=qNN{kK#J z>%^L~vyUjD^iOV}#-lD^vkKIGFV&W|slblMZXH*Hqw}LjSxssX^ZdzCuB?utONt!q{p!f#{GGf1 zg*s9$q%?J?X<(lI?&W-x28@09GrapWP#*UB$tNdGyjoEpZCI@d2k(p8C(J2$bGgOc zyn=%3E|1(qR#D;UKeBUUKNV?@MmK3)(84p(%w65pT&k$qLc`vq&`j zckS#G*Cp^d;Q!e%krNH+^kVx0F6cFV-1Mk|8?%bm2g)Avpr*KB(&!#99<~!2E{S~5 zzYsw@-^UMY(OV%cc1zLta~t1jNddHvZ8fUv5WwleF)<4=$C598jm7L1Lh!|HVH6FL zOSKPdIQvx?$5g1tl`o0l#Mo;C`btsER&Ts7FfWQb7IDepu41retDlt17sJ2glQYxY z;%Gk2TxYaR9NAypySfX+@$|;9xje4~j8A>oJGxZ@vQHX`0}mvCn-x1txg=r3ejWG5 zO%k=cIqtoC@_v(k_d>3po{B!jxzoPy)GWI!aW*t=;~23P#nP2X^qh5z98h`o1Ykw9Z? zdh<^f1@9&$n_T2D=3aX(g6!GzMX}WHeDYA(dvueMr#v>)#V;or2j9+YO4pQEz;t}t zUFpLL7|5D&m3XfJN#@jldPa&UySB;qV3HzuGp(ln{ZT|ixlnGWn-ZRV6xuOLrYw!W&c&XP~q))La#Ttlw+z-c!ZP z>V2CPMAdMy{Y<6$DmC00eV`wGQVsrV?+LE2Q-k%BN3ywG>WDrt@c4nfI&QzZ;umpB z9SeS!v`re-QStH{2alu%_eEo>zjD$| zN)Lo{mgO!DePqW~J(=`2z(jbncQ&^nj#cOjxTP^bKQ53VyqWC()jGB@wj4NbUKPS0 z&WU#pbl~*i9kNT}P%`XBlu`oHB z^g|F4o+^)SjSAtNV%3iI1H#BiUAso_Bbn>P2fz1MiNZQMdavXne-pz@vVZxEnrhzdlz`CjLXMGIGS|Coo%6KFxr@U(!a7b8gXwbi z)q|3xLP?o&ag+i_)B1mkWPYh19<4Iqkw)p2_|i;IX=LAtT%Gh(8tX>py zPqWl#<)CF=tlqv!9_O|9F1{*|hvQHAq(vbGe9i2WJMF80^FkNuf?p`WN$bYDW=%y1 zxh+Y$Px8X{kM+kTyA*M8Q_gx>LJ4&r-%mZisf46hN;Q2^3AV$pJUw=i-0-JXD4<3e zE%BBiUQ`t{+~u0vd|CxplMknF9aBMs{%_*wCRGH88z;Vhq6&rSCATaj)KJx|lWMU- z4Z1h1awj9y5dUFDBD6>iygf^6n|`RFRmABmpQbu!QlA;j?dm8v!i?T_ne1hL*NBvN z>eyOi96T+o0gYB~(}dL;SbkM$S#Z1tE}aYcRoS3{s>d&0o)FT+8SC8@-<>s)Y!(^I znXHMWrWg5VzG&hWmHK&mPpgOeAJ z^}LPM!TNx4rahM~k_W6#`NZoYI&RCA$BHy~u6JXpKBhq-HKR|?OAo&Umj2?_)W=2E zti$DLeaxH5JKP>J!0K~>r>nROan)nn#3MZhUdIjPKj37-QmI={T#to=og!;_iaFq& zGE?Pj%Z=cS-up$bcyT&x_lX@JNzQK9tbI@Nw0XJxAh*5{w9iRs##|-mxuB(WZKEQP z%;t~jl@`N8QO+)AF6k2rWvaJWl0G41b#`=}I3f(=xf2~F;JP3nVNK3w>EBITRqQ3P z$N!vXVTB}`m00cDSyK2}dMD$^Z7FECKT6*yBMmR}wfFT;NJFqg+}&ne8a<5l7oY5q zLBZj#G4JYS;7}!1k;9OM*v(&Wy;5Z%HAMTXyGYJyk&JXnFF9QHI`z<|K@JjXqGHeK z^5CBhYpl9RazbCu0oy5gkl!d1uPqAjdi9ZES)qXEN3_B}sVG9h-hIa!GQZ#K5BcBk zRfO3-j$1qqO2~;jbHYDI39%n;Fh&KGajfm*!K?d}p?v;W|M6yJoP76vvcyOQoSHRD z>{3)v9Mtun`Ck>>X!ALlvr`qfe>F~|)v2QD^QR(NX*G1rPX-z}sv%fo%JqJ@8mbT4 z)}4Bw2BXW%oZt1T!C|}PheSDbIEZu}f4f#4)yrDCF2|7l>p9->>#;iY_`ZMr{!1NJ zJcG|p>S*A)83*U*T^g8E=_vYfMFU5z_GZ3p)j)3d1&?DQnrP@=@1?d%6YQiG#j=x{ z@UJNm*j%TH;_}01F+Jou328&}KGq4k3T8gm$IikL)rrQlfk0OAIli>Lqc0GXtYno-5l9GY~$;#b0)fiF1*E^k0Orkp87$ zu{F;K+rM@HG!5ZKSBcU1&rp86eXO7QW3?bm=|&r3FA77hq~P3>6QUS%F?5MY7sIBz zIVU=O#X&b&Big4a0Tpp^%eU_&u;`!TIDSYHFBENyI3=X;#d0!cE!o#9#gQW)$vKW_ z-EueJnKTBUl-{jeAp_IuThY!9GKkb_P`k2H7Vp;bmHc}y3vL;s)h&b^C>!^m+x18e z?ryE$2KD9PepiqqE1k@9%;jx$5(-e~VvB~vD8TXL=9<271^ip8hsY<~V$hB!ID**_MRiBN`~=U*v_0cGr)ZYjI(tOED!j<3^Y zDj;rrJRqQn|^%U^m9O*NjuhzI)!wWKhxh+_8-( zkcysAV&YRi6*6fDydIPM;XWjrS;5o-Q)cPO$zUzmzKD)J@>mOJJTA2FT-3syoBJD{ zIcP)vt#em-f;Oa%$JzR}Yh&Vavgnu=ndh0N#(jr$P<%aqNbH3UqPF^P=a$z+`!)&p zumD}qZ4{jDztF{@f$sW`>NHH;8J)I2MuW{EFFVH`8a{Xb+DbU;p)E1;OUgq%OkQ1< z_m0f@9{F=#F_-n>utiXGm$(6ZIxY>{BpJZ(%y$tjWja=r{V~{5K*t^)=XU{4h7g?D zb2f0+5Mnm2wVYcSxc$v?sJEJd-})B4UyPV&I3{bKP|8H*fl9%vPAsTvWCl9(7-7WR zZ8hhJ5f1CtiR$PYL!M`a@@Rj6=aEX;0OIE94Qfu!I^H?>Uo%$miQlW;pajqAk zf7GyLP5`U))xr3%Y30;^>UdG|lX2>rI<`mc>*Z}#$AvE~rgBlRfbGmX{O%q3MT3F_9)`azE@50eUP1LwARP24FiLKJ9 zEH;_rP@(T!Yb_}d{~5ZnI+y|}(le&yQy^rkdGX62$<`YvlyF_8Suz15wHmiO<& zu3e>~A^U{l+()vXb(q)ZB(<=0)4I-_^;(Ga=iVuvsD&toF|q8e76#5<_HYo@#&!RJ zaKm-l5O;pY5W1+1c zH+r^5508{(Yh>dI)2|^m`W`*#OvWNMb&YJIO!G4+sem4!rx3uUuUxC-;`;+y2e2I z#)gQxQ3jsBTr;`Hfr;dME|H?yOk{Hv*IyQAA+6w0W^Vd=lglMlvSGyumkZE;+^v4^uw62yeRfbrPLUPAdWt?rllzCJ~ z1u1oPoc|uGAfJ1;VzGrPwr&j*`1Mp3PWv)8hN-LJ%dYK$iymr75VzsW$RPQcD{pUT z7s(%Ao29R*sN>kr!9gXGkN;e#R};IUj*QVGr%#Z*Y_1zrbXHsgKDT&O*=seR>X+wn zI!*)D;d%~NYBiwfesnN!K?AbQZcTFLn)tP$ZvN&$P3#wN7ZlDXud9=d_YGP%gymW-ByX5jeSIfH#r*HDkvS`Okh= zmbW7`UGlz2^DHKN+Oln+CAdfzoZq5$5wp5j=KJ)B7HBZI+}CX#N5g`$UHjE{G{kqk zUB5|54-rbmiZMQV7a}Bh-dj3`HKMKF8XJOL6p~YsW(e^& z`f8)R40I=Cs5*fG+QZ{Y%Oe;lxP87u{RsmO>${EY{*ipMN=s7FjtTA=IU4&M6D~55 z56!=z4nEDc{CcQ=B~%%fv#KN}&H#lX`a#%K{-{67EE7~IECdiGVCpt)F3v02y*9L$eI_&zZtoZ%j77L|nK0UB*R+56Y+ z#NWYAT9rpNw*ER-%cj(TUy!6=4@b~jTVFA|gL6HY5YYjbCN*e*pBB$*i;qbWiE zVwYmykP^;^trXZv?gP2^Z02$#d1TbHO|xKH1=7)xBf(cyA#SC2P)kV-rK0?62Yu9V zvS-`rYI6P?s!G~CFt3L4kM=&NNqgAW?Gsw=VpbPjSv0(QucW_)jN<2IGh7HquXMSbAn5 zw|S9(i=DMDe1%bw^~J|mp;z;jo92T(1%R$ zOilm1KD?;{L$Rw2VAFZXHuH)B9!fsDu;qsVZe5I%eq}{R`R?jY@e6eP$mzA*{GE>U ziuKxcgdr}sjdey}HH7C&i}N+phUmXk7x#^vSEc=E zdlt*XX?tZsO`S-i>Q;{B;wDp-Rf|BJAC=t zBXv-A1Y~*gYoMXu)Lzj|1NkaVNgP>Z-dF3~SpHK387+CAWXQgzh81qS7OjcRYKQMk zlKi}9v-cf)Q40RJed5g8L_xy-gs1vfC|Fmp^XlYR3d$`v?UYob;$pd?;T2CR_I}?| zo|;9)H5cAsjR7jge;uz_uB`=E!%ALp(%)?m@twJlqlNZp#>o$)$J?TIT4<2$=aF~M zygvA7V;TRme>pkYh+ERuyKhh%Ee{sk={h<%Ot1Hu^45WO60^4{TL)V@%Z}E3*THD; zZI>_Fx+sn7JF4lUi`R@;f!jH{i26CB=r^Q`lzUD;B4{)ic6l{__ow0bi5+ewc{FTZ zv�@Pa5uv?6`W1rH9*JuRUo$q=&h?8$B}~>!JLo|6{HNJyi9)@)fbuhl$P9y{0&Q zl4l8*4R7_4`#g0rTgCu4U!3UuM$VUg&;HxOmt%m4{-X)3aRZVAcC`mt)6uYJq4CRU zI_6y+cOEC_&gv*}g`--As7au%>^p3T{P}0>mY0Uuzc^gT6k%ZZoKNr)Z53{klY43xD#5pSttVCQ8^xeAh7D$-cne=0NarsW4$oHG+6)w?ooA7>)B&9Bk_ z5ffp)>@LnRCXQ6C8c5Y*0lsRLo*pa=&#Irhag&8=hH!S`Hx}aJj{HtgH^P(N7^OvT zBQ#nLj<`HD0{vg9yw(ynK5%+RXu7ZwtEf_M_<)UOq4m%F#f%Xy^YZxmFk@s<4=;3# z8AD{*VTq6XP4GvdD;(UWQ0dAHcY0uo6?rdStcWm!=jywm){*Ae(l&f-U#A6@u9paG z{~?9C@>k!_{gQ=Ovaa`9E(J6UTsxhWt%#ZOb3JT9Wn4cRCv(?M1y}gY3$%8qLU}A| z@P?rp8c(c?4$CI@`PABzQh8BX;RIe`mu7%_% zF5SKQ+Bmk$PSpBLg7%;$*W6JT=`O)3X{6s18a90Vo8;)x+Cf)KQ5w3atAb9gr$K_@($+wo{rSA zkoMLqblm2defpt?j#uJh-*WX0L5;k>=o4ZHKOwD83blrqtL72@LGt&Qx?FQBodL0C z*V;|44D4c+-4BT*=gwLwMaOKC!^7U3ZfRzqIL9=Y@|OXPS0^LZXfYA8P3Gd(4NN@z zKvUfn#e|%Htj+#BCit=r&83mtVrQ6PgaGA*ddag!I5Diyq59eg@$bum{|K?swo%;o`+7DS z$~?>5ud)%cgF5(rfQ>@OIId1pW9a+y&9cuMqxn|wg~}hssEOGmnC@f(QG(L%{=@|O zSsu zFH$d-v2)d-bV9~+N>>B)t;Y^@q-kLHon?pDh-zXwk8kz5BbpcqiI{o(jXWpCai63` z3S@=^YfW#G=SBjU!pmkU7=L%GC3`&;tF$(Wm1k2SFrT!m{4W*5*{_Uy)@tFXT3Nz> zH?;ttea?QPqz5sbw^g>(#%sqfb2m?E!_&3tkVvaG+Bq6?Pbri0;J*PL3fb3I-myh< z4|E`UWPnS3MhCmUQM2w5y14Gf_4)2eUF_{T{J`*yE;^bbwAM({5NNS!qsSH-M7C)~ z$KIsjjb_)Hie4Jl&h}K+=;&cdq15)QeR`x*0PtVqvePJ|1`9 z{+)eHA6ogZgrcA8Lv@5UcSOJdJ>RXJsTkc&=q9wi|#^`{MT@H9FE- zbH5etp<^oj-DBrGlCNV%__qC_Lw@%_Ql}-!A8h}Kp%_DKe`;cTqR|li&RN5q0%We= zq`0*jl08jZKd9-#KvmbeKW$+Qr0y;;oJ(imB%}6GLOlZyllZ;R< z>u{rQ76=EgAY zs1r^-W(?=9ux6gu80uo)uth>nndW~j8ONLrt2j!?0fiyu~7!0oHkXqkp3hD_!|-!rT* zv^Q~3Hq#om!lCtNGUPGst{tVyqYS_N>M2ih-?K8u?S@;D8oJUH|NL@O#~{0GxjnZA zj;F>RG9+_<)R_K#QlIoE?16WI1tibJNSwK$M}Y|KdGu5o1zWD3>bxvMh1jOz&~2eq zgbw#Up6H+=PblX4D4~U-)7?FlWX|0@?u|U3)54DZy}#TxY2&~5PgKh9YoqzI>a5NZ z9bC*2rGDN-?j3jiY@Q+K#p?A3-WE*jK+k2#5$XzEaQxx}{hPf+2FN;O>p!{a&`kF0z5HB7T@XXXhjrZv$o?$&C{_@FP zVWf|Vb-GC=;rf`ezg5;%qmQm9--E{KW8iubi2ypj+M7ueC3M)nq-;JtPsgzf|7pzI8RACJiL%TyhIl-q=oQy$h@j~^ zwqJ!A=(H1WtuRNz;}g1X$KPy^|x7nW0?4*;icesp9#`U3JSK8y?u6f^P0a*@|?6l zg$#v-6obXmptUSShHTjAAHu@sA7fpDnJhGx%bwWvhJ{OsY?s4iz8&wJIkZj72$jnB ztW-A{;TUtz_Lk#D_{eut{1nM8ANDA1U*Bs4Z%=QmkY>Y#RU{ql$i^D;rXKmDY&>(z zd1F|_#=U9X%)TFN$ORui>`pPpi5l@kFLxTFBeLb=#v8_9{#~kU-eHX1!t*yDtC}Eq zKlcfBFB7<|arbP0wanYf6g-Tdjg2X!;Mi^Yjx!ciyc1U(Y%8ZCO5Nk|w2>Ar1~L>R zvb8WGwuT}utqtcBOGNS_wK24MLMoi}BL;~HLz50V2#@1?A4BGxeQJ|VIJtK`9{c11 z)m<0Vls)HbN_Alqt?7DNmLO!$^@w?4)`otEEVU;r+=zn;CJ2B6Q< zCgw;Eq1=M`T@gC|oqtgCZ!;a<=LWa%-J&CV_bK)FBXpRwT+BUSVhHBbHBzHdhM;NA z3vPU6h(GhOvu;Zn;2-`r&PQ@cs(!$pryCfk|I9Fn4Pk(H{JGio>kJ52GO_j<17SZ8 ztL+#dIlNk~^nxH0{SH?~eleJc`pf(Lm@CO4TXMIrh+x96?a#!jOeS_6yf%5^B@@?0 z%oa4r`EuEJ+dgg?7H)ZFSKE-i{p$$l%%|NfIGxJ1ZzKK6+N%$rtteq(U+dr$o#b%u zx621E^BJLq`c&aG(+G}LgJq)IjZjgLb;0ddWPW4!7|uZ0v4RY#3``qfV1siuWHIVqV#WP7IP?H2jWs?238^Z-nF#K`tfBPIvkn%dndrOQ7`Tsg=QxDXbAe8&V)t_9Z zs9oVAE#qiP?!C8_vJy;DcCz|o`e##YOVrFrs#IWB*A{(jXzbMT!B&Jzf-fI#IIwH@OYP?Daa*+yF;f?qyQTGI+O)6PEe z->krGvu$HVl{EsohnQ%yK~C5f4rda<8B(;~6xRezQ%Dc+_SMrgDk>&BsAtTzpnWslf398&_JpsL{aS5!UC(>Z z`&t`s5;r+U*y@lz_0M=pu@3r*9Mlvwbn#S7UNiHIE&>*P4(5@bq{pILJ!caQTRcKz zM~Z0}+IIbZy@Vco@ACc&575J(;uS2rmwGU)bnkao(?{8@_LohE^|7r!F#Y>$eXMz> zxU@>u0KxL#6@!8d@NZf8gj$^e0^2GT`lZNzp3@xqxSNhxPxoe_Vlv;~=r^x%8bVe1 zM)Bo!hTvLQWg&Lc5FLA+?B$0Ik#lzQzb-`vmdW6&kSzmm8l*4D`jGjK_NDWmXJ7~4 z@!&Rx8G{Eips>r)xWkWtY%`=FCue_^d%d3mPzzqX5ye! z;r-zXCTufp_lxy1QD&;`yJaa0dbSIBjfN~NOkeWf@5+L^W&Mv;M_I7imYm|5#lo~l z41d*Y7Lt10cy~{*U^B7)(l$jhzpH=E+_y7=kLRBH?R$;jwb(gyDA@?NXl1#JRpg%O z?VAS9AtQX3)((%8WaHWirDIoZ*f=TZY-Z=j#$T?o!gH6|NI%4UdZLyMY2oi;X2036 zTxq)Qp{g;GYI6uKXJbULpLAM88N;_d?uuW5F`mlo*?+so7zA_5l0$}^Qv>5iF03*^ zi@xI5gU3wp!tgb{=8*{mtjis)|1!Zx2mW&5T4O_86fTNOQE z3Z5gZ?`L(*Q0f%wy*AJc&Uc!;CCbdezc%i#8MiqUekj~E++>bbVYjrxbIg%_@cp}r zC1lsw>#MB*Zh^^g zFKg(!jUGsD~WZLSE9~eIu$i#wA}rdS0iEiVt;PLO1Jxm7JY> zqlY{{=yT#t|88Bdy3Yz;>C(lw-t4v#S8^}eSE0oFk_OJBOQj5q_3-Awvi1UUzBG%d zp)Dc3_N$GD>?3^i5oVinD(Drtf0y26sHTnGYSRCi#R?ZsWjXPRC+} z!$3yHhOho7n$?4`WvBbANNc1few^I-0j!rW1f^BQnpu|FN`Ma?Db}X3q^WRS)c{`2! z!jj|*ER;Wy&%Ikl_V;D?wlAG5{ArPS!X$e;fv^2?A>9ZaisH2%u14@<@fA5n8X<6$ z{%`LcBjm0u^!(6d1er72KgCTOp&&#s{=6C+IsR#*qbu2X`1D>){y{e8Ge^`v-(cg7 zP~E9RFWI>KyRPf(1RI<0W~Au+pL~~QW^GtadUy8ko6@1i&`IKMj<{`%iJ+vFms*Wc zYah1Y!)bz*QR_1~<26$#%o(Qlwwhwb^PZEqh#5BSznng~(hO%cRR5HnGDFX)ES}T# zW{Al#ow>5q9AA&Lr)xWz!}7#W-H>E+luXs=f9^ELLfn1-TmuWx@2vFmh_b+|``tEC zA1u%pou+kxbeU8^{=ht4a70(0M}L%C8ITj_NZtd;;j4n3jn-z6{J0uBUdqR>wyUnLBu| z3Bif_&0meEaI4&S=fDare8}@Z|CFwck8RRv6*JoClZ@F_O?vX$CV#cb4Z3)D?U?TC zVO<3A%qHiOyso1=etO3eJ*17;7aB$DVI!xxzS&aiqh0!tuvj71 zy4C=DOyjQq_s9TejwIJ|sL&xd{7QWxnvR2k2TO1D(qZ=8S&TvQ_p+gT|30T1lIKQT zy57x`zND7wob_UM5zjwIL&4d|! z`&bU03Aa_V(yKNz@oBk&?iDiMm5UDF)9x{WhfQJLByU@PK67@4#Z>wZ} z%}rUu!W%(HxsqTOHeEmYq5L`vLN2`n59(Ot`809mYa^r|tcz8Pkut*H)zq*6DFB|`T;`UCb8e@T@FWZqcjt&-CW{W=4JxrgQY9ZpD+RYG0`hf zY=X8eoBS+#O>mt4S&SxWiq?_{p+P%SH0=6R5_5>;mbVx4g>y_XPEQt2{bGun+`bo0 z#LVEf)2n-7xf$Xc!W;OHn&F(Z*o}Y^Gkg%~JG1tu8T3s4QC`r@Q5m1uGw*GV+OYFq z6tc;Fe{%Y|)1WyH9?fRI(X&8ddBDlm0~V;@w;Inbw}5MGb?9|oOF;L@F>zN*TvH5+ zJaX5P++*(gykm(KuC%IM_i`um{%Oxk_h(i}>`BjEt!E9z6Pu15zF`f`Ez3+2s< za`i?2szL_T(^`E5yBXNZmA~$sC=**pk3V#?X5w-;EjGfB$gvwv1ehspy2130CK)eJN#Up^d%2nxEV7wEbMpQvGfL+ z@AFZ9Z^UGbuXE2Fm-chW702x*ZmY5z5@2=!V1{%|MbbJ=rhURC+b^8xQsCs5LK9@ zZ;Z><@fRFjjqxFL!Hi9Mm4*P-#2xpHp;)`(-s|_IU(q#gI@qzij4UQZ?e@%QepoJS0_cb&Wx-Oa#!9QKKuYKwK5 zC7Tw^vxQ5)=2_*Pws^7qUHOeWw)o3@KF`04IA*`8pOK**Dt`Uznc!uIl?wl49yHhU z3*Q-aSJ=^h@m8dyV2@K96CRX`?a^s$nIqe7j|b5vEw_s8Q88ih4e2N*G*bh|&U9iz z=kti3lW9z7=SyFIZ)D=ynHPquX0otDqvu`JW)`Z|x)$%LX2JGqhIHmkHWsE>1`ki5 z{r7L1?w4NDzBtil67fp%XRWU^*Sq=N z>t0iCd7s(QHjy z)~CIUJhs>hpLpG)ukEnH$o)2UIi&B5tYwy`-~8VvtQ@vi-WnpkwB#rgYp7Vbo>{fP z8q?1%=?{;!M$MH{-mYx&%NJGa->tQVW$LMUszYrMw&-li-WfLd>ZF#%_OL-&{icK| zr0<~J7e%6M+Bb_Ys9$O|zVo45D;6=}ukw5A!JP~|@Cb>0 zmdAkeH_x3LJ~EJ)9;AFm)fQsa?`oc~Ma6d?qtnFatD{2V6OP;Bj8W3mNmaI3aC6F| z;GuTV&^WBI$S}vznD?Va{gORY^D|C1ezu3w&a>$z`lN5hu=NH@n7CiFw6FCf6KbNk{ii=N@q_y- zbo(?Gg2xswC=O*|)P^rOb%TW~EuIZa<=D9V;#ISsD;vDv5p4sf*|1JtpqKrJjqKdP zpuh7tu(Ida9=*ZA^MZYrz7x4vccQJ!C4r0fQ@6A}3;}e-w~LrO+KX?`(P)YXrl`%o z6;TV!U2a<7WXhxGrr%cm01wL|cAbB$!iUlOF3Vk6eCU09dHj2n0Ir>%`DKQI z0rn;i@wtbo(d5f3sDG6pD_NgOduHpQrl)VnSGgV)R6WK5Q(qrd$tE7}cqnGAUuyxk zZuMKP=Pj`L@NW+n(z(sx9lu@wS>nd6)5BEkERk?E?7+`JOLVrnw8##S?|uH(@(D$j zP|lqnw(h$n+*6)81nXL%wC~`GK?f`B|6#O?M?QGrc=}&GZH3Op9`_#=R@gM+V$`}n zR@gYpJ?|;;$rk-ZRs+N*`tf7xl{Q%;fATBG|IS(CRG??uPvR4cf5qS43|Pah#C6q! zX*O_9GxN=Iv%#y)qt2e%Y=cclRK{O9Z-a90&cxamHmGk2ZkRM^gSd>b9Vx~PL@(;g zvGib|_^gbt7|TGM?uHjrE;A5X6j-w54Fky`%DK}<+9LACu@weZ#3_r|qhtJRQL`zM z4(Hlp+3lUfSKhNlRY;MidWS6rr3$C*CfGsx>*45j2Rra{!xvaY*YV#aFM5jNC?XhOpqNt}1tz&BCoEYaBmsV&PaLlhJaIg=Lek ze*HLvjpH>9b5zA_q)c^CJ)6kJ`;we-A6~JMJm(N+i~$GAZc)49A~|U9y|0m3M!Y}# z^~cu9T=Zoz}u4=JIostoi6j@Kk-4!>4mdDHw1PU{7j_+2JWdRD}&j zixsCqduCJHkY&`9d3pYN=`Ul9Q3x&{XE76htW{Ph*v-O>eJ{fliSJo%)<)0UOpt$z zf6L>HDKL8bil;_q*h5zWm~Sw{^#yhs?~2TjcG+pzVMTLfI7c`CbumYj%9EOyRCAQx zo_k{Zb91<`^5YjPlMlXs$Xuz+0^=-99k#|&&hs>SA>+0M)V}X{u#b9K9}q9QZD0xe z!&Oe@3oYT2|6s>p+7F4yPdRXvlNoM<&=JmQ2aehx<4H^G`Z60_)JO_* z{b>V9`ne-UlNosLqd9%J69c#Wzf9>|&%pHf{M~Jt46OcoVe!!CG}rSNrQ7`_o%iHQ zGss`rcKJ?%v4<_(M(xP>9&3xqre4o`uh_y`(>R~kV2k&S!qIOO?9f>Mu&Bh=4)0tS z8mbeQ>v$;?6%ntTa5%d6Q;{9iy-hxC`C$jEiCyU#`u6Z$x@d%8o;`|JD^8BvLGyk1 z!T5lDdvv@!pZ>ee9?t_l?3U>=aYpMy{8Be2%r0s@Ss2g6`!c0syL(K$7^yAP`oTnF zj@M~9;uu55j-eXMSa=#-6XSQBg|o8ARQb0oq%O;wGkzQ!IexO{`yOnVNGp}b9b}_1 zvpLVPj*VwgFD`AL$ib`0+WUX`lipJ;f7NAk5Og#&C$x`)jw_#T{uOhfvAlg@Q#u#n zbM{+CcXH9ZV0pX|>3)*s;O;fgiKT3@{~<00KM zc)_yOJmlY~&scev-VcORmY-1K<62X_?egV()G&`9+V+BvH^<&@o9rgQ`l{xHt6c){ z7Y*n|mI~3dZGGJ8Wkz@%?fcK1`i*^hnSTvv@12ypt}g33<){nFEA<|kV5#U+Y~m%# zlcJq|{^6RT`Q0n`;^Wjy6!p4V^_f9&()Qo^4(8D5(tPEcZjR1-EpvZ0nbZ5Y#W-yv z3)nt5^`AI|@}Jn@L*HMtKwbLF+xBf1&@t6kK1{ifg`H=gy`Lq1U3k^tm|=;_iTcdG z=ax8CeyeLKaZ5n0KzNO9g_}b=vIfGf(Bm%+_Bvw)uc=SRx4*K2*}t!&Z~teFL^Gev zdV6d5-d%9qKg1dl`;?u$4_l*u>gmEaVD8Ut4g zGUbdO5{H)+G=BTaK;*M0g}K_c=!}T|yIEq3uZBAxx=~Jg!%flF{-iC|-0X;BR@kES z@u4rZMT49fg+jb64J7SL^FI^AXJSBZ!kNbXqz#d&E9w7vLUmx7aneu}Jv4ifGRN8BQ+AMYFZ{=cs-1X#;CtO_HzFp2p5g6+tXqadP zj9(UTve1ik&f2liX%|qu!mF(B2Jkw}Qbpx6@LjZx_jNoEt9CX74bI`gRz5lR`7R!g zZ~Sjivy_MO`SLGvNApo`JojPCJU(W=QVI7y&&O4bb1DUFh!p7yY~+b z%@A>RvCT2kzrgq0)dS>5e)!uFTpvpPmC|mbB+83AdRa1~i5A#+!62z%g#~h(LU$UG zzo=ZqJR~>75;sF+{*^-NrzAAp>D^(8uBykC&mLRS`B0yYhvluXr{>)9!?1!@ky6-@ zC@aKB1%h76H`khcdVZ?i3Qw(4W>1@9jlOx(-V@YU&l+J>K7EfhoCbalseADMee?UK z!ftDb)l{Yq=-c4s5EK10(s|8#2m8bEHrW5L=k26?8~nXf9%$NX17)KOS?yQ`R>aTL z){`)xvY_(z*tHB8<_SVeXpW!I&Tq9P-*94z!-~kEwy4+KRJq;M7EEzRa)g&Hl8w%O z6eQRpBb|9?=q+1pEdN-0y~P%C8s$&?H0aZ-*>-{l68f?2ziJ(sJae9cFcV zsBL>mAN!9s6L9 zP5-ikMyk=A-cpqRn8!rDdDQez;Y<{DEIb-=iV3;e5)c0uOkA<~D_<*5y1rsv{mh1i zO}7`Wo<}}pXPmFy`Xek9y57*|SFs>lI<)_RJR2ICSA7QU*m(80@|$uP8%FYv{r;V0 zW2Wnw3yqCzu%id3JQ~ZvmB|hd@49j@TWBn8-opV?Zcd^L@l0k*NAZM_q;tKsAC}O3 zzm@&IUlh+p0{>2JYZ(`QC@ZiV38-at?A~Pz%sjNh?XNSS-*e66+8W^Rq9>cn4g-Z( zb)PLSBHS2%WLQBb>7M(ddB_AF%p69I36b$IMltoQY$FfVhp+tkb%}@Atu7fY%{&w| z)*U!CiI28z_srgV^I=%ir;>1*5Azd+-S0a2Fc4dE4)O(fb-&KQ?4$s~R|D6gm4%pF z9CNNQSqM&C;E(^TM6j`xOlnsZy&~|GdqR zm!e?1i+YQqIESH|mlNO1{b-;0+8oCs&xU_sS-`k z5|__EHd}>NZv#a=@5Jq67}#jWjGWGAAY(ZdLBKsK2@)3>AE!Z%T- zyB&JX?cg0te#(3U45K-2HJ@j8nC7@n#EQyUG{=Se^KU<5*&}A*!?k`P_QfJ+FD9I{Ay%BRB8awVizRX$AW@c}!^exlXtL z#KeK=-1XZuSy*wsqRl|eg2#WKt){JGfg@%6q@1VkcLlx(eZ#_Unf&s{ifk;Co3!Q( z&2!F;aW6GjvoUF*RAK5lHul~>FQ|LV#_Pb2^&(Z;PoMh7MoKu?>d&xVzlB3QmK^6r z`>J}>s*^U~IM80AXsR`x3zzYqm#Zx0BEIp(GUf>`q(AcKTxsB<;QfEz0%hO?er{c5 z0&MaqT)1Km;E`~8gFDS29YPzQzorkJ)Wz zPo_2mKe2>llCFR68Y!jU+t#7buM}p zzKkVby&(3^n*b|pXm}Ji`kEE$9UW!EXg@8SbT8MGYmNK0L$9}OwMNk!U!~|r*4V9X zc6SE(E$26lU1Z3y!QMHihaTNvgQ$?i?3>qZ;CJBPyh9yyZewNjb6@IjRqZa>G@bkv zM}OWJ6z&$?YF z*0!g6Mv{igJJ=&s)p7Z$4faq;Gx9dRV2^`2lAotv+hdMXwANVi6BqK=?MPrS@h91; zYg8Z;t*05C2dFo5d6k1Y`!N%)1LJ$-ddYwB%`@&YU}2kV^m0WH7VZ~sS?9BZg#vCi z|2z3E4A%OOWuI9vz88D`JMp>g5FNd62R2Hp>ZZ7EVuSJFTVuv$@*!`BH_vZkV|&pB zi&PB`6qei+&y{k(3cobt!X^%G>#f;yB!_rr!QB%3&m2Um_>D**e`e4kbMB?NT=Fk{S5liNHjF-{n^LK2a1=! z{GEK!w2BXt5|so<-(Y`XjDrAc_{Xd*5(L=n{wliVxd2nvH+zRq5@N+ItCa^Lg?QkS zG3-+(LIvuK^4Gv!;g zQ<@Fwe1_m{@b_)4=J4B^H*(Sz3zR;(tUjK&M?B_@R;6KkG4%i< z#mQlT)NlE>bM&|)oiz6=(woGjdse}M&tr*ej$9HQ%6Msw6?Y8Qadm94GV}TUCB8Pe z$NDkV^^^@R)bF%&{9r@(tu*(>>oL&0;>{5oF9w>N_Z!8elh3HkTfMWI0oL_#8mmUz z!XVH@!$n{V|Div(2&vcd{m!vhORn0YPG!!92cK-Am2skFg*N4%N7_ekqWn|Gz%Q&fZ<0?T{TmYsA&@#3e=}(xRyM=+U#y=GP{B{1n*DopsqBFI2u& zO`~4Cw^{I{t}#r^>=(H11?5CK_6EwtE2A~dH6qDRtkan4_4GLtGrDJ}=*W?-FVv4) zVZlP*%YI4G5*DoY*DRj7kA;}o7RuR$EV>WMK;7{N3(D^<&QLWV-({1>^bxd&HcTAe zXCBW+C$IYKk$g5B_DaK@+t^qg{I_(D4*85#mwYZbbC6^7*L>+#4!ZmMQg`KYsHeKq zc4{jJDXNe>K(AQ;6ma zQG97ex^}3N7dQbiE;qXMg8>V*?n`mxR|X-fEa(jJd+?0x#zG+ZrrhPO4?w4vzx_oy z9yG?x@0&1{2R%c(KdwR^rmx%5>lHwA{!e9s8*%-mukQPV#5XYtAGSGG^U&p?-o3St z2Os+~-4S|x>V4=H{E_mJ^h~ESel;J%6?qHmN%ym?SJj(T&~vdhD5>BdA1y6o^@M0PH%nRUe^Z^3h#@@TniSX&GAO|dJPFO?5aF<`XzY2kl%lBjwxPOwx4{d zU=HJ!_tVUO(fh*E^6Zk!7Lb47I{$^l5*eEtx8Hk8e*MU^)13r#?$k&rMvZ)%+JiG1 zg4L`k7ZGXxTS@0HTH6AKKDNfP+;M$g<7}|8kn2(!V1o_+7B8yIA#QIdTiQZ-|KirV z?;%_U7Kaz7UnYOi**PPotB^S7KuPcNVYb+@_PDPj&ldA?j@`UZ`DfqLMORy?*Wxzb z;nbIITkHxQfyNnjsJ#_EgKo0GtS-UI5r^&Ik)~C@?71Cs#jBR8j=9Vi))<>juunlQ2H5DSa_Jszt)VNoy4%9%O9!k=ro zHvY5N2)XwlGS!=nAMYwVtM;-XK01Dr;X~5-h^Su~-E8z$%@){DpC)RysrwKQ4ixJ< ztcLF7V0cl&c;0Oe?20aUmv(UQjLl9zK8g5bYh6aA8yCW`13Uak=TjQ)S9{;)B6eP= z=X3I7_Kcd6*Q5%}I&$mtaq6cjbM$|lmyoU{;^=AT$X$MMlgm4llY#f6SH{G*Ik>kcQy~I3%n2Mtl;5&RHV_| zJv@w_I#m7tdVepIJKA5tgWH!&*Au?;AXHjpF;bI{gO|#!0bJ0{l=LzFf&wC5tIdWi5`(6PIJzQ!F z3+d-Or(~!65nztx7vm>ZLYy7fbVPo&5YFtRu>L$Do?ss5+&>}w+ZJ4(>nwuGcsEY< zSrNkTO|H1FAci$|+@7>WjH@fX<&KV&pjUHM#J1}a;)!v`{v46wse6>s?Zsx;UcfK& zp}qJ8v%r%{e&=tkiLt*UEfMW|yFEzF3QB2AA4Y~1!raD*UDe625l7tdBHmdtSD;hY zVvX5Z{g*`KN0$3Ub5-bEcB7#C#Mo{da(^%9X%NRx{QUdXp(OHSdh^sLzGk3QJA3A! zt}Uu}7^NlqlkdVEF{p9YmhP3_H2N{^rPKeb;=DAlL%_?%-JzuSY)|&4+~amAJ-2__ zlQ;An90_cx(6GlF?xW5+CwnBzR#yxoKQaABU!~tYdz=XT?lkfT<)RNx^bI#=QjY7Y zvXXq3apD^XoGA~zKe2CpUMcB*^3&^A2AJrWn-L+S9(>i?ea1=t~| z=L^bMP>_An57 zr6;d0K!ED(saKf-7#zt=e7Q`3YDe~(qbUL$YaWx$ctE~SopC^YC;gsohEoO2{kf|| zUS9Kr*t;g}e%l@)-dk-m=`0b#w<7o2-w`5A?U8(a?I5CDH{5+=nh0`NFiwJPpDrI8lPSTdq`x!9xJj{nq-@@7j*RXzdQ|>g%^a@# z6n}N^u)yU5vaNR1C$n1rkTHfhNa|mI z+MM6^iq0c3+f&|H>(HM1qyA6<`8312MblP1WgseZRnE_el!LA=>FExkoU~x()%qK@ zu(-{AuQ_OoyWXs_E}6U|Nt4CP$Tts_zu7{1 z-}vO{9pyrM964n_Z{k0D41|_B&a!19g**3(2l30g$3pHE>bs0Gy!XJNiHW1GxnPcC z!De&T!W3r~7FiiBUc8NXW%R=>S+`i&c)EA!u1-1^HBHS$ek%Fr?_P{En$Jd+{^jL^ zyV-QUXHsDr^@2HL&&}v2Uvc-DTui3isJ60GG-Ck=E>Bb}$0v}VSaQ6e=N<=72eVce zlFq}17M)Kfo!?WMf6U*5i+PUmTZFr~FxI;g#JtNzX2z+FE~N7rqgp#eq;t(7vl{=9 z|MG3=6uT!vs$)hhXWa1yE<|WfuOv>78OYf%dLJbSBr?s!T@X%^+((!@jdac6Gt1F3PI!@#)@;u9f z%w)R9r9vL&@zCL##?XHwtYQCnaJDk_XkHBVKaXSBpmbW&t+YHF7;k(~ zuVKVM$M+X(s50*&!oy zdx!1;J1m&A^4|sWV+?oy3n(+RhxVi1=0fseB8s#xyd-YlE4~q8(PfXdt6bzqQlGKq z_|r2RS2EG;_qg^7^?6GYhck*lGtpaPrdvCO_`LI^PXA&S^i6t}I?!BKyJ$c4HTmbV ze>aM6kblnKUv2k`%|=ko-ANbLu(7ReQSX~9Hq@H>>C7tWUG(Z)k0u8J3f>w$4jkBa z^pu^B=Fq*D_o7sY&!Z&2eFVhk6AsCEV&Ze3Vp-A@;`2)D>w!&iTzIy-T}rq~{^GM? z3dZeRM2ueeQ;d$KLK#dWp-E_<*BFtExYz+E#Q7`WPd|4aDQfO zWM39A=K63?lVZ|;n_qX_JHS-fe(djW%A@w}dwX1ihl`0K(JJa4M0V{v9_B#0&8>KI zei?Dh_f+kPTX~pqs^f0;5%Og^^p{lTlTYct=;t_^>p`EDZsZZiR9wjCXDjm|@_mpw zY$hM#x;n2y86Qr8vUNRyd~7;pyzj^kK3vvFhm@Y7Jyz6S6;1Q~{XP4i6`%N+pWeRk z;Rpd(<&zYb8VL|S`jCGy?Xw2=&RhKqrRQKr*687>C0QA(#faTA|HFg_VtCwE zcvG(`LCuJ`BX>e2`13&fVCYK;d_8aaXgf)9W$%nBr`}58amv;2R-z1t)Mx81jds9T zL-t=O<-)yHYu$&Bw89~yi^eUZtRdO)H~wCgH5R;l#u~kjdIh~|JA~8^Td!C-qA;F; z^GUO!!v?4asT8I2iF``&^d%|ZpV;Ez#-JOm)9ny+cy)al`H>m{Cl7hPvcsB>d&CSQ zdjv?WdKx0>yy~^sj=TbUOkU$NTJt|9w$@Kc5X@mBEBI04mVHd@IrH~<|4Zt3IrdC% z)nXxBb5d)F2MasnG^JT-EKCis-}UG@&G*0c$yG{hoL8(2{VJs#^qysrX&f8c+yjQ$ zciA|}p6na>lMTQ59oLS`;^3e3qN2qz;+4$_mck<(92aJHyszfquF>3yn*VWO)A#gq z2Zwz0{L@9N*KjdR^>cde1ujzOd@Q@w$i<0*CFdUh2Uxx1`07w@Y7?WGyMzPOH%v1; zwt%jOEsxcG5drMJapl|aMA}!+sMgz`qo1D`GGXmQpgAJ9;m%tia+dO373!6_tIWw+ zr^17GMY&n8F}=2((oQBHhToB1D)Z$bFLwCFX;D0E5D#-UA$~bfR`0zehljcC6*;9( zdDx?CAq{Ay=VJY&`H<&BNBx5HV%k&pr4=+iVDXV&*QOj!9P{~9^YpcA`LvHNX?eMi z57UD>OAk_C;qq61)}u=L`hIMRH~ICee?Tvie4D4EyWGdjB90G@@?tm%FqNn2+(&xP zFksqv6VDf(=$Ea{5zu{{$4Aep5umG2e@ovl0XmG9_-)e>VuIeJjU)I%EYGp{l1BUO zZOzpEQu6zQ7bjk3-x6ZpaVw{^k3yV&wwMz>MuaV?BDq192)#>2YOGozLU+>M)c&I) zoQaGK`|?}_N7oX+gi&JX-DAEL@x@5(iOx)m7Ngbt)HAh*Vk~}Y=(mIR0hMD@rgytb za7%eZNzOTXA9#eh=jEknnXA7oHB^e-jn{{sZjqvOFx~L!S{WXEoqPSGu>%hH)c&@f z>02}gngM4=9SG(6){eNF|8=ha$PJDmoe#J~n7G8>iRwS+`ZZG#=VR)Cg#&^ON z!+&(1L!)Tr4GtT>3j${T+02IH@bZ1Cr1y%y?V96%v$15S8^_q1gFmtAlj$=75aUsh zSD3}YlG{_Ju4(4r{jJJ>TgYE*)cg|rgE&2A&c{0+6S=6iE4t!I{$kisxtM?fE_Pqo zSh#CEpc-A4f5Qs!8KZLX0r}}mj~g~$Am2qJI6ZPB^#wGS-hs^tAmsL_e@)aI5IWWh zVqXF)p6%H)p$k}(AHlk&z{8aBlg~LAkPl;>r}2f$gO+yH;}qg_pZBZ(N+WrAxcXVY zS~3r_C;nFak;Oysy~>?k#XR&}EPt&?{F1d@akJ9^4=1XQs@@z+yyEfI-Pw|lF26HI zekSb`78 zh>mKNz+%haNj7XL9F;5A;jk2|jJtxohs!Xi@NM_AXc@}m-Styd9pFCc?%h)*4mc%O z_%rpsBXYW=MbCd)LcehO^BcRV$5S}!+2;c`ShRT8+?@f`hnHWw%2eGJ;lnMOtItyp zIA1GI&4hZ7uGz`MsL!r-WoP|DE#ms=Ss#CIwny-PkynJ|Po~Qh%!N!QKCD z@sVXJ_dl_*@!9>=9@9A3>2kN_a3J}PZ%dml)A^2{=Gi{kq<5{$odK7r_w^q~edALv zE?%d&{+Muxi_PDvJ+8jsVz^CV(X$cM^P&%HS~nG_9oBK;EthnE?$i}I;uq$c9Ur^b z(RytdxcwS&dd83R?UF0xvs{ghzgbT6Uf9q+vIS6C^R|vXl!wPR10~)%#38Sa4Oz+H zK|1C9<#0FB|JIR>p`kRdTeivv?xgQuy|BaYG!F_h4e$Bgr=CGx$?uRl9xOxG@7eZ) za@N!1O0SULZW=IeWVbON0Sn`E=7{;YE`Of;%#ZY~yn?rCGapA|QQ)BFr+6 zkLsLuAD`!ZaPD7mFZ@dR?02=(OBDooEemgwP7^>X6ShPO1#sgi)PDC9;LXyhGYg{y z&}ynI?m8+!w9VGet#<`5cDWO}<*fkp={pBH$+vkkGSBm^wvg^sJ-*nPNpt>d#D8v! zN%z~-uYcbx#5eAkt9B=ZbdEABhEXWQ%oD5s{3fo~zxp&PWwZ#&OFgEmn2TW5mBiRR zUj&1Tg#xW;5$+xHEO>TK1ec1^4bN!acMZ&A+WZyaq^HNxS;k`I9+;%?Zh;u`Be;s2 zcZm`3kTpbbm!1cQzB%i@i?NpfX4T5+5~%I%?M_-M0lOmHe*S3*oH_1k%UUFG{9tXo z%|wb5=d`BW*(AmKUCrXqYANo|pRqsQTn4%v~`J+}h^{>pQm=mM#NQ^-lljnyn)m7*@r(QusnlTs?VWKe zn;wzhuI-^e+<7k_#&Ho7yQp{kT5I6MrN_iO0mH{7eBeV6eSC5v`S0hSkKB;2ExFFCBBIzu?7zhyGy#>R0bN8IUNz*~;Xu>?{E)io?@cr2^P;gjEw-$hYsW zHgqL^7gyg*{75~{4;>ZD-tdG_&tNCA{e)PjHE)$B&G%`6=e0sk3bAX)eV+7@5b{6Y zZ@fud^E3LiWzldE22)#_HyVlHqb{`i;z%6-Sxrxu=DhvNC`;r0BCz*tE}C>l1c!JR zjyn1Lv()XQCXmnRFzTDRo23}96W>MEc!@D2>SRE7Uk-7L{fG3FO#g>G*V!*AJ^ z**C{Z=$vlNLoG+*{)d6z+F~Tw!Ic>7x+Q^~CTGaPpAxkDte^JAN(u$lj@6ETbSZy2>)CVuEbX&HzKt-v@{@%F zA46s+yRc!FIKFrV^}k)&Bqo7ekrWj3y4o=>(R4qkh1b z9`@tnFfOz|By4NT<6`>v0|vW(bE#MBR`rqc((ALvR#Ht8DU7sz?%qJ~lXHg(HUmww zYn5-3-h&o~%JJ`z&-fxEF{F+-=eO!l)-Ryw_@?6fw3n(p$!YI1=Yes3ZCST7<)?0e zlItNn>Q`@T2F>-;_rX)Ai*#8b6$y%oIGs$o79@Wq| ztcQ=LeBIMul?BM1qVLpcEI`cKb4wH?0_;kXj}rR}aM&YKc#h`!qRiM`=11u3-?wbq z@&#BdciXr2CF$JnfQUR2D8g`&^5AjWXYX#$ciK!nhuJl|4W|AUVeYYd_9kg z`W0ftYdOs9PZQ%{llh7(_r+NMBYyX_FJi3O)aEj8{b_0SUT<@m+g zV@uGT?Dvys?u(U5Mr1S5uDelr+6?mLqf|fZo?t;|sjk{L>dnZ{^t4u@zRakCruq(qVS+;lqaRn>srDhet*(&@9yq!U>nEiu>tW+Zi(hG-CSVhFHyoa%8^!9-xn_X zK|L|;Nwc1*^U!zYcwC7E59fnE?(ufz(ff@}-r-d|JbD#-DL#=0UBjL@(kD^bb7ajIJ_ol zzd;J|JXZ4;Qm*6}amFgTjCkhl-dRV;hZ*}>y*76!?VZyX6+N3Mz{+Ott?hOKtTnPt zQu81_50@>ML=ewJyY5R$65!XawP_tR*VWS(3=JqD-nn5HGx$+}ay`e2dqaeHH^#L1 z%tRpysvr2?C2n`&m=up#AjBkQf@nAO5h9|igJ@5&e0ATjtFcAtCfh>sH!d_qe>(Hz2(ao9@0!dRc^mV86RR zD@7Pp`mK`DEy7vz{Ds<@)bGh{)6B9J(}k;2QHe zvBW`-o%|*$ewIP$%G-f@h6A=eiqct zkhH9s`ZA9;e0ioch6~22xyoumTzF60=d|S>7vr`*SNlkO)7EnKS*9sa{kreQOb?*( zb@!B`QRKU5arUUwz8ZAu{^kpX^m^v5B$D`j)Dokl-J^KO2)l6W5AlrC_SJ4L9e8jU z(=Rik`Mzt38)HZU55+@A?h2y)G2`UK+j!6jN}`5B~p&vWy6H;LE9JAUatvbzh|76#&gJJ>Pcfv}I=DOFL1?-(P*LMUqng2U10QcXHto1b4TZa}f z253JG+d3*R@w)&jk4BW5DHD$;pZnfsEX1CB6ks9J2eiM zM2JvPeKzGpiU_t^4%-&ykZ)hW-MoP~exu^cBcn*~Nmmlm#;A*NROjxkgH|-h!#-G0#dq%d6P-x`!8 zh5LczPY%RAi%qWe1@}r3^I649%|r$#r~c;jAQ{fDn_;v3tPH)Ib#g|u%Fw=Y<2y|g z2fEMP_f^ma2dGJ76xE(MprV(h9INk$Q>ptK^Wz=CZ&7JD^2-rT9~bGLSU(#%iVagI zsyX4$|pW6zUMjRUWY!#y;54vL@jT7 z=zDz@{=Q%tt}bE0KWco4@&fA9e7bUS7WE`IN@nMjx^pnOU`AngAqQ>$HCLI;;!-bW zoz;nCE=K*wWgAiMH13^b_g(TQ?W6DOtGdvhy4vQ((+$AldnGD*r+|$Q_Bdk9w54+$We?uOE+QXh$e#w4Ez~2>tNzq`oQLtH)9wf#^02tl zc-N>8JWO;b(4Ir{y=ao1lKvDvV#@dYNufTZ+{V%)r+oSJek<4E9Zh}soR^HsqkR17 zVYB;*V{D&?*tOO1@%zWrKc{}t?|o71n4u}a432nOf(7NI{mC02&k^8RfGG0g3i4SD zrD30U5x4v?I`HbO0Fu_Ew){c??2o9pCchV8=k=eS_0_{$H|$$kLPhH=fR=IJh1x4gMrV$<>IX@8v{j zNqMt6Mo)wll55N6a7563dMD3qu?RU+#I<`jiqP8S9j16lgb_DRgjC!Vff;|h_ie2R zaR;lDnY|*qZ?{eT2hDfxh_C`h8!>*@*f=DT-k%vLf8M-KjIctP&*yY84y32(y|^t# zN^+pPV}lr0>sos}he#mK5AIabmmsIG5aCh@hC9!iypMc+nTp)ZxPA2ff;WfUZqvM% z{EOE3Ai>JlnG+ioq{zvU*_9CIFIX>1ZS#?0f~90dz#b_Ce0`SJZ7B}U(2eQ+BE^w$ zJD&SYkfHghfuO>f^grXzw3ux&#QYo|{NSz(aw{%nH~*4BLrp7nkqzt0FJK_Ev*iubF9jT^^Q}I;EiytTQd3ZU5*~No7$;gu=3ciBGUaE?Yo8k zEb0S1*?O>P3C(lw!q1C|n%++A6ZvA8doQAAR{CJ7{#%_zy%}+@0VR=@4 ztpen~>7BE11nG6!o&GaZh3HSwcKQg~SKqI;)$$gC>-+JbAd32Bz8>ab>69-mcDZ|k z`Zb|H*L<$479!cJ)l097e3?@Ro~|d3Ny`ZT{MlH9b+2<*Mo2|?*}<`z7(lNl$4vej zC&Ja`{q~m+(`0iwueOMzndV&ckA7Hf9=Kajc>OO z^rZbY+v?}kjbdDqJMCbfA;w0{N4s)vi;;9;>&BF~VnodC4*W1ce1GnT*(F^GjIC`J z^+STh$8AQh{3V$FuO!DYUV_@Yp9hy-l%Sg?p<_io1?Ck6#%}x@Kww>x*TmI&)Z7vzK09H7E_<;Ha+{ikLu9~$p~b-u$s={$Bo_V&)i zvH#KBUs%(b?&65*hvwhb9(Ba;^A~@Yb~)m7$XD)&*|XtyCbW~0GaD;<{4-pqIzi`N za8%t{C#V;m9_lD?ru#5XpIAF$4q7%JP+vCE1-q=P|29)k=-q9dED7bo4(<=1?$>3Z z^7DnLA0yeQIjb=~y^M{IHs@J-;T+WUjq1}J!G*!&uev(q-;a}{^WgH7ufBGlN;Mta zy}$j&<~4xJs*ltU%G`23gqn(|fFv&mOR@L(}|-8iNt4`+&-4(fUHaN~23LTWtq ze)X5WxOIgGFZuQTcWQZbzh_XyP4eBPw?4|3kUwL$v{zeB%*Q{QqfVRY+~1Xw^ah7L zd@NJ_s1|jZPkG9e-8xl#y!xxLhV`A!2ljNAwWtcf@EES6bH+RtYqeRnZjTVyr%Z58l7s9J^$vhr$ zOls}i%5lqtu=x|w{W4aF$iir)E#yD$*M2V6x-SGvviS7rw?bIY6DrO4O}@LqFwY#~ z7_Ccu7bbDc@xl$4p1Bgo1bEK~T_wWrv7GI?#O;I5vp2V7i7+Omx2ddD1k=k-`<}Ik zVE$v@&R%&j^-zY?%BG4DKI+M}r#vydW+X;$^A%%w+}LMpDVGX(UE+V?82OdjF^*Gc zZ=HL3Va;cn?;JVCi6Q^Q$V^^zX*KCxugPYKlq-SJ%#4g3z7p#B9K2x@D?xRk=S9Cv z2^MT|)>18zVCG3h_c?9UZ>UL0o2D$KdshAB&RR(EHg?sUSM#OlYr2sBWV00Pg@+AN zGNmYbvQf$YsT3}}l81Far1)?1x6j*kWmw2^&G(Q|FUX=HJTOv*;UAS-Yfs7O^I5Ac zN}tQ{tmyP^e>n%Ri^ur9vT^_;&-Kp2x@}nm8t?x%t7kL37rY^T#$J1>%Lnpb~w7$LOv*; zNuS&2o3*%|?mtMm7|MRl#wxjQ!|qXzTh`w?IZw>R$US{$DjK*jEtGHeu_Ryqsx-l! z^4K>;9g@0iphmXV>F!7BosHRrU1?yp__u9<2JmZR>dOU4FKA%o!eDfBM@H zPxGGtv$tjYA0FOGzUx>|a+U<^&y?V+xBw}1USL@xY$`jdj2v?tu9D_m!r1uI*4aj3$=&tqdj%R)w!Eq zl?&+n#CNsAHu57o-mmsn5W@DWer^uw-EUy;k|HV1>wvcOqk-f*wtiI*?hxW)#2WSc znL-3M85F3J->#VY@vX2)h{xWBeTxT$$h3)y^qDBa_fLWZS0?!_(t2mxg~T^C+}q=* zU(h&8dhHkW%QkF2r1<8V2p2rv_ZL-(AYty)xZ5ehzm<*d#foB7J&c+9iG29L-CaI< zGBM^|ll+Pb6oZ}H)H$%7a@bj>%g<9Ejdi-}VqBpZI%`H7rhTAZLc^tX?}kbcY_(y1 z$YcqMHq8WwC&3F%CsS`f34K0!W#99y68J=xW&e+&^A5+l@xr*QkWr$AtR&eAi8$u7 zrx{r(q^wf3BzqR6AtO?+h!#?jXjmcHql{?SJEPR^{Qi2b=)KN?N)-siqQ=X^79 ze*Lw@_T8tq1i18YTFv_#0lMD#xt?8(buG^4!LySH#cJtuV#qTT-24_?1rb&=C;5)_p|7d?dgv|YTLQn1@1Id2fzt2&lDyU=IJ4EFUNo2l2fV++ z|NH%}sE85277{G{ZnOCHj|6*E{`h`TCBud7f{i5feR$Ri%)4E}x^HfHWnYP(l8*`w z{la`;!l1TNl>+Sa!R1#T6vzx7B^BMJK)s#*zV+Ymdm*&Ea8QW~G}oS4+HoqB%XzmH zRN(V~gVd8DPJ^Gh`OhX z<((JC5PnBfpEZp8-bE)ug*KwEemO*AgQ*Er_%0gW#(j?uPJYg;1D{ik6HUA=pDAG9_F)sL>LMNgYTc*eGq(&$5O$lMf@Qf>-Q z;*vTNP`~e6zEjA@X$A#nHysd1Jrkg>E?aJD1{=Sh3KzsV^(N1ZC4V^noMu^BmTd+z zj(n%ou-?-;Zr?rp)eLgdS2iA5We&DnrC@}*y=VR(OrUOO{1IC?>u3(kPJ_G?XK~MP zf8tjX@?;aI_BSU#M?K%v{JRBpdwy`Xr{Fy5e3>pme4#hET>V*pPSXMeT7ARH85R)2 z{=h5bgZk#@Wi{`3)GM`1or8H6u-VRK>SV12@`B}lJAPWgkA7Eg4&)GyhiXk$ik&|J`+Ns0c*q_79f2UmJ>-5uQf>w77n7h>w_y1B7ZS8tTOH6`O@_yN zhx=Y?lHrB2l%x;VeaeBF2AtCX+FDH8B_o=(k6HCQswARt)B?dHXHuFlY6moNE8vkNNDzgrnC5a4yx{UnIH9 z6!_L0v104k+f$; z+YIjUOD*n4AF|3y#!3H-8N4$)_bERW^Hr|7s^{p-lov(}cz!{hQ!ph|wSqo;KIv8` z_V+kdCi(t8^kpW+ju>FQ8!EeZrk*p0%h@hl8&Z)QYdqoK{?Z(FecJr?RhKz@I(xb{ zdeI!tmr3*O+h_sf#D$JNZPe$tZ~L6G!n&4&Z#*X~K=k62;ngIZUwi9)^kE2iD^LNb#K?2mMyiEJLlYsv6?OS!|OXj&B5^3=y;9Maixhk3fL|dbO z`;o^vy18`AU=;!8^9z@=Fqe&;2{@3(ON7Ipcyv0k-is#pmpc&9mpo&3N)`Reie|c& zRSXeq&!#GLYAgb1zBq+iJ%@q?Cn@bf@Tf3Zb@wt?s={~J#0q;-3>=w zi04VLrXXOwIqDmwrGFx0m}|wg1Wc1BkOO^rBE?S}^-Wf~v-dtSv@UNZTe_3s)Z0O( z4*Hx@e5W6(l#;>u7S)*XgA6A-4|2W~qkyv0`1N>G3V2<6%sqO70)y$5SO4BaAM}jW z*sm@MxE-?zTeFr5E$-_A&l9P@J2$YBg8GNgV)VhQN-Fq$RQqYiMFYi(8M$9X8s3*K zD>AuCgWbt}UEIhb(h z_^|~A789CjiL`ysm~h3mO}?T;{F@;n7?vdwLkyc1n=z0|GcvU^}Mft=suid*E}|qI}>aQ zPv3EJT*yKFewTmb*hf?74|zgzL2ia$yLH?jIkCW=hq)!jW)Nv3(_-ds2KCcI_jksc z!PO_(nL!0+(BAvtsX-Iwsi%}2G2D!-|5#eOi zGny;oh1@sMw|V^ifF|~LVkP;QY^OPRP9%5tESQ6@v$ClN*84B!rKwuOCH(@4>w3nRt^7r{jH(P+x!oz>u$QdLJNy_{bAwX96yH5>j z*xzmH)|Ao+P;7g(qUaa_&NVv^zK$b+`Ic_)0rVxm2Id~#T8FwPe)HF}!vy$J@O|As zJ|d_b0ONukL}=g?>yN|!zAvFLIuq+%hB(eU9Zdx9!F=biT+C^YL6>74_W4FyCENALE&b2B0sYx&Kd$E34ue6s0 ziK%5KL0nkpTQk|MJIJ8LnZWg#j(&cYr%3uqGMtn98?-&041dllmqouPgXwfHZ~Fup zyeFp5$!(^9x<+VBxETe`cc>eS`%~b>;ip|w85D^0y=$P`NP(q+r*=a=L5l= z_&hLB90-!9+; z)HHba!$;9r40GL}@&NgdOk)sSZ$XR9G=^-SkUKBY&zHT<+$V;2FU7Q{Y)i5J|MU00 z9d!qN9bGO*3G{O^?M?p83Yvlzg?vB2&=l@V*sG6wo5G#T?GqX3%l9qbQLL!OoT@qb zMDPsy^0Gl!IsRYwMKX0BW~g6o9sSmH6mwRyq&3!8%)m#@>VUv=oKueq`Ez5RZ#oe6 z)(UmareoHt)+nG}*-T_=qd)VtGB2{<3pq&w*?tqwtD+9gQ9m$es@}4G&KC9izkWu| z@o95tx)K};?o`2-|4OX6rrog5yYK8So72Z%Br12 zT(I7E@hhlwW4-H+WjYxkS9UlqNhV%{0FxFf)r|}SsGgOK<@Y6k+Zyp$<4ZWVz7gm+ zTR?yzs>-QX^#sVT&+}L_Mu4AR4&{5TAp&D2oYIf_y*^&v&Yz6_`}>t&a$ZFE?>+O- zGWK`1#L=ZcSnmvv7;O!#_x5YiuTw^d$c?N&ZnTC3!}`rGim2mx)y)TNX;|NZwWFqCGtI9Fd~C5;i}d7 zLu61mZgcTQ3>osCn~bv_k)b?5mHwiQ4E&dNoa_06-;2smx2n;0Du8osaZ*^wQ+_&m6NKzm7s4zjTe zU7tPZa6j|>g|I?8;6&ezGCv^`NFrr@NwC3umRM(BioPa;?4701iQfx@ zanBr4QtHU37zIrigAJ16Y>3;Bn&0w0@#cehwY2Fm!6V@Pd1g>Y4M|mtDF4fC_%MJ^8@gpvJ80XcV z#_$3@fc6ZZFx z;P0ca=>&X_M51n@5Ap^*ef-2r1dzK~Ha3R!9v(Mr7T$pQD|OTU_2UF6v$PN$X&`lZg)dpvT$LS^M*Jg9J5;3-IqrM-Cr(2Z?WF{z0Nt*V7+@q z4k^wek3eA!nUR!9@Nlw!UlWA{(Z^+K6ONJKy(iblDAe&{0k!_`9%5dr{zshLgr8?_ zAC;aV!9+hfh$4plJlgtB8~XO$0_LyY??~cXe2PO&u>o8 zFw+1Pig>-?g&S9i&3aUn*%q4C_4R z`i4N%JsMA%um3ntgFw~G85fIbm`g~1kD8=`(&K|MBo#W`6R>hoz?@)fz2D_akLd7k zSIwa40v*=hyZpn=lmXp*se2AxV?f!}_*(r520ZD!HC?L6guaOtiA+Z()Mi{%wZFxL zP;=P|dOs5uzHAOXzKaDX-Q9MJrm~=FYBpR@Pp`mEHn1Ls?jaFvrp=`g-{ta%qX3+b{E(!k`{D# zeg0|C=n&?u?kf)xty~h-*^ciLYT0Y-+{h6%PU$I^}D`ll;w{j1aL|>NIDx!fUtS)>LJuK z2GTn=jeUt#FKIFMNV1Ey}WEo?nOoZ1U^xTL-1g#TCOy!Oe!B9f#$f`K3 z`(rNFU$NegE%PhYVZC2W3;Op8>s_DeH1`JU{fXy!rQV%bzvG_uVp#7lC+sAT9Yvi} zFYh-TM}kdCJ_c9vNg%DXZOgF+5~Rv88_uDQpQ$=TtrH=`e+KJo>~Vf|DXb~nZHfL& z^-QA^>Kd&gHTC`*sCy(5C>1Zs@J>#Ge|0Yz`t3(*%2rVzKA|UYM1cZF@1D<0AyXj6 z@Zg13UkdoPJ8t>!8U^@zOdPh9;e2act!6k#0SqJWORu4Vx7=x!Mx1Y5LMU1G$c0Ks zzs&83qC#_M!pMHC`yxiY<0ATi=f*)8Q;rcGoLoIye<-gcHuu;hVE-{*@PW2!6f6`0o-O`ZMP!fA=xK z;Md+l*+>RxDt&R5XkozP^2YWbqW`b|up>oAOxUV7eYw<+2~Dbnd)MdSb3kIPE`5jz zXO-oiwe4hq>aEO)d%-LiFcaqX+kvCqHVpU{_zb8FA}C3&A#3t%1E|F?R<0>&1jl8d$wp!#H* zvf(}g1Z6py`#2MTaW>=y4gJVSH^&b{=tsKocNyrTKhwwG<79_^Wa;(>X;Yk6^E-Vv zaViq={l?@QsW`8ayQlNSQNQ2Uwp2ca`n~PE=9@S7kuz?Yo#Ch@!j9YDWp##$Fkr@? z>cNk?Bp~GGEhQ32q`x7yq95O*f2DP^7tXDIornBlNkBi~zvD|D32r$4-hcQ53Em04 zG#4Htfr4QMhh~b)Ziv+h0D+#UR6z^2KR)KQdfixVmBW6*7R(LR8c<$ca2e63L5QiY#*`-wo<@tAs@@u+IJr+yL>2q}Yko%$@68ra9(eynmI?YcqB0kUye!~NtRf%n z3UXpkk4;WKw*d8~gSYy6QU5C%MX7KTAj9(C^>5hcMdtd6n`k(n-tQl6@mLwl1FRdy98Q${yZl7D^Gp*_wO1s}T{jdpWCGUC@_wrtcCD zB|@rn`DUeTBHq0l>DurP_Y5Cgy*e~Rge&2E>NnAc|D#rZSa&<_nbH6WP<_s0aO*oeWv#4-2yv6-a4f^|?oxg&osK8_Tc|l?`4K8er z5sERP0f%w8TgNf1_on=xn{Uz}Xm`%F!|!NNC+l7LX_^KJT1TUTQ18$4)R_h{>7d^6 zM|tuh9THZTui-7G!;R=j%^$;bkO_L2@=gZzzUg7_&ixFi)JmFlNByIzBPv~q{r`@r zt16`H8iLuNrPOX=C~OJOI0W)89|p)% z&1p}=Jr-K5t>e-ba7FSWL87vFGtd0>zUb5|u>`8O%?^UgHeW#H(`(zj{4*}~5(iBP)!Sv=ts5j?i?L|(c{gfO{-BUg~Cu_(Kzec&_l z#UEpWr&qAgKW+@$FO75SqnVOh=)*T1DWR0QVqgFGpKfI+3EmLim_5x#f5tdOEcqP? z!n1XE9Q%g-{hruQBVP0!V;<#-DU#thz8`Ipfd2c45v$#kjJ}xFs|K7~L+VMUJ$Ym} zwEd(mcRlWFQJVkJ#>v2KuehaLm;zDau5$Jo6u8aS>r!N6PUUEztQtUp`FYble%C2b zxD?{BfV|G`arND`Jrpnt+4N}aF9kY({8@WMjtUoRKEWcKvG2Ng`H(#ane9%X|1He15tCKkSrM?H5p zg#|(%l9l^ISup;D>+JPP7Etb~Q5yN#AU4|YH^rF^ZWVh9&egFYG`NTI*WMCtNg7-8 zAV>G)ZE&AUt1+x^eC5!I+`fD}@$DDP1Nd+MNy|KA3a`!XcFW)%)$T)%UbPx#@M~9+ z5)1DiH2H|$4|{J0S{q%IOn&2cKa(5XpRV^rl2o5@H$3x8gtj)?M7O=WXbTM z{zTqk6ZB{FnglMnp>Ol+Q0i|pT<{ZfTJ2Y{A|eq9n7PMk+V0?BZu?% zh?GeMTFZAyP z9edL@Q6VfyJU>963fVkQQf@d=q1T|{j$kMitVuT|dhSty+2LO%P)CJ^>h6cx6I2iy zpGbYUo(2KS56gDz(V*vm&zO-j4W`c3zUq#^zTcaEWo-csjOuQbjJMM8ec%G&7gkX3 zM@$8`Zl}WrF_qXq*zb==IEeG3&W{uOyJU76!AuQ9Q(eX!wc!bTJ(V^n+@~+F(C8qiz_cBFb|k<^m)Ap`@MyVEw3#T zqSSsmKR?BUQqFDfd2ceIH$|1ATFL~c7L(YMI2YdzZpzl@V*x|pipsne3l8kD%-45i zfs5qP-CwS?>Q5h3@__RE@Ah>$b6 zYg&jM9nBnZ+o zFWmHm1pe1e=VFmFn7X5rQaz78PKZim+eR`}mQOQF^^m9k)=IhHKn9JyZkH9&r?K2f z=6acd-2LWIcY_KtY=a@2q5;fh^~~)QxhSC3rQUN3{Yg%JYf~}Y%aYNm9>0kkLj9h# zx@s{L@Y$h%u?uxPJLt1sW<3RNWT^E=O;F&Cx8<7am`@3h*84SSQQ^A0@u&gnnm~?> zivxkU-?*;G=iMzT)YrHwjiGOOr0uA;^8o6c?egXdJT&w_{;oGi|59g&ai@w#gYBiP zollWtxV~88z83Y35=|m|$D_m=|FxQeV{BOmc4goJa zn|_ATL7~GX>}CNSqDp(pB|GWhE$Sl{g>_%y?DBO)odGhIx@nG%3^13FmR*Qr0R6W4 zw&qgo_Zxd22#z!0>b^5JLn2Jbi)OoT*vZ8Ep7r;&%$Zg2|+@3DMGJsPG+Y>WcD&)jpwrkVbnpl_KONEI2_4IZuci_*b;6@?_n_`uaH;yp#Ix~WEFV*}+Y~WAi*0@7vUMu3A+eX*Ac3jy_pF#V=;vs0@ymQiT{Ep+=gCh7 zp;LD^9aAAg1WDqNCeE!>_q_Wm{ITw9*JjEjWB#vF(*D(`Yq*uXWZ$$? zAu)ZudGQi*{2iu(KO|AlM1}lz1RA_MlJ!~U5azXvm>QjE8pw9HXy)W2$MawI)M@1W z_YJ&dl>DN>J-7W5o|1I<73B5gnh6~)?zAb?m6NB`&ui)Dg-(TjmE|1m)#-1fM` zJ0_UMIX#pf#OK3$1tTji7HF(j6jxSYL8|A0#(p9T!Y)Y(SNO2tVI7a@_8Tk+DDugT zeZvCHUBXk*(=1psd5Ujl8yl!6XIKApWW$cxSObv^He~1(29N$=!=AtPZ|@peLUwBP zjc@sua9{OvdmLCnIqzkSu{q3}Dc9?GQ6EhY_6|IKZ3-Xb(gqIWzM;MdI4&Z$d8BvY zZ;6~ae11&S-HY5#?kZ*j1MeaHiM(dhhCb(R)7sM;_am3n@ZFd%1@9k_ju$z$Ay-`7 z?0r|500hy^7b(cyjGcL6mwy`h;m%IUwfO|-y}vHB@H6TjrKi!gYtVO3z8Q92j|eO3 zPtxZOqp!nH;bJ5aVe_0@&HYj$7>gcG-|~$JPUQtoFEMx3b8Cr8MSa7}+nDt6015ZJ ze(1Z0q5p2g(d?az`y7Fo$|Kwp`GOyye4YnYW9`-H>g2o(T2gULs-VW+@IT1oW;AS3w>BzGu6iu^AQq zDa=^9VjkObL-JlyG;#+S5c{uXDVkJ&1#sZ&jd(!0h&h7)uUHOP1C6lZ|Sm5p6%4H>|w z`n_t-odFk&B*HEyG9a;rp*!=E0j5jO98|tD;JMGo0Y!c$a=r@!&!y4l(Up(;q{D=7 zO_bmeI_AMy!M@GzOmM3U=06U zc`aXDfCbymsJ+^##DbV(Dn;=m7QRoWx%_8~#qU98$Y5l(rX`Tqzw?rd zwFF<~*RPZoEg^Kq=zK@K6%+@~%em|~flV=F$9&|VYu}w&a6#VlTc?Uu+B4KeBC)}Q>8`C%&{STiHB5D3w@)WQToVl2Wx@MW8mfm=T0yovS^nQ%T9JZS-ob!kR7sRZd z*f&!^r17Ef^c)3vb_weHZKQ(wi$^lOdQ=!aZXN{(s4)FTTOvJ}3X7)60ZW-w_#jg$ zYAi-MK>!y8bl@Eb0s66vu7w- z!220;3Z~gkZ;;m%vpF8eL_IHP;W{fNO9x)#VQo!wI`T4kdy=rvr|^e)NQQu?=O<(!%FFp@EA264g?RCKEy4O{cJ0s;d&&Zy?w&g~?JQ_}Iliy%4+{=nKUC46 zz=jPQzwvgn*gzx1eu=-xhTHu|`Ck^ZK`lHxDr%AqjC}_Pw>2z*`J<#T;jAUhUrB3; zZnXq4wZdsDQ!B{M_&2q>%L-(E9ZeTOp7alg*ULyeNbz3uT)5FyGx(&~yzoyJ_sNgf z@rWSb!!0H$KE8ta@bO7&ik$`U`MI55gFL2ggqf!JJo=wAYrD(#5`ekt%=+cCcqciB zwKfXxA#BNT%ATD?E}i!(#NIS=aD1cH6y$rRz(EW_lEQ0xF0yV zV}2+f^}Y1t!gv3Wvw73GFHjx%VG$#>M|Rlnoo=@0B%`hu;Shbkgmo{btWcAxK!)IG zt0(a^GHln8j{h7$hT%`mQz@xr+*=~5HX}!T|L}}|(hu}63q}{d3R2+dA-3!%O$t0$ zTS-1_LxC|N2bQ6$)|60zl_FvphfC=ulrV;b*cAdFK46 zfJ_|*Y`QKKeGoZ@08T~4q)-Ojs&Zp#=Q3bhvUI9l69Z;kQ-NoZ0e!vQQu65QMD;p9 zyt<7ESBt|6?e(y)dko|MjtQdz`#ty$F@Y~azUS|0qmrg9QVB?YZM}AAP!A#+R(Q{Ka>{Xt2 z=f~$jI~2rvrl49n(Og4OP308jf z*E+Xa!IEfVyT>IfxVZcJpp=3&m|Upcwj^f?1$wE8$;M`Ij(U?#L+-QgNq635jP-y*?-UhW49=+l2!8hTKUIwvH`n@*P@gUp*)(FrmctS()NE5f>8t_kQUMy||i zkK;cs+?yI`t+jZB`i57h-3?w>0a`q#{e-j1Mx`;>I$`dsvD zQbJz4)ng7-ZxnD1bo$f2Eip3#Q+)V$Nx$6Juozvw(L9^y}jpdv$MVa%xn z@Xe?-sOLjV_T4J}jDF5OW0lVw47fq^zGR}nfHSO@XC_Gu*fX(dX4r>;`T9u=NT ze2W#nyH(BV?w{QPjO-r_WRmQUvsSc_QP0b>b=y%HP zx>fK7=iRNxTPjycuz+(=N#+M~5xRGStwL#-1B67*4tcQP*Ydr;a$ziZW!mpzd7A|{ zZhnqWEMvjf4H|@{ZWb(L)aE}~X2CUyV;@+S@lk6r> zXCjPUm<>?Oz&TjJb5$|kMfh;Kw8kznQD)%vwbS0xLW0 z$95`=H1$=<;{4ij&eERWpNjrM!k7QB&)fGG`*FUc!ta`@ck;c+*+2iLB+5yH%m0+q zS`|>=+}--opM?HQuHc?2%%e`uUEFAsi1};wuZy{bH0bB};xW~Zy52w~U1J%2O8?M) zUnx4QUYQ>#1g!hH2PDozbU3k#Snd)QEyc`BfeV@fkXt`SQ$S z9QAzBtQ2`hj{zrVmt%K2G2reE?ad3J<}`G3c+S`HSttC@2rZbZN5#l5c` znEx7P^;G6tut2c$sF;K^)_c&W_ZmT{d#Y}oTS-FQb1Gr=>*RBE zhy^cB{I{!r754YgnBY(uHY~q;d;b)$;n&ha%@0>L3|2{n^GC43!Q41{3;Lv5vu`;( zKe3^$Ej^t5n+-DtbC%XSEWylF$!6VtOE7d%40O6=30=3!{5)$d!CqfBaA1uU1b&Z7 zIA~`D8&7$<>l9i+>v{nx!ZvF#-^H5F=&Zf%QE!@SjsyOfMR<=*?zFK?Zt z!l%a(ZDCo++3XzsBT`KTRp~E5#4*fiU#|PBjeK#>*T9N??DOR|x5AkAxNqgPH8(yO zeHz7reQ9@a5B*p)cO>!$0?u5a%n|JKgMvJq!gP3KJ@+V66M5scaUohbzfP-G+P(^+ zgS$;92O*7)xsutQw%2s%>|{Un9>koA`=0EE)eInh$=KJ5d~(55V@&~_0sP;*ZrsQH z_KUGo*XpigJ{$V)<7V_Nx5|VBreU8~ZrgB5g_8*aQjG(7VoZn(9r;OBL|!M|a`T40 zsNZ{jC<)MT&OIo?q3Xf}qlTg4&=X9kB?)JVL@`0c)7`!k`8KV)DOCdxnLy|rlGc37 zgg^C4tLi(L_+GV?!b`E318;jhpq!1o+)(31f9(6Iin><5sQWK|N>tKC|EHU%M))F# zdD!uL--49b@MWNIu-V*uA z$_m2yyK>sItl&R3Ez*3&3aY*?WsCV*!)AqZI@NqOKp3@_;6}cV>+^}o@5l{hSWEXs z8d$)Fo4Mx=K3PEP;g{VCRNPM)1&9UzA7K zFY+J${8Sp5YD&UutwoZ0=<~e)JB&w~7mzeA+ zC_+OHQ~k}k2pI_m=%#ktFQRYbP#wbPKFEOe28*)w$fZf1@VnNMho8+lLBARq@MX~` zZ|^JvUauZq*Mfb1?1xdXH1>JfxGgUtFs~KNIlIVb%7l+XClc~;?^o;Y$)6`Yk?U6w z&Nz6M31JgUN6%ft=RoFr!}nQCXg|%d$GDgYe|O3j&($!Y?7qJ3&}Syt>J_XJpJqa( z(WrPl5Bi!4d0QA;SdcW3rgBIf>-(}q&nK+=Hv;QSZ==rN+i_2>)sF>NW%Z|mqF8uW z$b0^J2IgMBxPA9L!|zGMpQoOUEcmUr-f1^-asgc*V{y zh_3iP!1;Io^4-Aki>>W#rW!PK6 zs}I(;kJ7E+W@1~A?x+<+B*@7F!5UQJl@;q>SVQofT*PTB8(5i=P_My#f_ygt$!Ew% zXUN@%w8*glQiAcSVS2UMON9O;3CugsuEZzx>5NT`)Lx1Or%_%s6IqgsGl--8t z>s(6+UcX(00`3NVHLk`KP;0MTls=ApnMiwfbQb!V!X}>O$eFb@tUc5B2YnrBS$AF~ zDh#Pi<&&+Dr)=&qtVI7Nq~UA-Ijno9jTuDFwwUevDoVL;@bZdW?^l?FC-I~{%b=-@1NKlPa^9YVSU5%Z$M zj^bkv!4z^u1s!Uq0%T>s(Sb}$-s;KE0GrcyE~Kh5V1q~Rfl3ww z3j2B<_npK$CZ{``|D>RvDSu`tRgRy0A2t)eG9dU*v7_<-_55?g(?`V7Z`^u@dK>%v zHglbZZ#c&`-#flyg#JxDse9tF6BF3ohpP1bnV{OQR52LFgca}OyYjE&?>jf#xS5M{ zZnYWr+pCfv=|bin76;E3uf8$Z}mpQvEVe!3cVvH^F z6zW5}51qFJJA}$3@1ZW5J8i;lvIJ?5@qF{YmN4*%aF$!c3Z4e?<#@SU!H&@Ou-rRV zpq~2H?(BCf_!{~oAY!*Q{MX|5e0!2LEE&rx`*7oP;b#9qu}mANN@Tr$z119Ck0@Ie zQZ1mrt97l0C;>ut+9WmRVova}_VxzkI&031N=jZOf>Gq|zWy29Tj?)(9f+J}{CMMw zpEr?5woOaQ_=>*h5MgVUA{olOvWlM}pYxQ`eIe*S^mT&I_&8%;tIm0&tseKMTwAP| zYnc=X>>vMe6nXkvvwuZ5qTVs{-8>3EDG+|)VB0$65agpWtMZY%5jIdU)WE&jj`nte z67((4>zn?t!+Dnfp2xz@1>_R8G1UO;UhSt_RxX(aW>=&ePMx5E#DHmIaVqMc#`j4l z-qJusoU~Gk`sVrP*mbwo(c!jX$LdXc(61@?I%i-+bV0@biLj%&srk*gN;I~sp8TywlE7g6usBiM6VmV7u z*Vm8H2WD3=&+YUi*sWuMEl-&G*fthK<_*^t?m?ekJTk11%7QOS4~3>&Fwc@7clSBT zf;+i0L%UGtDCqPWS>Sx@t+eCz1N3(`4F}%$!n#-4Tay^u&w~6Umd5%87QCHk+$Wg(QIb+EY!-lY2#~qim*>Ha{t!cEJ z4evZg=6Ck6Vf(IGlS7Ma)akvvg~&~CM*iW^)v?6)`JIgx$NCo$tSUc)z7TU)bVh2r zB@8v}^nU)<5;`s|kYvUzVO{(MeVvU~Am>wmE65ymP{nbZ_&_TtNxo1n^d=o1cyF9u<$)df)$dA@W&SUn2&0gJbv0Vdmi8u+1}KYTM#t_Agc*xj5N zHSF{8-(5>0vCqqs*7<&+V4ZqsuGPUl|Kfak{8c}kQ^OM57DJg3eDlE<&udJG4ZNKG zJ%=$I!PG<&vbilXmda$f&y4f>w)(f@TxVc#E-QV5i8V1vn}*ugKDhfSXM zJ#>@{eIG*i+t1RLF#db=6KS6%H0}Dz*XUpgy)nGbF_;hVrE}P3rC9>6xvjg&YxIXM z65Fx{E#bR_0*ylebF;Q4j{+?#cs5u6PSD8;GTUxmNXI;l-{VOb&uc4qJ0$Nf|H}#< z{-&F&?6QXQ0n3;A0`}-Amg!Zg7&|KdZFd6hHKTazu5dnvvhn&-E}v zK3TCPFh}+*a%$$gm$swdSw7A@?u!1tLCp^9R5}HI#``t;B~aiSr>(kUEd^GsmMMJ8 zNrh(*mM_j@Zk6d|HLmSTg|~Ux@E2Sa|tCg2jp*>x85=<-;H}yPdCuG z-O#6r`uvcHKF;^0gd5pqcyG{5IceulyeBf#GCU=Uyn%TEA0O6zz0h3Y1$R2A93@iR zFVlfdi(jlMp~JPJ?Ola^bV!TYB&&sU>`!wpJ-QkLTvxB|TxZRI2tSQ2k!Kk&AGapC zFbnm(Q=8kJYP?sq;W5}Ff0IeuVCIi`>|RY>1zAZZq&Fw+tWaaZ-SEl`mN66Vc$XD* zS~4Mfi&(rJ=CZFQCU>_6F<~(DV<9~b_p{Puc|N40KS?Z=p+3g_lvcf!);Gvy_U^yx z*~SE6Q`!JO?lHEPZ=NV!Mm@Azpy8qr3&yVNXF17W{`A2z%Nq5K`KX747y39Hq1#U1 z-j6vghl$zJF%}%xv{61A!h$7rvDHe+$g!!3^z+_F|1)Oe{3e`hEpE`>xHaLv@EHOA zG4yqomELzgL!F~akxi+^e*Z7gNqi@A4m(P`VtO&>y?yHY<8cNXzSUjmbiz4zv1rST z-g!0zb~xonC9`2?-{DKFd^Y?S9JuMuJ2qT>{cj}v3mck5jpun6@aK<<3UpBScs1O$ z*`|VZf5?&jm0$@}*W+;!hb-~EkD3b#p_Y*1kiNGM=U`%B%K1+fmj8cG-Z{CimJkqm zdgd=T=44MF2c;=lLE45T2?M4T)TsWPR6T74Llq6m?RTxBb zX%SMx`>erONBD#FS!=kmgBBN5VGS8~?>ymLYXdID7dqX2Y#{IREve2y8z|~bx$hWi z3j%{jMn1A|PhR(P=F@1@No1XzUgV&8Z%Vbi$NLK+BBO$F_&p$NyuT3Bhdj{rCo99o z$g8Dx%68mBzDL3!)DwMAp5f+a>-SJVgJ=BM&tT+rR7yIYR#G5BZ$4`+`kNhA4y53H zSoc4qmYtD9BiL7Gu6~5~L+ZseUkp(}B~rbt0Q-LJ`b{O`6y)h&4?fy*js_+Ahg16> zpzbe>>4@y6!SG?>Upr9Wr$c~a-)`KW^3|++?LvpgfxabQaGv#?cwIz(Mh9t)&ioDi zbo@Sf$uLpZlVgHxxskK9d%O~BWX}L$b1Oa}^eZ2BM=%00mr}jyt{RQ{W*==&GjV|d z$Eu2F`h}6F{CMueiYyZxH#>Fw-OYp@GHV)s5K!-oZZ;^hXTp>0gew=knJ{_3UsfCa z$_cM~^8J|0T3I!{3cH8%YUfK{`R91Qp>3S6vJUmm+KMWdFH9)%Y2C*&#e}r-P_HNG z*MB;oP4UE>HvGo>L6sdWD9P~z^E>YKZGdxSTD1&23w+Z&>; zH+?vF_QoyL_mtpW;tyF+ec4Z^6uIVmt0WI4V2(ATKKJ4BFg_nR7YeIZSn#K*?zRr< zd&w7tc0=1y-(*MrYSm|hOiT6uD7x-wE*mdiN}^B7KgRrb%j{A779R4OyG?@{ z5+oRH3eTRPM%%}lFC867idi^Hj&`b<+k@@ zqa?61XiMYTK!&R27`2q$n3q}TWfhtr-rM|NM|KPSKA^mQ_Rr>sae3*Q6xICv@( zQ6DeaxVcvgQ=sN$sAQ`-1+Jc+703*yz)Sg+A&+_r{JdasWGy=tSZ-9uursJIaEbYH zZ8;T$%Ux$>6lqZ4?D#jMl?Hrk?e<>5{Q@V~RA-y{BQQ_iAMaFydoahYtS`e}gyhA# zoJ{OB6MyRorr>>rO#TZ!d2!2OBeL>*VgeE`Jtaf{^dwUeq+88 z)PDXB_L`+{UN1#nPf-`*;(0}Y+6(1{v3&&S&brK_G)sWT^uFmu79!j=OO%-vAOhdx zpS}F3Ysa(231@VP!0|v;U<39%PYM$L_8`yEWTuGE;=Gp{IlgLs4S5fDz4za2B0P6} z|9%;H{`&Ubuhv~eXlxtWAv#TjzMq1A#>jW{C3Bi5g-I~CTJx9<^{(6Y`)!X*QO|Cc zpBl%xKT4X}ULT13#*fKnkwStPx9wsnB_!}KH(V`4{oB&_wxeo>1O=;!Jufg9n08R$ z7?mSKz`u;SL#AZtmp)s~>P7~Y*FMFxt7KT|TF2p8iuu7}UGmj_GN=()nH=~Y2x)PD zroWE@JS(<5mB%SCZT)xu_GAi(t0X)&YNdcZhr^)nCMrCNdMD~jpu#EVg`2B)s4xnwEgS6~J$6L42VaNWMD_+Qx9*2Bbqhw=*dq%D^eDe4`711Dx=4NBi zuWH%x!OR5q4q4Z|e2zUIi{TRk5~iRhdUFraAN%-Xp0h{L|A{FHrX9q)u`XgQs(KFC z%T!NIkVU`8<5k(_YX_*6e4<>wB4xYiF@< znRs1UbKVkjR}EF3m-fhKKK0CbowtHo?@0YWSMcYRUMU<;w*pRgp8I*IWA_=B^IPVo=4CkT{_e{NwzP3|D z@Vq2`JYp>gR5!+iZbF|w<>sLIPel^2^}Opf!rZrkRcb9S`kl#aqRfMzQo>K*=0`>N7G1S2K&n_fOWBhL?-G%%QB2@URT?D>YBQ*Jap4D?C$~ zG=sg%VHT0MF$LH^b2F8zLB7L1T$-GNJscf_?Z&6|ETKAWB}o!>ZSEfK%M-UPp<`tI zx%StnYu{=z=6_q_p&XYCMIPLjUCq}{zQ`u8=peq4^|-w=*a zTrXOI_RKEsq*yDkIoVenhd%vnL$@DCOVQVi3)S1)jQh7Sgts@)r}q^IO4)$?X8N>* zyUjWR_@7|^aZ3Q_{kTV73-&NidPpo!X%V1*z4rdKR@gV|Nr~BFPXLj&VR=Cx0(8a( zDD8+M09AW`p7bpOa5sH;r1BW|R$e|bFnWQ%r(`!4EM&q#?4Zi&XB-8wcxcr`u&A{j{;TiU_Z3BQuTfX@}l9K zf{YFl^lR_wQbONH@aMzv6Ucim)by4fks!mPz-?pSw8-%B)M-;!1{qj{%&a&*41OF{B26V^7zpAOzKZz2%hw`Uw?Kx5^8x)4A{1C_XJfEUkAnN3K0{AkD6o6# z{Qaki6nqcyZx5_NeSB1E8~#s(#V?-BL`fobPu%SZH0rG%D8WpZ41$k?Kp@Q$3 zCr_TK(4dh2ZnsMk4dP=(#&R~(;o?a%#i;^1l*{X+HDljMViVq!$9;kJ)Ta}DEGF@xRH36fvio zl2%l1Lw;YqvrU;@9ew%oJevt~#J9)m?`Lt|SFQTHKS4d4thi9}2yq{_Yee8=7S8n} zwWp`bkndlL-KE)Lh4(C(mQ3_-I4FPft$tYHcV~~3Nw8tRKw;~HcFd<58l*xT6w$Yr zJS6%_5AQK#MDNx|exp33ESH4*=F-7O2_KN(nB~V5am5p$HN5YYZWj8K4ATv+rKo?q zw#OtPzmaa~J6nVNX8QP2`?qhXbF(cgq>$gtZcEW|<|o1z!kAx~4DuKL?MVV!M4+~Y zm0dwS>$vUWP66!gkX?1)P)>>jax*mPXDZ93KQ)RGWKND9x`sWvhX#tQzuZmmy9N)R zz2PwhQ5Cxi^_zHShyJ6CZ8P4{iIgb5gMH4k%#BSn%zJxsbK04x16~zaF78FYU-)WI z$`blMuM5|nie#|>QnAvBU;_)#`RG&Q6lMYL29J&JVqam1tEwOx?}zMIS+nf47kdg8 zHJ?14(Z`%@{o9v@xox9S{d>%5_4yq~bke|>N z5$iP3zg(8zcO>JS6+BeC_2nV*oHif(T{f9k@S?Q+c0JB}-9rzwMp4hEYxW;|iMTge zRhaeoiTfu?)cd{G^Kz;ffR6nOsHOOL=kV^g4Ya{2ke_#+gFIdokUn|MU9$hd3`VQP0js zdQ^OmCqfU;5IG(Fduu+p>-3ZeOR?Vk<}KLkeA1*&`Amd}FW!}*KZuZjwEoOTHWIKZ z9<#RHPJ%`jmmJ=`Bv>u})39tv0>{tF*So4JpTOZ51y`q)1koEdD7LVM=8+2enEvAN`dR9TlT~~!1qgm!-?`N&2oV+mJle+BZ%@c?FSf8z%yR*vss?j-nQ8hwAsZKc;b@bB4gCd!ZD{GSkXD?#6~a$o8HPe`8*<-U)eq#T$t)OW8zt^83%& z?J6Q@pB>voeMf|UnupV*Mu<=uAN7L^^DDK|L($tdlOTQfrC<8us8?G9#}ZXZ(CnC` zzS)=r53*Y4ifu^{C-liU+KUABAukJ4A~DzM)ad?#xK|!)FLFiP^Bu8^(Rf7yfo=u| z@e>JL{&gOx{E73Q#CzQjb*>UgPCj)f8GI?*lXhs5A$Vg>pGyf!cBN+ZwT5Td7M zfO_|@^A=Tm3PefON>Rfo@R#y+P4zwWMW0<7Pkc!McOeI-b<-61#e2%|2rm`lAH7k@ z(xk%Nd)W|YM=ESGt#eyVq(ZT9z{0nBD!5!#eVh{@1}h;2$1ox@5SeU`S+OX zk7qR4!N)Q?z)6RnF`o14o^&8@Xz#lGl@4{&!};Oy4EU{_9UF)H2K(&Dd#`!m{fF?l zudzq)u4cyTP!ZGzm&TOhs=V>88eAPejd>WGp{Ld(k~!2G#uX1>zo%`kj$H%&&r!{3 zU2{72HhF7v58lPS@*UbG1Ctg|y*X65PXX_y?Q=*gKWzz@*M~<9qQ5zJ&O|(S#1e9R zbUF&q*SsXd_eDg`3ZxGDt}Qb_K67K<@EXqjpe-h^n^51jl4R76Uq#>E>zB%zY%5UP z9ag-q)(Y1Cd!xMzb?wcNCkg{IR>1l%>D__#1pIFEOsW?0oL`Q2wSFiOu#cr*djjYE z^S=_A35a`vBWfSR5%;>c_WU)tL;$+DrCR4r^lh?2oYfx@;M@7;oj&MWei;v}Nrhy4Wa zAL;kp&f?ypoW0R<1QGT~yKIh2CBns{?fjC+>&vhFh^(n2!du?Ykxr;*U1$@!B9lb; zz@k1p_z(MQLvBUSxKXDr9{ZEG3wt>t8+VptpTArF#=S3Q$oqLd2`e2(J}YffBhdM?S*b zi+cQAY7-gwc;e+W2gwj~>()oFKbVsZecVFir-1zSf$w9=6cD~)5UGzo=-llF-V3KF z;N!09d;2m4@>mu+S{_p1O`AWb_$vy${=TK7a*_h4E-7U+ZKh%mFG1g9FBKlor?$_~ zsG#x4m=O_-dBHc*t(ZJ2Z03zUb@C$>)c(0&$l{gJt?$8>2h${UWKIHW<@aRuE3 zd=9t`{IdDh(P8?BkC_khqZjsXt?er4aC!DlsI@8sZrO#n>GU!n;%+bhg&5p3ARWGA z+-m|iKbX=tV?TP;($;^DX$CKJOpJ0dA4r|4n=`V;I}5_Qjxrm};W^`@%whCFv)cye zO;HDjKO7QUevNn4M$CKz1n_>;g}eIMwut-L_A+VAwYZ1DBXGzPdmq+bv0PRVEpq6u z>>lhHq$TQA7^A-vo!-y*U*~?$X^;v=9urWet%7r3_HF)^IWg1ml8^<~D*^Vm~nG_WwEiTJ(O#9H1A zBCH4|iZvmx-^R6#aUOZSu93lQ*(D3%KhVoxngQ1#nw^l?mQEfmTk!CN1(wnt^? z2W3S(aBU&Mu`|VHv_TTQu61Db{zZcGB4E*sxX(JQJxWL1S7fejmr)~wdaTYV9Wye# z{9^2sae@q%lQP4Ei)8rjO7gZrpJ(t`*ny^p*nhaX*nb`Ue$M-ko4P-cVZ2Cgd;E7Y z;`r)BGtT|=yQ12OlIVM~i!y&A@Bh@sHn>d3T=;e?NA)=hjHN6t8Dd|EuCKzLgZw`_ zb5eU5`Ogt0*LT)9{|EG_ABPbCktMN8MT%6&$`!#iXezMTNzJwUP$46ir}fHhDtv%V z5yzUS&~itN@NkX_L2nvkUWw7bCbm1vgn&AE%5Jqkf(HFVVZTn*;d3Aq&vlT64wHT> zGSa4Wcq8Q}xh4aB)#Gc4=U5ofQZ|$#8pyyqC`E#!yO@wIWE&fW`!>d*$2}ztO`+uP zM$J5N>_fknC>?!;Ia++exe|OItRokU=(Zp)n(5`1*pI#Z$<2#RNfxkG_^hxG?qh}Y z&1uwYTS8YXMqpbS)vzTm)paROVIygcHb)i+bc1p8}QB3Ib3k2&oT z{I}(j73|+Q+>(KOfBo(h+1r&?K=160=>0#hjX7!Iiu+Yw)u%mWA^lxcZ|Ic?bR zwwNO9!<2=7q{7{^Tx$Vf4 z{SKH@i5*xc8taR`q-dOCMjR2oa})}sXQ6I2Og|A@MuhmZm?$&g)kcCNsZKR4*kh0g8@*MI{C=CW z?1`J3$xzF|BJ%)!oqq9bjWNW%Q)+;SE#m%YYiuGH;{M*v*?g7@WFY+7+j0>1!%ix! z%d5ql_il{Y*&C>HPlaxL(bPePJsV`IC||J$M41&cW1)ZzrwOwd^)BC~(u@S`L2Tr{ z%>L7i0@Ake@17X|-+lV9nWr@(%% zb;T4OD(uaCv1de?iaos_MQMotzeNp)($7-iyNX8}-wi78yNG4VS5YCSuG)DA>f!?% zIHr|1)4=Oy&ikj>uh`J`hC|c|b7j-u$Ky9>@L*AS+bhh~CUf-Lb2s9*Pld<%dyMIz ze&x|#`D=72J6m1lH%^Ds4=i{3nKEFk$4aG=jM`@ZY-#o!{z>hh~5|Gz`_VVNH}N#HN4jE*F3;J#Klh!k8ZF8&HFbv zpW=RsUA2aIMj_?^($6Dd*%DsZ(ziZG{$IJRf5SiIKcjDa*WSVTzqTnp>kHz)3eym&kA;1`f+Suz|4tfUzs5vV zWCi_uvVeIak2eAQXpdD2V{qOt6(o<`#d$7Qq+gD@c0JtxtkRA@&$7+z=s5bC*ZH68 zAfJn}Av<|_4SC{_mm`nnNw$I#w zIV4Dv{;K`(ISJlhoh%(`C&A|afgX)9^nI>~isb&mpEHbL*FatS`NypJS4lEVQ0AW0 zsgvQ*lMRaX$aC&R?&+IH+>;wQI4OwxXQd?;-(tzIJy-j5{au{%?Gk<;E07O;s2$$_ zjtqC+@}2%PMuzyHkB2_uUO=CH5bqx3JFC^(*@hG-kfSy6^&j&6{^4x3C|e4w@V=0b z_n|bs^;U(af#C z(FeL^U-;(%g$ijy72J;A$cHxNRhwU@fja@6y09@q4Cnt7y^H3lh=1>H zgULSByUV(I`Rsqu-#iA>`htk>uTS-}_MyIA=N6!2j{AbFyi|Fd`&ZfA*7%~Y^QHV_ zibe_ncr4mN&KKc(AaXQQx0wJg^JlYe4dS1p?@HcWAVASoVz1^FB3Kx?l*S;xzxsG) zAxV=6^8M46Oe@s6^+S_i9C3bo+k~hh?p5{39%RHlQ6{nM$bBLVIfZZGdqxDm8;#S? z+K>kgU5q_6jQt$m_kRi(@Hy(L=3_%WtD^oh!5H=I(EW2<{-|fua&B(QGD5sYSIt)2 zkl+h7ov#~xobWFHy04eepFGa0xh91KrN*M=LXSwW_DbS8%{mhNTddA;?813pAaf&q z68E_@<-#YHN$~L4qgRJ{$#9Oc?q!uU;+1P`$^0PZS6q*OEL)OcnZMosodX%7D(;Fj zBhT4(Ie~8)=e#B*(RGOX7{`>K{%>&~AX7N_+$b6Dn}nJ?!hGwfvVc^-EHL8RA0}1uCr7l1i4br9#ZSl^d@g zz89E_nsb zx`z(q?)Qc{B^glHCU0(hfdO*r{Ju5=4A|9jAa0#C6DHKT*ge-i5|L-B4LNPV9g5$mSp38Y*zI#{8uoZjxh6^dAD-~8SZy-DRpcn7%Ot_tA{=r_d z5sym;_A>iwy2z@S-(Cm(jtuN$?)=+dpyZCdv^x!>e=ZZCXSR{Xk8_{(%01@)`?a_D zgJu1Y@AU8I)ES<^eZ`kbH#=EzfAHn{MTRKu*Q(oc2B4pF$7U-1uqhGhl6!Kij}yT) zaBJu^^7{<26Q8?daUUyw_D>l4mvWXuX-nn!TzvkxQyXzVR&SP0LfoITyVn%8dkRdW6Nj;nJasidq1uE5r$YxMcOE5yE~$3H`z#4)4{xk_jy{g! z;N9LoX(S+QV|MNXOW%&&G*Y|?v3u&H;+vu7IfEn<9y&{~|+Ci&iunA>*E zaDJ`E-rD6!LkC$M^lLc$bh6RUX>&a?tmBM1)<8}BcR$4WkHR~3$nTA5VjD~Eli`}a zaDUq~d=7Z#MEG#tM-P3P4@cZTQ_!!GN8Hm>E()>pQ1A|7Sl`aw*mqVAlMO_kzkZ73 zCr+jSo3qVBE>{YCZ0`F;K%X-}dU4aY6wJR)kLXPmQ6R%P(u43C^>L4sl1k2FIvu`;@I#<09Rgnd=rYWr!~NLo49QP)=xXll zbr5GjUti;<=~E22z~cTot(F0V9Eqz3q?ynnL-C5Z$AmNU!wu~g)_4{={GBD<|77{} zLiF>T8KlK#2pq-xgll#>KmLe!XX#OzW8b(D_p=iBcf_DCI(PKV-X%-$ao7*NsE7N1 zJ>9p;#9s0PzZX5ogZ{49?pw)2{hJYU+>iQJ z%xnA|i2yRzr}CW6pq_p6L|}a!-WfTNsL+suzUZ79e{}=$`yZw~te?^6*R-9H zv*Q@{a>5iwekdHn9P2z~)2DN&XUp^n=cBN{CXy8M?=}fOM}D(EgZ^dlj`t@%HeqhX zYrArwkA&Y*d7N@}7T*I*$tz>)kjLEB7t!8^`-`?2i8mC;z!ra1WeNTJ@LNOrjubL* zUkT*+jC<~PCU*~<3?##Ka}8nkYh;i+9=o>|b*&>a`e9-f;@|X?&?WRUSAIX$yNNuf zRej%b2jZS}W}THf;y%Ftg6kXfHO1MrO0H>9;Ke1{mMk=JY{>PtSNfZI#$>C4D>eloWA8ue2ktw?}z3jKb>fJS;_S?@(A;0(P zpF5>Xh0_+lEKf3!-yFHsw}`yo*=Jla=r0jJMyK) z=SjRvG+0&m=ebpq4oB9T)!slp^nPLF*2W+@=>N6<`n`w_^5p`l>nG_j@~o46zZ3&Z z!hJ;Bof)tc__N}9F$3PXTL}zpWI{+(_U-kk7X-Eb8vdDKf=7luuVjif$mflG7sc;b zyw#(xJ!WeTRvS~`hMonaK79Ma<~#N%uDYHI3dWq+zd1h%`)_8|**Deq;~fU_z^+aw z%(dP#WK5H+AmPv{6VGbY$Dxnz_m5&vf}5nfZW94kUH0~CDdK)f_T%Wcme@ZIsekwb zeNGmOO1%$=e`|~G=*)cVHN*^E_dwp0{yir3=qUCd`nsnganEp<2S>#}VImZ^97%hN zbALxd-bQW<%%=*c3tCX$rg(3y+7g6%;I@a*$aVC6RvXhO1=!bAk(58(h~2o zdu-mB`?68jYUJ*p>cbwUVa7(=_8r(a7Vo!@L!PrnCe&ve&U>-w_$TLZ-j@h_PCrE4 zPcy_Hmm%(5LK`jar<35sE8^7oC)i6^IdNeh`u3B)&hvWqFSk31J?1mJQ%hk2b#5<9unO{fq4?-yhRAc?gz5|W;=Dgb zi;n0*+&?n1FSkbAXI|ev!i~7k)OdJqDS!gM-GaGym^u>sX%C2)_dwgg=#j1 zXi6v*&h*Zj`rbnS=bZnX@>BdTN329d2NkCFam+-1qe6YZ0_WjPH251axTgd8|L?DO zROJW_p6WyiKE(O|!|z_YIO6|^c*B?1*))i3G<@@_g$7@qYgirnP6Nx`e}115po5ua z|JX$xI(XmskYDCP2cAzGL@y-ML6e=OPp**;F)y}WWGvDlIH;zj9Q6U=cIdH#ry0O2 zJ5;^*F$2F-)GibDhXLQX+T4W*Oz_Q37^#2CghL!dmPZd*Lq|}Sj>E7u968CX<#I6t zHEGVkHO=O*cwwjWH1>y%Hr)L92X*qaaV;huRmv1Hf{ebQ~aCVDck zr~kq!@J_20+;KTq&9jJm=>;s`>%|Bl*%P-UkAAo@P>|NefYKX#lALebb_cPA> zM2cV+7vf%_OOHc*fCT%Zrxy6;@%P#V-kjY)2H~o&HDw}X2z^PAa8o7&fA9gafFT*O zuM$3%GRV-~zh2DJ9d+)@JK>|DWcYQ-&EEe88O)-?HwxyHA$?!Yi}G50UY36jI$&>S zLtN_99q8wz$YkD~TtPnctawW^AMQ0i;6Gc7{GLy(>gapqIXOpC{8>qeYY~-rCgT2? z)0LoZ#QnWCN85mF6nMUq--(n%f&7>k9Jbi+`EcBIAszjlcQNV0JJ8?!+ay`=nFakD zYAH;j&i%V?r55&5!DvC?%Cr#`JkGbC`Ed-N1I3LWZ7xz_b<5LgWz4;f47GQiN8i6s zlRe{LBNaH4en&)nrs93fR(6L!`17)z1B3iDD9JIA-h_GB;X@w_=PhWk4l~c3(=-sI zJ5K0FV{hobPEdC)4X)V5$p<3-1>{w?(PwCIKU$U<$xVksmtx`l`|0pXx>qa_^}sMo z!N;C3?Ax89DOzFAi1UW?QA^avrUmO$4sBw9YPqOLxefyioH=ft@L}NH7s(H5PZ%(l z$NwwhHv=4#G!nG*nb7IN!flwsgr>bO?|HAWhVtL3ou$FnAZU9$DS3|#9J12CwF~!+ zllNa)SBv`uHx08{?Y850C@8`gp0wh9Dur)Czm<^piwNu+amQY>T>tvi2UfuSR*^o@ zV+CtI=(Do05rBD#d#-9P0gg0h#+6{dAtUE1O?$#f$vkYpStWs1e@>8agZa zIRACbSAP9L{QGdP+Q~^0;Z*a-25Z3Yv+R|5nQMc5rnQVu=>id)lK0#}h+mo4)A;e&@YLNT{Wm9tjUlOcim^}MdTx|mZb1`>*? z*t2{dvG*MMId(G-Pkax^nd8E{ixKw{AN{in5chR;a~H2OF@F_#O?LCZocT(UEm*bynUor1G9~fM{h6)XPzeGz2qP|@}%JX6m6&yT0NcRm8 z{~H>{-dQ7#!=qoAAm6EZdcs5~8hg?1`)m*0ML#G#$MIby{=12x+pA706nr|hPZj4r zcY=n#=tde0c?}B0A@6B5_CJ`YO@q*bO+IQ2^nb?HS1xx6n-)PWwatnJG7ae>{Xp~QT>5w2}aZiUr2ZD?+Nz9jyzem`y=>I;& z>iug<&6pcx#ETC7z#Q$XMvQQMnA_eQ7U%u0|_)Jk-Ti*@I8_J*KP^<{qR5g{3;_5M*;F41GRj5J>GLT zcZ#guLk63|mw`MpWC(k7?)vyz+}n~R{Ch5dyhdz{b8eq;&wh@$SBOnN%#HJ&ezwvm6midTb7zns;{M3d zU;Xb_@wr*?3aI3#!cVo9oDO*^B$9$Zi|V6)W9RkZ4xI{REk&{R9#oiC&^B?2pn}k* z&fHSWxdONG6c9?OKwMy})o-POE$Q*A_)#i6c;=x6sCOfs4k_6PB9GCYJ~gdOgGSfU z%YRI05WfF2cY-7KfsQxdstl%q>$|dbk+<+YFrXK^wgR7*fMlhE-88tmI@W9WlLiz4 z-tPT;bP#YkvUjHn9U>S36e%(t%op1$Y<=k9G@Re^Ed~8iomLT+8hkIPUHSTI6!{R} zR?WaI45;UKymL~60ZkE{2Zx;)cz1MMk8uNgM+(9g^cDvAP84?CSjPm~1IMqNdQ8}V zVsMr#oQXZueA$?GCIm?cZapt+4VF}s$f5*mh+;mas`J^v#Y%F2bDa&a>icady=x8+ zVk7^hY_^1D)#AJ)+z)f`={-?sE^-hd9!cByHU+MGx+DDx>+jNQ{YmuSJuV6*4b6%&vXU$GI;`NhUnj) ztQ`1iIe~m>^?e23DhcvPhI%*9&l%xcjTn?i9je(T^GlBmfA1xp>_vWWXYxQR*^LaI zexEJn!mzJd;IcIx=e_o>^roLU?>mcyy!RpQzr=50v;H6V^*s7si2Jk#=eK^CTWxij z20uZ(>yz}5{~Y@FHJoDAC-o?>Zsly|Q7YzC!Hn$;^mB@@eUD=VW3Pudnd*>Cfw-jy z-Tt{0aA2|adw{rq-F*A`2;%vR$K7i~q>{ggw0GhN8? z9r~IZp8aO)p;94xSEE0d8|q(osl9&a??hZfJXi1XKk%(FDO=A9n# zK9&YAc1A?SBk$j+GFt zATi+Ra?0mP%#%wO^mk?EGvH2&N-!0D)BeXwYN?nbtYcM3l{8_(4Ey4Le_BHG$LbX~qBF1CLA-Fy{)8>5@0}#y*-M^Q}MX-ZyN4 ztIlPZW4)JTDq?S^i{c?ZhkDnaniBnn3w?LHr*C@XNzlaC`&RA z{xLtyag#EIJutrt9^{bsEx^8gpS=y=OAhP5e$|m0 zTStc1x7s`Z-T{E24$-C{W6?T}87N^WB4qat_GvjXC^#(-8Na zFSeA7{6Fv2wD;>H?)$D+Pd`Q6XPnZ-YqrRDZZ$vnL!pBBlQVj6U8#`QL^o>*!JoUm z_1iq=x)Bu#ekKJ}xHA_X*xi8t-W6Mw)<=c+wtTu7^HeD9marLPr-4rlq1Fd|{>I_u zi&PC7=oYeUh{3!|N8QA3$0^LeWWzc5!>|`!eo^HD&i(smJu9rrXmFy!(IWdD?$da_ zONyGJ!ThWB25Z>pU{o1Q5<>sy#rIalVO^Z_{5yZT+0x;f*45e;KRWK9hja3zVLsdx zzl%~yhuW)Bg~k1JPz-hzQ?IA#rm=FY(j71q$ss1bX%(+23Hmzu-w+u-+cEcsthY(Z&;>GK+UsJXM&m6O=7 z3sicTpLP=UvX3!)O9S3((_hj5$%T7dGZfc5_#AvM-si)L`Zoe@_v4zs#7@j@vodM=Z{B!b9A$d@#?; zX^->#-S}xkUo!lAzomXl0zMy0O5bmxk2yN1d;iyS#QD+>wH=+<%ZViBh@h^Oi|?tJ z$6m75FVBgG$nWiX-GX$H=X7#BN_~zzNBSeXqBP=u`#FtG0f_sAt8(Lwi2J^tWxMr= z`}&@oe+LowFK3wtJrVbpMbe}1A?|~=IneqM_uPz0RuSa)v^#OD_K176oJU2^5chLS z=Mr}!?zdQW@5(^j@8i4nPX%%RM)K^7kzgv2J{7B%VxC)`UZ$IqPlXO5UthxuD&Bio zR@?j$@2BLc6ok!E;du7>cS;**u=8@+Nq$ip9Q0g_(on@*w^%psjw$w_Uk1yO>}imq zK6Z}mM+4u?+w*zXXt2rm{DWhd`=+0NBH@euX!~u>H`d_X=gwvQ@o$j^At#IGFCg!s zF?JsgQbb>;)%=Nw2^}JTl;~MI(P3!1%-sz2FHzY3^eXcI2XP$k5y*e~(-k)S#`(`Y z)tKst_@``b`aO&JK)&?`mXbpZ;FQVF??Qhx;)Az%P%Hx~OrnWjN*K^_Vvp#-PnaVd zsNdef&IG5D;`}x0OgLM(^`_cM%$K*XImeRDgn+f)W;;GG;iBc&hhhBIAYjm37{j!N zGU;QnirLoCEHtI&vepLuci!jnt~T)d73Ey=Hyc>i{$-V&VGG*lq;kS>4{hPS$f0x@ z+!MGY%61cTCjr&~Nci+=|`58~OkSlErdo`wevZRIbC5X54*>C;!-$5L2*9D+VS*S{zG zIu)>=$=_GAjQHClUL*vau* zuYMvQ`mky99i02@TwbAncH=z1{Kk6_ef&d1!|Jx^>*U#-k@7u*`&rR5)w)q+P?&x8 zwlov___ymrhM$tb)YReZ+cxYi>>)G-8Ax?2cv9} zCW!lqqx}YV5ckgCu3q_x^S)4Hp!Epi{z+|PKsw_7TvODBf9T_L6o+)#BktFdmuxZ?BWYde4C;Y8zqQZN z*Vq45Fexca1DD~m+bfahx2IfHibQ{Nr-{a|7&{uAeaUgD9d&Ni$)CDR-R=)e) zxnm6+_wsk#n?)b#gQSR=u?_S^SM5o7Vgt?JOgU2z*n)HAXOrMbTj1wW^EqZ>iM@k_ z`(4cMji_itYiJi=nI=O({hpAUJ^KcCz0H3#tiPMi1vI{Kc=<^I{F$p4pD6?@~5|FE!! z-q`Ab_Z2ELNgjy*OLzCM)ZIt_|Muy#()Flwe?&6Mk@vJ@_H)JjC4r@y&i)eIzuI!~ z=PtdyxK~wDPu0V@pRfHlug(E`nja?~wFaQy(>hb@ah(kI4tFhzP~RT;J2vruA9=@m zb!XL2$nQskS1-7v5t(InOyDc9H_;!mZ}EBJLYA zZdWAW{_e!^R#!H}{qVa}(H9Z-N{+tCQ+OBA{}Fll7~(!SQ&n{!2=RT;KHna3|LK_E zz(Ov*4|;44->#(sqnXp2){Q*L_v;3^X(}8{?km{Fg1v=pr!{tOqrrRJJ7Xwf&)@!L z;}ZiKbiDboS<{*Zcj|^)zn`JOw@BH0{g*M{eSE-$B@>^I<7x+-pCbOH7yY===ZQSb zv9xZS28U#}b{<(pKZsPH^+gc11G_XcZDjM|paVW~w|!SEd&s#@ZC+o$OuAs(s0&4GS@*|k5sG7NB!l`Ne)%mAlz z?t31i4sPV^Uh5snfZ>ZzwCOphhkq^bUU>ofT(i8E@x$I4B2A|CerH+3 zb^{%S{0VE&u*%uQb-)Iu%q~>#O0WUGFCF*4{sn5LX0bO($NyljbY6B-E#_kDcL#0r zJc<6N0!u^*>S4#{2amX;585u0fS*Dq0=uQgmj{CX?;mbeU)93sH+X^N zZYT)?Y!4M%#S73goaG9Ls!JwOJBx5Db| z$oCb@-sM)K&W&1;a~_Mtz4PNFhuAxKmuI)2Zp|}%U*yu%=iUcd74-4b^G`EPu$O-~D%9dQ;=eC^Y!mLKKNKrxyBUXl1e zjt=HjvzGH8agV)C>yE4YN!(9qp4VIrM4el5a4X^V?brwtEURm}~K{E5bb2Xk57H6P*TnIX<&W z9yHj$$#73jIP#ka=Z6-^^XGLwH}ArJ1I_H1n(}KJ^0vel?;#qv@0ED;2l>ut`=@3N z=<~mNDt4|%27R0dkFB)z=-_H_D0qp1yncvBeCt^{-K4{C;q|RVYv)QXQ%Hvhknr8XU%8AW*8tWfA{q}ZYKQIO2tc>Oej72x$rsmij+N_ z?>`GeJ+Sese90pwc(M)-{rHHV+?ZCd>)dD!+r$HZHECKys{e_-HlEh7v4I(xKQwg%TlnOfJ?`IZ3#X(bTsH*R z;dfn*IcwlPg80Mz=iOS+S9Pt^{D?W4&XeBdK+Fx?PB(hze8>K1XmsNy6}&&5@q^Ut zhI{O3QCHiL4>jF<5_k-AFyr0Pw~wzOL9|3^ppP8lnT_pNVTb%ojZUTa(3;4d!daiJX8}|-}?N7+d zVh@w(?PP=cR$2O-oEC!u7M4Q)+C4G1^36}(bs7DBox{eO859UVa{1G?GR%8he^Q!ILHJmgWG$~}+in`HYW57BMW7M~&+sb5; zQ)obL-nx?&ef^BbsyeruXt3+V`I_U{@0nhR6QrTP`9@IqTgWDyc}MnMCPbZ7@sOl2A>(_>P8MG#XyluI z^2lVuyT1Ogj8{y^GvnRZHjjO5q20EIV%E?G>qC!W-zaER#5@7>v}w|s8J99^un*9G zd+)n74BpmW)mOHG!!~+jcYSQ|K6p-EW1|hshdo>^5x0dW@;=_aF}5I~Y?x%tYX|GE zNwSqT*+CWW*+*mp>>IW1_HJE^{m>j*HXH5_)LF}n8{yu&A~X5t9QLBWut@ROy5e10 z0|Slz2SiZ*p`)yZJ&3v52dezockAruw6xX4{ajk-o)QNV0L?@9dJN`S33}o7nDbh8 zJgaf;#(NE?KlOZG#P73cwx=wk&o4F`f8?tM8P-v#;jieZTf#-{KD~tDitHC|2 zM>{MO+>!4byv33B0`n`Co9*h2sBe$Ik~OFIf*k?N;G$%8FzQ0sOl*~^G zob|fA^EU_HZ9C*Kab1E6-t#6kT%5P7UR~QY zJkB`MUYE;LPv5}3I6cYu|GK9CY3H;}&5oq_XSGgKA9T+CpQ9&$^HtZouy?6o?kjf} zABMkMnIQW5)n@$MI{Tml@Qz$pu$WR1gMLcpyqSNBL1(0Wp6<(H5W8@*iYjssb(XwH z74Y3h-TI4yF!$9IRH{jaNe%bv>-@EtbhqK5>s;U-m96*pY!TvIJ5~Rg8jPH1RQQM! z^q;;D{&oBUCM6o<1<*I(1#>SdM?(j)?Ot2*?*Dq|Bt2{8Wh}A|b$%eUWzoML_q|Vd zv&i{P(@Y=u#u>MVJ%b-0PxR?qjM7JZ51yS)37!TVwBNO%9k~hy=fi;$E>K|;cMX3y z$)?5c&ZgNuVUygQNtWItY^sZ>((7Bvp-G)*V&38&yl<5=jw|NSLbG|dWu|fIUcr|k zFApxIzF4V~^M*?|1#zM}Y#v?O@_CbkG@lF=mX#jB-WAsiM`Kp&BTriEJIfgRu1H65 zf{Gm8p*v9b*F=c?+%65)0p$PfLyAuh!56;GR<6A&kGziYl*n4-A3AiyR|%2#ab7g{ z{vYT-r8g|BW>$a?NO!xuPzHeKw9!k(&m#|rWXP2bRjh7CXr{<{-;9sRzN$8ahJJ8?Q!>8}cAdePP;hq5<|IN5n z8&1K$9osxw9AfK8=|eKC9ornq{1-dLImD5+*<6x#PH-fqP2?J%Oz5D?_T(Nfb)>lo zHS%Q*z)74j1xfJRic@t#dnN+MS7~Vcn}z&NXsTisd|kWCAAQ3%GH5T;BrJl@pmy`S z9fM9yPb@I~#vsw?f`ij0F{x>! ztxOwwPn3@7l}z|v_p>|);-LHI9FSh{*&BR#wu|r%cyHu@*v-jlnE%Cfle++6Cb?FKjhroX$(mGc1f&T*(N;}7ZfBrQ0xCCJSf3Vxx-j4I17Lw+?v$aEZGWIrXygT@!pf`w3n|jx})?P#IPO|5V zu!&7eBg>T~r*cR=w0PGxV-EdjF%nxI%psMfFBP}r9vrb`FWfzmOZKUoD{Sq!G;iDz zk6GDVT3_-Z`<*fm?>41+_h05w%CM(*HxoMsgAL5hcgmnrzM;+rW3D#!zA`X_BwwT8d-e9Zi8DDeKY<7>R(101T! zoNU%)OVtbFpIt_d*>n5t(htyoyi0U)9X8w1p7Q>!dhmCTX6VQi#=-~q*YQ9!2mRfL zuYIWoxlXs_zC+)TSB~l{`6*#fwWhcF5~1_xn(i(+VPa3L!hD&Je0ypu9N(0&AGuBU za;MLy?CIFJduMN9?oV9U^55jA_9TkeR>s=VUzGN|k_f!BDgU6ydl?6^9#GF}Sp+?1 zaKJiY9sH_2fAS@n4m7>&XtlKu`d1OgTD-&9=QdMO!YBoOM4KW0U_NpT(c15#pTnok z%=t5}1N*ItvPIbFt#4OcE0-eaNLF`uE_yNFkz#gA&i%d`J+0E*;)&4lBTKK|ly%2^ z-|Bx-IT(1}&|usG=$S^Fzl1Hj=14Y1dY3ko0N3jj_c%eq=Rr`X0rf%b%zh4}J5d z`N<_8?tl-!U1;p}l0gimUe_h)g*pFN)wm2gr$YN<^`IF{k~ZvFAp^Xh)@HSJ2ztNu z>KUu_otSw4R7|@ukcqrO%}84UlN9O}s57#ebhxblojGv7RDR5VC0$JFPDof)J|1&D z@t&;H92UJAO<8$uEpU%vVp2MbMNg})k9qH7(Kflg8d8}5`K{WF3poF5or49d-m++B zWPR_zDDFX9eaGNj_+uqLIYKiwJsG;*!ruX%XqVEU`Wf5@?(VW5rNBdzq83X+Ct9T_ z=GCCWA?==Hbq}|4DC+fraPAQfU78cd^)82gTI=)p#{@2MZ1>)`w%}5{dF+&9=fM*u zF9|3fB433kt+^qAwjmzHR++7q=qxbA1a|gu(w^ z{vT`byd36!-ma7X!S^ay{Gjg^dRp3wnpO<(U+)OcQ!n8ESt^Wqs#VDMyQc0;!u;Qq zYcft0de4LDF3AUiFr2~wMi9D@(fBFC$=wB3;O17g-}sr z20cGia>$cT+=9V|QP=n9;_;W_V|RUQL4bW^mTl0mDUc!sCG zXHZ7z=Sk9k7&K#badUw*^qkz;LuaA$H2M}@zDLkCxBv2)&ty`*$x_QEUnb3?*ywif zT_#iaCt>av%Cnz|Jb>=`^GmO0Ba^N#@NRzu+>`MlysL22w{xo3&yFF16?JDQ(5nM*qo(eoe5vTveNU#|M^0;a+V%? z1fnhciq<0Z-w{QS)u=XpyE?xG<@LYTAanug%;Rd&c)MRWa#E7nmo^r zY?rmW4OwD8PfpkI7vKQ{Rp&&*laX6%R5>C*o{gEj?raA1{%7*LEn+6w(~4!hKl+&e zdZp8~UYbF_AMKy?f80M1%XME8X-|7S_g`Fe5xR~=>r$U$dpfbkP@^ zuU0fwcuUfO8gm9`JcPa@$}D;;L|&)gBcD>(&~@fJ2Oscvpr177#*`T3)Z`=?o31zz zd%N~7lVap`{%Gv_2Y$O>EtL}nJ=6Etg4&nR@oiWMs(rH@sjjos{F5$n3fbc&i#8&E z^ZG)+7vGVJCwkaU+=HHCLx6oG`YK0y0!4mY!aecYVq}Hf&V)0YTT-ECzEzr^@a3Z; zxzrz&UV{8WQ%vaBU9t>XHhjPA9&{ZMvvX=wjF8XqS(WBwk9mGJqU9-iEfT{keJLF0 z+D%Nd8hHlCZ4JBpZZYt#pjN;N==u*69!;6i!l0qF=+!Fy4Dy$2SZyW2B#&zOZJE&b zHJ=aLtOn2hCcB~dAM$SOiCUTCJehRkbEcbdIFlqel}9Vj!3UH0A)cBCd|!3T@Co$J zU6*A3m}2g?9&S9MF^)xM8%ApVX0ga9uGK{cxFhgizd#}_L<{_UYW+6m7Yg{ z^H0xF+j@mX?ZKhX-C~`kK;pGm^dOsdc3DT}t77hV_&)z+0UpqNrp{*{ zha^>#E@oZh(CNB!ky0%jT6fl@Y4LO}ZTJze_?b0)=1foNkFi|3{yrz_OCy(zS3iE( zwunb({qyI1JjA2gx{mzWzj-8Q9d0dhfKPq(BGVQt35b_3d#Jz){p51RFW$0v*CHp! z;X)j87T2i175NFHPdzgSjp2{+$A4{rPq1Q+=f%h9dBu%?b?G5|fiP#0=}J0w)Mc7< z{2>QA(DJ*hIY*%H*QciL01g_<(fG(hzGsujMAMz4c4U>1p3$v}cO2(N`Hx!nsH>`VD~=Vk8d&FIDJ zhxXleX41)hT?)>?JC`-~_nDqV&hwhjA-7B>WlKpeswhVgl2dzGBvK^a+#AoL2kRahRo-OL zW`}pG`p=>NPtC0{{>-9xyqcebqR>D83(9eu&!z)Acl}FU&nDfaUq2PV7x+87wC`ag zn>OT1t#BXfkum4^ZJ)J|$C+3S3*K+7zo+HoCl|$7BB1Riy zIpib1wfD>e4&|6^KR)$4hmPvx6=criQm|?Te+r9B!p~8kx)ZpRFudy5)&?%kHqMc_ zHit(~uDXT{`|$9dhv6j87d+B=^=YPx0iVu)IqRMHgint5Z?(1<31~^2guz1OkXp3- z56v{Up(c-iD$}1KXU&TZ`U2h5>f&y85b{E1=RNWtKLlP{v~rdd^wGymJwwiac66X^ z?KTk)JM;wua(m!|z0g#4sK9q%-!6&k^1wl{g5UnD<wtE>$5XV7<^2%@iAz{k4hwX?tnxrG&J zrKu$DNL{k$MaqG94Ekic#`KZbth28By9MX>^S_VxJ%Dp^qMmOGb)?o02Rg1n*Kxn; zzozXba+}7PX{fGZA9g}++dK4Hj)Yd^{X(y0eb6kQDd=atPAyiPi+v`I&o1ZaF(}Zr z?~0)ngKp%>A1Q~f^H}fK==wkgxpsQqDvyJ&D^|VMG=o70=8aqb@&Ry=*~_G5_p*MPi?V2kf3>N!3g)@O z>l12vEIM*sMlT9;KgHX6mW3ya_@?vDdq=Y9&ccN3KgdC7#~m3S1n&2pz-jfZW5G9! zJ?r~}MGEtb+{a7eTssD4F4e-EUpX>kiaF-~tJj~B-P!cJAwYE$^Z#0fa>wd)+zbBN zO0TDEYP){jJF^=-oUUa*WF7Q4%LN572+2_<<$h}1`(hNIe zPu%9bZ9|3j^h@aUZ0TG0T@vYmR>SD4L}}^y%yOXFs*f$Rp>tjl zee~~-7LOc9Za-~p-~sqq6Ljj92g+IgVWN0`8Vp;QY~`liAS^9O-WF^zW1F zq3^g?sqwx#(y2M^YBA7t_KH|UomYa68FQi}W*LLNue>(S!yG#1MYgMs0QVsA@5c|& zb*_9W6`VkRAxQmIif$T%-tK5&yhMKUa&yKSuUFXnU|`iN@tHx*DLba-jv)spVQJ_j zk8}L_gNCX$`YX@Hg1#FwX=csg{@1|yg)dGBUimO-Izuk42fnVk`QhRPshI!2-&G!h zzM1FWASn%fKjM7Vz>|;Iua(@Tnmr1=lQ-s6BhSM7;+nPEI>0YkbDvk5vgp*O^TW6J z_&KlMt0RC#A1CZP;eokdnV@KHp2ec+6=@TWJ;C>)T(v|WxaaqsnF|;rEMh*|cIDR$ zHnk`Y9hP6grrZB)W<1-19{%4|WwXG4zp3uqq)=KlgmmSYjl zzlz-P9y#bi7rWzGfjS&wY2N%a)do7y_gh+DppUZMdZ(^ThHr5A`8ZYh1%Dj==DtO~ z$oBlzH5s$GbY+3FTJ1)h`!7QYclL4VXlft-#SP%3GG1ZUM=pI8$|ft!b2|#4qQG}%irt!SH&l_q;$PES^~VoD&w^HsDNH=9PC^A z9l5;2Lf2EsS?GTn<0jL2W{;97roOTp?XF^F*DfFMkazd}V zT6;=3`$RnWH@*W8it0NR97xOh6zPEX?rq+v9f)8YTJ2l9XTtFiHJ%dt(j4S{pyW7qg0 zAGc0&Y*xV@@L;h@!(;FP%&%FgiR7@!po5t>?9aB2Mg5J~%AToUiGf8wXbL%&U?PSt})5l2d9 zx?kr}r2qN&yk9&DF-jbsValhgLdnJlX?!Z>+-&rjBA~nJ<*%i-2l;%gG-d^2jY08zm)fu&3>xLTR}l@;%A@iOZn_1;5oc8}|sh=-bbJUy$!H z`m`Z#3Ha|TyK>7(y3jKNFIgu6|6B`g(w9R&tL@JYm1vy*J)>_gsQ~wHZT77G@B%(T zz{l(#J?OK@T6}W=?s=9Gtvnz4<_?`wC3hp_kVP&qv{{aHJ0@j9h(CUB=x?|UbN`U& zw{`vL(Dx@@2-bj}&y-Hfoz{#zvzyJ7%%9k6buN3+Bnja35-np5HTY0H@~YE;^M}MY z>eT?}hy7l8QwaZ7qUFAObr^%bc~wa$BDWK8cD0mgHiMYE9~H4Hu;*mJN0-~mpm7=7 z_E`O9&_ILGZ~0Uvt%|)cB&7!2v%Tc`r&UbS5b9idu!Ttu`q7$a-I;V{VY5`g0Vcin z&l(jb;C`^zr7^R>18i>GcLL5IYLuH6){MO8s&U?Te=zBuL-(_($ak81{niRsWl{B~ z!6IekJjYLKDQ~xCVgJak2et0VJq#Av4npTSAyeyOdlosL!Z_L9Y!(@~i9UJq3_SQr z%c?IOEXpyGJjle{pVVEsKt%!Pe~QL*!==FSF4rm^Zer8LLRH(Fu599nZ}FE3LoP_Y zE$eF%n`G)8c(%w*9}yeZV^PnhuMs8hI)9;WW@aO|NEW%EgSo?+y1+Sme%1cn!l4tH zrw22AIdoRk-qP+Q{DGNScc&I`s5j85@JADe)`)&wJpUhucJ0_;S*gw?pGNl{X)7-6 z?Z2$HIDktVThE;2rE#gj(8Bd+E&OGfn^9&Hd34w)xZ;gIkK$U?kL&vKNXf+BPwghY z1C=+N^ZIxsb9+J4meqW+e9>@2Duz!N{xc(bMjE*6HvSN*(6~NZ66i{h`k9T2loWQIus*Or!Uazw42AP}rXIXAJ(?1#`O@ z>JD^SwkG@p{I1~UNVPLw*h8!TVh#)V=cv}`meHHYCtH30n~L-A-8KI+2f57^!P|{3 zB%s?|KDIhU19?kURrD0#p6#1NNNNcL_o--Ku_)CGfueo6qrOIgUi}f+;V- zbH(A~1!C?i1k9cGYRr*jt|YYA&tOoE;$f##$g90n4PPe>yc6^N>76Y?==W7!iR^v& zF5Go-UJ0D9GWKm<7jXWp35)0WAh+{qUD&n82IxFqt?c>Wx01UXA|1hRMFOT+?g77j zQz23u34ZIDcd6`<#sBv^7_JO;!Z~hnZ1dm8q|YhZ`#fTiU(k@d!%JtncVplgwGfH9wQABg8qr zc3@=}@Q%xq49|*K;QNgVcj_}()W2;}rD7?I^o-9$#W%6&YL?U-^PlL8CEXubCxN`D zYe{W5_^wl8Q;iJf{*O0%_x^TdlSn4Ne1#tyGtFAB0l3F4>HF6Y!2PUiQ8(Sn*|fV; zNz|>4O}on6d0&U2hX#ylh|lEEip6V2%2sk{qFd1uEqict;?C$e0N-p%HsAM7%)YCZU`#v0*NPcHTs=8c9zC*?ng zQ>nhsr8Ay6mzN@c`k$)dq(3uwRAC;Ge9)XnNF$|L9^lc9hvT%r6!56`l69O)KX`NA z;V7atxiDY~!1f;Rn=pOS(ee%t}f$@qL3ocPcA#@^?pCWEd!^Kbb+d zt8V@$hPj`0+crFCErS{xKR>?&U9-8Evn3RIep6{dh0Q zj<2Iq;A4#}6=r(D#|nHadw4p0tjl+EYtJbFzuYmGny7>G9Rea3=i_hf5;i>}X!R{sQkyYuoD!!hK4 z0uPl4f%DD2t%#4;Mvi}3U)!7Y$obEf3(!Wc?V0xOHOYSHJBs~P)rw+KgavzbGw{x* z@oNijg6H1aeY!vE75p%}Gdr5Tu;^O&aI-#q-kW{m3u{3`|BAe`=TZk^oXOoGlhiuOaHtCCdRVf1ZTf9`6cu$l= zj)%*v-_GUGqFD2Vk%k;n+Ol7?l#RJwqI4n!I_TBhxKhot9P+rEuetjUhdd4RwNEr~ z=+UQiylBaxNa5IpaPWYX<+?`E23&es{j;-7$fc<*7jicp=8~!1`eo)fxwL8H)>A$8 z_%1{jI=PGR=s15}$;e_J{FjDZe>gl^s(Ni@@o^q~vo?EJQqH5-FMWy;=vm>@^mv5u;*>^n|pr(k&}~u=_f#LB4g@7Q(5%DY`EzG z0S?FseUTBreggYUq?UG10v>w&S5)K({D2kDgFn7Q?x&AEKl|8b2lO{HYsSC>R@_Z# zi#+c@#+i&g0_2!e+%_$#fbO|({_?#aMKSNcTPL(Ha3sqIVVaGmjx@>i@s>|G|Blyu z_NYfVa?0rXlfHj5<6;JhXVRM~1X$i(!U zVVWs}c7?7kItiZp{?v(D&HczFghqM#o@9{bJe$fL$nDH`e zU>fP&ZLf04GP&_&f`cBP5huE<5ESkFDOpRn7e6Yu!8wx9-Z(g?) zJqWxrZTUmfJ%54s`-@!TWZCqA8~deM6X)N5YqTSD&Z&kk)=uTHDNfgF>6kxqa20dk zFFVer*Q3j4XJhW4t9&LE1mD+X>s8BS_+Brf>pEr)u*vwTm(z$ehYs(&IApHPq03TP zAyYRZ7cqYFSxfj}aRZf)W`uFT9-g4;94%>iJe>r46 z?ct`^IRC4sKZ;Hl&I2COaC*A+qYlo0Qu^cojsv}W9bPI#?&0;Hi{VqU z9VoGY&3gp>GyhSG)hp=!2PHxc+~*+2IYYlOcOAY1lk1b3oZw?sc(8`U9ck+oXPf1h z;EUO+$tOO|0^E}+5uf9`9KA&Qre%+yZ(1*1$h)`= zc<7*3tXw2~s~4Jj^HZSvpWgB7E#|(_xwKqk=sV)i=2Y;zfrr-L8(uX5`$^Uhr8Ov_ zk685TmLc#?@cWFL{+pSUnRouf0T<*sGY?xk1);xH^gUbc6!cBqUkMe^^Ft(pcs9WK z1G10TKLyS=zGcf>3?FyZ#^B6@!1+Js#K_hG=f_JWZ<_<0Kj*UUeh=XMl_xSp^W9j~ z#5(*;^Z@4hraKYB1mxY6?hRBz-zjbB{<`52^iNLNx_aaq-0==j$S?T5u1||ifp=P# zdWb9m&yDzWuw(5SPIzdy`$OjslJt6Gn#?A5zS%m50_dNz zGcq#3cU_$4w5&%S`dSf7R%ZfwlVR68y=Qai?$m6TDf%25Vua~F>+4!N>s&V)`>sUsI_#ixI3pT4CnKJ|Pe@QN=PovJle!}}*iaiNCfs5?q z{=0Mt_h44E!Fh)X$p2i)J8uGAbZ+SjSMzPqd!8;ypNaefC-|?J0s4!V_d70B1`qyr zwJ~loe6NWUr(HCI{<9>q?$}iHR?g)~n;b;0Ctmvf{)QCjovE93)Jh!5Buug*0_T71 zuy9a%6uIVzG`F@{3_2(FQ%^)6`D4y^|3h}*xt>AJ!9Ku2_Vb?qj0XO{`F8P7)veyk6kc(%0>Z;N^-(7Z^F+?c3jdgcY;N;vemB#US&~1 zR?vwr#qfJ8uDA*7koRo6I?&b2qWLS>QU@lo@qWpZ7)@p9G%iO4eZV`F0l~*!TR_Ku z9k1Ky%%;=7ex4W~#HOp#VbdH>q5pO4>6+#&^ddudw#GhY(<2SjpCPU2OXf-4&Vt|j zs#E=@vJ8hz&a2$5)8x?0yo(a8CYbx|s}^hd91>f>Iyng3)2%=L(2N8Qc_*wCre$+z zmQ$ZhdKHKE-XGq)=nL-6*NDvj#JEJalByciaK0nEf|QN9lw(u)Q3m+ul=s!g73kTF zf1R0cjq`7DPIGT@8J8}C4@-_N5( z@{?Cdq~Uv@Uw3=@OCIeXy02phJmhe^fK{&r|G=VA){w`iqdSxLe>=%1iP!5Vhgb7y z#Jzsbdr<++mpOE`b)kUjmS^<)TMFoXzSFY2y#lIM6JM#HA)xb?PYz_i7ZBTC)m40v zkn9sC1WO(jlKxVUN3QP3Ut5U%TmWC;ulANj;~wB0n2$@lMAYrcRiv-Iav$C;nj`eQ zUS>~G-uF#s;vUQrtNo;B;6Pzywb$DZJRsul{QS!fbb9gF)zViEw9a9hr^+baeHV?t zwj4NU%;v7E9dbV2?rdhcANcX4qf_pj#`hrjeg+5lKjgWlN;B}!4axHf)|me%hu^0( z;`|%u_Dzdf1>U=VS9+KugC-;`&UosNbDiqE)DL`D^z5W_$8I3!x$W44`Og^G6FF|F z=?4bh3sv_RhOQs5J?XpUOeP(?lY78)Ig{RtNYDI=xj#vJjk>uT&OM_bR2YK%!iZ(u z+OyDqzA4zXXESMCLx`u%GbRyj5N65XW{ zzrKq_8lU#;twx?_X2I-DLiByDk6)-8znD#TLKxp}n;^FkS+)BB@Xi+DBEA54=ii#H zJU)1?k6GH;&@|}!qYRsh`#As7Z!Gld*i>ecuha;gbMc$@s7&O29+_V_e`gMdQul3( z6Iu0te>e8eap?VWi~I9ky*RX4t#kabL+HmG5ypsLfR3Mo*~nBY@Z9`a%sV}hY{nU1HDPv z+WxkjOR9VmuJDzgwr=K;Pe@&mHgqAQ;OPmRGd#Rg zpJ6w-gh#)&AG;#>%%krc%6iVq@oD^%tCqirPfq9d);#dx6N|;Y!9o6R`sj@i(N8=^DxX6p%x1Mx8 z7rc4>&Xr%`mj%6=8I-pc`x!pY-ln=2zXq2rPtHOvbl$za>a7m6xz#$7mg1Fu{om+wy{p~*UV%XuV%0)J z^>Chh9V>Nl{w<~Y%%{QMvN&GezVHDo7Pv$TvR=p-h_yT=&|B{WVz&+A4R*JBo z^N8OyW+u;NQbFyErd?~9G_J`@;S+i)zrzCS{`nxEzq@Y!6U_a9>dCvIY|{J3Em;A@ z@B<9;SNqj7Y4ptnwH4o)wBTm6^rJ~EQk!v?xe$1VbM=R`Gw_b>Zru_)>|z20b-TW73lXa{r7!I8}y$*-_jQY*#96iAnye~ zH|S@{eTfBZN-iD_%`rgFcdL?)(4I}JKg~L&;*GtD%2m-{fp_Gimk+;6V$;VG(dL)n zxor|#SN2q~$u!PsmBvRlRnHsHjvmFHInAAT(8wH+KP6jxDvKFXo(i6LJ! zW^zg0-)mPteBeWWeQ&Sa3cqVkP{1E=E>)$S+in)kB^}f14cgbZ6eBVCHNS#O2QRr@ z|K7!=uG3GMy*U42+3)Y%Ux@F((M37_(1W;#*v~Y*cr-uI|J=|C9u>=k?;6hMQF-|G zx%O}2pOwG+u04TI3U@pQvbFiN=lkCmGZ=hYm$Ie(68z-Zz6rq>Z}Vxt^eLm=pZOG+ z6rj9WNfb`#%tng3YWH?soz0 zztwDEf$zc$Q#qgIzCw!nt~&S6DcV z&#aq*;*c9Xw_dMR??2$5jc*p(@4>$EXP-r-;SXd;kKBFT1zvn+vRSgCBPD#u-ZdY3 z&^501f4}e@D1D>czYG4?uu(|r-*V(T8(gz1zhFNPLt~?oB=S9<&MC~&Wl&Kl+xIK< z{+Vm1x86oi(Wld7^$GCaTQBR9;&Sn;cE-fo8U_`v-}~O_8-rGw?hUm=el0&M!1*?O zt*yL>!}05(cWRzW8RRiZ_vTuo@6a~~<=0M)0N&s8^LpLAo4`L3L-`lsXO+m@n!mOK zy_SpB)8mJc@1MGUvJ^P19Bpxby>#_?CO zsa|%dNYM&@R{gj|Z=maY-#eL^5RAOr;5k`g0-Mxk9a^^f2AjAl=RVH|-pLoWo1@+W z|Mz`&t>JGrNjHqi?}5K{EGk0br8v9l&$nDe-D{!sl&m9@m2W zbHictEAuXKXzrNqxvQA_Rv(@O>_F~eL#mrjDDpo`dGV7v;CoqDY`K4KK9~Hgj1J@& zap~lo%i=n0=%2sd<|^(*-+o5U!Tl$>q}4ptj*I?4pmJ-&^J?UVibdbN>fw^pY~Qs( zQ^0elymDGA3|IDFRr@ngf$hw*BQF)9<3x^Cj@npPc2A z-LgXB9hxjIi|@jv(*4!z5`;vnxM^+!LTVz0fx~3H3&}M1I{OZLh$ddTo#_hw$nr)Z z>jmC5RVw?1~t8!S4^g-=*h*4~x45DWT^g(=$B1 zEe!sz*j>M_8|cBTW1mWDfG<4Q-)jF4eXw-~n*YzYUGUBP@CLg7<>#+P|9LTJ%tTNvHxi?X=K62;Y}N%Ywoma zeF46EC``%pMJSUVOjG}DmxO+ntwpT&9r#@vO)KUC@1H67w|hTy{lKYr9)^ekr_cPN zwF+~8jY(Q{^V)mKC}t=RLg5qGcY3 z-Q|FHnm4Azn*r}s)t$~3jN_hx)_?WY4Bu^%Pbynd$?U^ z-)=Tt$m)IgIEGCP>Z0{YSKxbTR}Sne#-8;BiGzYV@Zv`69DCrMl;De^9O#=l4hK5- zg6DpDdd}j;e;ndQso9US0={v*u?$UE`fBN;Cmq6}N`cT~!u6MooO$g6=74)%aJ-+ilqUV#6TJ5zLl^KI|Wi?ZO7W66rU0^lCbe&d`3 z=svG$`m3eMT>ASsX7B1kE;U}gQgE-1OOGU0ZGQm$XSe@kmZdb0>hzv(_18g8R0^Qm zl1FQKZKWlc{~O|R&X13QFXpcBa2EWrd|jjU$~DkMrEk{F{>7u|Uly6Hn!%?o=h7L+ z*7B+Q+YEueGoQ{3Qh{qUpDu26J7$dUK*-L(PonSn^fphiApkj}SNevZuFnzBBIj7^ zO{)Y{v8?07Dez>wRVQT|eKGev+U5r09t7;X*D01SAhXFy(W{yTB+?(uS^#`BQ<~x8 zw^B&XdMn-E_z20SDn8Jn5cgn(ip0xVPUyv65ce>$qnARP_*&%d{>|B`dnp-vCjN|w zwPDY5_v#NF0bJ~X$USfOAsu@luKNex{DK_O_HRojs>AOpo%_%Zym))!Gm#51*xTu0 zQ<{1odr$sd+~4*Ydwh=mDy@`d&>po;--6W)O26RzunYRJ`rPWoO|MGp)>UB3UNlZH8gMqVP^ju`plCTx_Um)vSi~AEUa{sna?L-R>eR5mA-dIexE1=&0PjMjFZMXB zzFnyKek%0H21b>xI-87s^K?B7&}$cq%R6GvroPE#QD=a6hKeI=&mLq`jP?E#vB_+@ zF1s~9{5G2s4I&rps%BHGa&MXIM>a``Eq3CKLjMnxZ4t;r-`w6Q?Tfv-UIzC&<2NAJ zBN*OT$>q>|@9GUodyw-C==y#1IQH&p?~R?6&LKTFZ|_$n_%77RNaQu*dm*YY{m~B& zP3Y2an=AqTDyKE`2G?P_X77D3EDR4wsA>u+muS?Fqd}ywcq*|KG??xhbol+<55!Z{E_E2@WGB=dnO0` z->lJNAQFq*=!C_UmoWdM@(P2*asInbyPBH(;E_hXvb868K=GLr?8W92->S#)H4F1T zxV_U7e%YTm(`9PueBuUP8Xx$QPgh1}^+){SQ~go*3q`U5lD-gh_~{}6O~jr$Ib#96 zP)x6^W(!F4}v<`&5^3Ns&N=V|H{GztB2&vKYyW27&Cz1^slRSvN<|J#83|!1G z!f%OJ+l?G(PH5rzfYZ=VPapfX;XU3rI%f03Rn3u9^+ICA`FOue;n?(4^c)-93raPg zq6d&W%f)RF{;;X`s#f@5K7R(bjah;ZyqsgI3?6Xwgr_hFJ(dflN6HJ1l zogZ3vUV9Suunqah`9Sv>e5xP+5c6L@*fV}5&VTb7!)>1qG3oTv$+aJW`)h|XIL2j6 zDmyRrL;^XU9@S}N4cx<49m!Oj0sS&+(Q`lexijiy-Q6u&bWmP-*FWSKewv9aS|5(@ zLH0k@)k*NLq(aen2I$09&>>!6y zN~dmBhQ2Q|S-1R10S9>4>96cd;OZH09N2gA>5}p2PD@?k|I{ z>*riNdo%p3-|wH?b>-61Y5zTphu-P`R?{vgkxP?qUJIX<&!wg(6`5~d02ejcBy~ae zTt87F$x#&jfVrK)OXlJ{H(blzW5AufJS86Ssr|HF?BpIk9lmK>_ZYmm>f0^jb`=3V-1wy8`w9U$eYHCyzZu_!%M!o$ zA%`mR($~}KfPg$LU-Z@_3dpkQZQvH*BBKPQ`73Y_YUVGN68j7OaL=>hpeoLLn^E~w z3n3{c)&AWRETrPSnwvJ?#do6a&E%~jPUQ4q=xMC86RqEvt$8C8Jsth`(Jpuwrt+mK z|N1lsdg`%ecw7MXoBKJe2z}{5&X4N<-kb#;Xovs4`CR1S4lhfWOT@mmzqjhYqxVvF zdrtbj@#rJYTk>VuGW5Krh@bD^VSm+;_xtpYLMP&UGCvF+9MG|0M4=Hmx9H~|R7SxU z9L{7{qpz!}NJlpT|F3vZm0ke+=^Tvy(-WM|rCxqgixe6O1wRRTRv| z?bdjR`%-W8&!Cw_Z%-!rPQ%>KEvj}&o`(F*2BBy_c&^?*rMWW*^If)e*;FQUn-E#= zM(q6@eKlAX8pWox_uu*^UxwaaG8hqX4|D&)f%cl$Y|4y1y>Uh_o1#MRzPFypA*~42 zq65n4GjbcN)6whNKP5uqV3lrI(3 z_3trgwkvG+fG1C|!0eQ*r{pL9e=yYzllmNV7PfF0X zmP5!{ygs8}bpibOkYAQ3{N*bJgOcLFMNOI-)e^V|_co@+jhii`?*B$JuC5o-oo#un z={tpFd2zeLuM0w|PVDOzc_*aEN(tZL+Hf@J~zx$M-_%|Myw#%=*8-tM-00jXRD-5*m6N(^PP- z)qA#@t!2^Pu&Gz=p>s}}tDpF8H}=+UoT&X7xF<%xXHCQn>^b)y$h`BEMT@#$9y;C$ zeaI|SNg8J+?$?@a?Hmx5zq;usA z^nKZ%Ut_Yt18UwMw|T~+zOo*!RhSpt9Sf{whE6ZXhu{JpzUZ43HeS1xQ8+lDzm=l*Z0aO8cIZ$B_O z&!wnRDd9ED{lKNKpBZEB8^*j=Rrt)M!p}uD8smZI1Am3yXd!4_tzHP6ajS{eHB*Z7>b{8V19y z(oE3z+8-JFeJ_J{l)SNMNyj^05wWAgZ_tCu;2teR?nf{E_c<@%pt-B(wXm##dy4y3 z7yDyh?dq`BGU)z_<0r9B!tXj0G0kX83wkXN|5+;_*Rw8OecRY<7Dc&zTcKjWBGq84 z!XwD@?3mtDVYQD%H)kp^LQbQnwY%WuLgX2)1$7zP0r$*ooD(P2gB;s;3`wpCO`JzZgzlQaUAppzCMs(EgwdUB7qxQsFsI4$Zl~ zzGiX+hm6lHG~aoiLy5WCuU_PF=&8$Ofi`@t_N}2GqCda~+w@`M5AfWy=ZE(SFf9!#CKwtWib{{GwJbRhjloiX&DN%$clcn*NBrKNACe#s}R)pyJhl3)Dqv>e=n>NIXfkCTv+ za_6WTS#MtCO++-a3AXbdnHhFqJg6I<$B&uRI|*f=y;72-Th@5>xRD0 zgOs;V52Js4tjzH9&}|1Qu8zO*1Gk;#2c2Q^2RLSU zztrn+^P~_4<;JCZ#X}d(@i&@quLC?G{YI0tG;(YCZLZ_jFiB@~;*&0C@Zb2i<0nR= z*CO7ysY3_O zKc~R&ln-=%zD!IQvw%hFjk+3Hukp^s!jONv`*0t^#xE=f-?b}LKbxY#rkX9L*0LtR z^ULP$Sjb0?r{x`^Yag3DT=QQz0Pnjjllm8O6Zqyw`gsrZwr+`R_^i+YUhsJP)7W9W z4{+b*`P=Cn(ygywIl35o-nOog{%gviyi1GJ8{p>_Xz9r%1|YAjd)CS%4*TDZoYH7P zuXl-qL!EmW^qe84@8@O?O}`K==KPC8_a@DcdkdbMD{nW^0X%oH>wr|{N^Hd%k99y5P zUc{rcxZ{Pkb?A{T8>nsW)H)`VyONum)^O6+@_f0525=l8)E_>pnJZ>K77&83m} zchE)iI>S#_trw6?y6?@+4)DbmRrhb-2A=F&_Igb)bkk{lM{A%D9eUJLw=Nw%LeXGD zCUO<`2ZoH6*5RJKoc3k#s{r}%vkL!-3rQy9-jxOO!3Pwl7AqSIY0dcKpF?mD6pw}2 zygMkQe6I)0{wyKoTwG!NzEMaFO^J&WSwlhBP(xJJFLV zrDqD!+m|pWq{i|DeejM_jyL%5f<9l$* z^G0SE`T%1Kzl8c0f+yTLp|a*H_CoYu+LD6YbMd%ADJ={1ySmj}w(P-PhTnm$uBlA) zp5DCAdBUV;-pjswL;t)ol%DlWnngC|^QM1Y4nDi17xd2AOQyb)W|QXSCY6fCnEOHUZ&z$$)AVzTH!gL< z{;FTocb12-X_3~yph5UrO0lu+Z|<)CYu;a`4dHWlI#=zB-h1PTL(~Kt^0blk@FU+j%Cr!D-Hh`hxpm83=saBS4aIU6 zY)Dj&+V+Qhwxme*Wa;D#_}-SR!A^o(i^$2{{>?cf2z=viyfJ{8SA9r#UenHe$ zL+K3o%fa;WXZNT?{NN2g(^e|Ui{Sk53V7(sTK^KapH$-bH|pcDH8e7GKJoYMEi^*> z_?ML*q~UvPA&xD`AAJ+(6gz@*aP8=?*48{4VM&+vVt)buId{xiY>7ss3J%k26!9)N zwI!9FrW4Pt7q{`1(@B-e4kK}42FX*7WL;l2^!mR&^d$aMDu33KEt-re|ghZ&DN zo!yTnp)Y1cRD~x|9(rm2c1KQKfAnBP9XA(OgC96dZ2SNBi#!yp;wRvX^~g_3gqfrN za#A>2A9~P~K%{#%dR;Se#a$D~yJhIspJpQOCfA28u#t&bdMIj3&IMf6sx&DQ;14S(xi zpSJV{BjdcL7*^EKT22ibEj3dLEI;Izqg=L)UKz?@%EZlg7c z=R7M^JpkNOF1PGHcy3~e{#XKdu4>a}aXau_zSkKuGT^x(FQUEPS%BA`UHviw`sReQ z{^Fji`2E5C^PjV^NB6bmy-ei$w@$p?PVKQFc1z}V+os`*B^jHqVh4Y{l`gVO+!o(0 zlYPOfZcFy8Z@H%dynpn~DbWZg@BwSvpyi=B9~`?vZ{0xtZD4%vJbJ=6O!8X&yO8^t z+@n`NWs6?P<~bd93YnX3janrM-DiWfAdlC{mmcd(GpbhZ(Ht0FWmp( z+gSJ3V*dGlM@&1SUmz%b0I!lFPUdEEh&4Ar?2+J%cV3-EwY$zZma< zoJl2DJ${DmuWrFR@WUZtoH>bi!$dn_5qL-{{#!|jFpVfLi?F)AlSbnHDC`k}pY~S7 zB?TY#hQI8tayE=ce(y~@z82>ozFtcBemn9PR&|Hgf1?pqpA2F1O>`poQlMSVm`?Or zhk1`jL0@Gr4*U5AIB7O$3tf{zMA8Dw{J|T_c3*t;7d;&Ag&&8m*`hyV>omH#1AB$) zqr#5LqVMG%ZuSViv8UhFO$rs}WFm`WWDxndsimErC(#3Vz9q6E9le(;cbImb@!-Q^ zVh3HphX==dgBS4*$lr^NKPPBOw)fnQ+OQ8jUG3g0JDA|Pk;3^O!YxVAt-bnY$aTgm zB$nKR-<9Y2ecL+Vp9clbGI6;7A4l4h>R|qPd!Hz47{S--D(;Vf&TmBDIIepY`G*Jg zZ0GWz^JMV^i#J)3xaqHfR^YqAdsj(rgT8-m=0w2_A!{;3H%zZkMsN2P%j+QcTKA^U z++5*^9?OH@&APz*x|xhDy>x4$b|z=5Fz$W6zlxldxc7Crb7B-fTNA0f=lcCwZOAhr z^QIC}8xor={_n{y@K*h7?m9yo^5KWVkpc%B;=A6S)7m_gsHcGX}=mH`J1 zi0+(hL;kJf{gd($?18A!;JdVhJ?lI*LR0};l9zR`?-2Ygf37GiZRkAj*viX~QEkbc z&A)iPy)f^W6Z7likONBkIG|8uOX{6EHb2I_@8KG#%KU}@6g z%>NDJk*XngDw)qPJIe_k5bG`ZurQHIwz7XX*o8cuAvOH`m1-*a+QD^Yq?1az$wqW z^(u{UstU`kFQAd{ym43Fw9$yJlem8BG>yy`sJxI8q!XX`1e2)!bYdT^9~J3ICkuX6 zxzl&)B(~wy!@ecxt?jDb88ikd$P)^gmBYS8J%cZiY-Yr~-z)bG^rOJrvUNXJU{4V9 zyU%3``ZC6qpH3E=lN}a8MM7Vp7cn0;3huBV$M(H8?1Dd_@t4cjEFJrNR#$O4c4Cj) z^Hb8-mw=O)YeUWP4#cT{;A4URYg9L|?=^V9yYeC@p-fBi@r~_|Z;i-%8ofOiH;(V0 zc2*k*as&4te8Q5x75p}Kh?^Y6KB{H%w*)Z%f&#Dglp>IG`$pMws{rrAVr7RPaDU+~ z`A6;WxAuC`>{6CvZY_Q<%!?t9>2fk>47lgWg~m$Hleq50tc9NW^h<5m8~D9d&Gr>@HpFDh zpU0_Owj{IUNL!#3ayxnVt~zNz-+Z`oIrW4sVbi56(OsbD*w)IP55u2}{daY65F zYB=gBL?!Vdy|k5bRPxzmmEF)TD)#N#onO-Ze@0G z-t&?$#^#-8XfxIiPT*xr4ajinI} zrgMQ&35}Q-2I*II;GB%8cc*-z;d^s$?F0Deq)v89belSzM6%S$)Z5WX5>Md6nPfT< zp3XlN-a{v=1O?6NH6+DYQdB zO+V!o(Sdzf5()B33m>5$ZTXzKYAf`hRh-qPr}2GL{v+uo*%oAIvv7yt8}z*vX8+KT z`~P?FzHrNKOVUZnbEsk<$M!6HUtA<~qPmr5lHh;Y^>U}JcxOr0Qd8}@mZ7ic9~}Qu z8n}Pbt>poFDRBSF`jCP) z@PyHZ2KzDiV|&W--~WT&v&}VA40zwqRH9TCIW`l%;7fmx0>6B!yIP2QzdTW5cqj4< z^$+shuczQ$NFH4nxd+}`|NWofGvIw?zHh1@k@Io(5Ig+OhKRiXQEn(?OSIb$^cyOH z?;aRPH_*2wtD8GH4WRD}uVP9b_eFjusA!S`e@i@Txr;CI4N_MVs|udll1tmTXQzSp zJHnNKpcsxc5c=ux{RQ2zwSEm5xf%D5N@Mndd?1J*{haK4&CA z-}x*MqjHBr;%{~S}H#W!pU%YPI>Kx|3 zyME;UL=Kf?rw!e0egNONRQo1>3zd|Xng4v^9AdP&vH1<06I`kqHhjSM9 z@%L%FcXopxEDMgjZ8<|D!Mk3mSgxUyEK_bTstTQ4%@R>lwx*MHvI8lz;dl?c`Hc-9 z(aBs?6HV+F^i_szN31S`C~Z-{v#NkWWKMgp`FianNq(~XTC*o|sY&~Dyx7f&{=C+j z+wha~u+>Pg3*WnV-zk;}-^?SowU5mnK5+DpvSj#Vr-Yfe`=O88mYXNNEnRpoI28kLK;Q4%xT}7V3gvF@76nMXC^XAjp*o&_EtYWz{?tL?j&G%Qs z*NX8Ga*64K|Lf^E{rxL?T>~~PI;(8SPJTfre;Lg2rdYXxeaJPW>ZrDx*^+A)EFO)y z*%IfX`!D`L-{JPh+KEjsu8Ch&dVWmA<$-~rzz8}oW8 zxPL|9mF2G6p?6m9N(|S;dq7V$={`aw z35^N*CYJDrHJaY7g8tL4R^74!{I}@joGJnSkC>fmX$1aRqO%t!uVEKQug}mb*DutvH9_jqXjrfG%fMQL-@v#Y-?NeRA}Uf z#3iGc!!%O6@#%1e4GsHD;-AF0~GUZ@aMrW5t`s#o@z(TQ|bje=?bo!C;`AB)0YXl{{o%panY zoi|3(?}#!;(b}Fihf@r4VkE3gqmx16YyBht!~Paq>!eB7Vl%?hXtK6f3p!D1*NH30 z)y+Sn~s&o>TAE#MrW06QlSCXESjB?@_eQkkY|E|2TofB^vSzPmhkN z2O`%$k?%bL+#jkT_C;2{ECm2 zPyU5JkoKQXIPU!w6Lb9>J8g-&;*!(ZBevw2P+nFu6S)55-B+v7b5|ag);gSIOUi5V zxc%;c7i$KdC~d{>i`XcR3(V5xLXI++C8X&`Z~fbm-ML!e5q)t=>5Z-b@}ZNd7|K zId<`MmjHBAtBp$Wcn>IboDMHe(8;}JrP;#Xbnx-)WvW?pvOS?I>A-V3dQZvh%UBs? znRL3m7GaQ1sZ(9*5e#C<(4d|A${=yC;_r$q2R_O!>W~;i?m|QL#GZ@zK9b14F^_Td z&Gd7x)av4UkF~YeSdp7P!oBJn4|Jkh+But@@Chd4N^k!HFDU$5V&w^5Ed4`Wz_|+h z+swMh&P`a7oWQMhO9Id{&wJ`Kk$<3c4p6?HLSNmdC}cR=iqyn+a@Zs1rY;_*pWA0e zc7E!nHZMURttzz~1^(Z@q^m3f{F5_e8s(4s-*%m}fehwf^Ztv!n=;^w1-Kpde{4;@ zJ0F)b1n&PQYoe020DkOm-0LoY+=BnO^AK{JrybQi#({gpH%n(H!Pl)2n_uxg1pW2M zgS;G>$n9s$+<#qVLo9QSpFa(qCr>%mwRy&d)cWh%&2ie27Hxs&v%vf3U(9@HMV@C} zXMFO1xc93*1yzflwIxcY6~;5J*b)|l3rW1_btQ53OSwI^B`QbeJDYluXS?>Hc^&lq zP3!h6&^VE2VB_O2h0a51IT^7W`OdfFjRlkw=zV?A3u?o?|8+Qj$DwcvaoxP-Lm%#a zjYR90m#QfwZeIALaSz^w-Bs_&4EkWVj|LU4pc1aLAvGP)drS&DuCpQk>2UXIw$)bj zg7;s(+^G)y9w;J8KSU+BuGAX~pMd@ue)9NFI+d`pcAxp@hJ4WMJJnqQRH8Ge;*%B$ zpKDafSUrtOB((!%))d13U2pYBrix1Zoo*ctfDX#E54@J<(f0rt>18(BJpIGzr`a>F7ExhOK{Z1Nbmf2-G_YuB=ML?D}3!RiE{oxGR zKqoh51-BZi(Fw1;uZsfSgV!zx^ujJ;{`;?Y&ZW`GBrmODXA_-#YZOp%`bsAWS(0ie zWEmu?z=)@f!60|@`DfVgFv$H!w_2kGnMBpiit-q}ooWM*jqgOw$#=0;Cb`%vq%d-+ zz+M7AG0zhvF@NMoWq7~WJVT$x)-z88J%N^I-IHM^mgH4~xlb&3!6)5XWqss9r{4d_ z@%nB_)*SwlQVu>qzhoYF_BeX#tBh`PAotcaGq%`p%Zi*m-|aHg4m{*B92zlaMO5{@ zU(O3y6T!D{~%#EWeU=6`j>W8;JGpcmqqz4k=$3u)#=ReKJ|k8R z_db*V`G3=k;KkQUxj%#N%E+)V5s@YjpVlR?$pFWH8)VtF6Zd&gfT*t){I6T*y$21b zcD_x@x{~VBaIPCVY5x9S?g__5mVE6%p_uZOfv3H{7`97{p=%J+XPCyCX z2fi$Ph?q(wTGwi==>ShYbo-jhTPjf(`y`b9nM#IPa(#_{!yoAVzH}V(ALq=tSSUgx ztTO813XUjeIpKNo$`4Z%&(%+QdmGC!Tw%)=6Tn*OinEYto4< zSD@WfOFCK8qrzVAMJJu&4;}WV(#fm0lWU*W;yrjs@!mR4C!f5e(;@{J$lLE(nXAVj zvtwdr$HSnn7PfBf>SmA*i}r=GJxn6FhTGfG)r{B+x-{NEAGzs`>v!P^?3+$Xjidk{ ziEL255{w?fX7}s)f$Z30TW&+$W{AG;x^v1SI0x-H(M^gi=#i<+=t?6O6fk{PH3GV5 zt*V#EANaw`CeJN>h91<+zm0kqK3FbIuj~4I_ya6C4)58m$zpQRrw8zT1)r3xJA}ML z35TrZeNXhWr2Tj|CS%U`DY&FoLihKTICiifyuf6AlM?2?xb|PTtFR66isxbQs$oBm zT*Z%5su5?*b(HR)E_9yen7Vv#>~(mRalG_$HNGcv z@yYyo;Qe1bVn+|nAkS9%nevYVI=)CtX*TZt?hRKn)o|~Z_kZzyf_p#b#DvcQ=saRt zZB0$M_jmR1c^%3^u3<^3v=jIK_CGuSqu}1BR2*CNcN#vgz2ROn-1`H$eO`NT@AH0q zI=V#+_kTf4!4?JJ_LGAg8fxGH-Lgk%2Y^#%UiGCx?_BnbDL+S{lEJ@%&!}gpWM@vT z_p~>B;`s%(^l7cPUG%m&$FhR|a1J~S_8&#gT4Gy%Vd!n>sjgq%)2qQ7RGxqS z@f>`iv$OW(7>zg@lzmTGM81NDx9~kb{4%5RT73nahk-zU)&q1B5+*;rk4h(M&xghK z`C;x=^;u2v9^AfG*EaQ-PS{z__+B5Tqfh>NyA(HrjH})6D^g>SzuD4W-<%obr@@ak zJ>bs{uMQ+7|HPm7UtD}?%On@xJB*3tnvoaVuje^Nn3M5AH<<*y3$;scy(sVzJfsE# zW@gbl3$VyIjGnOak^3A6fr}2_UN5DKbHHWx(eveU_`LJs0j%m)WHFdpkquvLuL#dc zy;SUN-kLxA{~QG4S%;VHH!H$^(XiKD6gWTiGkpv^U@p`{at!)EyZbChI&%HCdEv0oMu z55G%f%KYU~23r0L1;v|-?$2uIx%zf|Zy z1wW(I^Qq)h)tI?xe$l*6aUX*P^f<+JT&v?=FVh-+q9j#97r8$UO6aX=SUcG6-`>??;OjgM{nMrEA83CuCnaa02|fbkoW` zRvVZ^ePq|*R1lN6zj+cm@D9D^X1BW<$f0Hg#B{93yP&cBxTSpu`jpk&|7hsZsO9E0 z2>QS;kb4r%e1iS9S4Q&-a1O@uiLV#*q0Sf5uRghBk6ZtK(YjpZCNeK+r632lFXjww z5`5StaN7so?bf7lzR?K>}VgB`4chU;sbNwg2PGa!|@Q!jx zWHbC-)*?L}Vdy<;0%l(RL4Vz3)yN0G1JHjIPZ?*?pzphVG;#OCzQYD>|Ak~*ve3J3 zR1G~|HHw+k-skXv=ZD-^ezqmA(?##6uRxxy*1&@keMZC0-Ykad6hbXyI=Y!4x14k} z!t)GtA0Dp_bm%-;I<8rJfcLqwVxw4b@5`6oRIYzTAzfwWMf@e|b7AoPs_b(}VH|D!+|Ai~M&?EJ?p9(t;9P?-;Dd2Ww+qfwNqq;4X~=RK5xZ;uONx(1J{@M{xv&F!tB zT;RX6sg*UB!2fxj)h}k?3o~EW`#i_|vwmdouwed;uNa>X_s6@jwV&Y@jU1`GyKNnE z)hDyEr~fOX5$>07TWi6GnJIppmtKQENd9pd{!An48~7?m|I$dtb|!DeS~@9kvyG75 zOeYQnZ8Py&baIFC>GBHjf>6N$&s0}B(K~YTVDM!+S*fF7IeUvv`g=pSOFy9_H{PXt z?gO2aKRp(32z=T4o_60Zc?NmAT(OG%ID@SFv1jpvKZ9s#1o(yAV-U9sR{vhkF$muo z191^8CVA0gP|SLpN$3mnS~+X+9hp1h&Fh!2ukK~dtDAA?m5rSi@xWg6XSeO<`{5tx z?9o^;c^}`oE0-G$U&6bv!r-AG&Vj}3%NE&-$PaD0t^5+XIICYDOg_LDUQIY#XZWm1 zl%A*dIW6cyxlxy!PFs`Vf!JLt@By^!WtA481Mz*;{BAIe+{4ZCHzw>hM0bC6qp|{U z|B{q1H~ij|MAn4w!2dh;x2bc+;%8A|oh9!76Mt%?mN5UNKg?-=zKuRFAJT;kww2`95f zA=jYXalPnTGldLnGm#H_55HF+eA4kZ?*B`BZ;RvJ|0kW*#({gk-Z$ENMhf@#i{y^p z9mw%VJ?O53&N)cAkyWZsC0QLphB;>72m38%vYF6-sFd8|vs5A#c`B{ZAA5wvyx1nM zQc3fd74lNok&k;?d%_iZ=Qh@ig_rlhBkl;s9!2hG)4^wM zpYgtg@m+UX0FJt-+7!tK{c``e2mR~db7@HMoRp%GPKSouxMGOFiQ9KR5gIY&JDS6G z4EKD(NxB^cbF0|7gA@4YlWT6zPt1RC!*up;%zyDiv$*FO$P10Nn?AimBO(RDK5|cJ zq+;w_!mn-`X|4apI1E0#{6Hs%ICLS6yT!+&R?$gILmpSQIGvm;dUo1v7kKiB%?<7& zbRw0??j1>^69L0Y`?cT&C0{nA*CBUj;TX|fTZnx2o3d*Moq#@_gv%;6Hr^xxOJa^Se8PjQuQ``+1W=-beXLwDjUUMBhJrM1V;?tlE5{ zht4F5!R;P`?M&jDZ}rPlAN$*PoPPOR8U9+WnY?m4a;R>9bHb6U&^$D6V2S>40>6|| z(=_(wI`q$%sUjb3%fC1L0(!r1MGX4Nz>AglMb}PP5&1@*K#RovFJhY zA8%{2ez%K#0N#NIkK-TjUapS%Y@^3-=E>ywya!|VQ z@xc}F0++0tjYT%(zM%D&-|)MRKQh|wg8M)1m1NWo%)h~y{c>aM@6nZ7@%=sY&UsBU zv(JvmD`@b&_X6&(xuvi>1$s|FUxmmC?ReS`1+po_d=yKfS&1Cy$njM$RYW)nJb*l`y)`8Mf+xmlm;E zK0XFLzUaE(eH$uSHUA~K^fdDPyLx}#y#U>RRgB@|5ab~e7F zbGH;hFEt)cajm41DgTJuEzMMNkXv3&?G=@r5WDca4!Gyzmp69sHc(appfsPT{Nd{6Zkns4Y@i-ZA~s^Kb?eytof^jcR<2u;?=Y> zaz(V}b)muF%W{fZ;^4;vhqo1s+@q6AE_b&7eun?f*osTZ6Lj*l%PpCO9entXxZ5S@ zM!93pbCV7;$d8gGxu<6s#I!6k?|mYJltg9@b2TwYLZ3rC$8QF)H!M}CS7Q=AjdLRr zmzadTC4|V#FiE0DPm&RGsuzb|RE{}eubjMiSv#vGF*n#hk&S$*#VXMsL%qO9at(1g z@>WFATk`I(n-%G6(wF&n7yiKMPd{S5pf7NW`lby2n8fC>pmWP9WdE!Z>9HIfvlGVV6P_&{zD(ch>>)9~o7mk$>72-(mAjF}rL_Qa$b3 z0&d$9-+g;ywgLC=&=|~cg3g~3p!P)PA94~`T<2>xP)K+`J!otFfIO$(r$Tdt2D(9YhOCeg1xF0Tkr;zsPLXO=W$RR)H zeMuF7F2DWLI)6#br?HPjEc~r^uMVlCX~3UyANISchj+mEfpqps%sE%up=<`;hh=6g zx7>hVp8d1C?MEd)IT+EUSEz&}TP4&a;l0q?p3r-XN_?v3%YNOZ64wY$(Ji%jCrmRr zPebp?T<6kI4ZZW^i-0VNPgEiot-bCBa8HLxeY!Gm&!v9#p;2BM`C0Nc={|5jjf58D zfcGx#xGqtx4joi~+pdK}G}7aG=@=FIe_z?K&`;=}kK5LH*1-pJj8;yp3!;(5gt%o( z!2g2%x@i|~(#RSouL`xhcpvlyWDa2dw>h(s?3c(#3{G-e4g>$2^y!_2KW6q)IeBgc zbk4UkNu$UQz3d$jJ^>tL^n1@qBMmzC$@?gMFv2-_ZWJfNq?22{lujPJ1Ao^$?|Olp z-O=`~&%g#l!mdb9 z@^&M?=#I5^;8Bm4?LVOmSbf@%QKfX#w zUiwKghfpDMqDm+1eUOvRm^Y|8Dv$pA-Zqv(3ikedzsaP>#6RqD_KP_C`RgGY!dW}^O3lrNxJG4otVpsU=kHtH3q;P-*DvbF%lGhwtF@fg zudpTGXZcy3WiiLsc+@@}vL&S*{JH6;YzdW?A96Ds??TIM4%R&6KyRDgd(n)&=NpCN z*N-8`Jko!0WI1&HPbZ|ckn5TKPuo!idCtbqIffk;`1QiY&AjKa|2)9<-U{HJ{ds%E z?iW*tKid`==~fE%&T4G18l{lJEVl*Qf6zfy5@(Dj`s(;v!Vj-T$K zOvB%@OUerug1uA?r zi2)zhZmds9N8YD-DYUczzVNqp+4hIX3-$Un%rt@*Bq;@L>Oy|**YP;(Au1^^mf4;^ zh1}@wfGl?Co$0&@hrHQo=+SaVu?hf(w5$Kgk%WI`QMsGB1O4ExL;nbHf7O*W>RRBv zt`*K-X_mnGV>|4Nkb|fm$y_c8{eMlUyjwH$&pU2^lGCC8{21)HTL}JpKWIYdJMce$ zy`NgZ6a4qwj(#-6{ojzbUE(z6zxtM!!RxOylBrSYmd;8iJES5{G_IqQ%5ABcrm}RB z_;c#F8TJFuo^t_(;eJOM@>vajSFgUAc7el5q%Bx80P*#ZfZRG2P~Wd$(FJJ*}4bI+KB zL#&5?_ij6)b@TJajo9a+{%owZ>n-{SIz|Hgo|eQXC0cJ9ewt>(rMW+Pz(u3ZwHMGI zD2SDwG)8VNiTZAONfx=FU3p==4CMYje1G3gu_g|!i;^aj97-Tz^)p{Rs#mY`eodgD>PJf0masd z;2ZBjT?X>}8NxLmLa@)=s6VnY$Ck7n*t%>G_kT&~v@Hem@A@o2%>cZ&?`~DWT}kMh z;SuqvghGlg{8zKi7Ww8kYq{inko(yo6ZSRn;BE5k`Wt^Vm0_%D(khZd`*E% za>i`#(XcmN&x!rL3-n9hch^_=QVI2=hQ8Eg^xUlu>+FNhDQC1M&nz1{>VE&kvv;W2 zW81Jf>M{H@t192pHspx1^om};h7P1v-^T&I%QAm(+kvlC@}TV4n<(f#^uxP_##h0& zeK4+O0=>Ut;7L*!aL@j+jNDVeJ&(SK&8*j}&^L>8^ClmMojT62rqA>qDuS%7;F#qmu2^mAubRu4LOjJ;nPN+`xrVkF$NleJ! zU#%8&;`(T6+6p-6oZObcivgJXyNC0)#nZ`w3${*IZ_`O(wELc0kKils4Za-NMJGMG zSOTfQL;Qye$M-D5e5kHJrHeUhN=!XUCNM-K5vF@Pft zGkoE%9j7$TtO8HidQxH_<{yJhx8+YNDKg1f0aoFM3?`Y;ihi*=8@iIF%9rO%_v*@M9(19xA(2%Nz!!qTSMO{9pOtM1HGcu$_wAeX z{|3MZ7E|0yKO-k+^FwCzC-`)W<{OEX(0TGx@1N$U5$9de({-D`b1DBd$!?>OgSlQ| zH}=5qJ-isd1-YO5rt2urPSD7)z4;!O88qVbl*5+>+`n40cdvN>dIL<08*Y)Fp3~snE!_tzJ1*b9&A22pDKQkPOcj_+_VP|xOM()g`gvym~Ili zzQ+gW!!&36KqPzuv1eUeH|a#PKKt^^`@lcZt3MKX1r&apTL+;=(l z3&UUAvT|EW>jH!5=w&{3lVpIIq|w_`*VzfzO3zCb|4P+WC-x9eLU3 z?ynwTN0#QQxp-{QSLhEqIC#X8#8hfodtlGj;m)JCjIFT;^j)U8%46hDgN9jY=+78h zB=YxJz%Q^ppTe7l98uFM_N+J96Dq=?aAyttv1YCXt^+p6hs*CZIuD*ava;_x_`tgP z2hz4Lk(;ycu6VU*LwJ@ba>>%bJ3D9x-+>26Jm`w)KlnC5N=oXZ&?v zqv_8(_yZM!^r64DWR%q}@fUPYrpH61Ah5U1C^&Kx=ATP+zq5V-^q{2hqN#KWk&IA0 z$d6pxZB;GN<~|C^j!u*0N1nOu+)&LwPUH>Rdkl{V;T)ic=PHZ*W&5e~Zooa)c!oue z1NW#GUTI%<4ESE`O=OJ?=33yxzT?n2O=8UF-R(MZ}=cQB2}nO!+O1l%9D$i8kQ1ADldPG01I|0`nNQ)K*z zMn)N}^NnpZqVymADIGp=+`Zu5?c?wVc3l+Q@smdUI%=C8*w7bnlJ|X!d=TH@`K>WB zI0peUd#_^to0w9OUGT+tg9GB7Ptr-s^SzE#2Rcz%?LJYCyhM&E^SS30I@w*YA@tYGd^t;1z%7YVa&Xn!1+jvJ@G}&jx-r@ zaPG>sBbzcz3i*&r`j;f2HWQ58ov3Kz_D$$nicip@67U_2tdz@depr#vU_D1NQDnh@-v;8P!Cal~n81w(>5rgL$=HJJ2_;Mt8uV~WL z%NM^Wq*+t!^9yeDaJ`BSg#!1>{;3w?+Ds+xH(ReWcEh(lai}8U0Om3$R`iw$l?1Pk z-Wdnnv))!&iQx*|a$Z0}#1H4jM{Bqed{=*?xzd4TDs*yERFi`qn1e>IJao?HcNH5h z!Qb6Ot?ha940(oRnWIw3H<+9XdF(Kb+=JUP^Stl4_k-sTd|FN;H*?Mw%B}%!zgC-n z3Viq6(I>RhE#RlmsXvx>V?PAfmnf41=!I=euqZdi{rz_|QkqI5&*iAD*=K0PXzSi% zD!@H|ersOq3#Sno-8c6V62Twtozrr z^Bs-sD!br+eiA(4uUdx0ZyG6Z;1yruzLG(XuzbAAwueDhIw}^2;~WHez1@67 z2s-L7o!xu)F^O-@Fhl+nldMP#{IM^IN$f7Kl+XuXc=4`(mlls55u6`?6>V)tPF*|L zzxAmdaZu*FAqIW*oX)vW_DASvay|PzXJ$oMZvAq2(P>2_bK7jJ4eJQsbyFzh2S@6Ui7E==c)u7u(GOgdI{EK7^nSAuZNubM=0`8YtvNRJo3_X%H?2#|@9tsy{>?0=pU`gKp-kd`|e~M?R z8~*Obk4H4hfO~cq`5!%>hI}W-O@65Y@PwZdN2*=_>=vc^H1hO^?NLs1^t-lX9dfpVzOVoHLjO7Be}7tq zQzaksuXs;f<>xEl8?##m&D}#^Ip{%To&|WZ&whv2M>-4=ELXMan+1cMioY}|aF#({ zvdzZmTxO61llL}eW-*9M1q;pWG4N7=?7oaXoD;_P_0`B*Y+aP^VZk|Qeo^H69yz3! zdB$q9R3_OHQ=`Uml}XCk!b&u&n8ZHv@pjKyoQIu}W;b@&k>)Kz^NN9XB;ifulK7+@ zxt_?%Ff83!-X+v+o z(5bNTCEf!{kIYWV%g}}HNFE%j$6nj}^txB9n^NTC4xi@{>O+2ryVJ6p1w40~owKSO_7g_QrrAUP4;y9~4|c zuD*CXTaI(WVpx0THTFC2j5wyefV_Wc$NJ5f|GxqcZcJhR`OeACoL0a&2s02W*z^DI zMM|fa>ft?j7Zw(14n1^O`=W#cdb;Kh?JR$SI0`)UWjx~WSDdHylR~xNyZm2N z7q;*~-K^etF$#Q_{xJ51kA^moGp;JZh8n>f<9W8TFY}?;3D)*-GqsdP~exA?H>Q)XynP@8IQ0`=tGlZN}GUtj0WeHw^pN9e>Tx5 z47rEyw`td`Un2*UH(`Hdj7DaLMK7EL?`@)8P6%8E+^!q{po5oAgfzl`YKqZGU@ZHs z*ISVbda_m{eJ`D4rcZgtLI2tIqSv+>{8#+?A0<)X|9x+7U8}r^9@*TN@MO%t-cn#- z4dy?HH_%xL^Y7fh|HaQrIyrCd{aUCUIEpRIE$tof6VFQLtJBb1y9TmmfP*@=BuKwn z%OI6+*SQ^#W03T>iF~}{Ihwbkd8HBnwc3waPI?>ID^7A+cX`eXHxZ5yE!h`zC ztY9Wd8JarNQ_Lhh8N%7>15EN*PSZFYx~fI}HWc{m$fL)ekJ^BfDgt=C`FQQgE7g!_^4Z0w7W5biz?|E!#HVZRJ~v%lY> zpPt2gFy@{rxU3Q1eW@+wT|f``K*fFo1@r+nFr!cGVZs;YzqBPY9(jp^t4)vVkb|(g zvhKsAEtxP`UZV#eY)HV%cdI6F&Kt=q<>>Y1Ny$2Lq1TwRvRnNK^v`uRk+t#Af9%#2 zY*_;Ty%%cs)`08({i>PxTHqg}KR=TOasMlqwNdV3{*%PhZ|&2Et~33|Cjz{8s{M{j z<|*Vj1-q{XT);k)&}CkV!2JUCs{`*|!(KPfM=7hasU+~oOJ5!6{B6fxrCHQc$q~Q2 zy~e;j*1~E|JKiEUr)jqCCveYP_n*bQAHYq5^G^@20IuK8!P>_Mokse-xHb5$DCOdR zueRcQGgH~R>@1PS&!_3I{`{+cA?x7QQ z6gbE1(+W##I!RM9jKHUX*z|!cmM3j$3JvpBJ|09jF&-fjOfbNDq7gzYN>C*ru&9|0VZKAL1Q2^T=kmRv6}AZsV2IbOuSG9iAS$&mf1Hr8OGQ z7{nMKscQVlAZ5zh_N&+rp!rT<&DB9KXvB3z#s z=Q7Fu-`QMwFW@^@zIeNn#g3#>BVwMYf-giLGBUYfhdsdCb~AvJRv9;2|J`X%$`XqM z&SS5|a>Z9|K1?g}*KqA7>T>joH&p~y!&f#9i>S^X!1p3cH_Tn$X+!2Hs}6_y*^s5x z+e-xT9?<67az@dQc`)r^B%o$X{PHes^~avK!rv9{wa7&n(roihkq27lS+^r&2|CiV zfg@k=4vf6481p}l{z{|gT(}o<|49XJc4tyZ?dF67cbh0gVc@B^z-RDf&g89iY{*+) zbP!kx{@b72B|a(-|M&Yyl|ArJ=BU~1GvAp_lW5K_nMS1**)F$1bRLf{~B-TJ$F5<+|mcBeg8makW7q2jZypuPodE9fPhjUynMMxOI6lXE3HqYnpHe}rWWtWMGn(;=%uHQcBZS&Kri}n zHMN_ANgR*m1$Rm@NzJ@ug$;ZJ)0jT>Cgf7PIb_U z4m+;y?odZ=NZRt3DtN(XtCWL1@W=FXPv1CK;PT-!);X)Z_fP2EVEPO?Pd-lrQQ+&M|_c(t6f37I>%;4z6%UkGVMCz7i zh#H-o;l7Za4Bo5zF)E9y(~7ko(TUxg#GS3cKTj8xUPR;mpFR3ccv&hwYNrkvod#+f^d`ACrji7=3EH$s{Lr7(2w8n8dioE~IdhNoFI5 z6AuX5L5HI4-gwXszTAqy6@GT;2_F|(dTd8l=3Q~Pvf7^Hd9Uz#=50@?FRKLm2GL_v z(=M5Mg+0Ej3M@8xAYX0%)b;!qYcg{zD^%e)_`&ZGg}PiD^0;Fp$P|5HolSjnE~?mj zlCcn5>4E%QsNXUh=tBq7Hb(Cl#dnY%J#Onk4<=G*&HmPd$U|@B-F(Ia{dTowj%)A^ zBn|HJ{Qq8`w;C7j9sv&8I`RB#7I;8C{mse{_+OuI?>y0`guJKO!|6LZ&_R1<*Q`H* zbFodsN6;QQ{65R#it|)*^^J=N8|L5j-63N(%)d~9oKzj=-#{&;T>Sy|;g+OiUj*+J z{qH+>&@1?A!#A@mN2nxB?N$vNaR1xXDZ48yxR<9R%qCW&uf9BHo!mwmAxg!c4kF(W z_l#reh&ps2sm*KE4*|b)k}Z6|J?c*<277^fCRUtkh;V~0BpqhF%m4rQMe1AERrFcX z&n!Azr;!U6zTW!*pKC?IdCULq!_V4TD9!Z*{a=^n{qfJ?2Ylcd78{_EQxUtimwtxN zE4$L--~#wDGd1oba8F0bO2Ihbo=U$~*&`D0s~jWOt=mo~)s91&GaAq@+hx}d>Ek`v z)*}4T9J**o*bEzZ@6sL>LtRh!1(%C?ZwAxJTUn!>;&F7cS+{SXF_TV?%}<<)gZ?S6 zAxVjV{?oofF#G}duMT7D%(?;OBOKGG3W0xKI5ut%#QiTe#Mz#R`S;CxsQq0O_e)Lpf1wA(gdN{oOJk4?gftL;e4 zi(S{&sM`^rD-EYsJK`O#PPJ?8tK4YDHn-B+jIwrqUbs#7@*mQc%!} z{0^NC-p*r99>3q=$5CueICM@nzmvs2m5b-=e(#@#Dw2EAR&*HvFArSU3_k z8D)dWbB<)Mok5ySo+EKpE7z7qAE4Z}qKmL$pWD}yKdgnYw>&Meegr&#BQ0^NcL#JF ziJF(Yp#LvbxNf(Jg1Q$mW>53RzMd1dk@;c3_Z+rf)Ohe{esP`Wz(4aN>cK6z|9=aA zT#<x?%=&2f{e1mrojU)@8x!5MgFGB$9^n0%{wNlSVtn7*ZKk*exGIVM%De;Tp-iP>XaM*so@4RU zS7)N+AX&b0-kJ2%x60;nLAMVccDDfT88~&QW&wKt%y`JLr`s_974|73P!IT|QSPO= z8HK#JAC%Rwrx2^4EBdOy{R&+LsRjWQ!nMbs=j3_do^i+Aig*e+Qlm95n+~0S@IiIK zWB9_lT$|}t$Uy`>y0#Pg=f^ss(7n)qma2@`1%dxAU)Ab0IuCyQKAVzef)^O>x|bkwh(@ygeGdQhpplRnEYOdlk&S~Izd4c5cJ*ttDnma|kKImkn<-TUZo#m z5ShzwQZBz>5H`Q$&quJ|C_&M4OTZpG(tV(6a2ESlHXm8|Zs=rB%FJ5)>%o_8zaKxs zEeiZU;dED>i9P3ZH@UYD@E+2HMBHuYq{A;3=AXzw_ZR&VJbeVZkJ7FAKfptOV$J#X zW51`}`yJ1WkcW`eW4@3?A9#7>aIw~U__@>i+0km)W92?7s|+4coHA&ohTP9S7nkHm z9>^~Q1WVt8{u%O(XZIH9KVs~e?fb!hcbeX!^A%$5B`P2|5cr4vdsz7m-2dv2CKgVh z{#mcq`z@cr`O5TbqOd{N`6(%XVI}5Q{~36uA&6zDw` zNBQn96QhuaAx09pz&*Av<@_Chd)zz=KCJ=n@yL6Z_SO=7c$?VV183alN~?9FkK??I zQeK}4!g;BWm5aQHoajB%ru*Q%%?C=IKi;E|sC3nIji(gCYGmo1^O8dL`Z~AmZHJ!v z(D=*JkJ#&8Bqlxa4fj4pn{~+&_+DEM*z5-X-S%ORR=GIx(rSB_9tZyUCL-nGfcmEo zSX{e``hQ&e_AeLe|IYjKrR~S5WZBVWp5M>lo}YGebAujq&6%UpC>{A~{%}V8Q{W@7 zd#={?I9L09cv6ug+MU0g)B78h{Pziam6yUFUcAS?9DTsXzVpGT5{(pcO#HsPmqz{; z_Rg4r7bvzWx%2qJPjE0bTDXc_g=vg|#X}n5HfTSw6a3)5gIEIB2#qwX{dk<4lTJDn zIw^&Ubn=Nk>P0H_qcBNx2Qae1~;0TjP)e z*{QTj80hYD@UPrp25AO!&V3Z?{}Mz34qqnlp#&<{Qq90e)h~SH1@3RC8upI|?*C3R zah*Gbd%Q`3LoX73@K9~QvFpg|i0ml}f!-7P`FCOv^q#uCJ6^j~;rF&anbQaEX&l~p zT>!Y}@}2XmI)Hl$G|XC}fqN_!!`A361O8B5zvY`Cg;XjcU$CA+ejgMlGFGAx9kJrr zIpCh4JwZabz&(s-pZ$&k_l!7BPHtg9$2ajVUhoF)_xU8fIgI$(nO=T&4u>f=K21yVw-_-+?a$+5Y$meK!#PwU>(8R-I_nDgr`8H2B& zuW_1xfl5|SR(|{eK2W!&KPF%!jrdlq+wf4EMsi9uUff2W!a%_!+Z}i)N{!{GB6On0 z9;N8{L>h@+CFHfVfJOpYtHV5+X{0&Qb=C{~z|QAkvlaTmbU@NluT6APer>m=ZnsC4-IV>9YzYrLp@OE|2+!P34-p)Y*cFn?sslID!J<>=7A-* zU5~#Hekrt(bdn4dy)yL*Z#UUSRkR{EN20vGGRV;fRe6Xnix&Uy$V_t-y zN+X55;9s}tD0H8lD=RF@M&PgU?AyO-7XCpG&q6W$uj`k$xx1}`zBAR>xJw%IVjO0{ z`YKeSW7;b0sR#b5wc-N5_g?y%o{A^X0&%u$s3=T#un(J7gqF+Y5vCNKZ}Ld@!&pR>39FE z1dZGcxqZ|Rd_eCO=LEMQbRUP;9cJ(gSbewHSb5XPPA~RXYQRGoZ!@hppc9R-$o!co zp%K-mr#m^`&`1`i#n=V-X)1dJuBF3Yj#sQ>zk_}tUo&>5b3dIJ&=Xb`dD6*pRhg;x ziO`dVjmM;4(#h&Dqn*VwbTVJ^v%_DJLDqRq1bBEbh#Pg=57p-kQu=g#&6+JtVtM#} zofYPq^i2@jmMB{E9sAri*W1%MYLT<;sZyN$8&v-t7y(KjZgB-?5Ij@fT9BJjQ-vj-|_POR&OA6k%KR`R=Od(Dh_x@W8+!JQ;D(>TH3i)tdjUzV- zd*sXwtDCifyUw+2||6ArZX{ny2k~sbR_bXzM3l%?~y#e+AoBw&$nSAI#AFV57Uf>)E z?I;s!r;>2DaCfIq$eH%5ZC&=0N}6=`Z4uzWT>cfQlTpAy@nhH4pWX~Ud@(TYJM_`| zAmQ}cgYXFk)JKzDX(YY$obXgIjX27toaBm!ua+(A^!EXcOlxq6eypYuPCuX0w|z9S zb**q9_bd&*JZI3ImB?3cH0_K**Hpbdc`(Izsj?UEKmhh5otNXz>%9~EJ*ACzHv#{oY;I}n$Ng_!X&0D-`X9XbhI>~C z_-x-uY3gOn|4zNOtxo|Dcz@Nd<{^CG@|Arz;PZwrX670|?>w%(!o3~1zeLg6i+l!e zNbH)3`GLIi)2;6tkZ-mvZrb=ofI|9$9-LW_ppcWVE29@SgNLe&c7D^QkhUMutzAa& zrM#xzJweXFqRaANG#xm7xGl&DxF`3LMlv#VM3|m3&I;UP?DsdlGZ{FEuXssrHu`|P zgy!WU;H&zfOTIPW!wDsNM?2tuY4&Hj0rxi_=n)D6?iV$(SiHSJA!EWT-u6KEnduhS zQV^w*rCXgE;^e8sMsbtHzZ_6YiC1y;Uie#1yH{L3L?xT|*M9tQqbl}(mm2maA6JN;)I^{=W_C?kOSKYSy*A)t*)%+B7ALKcot8ux@N z&fvVAf9e^^P9x`Y*-wFEYhpiW` z`TAl`x$Vm(MdT>B6W&cg= z7VwcFXKFx*7K1$cBzQT_i-G-hQNw0Z&NUyLX$UF80E$&54l1 zN%_Cg2e#_>M?GxBp11AE^asE}$5M^!IKhK=b(XnxFLNe0uJc!K5P|*@@`kpcfcsuL z(B2*T&&%W|Cr*R^avl4+UlsVjdD(v@$-qAsRy==FhWmdebMD$r)W4wIq@YeJ^nX?R zz|2ROn;G4l+Fu6T^E31N2zam4_xsoD-$L(SyV*4iKJPOzyTx_D{giS4(u8He`^R24 z&8(u3?(uipTGAA9U?OkGbt~@cEA3GcJFy2*Fthm@d|q9ewN8vJg$xy5G!8?~!KC$p zg9maxZM{6L2g1RZYr4mjV=3f{Tj$h@JIFZ%2yPtD!Tj*qfXaq4?Ahh8`km7NKW*JR zzMI{c6X<-Te|Z?+7jf!~p22>t_0pS?SW&0hC!>q_sU%AD_wf<%-p+?X2R8rHea>#F ziPXki*lX^z%A5>QN9 z>I^M1-j;wDC;tpSs`7$Hgb&IYdURucljF*480I$jmd3olx|~i@0(^JpOVUaB{I>*d zZG3Dh)M>H;52$6~*>V#3qsQwzy<_R*>oUfT*+M!w+e)Ww?!nhtOiJ^XFi6A3_4+oz zN4(vR0}l2KlE)tsoEi@u>H3ee3f&A+|ElZ1ECnX1F+R5D>+>gC6OiDbh+sC_`!?V_ygq+8OC7ve{rtLXM&P%8JDT~S z|Hy<*X)1yLo{+vO^z$_KJghTRbqD^@SNDof!u>D1%Ow6h>fbH!{oM9)@Z2~y-rPpu zoy48@XL_Nhs!8bcjHAD7^j|MC;SvIU5HixeNM(7VOd|pHCJ#Mn@(EH;Qr?&=DNGRWZ?yZs7evUXy|OM;+HQECtvf(bmTtdybsXr;d~D&G2={WIt8(Auq?mGnF$&A!~Dz`Z9iD z9wyjsIAa;^i zna)bBZbz|a>zHmScK|*HzRG!p9K;v(;M;z?0fky zKdPVk4)~{EJANP?_y4Whtho%-KSjm8VhDbK7O$eC>na-F11mkZeFKfWSh2*?ayyN% z-8mdnV?ZO8%8`$*+t7&8W!`~iH+-F1ZRP_Ul(qMeQhW^Nlk>D@H8a4ASuP}7~s&4jcLf+yTBUoJjJBZ6ZoECvE}LXGSCOqZtZ32HwHOyU<9^?M=w5UX{N5nypECGkTULDRihwTUHv33gybe0hq0W~N`oSYOmr5N# zA8;J_FeK0EOkO*k-@P9==*sB2@n-Mv z=r^oS*9}HF6Nz=aUy72P$&!*?Il90<>qSnw2IBtz8NLwWgZkeX*sPMH;Lf>KFZUyD2saZmY&H+zPZfy>iq6K6hdCcOOyfk zzne3puchGrr|=X~PT-!`_G!Hyj2!cYLQ2^s;CAKfb8R=_2M28t?7t5jl&7@j1N2V) z7$L`A=$&f2#B|%*kehH{n5+2!{piP|u2SgzIw_MY3;se^4SGA4!-e~O*85hzFz#hP z8J}|Ce%d+9XC11z=dW;-{@z6;k@qtPwj7`mKJoe_U+6wJf{c%~yHkluQOLN#Y52Ym zA2)PHQOS?ok*;&_zb>6+V>Lq#;;z|#d);U71C&GM4%T4rP{+x(*f+rYhYv1c8G;{R z)ERec27STWu*e(te-um8z**G)r^hn`%`!BSsQdeiqZ*Cuj{Ejl3wr2gb|*XfVd$K9 z3-X7d2cK6J(=g;VGkKrd|uV>Aup%Jg9n6mM=G%~Dn z_iQ`*fZ{@#x;s0aG%_oWG>XDEUdXz#d>ec;=hZaLeRQ(hlEe5cjZT(5|1`1`^Ey9G zFN}Og&O)e~dE!hFc*8-lXFqWczBs?Uxq4KMCxeJ_ z`O(+hWe~1!=|T9p{yHSN6ZEw1N8mej0U=Yw;= z?Km{!7y{k2GLFwI3HpEC)3XUrz=xxDuJda~uBg-Xm-H}la3Al=)ci&MC^k?o1bu*R z(NKR>7I;1BsO4>K;Qr*Q@NM7$vc)p{)F|M|RZe<^@V_KW#bwH&|H~gVmb6U-&e^2B zCNT@=MDJzu=@R7F{%+YQ0Q_^B>Y!wY``<^t&YXt&&vS{iQ$qa{)tK}bsQ_OpZI&iWC`yo8soi5fP|8t>s-wo)UkKed@-u?tW z5Pn7a?i76GO?M$jhksYFY5Vw-oAVAd$%pA8q86EPMH;KT@Kven5O=%1Gt~J zSL4_0LEP^l-nDX6%mX)SRk?a156UfVT^<78cZ5q|<7Fy|mavJ)OomRBAK>=?JgCLJ ztG|n(BL(t(eqBc;C4J7}P0&BBQu-f$9Y%gyW3E{n{CE38e(V$A|BH6{ADn=HmIQbV z=;8k7%{sWgsFO7VbxjJBvK2UVX zFrGt}PTul8-yN`nPL^Cdo>6mLXSxjc1Y{mwP;$m%0$Mo9{YT5xmo?%0bi6!@gc8Gghz9 z@D&7(I0!NvN!?_~oi)waJ6-bpQ??*-q33_5^K0WB3o;sb*#WtVks=8;oCDKKe6gG< z!2M3)Rx6947is6UdA8&GG+SZU3Dkev53fy2k;e(&B=T`B{9cWN1v%&gCVmtty!lK# z$KKV>*dXU{%hvCPJMMSGgiR06AP?sqbX7anne6jm^EjA+{QlINKP=C1UQ+6$P3xeq zUJ!n!*8`s`Eat{1;Q!Z+?VoncIg{tdT-gtz{=?2swJD9GBihBO~M-ro-8Me<0_;)%P?g{2F{?t>d15Zv#(p zc545d^Xk?P%gipP5Um(*htIE|kLoP@wfZgkhT799jS&io5V&<@Lb*e^=HXo?rmi z57dc@`T)n&K7M#O6#FC+YmTSKP>I*nl^(X+z)LeI(d?q~>;UJ@5}p zT(JWm?*9e}s|)I=|2bLy52+0B1Ldi^#(vQI4I(4R1^C4KuU1CffFBkTDj@?s$ffFfpGzUov?22mbvV(vg1f%N9mL4f@6CcxR&S*RTrk(5_!e zX@+znyw#{)#*t3g9Fz8j`O-=8*j#PzWqiJVXu|kDorJFAi=BNzNB(4GI^TObIXx|q z`06j6IG#4+^1?Z2l$`l(r;FT$SZ);ym4Q7_Bzr!JfgJa*QiW#>ypwal`sE0NT#b(@ zc(|TP6dQJaUZ63FxKhb8&mtz7&tOfyBuT{~yq6%N2zds~(Q3JUkiTaB7rqDrY+!NoZxc3KK zQjPuL=T;|_ExF`O;;-C0Aae`3=pT24Ugjeodg9r~iE5mauckk;-eAu&$=k&a{pVs< zVES_K-#=Qv*^4=lNA5avUK04HVBkU0Zq)z%zljo?Q2+bKcO36Q{U^SQ@;zvc`IN=k z%G*rnn`1xDyzs@l7=Lf4mxm*#d~fNS_&5rgpH>Vty$fGpndXiop}leq&y8-mZRlIdIRaXH1?o@UPT079LzVx{H-POneF-v#9 z9m1ZWu%L;fot!ih>{oVTOc=QS@yyl@a>&8unrw(tr;!rP1HaY*|67U0B@Cecoo{w* z?L+-595CA_fcife?oknb9ynh|vPm})b^k_o%dRXM5#RGhETM!()Y39N^%`l!lq)cI zUq6k={Z^1Khd&@z9xrx_jZO|62>tM94V_5)ZQy>dfcj@mcy?$f>U#C*1`qTB|C5qt z+DFkBs$Y*cpP`e0u?AlP-(bgC?Pu9}$e{-Bq;75ik6wuN{_+W*3tX5IWnmC46Y3c} z%tB_b2aP?%ISAO6e>~rbK?c4?lzWB)7byf^y!ePg_OAMUs;39~>S?)#>)cFI@jYrj zYd4elMCMs-zQ80AlZP+$^)gBKoNbPQi3@pImKmm=Yfo}sG)Y=M#+?2a#fg9WSOS(L zn>zL&e|j*+PH;VPZ@UA%mziR|Ah^uyi4XG6o4p24LNC4X?dP@)I0tc2`x7bM&{2Kn z-2d$X3Loozv6&Bh9|T)ATF4>)&!=p(lVINENp+t1Va&mQmoZq0KCqN`yY%*R@O^FX zwBJc^CI%N2EnKrPHx{p2k^&yw*7mA>e=FwSKU;@He1zVrKFw)~+=J;-vlHd)z~f^s zam{Psa|tcFTn7Gcy&<}KDe%w6?G%B3^IhpNZbSj~|2sv2Z5Z|6s;Q)|J4;&xx=*e3=;o^*@OwX6Y3sg%KSWNQc|MPG^kub92>h=(c5e57dr2Kd zy116oX zjqTWV@ZXWw{ciW6`>dsIRsj$GoAaDSzX9`RUtT4r_tJ=H-jW{sNg6p@RHWy-2)!ty zYs*jIAca?7hlXWNvyoxwcU$M5+Wa#w|Lxz>?`@E*ggzhi90TJ6gi}}qv_?Wm`B?ssdOQN6L~mY zZ*Eat_zFdBdFpO>4=JZhiaYjSf3VaTM}9PaG+(Q@3-e@GMt=zW1fMwVp~eI+=(*!y z!@C)Kt=ij^jrKZ|q(2{$_dyp`OOiL)>4SHIgR2bpUWESn)A{A;+sHpFY@*E-;+@ov zLDhEPpsiXPDZ=2v(!)z%bbo;!^in`?Jqz&tUvBmJmC$F>c(Q$E;KRP9hb5?C?&Z^- z=d`^PA{jxwIAR4qY>`QmL;e2=bKa(a`qz-tahOK^_j4_Kdm#aHybXz(Uo$WlS-ieP z;R*6VNu&FBzJ$IXo0Xy5j=9Jm4>VYz_Z!Jf?0W{i-^ShXm&GE5_=iR+cdtMW=TyLd zM(dE@IceaQ4cwo2O1Av32J#KRr1bO+aL@OicRO_M&q8)H&h}>+u}1g z2p-+~#l~`qN|xA9vve-OJ%4NMoI4+IiVw?>m^h8_3`7NwD1!HXD!kRIjd`#o^}BkY zf4XV^KF@xHM#{{CO0407)owPh>ID9G`Qyra4*17K_h5%3?teCpr60Ue|NQ#2;ul3Y zH+y;X57g7hh1h#FGT_0SZ*AH1$H5Ecuj@Vr4|o^)`fvbpq)+JG?{7)cNupnZ>K5=} z+O2(Qn~|?BWxap#z73r;UyQk#4L+dA{__txhn)3~uB=nn;V+wis&#n;KY8UTVTqUU zlZ~CP7537JdftH4?io6X+9CF6as`7-&8Iqc$uY>W*4A((@MJdqk9hxJCw?o2VrhxR-tWeFz!f5exn!*Bbx{)t9P6q8W4AE%vb zW)k&?%+@R^7jom-TvlPM3%MpgaLY#=dtG`ii$zE~lA^oZ{JM>JkH&b*?|(Y#mUVp6 z8*H73;XMmAw+qNuXl4ARKrf1&4N0bUI6;5O*D(8mb0D6jS}lk<#!=7ut>6WF9>`{W zGlu`gGBKb>!(Q_gMuZJ?QLVV?W6t0MVn>%h4+J0H{B~XA%L?#@nr9{l+tD{NuR7}j z2Q`g*?u`Qv7+*OQIKdGz_J}bfM<#-T#JULEr>d=9g zwyz&)0{#z)ymL(y^}p=Msh|;#7a4m(CLQ&EqD3J@=sybC7xALSu><|( z&`O@OgTVU=8%Kh{d-ESt`|Vh$uIJ-KZhsbSRbVeSLnY7`Q+2#FIBOx2WWk zLQAz$4)$p6|NZ+|8I|;K-K@%Kfd9LFl0Mr_B@aq&Y&ZIhzrW8sD)R^ao=9Mo0CXS! zsAWdcD`{jgcwdU>dK%I2k=b9VL?c4?)aOs>(uh>#S+@iG;pYY^dhfA=A3%S}e+2sH z`DI;Rv#zvFF_3SHFy!txR3%^n&_ z*)lSrHU`{uyY1$hKR7q*eyi@{p_5s!gY1>y0pf4WzQw{P-pjiAQk@>=&t$uF=)gfM z4{tx@&7>1b1%2oIDddaPlOFM2p_3j_>CVEtsP_lA%NL*z-QD;pcD@P0hOa-? z2l+UP&;-B(x|eXsPi?{+OkK9z5nbpzPky!>g#K^S`b>So8S`4IT}R}h|J3h4uxnKq z&WpxI`9k1-*0eu2_;CMk%Pv2!i29#O)1~mE{zJ!-WS^t{Gq~Bj$tU>2aR(yfr!n8M z?mM-b758ucj*=z;;FjJeod0re&GoV=;Y#pjJJ@42k@E~RW*_V{fzF>SLv@1Q55={y z+ZFXaHBi3GAA1o;6JFeopb}Q$7KEi}yf8#>c<+nr9!foGJQCF-I3*k*c-?1b)#$80%k zRcJ(V{L~U>J=ACYWe0w9)Oo&1Lze^QgnR4QO5ABgz`%N>_%w~2WY+q=y+|WEz4Ptj zNyx)-OPfb!!x2EsDJYh`&>Nd@IJ__T)zl6 z_-ky{gXQb!*bja+k!+@urR{>#4Z3uqb1W|+$J3jmvDe7RZs^~;WWxVhoux=Pk+nr#UTd9zmy~zq zjXZ^LcCfI>IOdkC27-@(AAD=Mxcn^oftZoE{wC<8q9#py8r?7#b9sVV0)6zvWp{ZE z;GxK0>D;G^FemVLnR0du^nbxqEaOAKO=YDlHqb*$o(>4}@Pm(DIdVx@2Ke1Xq3DV_ zbekT@qinc$m+u~WwG#L8Bf*2q;CJ0n zPgpCq6}iuAPQ`)*K3Mz4;7L>D*rL}&J+eoxr|MLf)iLaczFwm{aSHRjb`pUnBJuN{ zr?w1V$Gl9Z(~wyv>iG7C zLow4CIR4n|7H9asoW?&)R535PB3jW<>N5PXb)rkQq|nF)#YUea@PV5ShO}mv;+!C6 zF7*ohIr>!IOW>c!%(|2DsQ+k-k6DSR|A8`rm^S1^KX#~;8Nd(V8jKR2M{d+>kMW;b z9Xhe<;8)f~Ug)~{2hL9DLBR*v{A!Sws1dm)EEI{7$LgwHfsiKbtyt@~n?nctw7xQr|ABsV^Q2e$fya1vMpsl_@B{V< zNm-ctabVsz^T>3!qBHp*BHFSJI?-~IB(9Ig@SaP~-3`f+$PvA&s=1Sn_fnGD%u>uXMlQ-_pbrRKmj3Cw1$pI*4q@kaLH}2%*vSVT zfW^gX{I00)uLYsk;s3f%DL=@I2HrnV(M7)n|Mywds^@v=51YRP)K*c*^F=?i&^Ejy zqx@yl9Poe68O{|dsQ+c`Re=r~wW8NZ5BOfC zce%Sc=GqrGP8@fn60Nig-G@AIua^&hTOS0x|3gBh3-gZi8f*RhZ&LA&vUw0k7V>b@ zKSmbKg?>8%LX*kla=#x1$3XDjM~~H8jU!GW-n?Y2O4%a zKyv&n@}Q-^EAp>mp8nuq_*M8{Bl13)QPBTynH?;>1O0R5OdaoA=s$ZKUF^5_fmf{1 z|62_FZ()?-=>q)Y-VhhK2lxLLLouO4sDFFs`>Ipkg9o$eYG3?p zPbUH@)OoGrbdo$@y6*$@pbnl>uKmaj)jO@7*U6xh+M~x$F9i--(ywW%`-)C}`#+wV zL5@gCxJy-anocC&e`IiSFvv}NxksU5$Pp#ovn|}lz&lsG_p z=z$DkBi1cuhkQlO=hNm1c?{Czpgp^*i9wj+vA2`P;V+l)>yJP;TJ3S}dKmb!W~-q3 zh$Zx+%O{Q&oJQSC9(H`0#UvjO;??m!oD)u|?~FArM7ngt_zGJW;v=GePCCzpd=;x| zI4b2zI0lVZ?wZH`Q(x~;5jNy0WLM?nK~E*i2L}70A0^i&Z=fS*J#}pHj@i5uxuVHP z>Dqw$Hq4~jfFI~)SO=D%A3T32dFN&n{NPyjD))QXr|5E}E$RjK1oiXvtAZC#&Q6rv zhAw2Hvi;pJZt&e*{a+oWP|t^BvZl}ng0k|&>rF7XvTsAltP^xCqOMR-chZ?M(@HS0Ix`{?QP$TJwa#be|2?G zp9!z-&t8fh;*vE4fs=c3HKUnvbb zXZ998)_mwXKmPNXsH71eDVOf=&6uC8e7|-z^v??Ayj?bv(1A`=2Uh(BZ^*qNb^!SQ zuF=YT?sf2m(?);Jp#JR_c)s$Z{wK@EKTuKsf@MEwQ+9MRSbgSr6?pJipRIi-=4wou znXKwpksqDCT{4Qf0^MipgMSo&Kg8Aka;`y+&fGFn9r+={0^ymE2|DIJ(_Qy0f$sT4 z?rrQU2C-|Ay5o;NaA1l$$+{E#fMryCH|Ep6UH92x4m>m@W_DFKj6qVYzETuY7^L-1 z<8oE_2S>h~Ryo(kAc+SVE&5*>L|DxluxnLY(SEtT6^^WQ$9)el?eG?Al7 zQ(E(?mxV!?NRMz^Ve2VdR6 zy`!fH{JG$4A^$7Pc_lRX4kGs>rJi%^2=q_0bs>j>q5nAjy*haa{CBCZ5!VRtzv!2B zg<8NrKeq;YSfc)=1bvLuQU7(!qHklU|G7MeBCiwBMNPloYYV}7xIPuidj%!|b{Bum5h_`-sYjy?esAS`L9+w= z-V-tZl?({dh(q>w4|^%({bP3>=un298P-~1xD&d)XcTYxe&l$vhhzWkUH^0`>Q2s4 z8VO|MvXN;|$O~>brD&%1S`augX)O*t>G$#LDg!$T!%=DVl))a(I8M{j5kQ-{+@~=b-*y z+47IvMg7x+S8i)W{ePVFOWK6`FVCMXs|li$m|bpH(%_3}pFQUN@)jNVc$TQ-)5*5D zv({7a#|HNHeUw$E8$x6H5&YQA8+AT@Z(jLAI)!``fC1TtrGN7<}WLKoP(GIfeZm}^o3?Kjt7ZMvP!G?PF@v!=M5qa zEMIY648txBtal-*t0U@n*tw8+7QX*>-*F*Dx6==|{&XQqt)9+>uCAnao3(q(G3+@V z-^A4k- z_>+l`(>pc^)L{R=u*BLmgP6nI=kvyS0lA^qVFT*Im=91@^lMUv-&>Sqy&t|nwU@_< zw+^`H3nsE+&wf+Ylz&(}uG_VVNLEL2b zi&5}}Oo8Wj{~-64{CU4T^iSs!rl>9SALlCfFarK-U!cGB!%iyMfA)zI0si59!Oy`! z{aZM^ZMH)F-`>)_?Vs)$qC0;10qQ?`R%~487UpBR)cBopFdrbmdGUNXe6^Uy!k9+j z{3GGTXM2%2zc-Ao_u`?@ZP}ChU0C^X{1|zw9$7Bjl|8#ed9&m;qn=VUCK5Z z`JfaYF0%`|P}|w|Oz_^@c6J#X9g*iL_-L8wj((v)SCu=B{4F=SWsK=eVP-`oQA zKlSGPrwG(Pw`D=`R5W}uzIu*||Z? zWj@@rX8lj_oDz+6(=(bh`3@hZmC&hJDB(j;C{$GRd%lq?zI;CVBQP#Vtj^ zg%q}|?z_Dk{&N;<-G&esGIvYzlHE%e>{;>Yl3MFZ_;sy^4@SEZ_W=H!Tj|*M9?2W2 z0i0C!wI{Y1^9a|DEp}f2hJ9Q&t~)&12%hXG)bnqz#9>Xx_NBqtH@bYO`*0d^(U+QX zQ(wX_4hvkjOjcy|nKd~=pg=zOm z4&WVCaaQ_T>}&Y+Wc1f2_|m2O7@ zaR1YbXIcGF|7+Q5MR%kA>k@;P459u-HSSf~SAZ|f@0EGnggJo#-HIXTKH;h zb8I~8#=(0Tf!hNDzY4)&L zk7%Dp)zAkb#wk7)HPA;7e|Y}#EzZTQ_vcfAgSNd0U-uO}z(-BHt9lic1XOJDkds9Y zf<0GDRuewe%kL-Zjp270aPJqggI;9PtuE}2I{s@v)CT_hmW|tE|7GAG<9F2PROp*G z)jwTF{l^|&cFz;_pYSn{TcR2B1S#4w>F=oI`HQiNrIVPG9L@CD{TFir?AF&9+%$4k zgJSEk7Wc4@OS^+Se6Jmz16msJxkN6SvKwIkgX%*4^F!DR^j2o_IC!si#Sh)p-q;%? zV5VLG-fJepyUPT;*P(m9>SHQ$(=M5U0gr%l`q{4vl%Zez)w+_?fV$6=ceCh0?s-V^ z+~Q~W0BfT(i+(~!I+?X3gq=?Ei~KCDR$;%~uGDfOO(*Mar@kY|0X{4 zrf75E{F8rIy@&pjRyVZO0{pk|^vh?X!Qjmm^~UMgLF+)zRzLKfP+3-ej2&btJ{^A28A<7<>%IC%WuLz-pFR7fIe`OqEBXC zV(-zQ%)Br1rkN9)nrq;nt(lh4`hz)UcY~%*B^f61YCUTjuKVvCG?q(2FRI+U_Nuxc z?*GcwLJQ~zOJ6nWR6Yeixc&5NR}YiCjcl~70#A6vDgQ}K-i4@_)uuLExezb8G+~h_ z7t+)zvGgnY!fjtMR&N8$JJXR+#`t>@j$+Mp*p* zdd#JfXg!yc3dl>;?kO7qK5BU!{3YdzGdYwhQ`iOFlrLQ9$uIZ@V&YHI#}>h(k50&# z!!KK!Ev$7*2e~*cR(ECOBw{8{&KY>YH%M@MD0&fkQW2xLGY#K=SaUSF82ceyH_kOZjdvd}o{zbs{}|1b~yET8pBcSZlMi7bvZhP6GJKF*=)P1d3EsQK=}YkIYskgDE_!|H4t~$) z*=C76%nf8D&OWaI5Ad#xrZmC#EnF~O)(5?)eNSZ07>ztUY>;mM8#rr3^6zR6I?+hv z`PGB`PnV4}=fe%iy-jO8x~vNQM&_+&m_GP#l<({n3+S8$&u0ppf!}|aX-%I%UcxNq zsreZ?k=0vss^toud{}N-<^}vO$^7tP2k;NG+&V}V_y6Ie6OKnv|NRrq2?g)zWW$Se z|J~ovXRM@h1Xvg(tYpm&N$8=;!}9Sy(hQ>iEi+XJJixK7@)eH(gQ%3ZE80O9ZKKdG ztN;#jQH}SL4?&)kZU2ShYYf7FpT?-mWRN$eWh*G9(1|ARFONfxf^mQTsXO*rygR?{ z*^+tq438xaIA!u5jnniSKC5Y z)BOV8!`S`#SLY2X33fKrp3bI{bprg)>q@CaIdo^XJ@EfNS>O0)eaIDwf4%y;Y$PHqpr8Gcmi^v@yphNzvY64Bz*PUb>wP@Db04 zi!>L!yVoJme;9cmC&vI6%?RlFE-(7IC7k%Oq~Zkn@>p_6B8ZCPI2 zhAwIxM={C6*SD%$|3Ur79@=HthWcO5+1b#6`qwmS%3Fr|*LknReGEE~;dsV2P67B{ z#$ufx!GrhY^!}Mwf&WX}BkZ&r=YWwf#D~3(syB;H2)HmvdUB+O2lm?8OipTT1`g`y z>|1mAHiMYn%60ltz#y_t-mg~H0XH2HvMueyJi@zWX@9>nNYW5>#qe?_3D|A5I}&pU zi+Q29=hTohE!$Lgz?4b;JpAI5jhxY&!*@b9oI{=O?NS>{VG=Hb$z5{b2Zrq}d)B^X zl6TK0FL3^0l8p&wK9=Gx*yrZZ=?R_?lx*>7xrYnhZ!PbgO>!aOC00`xT3pDv^jPOy z^aYj{o1VMou4Ip_^B&84u0*SIWM!%7QDU>YBasjDowgqI4gHwkFJ8)56T2QbNT<}| z2yzy`R=W=>0v~l>{%E1nfc+_gF8+_F@g7Zy)tQy>4I+3X|J$LBxv^U^yxlklAtt=4 z*8Xs9=T12Y#UWo*XtDc94uy>8C-5Dv#XH;HmHL|Rfv4IAU1Y!q^1pjcsPTZ`ZmI~3 zSPwtAXf@lW?a)Er3c0HR2i*;cP<>)gB^-~|ymgg(?d(O=zr+20D)q>}pUc$Da>e{g_YYc!KX^hQ%k1a#&^5JL z`iB$XAMAQR+MWS@KhU=|zYw|567Q{{)imV3M{gLnp>OovInOnKymTTt_8)W~hWz%t zAm}~^Ev`RNTk-Gy?tA+cy8rclr97HpHz4~^(5-Q(Z4PDF+b+UUY?$oM*Y7NBsNW38AL;0&#?eJ zcsGaE%3ezbdB4?g)QFCAa_LnEyB~C-gy&|fBN=4)>H3o)NytZN|6OU4gMAf-t6zs! zG02lp4I||@(22NH)a<|qM4srR2`=Cqm|jz$38J0{mhH8dhyEiKa*v-d39qEo(`$#B zTp=nFflL^^W4 zUCGk1Qjr@CuEg6=?&bcSN6DwrX|?5;WBBEI_>k$a6A^6niZa*5{<*J8W#(tGU#L-Z zy9Mx((*4PVkk8-|djF&7y2H6{-*zRkA}Uf=LXwoMsJJ63BT5s;6Us7itl``gB^$t8g&zwY*!`;NKj zdd}*Ac$|aCQwbuf5y(p%Y1*=~06j=?(`1_l=u0Y#pRatyebEqc&vpU2QW3+P0X{IW zthnxuEPB8)*5SW#4~YF>t4KM9?|(tZ!7>`=os!j$4|^cTd`pk?(PSItB70`b&Y#z5da3X)tHXif^^Z($s z$15d(fA&4x>*Rs|%D)C8EA^3k8$Z0a68QgiP{rgJ1M`2*#6qPj{+`my^tJxh{9EPS zS(Z~Ye8&Y=#b`KVZ$w6f>CPL-O~ekDsNBQ6b5PyvaEc9SDt*%J4*kD!Zg!yp`sZ`E zqVP@7e^N=}y=3s;*+)HsI+*|UFFrZNh52V(ezf{8@GnQp|GOIamo=1pa~AkN+&pI7 zwGaA#NcC{=QQ&@NQqLE8xu4Rx-o;KhCyCV@iZ^gCEJgO=LHUA%802=&Vp)O(p*VM8+TWgD>a?&GUmF zyxr`lwgdOU$SI9uhMF`oCKtE8&Wc8+GjAww@TZac?Q1R$7tqMx{=5T1{WS6}?MTq* z8ai=y$Y!VFUI;$Z>{Aj!C)?h}U+Es9lO^x8t9q;$gpF0IZK)e_N__9PS1iL^BRU!|FFf(L)zq_erC9R2qAEVm`- z`|2m1kNo}xeVXvoJs!~ids6PVRIIQjo7I$$ltKTgy3+6C4*okZ8ntF#4fBj+j@kiy z|K}=qy*vl}R~hbIqX+zZ%CeYqyMf=*`aB*2{{a@2yi(D~|8!?x_d(vXK>qOh>SFX; zVmb$Z*I1KsYr`H^=sxU=>pyTn_i3qg_WCz&P4*^h`VT_)8S)9bR>g<@*Gkc$7;*G@ z*)4Y3ZilZm=F_OI0X_4H?nVwn_+IB~0{`EqD1B(t#T*9m550SpZo48UooS(d;THA= zRm_f=BM18FJfrnonhkkp(oeT9!hDp()C#GBe~>7_UjGrfIll*l}J{vyVVXKO>i~UCt!$54za!|yv;%*Y8j^_+2A8E zeAote;Xbg}sr+DTNrR3k#JR+eMy#sZ_S-#zuki8C%*hsx@RfE#~=kf2Zfk77$hk+`|=|4Nu71QIVxg!m!{p^>b*1i zmeMcI?thLwyA->9$z%V&-&DO-9DeeC@kbjt;3IFR$S%}4;ypd{Cl7Qn7ug+8_t}AS z@ZeHI@!$9O{?iX0TL3Sh`?XhHV~5X6++RJzJmfp8qumBwNO&?|ZWg|PXX#yyZXx$0qT2y~w`%Y&_{$TxV1wO=oR|J6A^^%y*0VpD$9#ZSz1|-&GhLvqkUspV7recN=mu!Ou45HuBF!uG;sa;U8yfSomewkaEwJir&S* z_X&QLfEw(Z;4m3Yh5t4Fw|M5`7aP)ZY~NqO3Ft?hmkOL%DC7{8W$`CJg}jOGX!Df- zAD}Z&?!o-OD>I-{NQ*++f0o`71ODsioAr(W|C!-xp9?NhNXh114hMbl-B+$WE)Wi1 zKt94~V=8#`@nT2&Clr#aZ=uNo9&mc^-^X9!kG-qDXD0j;{6O;R$sEiN4kI&`~%S=j^WUUKCn6+e{qLO9%h#RN=N~3 zj!k`S@`6f+`K#ajZl;nQQ57>mzo^7^(=!iK4jPGlW5G+4q7mlZj<#tn%tJ9MJOuZ_ zWc|$Z+rH@WJeJ(6l1?KLwaU?@Z)wCa^lMJ_G>xp6uUe)kO((}6hOIF+qZ5{vyW#@4 z7sggKt*Ys!6JvXUzSBw!5-Ya#_2feaF?#Wna|!ZErhk(fa&}u1^96q9y>Rr>M4t!j zYsdSn2BD*kyjJ9iWaOnwnpPy-qF=-dc_QZcZJ{$k@WXmPtoRGPRIqknat`NU$jI2T z=eHGM^gYO$=0b0`vH4oCGc(|>@Vl;KOG?#wvc2Vx^G4*KWj~(Hv;YrC*}|BY`-i;{VkvAPtFWge%s@Fp z0&{)ijj8=g$YZV%>PyjqK9d^Q_~JNppcbyhP%7Tf8|0MQhWTGxF3=)twUa-{%piI;Qwcw%FVMwc&9aRpLOvR&cmJDgMV2u z_pDZtlU@sdO5p7fk+dOae$S~HDB6%?7i;VFv}}lw@{#SDN6?3FP#)Q8fjLI*iRbDI z$o+E^8_z)ZPnu6?>JCI6G-#7WWi0r>of%3_rVTNv57c{50=byeXWrI8g1lF>Whvl%LkaFiaTlbLhj9rGS^(rj7eGyIfJ zv=n7$>lW$cRo?aK$P*0G%JsIx^DTqKHJu7(LEk?s&eV6yNlS9JY-`JDq|Wgg=fLopMD#1@ zq}CZxKI2=k2dK0#GjTt7akjvg<(P*I1`0HFp$m=WzT*qJ1Amyd@y_4m^JLCluRa0y zz`NhfRgv%m9NkJI{~!nVhX0#L8Rj6xlA4n%!2_m7PZ)oL4)kSmZJHT!|NPBzjduGm zr~G}lR~G(PgsgZ-B=r9doimv)pnv*1eR`7s{bw+;E&D(uc?v17x)|3X{C*dyS7CS90Ae;V(Rm3_~A!-n4Dswz{L`h zq0)9A=fu#ytR@TpU6}mwr_a#`c;jxFQ;&Inh5w;P9X8~S--KKKHyiSn>n6Q&8uv@q z^05E=VcxoeK5GQ9f4A}U`;$_bTYkpM7b?LAex`9w8v4&s%DhGq_^-C;z+0>HxF<4; zWOriz5izchlg9VIGURlWHt@e|&aWyE_@8r~UCIXhf7QKvu@HVhi}XA1Xz<`v;pSg2 zpoezYJGM#8P>93t-PP|nsN`>0=!=F8RAN57^RS3Km0Wn={pdC3pck`67IglX!44) zzAJcvy0)CX>N*xoN2CK(c>&(CMS#1aUODef3@DAk@noRpAMzbh->-P z?uuF(`FJtt`TZX>BKpc+{1iW(xQ=Q)kKRKkJ9^gc)M0`@r*WmFC(ubzuWHkaE;>FvztH*B3dk|LEd7?YC)8mW1oHL#$*YdYmU*{I!rb z;+T)UEr-0d;$i-8Vs7Zwy#4gdAq9M)^F~@gJ@&N3to><$xk!7ha7iT2!SSDMryoKm z9S{HZVN@5rfox;V$5zo zh*C|p6M!F}n?i59wiG=qMn&ye%t0IEc$Ykv0Y1ObLsP(mgSB^Vkva@~m%5Sz7Pu!~ zTsyYvqBYU@Uc4f}7rt)DTCLJ>oR<+X{p?ia*f^elvH<_J;|kp0gZaPX=RMQSz`wmt zNSHS8&n-*Yt^)i^e_p?aWd-uerf$Epf&ZZ33^jFW?2T6au=|lRekN}aSPtFuyU(vG zUFe=h#br{i&^^CuoS%ztn zrQiuiUCQzr(0_S%?pSsg@)EqfXL5$&f33Slp8UnW_6=(sYT3~XYdK}{MUX-ij6MbP zZpMB&N71|bDior^44jD3!Tb`^a%qVv_^zYzhpX1ei%u4fu5-e^mF1$1?}7hl4!6K8 z;QtHzsmocw|G95Qi_L`;qPl6~;}+mQ+9#|vr

2|Eb$b`${30 zf=WEq{s_&lgO2lZ(*KDpeh!H$mF=OD5_h+3VIwMuow+L43O?MFd^K_0iAp+TUwrgL zFS-AZ#`UXlz&m?KybJzWL~|kE7La!hEX%Q@2f5p>g23swWu@YBLdo}R4AK+ZzW{H{SAjgY&A>$|?w z$UY7Uo~D&_^8Dd@vlJyd$@P&FT53)wiu|X&-rRxjcJA<1<5zSNFqz4D=O6S{&ttN6 zIt)@BXw1eDk2&d^rP7TxOv0_le{?k)@<)uO6zLG`zvg}R^!G4&nu!5M2e#vVfp)s> zIVy4$*%I8Yk(h%vT{Zj(|KM5aXrfJM? z8}MfP(A{;&34IgwTRaM0e62L_(u;!gM0|iUBU6tY+|{6*Cw=G*l*x5m#XYce>e%N9 z=%IIWXE*VQ!@ttixwN2YO|A^*Uq`EJ)V z{NJdl?OI+*m}?G-gug7bCXdPvxIeGL{jgcP#JvUg!pY^4%Q64=2zgJKVg7j_yzaO! zzW;l@R*!lE|0C}b^2~t$u6);ne9--E^Kb2Z2>cK34SyzOie7K7D$8waoC~7F)o}^; zL7RHPT3_TI7}}*;q1c=C;(F)*`=o_!gi~Ge;BQG?&bR^HU$W8pd{85LFj*n`_j=%W zosVgX`3axRILRz&4tY?4g5x=ynC~gR+be`9WLSK+X^#wW{YXxe75;D7(;WNV@V~wd zb6oT}P9e>vw}-lI(2I#Jy=HhB`y))gv9?{Okfgkqr#!;(oo}}DBq$t^&J0>6O+hUJlbn1%!XW?;K$4B!GpyjRTPiQP{}uM zwwKLnRPstfIz3h&x=!S$*}St6ZdU;Z%LlC+ghY%X1aTt(O`4Fm9ILuIk!q1T}s z@xR{C48F{n-d;e5f1rCIL+KSO`jO5ry_#g8_aAZWQ^PqhPIPs02S28z=eGQYPoU1t zjO&TV-mA~rb{_Bt?%v-#H}ej9k%nEhGjvgj@J?32MdU{n%hrsp!S`KM=)yW#>}kl~ z?4G27JcN|CX#7#|VM^5wAqsjho;~ei;K5fOXMA`OU`>`N|9SWqy_frfOTPE!Vvn3q zuZ9!+uf%1&@#WC}FHU|itB3yiW&?{_IvyQ0RBfp{g)L3 z|F$D*f~O`ZB;?rMI4f4@`?1$~7uQnBZ4RzA@1*fvS5p@4RK>hsetT-;A@s}Mb5v)6 z2grG-iC%*qv{uHHKj|u!9L`&+DFj_KIdt8ZpUKEkFHxVDEQXG1z-CrokH4oY`ev|~ zN*dJ9Y59#KZ>OrpRlp8CsIiFM9Xjc&jW#T!$Q4Dgb#rdQJY>xr9F+ktcv~$#B;-jW z?)SCz`6FqBXYEj-B6QPb1+yp88j(x&kDiJ72|jJyc-xShPAKg?EFAK5vfe-82R2cV z{;-fHWmh_(wpB*fCqqwKI3NAt10DPCcAt-1!5|gatt>Y0XAt&V-x6O2FvyErw~8IU zFo>|&x#QPQGs(#<)LZiK8mVuW40q8$B7mZiq9Bljjrji1Fd}HrN?>~wE_l?`m zO}s$ASU^@jy%qZs1Gm=w|2|&4&y)IEHt3WAb+=qZu*b^d%>^sm19|FEJh2C%|IFrg zDxHPyZy8#n>4Bv1_;;6HzMDBBz<E#SY8`%A}$aP+-4To{Zyr>RhhPNcq$uP&7=;b!iMK8g9B%t(*W!4ujJ@3;;g zz~qP=Jr6x7BY)OCGyy&2FdHX<0{8{@&x%f0QOOrditCQdYT<~vGHb-*upa5>@rS>%cwY$I(R*wF}GHYWH9^wN?wx6Gf$ zBVQplz3-_mj*Lmo~?W%6CKF$GuqFs>)`~-I`2hUSZ zI2SQed>*mj(bY@Jn?*mLuQ?`@G9UshH>gn2|bn z^cscu83RGsk0{Wx)jb*afm(A}Ja_;%cm4Q@*O;HaOPh zXFXhHZVmk3V-Nqk7x*`SHXA$x{2w^=-X*dSydrL8mq;aY6h?NXcR$z=rBZ#ik$#+q zFc$CKf502WM*BVB`$}?)))(?3pZ2_@en1p^;}Ugg-1681k)JQ3xEH_wUeWxN0r+qH zj{DxHq2KdPAIM=)NVSgl+kRK*{CAboMB)Fo=4KjFqp&aKQJ~(-bogCfH+M)EL+@m< zPEM@By^y4Drr3&iJu3Ha>IMEK2F3&MzDWg3;7&%cj_8NmJGv+Cm8=+*d0E_Fbg%vp9Cr zNcPp7cTXm1L_Cbm+Xy`Q!fFM6+a1t{6!@wR;v78uYw&%?Meyg{9@nlzNBt)jkzZa) zC!Dm+ig&)je~Yhk{vgP}yX|it_8Bn9P=Z=|i9ds6Hv8Skde0z-+(HzaWSPYC=trhY z67B~B<7K8-(DRwOA)?8Gy^RJT+ZEAEn35fCW+Yn?);Li?^={}(`Ml|)$W=I0DQ5jt zgC6^rb%F%b`oVo+e?RoS9zxz6!h-b4pbFFYp z8hXE*|K=y~hx@nQzr@sr?{)9`3Qh2VS4#@x;D7zgV7r0- zV_N#w;BBwat0_#mZ4MrAj()E}`Wx~_4CTLpv*^_vD9VlDw!!{{zWfvLf7^K`S>C|^ z5?c^mF$ev>NGv{R1p24kX_x7AE9BxVPRMV+g!yL2y4st*@UuFcSe}GIFZB@aEd~A; z?s=|G2L4OFxo)8Y{|q~YE2}@^e)+&5ojQQreIDTN5ecWHis?`xRq zmcBzAI*`kA|BKs^`x!5A{eNGUxqZb#pCS0~<)l#lv*4>Pr*pJz@qXC@{>m%v_>OzG z?#sCiKKtq1{h!hB(efG%lpbQw=qazpn@^E|@0ac`KU z-1eHnd7+**Q^x%7anwR_g#hODQ#@ibz(4c%|xI!SF5oXLicI#6)#F-spEdlh;nesD5K z?=AgjM(PY=F+DKnb%8-zlscNcvKS=$%nri`6AY62Z-QgakV$T}=#~AdW|HKd47zP7 z_FV|aP~V7QJ}Q(i;y_P1?P-p>Yq=E>zN0XC8F|y}An83O$W`3`FMqZhF5qY7(M}i-S;Q#Z!m+p22^taafKb}5> zeE(%Z{xVCvi;-;oFB!hT^5`b1^1H}Sa9%Okl7e3Rx3g=<;0J6|(ut8p4)m)nZ+{== zpwxjz)s5f*nYPuQQ{cgQPQT7FgrHaY(yscU_t=}Ol5VsYeO)D`fu_UA?JOqV6}#zmm~H=KYV)lgE!`*lS*kep*G~&J$=>sB;eecM|U~!U%X5Aqag6FnV=ub4*c&F zDc;-({NLZT`+X4bKhgWBMs68+=?sPcF?`>zehLXP@O?R*9_+cZ1G(kR;>lmogY=)z zbXG6|u7B?_x^fOVp5avmMRxGP-V}(Ac~FSY!BKAcK=9x8{845s_ORPk?a9fckWSS& zo9Pnx#F6X19D0o&ndy;T8SNCjTXXs6ns49%&Xtj&)9@35)A~0-|KW`Kcl{0U&ykyG z5-5$iUTUK{9r(W|-KT8>{Hr7cB=`dVt){FgwG=7|l4)yE0{(UX9T;i6NhNvCGCk4o z13V}1c1D8-`_TPuK0*)uG%IAH4}aKje_A^mc)*~SY&6#>l_*OEJT_kj9^ibXgJUh` znYZW7_+)5AK=}NDtGn@CrzYGuWke%i9iA-BK2IZZ6K86CU1&t2TupQM4h=e&*TrAS z@CVqFjUPM%Z|JBO;Qv4)$*kMooCH6%dZXSQ2tPT{;@z)$5%^`H$swoznICv{R0HRrBQxjA(I<552@V))>7Z_mO58?x%t?yR_c=>0-!+g83pU#y6W-Q)xM1+5W#F9QFIzH5W+fq$vV&fEIH z|I-UH{@nZ&V!+gR@fi45v#;Bsi`+x>ztWF21Umii#w#ku_%*kEbCfxF@Ri$PqxR5o zCRz2#RSIz`p16J+`A_+b{EGK+=*xS(cUzZ5AjbH!_Dsif>&?JvaKj-%RVvwiFoyRt@Gq8G zH&+k*e>hXI;REo$c+lX%+!ZSM*y=f;2mGISu#H|B376#_T$CaO0 zr4JrFY;%ng3_Y~ZYTf=dBiPfT-O=Cm5B}P=`z&LWJ8Y@@_pc5T)5Gj+EqLZpEzM@w&!H-27CC1<@%M{vNt8}Il>*K1y z8!#6g9Y|TKigR#B=0bsGJDsH2tvNbBPbWuSW&FA>$soR(M=z!rF~}Lcwwe824DxIw zg0JK;gS-j|AZ%j{lB@9`+FKpx;fU{|emIj%H~i#l=C&nW8^^t zmdlibCp^*8Y=-`Goz$iqWB%7lu+~ZXgS{%x*9gDG{Ijija6|!}2%>^j~v47iQ@sX~P%wjbgY5V!y~$9$*l&YGLJnjts)hr91y3kwNycEp{Jm zW01zK?%*2u3>&}6%3L_hB%>|sWE_i`ojjNKN&tl$SJjteRh zxDU2-{k_JahP`h$O2mbZBmcm;RzDj05LJfd`>O!p{gXp}CFY^DlY!Ia(1m=~%BOUE z#5=;rrIR)fgFmp-hRbmes9g~?e7Xkv8!E;*Me!~MTYiH663jt*fgjzN#>lnp`4z%A zkACAy0h1M1;Ey>8xa!@)cm4de-rX@aWXZyh`vZ@#H*2;=PNx)mbNy=^>Cpcr6PnwO zLH`^p+IWt86!(TzUurn`@As}X|Ndb9FVA>u_y7EJk#Lso2L4}^-1OKE{2%j5}dq7MutGxaX?t?!=zh+k;SL!IYqEnQP{TI$O zHx)YGzxbp1=P-POjXSrTpwUTN#`Hp+51njU<}gHyr(=I*@f-8!bi9u}p!unTPCozI zv{w@6V9U}|3vR*;vUA#3$KJ)^-Oazj6S((R6@#^?|M*bn_={u8C-MC-Q>W}%4pl{X}=HvbE|Mz5y zR_O4;uZq1W-64j#KWc-5)(+^LS??9D6AD?leQ7)i-~Sng14k0@Zy=e|dL8&*T9^@b z82In(9yVDPjK3E)%b5)P*M&C)E9N36${b34@)G)w&5CLHM(oupeA!&gU?zLF0Pz2n z%OlGY__y||bNTR%O7733G}`{9lJbeg3rd{W&$!rsYTE|nenxgSoR-60BCCL-ReLel z$m%pQ!2`r=SNNQO9u%@!SnSRv%tI_+n)#8Ja6CO^^*f42G7VP9%VyDtjrHwQZ_03v z^oPE5K_3lizSv~*4ZUSUTWu%Y13Oty)URGmC-PqMcaCnMlUp}>lL?^{Pl@|3qbI-< z#yoVK9pE4H@f3~t(@AX5y#j|6I%)bj?JiM{d%>N5m0S;FGn7kVO@pyqr=`$Jo{bAm@Fx&8i>h2GAyPwB@_!*6z%-9GgR z_d@r1RfU%U*i*;c?Q$AC!DsPP%f|2LNoo?&4?v!-Zq=Pn!AkItC6rq~nc}-Y8S-Tk z=U~Hrw_^&ScxT}Jj;2oV0`;G}qPNyzehM5YID&bo_o~#Ri+{0Sy;3_adlmMY)KFrC zH{%|-?^)4;Jt)HQQHwv0ARj%wIrjp^hCEoW$8!ODK<7gZyCgQhO3 zyao^6UURowx&}S6c#ge0+ii&Ye6Z)(ckm3B1QC1qzaMw6TKR|@yi{y^S&j&Js?#U+ ztMbrqo?nm=)r79&>fRG-gt>=LiP~q5y>Kq3VVuDK>TQeDYk+^x#|g9l)uTrbVVL0 z@}$EL;QwxPA4@_M^qrpfmXr+i=tVRR?|+K(afg|*8~Cr1NHa46{_W16zu^P?^M}+~ zw9gg(15Tm0XK^olSn2M= z`Vj96?0w%?hrXGDc5Yf8n>E>3tF~g7JpAN+H$I#^id@{JSzGxfsXovo=}#zY_JUa|4km_N8rJRtsyc3 zU(qjRKfL-=6Z-)5da z2mIesU-reGf;~)JEBAWge7tIny%>Z!<|9M*7Vw`t`@-29_?OdO&9DUi73qE|Tbn3k zN7HC?Kk$ES^zz1AzrZV^L;J-4;ivESS2@UkK7CnDQxX9#Qz$l%<PMgYP}Z zaqnz>DyfX3ByK$o9Y?@jEQf)gKTo=;y5aA?*r8nSkDjoqb0;mDO3uVL{agDG{P)4C z{msDtT)XX=G~hpVs%~Wv@So%=Xe3H1ad*Fm*nO zMuMz3h+Ywm%nK(3eZw4dVgI;DZzpm`t?Z|E{-P0+4|4V+OX=ie-WTdR0pMG|_DHEL zoy@*_aefHAc+FgdN;34JD8A6;i^$hKp4$4C(-%HL&O~@e44nuwpKQHWh`ldQTKojx z(#ds?YxysR;3stStPN#hkRQK=K9`F#u-{;Cg*$p|k|vjbESNKhP*ksRgb#zbIv+q_ z4?LMBk&*@dD4+e=64N;b@vLn68?cp0#H&5|GAyB|w)izYPGAyaUS1hK=tZ zZHXY;aKKQhE%t1f4xK)MeZC4R#$Sf8KRB=}T~Y@<{f@2c1Ot)3`x23JxCZw@lR4+E z86^27D>v?wgl{%3c4|-`eVL5!2PNPexR&(lC5KoOJ;{QeA)Es_!JhuZ@QWo{E;wxj zFQED^Dn%~`ZgbmhzldOtH?|#=K|ZK0O=83ky_g!-125OY7jtG0jr!$^{(!~Do1230 zZqhc9CDrf)wz9RF_7@{Jy}W6IANC;r{Q1T1c`teaPut|~f(P##tdM70j{UZqo=~<5 zP{^Vjjg?gfeU~od@MtykRwAj~zxANgkLiEsJVPOSJa4Ow+2Z|xG2g6*o)mIh$|_#@ zE^?gH4iYi(cvoY^M((a0@aln|Q*$pdFR2?DE&=|n3PunA0RCg-w+WO3|E!^0_q~CC z-^iC0J9(&NT>O<@EAY>ok~(a^jY>A{2-RK${x{V}4f`9w*K%uS@SVXsO~)7qqnOZz zh8$Qnx>K=_sCIqMZJdL(-+8oRz<-CHT7LrmeK%WW+$w?IGqcZuyoPRC^UIv01HH*+ ztF42;|LDzQF&)5v(B;~ILEzukW8g0@@PDXr-M^E-zjsAZOO+aO4@EtL$Mv8C84K0$ zBOfHU?)sj2CiKlO&kqZF(#Qd`$NOn_(W{A!Di}||?+=goyv(N&6*J{!jg|QQ*b_fD zw<14ezsutT=Ahi#FP_bFG@Rcb=aqRezf43~EMVWGzUa8GvMQZaFVFfkq)#UY46!Ky z_rSDZL)`Z(bP~SLrQZbkx~S*RitI5DO^NHI8oYp?d?arbOAGFY=G{%1zv$$&y2}zv z4hFe6uulA-6!5Rue#KvlL5?Vj@}00`klB?HZoj5hm%a%)Ifxzn~~qKep>Sli0KI6fj>g$>#|5oCz*lViNKE5+~J`Y?EC5 zQLo>Ys9(stA+Y0*_g=b=vaWABAt-|rao&XY&;$C>E!`e}BBfe-i;F7@(=0x!r{DlX5qAt~$g zmOH+}JCcXTYhqh5AHBH|V~8B+^6l-(Aq%))zL7VMt1#DRB#%r z>G0|zA9^HNBkv@7y?8f_k3k`Psn?p-+|hG6(1#7}$b)(X%ZV!n@i$u`ac)S z6@PGI6Y$Tebt+>w@NYk2Jahs0k9&~NPSma8E+pr*K?f?k;E)sVP9wd< z?@U-Ad|_*rS0(ppMAy}SivaY{D7E#n+3<($40ZB-;R{T@Y2r!v0$pgQ%re$#8o9NK zrT#hQAoFG6D)qv2^1^%kr7Ha5b_;3@_kNs*A*bFWC+Vc+=$9luJMaT(rEMp`i?u2) zNNtb8cfV%7H9dz;*b?7edtXf_ISWrpUV;~>Rq*`2K84%`;~U%FRSd#ow{_?8tqhVD z$gy+*dePvgXU)de4ARD-*QVghAYW@Lp7ta&$W-zA$iy1VPY<|DKK%e+HnY}P2mPp! z%d%w(^HJrWyS8)(CV7?`B2bscBuiw@l!|}Fy!2{8qgCFPbZf*tm$+?9oNop;K3Z-^ zvP>11J`KYAfZ0hSlIXAXdG?;4x{BV~t);xjaWBkw8{8UPVojVEw}oy{#QX58RXM2U z;J+HJ`MNj33!bGHmOO%=oUP?)`xd?Wqp7B!a1J=j#S0ywlMY%>OW8>y?_+l?gKHo5 z-*SpKxSJvW|9L#(^F`z$^o9MbZsT59_jaBieBfE2xj7f^0qYc{)^iOu#PjQ?Un0;$ zrCG;TpP0n{IP;Vr0vz}*XZ=p138SZ5RI%mwcIZHj<>$Xa2Wn2;Y`pmx@}VaaW!F>i z9>8qmjap~m{uUoa*&p|X-LwHc2J=n6(-GPu$+J^My0fd93jgSoeW{{Ys8 zC;QG~AJ)L+^WVU~uf2}VJr8`xPcZeB1ECik;#qhP{HLfiEwz6HKKw(ehwC|dl+SMR z<m}e{ez-!{2KbLk=MuID z{wL)x2LuEES60u3HJ!qD{4KkQJn;Whj*~Ob4ZPRt;--_(fy&tr?~;wfdD!DBAe#-H z$UU<5^h+A4y)znB*@S!G^BGAB{NaX6PG$$;3ykg1xO;&Wb3aR#Pro2^&SK)0f;mX5 z&g4+pUYv&(U#8j-=%M^PA{%VbI};mou>&8tS;cu@{Vw(yy^m?RgIrx@oz{m-C3Nz~ zcw%t234UAk@iU5;hjw2$*t~ra{&UjTI@WazQu>K?d!qt_d}{AHn1+1CG=lnh(2F|U zl@|qWFi6k)=`&oZ4069YDdSBwgDgm0+?M){L9F_-n6oRv6W%Sp)mLE>wb*isjun&e zc{b;?gfdCAfY~+E*G#;(xMlL=3R}W1X4G4B#1_8c{*hhTI2W0-KAbXkgU!2yALD(Ih`KV2^}cs<&i_u=)aiVoO~?hM!OvRLSv(E=x3224 z&IA7Q?!-K@h(rHzPoy+g7V;Ui4k1IpzuuABb!EW+q@YK4I`Ho!+i@=i_;-4~jQ=U{?>l=}`751< zy-??uYzO{d#eWTnx{dsFbkH`bSojCEe>K}5VSn!x2kW92$OUC@W0r#l+bNk^EcD{< z?P?8k7{#w=&LoL0!(5+#(~Elz{4kdL-kRuJHh<^6P`Zmw%=+Z-24W79cfVL%cn-Nb zw|Ry-auZx)|GvxIpp&@bkz=>O2Oj%9ZnDb79JSFjyRr&*9^cJjLvmb28-N!wUFxhA8CW`$&rCI9lb|T-*cje!s z1L%jnQJ-38hFqu4vW*+UU&;0{7A~+msBYBp!Yr=P)MN=i*l#o=_2rhL*c8g zBLAb5wY&c{@(*WKW!?JV|DKJji>iVDB|M;&c8v>j{Nbgq_=T|_w7sVOnjG>y!8w%1 zJL?PLS`WierjqzAcEKfBY%!Gk5A3EYWaMDK=0a)SsT zoxHiTI<*x%V1N6~jqjibt>IuD=F!Do(`Jvls8jf^53sFpvZa%5F?FAGFFJ{4K7FYk zhWnr{d6`N&oy-S+y_5u>Aj!pX&+T_~;%CYFWacY!Mqkb(%t9x%h;%p`&(9zijCL7J zY+;a-l*CQE;02e%wm2_8%^-De*PR-1Vi1|Ewemwj@YBZJD%T)yR2&&unE-wep*NKG z4EMqIB2388jc#%rKAa)PBzbGfBDNl7l9G|F-Z^f#4=6@MJ(!P*u4S1%Y-19shS!Qr z9^3~OKWCH-ZOPDirIQyTZON^Ohoa`=w!|ppuS|u#9dQ>pz2Ec;_Q=0n^HRVWdr(_T zUCQCJvC&I@yh09ptE@*?+ey5~5qUM+Gr*c0d@9K!hg^}-8*T%eKHL)`dHtJNaSpDi zcS=GpJ(nqy-i>pxvwnSiF8Hxl)#B{XHRPYkGR^W>yaTgJlSVDFA(uT}n_1wG^-Fgi zEP^hyXWJcG#60)|i%(rCauG(R@-H>Oho3%_Uf8l1_>X1by9+-o`|9uuXB&L?^-Xlg zTrfAK)IV7P9w1dG%~BDM?>m3_Ug>=7&pi@dpizn3TztiM z{^yweo}(fh$T7qlu=B3R{Bz`@f3qxdJ-vc6j=PcL5q_uqLm#>RmQz2p&){cNUXYh9 zbWGNx_K6IVOgF7{42`b54ZyS+n+e&c~B2~BF=uZ zlQsh%u$Q0bXP{5K_G0rYHyW9k@h+4A{^c6hGxTG?10MMH-N{5AXsN^ck!SD~`jvOv zzQOspOufwmKP=7ivrF4g{CE8hY4z{}UanpG?FSE?ytgbotSOE?b&loRUn`(rcJ<1( zyV{uJ4czvHK@Tc752)**(h0LoF!+)ioy0Hy_tgx1Sn=X$X3PUR@!!NlQ-2J9ERsUg zsskU6KHB!Yn@++GH+;#%JUI2C<1@uiW#$PD;O4`%4kN!Lb9@Ci?i^AKZV& z6TX25U!0MT2ZK25(=>OFV36Vc3rlX~Gl)p5i$FDc&3o_dwXy;~cqy{sdNA&TE|H8E zcc2^jHY)X|ABMm7>)jeHCnkAV5}(-<$0Tfd8Qq&PA1QJ^EnhXuB&vtCu8+fi_UsjC z7`R|dE`PqHe(0Gkx!9T{eL=vEXhz)FBot~#yovkcyGzh_W_pTLgkf(fFK=)Gd^Y~m zlK+O)(Vt0|>e_k*@AjpJt)9++uco$ZUrh^qXl~_C!q}_ToN#d4tOW9IoepKZI>`AS z+|203IgouW^tQ&whRmFhI=eanJpoI#x_|J=ZkHU}@f10^i`$%6QGOyf(Kx0f16@e+ z#nxLw8_-{WC+BGlU%2)MhkqaLfvEmJ%+Ax`yG+Ly2Ji!hC3ST7U&kJZkW;4{BLC;n z&)I%wA|GKtu3H2i+$eimW%E1u2;7#N3n%jrZ^b@E?ayEP)oG;LBYH6#_>T?}nYw0%x#)w_$+N(J;mWBOI&ScX zFYl|`1N>{BF%i~@p^=Q4XTFxef0FZJL-;cqX}hU0&|gm@vaPFL>v!SY1ieaY`9ULE z3%{#;=4r(LRaC_Bm2~71%1V#H50DYe;qykHtm^4v>L>VOshmL{oRAxpc6HgKV~zgI zD$71o=s{hf`$V&D(aGDr%W4f{k&n2mBexHHSmbZ(&N~%!ayHM1rUqST%;BN%;qTxV zeHqu97cgHX=+(F49=P0CWMLu0Ab%yZ`L4n*_>&}LqG5`@GQVtizAb}nDk@DHzRn=- z8$!1(-beoQ&8~CoPcc80##e0m$RG-OiTX~z8N{u2rgane!3(D%aU0wRWhYGUT!C)% zT4rKH8u+phceKKZ2qyMkU9;jUW0FhvD-SzhJ}Pt(ymv(ydg_C7GH&pnsr7Q5cSCK7 zzk0O##vWU;qoiBLQ_YUhm`lIg7ui9-42!Q9#-3{#jchyYwRk1hmyyPc{M@luzt-Sh zsMXPm^A1DalyYCZ=u2Zhy16@lB(-by5O_v zwMP?Ag11J;qD#KISj6F`v{x#yL&N+r*6f7Ekw zcD{k``C~wAs0%)sewWo};D6b!z3K0P|6jHvS&xDLKVr)_1p)srMdTix2mbSdn!A;D zBlq)F^B}7}jjZ!?b!`LwBaC*>Wdr{aA#Y9v0RJYfT~Zf;|NMD}X=~tromh_p1^9od z)V$9X_^<0tk$nLCJ4Pfd_H=?LUo6g22LAO~>1vsC*x$>TY|ub|?0DwV!YSxL6HBr! zTDH;A!&P+a)j$rkM73ir`U9#VZ^OKxhxXAOmWyLA(KBw2k8{`QsjqF^MQL_Sph z>H3gP7Gh4>Z-y=!+r`->4L&?5v~`2m0DAd#_2sJ2g|=qYi=RTiIyn1;<4;lKCs^!$ z&EX!1Z~Vj>c8Ecg$A1OBgkSK%czo%dD-3eCIJ<}EF8qVAA2Y|(z?&x)xZTSbsrY#@=VeuwZVTE?t_!zw}j7KfWM}`nKK!Dd5`70 z-;AeB(%_i+NVOk1y(Mv^cqQ=P^RuN>!G`VNj>x*cUSL;4zf*lBUHC0>+@)G&adMc0D!-SI%g9+rTWsinpP*@A z*7gg%%M!Uq=N927m-H(52CHG;gx`~u$>%Wt>%L3+j=AX8=N;W&aSkl`_(o=4!e5hn z{@kt$`l+I^k=GRZ1#E_VXQ7X7Joe|wwk^(4Uv$f zVV#SWT`|5aNp6{1M<&TJ^PAD8O(dEJ51vZS>5wGS%9&7(R%t~CQ7t(KZRBbnt6VwS z_w(1hUi0_+`}=<0$LIZ3qcf}2p^FySS5$?EVE); z`31*~H`<`j=YS|Yl?6Xc$n5V#{`1}3kj})3AmVuRkDgbF&_!!c%BNk1k8IWQSho;+ z0>a>|o3)t#S5+%W0{?jf%rmyY|4~&NwWGj)?EJ{PMBra4r?x2>_-|WSypjm~zw{1e zgaQ8=+i42k!2i$>J7mp(|EuB}rSjg$yHPEtr-1+0c@y+j;9o0YbhZTe_lmB(D+K;M z4U324f&ZxJf2+g+|4;2rB~pO@`!e6#mH_|sx|9OZIPQf%JtZ`Of3+?z^53-_!hJPO ztpWanF77M+RhL6PW*V`$(1Ezljc@ik1OIk{z92T{`%+)aLgXW!t)Eof0zH)JXx;P- zJixR@Zn``l_rZF}Yu)#tmzste+daeF(`%X_23@q6f8yiXDGt%qVFdgPpN!W3B-8}^ zHmM34VgArZCxuT7B?*^&&?s|P!#$uP-21kX3!RkC-?1V9UmmLO=(z|Ud`W0cm2pW} zN&dk{&0HcA`+R0*kV|$A)j4m0k7nW=CFiq|Lf*wJpv{OP2Xi|e@?0t6WpwKS4fnyS zo@$;A-WG4jIarikiE}c~aF0R`iAJAHJS52@Rb$(#mJE307|k`_!jFgk|HAN?OFSaI zW>wYD8y<;}^Ur&(&L;xzIi2*=e9|kXI6`0I6Uig2R(tF-Xuc|SY#l>CsywSL!ydi6 z;>+G4@R{8yC6*EVg!_lm_4(q+OXm(-XX^w1Zo20k_oGj1Y9=e<6m%o?+$&w#0c1sC zOZ)`RfiGuUH@zS44~R!pWGx^!^h@dP2Ixa$@B6lw>*M#1ok}|VfzU-?j|4XIJo5wf z1!3qQjK>3G~YbkBZ8omZbR zKM6!9*8u-BS^M5=1OM$jB|mfE|A40FLrdV_Gq&!DDexcBEvBal{Od0tN|T|WkA}9S z&jSDY=O!9^fqw~g-Ks~xzv*1gbP4dkE^_$m|L+BK`G{S*0{r*+yBOpF|93S06J7)S zbK@HrL!YrvBYd%}4E*mvSFs8f9Q_pj{02ifUE(<XYl*pL~39*DmTL#g?6^d!bLt!CweKPX#T3GN~v2qHAt|vyMFL1$YHE$mNcoKX!DN6tS8Q^>8&7?P(!KA7sMxnV7 z{X!*r2dZm>@m|B>ze=7VFB(Jn6!u`AIyG&6dpwv7EQ#wq`i#CUqs7;6X&k)gd1pip z_}_J`MB5wqzc-f}QN5ExT-LQT8aQHpzi?_(qYv^vqPiR5d=9Z>T2;G7bMOvIOq)wG z2YodMg%RMvES1Rdm*pI?5VU8~=Xcy60<~pT@PKPl6!hKQ zrYW8j`oL1RGQzN*5Vzwy)eMT*NT16o!Z}d7-srimgCY;rR?DW%<2RvcUA8KZST{A( zD(&DeJnJ!xg`PSwG-yP>5?_##~ IZR-&756-ay5C8xG literal 0 HcmV?d00001 diff --git a/rednose/helpers/ekf_sym.py b/rednose/helpers/ekf_sym.py new file mode 100644 index 0000000..1f3585f --- /dev/null +++ b/rednose/helpers/ekf_sym.py @@ -0,0 +1,600 @@ +import os +from bisect import bisect_right + +import numpy as np +import sympy as sp +from numpy import dot + +from rednose.helpers.sympy_helpers import sympy_into_c +from rednose.helpers import (TEMPLATE_DIR, load_code, write_code) +from rednose.helpers.chi2_lookup import chi2_ppf + + +def solve(a, b): + if a.shape[0] == 1 and a.shape[1] == 1: + return b / a[0][0] + else: + return np.linalg.solve(a, b) + + +def null(H, eps=1e-12): + u, s, vh = np.linalg.svd(H) + padding = max(0, np.shape(H)[1] - np.shape(s)[0]) + null_mask = np.concatenate(((s <= eps), np.ones((padding,), dtype=bool)), axis=0) + null_space = np.compress(null_mask, vh, axis=0) + return np.transpose(null_space) + + +def gen_code(folder, name, f_sym, dt_sym, x_sym, obs_eqs, dim_x, dim_err, eskf_params=None, msckf_params=None, maha_test_kinds=[], global_vars=None): + # optional state transition matrix, H modifier + # and err_function if an error-state kalman filter (ESKF) + # is desired. Best described in "Quaternion kinematics + # for the error-state Kalman filter" by Joan Sola + + if eskf_params: + err_eqs = eskf_params[0] + inv_err_eqs = eskf_params[1] + H_mod_sym = eskf_params[2] + f_err_sym = eskf_params[3] + x_err_sym = eskf_params[4] + else: + nom_x = sp.MatrixSymbol('nom_x', dim_x, 1) + true_x = sp.MatrixSymbol('true_x', dim_x, 1) + delta_x = sp.MatrixSymbol('delta_x', dim_x, 1) + err_function_sym = sp.Matrix(nom_x + delta_x) + inv_err_function_sym = sp.Matrix(true_x - nom_x) + err_eqs = [err_function_sym, nom_x, delta_x] + inv_err_eqs = [inv_err_function_sym, nom_x, true_x] + + H_mod_sym = sp.Matrix(np.eye(dim_x)) + f_err_sym = f_sym + x_err_sym = x_sym + + # This configures the multi-state augmentation + # needed for EKF-SLAM with MSCKF (Mourikis et al 2007) + if msckf_params: + msckf = True + dim_main = msckf_params[0] # size of the main state + dim_augment = msckf_params[1] # size of one augment state chunk + dim_main_err = msckf_params[2] + dim_augment_err = msckf_params[3] + N = msckf_params[4] + feature_track_kinds = msckf_params[5] + assert dim_main + dim_augment * N == dim_x + assert dim_main_err + dim_augment_err * N == dim_err + else: + msckf = False + dim_main = dim_x + dim_augment = 0 + dim_main_err = dim_err + dim_augment_err = 0 + N = 0 + + # linearize with jacobians + F_sym = f_err_sym.jacobian(x_err_sym) + + if eskf_params: + for sym in x_err_sym: + F_sym = F_sym.subs(sym, 0) + + assert dt_sym in F_sym.free_symbols + + for i in range(len(obs_eqs)): + obs_eqs[i].append(obs_eqs[i][0].jacobian(x_sym)) + if msckf and obs_eqs[i][1] in feature_track_kinds: + obs_eqs[i].append(obs_eqs[i][0].jacobian(obs_eqs[i][2])) + else: + obs_eqs[i].append(None) + + # collect sympy functions + sympy_functions = [] + + # error functions + sympy_functions.append(('err_fun', err_eqs[0], [err_eqs[1], err_eqs[2]])) + sympy_functions.append(('inv_err_fun', inv_err_eqs[0], [inv_err_eqs[1], inv_err_eqs[2]])) + + # H modifier for ESKF updates + sympy_functions.append(('H_mod_fun', H_mod_sym, [x_sym])) + + # state propagation function + sympy_functions.append(('f_fun', f_sym, [x_sym, dt_sym])) + sympy_functions.append(('F_fun', F_sym, [x_sym, dt_sym])) + + # observation functions + for h_sym, kind, ea_sym, H_sym, He_sym in obs_eqs: + sympy_functions.append(('h_%d' % kind, h_sym, [x_sym, ea_sym])) + sympy_functions.append(('H_%d' % kind, H_sym, [x_sym, ea_sym])) + if msckf and kind in feature_track_kinds: + sympy_functions.append(('He_%d' % kind, He_sym, [x_sym, ea_sym])) + + # Generate and wrap all th c code + header, code = sympy_into_c(sympy_functions, global_vars) + extra_header = "#define DIM %d\n" % dim_x + extra_header += "#define EDIM %d\n" % dim_err + extra_header += "#define MEDIM %d\n" % dim_main_err + extra_header += "typedef void (*Hfun)(double *, double *, double *);\n" + + extra_header += "\nvoid predict(double *x, double *P, double *Q, double dt);" + + extra_post = "" + + for h_sym, kind, ea_sym, H_sym, He_sym in obs_eqs: + if msckf and kind in feature_track_kinds: + He_str = 'He_%d' % kind + # ea_dim = ea_sym.shape[0] + else: + He_str = 'NULL' + # ea_dim = 1 # not really dim of ea but makes c function work + maha_thresh = chi2_ppf(0.95, int(h_sym.shape[0])) # mahalanobis distance for outlier detection + maha_test = kind in maha_test_kinds + extra_post += """ + void update_%d(double *in_x, double *in_P, double *in_z, double *in_R, double *in_ea) { + update<%d,%d,%d>(in_x, in_P, h_%d, H_%d, %s, in_z, in_R, in_ea, MAHA_THRESH_%d); + } + """ % (kind, h_sym.shape[0], 3, maha_test, kind, kind, He_str, kind) + extra_header += "\nconst static double MAHA_THRESH_%d = %f;" % (kind, maha_thresh) + extra_header += "\nvoid update_%d(double *, double *, double *, double *, double *);" % kind + + code += '\nextern "C"{\n' + extra_header + "\n}\n" + code += "\n" + open(os.path.join(TEMPLATE_DIR, "ekf_c.c")).read() + code += '\nextern "C"{\n' + extra_post + "\n}\n" + + if global_vars is not None: + global_code = '\nextern "C"{\n' + for var in global_vars: + global_code += f"\ndouble {var.name};\n" + global_code += f"\nvoid set_{var.name}(double x){{ {var.name} = x;}}\n" + extra_header += f"\nvoid set_{var.name}(double x);\n" + + global_code += '\n}\n' + code = global_code + code + + header += "\n" + extra_header + + write_code(folder, name, code, header) + + +class EKF_sym(): + def __init__(self, folder, name, Q, x_initial, P_initial, dim_main, dim_main_err, + N=0, dim_augment=0, dim_augment_err=0, maha_test_kinds=[], global_vars=None): + """Generates process function and all observation functions for the kalman filter.""" + self.msckf = N > 0 + self.N = N + self.dim_augment = dim_augment + self.dim_augment_err = dim_augment_err + self.dim_main = dim_main + self.dim_main_err = dim_main_err + + # state + x_initial = x_initial.reshape((-1, 1)) + self.dim_x = x_initial.shape[0] + self.dim_err = P_initial.shape[0] + assert dim_main + dim_augment * N == self.dim_x + assert dim_main_err + dim_augment_err * N == self.dim_err + assert Q.shape == P_initial.shape + + # kinds that should get mahalanobis distance + # tested for outlier rejection + self.maha_test_kinds = maha_test_kinds + + self.global_vars = global_vars + + # process noise + self.Q = Q + + # rewind stuff + self.rewind_t = [] + self.rewind_states = [] + self.rewind_obscache = [] + self.init_state(x_initial, P_initial, None) + + ffi, lib = load_code(folder, name) + kinds, self.feature_track_kinds = [], [] + for func in dir(lib): + if func[:2] == 'h_': + kinds.append(int(func[2:])) + if func[:3] == 'He_': + self.feature_track_kinds.append(int(func[3:])) + + # wrap all the sympy functions + def wrap_1lists(name): + func = eval("lib.%s" % name, {"lib": lib}) + + def ret(lst1, out): + func(ffi.cast("double *", lst1.ctypes.data), + ffi.cast("double *", out.ctypes.data)) + return ret + + def wrap_2lists(name): + func = eval("lib.%s" % name, {"lib": lib}) + + def ret(lst1, lst2, out): + func(ffi.cast("double *", lst1.ctypes.data), + ffi.cast("double *", lst2.ctypes.data), + ffi.cast("double *", out.ctypes.data)) + return ret + + def wrap_1list_1float(name): + func = eval("lib.%s" % name, {"lib": lib}) + + def ret(lst1, fl, out): + func(ffi.cast("double *", lst1.ctypes.data), + ffi.cast("double", fl), + ffi.cast("double *", out.ctypes.data)) + return ret + + self.f = wrap_1list_1float("f_fun") + self.F = wrap_1list_1float("F_fun") + + self.err_function = wrap_2lists("err_fun") + self.inv_err_function = wrap_2lists("inv_err_fun") + self.H_mod = wrap_1lists("H_mod_fun") + + self.hs, self.Hs, self.Hes = {}, {}, {} + for kind in kinds: + self.hs[kind] = wrap_2lists("h_%d" % kind) + self.Hs[kind] = wrap_2lists("H_%d" % kind) + if self.msckf and kind in self.feature_track_kinds: + self.Hes[kind] = wrap_2lists("He_%d" % kind) + + if self.global_vars is not None: + for var in self.global_vars: + fun_name = f"set_{var.name}" + setattr(self, fun_name, getattr(lib, fun_name)) + + # wrap the C++ predict function + def _predict_blas(x, P, dt): + lib.predict(ffi.cast("double *", x.ctypes.data), + ffi.cast("double *", P.ctypes.data), + ffi.cast("double *", self.Q.ctypes.data), + ffi.cast("double", dt)) + return x, P + + # wrap the C++ update function + def fun_wrapper(f, kind): + f = eval("lib.%s" % f, {"lib": lib}) + + def _update_inner_blas(x, P, z, R, extra_args): + f(ffi.cast("double *", x.ctypes.data), + ffi.cast("double *", P.ctypes.data), + ffi.cast("double *", z.ctypes.data), + ffi.cast("double *", R.ctypes.data), + ffi.cast("double *", extra_args.ctypes.data)) + if self.msckf and kind in self.feature_track_kinds: + y = z[:-len(extra_args)] + else: + y = z + return x, P, y + return _update_inner_blas + + self._updates = {} + for kind in kinds: + self._updates[kind] = fun_wrapper("update_%d" % kind, kind) + + def _update_blas(x, P, kind, z, R, extra_args=[]): + return self._updates[kind](x, P, z, R, extra_args) + + # assign the functions + self._predict = _predict_blas + # self._predict = self._predict_python + self._update = _update_blas + # self._update = self._update_python + + def init_state(self, state, covs, filter_time): + self.x = np.array(state.reshape((-1, 1))).astype(np.float64) + self.P = np.array(covs).astype(np.float64) + self.filter_time = filter_time + self.augment_times = [0] * self.N + self.rewind_obscache = [] + self.rewind_t = [] + self.rewind_states = [] + + def reset_rewind(self): + self.rewind_obscache = [] + self.rewind_t = [] + self.rewind_states = [] + + def augment(self): + # TODO this is not a generalized way of doing this and implies that the augmented states + # are simply the first (dim_augment_state) elements of the main state. + assert self.msckf + d1 = self.dim_main + d2 = self.dim_main_err + d3 = self.dim_augment + d4 = self.dim_augment_err + + # push through augmented states + self.x[d1:-d3] = self.x[d1 + d3:] + self.x[-d3:] = self.x[:d3] + assert self.x.shape == (self.dim_x, 1) + + # push through augmented covs + assert self.P.shape == (self.dim_err, self.dim_err) + P_reduced = self.P + P_reduced = np.delete(P_reduced, np.s_[d2:d2 + d4], axis=1) + P_reduced = np.delete(P_reduced, np.s_[d2:d2 + d4], axis=0) + assert P_reduced.shape == (self.dim_err - d4, self.dim_err - d4) + to_mult = np.zeros((self.dim_err, self.dim_err - d4)) + to_mult[:-d4, :] = np.eye(self.dim_err - d4) + to_mult[-d4:, :d4] = np.eye(d4) + self.P = to_mult.dot(P_reduced.dot(to_mult.T)) + self.augment_times = self.augment_times[1:] + self.augment_times.append(self.filter_time) + assert self.P.shape == (self.dim_err, self.dim_err) + + def state(self): + return np.array(self.x).flatten() + + def covs(self): + return self.P + + def rewind(self, t): + # find where we are rewinding to + idx = bisect_right(self.rewind_t, t) + assert self.rewind_t[idx - 1] <= t + assert self.rewind_t[idx] > t # must be true, or rewind wouldn't be called + + # set the state to the time right before that + self.filter_time = self.rewind_t[idx - 1] + self.x[:] = self.rewind_states[idx - 1][0] + self.P[:] = self.rewind_states[idx - 1][1] + + # return the observations we rewound over for fast forwarding + ret = self.rewind_obscache[idx:] + + # throw away the old future + # TODO: is this making a copy? + self.rewind_t = self.rewind_t[:idx] + self.rewind_states = self.rewind_states[:idx] + self.rewind_obscache = self.rewind_obscache[:idx] + + return ret + + def checkpoint(self, obs): + # push to rewinder + self.rewind_t.append(self.filter_time) + self.rewind_states.append((np.copy(self.x), np.copy(self.P))) + self.rewind_obscache.append(obs) + + # only keep a certain number around + REWIND_TO_KEEP = 512 + self.rewind_t = self.rewind_t[-REWIND_TO_KEEP:] + self.rewind_states = self.rewind_states[-REWIND_TO_KEEP:] + self.rewind_obscache = self.rewind_obscache[-REWIND_TO_KEEP:] + + def predict(self, t): + # initialize time + if self.filter_time is None: + self.filter_time = t + + # predict + dt = t - self.filter_time + assert dt >= 0 + self.x, self.P = self._predict(self.x, self.P, dt) + self.filter_time = t + + def predict_and_update_batch(self, t, kind, z, R, extra_args=[[]], augment=False): + # TODO handle rewinding at this level" + + # 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] - 1.0: + print("observation too old at %.3f with filter at %.3f, ignoring" % (t, self.filter_time)) + return None + rewound = self.rewind(t) + else: + rewound = [] + + ret = self._predict_and_update_batch(t, kind, z, R, extra_args, augment) + + # optional fast forward + for r in rewound: + self._predict_and_update_batch(*r) + + return ret + + def _predict_and_update_batch(self, t, kind, z, R, extra_args, augment=False): + """The main kalman filter function + Predicts the state and then updates a batch of observations + + dim_x: dimensionality of the state space + dim_z: dimensionality of the observation and depends on kind + n: number of observations + + Args: + t (float): Time of observation + kind (int): Type of observation + z (vec [n,dim_z]): Measurements + R (mat [n,dim_z, dim_z]): Measurement Noise + extra_args (list, [n]): Values used in H computations + """ + # initialize time + if self.filter_time is None: + self.filter_time = t + + # predict + dt = t - self.filter_time + assert dt >= 0 + self.x, self.P = self._predict(self.x, self.P, dt) + self.filter_time = t + xk_km1, Pk_km1 = np.copy(self.x).flatten(), np.copy(self.P) + + # update batch + y = [] + for i in range(len(z)): + # these are from the user, so we canonicalize them + z_i = np.array(z[i], dtype=np.float64, order='F') + R_i = np.array(R[i], dtype=np.float64, order='F') + extra_args_i = np.array(extra_args[i], dtype=np.float64, order='F') + # update + self.x, self.P, y_i = self._update(self.x, self.P, kind, z_i, R_i, extra_args=extra_args_i) + y.append(y_i) + xk_k, Pk_k = np.copy(self.x).flatten(), np.copy(self.P) + + if augment: + self.augment() + + # checkpoint + self.checkpoint((t, kind, z, R, extra_args)) + + return xk_km1, xk_k, Pk_km1, Pk_k, t, kind, y, z, extra_args + + def _predict_python(self, x, P, dt): + x_new = np.zeros(x.shape, dtype=np.float64) + self.f(x, dt, x_new) + + F = np.zeros(P.shape, dtype=np.float64) + self.F(x, dt, F) + + if not self.msckf: + P = dot(dot(F, P), F.T) + else: + # Update the predicted state covariance: + # Pk+1|k = |F*Pii*FT + Q*dt F*Pij | + # |PijT*FT Pjj | + # Where F is the jacobian of the main state + # predict function, Pii is the main state's + # covariance and Q its process noise. Pij + # is the covariance between the augmented + # states and the main state. + # + d2 = self.dim_main_err # known at compile time + F_curr = F[:d2, :d2] + P[:d2, :d2] = (F_curr.dot(P[:d2, :d2])).dot(F_curr.T) + P[:d2, d2:] = F_curr.dot(P[:d2, d2:]) + P[d2:, :d2] = P[d2:, :d2].dot(F_curr.T) + + P += dt * self.Q + return x_new, P + + def _update_python(self, x, P, kind, z, R, extra_args=[]): + # init vars + z = z.reshape((-1, 1)) + h = np.zeros(z.shape, dtype=np.float64) + H = np.zeros((z.shape[0], self.dim_x), dtype=np.float64) + + # C functions + self.hs[kind](x, extra_args, h) + self.Hs[kind](x, extra_args, H) + + # y is the "loss" + y = z - h + + # *** same above this line *** + + if self.msckf and kind in self.Hes: + # Do some algebraic magic to decorrelate + He = np.zeros((z.shape[0], len(extra_args)), dtype=np.float64) + self.Hes[kind](x, extra_args, He) + + # TODO: Don't call a function here, do projection locally + A = null(He.T) + + y = A.T.dot(y) + H = A.T.dot(H) + R = A.T.dot(R.dot(A)) + + # TODO If nullspace isn't the dimension we want + if A.shape[1] + He.shape[1] != A.shape[0]: + print('Warning: null space projection failed, measurement ignored') + return x, P, np.zeros(A.shape[0] - He.shape[1]) + + # if using eskf + H_mod = np.zeros((x.shape[0], P.shape[0]), dtype=np.float64) + self.H_mod(x, H_mod) + H = H.dot(H_mod) + + # Do mahalobis distance test + # currently just runs on msckf observations + # could run on anything if needed + if self.msckf and kind in self.maha_test_kinds: + a = np.linalg.inv(H.dot(P).dot(H.T) + R) + maha_dist = y.T.dot(a.dot(y)) + if maha_dist > chi2_ppf(0.95, y.shape[0]): + R = 10e16 * R + + # *** same below this line *** + + # Outlier resilient weighting as described in: + # "A Kalman Filter for Robust Outlier Detection - Jo-Anne Ting, ..." + weight = 1 # (1.5)/(1 + np.sum(y**2)/np.sum(R)) + + S = dot(dot(H, P), H.T) + R / weight + K = solve(S, dot(H, P.T)).T + I_KH = np.eye(P.shape[0]) - dot(K, H) + + # update actual state + delta_x = dot(K, y) + P = dot(dot(I_KH, P), I_KH.T) + dot(dot(K, R), K.T) + + # inject observed error into state + x_new = np.zeros(x.shape, dtype=np.float64) + self.err_function(x, delta_x, x_new) + return x_new, P, y.flatten() + + def maha_test(self, x, P, kind, z, R, extra_args=[], maha_thresh=0.95): + # init vars + z = z.reshape((-1, 1)) + h = np.zeros(z.shape, dtype=np.float64) + H = np.zeros((z.shape[0], self.dim_x), dtype=np.float64) + + # C functions + self.hs[kind](x, extra_args, h) + self.Hs[kind](x, extra_args, H) + + # y is the "loss" + y = z - h + + # if using eskf + H_mod = np.zeros((x.shape[0], P.shape[0]), dtype=np.float64) + self.H_mod(x, H_mod) + H = H.dot(H_mod) + + a = np.linalg.inv(H.dot(P).dot(H.T) + R) + maha_dist = y.T.dot(a.dot(y)) + if maha_dist > chi2_ppf(maha_thresh, y.shape[0]): + return False + else: + return True + + def rts_smooth(self, estimates, norm_quats=False): + ''' + Returns rts smoothed results of + kalman filter estimates + + If the kalman state is augmented with + old states only the main state is smoothed + ''' + xk_n = estimates[-1][0] + Pk_n = estimates[-1][2] + Fk_1 = np.zeros(Pk_n.shape, dtype=np.float64) + + states_smoothed = [xk_n] + covs_smoothed = [Pk_n] + for k in range(len(estimates) - 2, -1, -1): + xk1_n = xk_n + if norm_quats: + xk1_n[3:7] /= np.linalg.norm(xk1_n[3:7]) + Pk1_n = Pk_n + + xk1_k, _, Pk1_k, _, t2, _, _, _, _ = estimates[k + 1] + _, xk_k, _, Pk_k, t1, _, _, _, _ = estimates[k] + dt = t2 - t1 + self.F(xk_k, dt, Fk_1) + + d1 = self.dim_main + d2 = self.dim_main_err + Ck = np.linalg.solve(Pk1_k[:d2, :d2], Fk_1[:d2, :d2].dot(Pk_k[:d2, :d2].T)).T + xk_n = xk_k + delta_x = np.zeros((Pk_n.shape[0], 1), dtype=np.float64) + self.inv_err_function(xk1_k, xk1_n, delta_x) + delta_x[:d2] = Ck.dot(delta_x[:d2]) + x_new = np.zeros((xk_n.shape[0], 1), dtype=np.float64) + self.err_function(xk_k, delta_x, x_new) + xk_n[:d1] = x_new[:d1, 0] + Pk_n = Pk_k + Pk_n[:d2, :d2] = Pk_k[:d2, :d2] + Ck.dot(Pk1_n[:d2, :d2] - Pk1_k[:d2, :d2]).dot(Ck.T) + states_smoothed.append(xk_n) + covs_smoothed.append(Pk_n) + + return np.flipud(np.vstack(states_smoothed)), np.stack(covs_smoothed, 0)[::-1] diff --git a/rednose/helpers/feature_handler.py b/rednose/helpers/feature_handler.py new file mode 100755 index 0000000..f76235d --- /dev/null +++ b/rednose/helpers/feature_handler.py @@ -0,0 +1,166 @@ +#!/usr/bin/env python3 + +import os + +import numpy as np + +from rednose.helpers import (TEMPLATE_DIR, load_code, write_code) +from rednose.helpers.sympy_helpers import quat_matrix_l + + +def rot_matrix(roll, pitch, yaw): + cr, sr = np.cos(roll), np.sin(roll) + cp, sp = np.cos(pitch), np.sin(pitch) + cy, sy = np.cos(yaw), np.sin(yaw) + rr = np.array([[1,0,0],[0, cr,-sr],[0, sr, cr]]) + rp = np.array([[cp,0,sp],[0, 1,0],[-sp, 0, cp]]) + ry = np.array([[cy,-sy,0],[sy, cy,0],[0, 0, 1]]) + return ry.dot(rp.dot(rr)) + + +def sane(track): + img_pos = track[1:, 2:4] + diffs_x = abs(img_pos[1:, 0] - img_pos[:-1, 0]) + diffs_y = abs(img_pos[1:, 1] - img_pos[:-1, 1]) + for i in range(1, len(diffs_x)): + if ((diffs_x[i] > 0.05 or diffs_x[i - 1] > 0.05) and + (diffs_x[i] > 2 * diffs_x[i - 1] or + diffs_x[i] < .5 * diffs_x[i - 1])) or \ + ((diffs_y[i] > 0.05 or diffs_y[i - 1] > 0.05) and + (diffs_y[i] > 2 * diffs_y[i - 1] or + diffs_y[i] < .5 * diffs_y[i - 1])): + return False + return True + + +class FeatureHandler(): + name = 'feature_handler' + + @staticmethod + def generate_code(K=5): + # Wrap c code for slow matching + c_header = "\nvoid merge_features(double *tracks, double *features, long long *empty_idxs);" + + c_code = "#include \n" + c_code += "#include \n" + c_code += "#define K %d\n" % K + c_code += "\n" + open(os.path.join(TEMPLATE_DIR, "feature_handler.c")).read() + + filename = f"{FeatureHandler.name}_{K}" + write_code(filename, c_code, c_header) + + def __init__(self, K=5): + self.MAX_TRACKS = 6000 + self.K = K + + # Array of tracks, each track has K 5D features preceded + # by 5 params that inidicate [f_idx, last_idx, updated, complete, valid] + # f_idx: idx of current last feature in track + # idx of of last feature in frame + # bool for whether this track has been update + # bool for whether this track is complete + # bool for whether this track is valid + self.tracks = np.zeros((self.MAX_TRACKS, K + 1, 5)) + self.tracks[:] = np.nan + + name = f"{FeatureHandler.name}_{K}" + ffi, lib = load_code(name) + + def merge_features_c(tracks, features, empty_idxs): + lib.merge_features(ffi.cast("double *", tracks.ctypes.data), + ffi.cast("double *", features.ctypes.data), + ffi.cast("long long *", empty_idxs.ctypes.data)) + + # self.merge_features = self.merge_features_python + self.merge_features = merge_features_c + + def reset(self): + self.tracks[:] = np.nan + + def merge_features_python(self, tracks, features, empty_idxs): + empty_idx = 0 + for f in features: + match_idx = int(f[4]) + if tracks[match_idx, 0, 1] == match_idx and tracks[match_idx, 0, 2] == 0: + tracks[match_idx, 0, 0] += 1 + tracks[match_idx, 0, 1] = f[1] + tracks[match_idx, 0, 2] = 1 + tracks[match_idx, int(tracks[match_idx, 0, 0])] = f + if tracks[match_idx, 0, 0] == self.K: + tracks[match_idx, 0, 3] = 1 + if sane(tracks[match_idx]): + tracks[match_idx, 0, 4] = 1 + else: + if empty_idx == len(empty_idxs): + print('need more empty space') + continue + tracks[empty_idxs[empty_idx], 0, 0] = 1 + tracks[empty_idxs[empty_idx], 0, 1] = f[1] + tracks[empty_idxs[empty_idx], 0, 2] = 1 + tracks[empty_idxs[empty_idx], 1] = f + empty_idx += 1 + + def update_tracks(self, features): + last_idxs = np.copy(self.tracks[:, 0, 1]) + real = np.isfinite(last_idxs) + self.tracks[last_idxs[real].astype(int)] = self.tracks[real] + + mask = np.ones(self.MAX_TRACKS, np.bool) + mask[last_idxs[real].astype(int)] = 0 + empty_idxs = np.arange(self.MAX_TRACKS)[mask] + + self.tracks[empty_idxs] = np.nan + self.tracks[:, 0, 2] = 0 + self.merge_features(self.tracks, features, empty_idxs) + + def handle_features(self, features): + self.update_tracks(features) + valid_idxs = self.tracks[:, 0, 4] == 1 + complete_idxs = self.tracks[:, 0, 3] == 1 + stale_idxs = self.tracks[:, 0, 2] == 0 + valid_tracks = self.tracks[valid_idxs] + self.tracks[complete_idxs] = np.nan + self.tracks[stale_idxs] = np.nan + return valid_tracks[:, 1:, :4].reshape((len(valid_tracks), self.K * 4)) + + +def generate_orient_error_jac(K): + import sympy as sp + from rednose.helpers.sympy_helpers import quat_rotate + + x_sym = sp.MatrixSymbol('abr', 3, 1) + dtheta = sp.MatrixSymbol('dtheta', 3, 1) + delta_quat = sp.Matrix(np.ones(4)) + delta_quat[1:, :] = sp.Matrix(0.5 * dtheta[0:3, :]) + poses_sym = sp.MatrixSymbol('poses', 7 * K, 1) + img_pos_sym = sp.MatrixSymbol('img_positions', 2 * K, 1) + alpha, beta, rho = x_sym + to_c = sp.Matrix(rot_matrix(-np.pi / 2, -np.pi / 2, 0)) + pos_0 = sp.Matrix(np.array(poses_sym[K * 7 - 7:K * 7 - 4])[:, 0]) + q = quat_matrix_l(poses_sym[K * 7 - 4:K * 7]) * delta_quat + quat_rot = quat_rotate(*q) + rot_g_to_0 = to_c * quat_rot.T + rows = [] + for i in range(K): + pos_i = sp.Matrix(np.array(poses_sym[i * 7:i * 7 + 3])[:, 0]) + q = quat_matrix_l(poses_sym[7 * i + 3:7 * i + 7]) * delta_quat + quat_rot = quat_rotate(*q) + rot_g_to_i = to_c * quat_rot.T + rot_0_to_i = rot_g_to_i * (rot_g_to_0.T) + trans_0_to_i = rot_g_to_i * (pos_0 - pos_i) + funct_vec = rot_0_to_i * sp.Matrix([alpha, beta, 1]) + rho * trans_0_to_i + h1, h2, h3 = funct_vec + rows.append(h1 / h3 - img_pos_sym[i * 2 + 0]) + rows.append(h2 / h3 - img_pos_sym[i * 2 + 1]) + img_pos_residual_sym = sp.Matrix(rows) + + # sympy into c + sympy_functions = [] + sympy_functions.append(('orient_error_jac', img_pos_residual_sym.jacobian(dtheta), [x_sym, poses_sym, img_pos_sym, dtheta])) + + return sympy_functions + + +if __name__ == "__main__": + # TODO: get K from argparse + FeatureHandler.generate_code() diff --git a/rednose/helpers/lst_sq_computer.py b/rednose/helpers/lst_sq_computer.py new file mode 100755 index 0000000..d32f9c4 --- /dev/null +++ b/rednose/helpers/lst_sq_computer.py @@ -0,0 +1,173 @@ +#!/usr/bin/env python3 +import os +import sys + +import numpy as np +import sympy as sp + +import common.transformations.orientation as orient +from rednose.helpers import (TEMPLATE_DIR, load_code, write_code) +from rednose.helpers.sympy_helpers import (quat_rotate, sympy_into_c) + + +def generate_residual(K): + x_sym = sp.MatrixSymbol('abr', 3, 1) + poses_sym = sp.MatrixSymbol('poses', 7 * K, 1) + img_pos_sym = sp.MatrixSymbol('img_positions', 2 * K, 1) + alpha, beta, rho = x_sym + to_c = sp.Matrix(orient.rot_matrix(-np.pi / 2, -np.pi / 2, 0)) + pos_0 = sp.Matrix(np.array(poses_sym[K * 7 - 7:K * 7 - 4])[:, 0]) + q = poses_sym[K * 7 - 4:K * 7] + quat_rot = quat_rotate(*q) + rot_g_to_0 = to_c * quat_rot.T + rows = [] + + for i in range(K): + pos_i = sp.Matrix(np.array(poses_sym[i * 7:i * 7 + 3])[:, 0]) + q = poses_sym[7 * i + 3:7 * i + 7] + quat_rot = quat_rotate(*q) + rot_g_to_i = to_c * quat_rot.T + rot_0_to_i = rot_g_to_i * rot_g_to_0.T + trans_0_to_i = rot_g_to_i * (pos_0 - pos_i) + funct_vec = rot_0_to_i * sp.Matrix([alpha, beta, 1]) + rho * trans_0_to_i + h1, h2, h3 = funct_vec + rows.append(h1 / h3 - img_pos_sym[i * 2 + 0]) + rows.append(h2 / h3 - img_pos_sym[i * 2 + 1]) + img_pos_residual_sym = sp.Matrix(rows) + + # sympy into c + sympy_functions = [] + sympy_functions.append(('res_fun', img_pos_residual_sym, [x_sym, poses_sym, img_pos_sym])) + sympy_functions.append(('jac_fun', img_pos_residual_sym.jacobian(x_sym), [x_sym, poses_sym, img_pos_sym])) + + return sympy_functions + + +class LstSqComputer(): + name = 'pos_computer' + + @staticmethod + def generate_code(K=4): + sympy_functions = generate_residual(K) + header, code = sympy_into_c(sympy_functions) + + code += "\n#define KDIM %d\n" % K + code += "\n" + open(os.path.join(TEMPLATE_DIR, "compute_pos.c")).read() + + header += """ + void compute_pos(double *to_c, double *in_poses, double *in_img_positions, double *param, double *pos); + """ + + filename = f"{LstSqComputer.name}_{K}" + write_code(filename, code, header) + + def __init__(self, K=4, MIN_DEPTH=2, MAX_DEPTH=500): + self.to_c = orient.rot_matrix(-np.pi / 2, -np.pi / 2, 0) + self.MAX_DEPTH = MAX_DEPTH + self.MIN_DEPTH = MIN_DEPTH + + name = f"{LstSqComputer.name}_{K}" + ffi, lib = load_code(name) + + # wrap c functions + def residual_jac(x, poses, img_positions): + out = np.zeros(((K * 2, 3)), dtype=np.float64) + lib.jac_fun(ffi.cast("double *", x.ctypes.data), + ffi.cast("double *", poses.ctypes.data), + ffi.cast("double *", img_positions.ctypes.data), + ffi.cast("double *", out.ctypes.data)) + return out + self.residual_jac = residual_jac + + def residual(x, poses, img_positions): + out = np.zeros((K * 2), dtype=np.float64) + lib.res_fun(ffi.cast("double *", x.ctypes.data), + ffi.cast("double *", poses.ctypes.data), + ffi.cast("double *", img_positions.ctypes.data), + ffi.cast("double *", out.ctypes.data)) + return out + self.residual = residual + + def compute_pos_c(poses, img_positions): + pos = np.zeros(3, dtype=np.float64) + param = np.zeros(3, dtype=np.float64) + # Can't be a view for the ctype + img_positions = np.copy(img_positions) + lib.compute_pos(ffi.cast("double *", self.to_c.ctypes.data), + ffi.cast("double *", poses.ctypes.data), + ffi.cast("double *", img_positions.ctypes.data), + ffi.cast("double *", param.ctypes.data), + ffi.cast("double *", pos.ctypes.data)) + return pos, param + self.compute_pos_c = compute_pos_c + + def compute_pos(self, poses, img_positions, debug=False): + pos, param = self.compute_pos_c(poses, img_positions) + # pos, param = self.compute_pos_python(poses, img_positions) + + depth = 1 / param[2] + if debug: + # orient_err_jac = self.orient_error_jac(param, poses, img_positions, np.zeros(3)).reshape((-1,2,3)) + jac = self.residual_jac(param, poses, img_positions).reshape((-1, 2, 3)) + res = self.residual(param, poses, img_positions).reshape((-1, 2)) + return pos, param, res, jac # , orient_err_jac + elif (self.MIN_DEPTH < depth < self.MAX_DEPTH): + return pos + else: + return None + + def gauss_newton(self, fun, jac, x, args): + poses, img_positions = args + delta = 1 + counter = 0 + while abs(np.linalg.norm(delta)) > 1e-4 and counter < 30: + delta = np.linalg.pinv(jac(x, poses, img_positions)).dot(fun(x, poses, img_positions)) + x = x - delta + counter += 1 + return [x] + + def compute_pos_python(self, poses, img_positions, check_quality=False): + import scipy.optimize as opt + + # This procedure is also described + # in the MSCKF paper (Mourikis et al. 2007) + x = np.array([img_positions[-1][0], + img_positions[-1][1], 0.1]) + res = opt.leastsq(self.residual, x, Dfun=self.residual_jac, args=(poses, img_positions)) # scipy opt + # res = self.gauss_newton(self.residual, self.residual_jac, x, (poses, img_positions)) # diy gauss_newton + + alpha, beta, rho = res[0] + rot_0_to_g = (orient.rotations_from_quats(poses[-1, 3:])).dot(self.to_c.T) + return (rot_0_to_g.dot(np.array([alpha, beta, 1]))) / rho + poses[-1, :3] + + +# EXPERIMENTAL CODE +def unroll_shutter(img_positions, poses, v, rot_rates, ecef_pos): + # only speed correction for now + t_roll = 0.016 # 16ms rolling shutter? + vroll, vpitch, vyaw = rot_rates + A = 0.5 * np.array([[-1, -vroll, -vpitch, -vyaw], + [vroll, 0, vyaw, -vpitch], + [vpitch, -vyaw, 0, vroll], + [vyaw, vpitch, -vroll, 0]]) + q_dot = A.dot(poses[-1][3:7]) + v = np.append(v, q_dot) + v = np.array([v[0], v[1], v[2], 0, 0, 0, 0]) + current_pose = poses[-1] + v * 0.05 + poses = np.vstack((current_pose, poses)) + dt = -img_positions[:, 1] * t_roll / 0.48 + errs = project(poses, ecef_pos) - project(poses + np.atleast_2d(dt).T.dot(np.atleast_2d(v)), ecef_pos) + return img_positions - errs + + +def project(poses, ecef_pos): + img_positions = np.zeros((len(poses), 2)) + for i, p in enumerate(poses): + cam_frame = orient.rotations_from_quats(p[3:]).T.dot(ecef_pos - p[:3]) + img_positions[i] = np.array([cam_frame[1] / cam_frame[0], cam_frame[2] / cam_frame[0]]) + return img_positions + + +if __name__ == "__main__": + K = int(sys.argv[1].split("_")[-1]) + LstSqComputer.generate_code(K=K) diff --git a/rednose/helpers/sympy_helpers.py b/rednose/helpers/sympy_helpers.py new file mode 100644 index 0000000..dee9fb3 --- /dev/null +++ b/rednose/helpers/sympy_helpers.py @@ -0,0 +1,90 @@ +#!/usr/bin/env python3 +import sympy as sp +import numpy as np + + +def cross(x): + ret = sp.Matrix(np.zeros((3, 3))) + ret[0, 1], ret[0, 2] = -x[2], x[1] + ret[1, 0], ret[1, 2] = x[2], -x[0] + ret[2, 0], ret[2, 1] = -x[1], x[0] + return ret + + +def euler_rotate(roll, pitch, yaw): + # make symbolic rotation matrix from eulers + matrix_roll = sp.Matrix([[1, 0, 0], + [0, sp.cos(roll), -sp.sin(roll)], + [0, sp.sin(roll), sp.cos(roll)]]) + matrix_pitch = sp.Matrix([[sp.cos(pitch), 0, sp.sin(pitch)], + [0, 1, 0], + [-sp.sin(pitch), 0, sp.cos(pitch)]]) + matrix_yaw = sp.Matrix([[sp.cos(yaw), -sp.sin(yaw), 0], + [sp.sin(yaw), sp.cos(yaw), 0], + [0, 0, 1]]) + return matrix_yaw * matrix_pitch * matrix_roll + + +def quat_rotate(q0, q1, q2, q3): + # make symbolic rotation matrix from quat + return sp.Matrix([[q0**2 + q1**2 - q2**2 - q3**2, 2 * (q1 * q2 + q0 * q3), 2 * (q1 * q3 - q0 * q2)], + [2 * (q1 * q2 - q0 * q3), q0**2 - q1**2 + q2**2 - q3**2, 2 * (q2 * q3 + q0 * q1)], + [2 * (q1 * q3 + q0 * q2), 2 * (q2 * q3 - q0 * q1), q0**2 - q1**2 - q2**2 + q3**2]]).T + + +def quat_matrix_l(p): + return sp.Matrix([[p[0], -p[1], -p[2], -p[3]], + [p[1], p[0], -p[3], p[2]], + [p[2], p[3], p[0], -p[1]], + [p[3], -p[2], p[1], p[0]]]) + + +def quat_matrix_r(p): + return sp.Matrix([[p[0], -p[1], -p[2], -p[3]], + [p[1], p[0], p[3], -p[2]], + [p[2], -p[3], p[0], p[1]], + [p[3], p[2], -p[1], p[0]]]) + + +def sympy_into_c(sympy_functions, global_vars=None): + from sympy.utilities import codegen + routines = [] + for name, expr, args in sympy_functions: + r = codegen.make_routine(name, expr, language="C99", global_vars=global_vars) + + # argument ordering input to sympy is broken with function with output arguments + nargs = [] + + # reorder the input arguments + for aa in args: + if aa is None: + nargs.append(codegen.InputArgument(sp.Symbol('unused'), dimensions=[1, 1])) + continue + found = False + for a in r.arguments: + if str(aa.name) == str(a.name): + nargs.append(a) + found = True + break + if not found: + # [1,1] is a hack for Matrices + nargs.append(codegen.InputArgument(aa, dimensions=[1, 1])) + + # add the output arguments + for a in r.arguments: + if type(a) == codegen.OutputArgument: + nargs.append(a) + + # assert len(r.arguments) == len(args)+1 + r.arguments = nargs + + # add routine to list + routines.append(r) + + [(c_name, c_code), (h_name, c_header)] = codegen.get_code_generator('C', 'ekf', 'C99').write(routines, "ekf") + c_header = '\n'.join(x for x in c_header.split("\n") if len(x) > 0 and x[0] != '#') + + c_code = '\n'.join(x for x in c_code.split("\n") if len(x) > 0 and x[0] != '#') + c_code = 'extern "C" {\n#include \n' + c_code + "\n}\n" + + return c_header, c_code diff --git a/rednose/templates/compute_pos.c b/rednose/templates/compute_pos.c new file mode 100644 index 0000000..3c7b16e --- /dev/null +++ b/rednose/templates/compute_pos.c @@ -0,0 +1,54 @@ +#include +#include +#include + +typedef Eigen::Matrix R3M; +typedef Eigen::Matrix R1M; +typedef Eigen::Matrix O1M; +typedef Eigen::Matrix M3D; + +extern "C" { +void gauss_newton(double *in_x, double *in_poses, double *in_img_positions) { + + double res[KDIM*2] = {0}; + double jac[KDIM*6] = {0}; + + O1M x(in_x); + O1M delta; + int counter = 0; + while ((delta.squaredNorm() > 0.0001 and counter < 30) or counter == 0){ + res_fun(in_x, in_poses, in_img_positions, res); + jac_fun(in_x, in_poses, in_img_positions, jac); + R1M E(res); R3M J(jac); + delta = (J.transpose()*J).inverse() * J.transpose() * E; + x = x - delta; + memcpy(in_x, x.data(), 3 * sizeof(double)); + counter = counter + 1; + } +} + + +void compute_pos(double *to_c, double *poses, double *img_positions, double *param, double *pos) { + param[0] = img_positions[KDIM*2-2]; + param[1] = img_positions[KDIM*2-1]; + param[2] = 0.1; + gauss_newton(param, poses, img_positions); + + Eigen::Quaterniond q; + q.w() = poses[KDIM*7-4]; + q.x() = poses[KDIM*7-3]; + q.y() = poses[KDIM*7-2]; + q.z() = poses[KDIM*7-1]; + M3D RC(to_c); + Eigen::Matrix3d R = q.normalized().toRotationMatrix(); + Eigen::Matrix3d rot = R * RC.transpose(); + + pos[0] = param[0]/param[2]; + pos[1] = param[1]/param[2]; + pos[2] = 1.0/param[2]; + O1M ecef_offset(poses + KDIM*7-7); + O1M ecef_output(pos); + ecef_output = rot*ecef_output + ecef_offset; + memcpy(pos, ecef_output.data(), 3 * sizeof(double)); +} +} diff --git a/rednose/templates/ekf_c.c b/rednose/templates/ekf_c.c new file mode 100644 index 0000000..e524f81 --- /dev/null +++ b/rednose/templates/ekf_c.c @@ -0,0 +1,123 @@ +#include +#include + +typedef Eigen::Matrix DDM; +typedef Eigen::Matrix EEM; +typedef Eigen::Matrix DEM; + +void predict(double *in_x, double *in_P, double *in_Q, double dt) { + typedef Eigen::Matrix RRM; + + double nx[DIM] = {0}; + double in_F[EDIM*EDIM] = {0}; + + // functions from sympy + f_fun(in_x, dt, nx); + F_fun(in_x, dt, in_F); + + + EEM F(in_F); + EEM P(in_P); + EEM Q(in_Q); + + RRM F_main = F.topLeftCorner(MEDIM, MEDIM); + P.topLeftCorner(MEDIM, MEDIM) = (F_main * P.topLeftCorner(MEDIM, MEDIM)) * F_main.transpose(); + P.topRightCorner(MEDIM, EDIM - MEDIM) = F_main * P.topRightCorner(MEDIM, EDIM - MEDIM); + P.bottomLeftCorner(EDIM - MEDIM, MEDIM) = P.bottomLeftCorner(EDIM - MEDIM, MEDIM) * F_main.transpose(); + + P = P + dt*Q; + + // copy out state + memcpy(in_x, nx, DIM * sizeof(double)); + memcpy(in_P, P.data(), EDIM * EDIM * sizeof(double)); +} + +// note: extra_args dim only correct when null space projecting +// otherwise 1 +template +void update(double *in_x, double *in_P, Hfun h_fun, Hfun H_fun, Hfun Hea_fun, double *in_z, double *in_R, double *in_ea, double MAHA_THRESHOLD) { + typedef Eigen::Matrix ZZM; + typedef Eigen::Matrix ZDM; + typedef Eigen::Matrix XEM; + //typedef Eigen::Matrix EZM; + typedef Eigen::Matrix X1M; + typedef Eigen::Matrix XXM; + + double in_hx[ZDIM] = {0}; + double in_H[ZDIM * DIM] = {0}; + double in_H_mod[EDIM * DIM] = {0}; + double delta_x[EDIM] = {0}; + double x_new[DIM] = {0}; + + + // state x, P + Eigen::Matrix z(in_z); + EEM P(in_P); + ZZM pre_R(in_R); + + // functions from sympy + h_fun(in_x, in_ea, in_hx); + H_fun(in_x, in_ea, in_H); + ZDM pre_H(in_H); + + // get y (y = z - hx) + Eigen::Matrix pre_y(in_hx); pre_y = z - pre_y; + X1M y; XXM H; XXM R; + if (Hea_fun){ + typedef Eigen::Matrix ZAM; + double in_Hea[ZDIM * EADIM] = {0}; + Hea_fun(in_x, in_ea, in_Hea); + ZAM Hea(in_Hea); + XXM A = Hea.transpose().fullPivLu().kernel(); + + + y = A.transpose() * pre_y; + H = A.transpose() * pre_H; + R = A.transpose() * pre_R * A; + } else { + y = pre_y; + H = pre_H; + R = pre_R; + } + // get modified H + H_mod_fun(in_x, in_H_mod); + DEM H_mod(in_H_mod); + XEM H_err = H * H_mod; + + // Do mahalobis distance test + if (MAHA_TEST){ + XXM a = (H_err * P * H_err.transpose() + R).inverse(); + double maha_dist = y.transpose() * a * y; + if (maha_dist > MAHA_THRESHOLD){ + R = 1.0e16 * R; + } + } + + // Outlier resilient weighting + double weight = 1;//(1.5)/(1 + y.squaredNorm()/R.sum()); + + // kalman gains and I_KH + XXM S = ((H_err * P) * H_err.transpose()) + R/weight; + XEM KT = S.fullPivLu().solve(H_err * P.transpose()); + //EZM K = KT.transpose(); TODO: WHY DOES THIS NOT COMPILE? + //EZM K = S.fullPivLu().solve(H_err * P.transpose()).transpose(); + //std::cout << "Here is the matrix rot:\n" << K << std::endl; + EEM I_KH = Eigen::Matrix::Identity() - (KT.transpose() * H_err); + + // update state by injecting dx + Eigen::Matrix dx(delta_x); + dx = (KT.transpose() * y); + memcpy(delta_x, dx.data(), EDIM * sizeof(double)); + err_fun(in_x, delta_x, x_new); + Eigen::Matrix x(x_new); + + // update cov + P = ((I_KH * P) * I_KH.transpose()) + ((KT.transpose() * R) * KT); + + // copy out state + memcpy(in_x, x.data(), DIM * sizeof(double)); + memcpy(in_P, P.data(), EDIM * EDIM * sizeof(double)); + memcpy(in_z, y.data(), y.rows() * sizeof(double)); +} + + diff --git a/rednose/templates/feature_handler.c b/rednose/templates/feature_handler.c new file mode 100644 index 0000000..3309723 --- /dev/null +++ b/rednose/templates/feature_handler.c @@ -0,0 +1,58 @@ +extern "C"{ +bool sane(double track [K + 1][5]) { + double diffs_x [K-1]; + double diffs_y [K-1]; + int i; + for (i = 0; i < K-1; i++) { + diffs_x[i] = fabs(track[i+2][2] - track[i+1][2]); + diffs_y[i] = fabs(track[i+2][3] - track[i+1][3]); + } + for (i = 1; i < K-1; i++) { + if (((diffs_x[i] > 0.05 or diffs_x[i-1] > 0.05) and + (diffs_x[i] > 2*diffs_x[i-1] or + diffs_x[i] < .5*diffs_x[i-1])) or + ((diffs_y[i] > 0.05 or diffs_y[i-1] > 0.05) and + (diffs_y[i] > 2*diffs_y[i-1] or + diffs_y[i] < .5*diffs_y[i-1]))){ + return false; + } + } + return true; +} + +void merge_features(double *tracks, double *features, long long *empty_idxs) { + double feature_arr [3000][5]; + memcpy(feature_arr, features, 3000 * 5 * sizeof(double)); + double track_arr [6000][K + 1][5]; + memcpy(track_arr, tracks, (K+1) * 6000 * 5 * sizeof(double)); + int match; + int empty_idx = 0; + int idx; + for (int i = 0; i < 3000; i++) { + match = feature_arr[i][4]; + if (track_arr[match][0][1] == match and track_arr[match][0][2] == 0){ + track_arr[match][0][0] = track_arr[match][0][0] + 1; + track_arr[match][0][1] = feature_arr[i][1]; + track_arr[match][0][2] = 1; + idx = track_arr[match][0][0]; + memcpy(track_arr[match][idx], feature_arr[i], 5 * sizeof(double)); + if (idx == K){ + // label complete + track_arr[match][0][3] = 1; + if (sane(track_arr[match])){ + // label valid + track_arr[match][0][4] = 1; + } + } + } else { + // gen new track with this feature + track_arr[empty_idxs[empty_idx]][0][0] = 1; + track_arr[empty_idxs[empty_idx]][0][1] = feature_arr[i][1]; + track_arr[empty_idxs[empty_idx]][0][2] = 1; + memcpy(track_arr[empty_idxs[empty_idx]][1], feature_arr[i], 5 * sizeof(double)); + empty_idx = empty_idx + 1; + } + } + memcpy(tracks, track_arr, (K+1) * 6000 * 5 * sizeof(double)); +} +} diff --git a/setup.py b/setup.py new file mode 100644 index 0000000..492b58f --- /dev/null +++ b/setup.py @@ -0,0 +1,26 @@ +import os +from setuptools import setup, find_packages + +here = os.path.abspath(os.path.dirname(__file__)) + +setup( + name='rednose', + version='0.0.1', + url='https://github.com/commaai/rednose', + author='comma.ai', + author_email='harald@comma.ai', + packages=find_packages(), + platforms='any', + license='MIT', + package_data={'': ['helpers/chi2_lookup_table.npy', 'templates/*']}, + install_requires=[ + 'sympy', + 'numpy', + 'scipy', + 'tqdm', + 'cffi', + ], + ext_modules=[], + description="Kalman filter library", + long_description='See https://github.com/commaai/rednose', +)