From 10dd7e691c48df65de852eac30e2e955f0214eed Mon Sep 17 00:00:00 2001 From: krishauser Date: Fri, 15 Dec 2023 15:17:42 -0500 Subject: [PATCH 001/232] Initial commit --- .gitignore | 160 +++++++++++++++++++++++++++++++++++++++++++++++++++++ LICENSE | 21 +++++++ README.md | 2 + 3 files changed, 183 insertions(+) create mode 100644 .gitignore create mode 100644 LICENSE create mode 100644 README.md diff --git a/.gitignore b/.gitignore new file mode 100644 index 000000000..68bc17f9f --- /dev/null +++ b/.gitignore @@ -0,0 +1,160 @@ +# 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 + +# poetry +# Similar to Pipfile.lock, it is generally recommended to include poetry.lock in version control. +# This is especially recommended for binary packages to ensure reproducibility, and is more +# commonly ignored for libraries. +# https://python-poetry.org/docs/basic-usage/#commit-your-poetrylock-file-to-version-control +#poetry.lock + +# pdm +# Similar to Pipfile.lock, it is generally recommended to include pdm.lock in version control. +#pdm.lock +# pdm stores project-wide configurations in .pdm.toml, but it is recommended to not include it +# in version control. +# https://pdm.fming.dev/#use-with-ide +.pdm.toml + +# PEP 582; used by e.g. github.com/David-OConnor/pyflow and github.com/pdm-project/pdm +__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/ + +# PyCharm +# JetBrains specific template is maintained in a separate JetBrains.gitignore that can +# be found at https://github.com/github/gitignore/blob/main/Global/JetBrains.gitignore +# and can be added to the global gitignore or merged into this file. For a more nuclear +# option (not recommended) you can uncomment the following to ignore the entire idea folder. +#.idea/ diff --git a/LICENSE b/LICENSE new file mode 100644 index 000000000..79cdf2ea5 --- /dev/null +++ b/LICENSE @@ -0,0 +1,21 @@ +MIT License + +Copyright (c) 2023 krishauser + +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 000000000..72c6bb591 --- /dev/null +++ b/README.md @@ -0,0 +1,2 @@ +# GEMstack +Educational utonomous driving stack for the Polaris GEM vehicle From 4cb8e61f8a2950d93e783a3f608a615f933e4a4b Mon Sep 17 00:00:00 2001 From: krishauser Date: Fri, 15 Dec 2023 15:22:08 -0500 Subject: [PATCH 002/232] First commit --- GEMstack/__init__.py | 0 GEMstack/knowledge/__init__.py | 0 GEMstack/knowledge/calibration/__init__.py | 0 GEMstack/knowledge/calibration/gem.yaml | 4 + GEMstack/knowledge/defaults/__init__.py | 3 + .../knowledge/defaults/computation_graph.yaml | 50 + GEMstack/knowledge/defaults/current.yaml | 30 + .../defaults/gem_control_defaults.yaml | 3 + GEMstack/knowledge/defaults/gem_dynamics.yaml | 15 + GEMstack/knowledge/defaults/gem_geometry.yaml | 5 + .../knowledge/defaults/gem_slow_limits.yaml | 8 + GEMstack/knowledge/detection/__init__.py | 0 GEMstack/knowledge/heuristics/__init__.py | 0 GEMstack/knowledge/predicates/__init__.py | 0 GEMstack/knowledge/prediction/__init__.py | 0 GEMstack/knowledge/roadmaps/__init__.py | 0 .../knowledge/roadmaps/geofences/__init__.py | 0 GEMstack/knowledge/routes/__init__.py | 0 GEMstack/knowledge/routes/xyhead_demo_pp.csv | 1279 +++++++++++++++++ .../knowledge/routes/xyhead_demo_stanley.csv | 1170 +++++++++++++++ GEMstack/knowledge/vehicle/__init__.py | 0 GEMstack/knowledge/vehicle/dynamics.py | 82 ++ GEMstack/knowledge/vehicle/geometry.py | 58 + GEMstack/launch/README.md | 1 + GEMstack/launch/fixed_route.yaml | 27 + GEMstack/launch/fixed_route_sim.yaml | 35 + GEMstack/mathutils/__init__.py | 0 GEMstack/mathutils/collisions.py | 9 + GEMstack/mathutils/control.py | 78 + GEMstack/mathutils/differences.py | 86 ++ GEMstack/mathutils/dubins.py | 117 ++ GEMstack/mathutils/dynamics.py | 221 +++ GEMstack/mathutils/signal.py | 25 + GEMstack/mathutils/transforms.py | 100 ++ GEMstack/offboard/__init__.py | 0 GEMstack/offboard/calibration/__init__.py | 0 .../offboard/detection_learning/__init__.py | 0 .../offboard/heuristic_learning/__init__.py | 0 GEMstack/offboard/log_management/__init__.py | 0 .../offboard/prediction_learning/__init__.py | 0 GEMstack/onboard/__init__.py | 0 GEMstack/onboard/component.py | 19 + GEMstack/onboard/execution/__init__.py | 0 GEMstack/onboard/execution/entrypoint.py | 133 ++ GEMstack/onboard/execution/execution.py | 321 +++++ GEMstack/onboard/execution/log_replay.py | 86 ++ .../execution/multiprocess_execution.py | 56 + GEMstack/onboard/interface/__init__.py | 0 GEMstack/onboard/interface/gem.py | 131 ++ GEMstack/onboard/interface/gem_hardware.py | 145 ++ GEMstack/onboard/interface/gem_simulator.py | 135 ++ GEMstack/onboard/perception/__init__.py | 0 .../perception/perception_normalization.py | 39 + .../onboard/perception/roadgraph_update.py | 24 + .../onboard/perception/state_estimation.py | 82 ++ GEMstack/onboard/planning/__init__.py | 0 GEMstack/onboard/planning/motion_planning.py | 24 + GEMstack/onboard/planning/pure_pursuit.py | 120 ++ GEMstack/onboard/planning/recovery.py | 37 + GEMstack/onboard/planning/route_planning.py | 33 + GEMstack/state/__init__.py | 32 + GEMstack/state/agent.py | 29 + GEMstack/state/agent_intent.py | 36 + GEMstack/state/all.py | 53 + GEMstack/state/environment.py | 27 + GEMstack/state/intent.py | 23 + GEMstack/state/mission.py | 17 + GEMstack/state/obstacle.py | 25 + GEMstack/state/physical_object.py | 307 ++++ GEMstack/state/predicates.py | 16 + GEMstack/state/relations.py | 83 ++ GEMstack/state/roadgraph.py | 221 +++ GEMstack/state/roadmap.py | 12 + GEMstack/state/route.py | 18 + GEMstack/state/scene.py | 39 + GEMstack/state/sign.py | 95 ++ GEMstack/state/trajectory.py | 167 +++ GEMstack/state/vehicle.py | 38 + GEMstack/utils/__init__.py | 0 GEMstack/utils/config.py | 87 ++ GEMstack/utils/loops.py | 285 ++++ GEMstack/utils/serialization.py | 172 +++ GEMstack/utils/settings.py | 77 + README.md | 241 +++- data/README.md | 3 + logs/README.md | 10 + main.py | 30 + pyproject.toml | 36 + requirements.txt | 8 + testing/test_poses.py | 36 + testing/test_serialization.py | 23 + 91 files changed, 7035 insertions(+), 2 deletions(-) create mode 100644 GEMstack/__init__.py create mode 100644 GEMstack/knowledge/__init__.py create mode 100644 GEMstack/knowledge/calibration/__init__.py create mode 100644 GEMstack/knowledge/calibration/gem.yaml create mode 100644 GEMstack/knowledge/defaults/__init__.py create mode 100644 GEMstack/knowledge/defaults/computation_graph.yaml create mode 100644 GEMstack/knowledge/defaults/current.yaml create mode 100644 GEMstack/knowledge/defaults/gem_control_defaults.yaml create mode 100644 GEMstack/knowledge/defaults/gem_dynamics.yaml create mode 100644 GEMstack/knowledge/defaults/gem_geometry.yaml create mode 100644 GEMstack/knowledge/defaults/gem_slow_limits.yaml create mode 100644 GEMstack/knowledge/detection/__init__.py create mode 100644 GEMstack/knowledge/heuristics/__init__.py create mode 100644 GEMstack/knowledge/predicates/__init__.py create mode 100644 GEMstack/knowledge/prediction/__init__.py create mode 100644 GEMstack/knowledge/roadmaps/__init__.py create mode 100644 GEMstack/knowledge/roadmaps/geofences/__init__.py create mode 100644 GEMstack/knowledge/routes/__init__.py create mode 100644 GEMstack/knowledge/routes/xyhead_demo_pp.csv create mode 100644 GEMstack/knowledge/routes/xyhead_demo_stanley.csv create mode 100644 GEMstack/knowledge/vehicle/__init__.py create mode 100644 GEMstack/knowledge/vehicle/dynamics.py create mode 100644 GEMstack/knowledge/vehicle/geometry.py create mode 100644 GEMstack/launch/README.md create mode 100644 GEMstack/launch/fixed_route.yaml create mode 100644 GEMstack/launch/fixed_route_sim.yaml create mode 100644 GEMstack/mathutils/__init__.py create mode 100644 GEMstack/mathutils/collisions.py create mode 100644 GEMstack/mathutils/control.py create mode 100644 GEMstack/mathutils/differences.py create mode 100644 GEMstack/mathutils/dubins.py create mode 100644 GEMstack/mathutils/dynamics.py create mode 100644 GEMstack/mathutils/signal.py create mode 100644 GEMstack/mathutils/transforms.py create mode 100644 GEMstack/offboard/__init__.py create mode 100644 GEMstack/offboard/calibration/__init__.py create mode 100644 GEMstack/offboard/detection_learning/__init__.py create mode 100644 GEMstack/offboard/heuristic_learning/__init__.py create mode 100644 GEMstack/offboard/log_management/__init__.py create mode 100644 GEMstack/offboard/prediction_learning/__init__.py create mode 100644 GEMstack/onboard/__init__.py create mode 100644 GEMstack/onboard/component.py create mode 100644 GEMstack/onboard/execution/__init__.py create mode 100644 GEMstack/onboard/execution/entrypoint.py create mode 100644 GEMstack/onboard/execution/execution.py create mode 100644 GEMstack/onboard/execution/log_replay.py create mode 100644 GEMstack/onboard/execution/multiprocess_execution.py create mode 100644 GEMstack/onboard/interface/__init__.py create mode 100644 GEMstack/onboard/interface/gem.py create mode 100644 GEMstack/onboard/interface/gem_hardware.py create mode 100644 GEMstack/onboard/interface/gem_simulator.py create mode 100644 GEMstack/onboard/perception/__init__.py create mode 100644 GEMstack/onboard/perception/perception_normalization.py create mode 100644 GEMstack/onboard/perception/roadgraph_update.py create mode 100644 GEMstack/onboard/perception/state_estimation.py create mode 100644 GEMstack/onboard/planning/__init__.py create mode 100644 GEMstack/onboard/planning/motion_planning.py create mode 100644 GEMstack/onboard/planning/pure_pursuit.py create mode 100644 GEMstack/onboard/planning/recovery.py create mode 100644 GEMstack/onboard/planning/route_planning.py create mode 100644 GEMstack/state/__init__.py create mode 100644 GEMstack/state/agent.py create mode 100644 GEMstack/state/agent_intent.py create mode 100644 GEMstack/state/all.py create mode 100644 GEMstack/state/environment.py create mode 100644 GEMstack/state/intent.py create mode 100644 GEMstack/state/mission.py create mode 100644 GEMstack/state/obstacle.py create mode 100644 GEMstack/state/physical_object.py create mode 100644 GEMstack/state/predicates.py create mode 100644 GEMstack/state/relations.py create mode 100644 GEMstack/state/roadgraph.py create mode 100644 GEMstack/state/roadmap.py create mode 100644 GEMstack/state/route.py create mode 100644 GEMstack/state/scene.py create mode 100644 GEMstack/state/sign.py create mode 100644 GEMstack/state/trajectory.py create mode 100644 GEMstack/state/vehicle.py create mode 100644 GEMstack/utils/__init__.py create mode 100644 GEMstack/utils/config.py create mode 100644 GEMstack/utils/loops.py create mode 100644 GEMstack/utils/serialization.py create mode 100644 GEMstack/utils/settings.py create mode 100644 data/README.md create mode 100644 logs/README.md create mode 100644 main.py create mode 100644 pyproject.toml create mode 100644 requirements.txt create mode 100644 testing/test_poses.py create mode 100644 testing/test_serialization.py diff --git a/GEMstack/__init__.py b/GEMstack/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/GEMstack/knowledge/__init__.py b/GEMstack/knowledge/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/GEMstack/knowledge/calibration/__init__.py b/GEMstack/knowledge/calibration/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/GEMstack/knowledge/calibration/gem.yaml b/GEMstack/knowledge/calibration/gem.yaml new file mode 100644 index 000000000..c6d1a9517 --- /dev/null +++ b/GEMstack/knowledge/calibration/gem.yaml @@ -0,0 +1,4 @@ +reference: rear_axle_center +gnss_location: [1.1,0.0] # meters +gnss_yaw: 0.0 # radians + diff --git a/GEMstack/knowledge/defaults/__init__.py b/GEMstack/knowledge/defaults/__init__.py new file mode 100644 index 000000000..eb94606e6 --- /dev/null +++ b/GEMstack/knowledge/defaults/__init__.py @@ -0,0 +1,3 @@ +from ...utils.config import load_config_recursive +import os +SETTINGS = load_config_recursive(os.path.join(os.path.split(__file__)[0],'current.yaml')) diff --git a/GEMstack/knowledge/defaults/computation_graph.yaml b/GEMstack/knowledge/defaults/computation_graph.yaml new file mode 100644 index 000000000..01e3d987a --- /dev/null +++ b/GEMstack/knowledge/defaults/computation_graph.yaml @@ -0,0 +1,50 @@ +#lists the components in order. +#Defines the permissable inputs and outputs for each component. +#The actual implementation of the components must use a subset of these inputs +#and must generate a superset of these outputs. +components: + - state_estimation: + outputs: vehicle + - roadgraph_update: + inputs: vehicle + outputs: roadgraph + - obstacle_detection: + inputs: vehicle + outputs: obstacles + - agent_detection: + inputs: vehicle + outputs: agents + - lane_detection: + inputs: [vehicle, roadgraph] + outputs: vehicle_lane + - sign_detection: + inputs: [vehicle, roadgraph] + outputs: roadgraph.signs + - environment_detection: + inputs: vehicle + outputs: environment + - intent_estimation: + inputs: [vehicle, roadgraph, agents] + outputs: agent_intents + - relations_estimation: + inputs: [vehicle, roadgraph, agents, obstacles] + outputs: relations + - predicate_evaluation: + inputs: [vehicle, roadgraph, agents, obstacles] + outputs: predicates + - perception_normalization: + inputs: all + - mission_execution: + outputs: mission + - route_planning: + inputs: [vehicle, roadgraph, mission] + outputs: route + - driving_logic: + inputs: all + outputs: intent + - motion_planning: + inputs: all + outputs: trajectory + - trajectory_tracking: + inputs: [vehicle, trajectory] + outputs: diff --git a/GEMstack/knowledge/defaults/current.yaml b/GEMstack/knowledge/defaults/current.yaml new file mode 100644 index 000000000..6f813513c --- /dev/null +++ b/GEMstack/knowledge/defaults/current.yaml @@ -0,0 +1,30 @@ +# Configure settings for the vehicle / vehicle model +vehicle: + name: GEM + version: e2 + max_gear : 1 + num_wiper_settings : 1 + #using !include directives helps maintain reuse of common settings + geometry: !include gem_geometry.yaml + dynamics: !include gem_dynamics.yaml + limits: !include gem_slow_limits.yaml + control_defaults: !include gem_control_defaults.yaml + calibration: !include ../calibration/gem.yaml + +#arguments for algorithm components here +mission_executor: + frequency: 0.5 +model_predictive_controller: + frequency: 0.1 +control: + recovery: + brake_amount : 0.5 + brake_speed : 2.0 + pure_pursuit: + lookahead: 4.0 + lookahead_scale: 3.0 + crosstrack_gain: 0.41 + +simulator: + dt: 0.01 + real_time_multiplier: 1.0 # make the simulator run faster than real time by making this > 1 diff --git a/GEMstack/knowledge/defaults/gem_control_defaults.yaml b/GEMstack/knowledge/defaults/gem_control_defaults.yaml new file mode 100644 index 000000000..3f81bc831 --- /dev/null +++ b/GEMstack/knowledge/defaults/gem_control_defaults.yaml @@ -0,0 +1,3 @@ +brake_pedal_speed : 3.0 +accelerator_pedal_speed : 3.0 +steering_wheel_speed : 2.0 diff --git a/GEMstack/knowledge/defaults/gem_dynamics.yaml b/GEMstack/knowledge/defaults/gem_dynamics.yaml new file mode 100644 index 000000000..ccb878508 --- /dev/null +++ b/GEMstack/knowledge/defaults/gem_dynamics.yaml @@ -0,0 +1,15 @@ +mass: 200.0 #kg +gravity: 9.81 #m/s^2 +longitudinal_friction : 1.0 # unitless +lateral_friction : 1.0 # unitless +max_brake_deceleration: 2.0 #m/s^2. Deceleration at max brake pedal +max_accelerator_acceleration: #m/s^2. Acceleration at max accelerator pedal, by gear + - 0.0 + - 2.5 +max_accelerator_acceleration_reverse: 2.5 #m/s^2. Acceleration (backwards) in reverse gear +max_accelerator_power: #Watts. Power at max accelerator pedal, by gear + - 0.0 + - 10000.0 +max_accelerator_power_reverse: 10000.0 #Watts. Power (backwards) in reverse gear +internal_viscous_deceleration: 0.2 #1/s: scales the current velocity to get deceleration due to internal viscous friction +aerodynamic_drag_coefficient: 0.3 #unitless diff --git a/GEMstack/knowledge/defaults/gem_geometry.yaml b/GEMstack/knowledge/defaults/gem_geometry.yaml new file mode 100644 index 000000000..1c307ab70 --- /dev/null +++ b/GEMstack/knowledge/defaults/gem_geometry.yaml @@ -0,0 +1,5 @@ +wheelbase: 1.4 #distance from rear to front axle, meters +min_wheel_angle: -0.6108 #radians, 35 degrees +max_wheel_angle: 0.6108 #radians, 35 degrees +min_steering_angle: -11.0 #radians, 630 degrees +max_steering_angle: 11.0 #radians, 630 degrees \ No newline at end of file diff --git a/GEMstack/knowledge/defaults/gem_slow_limits.yaml b/GEMstack/knowledge/defaults/gem_slow_limits.yaml new file mode 100644 index 000000000..ae7aaf77c --- /dev/null +++ b/GEMstack/knowledge/defaults/gem_slow_limits.yaml @@ -0,0 +1,8 @@ +max_steering_rate: 2.0 #radians/s +max_speed: 0.5 #m/s +max_reverse_speed: 0.1 #m/s +max_acceleration: 1.0 #m/s^2 +max_deceleration: 2.0 #m/s^2 +max_accelerator_pedal: 0.5 #0-1 +max_brake_pedal: 1.0 #0-1 + diff --git a/GEMstack/knowledge/detection/__init__.py b/GEMstack/knowledge/detection/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/GEMstack/knowledge/heuristics/__init__.py b/GEMstack/knowledge/heuristics/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/GEMstack/knowledge/predicates/__init__.py b/GEMstack/knowledge/predicates/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/GEMstack/knowledge/prediction/__init__.py b/GEMstack/knowledge/prediction/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/GEMstack/knowledge/roadmaps/__init__.py b/GEMstack/knowledge/roadmaps/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/GEMstack/knowledge/roadmaps/geofences/__init__.py b/GEMstack/knowledge/roadmaps/geofences/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/GEMstack/knowledge/routes/__init__.py b/GEMstack/knowledge/routes/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/GEMstack/knowledge/routes/xyhead_demo_pp.csv b/GEMstack/knowledge/routes/xyhead_demo_pp.csv new file mode 100644 index 000000000..bc8cb09e6 --- /dev/null +++ b/GEMstack/knowledge/routes/xyhead_demo_pp.csv @@ -0,0 +1,1279 @@ +-0.128,-0.002,88.449 +-0.128,-0.002,88.448 +-0.128,-0.002,88.446 +-0.128,-0.002,88.443 +-0.128,-0.002,88.445 +-0.129,-0.002,88.446 +-0.129,-0.002,88.444 +-0.129,-0.002,88.443 +-0.129,-0.002,88.444 +-0.129,-0.002,88.444 +-0.129,-0.002,88.448 +-0.129,-0.002,88.45 +-0.129,-0.002,88.45 +-0.129,-0.002,88.448 +-0.129,-0.002,88.451 +-0.129,-0.002,88.456 +-0.129,-0.002,88.452 +-0.129,-0.002,88.455 +-0.128,-0.002,88.46 +-0.128,-0.001,88.461 +-0.054,0.024,88.463 +-0.034,0.025,88.469 +-0.011,0.027,88.473 +0.016,0.029,88.475 +0.046,0.031,88.482 +0.081,0.032,88.487 +0.119,0.034,88.495 +0.16,0.036,88.504 +0.205,0.038,88.511 +0.224,0.039,88.513 +0.303,0.043,88.543 +0.356,0.048,88.543 +0.411,0.052,88.545 +0.467,0.057,88.55 +0.525,0.061,88.558 +0.585,0.066,88.562 +0.646,0.071,88.567 +0.708,0.075,88.572 +0.773,0.08,88.58 +0.799,0.082,88.584 +0.908,0.089,88.635 +0.978,0.091,88.64 +1.05,0.094,88.641 +1.124,0.097,88.639 +1.199,0.099,88.646 +1.275,0.102,88.652 +1.353,0.105,88.656 +1.431,0.108,88.673 +1.511,0.111,88.696 +1.543,0.112,88.697 +1.674,0.116,88.728 +1.758,0.119,88.754 +1.841,0.121,88.765 +1.926,0.124,88.778 +2.01,0.126,88.799 +2.094,0.128,88.806 +2.178,0.13,88.805 +2.261,0.132,88.812 +2.345,0.134,88.825 +2.379,0.135,88.832 +2.515,0.138,88.881 +2.601,0.139,88.885 +2.688,0.141,88.886 +2.775,0.142,88.89 +2.863,0.144,88.895 +2.952,0.145,88.897 +3.042,0.146,88.911 +3.132,0.148,88.915 +3.224,0.149,88.932 +3.261,0.15,88.941 +3.411,0.151,88.985 +3.506,0.152,89.003 +3.602,0.154,89.04 +3.699,0.155,89.052 +3.796,0.155,89.051 +3.894,0.156,89.068 +3.992,0.157,89.081 +4.091,0.157,89.073 +4.192,0.158,89.087 +4.232,0.158,89.097 +4.395,0.16,89.09 +4.498,0.161,89.085 +4.601,0.162,89.096 +4.705,0.162,89.096 +4.81,0.163,89.101 +4.916,0.164,89.113 +5.023,0.166,89.141 +5.132,0.167,89.162 +5.241,0.168,89.168 +5.285,0.168,89.176 +5.462,0.17,89.218 +5.573,0.171,89.226 +5.685,0.172,89.238 +5.798,0.173,89.253 +5.912,0.173,89.262 +6.027,0.174,89.268 +6.143,0.175,89.272 +6.259,0.176,89.277 +6.376,0.176,89.281 +6.423,0.176,89.284 +6.613,0.179,89.288 +6.733,0.181,89.297 +6.855,0.184,89.326 +6.977,0.185,89.344 +7.1,0.187,89.365 +7.225,0.189,89.39 +7.349,0.191,89.408 +7.475,0.193,89.428 +7.601,0.195,89.437 +7.652,0.196,89.437 +7.858,0.198,89.456 +7.987,0.199,89.461 +8.118,0.2,89.45 +8.249,0.201,89.468 +8.382,0.202,89.481 +8.515,0.203,89.476 +8.649,0.204,89.519 +8.785,0.206,89.559 +8.92,0.207,89.581 +8.974,0.207,89.587 +9.192,0.208,89.625 +9.328,0.209,89.633 +9.466,0.209,89.63 +9.604,0.21,89.653 +9.742,0.21,89.656 +9.881,0.21,89.638 +10.021,0.21,89.644 +10.161,0.21,89.654 +10.301,0.211,89.648 +10.358,0.211,89.652 +10.585,0.21,89.699 +10.727,0.209,89.696 +10.87,0.208,89.706 +11.013,0.207,89.734 +11.156,0.205,89.724 +11.3,0.204,89.715 +11.444,0.203,89.738 +11.588,0.201,89.739 +11.731,0.199,89.713 +11.789,0.199,89.714 +12.019,0.197,89.73 +12.163,0.195,89.727 +12.307,0.193,89.76 +12.45,0.192,89.774 +12.594,0.191,89.782 +12.736,0.189,89.801 +12.878,0.187,89.806 +13.02,0.185,89.796 +13.161,0.184,89.809 +13.217,0.183,89.816 +13.441,0.179,89.783 +13.581,0.177,89.784 +13.72,0.175,89.793 +13.859,0.173,89.782 +13.998,0.171,89.807 +14.137,0.169,89.844 +14.276,0.166,89.837 +14.415,0.164,89.854 +14.554,0.162,89.882 +14.61,0.161,89.881 +14.832,0.157,89.851 +14.972,0.156,89.875 +15.111,0.154,89.87 +15.251,0.151,89.846 +15.392,0.15,89.854 +15.533,0.148,89.85 +15.675,0.145,89.829 +15.817,0.143,89.864 +15.96,0.141,89.884 +16.017,0.14,89.879 +16.246,0.137,89.903 +16.391,0.135,89.917 +16.535,0.132,89.878 +16.681,0.13,89.884 +16.827,0.129,89.906 +16.974,0.126,89.876 +17.121,0.124,89.861 +17.269,0.121,89.868 +17.417,0.119,89.855 +17.476,0.118,89.852 +17.714,0.116,89.917 +17.862,0.116,89.916 +18.011,0.114,89.909 +18.161,0.113,89.93 +18.311,0.112,89.92 +18.46,0.111,89.908 +18.61,0.11,89.915 +18.759,0.108,89.895 +18.907,0.107,89.879 +18.966,0.106,89.878 +19.201,0.103,89.874 +19.347,0.102,89.898 +19.492,0.1,89.913 +19.637,0.097,89.913 +19.781,0.094,89.927 +19.924,0.092,89.934 +20.067,0.089,89.927 +20.21,0.087,89.91 +20.353,0.085,89.916 +20.41,0.083,89.918 +20.637,0.079,89.896 +20.779,0.076,89.894 +20.921,0.074,89.89 +21.062,0.072,89.886 +21.204,0.069,89.909 +21.346,0.066,89.916 +21.487,0.064,89.922 +21.629,0.061,89.931 +21.77,0.059,89.943 +21.827,0.058,89.941 +22.051,0.057,89.949 +22.189,0.057,89.954 +22.328,0.057,89.933 +22.466,0.057,89.919 +22.605,0.057,89.925 +22.745,0.057,89.915 +22.884,0.058,89.924 +23.024,0.058,89.95 +23.163,0.058,89.953 +23.219,0.058,89.953 +23.441,0.058,89.975 +23.579,0.058,89.981 +23.717,0.057,89.951 +23.855,0.057,89.955 +23.992,0.057,89.969 +24.13,0.057,89.941 +24.268,0.057,89.933 +24.406,0.057,89.94 +24.545,0.057,89.934 +24.6,0.057,89.937 +24.824,0.056,89.972 +24.964,0.055,89.976 +25.104,0.053,89.974 +25.245,0.052,89.986 +25.385,0.05,89.976 +25.526,0.048,89.964 +25.668,0.047,89.974 +25.81,0.045,89.971 +25.952,0.044,89.947 +26.009,0.043,89.943 +26.235,0.039,89.936 +26.377,0.037,89.934 +26.519,0.035,89.96 +26.661,0.033,89.97 +26.802,0.03,89.977 +26.944,0.028,89.992 +27.086,0.025,89.989 +27.228,0.022,89.976 +27.37,0.02,89.986 +27.427,0.019,89.99 +27.656,0.018,89.976 +27.799,0.018,89.968 +27.943,0.018,89.974 +28.087,0.018,89.96 +28.23,0.018,89.978 +28.374,0.019,90.012 +28.517,0.019,90.008 +28.661,0.02,90.014 +28.804,0.02,90.028 +28.861,0.02,90.031 +29.09,0.018,89.999 +29.234,0.017,90.004 +29.377,0.016,90.007 +29.521,0.014,89.974 +29.664,0.012,89.97 +29.807,0.011,89.991 +29.951,0.011,89.987 +30.095,0.01,90.003 +30.239,0.009,90.034 +30.296,0.008,90.038 +30.526,0.007,90.027 +30.67,0.006,90.05 +30.813,0.005,90.03 +30.957,0.004,90.021 +31.101,0.003,90.033 +31.245,0.002,89.997 +31.39,0.0,89.996 +31.534,-0.0,90.0 +31.679,-0.001,89.99 +31.737,-0.001,89.99 +31.971,-0.003,90.042 +32.116,-0.004,90.047 +32.261,-0.005,90.046 +32.407,-0.005,90.069 +32.553,-0.007,90.052 +32.698,-0.008,90.028 +32.845,-0.01,90.039 +32.991,-0.012,90.029 +33.138,-0.013,90.013 +33.197,-0.014,90.01 +33.433,-0.017,90.011 +33.581,-0.02,90.02 +33.73,-0.023,90.048 +33.879,-0.026,90.052 +34.028,-0.029,90.05 +34.178,-0.032,90.074 +34.328,-0.035,90.054 +34.479,-0.039,90.026 +34.631,-0.042,90.044 +34.692,-0.044,90.05 +34.935,-0.049,90.009 +35.089,-0.052,90.008 +35.243,-0.055,90.009 +35.399,-0.059,90.022 +35.554,-0.062,90.052 +35.71,-0.065,90.055 +35.867,-0.067,90.053 +36.025,-0.071,90.07 +36.183,-0.075,90.059 +36.247,-0.076,90.048 +36.502,-0.081,90.042 +36.662,-0.084,90.024 +36.823,-0.088,89.999 +36.986,-0.091,89.992 +37.149,-0.093,90.038 +37.312,-0.096,90.055 +37.475,-0.098,90.05 +37.639,-0.1,90.075 +37.803,-0.104,90.081 +37.868,-0.105,90.071 +38.131,-0.11,90.025 +38.295,-0.112,90.041 +38.459,-0.114,90.015 +38.624,-0.116,89.98 +38.79,-0.118,90.012 +38.955,-0.12,90.043 +39.121,-0.122,90.032 +39.287,-0.124,90.04 +39.452,-0.125,90.069 +39.518,-0.126,90.069 +39.784,-0.131,90.029 +39.95,-0.133,90.04 +40.115,-0.135,90.032 +40.281,-0.137,89.993 +40.447,-0.139,89.996 +40.614,-0.142,90.008 +40.78,-0.145,90.004 +40.947,-0.147,90.016 +41.114,-0.149,90.045 +41.181,-0.149,90.046 +41.446,-0.152,90.023 +41.611,-0.154,90.024 +41.776,-0.156,90.033 +41.941,-0.158,90.018 +42.105,-0.16,89.99 +42.269,-0.162,89.988 +42.434,-0.164,89.996 +42.599,-0.166,90.011 +42.764,-0.167,90.022 +42.83,-0.168,90.029 +43.094,-0.172,90.047 +43.259,-0.175,90.033 +43.424,-0.179,90.029 +43.589,-0.182,90.021 +43.754,-0.186,89.998 +43.918,-0.19,89.987 +44.083,-0.193,89.986 +44.248,-0.196,89.992 +44.413,-0.199,90.016 +44.479,-0.2,90.023 +44.742,-0.205,90.037 +44.907,-0.209,90.037 +45.071,-0.212,90.03 +45.235,-0.215,90.018 +45.4,-0.218,90.021 +45.566,-0.222,90.006 +45.73,-0.226,89.998 +45.896,-0.228,89.999 +46.061,-0.231,90.012 +46.127,-0.232,90.025 +46.391,-0.236,90.036 +46.556,-0.238,90.04 +46.72,-0.239,90.048 +46.884,-0.241,90.026 +47.05,-0.243,89.998 +47.214,-0.245,89.971 +47.378,-0.248,89.917 +47.542,-0.25,89.887 +47.706,-0.251,89.842 +47.771,-0.252,89.83 +48.033,-0.254,89.799 +48.196,-0.256,89.756 +48.359,-0.257,89.724 +48.522,-0.258,89.674 +48.685,-0.26,89.589 +48.848,-0.26,89.532 +49.01,-0.261,89.462 +49.171,-0.263,89.352 +49.333,-0.264,89.277 +49.397,-0.264,89.252 +49.656,-0.264,89.168 +49.817,-0.263,89.118 +49.979,-0.262,89.054 +50.14,-0.262,88.991 +50.302,-0.261,88.929 +50.464,-0.26,88.838 +50.626,-0.258,88.757 +50.788,-0.256,88.695 +50.951,-0.255,88.573 +51.016,-0.255,88.527 +51.278,-0.252,88.412 +51.441,-0.25,88.333 +51.604,-0.248,88.258 +51.767,-0.246,88.183 +51.929,-0.244,88.108 +52.091,-0.241,88.013 +52.254,-0.238,87.889 +52.416,-0.235,87.793 +52.578,-0.232,87.689 +52.642,-0.231,87.632 +52.9,-0.224,87.423 +53.059,-0.219,87.32 +53.218,-0.213,87.22 +53.376,-0.206,87.127 +53.533,-0.2,87.017 +53.689,-0.193,86.904 +53.844,-0.186,86.786 +53.999,-0.179,86.641 +54.153,-0.172,86.511 +54.215,-0.169,86.471 +54.462,-0.159,86.242 +54.616,-0.153,86.107 +54.77,-0.145,86.008 +54.925,-0.138,85.895 +55.079,-0.13,85.811 +55.232,-0.121,85.686 +55.385,-0.113,85.571 +55.538,-0.105,85.472 +55.69,-0.096,85.332 +55.751,-0.093,85.271 +55.993,-0.076,85.101 +56.144,-0.065,84.971 +56.295,-0.055,84.809 +56.446,-0.043,84.699 +56.596,-0.031,84.606 +56.747,-0.019,84.488 +56.896,-0.006,84.386 +57.045,0.008,84.27 +57.192,0.021,84.162 +57.251,0.026,84.12 +57.484,0.045,83.908 +57.63,0.058,83.779 +57.774,0.071,83.685 +57.917,0.085,83.564 +58.06,0.098,83.441 +58.203,0.111,83.358 +58.345,0.124,83.284 +58.486,0.138,83.217 +58.627,0.153,83.201 +58.684,0.159,83.197 +58.906,0.182,83.178 +59.045,0.197,83.186 +59.182,0.211,83.168 +59.32,0.225,83.145 +59.457,0.239,83.152 +59.594,0.254,83.171 +59.73,0.268,83.217 +59.867,0.282,83.301 +60.003,0.296,83.422 +60.058,0.302,83.476 +60.276,0.325,83.737 +60.413,0.339,83.953 +60.549,0.354,84.17 +60.685,0.368,84.403 +60.821,0.382,84.702 +60.958,0.394,85.02 +61.094,0.405,85.309 +61.23,0.416,85.633 +61.367,0.428,86.005 +61.422,0.432,86.151 +61.641,0.444,86.726 +61.778,0.451,87.142 +61.917,0.457,87.612 +62.056,0.462,88.108 +62.197,0.466,88.674 +62.338,0.469,89.252 +62.479,0.471,89.831 +62.621,0.47,90.45 +62.763,0.469,91.098 +62.82,0.468,91.359 +63.047,0.462,92.439 +63.189,0.457,93.155 +63.331,0.45,93.917 +63.474,0.441,94.725 +63.617,0.43,95.583 +63.76,0.418,96.523 +63.904,0.403,97.495 +64.047,0.386,98.471 +64.191,0.366,99.503 +64.249,0.357,99.933 +64.476,0.317,101.727 +64.618,0.289,102.87 +64.759,0.257,104.055 +64.9,0.221,105.265 +65.04,0.184,106.497 +65.18,0.143,107.743 +65.319,0.099,109.018 +65.457,0.052,110.341 +65.593,0.002,111.681 +65.647,-0.018,112.221 +65.859,-0.105,114.399 +65.99,-0.162,115.812 +66.119,-0.221,117.223 +66.246,-0.284,118.661 +66.37,-0.35,120.136 +66.492,-0.419,121.589 +66.612,-0.49,123.043 +66.729,-0.565,124.547 +66.845,-0.642,126.05 +66.891,-0.673,126.641 +67.069,-0.804,129.008 +67.176,-0.89,130.523 +67.281,-0.978,132.028 +67.384,-1.068,133.514 +67.484,-1.161,135.002 +67.582,-1.256,136.493 +67.676,-1.354,137.957 +67.767,-1.454,139.404 +67.855,-1.555,140.888 +67.889,-1.596,141.479 +68.022,-1.764,143.785 +68.102,-1.871,145.233 +68.179,-1.98,146.699 +68.254,-2.09,148.145 +68.324,-2.201,149.563 +68.392,-2.314,150.993 +68.457,-2.429,152.429 +68.518,-2.546,153.836 +68.576,-2.663,155.249 +68.599,-2.71,155.816 +68.684,-2.9,158.071 +68.734,-3.021,159.477 +68.782,-3.142,160.877 +68.826,-3.265,162.278 +68.866,-3.388,163.699 +68.904,-3.511,165.097 +68.938,-3.635,166.459 +68.97,-3.759,167.833 +68.999,-3.883,169.226 +69.009,-3.933,169.772 +69.046,-4.131,171.891 +69.065,-4.255,173.243 +69.082,-4.378,174.605 +69.095,-4.5,175.93 +69.106,-4.623,177.247 +69.115,-4.744,178.568 +69.12,-4.866,179.854 +69.123,-4.986,181.128 +69.123,-5.106,182.4 +69.122,-5.153,182.89 +69.114,-5.342,184.816 +69.106,-5.46,186.042 +69.096,-5.576,187.246 +69.083,-5.693,188.396 +69.069,-5.808,189.562 +69.051,-5.923,190.782 +69.032,-6.038,191.953 +69.01,-6.154,193.096 +68.987,-6.27,194.292 +68.977,-6.317,194.783 +68.931,-6.504,196.724 +68.898,-6.621,197.936 +68.863,-6.738,199.143 +68.825,-6.856,200.359 +68.785,-6.974,201.597 +68.741,-7.092,202.849 +68.695,-7.209,204.113 +68.646,-7.325,205.383 +68.594,-7.441,206.716 +68.572,-7.488,207.247 +68.482,-7.672,209.387 +68.421,-7.786,210.755 +68.358,-7.897,212.099 +68.293,-8.007,213.462 +68.225,-8.116,214.847 +68.154,-8.223,216.216 +68.081,-8.328,217.612 +68.005,-8.432,219.043 +67.927,-8.535,220.467 +67.895,-8.575,221.026 +67.764,-8.732,223.301 +67.681,-8.827,224.755 +67.595,-8.92,226.146 +67.506,-9.01,227.549 +67.417,-9.099,228.981 +67.325,-9.186,230.364 +67.231,-9.269,231.709 +67.134,-9.35,233.032 +67.036,-9.428,234.359 +66.996,-9.459,234.899 +66.832,-9.582,237.013 +66.726,-9.655,238.283 +66.619,-9.726,239.559 +66.51,-9.794,240.809 +66.4,-9.86,242.011 +66.288,-9.923,243.193 +66.176,-9.985,244.358 +66.062,-10.044,245.451 +65.947,-10.101,246.465 +65.901,-10.123,246.852 +65.715,-10.204,248.342 +65.597,-10.251,249.214 +65.479,-10.296,250.018 +65.36,-10.34,250.782 +65.241,-10.381,251.487 +65.12,-10.421,252.127 +64.999,-10.46,252.736 +64.877,-10.497,253.299 +64.755,-10.533,253.807 +64.706,-10.547,254.006 +64.506,-10.605,254.684 +64.379,-10.643,255.091 +64.251,-10.679,255.468 +64.122,-10.715,255.833 +63.992,-10.75,256.185 +63.861,-10.785,256.542 +63.729,-10.819,256.922 +63.597,-10.851,257.295 +63.464,-10.883,257.626 +63.411,-10.896,257.746 +63.198,-10.942,258.178 +63.064,-10.969,258.425 +62.929,-10.996,258.648 +62.793,-11.023,258.871 +62.657,-11.05,259.102 +62.519,-11.076,259.308 +62.381,-11.102,259.502 +62.242,-11.127,259.687 +62.102,-11.152,259.858 +62.046,-11.162,259.925 +61.822,-11.201,260.167 +61.682,-11.226,260.318 +61.541,-11.251,260.474 +61.4,-11.275,260.627 +61.258,-11.299,260.773 +61.117,-11.324,260.919 +60.975,-11.347,261.067 +60.833,-11.37,261.22 +60.69,-11.393,261.374 +60.633,-11.402,261.451 +60.406,-11.438,261.787 +60.264,-11.46,262.042 +60.123,-11.482,262.341 +59.982,-11.502,262.638 +59.841,-11.521,262.944 +59.701,-11.54,263.289 +59.561,-11.559,263.642 +59.422,-11.576,263.97 +59.283,-11.593,264.305 +59.227,-11.599,264.445 +59.007,-11.622,264.985 +58.87,-11.636,265.316 +58.734,-11.649,265.653 +58.6,-11.662,265.992 +58.466,-11.674,266.332 +58.333,-11.683,266.65 +58.202,-11.693,266.931 +58.072,-11.701,267.192 +57.943,-11.709,267.406 +57.891,-11.712,267.483 +57.686,-11.721,267.72 +57.56,-11.726,267.866 +57.433,-11.731,267.979 +57.307,-11.736,268.085 +57.182,-11.741,268.173 +57.056,-11.745,268.218 +56.931,-11.749,268.24 +56.806,-11.753,268.275 +56.681,-11.757,268.328 +56.631,-11.759,268.34 +56.432,-11.765,268.338 +56.307,-11.769,268.399 +56.183,-11.772,268.451 +56.059,-11.776,268.505 +55.934,-11.78,268.606 +55.809,-11.783,268.699 +55.684,-11.787,268.77 +55.558,-11.79,268.87 +55.432,-11.794,268.985 +55.381,-11.795,269.018 +55.177,-11.798,269.129 +55.049,-11.801,269.25 +54.919,-11.803,269.353 +54.79,-11.804,269.436 +54.66,-11.805,269.542 +54.53,-11.806,269.66 +54.399,-11.806,269.736 +54.269,-11.806,269.821 +54.137,-11.807,269.917 +54.085,-11.807,269.943 +53.874,-11.807,269.961 +53.741,-11.808,270.002 +53.607,-11.808,270.03 +53.473,-11.808,270.03 +53.338,-11.809,270.068 +53.202,-11.81,270.111 +53.066,-11.809,270.129 +52.929,-11.809,270.156 +52.791,-11.809,270.185 +52.736,-11.808,270.19 +52.514,-11.808,270.214 +52.375,-11.808,270.251 +52.235,-11.808,270.251 +52.094,-11.808,270.265 +51.953,-11.808,270.296 +51.811,-11.808,270.317 +51.669,-11.807,270.311 +51.526,-11.807,270.325 +51.383,-11.807,270.358 +51.325,-11.807,270.361 +51.094,-11.805,270.384 +50.948,-11.804,270.415 +50.802,-11.803,270.417 +50.656,-11.802,270.428 +50.508,-11.801,270.437 +50.36,-11.8,270.444 +50.211,-11.799,270.445 +50.062,-11.798,270.46 +49.912,-11.796,270.459 +49.852,-11.795,270.458 +49.611,-11.793,270.49 +49.459,-11.791,270.485 +49.308,-11.789,270.495 +49.155,-11.787,270.52 +49.002,-11.785,270.505 +48.848,-11.783,270.506 +48.694,-11.782,270.523 +48.539,-11.78,270.508 +48.383,-11.778,270.495 +48.321,-11.778,270.496 +48.07,-11.775,270.469 +47.912,-11.773,270.462 +47.754,-11.772,270.468 +47.594,-11.769,270.454 +47.434,-11.767,270.447 +47.273,-11.766,270.44 +47.111,-11.764,270.421 +46.949,-11.762,270.412 +46.786,-11.761,270.399 +46.72,-11.76,270.393 +46.456,-11.758,270.364 +46.29,-11.758,270.345 +46.123,-11.758,270.337 +45.955,-11.758,270.335 +45.787,-11.757,270.318 +45.618,-11.756,270.325 +45.448,-11.755,270.307 +45.277,-11.755,270.278 +45.106,-11.755,270.264 +45.037,-11.755,270.258 +44.763,-11.753,270.233 +44.591,-11.753,270.216 +44.419,-11.752,270.21 +44.246,-11.752,270.21 +44.073,-11.751,270.186 +43.9,-11.75,270.175 +43.727,-11.749,270.172 +43.553,-11.748,270.141 +43.379,-11.748,270.128 +43.309,-11.748,270.125 +43.029,-11.746,270.098 +42.854,-11.745,270.064 +42.68,-11.744,270.064 +42.505,-11.744,270.041 +42.33,-11.743,270.018 +42.156,-11.742,270.017 +41.982,-11.74,270.017 +41.809,-11.739,269.989 +41.636,-11.738,269.959 +41.566,-11.738,269.944 +41.291,-11.738,269.945 +41.12,-11.739,269.917 +40.949,-11.739,269.883 +40.778,-11.739,269.89 +40.608,-11.74,269.9 +40.439,-11.739,269.877 +40.269,-11.738,269.858 +40.1,-11.738,269.841 +39.932,-11.738,269.836 +39.864,-11.738,269.831 +39.593,-11.739,269.791 +39.424,-11.74,269.795 +39.254,-11.741,269.778 +39.085,-11.741,269.74 +38.916,-11.742,269.735 +38.746,-11.742,269.739 +38.578,-11.742,269.723 +38.409,-11.743,269.712 +38.24,-11.744,269.689 +38.172,-11.744,269.686 +37.902,-11.745,269.664 +37.734,-11.745,269.635 +37.565,-11.746,269.623 +37.397,-11.746,269.599 +37.228,-11.747,269.581 +37.06,-11.747,269.579 +36.892,-11.747,269.571 +36.723,-11.748,269.561 +36.555,-11.748,269.531 +36.487,-11.748,269.524 +36.216,-11.749,269.509 +36.047,-11.75,269.48 +35.877,-11.75,269.484 +35.707,-11.751,269.469 +35.536,-11.751,269.443 +35.365,-11.752,269.445 +35.194,-11.752,269.448 +35.022,-11.752,269.436 +34.849,-11.753,269.424 +34.779,-11.753,269.416 +34.501,-11.754,269.397 +34.326,-11.756,269.371 +34.151,-11.757,269.362 +33.974,-11.758,269.349 +33.797,-11.759,269.317 +33.62,-11.761,269.315 +33.441,-11.763,269.32 +33.262,-11.763,269.308 +33.082,-11.764,269.3 +33.01,-11.765,269.295 +32.72,-11.767,269.278 +32.537,-11.769,269.254 +32.354,-11.771,269.246 +32.17,-11.772,269.25 +31.986,-11.774,269.223 +31.8,-11.775,269.208 +31.614,-11.777,269.226 +31.427,-11.778,269.215 +31.24,-11.779,269.192 +31.164,-11.779,269.185 +30.862,-11.782,269.179 +30.672,-11.784,269.146 +30.481,-11.785,269.139 +30.29,-11.787,269.128 +30.097,-11.788,269.104 +29.904,-11.79,269.118 +29.711,-11.792,269.124 +29.516,-11.793,269.122 +29.321,-11.794,269.118 +29.243,-11.795,269.12 +28.929,-11.798,269.11 +28.732,-11.8,269.109 +28.534,-11.802,269.118 +28.336,-11.804,269.105 +28.138,-11.805,269.113 +27.939,-11.806,269.126 +27.74,-11.807,269.129 +27.54,-11.808,269.109 +27.34,-11.811,269.141 +27.26,-11.812,269.15 +26.94,-11.818,269.11 +26.74,-11.823,269.12 +26.54,-11.827,269.132 +26.34,-11.831,269.137 +26.139,-11.835,269.142 +25.939,-11.839,269.172 +25.738,-11.844,269.175 +25.537,-11.849,269.18 +25.337,-11.854,269.189 +25.257,-11.855,269.193 +24.937,-11.86,269.2 +24.738,-11.862,269.21 +24.537,-11.865,269.241 +24.337,-11.867,269.266 +24.137,-11.869,269.287 +23.937,-11.871,269.296 +23.737,-11.874,269.307 +23.536,-11.876,269.307 +23.336,-11.878,269.323 +23.255,-11.879,269.332 +22.932,-11.882,269.354 +22.729,-11.885,269.377 +22.526,-11.887,269.407 +22.324,-11.888,269.405 +22.12,-11.89,269.414 +21.917,-11.892,269.417 +21.713,-11.894,269.42 +21.509,-11.896,269.435 +21.305,-11.898,269.449 +21.224,-11.899,269.455 +20.897,-11.901,269.501 +20.693,-11.902,269.509 +20.488,-11.902,269.514 +20.283,-11.903,269.524 +20.079,-11.905,269.53 +19.874,-11.906,269.537 +19.669,-11.907,269.551 +19.463,-11.908,269.552 +19.258,-11.909,269.574 +19.176,-11.909,269.586 +18.847,-11.91,269.623 +18.64,-11.91,269.614 +18.434,-11.911,269.635 +18.227,-11.913,269.642 +18.021,-11.914,269.646 +17.815,-11.915,269.659 +17.608,-11.916,269.677 +17.402,-11.916,269.696 +17.195,-11.917,269.707 +17.112,-11.917,269.719 +16.78,-11.916,269.731 +16.572,-11.917,269.739 +16.365,-11.918,269.749 +16.157,-11.918,269.766 +15.949,-11.917,269.756 +15.741,-11.918,269.776 +15.534,-11.918,269.809 +15.326,-11.917,269.806 +15.118,-11.916,269.817 +15.035,-11.916,269.819 +14.703,-11.917,269.818 +14.496,-11.918,269.822 +14.289,-11.918,269.836 +14.083,-11.919,269.838 +13.876,-11.92,269.858 +13.669,-11.92,269.869 +13.463,-11.92,269.884 +13.256,-11.92,269.873 +13.049,-11.92,269.886 +12.966,-11.921,269.886 +12.636,-11.92,269.882 +12.429,-11.92,269.889 +12.222,-11.919,269.898 +12.015,-11.918,269.919 +11.809,-11.917,269.927 +11.602,-11.915,269.925 +11.396,-11.913,269.926 +11.189,-11.913,269.936 +10.982,-11.912,269.926 +10.9,-11.912,269.926 +10.569,-11.911,269.944 +10.362,-11.911,269.959 +10.155,-11.91,269.972 +9.948,-11.91,269.983 +9.741,-11.909,269.979 +9.534,-11.908,269.98 +9.326,-11.909,269.981 +9.119,-11.909,269.986 +8.911,-11.909,269.997 +8.828,-11.909,269.998 +8.496,-11.908,270.017 +8.288,-11.907,270.037 +8.08,-11.906,270.03 +7.872,-11.905,270.034 +7.664,-11.906,270.051 +7.456,-11.905,270.042 +7.248,-11.905,270.048 +7.04,-11.904,270.05 +6.832,-11.903,270.06 +6.749,-11.903,270.067 +6.417,-11.901,270.088 +6.209,-11.9,270.093 +6.002,-11.899,270.088 +5.795,-11.898,270.08 +5.588,-11.897,270.087 +5.381,-11.897,270.094 +5.174,-11.895,270.085 +4.967,-11.895,270.124 +4.76,-11.894,270.13 +4.677,-11.893,270.125 +4.346,-11.89,270.123 +4.14,-11.89,270.136 +3.933,-11.889,270.119 +3.726,-11.888,270.13 +3.52,-11.888,270.136 +3.313,-11.886,270.137 +3.107,-11.885,270.164 +2.902,-11.884,270.163 +2.696,-11.882,270.159 +2.614,-11.882,270.161 +2.288,-11.88,270.161 +2.085,-11.879,270.143 +1.883,-11.878,270.152 +1.681,-11.876,270.138 +1.48,-11.875,270.154 +1.28,-11.873,270.165 +1.08,-11.872,270.163 +0.881,-11.87,270.156 +0.682,-11.868,270.148 +0.603,-11.868,270.145 +0.286,-11.866,270.128 +0.088,-11.865,270.131 +-0.11,-11.863,270.127 +-0.308,-11.863,270.142 +-0.505,-11.861,270.146 +-0.701,-11.86,270.139 +-0.898,-11.858,270.13 +-1.094,-11.857,270.135 +-1.29,-11.856,270.116 +-1.368,-11.856,270.11 +-1.681,-11.854,270.112 +-1.876,-11.852,270.1 +-2.071,-11.851,270.104 +-2.265,-11.85,270.115 +-2.459,-11.848,270.109 +-2.653,-11.846,270.115 +-2.847,-11.845,270.137 +-3.041,-11.844,270.15 +-3.234,-11.843,270.179 +-3.312,-11.842,270.208 +-3.621,-11.839,270.339 +-3.814,-11.837,270.425 +-4.007,-11.834,270.591 +-4.2,-11.831,270.789 +-4.392,-11.827,270.99 +-4.585,-11.823,271.232 +-4.777,-11.818,271.489 +-4.968,-11.813,271.721 +-5.16,-11.806,271.988 +-5.236,-11.803,272.107 +-5.542,-11.791,272.681 +-5.733,-11.782,273.113 +-5.923,-11.771,273.6 +-6.113,-11.76,274.145 +-6.302,-11.747,274.704 +-6.492,-11.732,275.284 +-6.681,-11.714,275.854 +-6.869,-11.696,276.423 +-7.057,-11.675,276.973 +-7.132,-11.667,277.199 +-7.432,-11.629,278.159 +-7.618,-11.602,278.741 +-7.804,-11.574,279.415 +-7.989,-11.546,280.15 +-8.174,-11.514,280.881 +-8.358,-11.48,281.637 +-8.542,-11.444,282.489 +-8.724,-11.406,283.334 +-8.905,-11.365,284.176 +-8.976,-11.348,284.541 +-9.262,-11.275,286.136 +-9.439,-11.226,287.161 +-9.614,-11.173,288.219 +-9.787,-11.119,289.339 +-9.959,-11.061,290.53 +-10.129,-11.0,291.737 +-10.297,-10.936,292.966 +-10.462,-10.868,294.227 +-10.625,-10.798,295.554 +-10.69,-10.769,296.091 +-10.942,-10.648,298.308 +-11.096,-10.567,299.708 +-11.248,-10.484,301.097 +-11.397,-10.397,302.454 +-11.545,-10.308,303.825 +-11.689,-10.215,305.201 +-11.831,-10.118,306.53 +-11.97,-10.019,307.892 +-12.106,-9.917,309.256 +-12.159,-9.875,309.783 +-12.369,-9.702,311.867 +-12.498,-9.591,313.246 +-12.625,-9.477,314.596 +-12.747,-9.36,315.915 +-12.867,-9.241,317.285 +-12.984,-9.12,318.61 +-13.097,-8.995,319.908 +-13.207,-8.869,321.274 +-13.314,-8.74,322.628 +-13.356,-8.688,323.159 +-13.519,-8.475,325.321 +-13.619,-8.34,326.787 +-13.714,-8.202,328.25 +-13.805,-8.062,329.681 +-13.892,-7.919,331.116 +-13.975,-7.776,332.59 +-14.055,-7.63,334.058 +-14.131,-7.482,335.515 +-14.203,-7.332,336.999 +-14.231,-7.272,337.6 +-14.335,-7.026,339.98 +-14.396,-6.87,341.552 +-14.451,-6.713,343.169 +-14.503,-6.555,344.845 +-14.549,-6.396,346.563 +-14.59,-6.236,348.316 +-14.626,-6.077,350.136 +-14.657,-5.917,351.979 +-14.682,-5.756,353.826 +-14.691,-5.692,354.569 +-14.717,-5.435,357.41 +-14.728,-5.275,359.231 +-14.734,-5.115,1.052 +-14.734,-4.957,2.875 +-14.73,-4.8,4.718 +-14.72,-4.645,6.583 +-14.706,-4.491,8.416 +-14.687,-4.339,10.204 +-14.663,-4.189,12.012 +-14.653,-4.129,12.737 +-14.604,-3.893,15.566 +-14.568,-3.749,17.382 +-14.528,-3.606,19.137 +-14.484,-3.466,20.855 +-14.435,-3.33,22.56 +-14.383,-3.195,24.274 +-14.328,-3.063,25.96 +-14.269,-2.934,27.613 +-14.207,-2.807,29.274 +-14.182,-2.757,29.94 +-14.076,-2.561,32.556 +-14.005,-2.442,34.168 +-13.932,-2.326,35.79 +-13.857,-2.213,37.391 +-13.778,-2.103,38.972 +-13.698,-1.995,40.553 +-13.615,-1.891,42.128 +-13.53,-1.79,43.667 +-13.443,-1.692,45.191 +-13.407,-1.654,45.808 +-13.262,-1.504,48.29 +-13.169,-1.414,49.798 +-13.074,-1.327,51.339 +-12.976,-1.242,52.87 +-12.877,-1.16,54.37 +-12.774,-1.081,55.857 +-12.67,-1.005,57.34 +-12.563,-0.931,58.765 +-12.454,-0.859,60.118 +-12.409,-0.831,60.654 +-12.227,-0.723,62.74 +-12.109,-0.658,63.979 +-11.989,-0.596,65.134 +-11.867,-0.536,66.28 +-11.742,-0.477,67.388 +-11.616,-0.422,68.457 +-11.488,-0.367,69.547 +-11.358,-0.315,70.619 +-11.227,-0.265,71.625 +-11.174,-0.245,72.016 +-10.956,-0.171,73.446 +-10.817,-0.127,74.3 +-10.678,-0.085,75.13 +-10.537,-0.044,75.943 +-10.395,-0.005,76.762 +-10.253,0.032,77.577 +-10.109,0.067,78.378 +-9.965,0.1,79.177 +-9.82,0.131,79.974 +-9.762,0.143,80.294 +-9.528,0.186,81.583 +-9.381,0.21,82.396 +-9.234,0.232,83.193 +-9.087,0.253,83.976 +-8.94,0.271,84.738 +-8.794,0.286,85.456 +-8.647,0.3,86.133 +-8.503,0.312,86.722 +-8.361,0.322,87.204 +-8.305,0.325,87.37 +-8.082,0.336,87.876 +-7.947,0.342,88.141 +-7.814,0.347,88.354 +-7.684,0.352,88.525 +-7.556,0.356,88.671 +-7.429,0.36,88.812 +-7.302,0.364,88.943 +-7.178,0.367,89.025 +-7.053,0.37,89.085 +-7.003,0.371,89.108 +-6.806,0.374,89.143 +-6.684,0.375,89.133 +-6.562,0.377,89.149 +-6.439,0.379,89.173 +-6.316,0.38,89.15 +-6.193,0.382,89.141 +-6.069,0.384,89.177 +-5.945,0.385,89.186 +-5.821,0.387,89.171 +-5.771,0.387,89.175 +-5.569,0.389,89.187 +-5.443,0.39,89.175 +-5.316,0.391,89.178 +-5.189,0.392,89.179 +-5.06,0.393,89.179 +-4.931,0.395,89.184 +-4.802,0.396,89.184 +-4.672,0.398,89.194 +-4.541,0.399,89.178 +-4.489,0.4,89.175 +-4.279,0.403,89.207 +-4.148,0.406,89.218 +-4.016,0.409,89.22 +-3.885,0.411,89.244 +-3.754,0.414,89.259 +-3.624,0.417,89.258 +-3.493,0.419,89.263 +-3.363,0.422,89.262 +-3.234,0.424,89.255 +-3.183,0.425,89.256 +-2.978,0.43,89.268 +-2.85,0.433,89.264 +-2.724,0.436,89.256 +-2.6,0.439,89.27 +-2.476,0.442,89.29 +-2.354,0.445,89.288 +-2.234,0.447,89.298 +-2.116,0.451,89.324 +-2.0,0.454,89.334 +-1.954,0.455,89.333 +-1.776,0.459,89.315 +-1.667,0.462,89.335 +-1.56,0.465,89.329 +-1.455,0.467,89.326 +-1.352,0.47,89.327 +-1.251,0.473,89.328 +-1.152,0.476,89.333 +-1.055,0.479,89.331 +-0.96,0.482,89.332 +-0.923,0.483,89.336 +-0.775,0.487,89.351 +-0.686,0.49,89.353 +-0.598,0.493,89.37 +-0.512,0.496,89.386 +-0.427,0.499,89.391 +-0.344,0.502,89.405 +-0.263,0.505,89.432 +-0.184,0.508,89.432 +-0.106,0.51,89.431 +-0.076,0.512,89.435 +0.036,0.506,89.325 +0.102,0.502,89.324 +0.166,0.497,89.323 +0.228,0.493,89.328 +0.288,0.488,89.331 +0.347,0.484,89.33 +0.403,0.479,89.333 +0.457,0.475,89.345 +0.509,0.47,89.351 +0.53,0.469,89.35 +0.612,0.46,89.289 +0.662,0.454,89.291 +0.711,0.449,89.288 +0.76,0.444,89.289 +0.807,0.438,89.295 +0.854,0.433,89.296 +0.899,0.427,89.303 +0.942,0.422,89.306 +0.984,0.416,89.306 +1.0,0.414,89.307 +1.063,0.412,89.319 +1.1,0.412,89.324 +1.136,0.413,89.326 +1.171,0.413,89.326 +1.204,0.413,89.331 +1.233,0.414,89.335 +1.26,0.414,89.339 +1.283,0.415,89.343 +1.302,0.416,89.349 +1.309,0.416,89.349 +1.33,0.416,89.34 +1.339,0.416,89.343 +1.345,0.416,89.344 +1.347,0.416,89.344 +1.346,0.416,89.346 +1.344,0.416,89.348 +1.343,0.416,89.348 +1.343,0.416,89.348 +1.344,0.416,89.347 +1.344,0.416,89.346 +1.343,0.415,89.316 +1.343,0.415,89.315 +1.343,0.415,89.313 +1.342,0.414,89.313 +1.342,0.414,89.314 +1.342,0.414,89.312 +1.342,0.414,89.315 +1.342,0.414,89.313 +1.341,0.413,89.314 +1.341,0.413,89.313 +1.341,0.413,89.331 +1.341,0.413,89.333 +1.34,0.413,89.331 +1.34,0.413,89.333 +1.34,0.413,89.331 +1.34,0.413,89.332 +1.34,0.413,89.332 +1.34,0.412,89.329 +1.34,0.412,89.331 diff --git a/GEMstack/knowledge/routes/xyhead_demo_stanley.csv b/GEMstack/knowledge/routes/xyhead_demo_stanley.csv new file mode 100644 index 000000000..acb40560f --- /dev/null +++ b/GEMstack/knowledge/routes/xyhead_demo_stanley.csv @@ -0,0 +1,1170 @@ +0.002,-0.005,-0.03 +0.002,-0.005,-0.03 +0.002,-0.005,-0.03 +0.001,-0.005,-0.03 +0.001,-0.005,-0.03 +0.001,-0.005,-0.03 +0.001,-0.006,-0.03 +0.001,-0.006,-0.03 +0.001,-0.006,-0.029 +0.001,-0.006,-0.03 +0.001,-0.006,-0.03 +0.001,-0.006,-0.029 +0.001,-0.006,-0.03 +0.001,-0.006,-0.029 +0.001,-0.006,-0.029 +0.001,-0.006,-0.029 +0.017,-0.017,-0.029 +0.027,-0.017,-0.029 +0.046,-0.018,-0.029 +0.066,-0.018,-0.029 +0.09,-0.019,-0.029 +0.118,-0.02,-0.029 +0.151,-0.021,-0.029 +0.187,-0.022,-0.029 +0.226,-0.023,-0.029 +0.234,-0.023,-0.029 +0.31,-0.026,-0.029 +0.337,-0.027,-0.029 +0.402,-0.031,-0.029 +0.45,-0.033,-0.029 +0.5,-0.035,-0.029 +0.552,-0.037,-0.029 +0.606,-0.04,-0.029 +0.662,-0.042,-0.029 +0.718,-0.045,-0.028 +0.73,-0.045,-0.028 +0.836,-0.048,-0.028 +0.897,-0.049,-0.028 +0.96,-0.05,-0.028 +1.023,-0.052,-0.027 +1.036,-0.052,-0.027 +1.154,-0.054,-0.027 +1.221,-0.055,-0.027 +1.289,-0.056,-0.027 +1.359,-0.057,-0.027 +1.373,-0.057,-0.026 +1.501,-0.059,-0.026 +1.545,-0.06,-0.026 +1.649,-0.061,-0.026 +1.726,-0.063,-0.026 +1.804,-0.064,-0.025 +1.883,-0.065,-0.025 +1.963,-0.066,-0.025 +2.045,-0.067,-0.025 +2.128,-0.068,-0.025 +2.161,-0.069,-0.025 +2.296,-0.07,-0.024 +2.382,-0.072,-0.024 +2.469,-0.073,-0.023 +2.522,-0.073,-0.023 +2.645,-0.075,-0.023 +2.732,-0.075,-0.022 +2.82,-0.076,-0.021 +2.907,-0.077,-0.021 +2.995,-0.077,-0.02 +3.012,-0.077,-0.02 +3.17,-0.08,-0.019 +3.258,-0.081,-0.019 +3.346,-0.083,-0.018 +3.434,-0.085,-0.018 +3.523,-0.087,-0.018 +3.613,-0.088,-0.017 +3.702,-0.09,-0.017 +3.792,-0.092,-0.016 +3.881,-0.094,-0.016 +3.899,-0.094,-0.016 +4.061,-0.096,-0.015 +4.15,-0.098,-0.015 +4.222,-0.099,-0.014 +4.329,-0.1,-0.014 +4.419,-0.101,-0.014 +4.509,-0.103,-0.013 +4.6,-0.104,-0.013 +4.691,-0.105,-0.013 +4.782,-0.106,-0.013 +4.801,-0.106,-0.013 +4.967,-0.108,-0.012 +5.041,-0.109,-0.012 +5.079,-0.11,-0.012 +5.248,-0.112,-0.012 +5.343,-0.113,-0.012 +5.439,-0.114,-0.012 +5.534,-0.116,-0.012 +5.63,-0.117,-0.012 +5.727,-0.119,-0.012 +5.746,-0.119,-0.013 +5.92,-0.12,-0.013 +5.978,-0.121,-0.012 +6.114,-0.122,-0.012 +6.211,-0.123,-0.012 +6.309,-0.123,-0.012 +6.407,-0.124,-0.012 +6.505,-0.124,-0.012 +6.603,-0.125,-0.012 +6.702,-0.125,-0.012 +6.742,-0.125,-0.012 +6.9,-0.126,-0.012 +6.96,-0.127,-0.012 +7.1,-0.128,-0.012 +7.201,-0.128,-0.012 +7.302,-0.129,-0.012 +7.404,-0.129,-0.012 +7.505,-0.13,-0.011 +7.607,-0.13,-0.011 +7.71,-0.131,-0.011 +7.751,-0.131,-0.011 +7.916,-0.132,-0.011 +8.02,-0.133,-0.011 +8.123,-0.134,-0.01 +8.228,-0.134,-0.01 +8.332,-0.134,-0.01 +8.437,-0.135,-0.01 +8.543,-0.135,-0.01 +8.648,-0.135,-0.01 +8.754,-0.136,-0.01 +8.775,-0.136,-0.01 +8.967,-0.137,-0.01 +9.074,-0.137,-0.01 +9.181,-0.138,-0.01 +9.289,-0.138,-0.01 +9.396,-0.138,-0.01 +9.504,-0.139,-0.009 +9.613,-0.14,-0.009 +9.721,-0.14,-0.009 +9.83,-0.141,-0.009 +9.874,-0.142,-0.009 +10.05,-0.142,-0.008 +10.16,-0.143,-0.008 +10.27,-0.143,-0.008 +10.337,-0.143,-0.008 +10.492,-0.144,-0.008 +10.604,-0.144,-0.008 +10.716,-0.145,-0.008 +10.828,-0.145,-0.008 +10.94,-0.145,-0.008 +10.962,-0.146,-0.008 +11.164,-0.147,-0.007 +11.276,-0.147,-0.007 +11.387,-0.148,-0.007 +11.499,-0.149,-0.007 +11.521,-0.149,-0.007 +11.721,-0.15,-0.007 +11.833,-0.151,-0.006 +11.944,-0.151,-0.006 +12.054,-0.151,-0.006 +12.077,-0.151,-0.006 +12.276,-0.153,-0.006 +12.387,-0.153,-0.006 +12.475,-0.153,-0.006 +12.608,-0.154,-0.006 +12.719,-0.155,-0.007 +12.829,-0.155,-0.006 +12.94,-0.156,-0.006 +13.051,-0.156,-0.007 +13.162,-0.157,-0.006 +13.184,-0.157,-0.006 +13.385,-0.158,-0.006 +13.497,-0.159,-0.006 +13.52,-0.159,-0.006 +13.722,-0.159,-0.006 +13.835,-0.16,-0.006 +13.925,-0.16,-0.005 +14.061,-0.161,-0.005 +14.175,-0.161,-0.005 +14.289,-0.162,-0.005 +14.335,-0.162,-0.005 +14.517,-0.162,-0.005 +14.609,-0.162,-0.005 +14.746,-0.163,-0.005 +14.861,-0.163,-0.005 +14.976,-0.164,-0.005 +15.091,-0.164,-0.004 +15.206,-0.164,-0.004 +15.321,-0.164,-0.004 +15.436,-0.164,-0.004 +15.483,-0.164,-0.004 +15.668,-0.165,-0.003 +15.784,-0.165,-0.003 +15.901,-0.165,-0.003 +16.017,-0.165,-0.003 +16.111,-0.165,-0.003 +16.251,-0.165,-0.003 +16.368,-0.165,-0.003 +16.484,-0.165,-0.003 +16.601,-0.165,-0.003 +16.648,-0.165,-0.003 +16.836,-0.165,-0.002 +16.906,-0.165,-0.002 +17.071,-0.165,-0.002 +17.188,-0.165,-0.002 +17.307,-0.164,-0.002 +17.425,-0.164,-0.002 +17.543,-0.164,-0.001 +17.662,-0.164,-0.001 +17.781,-0.163,-0.001 +17.805,-0.163,-0.001 +18.02,-0.16,-0.001 +18.14,-0.158,-0.002 +18.26,-0.155,-0.002 +18.381,-0.152,-0.001 +18.501,-0.15,-0.001 +18.621,-0.148,-0.001 +18.742,-0.145,-0.001 +18.863,-0.143,-0.001 +18.983,-0.14,0 +19.007,-0.139,0 +19.222,-0.136,0 +19.341,-0.135,0 +19.46,-0.135,0 +19.531,-0.134,0 +19.698,-0.133,0 +19.818,-0.132,0 +19.937,-0.131,0 +20.056,-0.131,0 +20.176,-0.13,0 +20.2,-0.13,0 +20.417,-0.129,0 +20.537,-0.129,0 +20.658,-0.129,0 +20.78,-0.128,0.001 +20.901,-0.128,0 +21.023,-0.127,0 +21.144,-0.127,0.001 +21.265,-0.127,0 +21.387,-0.126,0 +21.411,-0.126,0 +21.631,-0.126,0 +21.753,-0.125,0 +21.851,-0.125,0 +21.997,-0.124,0 +22.12,-0.124,0.001 +22.242,-0.124,0.001 +22.365,-0.124,0 +22.488,-0.123,0.001 +22.611,-0.122,0.001 +22.635,-0.122,0.001 +22.857,-0.121,0.001 +22.931,-0.121,0.001 +23.104,-0.12,0.001 +23.227,-0.12,0.001 +23.35,-0.119,0.001 +23.474,-0.119,0.001 +23.597,-0.119,0.001 +23.721,-0.118,0.001 +23.844,-0.117,0.001 +23.869,-0.117,0.001 +24.091,-0.117,0.001 +24.214,-0.117,0.001 +24.337,-0.116,0.001 +24.461,-0.115,0.001 +24.584,-0.114,0.001 +24.707,-0.114,0.001 +24.831,-0.114,0.001 +24.954,-0.114,0.001 +25.077,-0.113,0.001 +25.102,-0.113,0.001 +25.324,-0.113,0.001 +25.447,-0.113,0.001 +25.57,-0.112,0.001 +25.693,-0.112,0.001 +25.792,-0.113,0.001 +25.939,-0.113,0.001 +26.062,-0.113,0.001 +26.185,-0.112,0.001 +26.307,-0.112,0.001 +26.332,-0.112,0.001 +26.553,-0.11,0.001 +26.676,-0.109,0.001 +26.799,-0.107,0.001 +26.922,-0.106,0.001 +26.947,-0.105,0.001 +27.168,-0.103,0.001 +27.291,-0.102,0.001 +27.414,-0.1,0.001 +27.538,-0.099,0.001 +27.562,-0.099,0.001 +27.784,-0.097,0.001 +27.907,-0.095,0.001 +28.03,-0.094,0.001 +28.128,-0.093,0.001 +28.275,-0.092,0.001 +28.398,-0.09,0.001 +28.52,-0.089,0.001 +28.643,-0.088,0.001 +28.741,-0.087,0.001 +28.79,-0.086,0.001 +29.009,-0.084,0 +29.057,-0.084,0 +29.251,-0.083,0.001 +29.372,-0.082,0 +29.492,-0.081,0.001 +29.612,-0.08,0.001 +29.731,-0.079,0.001 +29.851,-0.078,0.001 +29.97,-0.077,0.001 +29.993,-0.077,0.001 +30.207,-0.076,0.001 +30.326,-0.075,0.001 +30.445,-0.075,0.001 +30.492,-0.075,0.001 +30.68,-0.074,0.001 +30.797,-0.073,0.001 +30.914,-0.073,0.001 +31.03,-0.072,0.001 +31.145,-0.072,0.001 +31.168,-0.072,0.001 +31.373,-0.073,0.001 +31.486,-0.074,0.001 +31.576,-0.074,0.001 +31.71,-0.075,0.002 +31.822,-0.076,0.002 +31.934,-0.077,0.001 +32.045,-0.078,0.001 +32.157,-0.079,0.001 +32.268,-0.08,0.001 +32.29,-0.08,0.001 +32.492,-0.08,0.001 +32.604,-0.08,0.001 +32.626,-0.08,0.001 +32.828,-0.079,0.001 +32.941,-0.079,0.001 +33.054,-0.079,0.001 +33.167,-0.079,0.001 +33.281,-0.078,0.001 +33.395,-0.078,0.001 +33.44,-0.077,0.001 +33.624,-0.076,0.001 +33.717,-0.075,0.001 +33.857,-0.075,0.001 +33.974,-0.074,0.001 +34.093,-0.073,0.001 +34.212,-0.072,0.001 +34.333,-0.071,0 +34.454,-0.071,0 +34.576,-0.07,0.001 +34.6,-0.07,0.001 +34.822,-0.069,0.001 +34.871,-0.069,0.001 +35.071,-0.068,0.001 +35.171,-0.068,0.001 +35.323,-0.067,0.001 +35.45,-0.067,0.001 +35.579,-0.066,0.001 +35.708,-0.065,0 +35.839,-0.065,0 +35.892,-0.065,0 +36.101,-0.064,0 +36.234,-0.064,0 +36.367,-0.063,0 +36.5,-0.063,0 +36.554,-0.063,0 +36.768,-0.063,0 +36.902,-0.062,0 +37.037,-0.061,0 +37.171,-0.061,0 +37.198,-0.061,0 +37.44,-0.06,-0.001 +37.574,-0.06,-0.001 +37.708,-0.059,-0.001 +37.842,-0.059,-0.002 +37.975,-0.058,-0.002 +38.107,-0.058,-0.002 +38.24,-0.058,-0.002 +38.371,-0.058,-0.002 +38.502,-0.057,-0.002 +38.529,-0.057,-0.002 +38.76,-0.058,-0.003 +38.886,-0.06,-0.003 +39.012,-0.062,-0.003 +39.087,-0.063,-0.003 +39.26,-0.065,-0.004 +39.381,-0.067,-0.004 +39.502,-0.069,-0.004 +39.62,-0.07,-0.005 +39.736,-0.072,-0.005 +39.76,-0.072,-0.005 +39.969,-0.075,-0.005 +40.084,-0.076,-0.005 +40.197,-0.077,-0.005 +40.243,-0.077,-0.005 +40.421,-0.079,-0.005 +40.53,-0.079,-0.006 +40.638,-0.08,-0.006 +40.723,-0.082,-0.006 +40.85,-0.083,-0.007 +40.892,-0.084,-0.007 +41.06,-0.086,-0.007 +41.102,-0.086,-0.008 +41.269,-0.089,-0.008 +41.374,-0.09,-0.009 +41.479,-0.092,-0.009 +41.585,-0.093,-0.009 +41.691,-0.095,-0.009 +41.797,-0.097,-0.01 +41.903,-0.099,-0.01 +41.924,-0.099,-0.01 +42.113,-0.103,-0.01 +42.217,-0.104,-0.011 +42.258,-0.105,-0.011 +42.422,-0.107,-0.011 +42.524,-0.109,-0.012 +42.625,-0.111,-0.012 +42.726,-0.113,-0.012 +42.827,-0.114,-0.013 +42.928,-0.117,-0.013 +42.948,-0.117,-0.013 +43.129,-0.12,-0.014 +43.229,-0.121,-0.014 +43.329,-0.122,-0.014 +43.409,-0.124,-0.015 +43.53,-0.126,-0.015 +43.631,-0.127,-0.015 +43.731,-0.129,-0.015 +43.832,-0.13,-0.015 +43.933,-0.132,-0.016 +43.953,-0.132,-0.016 +44.135,-0.134,-0.016 +44.236,-0.136,-0.017 +44.337,-0.137,-0.017 +44.439,-0.138,-0.017 +44.52,-0.139,-0.017 +44.642,-0.14,-0.017 +44.743,-0.141,-0.017 +44.845,-0.142,-0.017 +44.946,-0.143,-0.016 +44.966,-0.143,-0.016 +45.146,-0.14,-0.014 +45.246,-0.139,-0.013 +45.345,-0.136,-0.011 +45.444,-0.134,-0.009 +45.463,-0.133,-0.008 +45.64,-0.127,-0.003 +45.739,-0.122,0 +45.837,-0.118,0.004 +45.935,-0.113,0.007 +45.955,-0.112,0.008 +46.133,-0.105,0.014 +46.232,-0.101,0.018 +46.331,-0.097,0.022 +46.39,-0.094,0.025 +46.527,-0.086,0.031 +46.624,-0.08,0.035 +46.721,-0.074,0.04 +46.817,-0.067,0.045 +46.913,-0.059,0.051 +46.932,-0.057,0.052 +47.105,-0.041,0.063 +47.201,-0.031,0.071 +47.297,-0.02,0.078 +47.354,-0.012,0.083 +47.486,0.005,0.096 +47.58,0.019,0.104 +47.674,0.034,0.113 +47.768,0.05,0.122 +47.862,0.066,0.13 +47.881,0.07,0.132 +48.052,0.101,0.149 +48.148,0.121,0.158 +48.243,0.142,0.168 +48.281,0.15,0.173 +48.431,0.186,0.192 +48.524,0.211,0.205 +48.615,0.238,0.218 +48.706,0.266,0.233 +48.795,0.295,0.248 +48.813,0.301,0.251 +48.952,0.351,0.277 +49.053,0.391,0.297 +49.12,0.419,0.311 +49.219,0.461,0.331 +49.301,0.498,0.348 +49.381,0.536,0.366 +49.46,0.576,0.383 +49.537,0.618,0.4 +49.613,0.66,0.418 +49.628,0.668,0.422 +49.764,0.745,0.452 +49.837,0.789,0.47 +49.866,0.807,0.477 +49.965,0.87,0.501 +50.048,0.925,0.522 +50.116,0.972,0.539 +50.182,1.019,0.556 +50.247,1.067,0.574 +50.31,1.115,0.591 +50.322,1.125,0.594 +50.432,1.215,0.624 +50.49,1.266,0.641 +50.546,1.317,0.658 +50.601,1.368,0.675 +50.654,1.419,0.691 +50.696,1.46,0.705 +50.755,1.521,0.725 +50.803,1.572,0.741 +50.849,1.623,0.757 +50.858,1.633,0.76 +50.934,1.724,0.789 +50.958,1.754,0.799 +51.012,1.826,0.821 +51.05,1.878,0.837 +51.087,1.93,0.853 +51.123,1.983,0.869 +51.159,2.036,0.886 +51.193,2.09,0.902 +51.227,2.145,0.918 +51.234,2.156,0.922 +51.293,2.257,0.952 +51.318,2.303,0.965 +51.356,2.374,0.985 +51.386,2.433,1.002 +51.393,2.445,1.005 +51.446,2.555,1.037 +51.475,2.618,1.054 +51.503,2.682,1.072 +51.53,2.748,1.09 +51.535,2.762,1.093 +51.582,2.885,1.125 +51.606,2.956,1.143 +51.629,3.028,1.161 +51.65,3.1,1.18 +51.666,3.158,1.195 +51.69,3.246,1.216 +51.707,3.319,1.235 +51.722,3.393,1.253 +51.736,3.466,1.271 +51.739,3.481,1.275 +51.761,3.617,1.309 +51.773,3.692,1.327 +51.783,3.768,1.346 +51.788,3.813,1.357 +51.799,3.919,1.383 +51.804,3.994,1.401 +51.808,4.07,1.42 +51.811,4.145,1.439 +51.813,4.222,1.457 +51.813,4.237,1.461 +51.812,4.375,1.494 +51.811,4.421,1.505 +51.807,4.531,1.531 +51.802,4.611,1.55 +51.795,4.691,1.569 +51.786,4.771,1.588 +51.776,4.851,1.607 +51.763,4.931,1.626 +51.75,5.01,1.645 +51.747,5.026,1.649 +51.72,5.168,1.683 +51.702,5.247,1.702 +51.687,5.309,1.717 +51.663,5.402,1.74 +51.642,5.479,1.759 +51.618,5.556,1.778 +51.599,5.616,1.793 +51.568,5.706,1.815 +51.54,5.78,1.833 +51.534,5.795,1.837 +51.482,5.929,1.871 +51.451,6.004,1.89 +51.426,6.064,1.905 +51.386,6.153,1.928 +51.35,6.227,1.947 +51.313,6.299,1.966 +51.274,6.372,1.986 +51.233,6.444,2.005 +51.191,6.517,2.025 +51.182,6.532,2.029 +51.102,6.663,2.065 +51.055,6.734,2.086 +51.007,6.804,2.106 +50.958,6.872,2.125 +50.908,6.94,2.145 +50.857,7.006,2.165 +50.805,7.071,2.185 +50.751,7.135,2.204 +50.696,7.197,2.224 +50.685,7.209,2.227 +50.585,7.318,2.262 +50.539,7.366,2.277 +50.469,7.436,2.3 +50.408,7.493,2.32 +50.358,7.539,2.335 +50.282,7.606,2.359 +50.217,7.66,2.379 +50.15,7.714,2.399 +50.082,7.766,2.42 +50.068,7.776,2.424 +49.94,7.869,2.46 +49.896,7.899,2.472 +49.793,7.966,2.5 +49.718,8.012,2.52 +49.643,8.056,2.54 +49.567,8.099,2.56 +49.49,8.141,2.58 +49.411,8.181,2.6 +49.332,8.219,2.62 +49.316,8.226,2.624 +49.173,8.29,2.66 +49.093,8.323,2.68 +49.013,8.355,2.699 +48.933,8.385,2.719 +48.853,8.412,2.738 +48.773,8.438,2.757 +48.693,8.462,2.776 +48.613,8.485,2.796 +48.533,8.507,2.815 +48.517,8.511,2.818 +48.373,8.546,2.853 +48.293,8.562,2.871 +48.213,8.577,2.89 +48.165,8.585,2.901 +48.053,8.602,2.927 +47.972,8.612,2.945 +47.892,8.621,2.964 +47.812,8.628,2.982 +47.732,8.633,3 +47.716,8.634,3.004 +47.574,8.64,3.037 +47.495,8.642,3.055 +47.417,8.642,3.073 +47.339,8.641,3.091 +47.261,8.639,3.109 +47.183,8.635,3.127 +47.105,8.631,-3.138 +47.027,8.624,-3.12 +46.949,8.616,-3.102 +46.933,8.614,-3.098 +46.792,8.599,-3.065 +46.713,8.589,-3.047 +46.65,8.581,-3.033 +46.556,8.565,-3.011 +46.477,8.55,-2.992 +46.398,8.533,-2.973 +46.32,8.516,-2.954 +46.241,8.496,-2.935 +46.162,8.475,-2.915 +46.147,8.47,-2.911 +46.006,8.421,-2.877 +45.975,8.409,-2.869 +45.851,8.357,-2.838 +45.773,8.323,-2.818 +45.697,8.287,-2.797 +45.62,8.249,-2.777 +45.542,8.209,-2.757 +45.466,8.168,-2.737 +45.391,8.125,-2.717 +45.376,8.116,-2.712 +45.243,8.036,-2.676 +45.186,7.999,-2.66 +45.102,7.942,-2.636 +45.033,7.893,-2.616 +44.966,7.843,-2.596 +44.9,7.792,-2.576 +44.835,7.74,-2.556 +44.771,7.687,-2.537 +44.71,7.632,-2.517 +44.697,7.622,-2.513 +44.591,7.523,-2.479 +44.556,7.491,-2.467 +44.478,7.413,-2.441 +44.424,7.356,-2.422 +44.372,7.3,-2.404 +44.321,7.243,-2.385 +44.272,7.185,-2.367 +44.223,7.128,-2.349 +44.177,7.071,-2.331 +44.168,7.059,-2.328 +44.089,6.954,-2.297 +44.047,6.895,-2.28 +44.005,6.836,-2.263 +43.966,6.777,-2.246 +43.958,6.765,-2.243 +43.891,6.657,-2.213 +43.856,6.597,-2.196 +43.822,6.538,-2.18 +43.789,6.478,-2.164 +43.782,6.466,-2.161 +43.727,6.36,-2.132 +43.698,6.302,-2.117 +43.67,6.244,-2.101 +43.643,6.187,-2.086 +43.617,6.129,-2.071 +43.593,6.072,-2.056 +43.57,6.015,-2.041 +43.547,5.958,-2.026 +43.526,5.901,-2.011 +43.521,5.889,-2.008 +43.485,5.788,-1.982 +43.473,5.754,-1.973 +43.446,5.674,-1.952 +43.429,5.617,-1.938 +43.411,5.56,-1.924 +43.395,5.502,-1.91 +43.379,5.443,-1.897 +43.364,5.384,-1.884 +43.348,5.324,-1.872 +43.345,5.312,-1.869 +43.32,5.2,-1.849 +43.307,5.137,-1.838 +43.294,5.072,-1.828 +43.289,5.045,-1.824 +43.268,4.937,-1.809 +43.255,4.867,-1.8 +43.242,4.796,-1.792 +43.228,4.724,-1.784 +43.215,4.65,-1.778 +43.212,4.635,-1.777 +43.187,4.498,-1.767 +43.173,4.421,-1.764 +43.161,4.358,-1.762 +43.143,4.262,-1.759 +43.127,4.181,-1.758 +43.111,4.099,-1.757 +43.094,4.017,-1.758 +43.076,3.933,-1.759 +43.058,3.848,-1.761 +43.054,3.831,-1.762 +43.021,3.681,-1.768 +43.003,3.599,-1.773 +42.999,3.583,-1.774 +42.961,3.435,-1.786 +42.939,3.355,-1.794 +42.917,3.275,-1.803 +42.894,3.196,-1.812 +42.87,3.118,-1.821 +42.845,3.042,-1.831 +42.84,3.027,-1.833 +42.796,2.894,-1.852 +42.771,2.823,-1.864 +42.747,2.752,-1.876 +42.721,2.683,-1.888 +42.695,2.615,-1.9 +42.668,2.548,-1.912 +42.641,2.483,-1.924 +42.613,2.418,-1.937 +42.584,2.355,-1.949 +42.579,2.343,-1.952 +42.524,2.233,-1.974 +42.493,2.173,-1.986 +42.473,2.138,-1.994 +42.428,2.057,-2.012 +42.395,2,-2.025 +42.361,1.945,-2.039 +42.326,1.89,-2.052 +42.291,1.836,-2.065 +42.256,1.783,-2.079 +42.249,1.772,-2.082 +42.182,1.677,-2.107 +42.145,1.624,-2.122 +42.106,1.573,-2.137 +42.067,1.523,-2.152 +42.051,1.504,-2.158 +41.986,1.427,-2.184 +41.945,1.381,-2.201 +41.903,1.336,-2.217 +41.862,1.292,-2.234 +41.853,1.284,-2.237 +41.777,1.208,-2.267 +41.735,1.167,-2.284 +41.691,1.127,-2.3 +41.657,1.097,-2.313 +41.604,1.051,-2.333 +41.56,1.015,-2.349 +41.516,0.979,-2.366 +41.471,0.944,-2.382 +41.426,0.91,-2.398 +41.417,0.903,-2.402 +41.333,0.843,-2.431 +41.285,0.81,-2.448 +41.237,0.778,-2.464 +41.207,0.759,-2.474 +41.148,0.722,-2.494 +41.088,0.686,-2.513 +41.037,0.657,-2.53 +40.986,0.628,-2.546 +40.934,0.601,-2.562 +40.882,0.574,-2.579 +40.829,0.549,-2.595 +40.775,0.524,-2.612 +40.721,0.499,-2.628 +40.666,0.476,-2.644 +40.61,0.453,-2.66 +40.554,0.431,-2.676 +40.497,0.409,-2.691 +40.44,0.387,-2.706 +40.381,0.366,-2.72 +40.369,0.362,-2.723 +40.26,0.324,-2.749 +40.21,0.308,-2.76 +40.134,0.284,-2.777 +40.07,0.265,-2.792 +40.004,0.247,-2.806 +39.938,0.228,-2.82 +39.87,0.211,-2.834 +39.801,0.194,-2.848 +39.73,0.178,-2.861 +39.716,0.174,-2.864 +39.583,0.145,-2.888 +39.507,0.13,-2.901 +39.476,0.123,-2.906 +39.351,0.099,-2.926 +39.271,0.084,-2.938 +39.19,0.07,-2.949 +39.108,0.057,-2.96 +39.042,0.046,-2.969 +38.942,0.032,-2.981 +38.925,0.029,-2.983 +38.771,0.01,-3 +38.684,0.001,-3.01 +38.596,-0.008,-3.019 +38.507,-0.016,-3.027 +38.417,-0.025,-3.034 +38.326,-0.033,-3.042 +38.233,-0.04,-3.049 +38.14,-0.048,-3.055 +38.045,-0.056,-3.061 +38.026,-0.057,-3.062 +37.849,-0.068,-3.07 +37.748,-0.074,-3.075 +37.647,-0.079,-3.08 +37.544,-0.084,-3.084 +37.461,-0.087,-3.088 +37.336,-0.092,-3.093 +37.23,-0.096,-3.098 +37.124,-0.099,-3.102 +37.017,-0.101,-3.107 +36.996,-0.102,-3.108 +36.8,-0.104,-3.116 +36.689,-0.104,-3.12 +36.578,-0.104,-3.124 +36.466,-0.104,-3.128 +36.443,-0.104,-3.128 +36.24,-0.104,-3.133 +36.127,-0.104,-3.135 +36.014,-0.104,-3.136 +35.901,-0.104,-3.137 +35.878,-0.104,-3.137 +35.672,-0.102,-3.137 +35.603,-0.102,-3.137 +35.442,-0.101,-3.137 +35.328,-0.101,-3.136 +35.212,-0.1,-3.136 +35.097,-0.1,-3.136 +34.981,-0.1,-3.135 +34.865,-0.1,-3.135 +34.748,-0.099,-3.135 +34.725,-0.099,-3.136 +34.512,-0.099,-3.136 +34.394,-0.098,-3.137 +34.275,-0.098,-3.138 +34.203,-0.098,-3.138 +34.034,-0.097,-3.139 +33.914,-0.097,-3.139 +33.792,-0.096,-3.139 +33.671,-0.096,-3.14 +33.548,-0.095,-3.14 +33.524,-0.095,-3.14 +33.302,-0.093,-3.141 +33.179,-0.091,3.141 +33.055,-0.09,3.141 +32.932,-0.089,3.14 +32.807,-0.088,3.14 +32.683,-0.087,3.14 +32.558,-0.085,3.139 +32.433,-0.084,3.139 +32.307,-0.083,3.139 +32.282,-0.083,3.139 +32.055,-0.081,3.139 +31.928,-0.08,3.139 +31.827,-0.079,3.139 +31.675,-0.078,3.139 +31.547,-0.077,3.139 +31.42,-0.076,3.139 +31.292,-0.075,3.138 +31.164,-0.074,3.138 +31.061,-0.073,3.138 +31.01,-0.073,3.138 +30.779,-0.071,3.138 +30.651,-0.069,3.138 +30.626,-0.069,3.138 +30.394,-0.067,3.138 +30.265,-0.065,3.138 +30.137,-0.064,3.138 +30.008,-0.063,3.138 +29.881,-0.062,3.138 +29.754,-0.061,3.138 +29.704,-0.06,3.137 +29.506,-0.058,3.138 +29.433,-0.058,3.137 +29.264,-0.057,3.137 +29.144,-0.056,3.137 +29.025,-0.055,3.137 +28.908,-0.054,3.137 +28.79,-0.053,3.137 +28.673,-0.052,3.137 +28.557,-0.052,3.137 +28.442,-0.051,3.137 +28.328,-0.05,3.137 +28.237,-0.049,3.137 +28.101,-0.048,3.137 +27.987,-0.048,3.137 +27.874,-0.047,3.137 +27.761,-0.046,3.137 +27.671,-0.045,3.136 +27.536,-0.045,3.136 +27.423,-0.044,3.136 +27.378,-0.044,3.136 +27.201,-0.042,3.136 +27.091,-0.041,3.136 +26.981,-0.04,3.135 +26.87,-0.039,3.136 +26.848,-0.039,3.136 +26.647,-0.037,3.136 +26.536,-0.036,3.136 +26.424,-0.035,3.136 +26.311,-0.034,3.136 +26.266,-0.034,3.136 +26.082,-0.033,3.136 +25.965,-0.032,3.136 +25.849,-0.031,3.136 +25.732,-0.03,3.136 +25.615,-0.029,3.136 +25.498,-0.029,3.136 +25.381,-0.028,3.136 +25.264,-0.027,3.136 +25.148,-0.026,3.136 +25.124,-0.025,3.136 +24.922,-0.024,3.136 +24.812,-0.023,3.136 +24.701,-0.021,3.136 +24.657,-0.021,3.136 +24.481,-0.019,3.136 +24.371,-0.018,3.136 +24.262,-0.017,3.136 +24.152,-0.016,3.136 +24.043,-0.015,3.136 +24.021,-0.015,3.136 +23.825,-0.015,3.136 +23.781,-0.015,3.136 +23.608,-0.017,3.136 +23.499,-0.017,3.136 +23.391,-0.018,3.136 +23.283,-0.019,3.136 +23.174,-0.02,3.136 +23.066,-0.021,3.136 +22.958,-0.022,3.136 +22.936,-0.022,3.137 +22.738,-0.022,3.137 +22.671,-0.021,3.136 +22.515,-0.02,3.137 +22.403,-0.02,3.136 +22.291,-0.019,3.136 +22.179,-0.019,3.136 +22.066,-0.018,3.136 +21.954,-0.017,3.136 +21.841,-0.016,3.136 +21.819,-0.016,3.136 +21.617,-0.016,3.136 +21.505,-0.016,3.137 +21.46,-0.016,3.137 +21.282,-0.016,3.137 +21.171,-0.016,3.137 +21.061,-0.017,3.137 +20.951,-0.017,3.137 +20.841,-0.017,3.137 +20.731,-0.018,3.137 +20.709,-0.018,3.137 +20.512,-0.017,3.137 +20.402,-0.017,3.137 +20.293,-0.016,3.137 +20.183,-0.015,3.137 +20.074,-0.015,3.137 +19.964,-0.014,3.137 +19.853,-0.014,3.137 +19.742,-0.013,3.137 +19.632,-0.012,3.137 +19.587,-0.012,3.137 +19.409,-0.012,3.137 +19.342,-0.012,3.138 +19.186,-0.011,3.138 +19.074,-0.011,3.138 +18.962,-0.011,3.138 +18.849,-0.011,3.138 +18.736,-0.01,3.137 +18.623,-0.01,3.137 +18.51,-0.01,3.137 +18.487,-0.01,3.137 +18.285,-0.008,3.137 +18.241,-0.008,3.137 +18.061,-0.006,3.137 +17.948,-0.006,3.138 +17.835,-0.005,3.138 +17.722,-0.004,3.138 +17.608,-0.003,3.138 +17.517,-0.002,3.138 +17.379,-0.001,3.138 +17.356,-0.001,3.138 +17.149,0.001,3.138 +17.056,0.001,3.138 +16.917,0.002,3.138 +16.8,0.003,3.138 +16.683,0.004,3.138 +16.567,0.005,3.139 +16.449,0.006,3.139 +16.332,0.006,3.139 +16.215,0.007,3.139 +16.168,0.008,3.139 +15.98,0.008,3.139 +15.863,0.009,3.14 +15.745,0.009,3.14 +15.675,0.009,3.14 +15.51,0.009,3.14 +15.392,0.009,3.14 +15.275,0.009,3.14 +15.157,0.009,3.14 +15.039,0.009,3.14 +14.991,0.009,3.14 +14.802,0.009,3.14 +14.684,0.009,3.14 +14.566,0.009,3.14 +14.448,0.009,3.14 +14.33,0.009,3.141 +14.211,0.009,3.141 +14.093,0.009,3.141 +13.975,0.008,-3.142 +13.857,0.008,-3.141 +13.809,0.008,-3.142 +13.621,0.008,-3.142 +13.504,0.007,-3.142 +13.41,0.007,3.142 +13.268,0.007,-3.142 +13.151,0.006,3.142 +13.033,0.006,-3.141 +12.915,0.006,-3.141 +12.797,0.006,-3.141 +12.679,0.005,-3.141 +12.656,0.005,-3.141 +12.442,0.005,-3.141 +12.324,0.005,-3.141 +12.229,0.004,-3.14 +12.087,0.004,-3.14 +11.969,0.003,-3.14 +11.85,0.003,-3.14 +11.731,0.002,-3.14 +11.612,0.001,-3.141 +11.493,0.001,-3.141 +11.469,0.001,-3.141 +11.255,-0.001,-3.141 +11.16,-0.001,-3.141 +11.017,-0.002,-3.141 +10.897,-0.003,3.142 +10.778,-0.004,-3.141 +10.659,-0.005,-3.141 +10.54,-0.006,-3.141 +10.422,-0.007,-3.141 +10.303,-0.008,-3.141 +10.279,-0.008,-3.141 +10.066,-0.009,3.141 +9.995,-0.009,3.141 +9.83,-0.009,3.141 +9.712,-0.01,3.141 +9.594,-0.01,3.141 +9.477,-0.01,3.141 +9.36,-0.01,3.14 +9.243,-0.01,3.14 +9.126,-0.011,3.14 +9.01,-0.011,3.14 +8.895,-0.011,3.141 +8.78,-0.01,3.14 +8.665,-0.01,3.141 +8.551,-0.01,3.141 +8.529,-0.01,3.141 +8.324,-0.011,3.14 +8.211,-0.011,3.14 +8.098,-0.011,3.14 +7.985,-0.011,3.14 +7.873,-0.011,3.14 +7.76,-0.012,3.139 +7.647,-0.013,3.139 +7.535,-0.013,3.139 +7.445,-0.014,3.139 +7.311,-0.015,3.139 +7.199,-0.015,3.139 +7.088,-0.016,3.139 +6.977,-0.016,3.139 +6.867,-0.017,3.139 +6.757,-0.018,3.139 +6.648,-0.018,3.139 +6.604,-0.019,3.139 +6.43,-0.019,3.138 +6.322,-0.02,3.138 +6.213,-0.021,3.138 +6.105,-0.021,3.138 +5.997,-0.022,3.137 +5.889,-0.022,3.137 +5.782,-0.022,3.137 +5.676,-0.023,3.137 +5.572,-0.023,3.137 +5.467,-0.023,3.137 +5.363,-0.023,3.137 +5.28,-0.024,3.137 +5.156,-0.024,3.137 +5.053,-0.024,3.137 +4.95,-0.024,3.137 +4.847,-0.025,3.136 +4.744,-0.025,3.136 +4.64,-0.025,3.136 +4.535,-0.025,3.136 +4.43,-0.026,3.136 +4.346,-0.026,3.135 +4.22,-0.026,3.135 +4.116,-0.027,3.135 +4.011,-0.027,3.135 +3.907,-0.027,3.135 +3.803,-0.028,3.135 +3.698,-0.028,3.135 +3.595,-0.027,3.135 +3.493,-0.021,3.135 +3.391,-0.016,3.135 +3.371,-0.014,3.135 +3.189,-0.006,3.135 +3.088,0,3.135 +2.988,0.004,3.134 +2.888,0.01,3.134 +2.788,0.015,3.134 +2.688,0.02,3.134 +2.59,0.024,3.133 +2.493,0.026,3.133 +2.416,0.027,3.133 +2.303,0.029,3.133 +2.211,0.03,3.133 +2.121,0.032,3.133 +2.032,0.033,3.132 +1.944,0.035,3.132 +1.858,0.036,3.133 +1.773,0.038,3.133 +1.707,0.039,3.132 +1.61,0.04,3.132 +1.578,0.04,3.132 +1.452,0.042,3.132 +1.375,0.043,3.132 +1.3,0.043,3.132 +1.227,0.044,3.132 +1.156,0.044,3.132 +1.088,0.045,3.132 +1.024,0.046,3.132 +0.963,0.046,3.132 +0.908,0.049,3.131 +0.856,0.051,3.131 +0.808,0.054,3.131 +0.764,0.056,3.131 +0.748,0.056,3.131 +0.69,0.059,3.131 +0.66,0.061,3.131 +0.634,0.063,3.131 +0.612,0.065,3.131 +0.597,0.066,3.131 +0.577,0.066,3.131 +0.565,0.065,3.131 +0.556,0.065,3.131 +0.552,0.065,3.131 diff --git a/GEMstack/knowledge/vehicle/__init__.py b/GEMstack/knowledge/vehicle/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/GEMstack/knowledge/vehicle/dynamics.py b/GEMstack/knowledge/vehicle/dynamics.py new file mode 100644 index 000000000..2954a1612 --- /dev/null +++ b/GEMstack/knowledge/vehicle/dynamics.py @@ -0,0 +1,82 @@ +from ...utils import settings +from typing import Tuple +import math + +def acceleration_to_pedal_positions(acceleration : float, velocity : float, pitch : float, gear : int) -> Tuple[float,float,int]: + """Converts acceleration in m/s^2 to pedal positions in % of pedal travel. + + Returns tuple (accelerator_pedal_position, brake_pedal_position, desired_gear) + """ + brake_max = settings.get('vehicle.dynamics.max_brake_deceleration') + reverse_accel_max = settings.get('vehicle.dynamics.max_accelerator_acceleration_reverse') + accel_max = settings.get('vehicle.dynamics.max_accelerator_acceleration') + + #compute required acceleration + vsign = (velocity/abs(velocity)) + gravity = settings.get('vehicle.dynamics.gravity') + internal_viscous_deceleration = settings.get('vehicle.dynamics.internal_viscous_deceleration') + aerodynamic_drag_coefficient = settings.get('vehicle.dynamics.aerodynamic_drag_coefficient') + drag = -(aerodynamic_drag_coefficient * velocity**2) * vsign - internal_viscous_deceleration * velocity + sin_pitch = math.sin(pitch) + acceleration += drag + gravity * sin_pitch + + #TODO: power curves to select optimal gear + if velocity * acceleration < 0: + accel_pos = 0 + brake_pos = -acceleration / brake_max + if brake_pos > 1.0: + brake_pos = 1.0 + return (accel_pos,brake_pos,gear) + else: + #may want to switch gear? + if velocity == 0: + if acceleration < 0: + gear = -1 + else: + #forward gear + gear = 1 + if gear < 0: + #reverse gear + accel_pos = -acceleration / reverse_accel_max + brake_pos = 0 + if accel_pos > 1.0: + accel_pos = 1.0 + return (accel_pos,brake_pos,-1) + elif gear > 0: + accel_pos = acceleration / accel_max[gear] + brake_pos = 0 + if accel_pos > 1.0: + accel_pos = 1.0 + return (accel_pos,brake_pos,gear) + else: + #stay in neutral gear + return (0,1,0) + +def pedal_positions_to_acceleration(accelerator_pedal_position : float, brake_pedal_position : float, velocity : float, pitch : float, gear : int) -> float: + """Converts pedal positions in % of pedal travel to acceleration in m/s^2. + + Simulates drag, gravity, and internal viscous deceleration. + + Does not yet simulate velocity-dependent power. + + Returns acceleration + """ + brake_max = settings.get('vehicle.dynamics.max_brake_deceleration') + reverse_accel_max = settings.get('vehicle.dynamics.max_accelerator_acceleration_reverse') + accel_max = settings.get('vehicle.dynamics.max_accelerator_acceleration') + brake_accel = brake_max * brake_pedal_position + if gear < 0: + accel = reverse_accel_max * accelerator_pedal_position + else: + accel = accel_max[gear] * accelerator_pedal_position + vsign = (velocity/abs(velocity)) + gravity = settings.get('vehicle.dynamics.gravity') + internal_viscous_deceleration = settings.get('vehicle.dynamics.internal_viscous_deceleration') + aerodynamic_drag_coefficient = settings.get('vehicle.dynamics.aerodynamic_drag_coefficient') + drag = -(aerodynamic_drag_coefficient * velocity**2) * vsign - internal_viscous_deceleration * velocity + sin_pitch = math.sin(pitch) + if velocity == 0: + #does gravity overcome static friction from braking? + if abs(accel - gravity * sin_pitch) < brake_accel: + return 0 + return accel - brake_accel - drag - gravity * sin_pitch diff --git a/GEMstack/knowledge/vehicle/geometry.py b/GEMstack/knowledge/vehicle/geometry.py new file mode 100644 index 000000000..1c9bb6754 --- /dev/null +++ b/GEMstack/knowledge/vehicle/geometry.py @@ -0,0 +1,58 @@ +from ...utils import settings +import math + +def clamp_wheel_angle(wheel_angle : float) -> float: + """Clamps the wheel angle to the range defined in the settings.""" + return max(settings.get('vehicle.limits.wheel_angle_min'), min(settings.get('vehicle.limits.wheel_angle_max'), wheel_angle)) + +def clamp_steering_angle(wheel_angle : float) -> float: + """Clamps the steering angle to the range defined in the settings.""" + return max(settings.get('vehicle.limits.steering_angle_min'), min(settings.get('vehicle.limits.steering_angle_max'), wheel_angle)) + +def front2steer_degrees(f_angle : float) -> float: + """Conversion of front wheel to steering wheel angle. + Both input and output are in degrees. + + No clamping is done: the caller should clamp the input to + the steering wheel range defined in the settings. + """ + if (f_angle > 0): + steer_angle = -0.1084*f_angle**2 + 21.775*f_angle + else: + steer_angle = 0.1084*f_angle**2 + 21.775*f_angle + return steer_angle + +def front2steer(f_angle : float): + """Conversion of front wheel to steering wheel angle. + Both input and output are in radians.""" + return math.radians(front2steer_degrees(math.degrees(f_angle))) + +# y = a x**2 + b x => 0 = a x**2 + b x - y +# => x = (-b +- sqrt(b**2 - 4 a (-y))) / (2 a) +# since we need the positive solution, we can ignore the negative one + +def steer2front_degrees(s_angle : float) -> float: + """Conversion of steering wheel to front wheel angle. + Both input and output are in degrees. + + No clamping is done: the caller should clamp the input to + the steering wheel range defined in the settings. + """ + if (s_angle > 0): + a = -0.1084 + b = 21.775 + front_angle = -b + math.sqrt(b**2 - 4*a*(-s_angle)) / (2*a) + else: + a = 0.1084 + b = 21.775 + front_angle = -b - math.sqrt(b**2 - 4*a*(-s_angle)) / (2*a) + return front_angle + +def steer2front(s_angle : float): + """Conversion of front wheel to steering wheel angle. + Both input and output are in radians.""" + return math.radians(steer2front_degrees(math.degrees(s_angle))) + +def heading_rate(front_angle : float, speed : float, wheelbase : float) -> float: + """Returns the heading rate in radians/sec given the front wheel angle, speed, and wheelbase.""" + return math.tan(front_angle) * speed / wheelbase \ No newline at end of file diff --git a/GEMstack/launch/README.md b/GEMstack/launch/README.md new file mode 100644 index 000000000..d90eabc06 --- /dev/null +++ b/GEMstack/launch/README.md @@ -0,0 +1 @@ +Contains launch scripts for use in the standard executor, e.g., `python main.py launch/fixed_route_sim.yaml`. diff --git a/GEMstack/launch/fixed_route.yaml b/GEMstack/launch/fixed_route.yaml new file mode 100644 index 000000000..56e35d17d --- /dev/null +++ b/GEMstack/launch/fixed_route.yaml @@ -0,0 +1,27 @@ +mode: hardware +vehicle_interface: gem_hardware.GEMHardwareInterface +mission_execution: StandardExecutor +# Recovery behavior after a component failure +recovery: + planning: + trajectory_tracking : recovery.StopTrajectoryTracker +# Driving behavior for the GEM vehicle following a fixed route +drive: + perception: + state_estimation : GNSSStateEstimator + perception_normalization : StandardPerceptionNormalizer + planning: + route_planning: + type: StaticRoutePlanner + args: [!relative_path '../routes/xyhead_demo_pp.csv'] + motion_planning: RouteToTrajectoryPlanner + trajectory_tracking: pure_pursuit.PurePursuitTrajectoryTracker +log: + ros_topics : [] + components : ['state_estimation','trajectory_tracking'] +replay: #add items here to set certain topics / inputs to be replayed from logs + ros_topics : [] + components : [] + +#usually can keep this constant +computation_graph: !include "../knowledge/defaults/computation_graph.yaml" \ No newline at end of file diff --git a/GEMstack/launch/fixed_route_sim.yaml b/GEMstack/launch/fixed_route_sim.yaml new file mode 100644 index 000000000..e84278667 --- /dev/null +++ b/GEMstack/launch/fixed_route_sim.yaml @@ -0,0 +1,35 @@ +mode: simulation +vehicle_interface: + type: gem_simulator.GEMDoubleIntegratorSimulationInterface + args: + scene: !relative_path '../scenes/xyhead_demo.yaml' +mission_execution: StandardExecutor + +# "recovery" pipeline: Recovery behavior after a component failure +recovery: + planning: + trajectory_tracking : recovery.StopTrajectoryTracker + +# "drive" pipeline: Driving behavior for the GEM vehicle following a fixed route +drive: + perception: + state_estimation : FakeStateEstimator + perception_normalization : StandardPerceptionNormalizer + planning: + route_planning: + type: StaticRoutePlanner + args: [!relative_path '../routes/xyhead_demo_pp.csv'] + motion_planning: RouteToTrajectoryPlanner + trajectory_tracking: pure_pursuit.PurePursuitTrajectoryTracker + +log: + ros_topics : [] + components : ['state_estimation','trajectory_tracking'] +replay: #add items here to set certain topics / inputs to be replayed from logs + log: + ros_topics : [] + components : [] + +#usually can keep this constant +computation_graph: !include "../knowledge/defaults/computation_graph.yaml" + diff --git a/GEMstack/mathutils/__init__.py b/GEMstack/mathutils/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/GEMstack/mathutils/collisions.py b/GEMstack/mathutils/collisions.py new file mode 100644 index 000000000..3ee293c3f --- /dev/null +++ b/GEMstack/mathutils/collisions.py @@ -0,0 +1,9 @@ +import shapely + +def point_in_polygon_2d(point, polygon): + """Returns true if the given point is inside the given polygon. + + Faster to create a CollisionDetector object if you will be doing + multiple queries. + """ + return shapely.Polygon(polygon).contains(shapely.Point(point[0], point[1])) diff --git a/GEMstack/mathutils/control.py b/GEMstack/mathutils/control.py new file mode 100644 index 000000000..8123d90ca --- /dev/null +++ b/GEMstack/mathutils/control.py @@ -0,0 +1,78 @@ +class PID(object): + """Generic SISO PID controller. + + Parameters: + kp (float): proportional gain + ki (float): integral gain + kd (float): derivative gain + windup_limit (optional, float): limit on the integral term. Defaults + to None, which means no limit. + difference_jump_threshold (optional, float): threshold used to + determine discontinuities between two consecutive errors. If + the difference is greater than this threshold, the derivative + term is set to 0. Defaults to 0.5. + """ + def __init__(self, kp : float, ki : float, kd : float, windup_limit : float = None, difference_jump_threshold : float = 0.5): + self.iterm = 0.0 + self.last_t = None + self.last_e = 0.0 + self.kp = kp + self.ki = ki + self.kd = kd + self.wg = windup_limit + self.dg = difference_jump_threshold + self.derror = 0.0 #differenced error, for debugging + + def reset(self): + self.iterm = 0.0 + self.last_e = 0.0 + self.last_t = None + + def advance(self, + e : float, + de : float = None, + t : float = None, + dt : float = None, + feedforward_term : float = 0) -> float: + """Parameters: + e (float): error + de (optional, float): error derivative. If not provided, will be + computed via finite differences. + t (optional, float): time. Either dt or t must be provided for D or + I term to have any effect. + dt (optional, float): time step. Either dt or t must be provided + for the D or I term to have any effect. + feedforward_term (optional, float): feedforward term to add to the + output. Defaults to 0. + """ + if de is None: + if dt is None: + if self.last_t is None: + self.last_t = t + dt = (t - self.last_t) + + #finite differences + if dt == 0.0: + de = 0.0 + else: + de = (e - self.last_e) / dt + + if abs(e - self.last_e) > self.dg: + de = 0.0 + if dt is None: + dt = 0 + + self.iterm += e * dt + + # take care of integral winding-up + if self.wg is not None: + if self.iterm > self.wg: + self.iterm = self.wg + elif self.iterm < -self.wg: + self.iterm = -self.wg + + self.last_e = e + self.last_t = t + self.derror = de + + return feedforward_term + self.kp * e + self.ki * self.iterm + self.kd * de diff --git a/GEMstack/mathutils/differences.py b/GEMstack/mathutils/differences.py new file mode 100644 index 000000000..ce73f5214 --- /dev/null +++ b/GEMstack/mathutils/differences.py @@ -0,0 +1,86 @@ +import numpy as np + +def gradient_forward_difference(f,x,h): + """Approximation of the gradient of f(x) using forward differences with step size h""" + g = np.zeros(len(x)) + f0 = f(x) + for i in range(len(x)): + v = x[i] + x[i] += h + g[i] = (f(x)-f0) + x[i] = v + g *= 1.0/h + return g + +def jacobian_forward_difference(f,x,h): + """Approximation of the Jacobian of vector function f(x) using forward differences with step size h""" + f0 = np.asarray(f(x)) + J = np.zeros((len(f0),len(x))) + for i in range(len(x)): + v = x[i] + x[i] += h + J[:,i] = (np.asarray(f(x))-f0) + x[i] = v + J *= 1.0/h + return J + +def hessian_forward_difference(f,x,h): + """Approximation of the hessian of f(x) using forward differences with + step size h. + """ + H = np.zeros((len(x),len(x))) + f0 = f(x) + fs = [] + for i in range(len(x)): + v = x[i] + x[i] += h + fs.append(f(x)) + x[i] = v + for i in range(len(x)): + v = x[i] + x[i] += h + for j in range(i): + w = x[j] + x[j] += h + fij = f(x) + H[i,j] = (fij-fs[j]) - (fs[i]-f0) + H[j,i] = H[i,j] + x[j] = w + x[i] = v + x[i] -= h + fij = f(x) + H[i,i] = (fs[i]-f0) - (f0-fij) + x[i] = v + H *= 1.0/h**2 + return H + +def hessian2_forward_difference(f,x,y,h): + """Approximation of the hessian of a 2-parameter function f(x,y) w.r.t. x and y + using forward differences with step size h. + """ + H = np.zeros((len(x),len(y))) + f0 = f(x,y) + fxs = [] + fys = [] + for i in range(len(x)): + v = x[i] + x[i] += h + fxs.append(f(x,y)) + x[i] = v + for i in range(len(y)): + v = y[i] + y[i] += h + fys.append(f(x,y)) + y[i] = v + for i in range(len(x)): + v = x[i] + x[i] += h + for j in range(len(y)): + w = y[j] + y[j] += h + fij = f(x,y) + H[i,j] = ((fij-fys[j]) - (fxs[i]-f0)) + y[j] = w + x[i] = v + H *= 1.0/h**2 + return H diff --git a/GEMstack/mathutils/dubins.py b/GEMstack/mathutils/dubins.py new file mode 100644 index 000000000..0d60898ae --- /dev/null +++ b/GEMstack/mathutils/dubins.py @@ -0,0 +1,117 @@ + + +from .dynamics import Dynamics, ControlSpace +from .transforms import vector_add,vector_madd,rotate2d,normalize_angle +import numpy as np + +def cmp(x,y): + if x < y: return -1 + elif x > y: return 1 + return 0 + +class DubinsCar(Dynamics): + """Defines a first-order Dubins car state space with x = (tx,ty,theta) + and u = (fwd_velocity,turnRate). + + If phi is the front wheel angle, then the turn rate is + tan(phi)/L, where L is the wheelbase. + """ + def __init__(self,turnRateMin=-1,turnRateMax=1): + self.turnRateRange = [turnRateMin,turnRateMax] + self.velocityRange = [-1.0,1.0] + + def stateDimension(self): + return 3 + + def controlDimension(self): + return 2 + + def clampControls(self,u): + """Clamps the controls to the control range.""" + u[0] = np.clip(u[0],self.velocityRange[0],self.velocityRange[1]) + u[1] = np.clip(u[1],self.turnRateRange[0],self.turnRateRange[1]) + return u + + def derivative(self,x,u): + """Returns x' = f(x,u). + + No clamping is performed on the control inputs. + """ + assert len(x) == 3 + assert len(u) == 2 + pos = [x[0],x[1]] + fwd = [np.cos(x[2]),np.sin(x[2])] + right = [-fwd[1],fwd[0]] + phi = u[1] + d = u[0] + return np.array([fwd[0]*d,fwd[1]*d,phi]) + + +class DubinsCarIntegrator(ControlSpace): + """A ControlSpace that integrates a DubinsCar by duration T and integration + timestep dt.""" + def __init__(self,dubins,T=1,dt=1e-2): + self.dubins = dubins + self.T = T + self.dt = dt + + def nextState(self,x,u): + assert len(x) == 3 + assert len(u) == 2 + pos = [x[0],x[1]] + fwd = [np.cos(x[2]),np.sin(x[2])] + right = [-fwd[1],fwd[0]] + phi = u[1] + d = u[0]*self.T + if abs(phi)<1e-8: + newpos = vector_madd(pos,fwd,d) + return np.array(newpos + [x[2]]) + else: + #rotate about a center of rotation, with radius 1/phi + cor = vector_madd(pos,right,1.0/phi) + sign = cmp(d*phi,0) + d = abs(d) + phi = abs(phi) + thetaMax=d*phi + newpos = rotate2d(pos,sign*thetaMax,cor) + return np.array(newpos + [normalize_angle(x[2]+sign*thetaMax)]) + + +class SecondOrderDubinsCar(Dynamics): + """Defines a second-order Dubins car state space with + x = (tx,ty,theta,v,dtheta) and u = (fwd_accel,wheel_angle_rate). + + """ + def __init__(self, + wheelAngleMin=-1,wheelAngleMax=1, + velocityMin=-1.0,velocityMax=1.0, + wheelAngleRateMin=-1,wheelAngleRateMax=1, + accelMin=-1.0,accelMax=1.0, + wheelBase = 1.0): + self.wheelAngleRange = [wheelAngleMin,wheelAngleMax] + self.velocityRange = [velocityMin,velocityMax] + self.wheelAngleRateRange = [wheelAngleRateMin,wheelAngleRateMax] + self.accelRange = [accelMin,accelMax] + self.wheelBase = wheelBase + self.dubins = DubinsCar() + + def stateDimension(self): + return 5 + + def controlDimension(self): + return 2 + + def clampControls(self,u): + """Clamps the controls to the control range.""" + u[0] = np.clip(u[0],self.accelRange[0],self.accelRange[1]) + u[1] = np.clip(u[1],self.wheelAngleRateRange[0],self.wheelAngleRateRange[1]) + return u + + def derivative(self,x,u): + """Returns x' = f(x,u)""" + assert len(x) == 5 + assert len(u) == 2 + v,phi = x[3:5] + turn_rate = np.tan(phi)/self.wheelBase + return np.hstack(self.dubins(x[:3],[v,turn_rate]),[u[0],u[1]]) + \ No newline at end of file diff --git a/GEMstack/mathutils/dynamics.py b/GEMstack/mathutils/dynamics.py new file mode 100644 index 000000000..8262d067c --- /dev/null +++ b/GEMstack/mathutils/dynamics.py @@ -0,0 +1,221 @@ +import math +from klampt.math import so2,vectorops +import numpy as np +from . import differences +import numpy as np + +MAX_INTEGRATION_STEPS = 10000 + +class ControlSpace: + """A generic state space with states x and control variable u. The primary + function of this class is to define the transformation + + xnext = nextState(x,u). + + """ + def __init__(self): + pass + def stateDimension(self): + """Returns the dimension of the state space associated with this.""" + raise NotImplementedError() + def controlDimension(self): + """Returns the set from which controls should be sampled""" + raise NotImplementedError() + def nextState(self,x,u): + """Produce the next state after applying control u to state x""" + raise NotImplementedError() + def interpolator(self,x,u): + """Returns the interpolator (e.g., a trajectory) that goes from x to + self.nextState(x,u).""" + raise NotImplementedError() + def connection(self,x,y): + """Returns a sequence of controls that connects x to y, if + applicable. Return None if no such sequence exists.""" + return None + + def nextState_jacobian(self,x,u): + """Returns a pair of Jacobian matrices dx_n/dx, dx_n/du of + the nextState(x,u) function. + + Subclasses can use nextState_jacobian_diff to approximate + the Jacobian.""" + return self.nextState_jacobian_diff(x,u) + + def nextState_jacobian_diff(self,x,u,h=1e-4): + Jx = differences.jacobian_forward_difference((lambda y:self.nextState(y,u)),x,h) + Ju = differences.jacobian_forward_difference((lambda v:self.nextState(x,v)),u,h) + return (Jx,Ju) + + def checkDerivatives(self,x,u,baseTol=1e-3): + Jx,Ju = self.nextState_jacobian(x,u) + dJx,dJu = self.nextState_jacobian_diff(x,u) + xtol = max(1,np.linalg.norm(dJx))*baseTol + utol = max(1,np.linalg.norm(dJu))*baseTol + res = True + if np.linalg.norm(Jx-dJx) > xtol: + print("Derivatives of ControlSpace",self.__class__.__name__,"incorrect in Jacobian x by",np.linalg.norm(Jx-dJx),"diff norm",np.linalg.norm(dJx)) + #print(" Computed",Jx) + #print(" Differenced",dJx) + res = False + if np.linalg.norm(Ju-dJu) > utol: + print("Derivatives of ControlSpace",self.__class__.__name__,"incorrect in Jacobian u by",np.linalg.norm(Ju-dJu),"diff norm",np.linalg.norm(dJu)) + #print(" Computed",Ju) + #print(" Differenced",dJu) + res = False + return res + + +class LTIControlSpace(ControlSpace): + """Implements a discrete-time, linear time invariant control + space f(x,u) = Ax+Bu. + """ + def __init__(self,A,B): + self.A = A + self.B = B + if self.A.shape[0] != self.A.shape[1]: + raise ValueError("A matrix must be square") + if self.A.shape[0] != self.B.shape[0]: + raise ValueError("Matrices are of incompatible shape") + def stateDimension(self): + return self.A.shape[0] + def controlDimension(self): + return self.B.shape[1] + def nextState(self,x,u): + return self.A.dot(x) + self.B.dot(u) + def connection(self,x,y): + #TODO: solve for multi-step control (if controllable) + if self.B.shape[1] < self.B.shape[0]: return None + xn = self.A.dot(x) + dx = np.asarray(y)-np.asarray(xn) + Binv = np.linalg.pinv(self.B) + return [Binv.dot(dx)] + def nextState_jacobian(self,x,u): + return self.A,self.B + + +class Dynamics: + """A generic differential equation relating state x to control variable u. + The derivative() method gives diffential constraints x'=f(x,u). + + Convert this into a ControlSpace by using IntegratorControlSpace. + """ + def stateDimension(self): + raise NotImplementedError() + def controlDimension(self): + raise NotImplementedError() + def derivative(self,x,u): + raise NotImplementedError() + def derivative_jacobian(self,x,u): + """Returns a pair of Jacobian matrices dx'/dx, dx'/du of + the derivative(x,u) function. + """ + return self.derivative_jacobian_diff(x,u) + + def derivative_jacobian_diff(self,x,u,h=1e-4): + Jx = differences.jacobian_forward_difference((lambda y:self.derivative(y,u)),x,h) + Ju = differences.jacobian_forward_difference((lambda v:self.derivative(x,v)),u,h) + return (Jx,Ju) + + def checkDerivatives(self,x,u,baseTol=1e-3): + Jx,Ju = self.derivative_jacobian(x,u) + dJx,dJu = self.derivative_jacobian_diff(x,u) + xtol = max(1,np.linalg.norm(dJx))*baseTol + utol = max(1,np.linalg.norm(dJu))*baseTol + res = True + if np.linalg.norm(Jx-dJx) > xtol: + print("Derivatives of Dynamics",self.__class__.__name__,"incorrect in Jacobian x by",np.linalg.norm(Jx-dJx),"diff norm",np.linalg.norm(dJx)) + #print(" Computed",Jx) + #print(" Differenced",dJx) + res = False + if np.linalg.norm(Ju-dJu) > utol: + print("Derivatives of Dynamics",self.__class__.__name__,"incorrect in Jacobian u by",np.linalg.norm(Ju-dJu),"diff norm",np.linalg.norm(dJu)) + #print(" Computed",Ju) + #print(" Differenced",dJu) + res = False + return res + + def integrate(self,x,dx): + """For non-Euclidean (e.g., geodesic) spaces, implement this.""" + return x+dx + + +class IntegratorControlSpace (ControlSpace): + """A control space that performs integration of a differential equation + to determine the next state. + + The derivative function x'=f(x,u) is translated into a nextState + function xnext = g(x,u) via integration over the duration T at the + resolution dt. + + Euler integration is used. TODO: use higher order methods. + """ + def __init__(self,dynamics : Dynamics, T : float = 1.0, dt : float=0.01): + self.dynamics = dynamics + self.T = T + self.dt = dt + def stateDimension(self): + return self.dynamics.stateDimension() + def controlDimension(self): + return self.dynamics.controlDimension() + def trajectory(self,x,u) -> list: + duration = self.T + path = [x] + t = 0.0 + assert self.dt > 0 + dt0 = self.dt + if duration / self.dt > MAX_INTEGRATION_STEPS: + print("Warning, more than",MAX_INTEGRATION_STEPS,"steps requested for IntegratorControlSpace",self.__class__.__name__) + dt0 = duration/MAX_INTEGRATION_STEPS + while t < duration: + dx = self.dynamics.derivative(path[-1],u) + assert len(dx)==len(x),"Derivative %s dimension not equal to state dimension: %d != %d"%(self.dynamics.__class__.__name__,len(dx),len(x)) + dt = min(dt0,duration-t) + xnew = self.dynamics.integrate(path[-1],dx*dt) + path.append(xnew) + t = min(t+dt0,duration) + return path + def nextState(self,x,u): + return self.trajectory(x,u)[-1] + def nextState_jacobian(self,x,u): + if self.dt < self.T: + #don't yet know how to do compounding derivative of trajectory + return self.nextState_jacobian_diff(x,u) + else: + dx,du = self.dynamics.derivative_jacobian(x,u) + return np.eye(len(x))+dx*self.dt,du*self.dt + def interpolator(self,x,u): + return self.trajectory(x,u) + + +def simulate(dynamics,x0,ufunc,T=1,dt=1e-3): + """Returns a simulation trace of dynamics using Euler integration over + duration T and time step dt. + + Args: + dynamics (Dynamics): the system. + x0 (np.ndarray): the initial state. + ufunc (callable): a policy u(t,x) returning a control vector. + T (float): integration duration + dt (float): time step + + Returns: + dict: maps 't', 'x', 'u', 'dx' to traces of these time, state, control, + and derivative, respectively. The traces for t and x are 1 longer + than the traces for u and dx + """ + assert len(x0)==dynamics.stateDimension() + res = dict((idx,[]) for idx in ['t','x','u','dx']) + t = 0 + while t < T: + u = ufunc(t,x0) + assert len(u) == dynamics.controlDimension() + dx = dynamics.derivative(x0,u) + res['t'].append(t) + res['x'].append(x0) + res['dx'].append(dx) + res['u'].append(u) + x0 = dynamics.integrate(x0,dt*dx) + t += dt + res['t'].append(t) + res['x'].append(x0) + return res diff --git a/GEMstack/mathutils/signal.py b/GEMstack/mathutils/signal.py new file mode 100644 index 000000000..aa40cceac --- /dev/null +++ b/GEMstack/mathutils/signal.py @@ -0,0 +1,25 @@ +import scipy.signal as signal +from typing import Sequence + +class OnlineLowPassFilter(object): + def __init__(self, cutoff : float, sampling_frequency : float, order : int): + + nyq = 0.5 * sampling_frequency + normal_cutoff = cutoff / nyq + + # Get the filter coefficients + self.b, self.a = signal.butter(order, normal_cutoff, btype='lowpass', analog=False) + + # Initialize + self.z = signal.lfilter_zi(self.b, self.a) + + def __call__(self, data: float): + filtered, self.z = signal.lfilter(self.b, self.a, [data], zi=self.z) + return filtered + + def reset(self) -> None: + self.z = signal.lfilter_zi(self.b, self.a) + + def filter(self, time_series : Sequence[float]) -> Sequence[float]: + """Filters a time series""" + return signal.lfilter(self.b, self.a, time_series) diff --git a/GEMstack/mathutils/transforms.py b/GEMstack/mathutils/transforms.py new file mode 100644 index 000000000..beb2f286f --- /dev/null +++ b/GEMstack/mathutils/transforms.py @@ -0,0 +1,100 @@ + +import numpy as np +from klampt.math import vectorops as vo +from klampt.math import so2 + +def normalize_angle(angle : float) -> float: + """Normalizes an angle to be in the range [0,2pi]""" + return so2.normalize(angle) + +def normalize_vector(v): + """Normalizes a vector""" + return vo.unit(v) + +def vector_add(v1, v2): + """Adds v1 + v2 between two vectors""" + return vo.add(v1,v2) + +def vector_madd(v1, v2, s:float): + """Returns v1 + v2*s""" + return vo.madd(v1,v2,s) + +def vector_sub(v1, v2): + """Subtracts v1 - v2 between two vectors""" + return vo.sub(v1,v2) + +def vector_norm(v) -> float: + """Norm of a vector""" + return vo.norm(v) + +def vector_dist(v1, v2) -> float: + """Euclidean distance between two vectors""" + return vo.distance(v1,v2) + +def vector2_angle(v1, v2 = None) -> float: + """find the ccw angle bewtween two 2d vectors""" + if v2 is None: + cosang = v1[0] + sinang = v1[1] + else: + cosang = np.dot(v1, v2) + sinang = np.cross(v1, v2) + return np.arctan2(sinang, cosang) + +def vector2_dist(v1, v2) -> float: + """Euclidean distance between two 2D vectors""" + return np.linalg.norm([v1[0] - v2[0], v1[1] - v2[1]]) + +def rotate2d(point, angle : float, origin=None): + """Rotates a point about the origin by an angle""" + if origin is None: + return so2.apply(angle, point) + else: + return vo.add(origin,so2.apply(angle, vo.sub(point,origin))) + +def heading_to_yaw(heading : float, degrees=True) -> float: + """Conversion of GNSS heading (CW from north) to yaw (CCW w.r.t. east). + + If degrees is True, heading is in degrees, otherwise radians. + """ + if not degrees: + heading = np.degrees(heading) + if heading >= 0 and heading < 90: + return np.radians(-heading+90) + else: + return np.radians(-heading+450) + +def yaw_to_heading(yaw : float, degrees=True) -> float: + """Conversion of yaw (CCW w.r.t. east) to GNSS heading (CW from north). + + If degrees is True, heading will be reported in in degrees, otherwise + radians. + """ + yaw_degrees = np.degrees(yaw) + heading_degrees = -yaw_degrees + 90 + if heading_degrees < 0: + heading_degrees += 360 + if degrees: + return heading_degrees + else: + return np.radians(heading_degrees) + +def lat_lon_to_xy(lat : float, lon : float, lat_reference : float, lon_reference : float): + """ Conversion of Lat & Lon to X & Y. + + Returns (x,y), where x is east in m, y is north in m. + """ + import alvinxy.alvinxy as axy + # convert GNSS waypoints into local fixed frame reprented in x and y + east_x, north_y = axy.ll2xy(lat, lon, lat_reference, lon_reference) + return east_x, north_y + +def xy_to_lat_lon(x_east : float, y_north : float, lat_reference : float, lon_reference : float): + """ Conversion of X & Y to Lat & Lon. + + Returns (lat,lon), where lat and lon are in degrees. + """ + import alvinxy.alvinxy as axy + # convert GNSS waypoints into local fixed frame reprented in x and y + lat, lon = axy.xy2ll(x_east, y_north, lat_reference, lon_reference) + return lat, lon diff --git a/GEMstack/offboard/__init__.py b/GEMstack/offboard/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/GEMstack/offboard/calibration/__init__.py b/GEMstack/offboard/calibration/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/GEMstack/offboard/detection_learning/__init__.py b/GEMstack/offboard/detection_learning/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/GEMstack/offboard/heuristic_learning/__init__.py b/GEMstack/offboard/heuristic_learning/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/GEMstack/offboard/log_management/__init__.py b/GEMstack/offboard/log_management/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/GEMstack/offboard/prediction_learning/__init__.py b/GEMstack/offboard/prediction_learning/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/GEMstack/onboard/__init__.py b/GEMstack/onboard/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/GEMstack/onboard/component.py b/GEMstack/onboard/component.py new file mode 100644 index 000000000..25dbc5549 --- /dev/null +++ b/GEMstack/onboard/component.py @@ -0,0 +1,19 @@ +from typing import List + +class Component: + """Base class for top-level components in the execution stack.""" + def rate(self) -> float: + """Returns the rate in Hz at which this component should be updated.""" + return 10.0 + def state_inputs(self) -> List[str]: + """Returns the list of AllState inputs this component requires.""" + return [] + def state_outputs(self) -> List[str]: + """Returns the list of AllState outputs this component generates.""" + return [] + def healthy(self): + """Returns True if the element is in a stable state.""" + return True + def update(self, *args, **kwargs): + """Update the component.""" + raise NotImplementedError() diff --git a/GEMstack/onboard/execution/__init__.py b/GEMstack/onboard/execution/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/GEMstack/onboard/execution/entrypoint.py b/GEMstack/onboard/execution/entrypoint.py new file mode 100644 index 000000000..c91f6ee30 --- /dev/null +++ b/GEMstack/onboard/execution/entrypoint.py @@ -0,0 +1,133 @@ +from ...utils import settings,config +from ..component import Component +from .execution import ExecutorBase +from .log_replay import LogReplay +import importlib +from typing import Dict,List,Optional +import os + +def import_module_dynamic(module_name, parent_module=None): + if parent_module is not None: + full_path = parent_module + '.' + module_name + else: + full_path = module_name + return importlib.import_module(full_path) + + +def make_class(config_info, component_module, parent_module=None, extra_args = None): + if extra_args is None: + extra_args = {} + args = () + if isinstance(config_info,str): + if '.' in config_info: + component_module,class_name = config_info.rsplit('.',1) + else: + class_name = config_info + else: + class_name = config_info['type'] + if '.' in class_name: + component_module,class_name = class_name.rsplit('.',1) + if 'module' in config_info: + component_module = config_info['module'] + if 'args' in config_info: + args = config_info['args'] + if parent_module is not None: + print("Importing",component_module,"from",parent_module,"to get",class_name) + else: + print("Importing",component_module,"to get",class_name) + module = import_module_dynamic(component_module,parent_module) + klass = getattr(module,class_name) + try: + return klass(*args,**extra_args) + except TypeError: + return klass(*args) + + +def main(): + runconfig = settings.get('run') + mode = settings.get('run.mode') + vehicle_interface_settings = settings.get('run.vehicle_interface') + mission_executor_settings = settings.get('run.mission_execution') + log_settings = settings.get('run.log',{}) + replay_settings = settings.get('run.replay',{}) + + #create top-level components + vehicle_interface = make_class(vehicle_interface_settings,'default','GEMstack.onboard.interface') + mission_executor = make_class(mission_executor_settings,'execution','GEMstack.onboard.execution') + if not isinstance(mission_executor,ExecutorBase): + raise ValueError("Mission executor must be an Executor") + + drive_pipeline_settings = settings.get('run.drive') + recovery_pipeline_settings = settings.get('run.recovery') + + #create pipelines and add to executor + pipeline_settings = {'drive':drive_pipeline_settings, + 'recovery':recovery_pipeline_settings} + for k,v in runconfig.items(): + if isinstance(v,dict) and ('perception' in v or 'planning' in v or 'other' in v): + #possible pipeline + if k not in pipeline_settings: + print("Adding non-standard pipeline",k) + pipeline_settings[k] = v + + existing_components = {} + for (name,s) in pipeline_settings.items(): + perception_settings = s.get('perception',{}) + planning_settings = s.get('planning',{}) + other_settings = s.get('other',{}) + + perception_components = {} #type: Dict[str,Component] + for (k,v) in perception_settings.items(): + if str((k,v)) in existing_components: + perception_components[k] = existing_components[(k,v)] + else: + perception_components[k] = make_class(v,k,'GEMstack.onboard.perception', {'vehicle_interface':vehicle_interface}) + existing_components[str((k,v))] = perception_components[k] + planning_components = {} #type: Dict[str,Component] + for (k,v) in planning_settings.items(): + if str((k,v)) in existing_components: + planning_components[k] = existing_components[(k,v)] + else: + if k == 'trajectory_tracking': + planning_components[k] = make_class(v,k,'GEMstack.onboard.planning', {'vehicle_interface':vehicle_interface}) + else: + planning_components[k] = make_class(v,k,'GEMstack.onboard.planning') + existing_components[str((k,v))] = planning_components[k] + other_components = {} #type: Dict[str,Component] + for (k,v) in other_settings.items(): + if str((k,v)) in existing_components: + other_components[k] = existing_components[(k,v)] + else: + other_components[k] = make_class(v,k,'GEMstack.onboard.execution', {'vehicle_interface':vehicle_interface}) + existing_components[str((k,v))] = other_components[k] + + #TODO: add logging and ROS topic replay + if 'replay' in runconfig: + logfolder = runconfig['replay'].get('log',None) + if logfolder is not None: + logmeta = config.load_config_recursive(os.path.join(logfolder,'meta.yaml')) + replay_topics = runconfig['replay'].get('ros_topics',[]) + + #TODO: launch a roslog replay of the topics in replay_topics, disable in the vehicle interface + replay_components = runconfig['replay'].get('components',[]) + for c in replay_components: + found = False + for component in (perception_components,planning_components,other_components): + if c in component: + outputs = component[c].state_outputs() + for o in outputs: + if o not in logmeta['state_log_items']: + raise ValueError("Replay component",c,"has output",o,"which is not in log") + print("Replaying component",c,"from log",logfolder,"with outputs",outputs) + component[c] = LogReplay(outputs, + os.path.join(logfolder,'state_log.json'), + rate=component[c].rate()) + found = True + if not found: + raise ValueError("Replay component",c,"not found in pipeline",name) + + mission_executor.add_pipeline(name,perception_components,planning_components,other_components) + + + mission_executor.run() + diff --git a/GEMstack/onboard/execution/execution.py b/GEMstack/onboard/execution/execution.py new file mode 100644 index 000000000..eb9753b47 --- /dev/null +++ b/GEMstack/onboard/execution/execution.py @@ -0,0 +1,321 @@ +from dataclasses import asdict +from ...state import AllState, MissionEnum +from ..component import Component +from ...utils.loops import TimedLooper +from ...utils import settings +import time +from typing import Dict,Tuple,List,Optional + +# Define the computation graph + +def normalize_computation_graph(components : list) -> List[Dict]: + normalized_components = [] + for c in components: + if isinstance(c,str): + normalized_components.append({c:{'inputs':[],'outputs':[]}}) + else: + assert isinstance(c,dict), "Component {} is not a string or dict".format(c) + assert len(c) == 1, "Component {} dict has more than one key".format(c) + k = list(c.keys())[0] + v = c[k] + assert isinstance(v,dict), "Component {} value is not a string or dict".format(c) + if 'inputs' not in v: + v['inputs'] = [] + elif isinstance(v['inputs'],str): + v['inputs'] = [v['inputs']] + elif v['inputs'] is None: + v['inputs'] = [] + if 'outputs' not in v: + v['outputs'] = [] + elif isinstance(v['outputs'],str): + v['outputs'] = [v['outputs']] + elif v['outputs'] is None: + v['outputs'] = [] + normalized_components.append({k:v}) + return normalized_components + +COMPONENTS = normalize_computation_graph(settings.get('run.computation_graph.components')) +COMPONENT_ORDER = [list(c.keys())[0] for c in COMPONENTS] +COMPONENT_SETTINGS = dict(list(c.items())[0] for c in COMPONENTS) + + +def validate_components(components : Dict[str,Component], provided : List = None): + """Checks whether the defined components match the known computation graph""" + state = asdict(AllState.zero()) + if provided is None: + provided = set() + else: + provided = set(provided) + provided_all = False + for k in COMPONENT_ORDER: + if k not in components: + continue + possible_inputs = COMPONENT_SETTINGS[k]['inputs'] + required_outputs = COMPONENT_SETTINGS[k]['outputs'] + + c = components[k] + inputs = c.state_inputs() + for i in inputs: + if i == 'all': + assert possible_inputs == ['all'], "Component {} inputs are not provided by previous components".format(k) + else: + assert provided_all or i in provided, "Component {} input {} is not provided by previous components".format(k,i) + if i not in state: + print("Component {} input {} does not exist in AllState object".format(k,i)) + if possible_inputs != ['all']: + assert i in possible_inputs, "Component {} is not supposed to receive input {}".format(k,i) + outputs = c.state_outputs() + for o in required_outputs: + if o == 'all': + assert outputs == ['all'], "Component {} outputs are not provided by previous components".format(k) + else: + assert o in outputs, "Component {} doesn't output required output {}".format(k,o) + for o in outputs: + if 'all' != o: + provided.add(o) + if o not in state: + print("Component {} output {} does not exist in AllState object".format(k,o)) + else: + provided_all = True + for k,c in components.items(): + assert k in COMPONENT_SETTINGS, "Component {} is not known".format(k) + return list(provided) + + +class ComponentExecutor: + """Polls for whether a component should be updated, and reads/writes + inputs / outputs to the AllState object.""" + def __init__(self,c : Component): + self.c = c + self.inputs = c.state_inputs() + self.output = c.state_outputs() + self.last_update_time = None + self.next_update_time = None + self.dt = 1.0/c.rate() + self.num_overruns = 0 + self.overrun_amount = 0.0 + self.do_update = None + + def start(self): + pass + + def stop(self): + pass + + def update(self, t : float, state : AllState): + if self.next_update_time is None or t >= self.next_update_time: + self.update_now(t,state) + self.last_update_time = t + if self.next_update_time is None: + self.next_update_time = t + self.dt + else: + self.next_update_time += self.dt + if self.next_update_time < t: + print("Component {} is running behind, overran dt by {} seconds".format(self.c,self.dt,t-self.next_update_time)) + self.num_overruns += 1 + self.overrun_amount += t - self.next_update_time + self.next_update_time = t + self.dt + return True + return False + + def _do_update(self, *args): + if self.do_update is not None: + res = self.do_update(*args) + else: + res = self.c.update(*args) + return res + + def update_now(self, t:float, state : AllState): + """Performs the updates for this component, without fussing with the polling scheduling""" + if self.inputs == ['all']: + args = (state,) + else: + args = tuple([state[i] for i in self.inputs]) + res = self._do_update(*args) + #write result + if res is not None: + if len(self.output) > 1: + assert len(res) == len(self.output), "Component {} output {} does not match expected length {}".format(self.c,self.output,len(self.output)) + for (k,v) in zip(self.output,res): + state[k] = v + state[k+'_update_time'] = t + else: + state[self.output[0]] = res + state[self.output[0]+'_update_time'] = t + + +def update_components(components : Dict[str,ComponentExecutor], state : AllState, now = False): + """If now = True, all components are run regardless of polling state.""" + t = state.t + for k in COMPONENT_ORDER: + if k in components: + if now: + components[k].update_now(t,state) + else: + components[k].update(t,state) + + +class ExecutorBase: + """Base class for a mission executor. Handles the computation graph setup. + Subclasses should implement begin(), update(), done(), and end() methods.""" + def __init__(self): + self.pipelines = dict() # type: Dict[str,Tuple[Dict[str,ComponentExecutor],Dict[str,ComponentExecutor],Dict[str,ComponentExecutor]]] + self.current_pipeline = 'drive' # type: str + self.state = None # type: Optional[AllState] + + def begin(self): + """Override me to do any initialization""" + pass + + def update(self, state : AllState) -> Optional[str]: + """Override me to implement mission and pipeline switching logic. + + Returns the name of the next pipeline to run, or None to continue the current pipeline""" + return None + + def done(self): + return False + + def end(self): + pass + + def add_pipeline(self,name : str, perception : Dict[str,Component], planning : Dict[str,Component], other : Dict[str,Component]): + output = validate_components(perception) + output = validate_components(planning, output) + validate_components(other, output) + perception_component_state = dict((k,ComponentExecutor(c)) for (k,c) in perception.items()) + planning_component_state = dict((k,ComponentExecutor(c)) for (k,c) in planning.items()) + other_component_state = dict((k,ComponentExecutor(c)) for (k,c) in other.items()) + self.pipelines[name] = (perception_component_state,planning_component_state,other_component_state) + #TODO: set any custom do_update functions here + + def run(self): + if self.current_pipeline not in self.pipelines: + print("Pipeline {} not found".format(self.current_pipeline)) + return + if 'recovery' not in self.pipelines: + print("'recovery' pipeline not found") + return + + for (name,(perception_components,planning_components,other_components)) in self.pipelines.items(): + for (k,c) in perception_components.items(): + c.start() + for (k,c) in planning_components.items(): + c.start() + for (k,c) in other_components.items(): + c.start() + + #start running mission + self.state = AllState.zero() + self.state.mission.type = MissionEnum.IDLE + + validated = False + try: + self.validate_sensors() + validated = True + except KeyboardInterrupt: + print("Could not validate sensors, stopping components and exiting") + + if validated: + self.begin() + while validated: + try: + print("Executing pipeline {}".format(self.current_pipeline)) + next = self.run_until_switch() + if next is None: + #done + break + if next not in self.pipelines: + print("Pipeline {} not found, switching to recovery".format(next)) + next = 'recovery' + if self.current_pipeline == 'recovery' and next == 'recovery': + print("************************************************") + print(" Recovery pipeline is not working, exiting! ") + print("************************************************") + break + self.current_pipeline = next + if not self.validate_sensors(1): + print("Sensors in desired pipeline {} are not working, switching to recovery".format(self.current_pipeline)) + self.current_pipeline = 'recovery' + except KeyboardInterrupt: + if self.current_pipeline == 'recovery': + print("************************************************") + print(" Ctrl+C interrupt during recovery, exiting! ") + print("************************************************") + break + self.current_pipeline = 'recovery' + if validated: + self.end() + #done with mission + print("Done with mission execution, stopping components and exiting") + + for (name,(perception_components,planning_components,other_components)) in self.pipelines.items(): + for (k,c) in perception_components.items(): + c.stop() + for (k,c) in planning_components.items(): + c.stop() + for (k,c) in other_components.items(): + c.stop() + + + def validate_sensors(self,numsteps=None): + #verify sensors are working + (perception_components,planning_components,other_components) = self.pipelines[self.current_pipeline] + dt_min = min([c.dt for c in perception_components.values()]) + looper = TimedLooper(dt_min,name="main executor") + sensors_working = False + num_attempts = 0 + t0 = time.time() + next_print_time = t0 + 1.0 + while looper and not sensors_working: + update_components(perception_components,self.state) + sensors_working = all([c.c.healthy() for c in perception_components.values()]) + num_attempts += 1 + if numsteps is not None and num_attempts >= numsteps: + return False + if time.time() > next_print_time: + print("Waiting for sensors to be healthy...") + next_print_time += 1.0 + return True + + def run_until_switch(self): + if self.current_pipeline == 'recovery': + self.state.mission.type = MissionEnum.RECOVERY_STOP + + (perception_components,planning_components,other_components) = self.pipelines[self.current_pipeline] + dt_min = min([c.dt for c in perception_components.values()] + [c.dt for c in planning_components.values()] + [c.dt for c in other_components.values()]) + looper = TimedLooper(dt_min,name="main executor") + while looper and not self.done(): + update_components(perception_components,self.state) + #check for faults + sensors_working = all([c.c.healthy() for c in perception_components.values()]) + if not sensors_working: + print("Sensors not working, entering recovery mode") + return 'recovery' + + next_pipeline = self.update(self.state) + if next_pipeline is not None and next_pipeline != self.current_pipeline: + print("update() requests to switch to pipeline {}".format(next_pipeline)) + return next_pipeline + + update_components(planning_components,self.state) + #check for faults + planners_working = all([c.c.healthy() for c in planning_components.values()]) + if not planners_working: + print("Planners not working, entering recovery mode") + return 'recovery' + + update_components(other_components,self.state) + others_working = all([c.c.healthy() for c in other_components.values()]) + if not others_working: + print("Other items not working, ignoring") + + #self.done() returned True + return None + + +class StandardExecutor(ExecutorBase): + def begin(self): + import rospy + rospy.init_node('GEM executor') + diff --git a/GEMstack/onboard/execution/log_replay.py b/GEMstack/onboard/execution/log_replay.py new file mode 100644 index 000000000..da0944a89 --- /dev/null +++ b/GEMstack/onboard/execution/log_replay.py @@ -0,0 +1,86 @@ +from ...utils import serialization +from ..component import Component +from typing import List +import time + +class LogReplay(Component): + """Substitutes the output of a component with replayed data from a log file. + """ + def __init__(self, vehicle_interface, outputs : List[str], log_file : str, rate : float = 10.0): + self.vehicle_interface = vehicle_interface + self.outputs = outputs + self.logfn = log_file + self._rate = rate + self.logfile = open(log_file,'r') + self.logfile_delta_format = True + self.log_start_time = None + self.next_item = None + self.next_item_time = None + self.start_time = None + + def rate(self): + return self._rate + + def state_outputs(self): + return self.outputs + + def update(self): + t = self.vehicle_interface.time() + if self.start_time == None: + self.start_time = t + if self.logfile == None: + return + if self.log_start_time is None: + try: + while self.next_item is None: + self.read_next() + except IOError: + self.logfile.close() + self.logfile = None + self.log_start_time = self.next_item_time + + if self.next_item_time - self.log_start_time > t - self.start_time: + #not yet the time to read the next item + return + #return the next item + res = [self.next_item.get(o,None) for o in self.outputs] + #advance to the next item in the log + try: + while self.next_item_time - self.log_start_time < t - self.start_time: + self.read_next() + except IOError: + self.logfile.close() + self.logfile = None + if len(self.outputs)==1: + return res[0] + if all(v is None for v in res): + return None + return res + + def read_next(self): + line = self.logfile.readline() + if line == '': + raise IOError("End of log file") + msg = serialization.deserialize_collection(line[:-1]) + if self.logfile_delta_format: + #assumed to be of the form {'time':t,ITEM1:{...},ITEM2:{...}} + assert 'time' in msg + if self.next_item is None: + self.next_item = {} + for o in self.outputs: + if o in msg: + self.next_item[o] = msg[o] + self.next_item_time = msg['time'] + if self.next_item_time is None: + self.next_item = None + else: + #assumed to be state dictionaries of the form {ITEM1:VAL, ITEM2:VAL, ITEM1_update_time:t, ITEM2_update_time:t} + self.next_item = msg + self.next_item_time = None + for o in self.outputs: + if o+'_update_time' in msg: + v = msg[o+'_update_time'] + if self.next_item_time is None: + self.next_item_time = v + else: + self.next_item_time = max(self.next_item_time,v) diff --git a/GEMstack/onboard/execution/multiprocess_execution.py b/GEMstack/onboard/execution/multiprocess_execution.py new file mode 100644 index 000000000..4590b72fc --- /dev/null +++ b/GEMstack/onboard/execution/multiprocess_execution.py @@ -0,0 +1,56 @@ +from multiprocessing import Process, Queue +from .execution import ComponentExecutor +import time + +MAX_QUEUE_SIZE = 10 + +class MPComponentExecutor(ComponentExecutor): + def __init__(self, component, *args, **kwargs): + super(MPComponentExecutor, self).__init__(component, *args, **kwargs) + self._in_queue = Queue() + self._out_queue = Queue() + self._process = Process(target=self._run, args=(self.c, self._in_queue, self._out_queue)) + self.do_update = self._do_update + self._times_put = [] + self._delay_count = 0 + self._num_delayed = 0 + self._amount_delayed = 0.0 + + def start(self): + self._process.start() + + def stop(self): + self._process.terminate() + self._in_queue.put('stop') + self._process.join() + self._process = None + + def _run(self, component, inqueue, outqueue): + while True: + if not inqueue.empty(): + data = inqueue.get() + if data == 'stop': + break + res = component.update(data) + outqueue.put(res) + + def _do_update(self, *args): + if len(self._in_queue) < MAX_QUEUE_SIZE: + self._in_queue.put(args) + self._times_put.append(time.time()) + else: + print("Warning: queue is full, dropping data") + if not self._out_queue.empty(): + t_put = self._times_put.pop(0) + if self._delay_count > 1: + self._num_delayed += 1 + self._amount_delayed += time.time() - t_put + self._delay_count = 0 + return self._out_queue.get() + else: + self._delay_count += 1 + return None + + def __del__(self): + if self._process is not None: + self.stop() \ No newline at end of file diff --git a/GEMstack/onboard/interface/__init__.py b/GEMstack/onboard/interface/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/GEMstack/onboard/interface/gem.py b/GEMstack/onboard/interface/gem.py new file mode 100644 index 000000000..55c44e78f --- /dev/null +++ b/GEMstack/onboard/interface/gem.py @@ -0,0 +1,131 @@ +from dataclasses import dataclass +from ...utils import settings +from ...state import VehicleState, ObjectPose, ObjectFrameEnum +from ...knowledge.vehicle.geometry import front2steer,steer2front,heading_rate +from ...knowledge.vehicle.dynamics import pedal_positions_to_acceleration, acceleration_to_pedal_positions + +@dataclass +class GEMVehicleReading: + speed : float = 0 + gear : int = 0 + accelerator_pedal_position : float = 0 + brake_pedal_position : float = 0 + steering_wheel_angle : float = 0 + left_turn_signal : bool = False + right_turn_signal : bool = False + headlights_on : bool = False + horn_on : bool = False + wiper_level : int = 0 + + def from_state(self, state: VehicleState): + self.speed = state.v + self.steering_wheel_angle = state.steering_wheel_angle + pitch = state.pose.pitch if state.pose.pitch is not None else 0.0 + acc_pos,brake_pos,gear = acceleration_to_pedal_positions(state.acceleration, state.v, pitch, state.gear) + self.accelerator_pedal_position = acc_pos + self.brake_pedal_position = brake_pos + self.gear = state.gear + self.left_turn_signal = state.left_turn_indicator + self.right_turn_signal = state.right_turn_indicator + self.horn_on = state.horn_on + self.wiper_level = state.wiper_level + self.headlights_on = state.headlights_on + + def to_state(self, pose : ObjectPose = None) -> VehicleState: + if pose is None: + pose = ObjectPose(frame = ObjectFrameEnum.CURRENT,t=0,x=0,y=0,yaw=0) + pitch = pose.pitch if pose.pitch is not None else 0.0 + wheel_base = settings.get('vehicle.geometry.wheelbase') + front_wheel_angle=front2steer(self.steering_wheel_angle) + heading_rate=heading_rate(front_wheel_angle,self.speed,wheel_base) + acc = pedal_positions_to_acceleration(self.accelerator_pedal_position, self.brake_pedal_position, self.speed, pitch, self.gear) + return VehicleState(pose,v=self.speed,acceleration=acc,gear=self.gear,steering_wheel_angle=self.steering_wheel_angle, + front_wheel_angle=front_wheel_angle,turn_rate=heading_rate, + left_turn_indicator=self.left_turn_signal,right_turn_indicator=self.right_turn_signal, + horn_on=self.horn_on,wiper_level=self.wiper_level,headlights_on=self.headlights_on) + + +@dataclass +class GEMVehicleCommand: + gear : int #follows convention in state.vehicle.VehicleState. -2: park, -1 reverse: 0: neutral, 1..n: forward + accelerator_pedal_position : float + accelerator_pedal_speed : float + brake_pedal_position : float + brake_pedal_speed : float + steering_wheel_angle : float + steering_wheel_speed : float + left_turn_signal : bool = False + right_turn_signal : bool = False + headlights_on : bool = False + horn_on : bool = False + wiper_level : int = 0 + + +class GEMInterface: + """Base class for simulated / physical GEM vehicle. + """ + def __init__(self): + self.last_command = None # type: GEMVehicleCommand + self.last_reading = None # type: GEMVehicleReading + + def start(self): + pass + + def stop(self): + pass + + def time(self) -> float: + """Returns the current time""" + raise NotImplementedError() + + def get_reading(self) -> GEMVehicleReading: + """Returns current read state of the vehicle""" + raise NotImplementedError() + + def send_command(cmd : GEMVehicleCommand): + """Sends a command to the vehicle""" + raise NotImplementedError() + + def subscribe_gnss(self, callback): + raise NotImplementedError() + + def subscribe_imu(self, callback): + raise NotImplementedError() + + def subscribe_lidar(self, callback): + raise NotImplementedError() + + def subscribe_stereo(self, callback): + raise NotImplementedError() + + def subscribe_radar(self, callback): + raise NotImplementedError() + + def hardware_faults(self) -> list: + """Returns a list of hardware faults (by component)""" + raise NotImplementedError() + + def simple_command(self, acceleration_amount : float, steering_wheel_angle : float) -> GEMVehicleCommand: + cmd = GEMVehicleCommand() + cmd.brake_pedal_speed = settings.get('vehicle.control_defaults.brake_pedal_speed') + cmd.steering_wheel_speed = settings.get('vehicle.control_defaults.steering_wheel_speed') + cmd.accelerator_pedal_speed = settings.get('vehicle.control_defaults.accelerator_pedal_speed') + cmd.gear = 1 + cmd.left_turn_signal = False + cmd.right_turn_signal = False + cmd.headlights_on = False + cmd.horn_on = False + cmd.wiper_level = 0 + + if acceleration_amount < 0: + cmd.brake_pedal_position = -acceleration_amount + if cmd.brake_pedal_position > 1: + cmd.brake_pedal_position = 1 + cmd.accelerator_pedal_position = 0 + else: + cmd.accelerator_pedal_position = acceleration_amount + if cmd.accelerator_pedal_position > 1: + cmd.accelerator_pedal_position = 1 + cmd.brake_pedal_position = 0 + cmd.steering_wheel_angle = steering_wheel_angle + return cmd diff --git a/GEMstack/onboard/interface/gem_hardware.py b/GEMstack/onboard/interface/gem_hardware.py new file mode 100644 index 000000000..abfae1c11 --- /dev/null +++ b/GEMstack/onboard/interface/gem_hardware.py @@ -0,0 +1,145 @@ +from .gem import * +import math + +# ROS Headers +import rospy +from ackermann_msgs.msg import AckermannDrive +from std_msgs.msg import String, Bool, Float32, Float64 +from novatel_gps_msgs.msg import NovatelPosition, NovatelXYZ, Inspva +from tf.transformations import euler_from_quaternion, quaternion_from_euler + +# GEM PACMod Headers +from pacmod_msgs.msg import PositionWithSpeed, PacmodCmd, SystemRptFloat, VehicleSpeedRpt + + +class GEMHardwareInterface(GEMInterface): + """Interface for interfacing with the physical GEM vehicle.""" + def __init__(self): + GEMInterface.__init__(self) + self.last_reading = GEMVehicleReading() + self.last_reading.speed = 0.0 + self.last_reading.steering_wheel_angle = 0.0 + self.last_reading.accelerator_pedal_position = 0.0 + self.last_reading.brake_pedal_position = 0.0 + self.last_reading.gear = 0 + self.last_reading.left_turn_signal = False + self.last_reading.right_turn_signal = False + self.last_reading.horn_on = False + self.last_reading.wiper_level = 0 + self.last_reading.headlights_on = False + + self.speed_sub = rospy.Subscriber("/pacmod/parsed_tx/vehicle_speed_rpt", VehicleSpeedRpt, self.speed_callback) + self.steer_sub = rospy.Subscriber("/pacmod/parsed_tx/steer_rpt", SystemRptFloat, self.steer_callback) + self.gnss_sub = None + + # -------------------- PACMod setup -------------------- + + self.pacmod_enable = False + + # GEM vehicle enable + self.enable_sub = rospy.Subscriber('/pacmod/as_rx/enable', Bool, self.pacmod_enable_callback) + # self.enable_cmd = Bool() + # self.enable_cmd.data = False + + # GEM vehicle gear control, neutral, forward and reverse, publish once + self.gear_pub = rospy.Publisher('/pacmod/as_rx/shift_cmd', PacmodCmd, queue_size=1) + self.gear_cmd = PacmodCmd() + self.gear_cmd.ui16_cmd = 2 # SHIFT_NEUTRAL + + # GEM vehicle brake control + self.brake_pub = rospy.Publisher('/pacmod/as_rx/brake_cmd', PacmodCmd, queue_size=1) + self.brake_cmd = PacmodCmd() + self.brake_cmd.enable = False + self.brake_cmd.clear = True + self.brake_cmd.ignore = True + + # GEM vehicle forward motion control + self.accel_pub = rospy.Publisher('/pacmod/as_rx/accel_cmd', PacmodCmd, queue_size=1) + self.accel_cmd = PacmodCmd() + self.accel_cmd.enable = False + self.accel_cmd.clear = True + self.accel_cmd.ignore = True + + # GEM vehicle turn signal control + self.turn_pub = rospy.Publisher('/pacmod/as_rx/turn_cmd', PacmodCmd, queue_size=1) + self.turn_cmd = PacmodCmd() + self.turn_cmd.ui16_cmd = 1 # None + + # GEM vechile steering wheel control + self.steer_pub = rospy.Publisher('/pacmod/as_rx/steer_cmd', PositionWithSpeed, queue_size=1) + self.steer_cmd = PositionWithSpeed() + self.steer_cmd.angular_position = 0.0 # radians, -: clockwise, +: counter-clockwise + self.steer_cmd.angular_velocity_limit = 2.0 # radians/second + + """TODO: other commands + /pacmod/as_rx/headlight_cmd + /pacmod/as_rx/horn_cmd + /pacmod/as_rx/shift_cmd + /pacmod/as_rx/turn_cmd + /pacmod/as_rx/wiper_cmd + """ + + def speed_callback(self,msg : VehicleSpeedRpt): + self.last_reading.speed = msg.vehicle_speed # forward velocity in m/s + + def steer_callback(self, msg): + self.last_reading.steering_wheel_angle = round(math.degrees(msg.output),1) + + def get_reading(self) -> GEMVehicleReading: + return self.last_reading + + def subscribe_gnss(self, callback): + self.gnss_sub = rospy.Subscriber("/novatel/inspva", Inspva, callback) + + + + + # PACMod enable callback function + def pacmod_enable_callback(self, msg): + self.pacmod_enable = msg.data + + def send_first_command(self): + # ---------- Enable PACMod ---------- + + # enable forward gear + self.gear_cmd.ui16_cmd = 3 + + # enable brake + self.brake_cmd.enable = True + self.brake_cmd.clear = False + self.brake_cmd.ignore = False + self.brake_cmd.f64_cmd = 1.0 + + # enable gas + self.accel_cmd.enable = True + self.accel_cmd.clear = False + self.accel_cmd.ignore = False + self.accel_cmd.f64_cmd = 0.0 + + self.gear_pub.publish(self.gear_cmd) + self.turn_pub.publish(self.turn_cmd) + self.brake_pub.publish(self.brake_cmd) + self.accel_pub.publish(self.accel_cmd) + + + # Start PACMod interface + def send_command(self, command : GEMVehicleCommand): + if command.left_turn_signal: + self.turn_cmd.ui16_cmd = 2 # left turn signal + elif command.right_turn_signal: + self.turn_cmd.ui16_cmd = 0 # right turn signal + else: + self.turn_cmd.ui16_cmd = 1 + + self.accel_cmd.f64_cmd = command.accelerator_pedal_position + if command.brake_pedal_position > 0.0: + self.accel_cmd.f64_cmd = 0.0 + self.brake_cmd.f64_cmd = command.brake_pedal_position + self.steer_cmd.angular_position = command.steering_wheel_angle + self.steer_cmd.angular_velocity_limit = command.steering_wheel_speed + self.accel_pub.publish(self.accel_cmd) + self.brake_pub.publish(self.brake_cmd) + self.steer_pub.publish(self.steer_cmd) + self.turn_pub.publish(self.turn_cmd) + + self.last_command = command diff --git a/GEMstack/onboard/interface/gem_simulator.py b/GEMstack/onboard/interface/gem_simulator.py new file mode 100644 index 000000000..94210e1e0 --- /dev/null +++ b/GEMstack/onboard/interface/gem_simulator.py @@ -0,0 +1,135 @@ +from .gem import * +from ...mathutils.dubins import SecondOrderDubinsCar +from ...mathutils.dynamics import simulate +from ...state import VehicleState,ObjectPose,ObjectFrameEnum,Roadgraph,AgentState,AgentEnum,AgentActivityEnum,Obstacle,Sign +from ...knowledge.vehicle.geometry import front2steer,steer2front,heading_rate +from ...utils.loops import TimedLooper +from ...utils import config +from threading import Thread,Lock +import time +import numpy as np +import copy + +class GEMDoubleIntegratorSimulationInterface(GEMInterface): + def __init__(self, scene : str = None): + GEMInterface.__init__(self) + self.dubins = SecondOrderDubinsCar( + wheelAngleMin=settings.get('vehicle.geometry.min_wheel_angle'), + wheelAngleMax=settings.get('vehicle.geometry.max_wheel_angle'), + velocityMin=-settings.get('vehicle.limits.max_reverse_speed'), + velocityMax=-settings.get('vehicle.limits.max_speed'), + accelMin=-settings.get('vehicle.limits.max_acceleration'), + accelMax=settings.get('vehicle.limits.max_deceleration'), + wheelAngleRateMin=-settings.get('vehicle.limits.max_steering_rate'), + wheelAngleRateMax=settings.get('vehicle.limits.max_steering_rate'), + wheelBase=settings.get('vehicle.geometry.wheelbase')) + + self.dt = settings.get('simulator.dt',0.01) + self.real_time_multiplier = settings.get('simulator.real_time_multiplier',1.0) + self.roadgraph = None + self.agents = [] + if scene is None: + scene = settings.get('simulator.scene',None) + if isinstance(scene,str): + scene = config.load_config_recursive(scene) + if scene is None: + self.simulation_time = time.time() + self.start_state = (0.0,0.0,0.0) + else: + self.simulation_time = scene.get('time',time.time()) + start_state = scene.get('vehicle_state',[0.0,0.0,0.0,0.0,0.0]) + while len(start_state) < 5: + start_state.append(0.0) + self.cur_vehicle_state = np.array(start_state,dtype=float) + + self.last_reading = GEMVehicleReading() + self.last_reading.speed = 0.0 + self.last_reading.steering_wheel_angle = 0.0 + self.last_reading.accelerator_pedal_position = 0.0 + self.last_reading.brake_pedal_position = 0.0 + self.last_reading.gear = 0 + self.last_reading.left_turn_signal = False + self.last_reading.right_turn_signal = False + self.last_reading.horn_on = False + self.last_reading.wiper_level = 0 + self.last_reading.headlights_on = False + self.gnss_callback = None + self.imu_callback = None + self.thread_lock = Lock() + self.thread_data = dict() + self.thread = None + + def time(self) -> float: + return self.simulation_time + + def start(self): + assert self.thread is None + self.thread_data['stop'] = False + self.thread = Thread(target=self.simulate,args=(self.thread_lock,self.thread_data)) + + def stop(self): + self.thread_data['stop']= True + self.thread.join() + self.thread = None + + def hardware_faults(self) -> list: + return [] + + def subscribe_gnss(self, callback): + self.gnss_callback = callback + + def subscribe_imu(self, callback): + self.imu_callback = callback + + def send_command(self, command : GEMVehicleCommand): + self.last_command = command + + def get_reading(self) -> GEMVehicleReading: + """Returns current read state of the vehicle""" + return self.last_reading + + def simulate(self,lock : Lock, data : dict): + looper = TimedLooper(self.dt / self.real_time_multiplier,name="Simulation thread") + while looper and not data['stop']: + lock.acquire() + x,y,theta,v,phi = self.cur_vehicle_state + #simulate actuators + acceleration = self.last_command.accelerator_pedal_position - self.last_command.brake_pedal_position + acceleration = np.clip(acceleration,*self.dubins.accelRange) + phides = steer2front(self.last_command.steering_wheel_angle) + phides = np.clip(phides,*self.dubins.wheelAngleRange) + phi_deadband = 0.01 + steering_angle_rate = self.last_command.steering_wheel_speed if phides > phi + phi_deadband else \ + (-self.last_command.steering_wheel_speed if phides < phi - phi_deadband else 0.0) + + #simulate dynamics + u = np.array([acceleration,steering_angle_rate]) #acceleration, steering angle rate + next_state = simulate(self.dubins, self.cur_vehicle_state, u, self.dt, self.dt) + x,y,theta,v,phi = next_state + v = np.clip(v,*self.dubins.velocityRange) + next_state = np.array([x,y,theta,v,phi]) + + #simulate sensors + reading = copy.copy(self.last_reading) + reading.steering_wheel_angle = front2steer(phi) + if acceleration > 0: + reading.brake_pedal_position = 0.0 + reading.accelerator_pedal_position = acceleration + else: + reading.brake_pedal_position = -acceleration + reading.accelerator_pedal_position = 0 + reading.speed = v + if v > 0: + reading.gear = 1 + else: + reading.gear = -1 + last_reading = reading + + if self.gnss_callback is not None: + pose = ObjectPose(frame=ObjectFrameEnum.ABSOLUTE_CARTESIAN,t=self.simulation_time,x=x,y=y,yaw=theta) + vehicle_state = last_reading.to_state(pose) + self.gnss_callback(vehicle_state) + + self.cur_vehicle_state = next_state + self.simulation_time += self.dt + lock.release() diff --git a/GEMstack/onboard/perception/__init__.py b/GEMstack/onboard/perception/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/GEMstack/onboard/perception/perception_normalization.py b/GEMstack/onboard/perception/perception_normalization.py new file mode 100644 index 000000000..2f2ca8c99 --- /dev/null +++ b/GEMstack/onboard/perception/perception_normalization.py @@ -0,0 +1,39 @@ +from ...state import AllState,ObjectPose,ObjectFrameEnum,VehicleState +from ..component import Component + +class StandardPerceptionNormalizer(Component): + """Updates the start pose and converts all objects to the current vehicle + frame, in preparation for planning.""" + def rate(self): + return 10.0 + def state_inputs(self): + return ['all'] + def state_outputs(self): + return [] + def update(self,state : AllState): + if state.start_vehicle_pose is None: + if state.vehicle != VehicleState.zero(): + state.start_vehicle_pose = state.vehicle.pose + else: + return + + #convert vehicle pose to start frame + state.vehicle.pose = state.vehicle.pose.to_frame(ObjectFrameEnum.START, start_pose_abs=state.start_vehicle_pose) + + #convert roadgraph to current frame + state.roadgraph = state.roadgraph.to_frame(ObjectFrameEnum.CURRENT, current_pose=state.vehicle_pose, start_pose_abs=state.start_vehicle_pose) + + for k,a in state.agents.items(): + a.pose = a.pose.to_frame(ObjectFrameEnum.CURRENT, current_pose=state.vehicle_pose, start_pose_abs=state.start_vehicle_pose) + + for k,o in state.obstacles.items(): + o.pose = o.pose.to_frame(ObjectFrameEnum.CURRENT, current_pose=state.vehicle_pose, start_pose_abs=state.start_vehicle_pose) + + #convert predictions to current frame. + for k,a in state.agent_intents.items(): + for pred in a.predictions: + if pred.path is not None: + for i,p in enumerate(pred.path): + pred.path[i] = p.to_frame(ObjectFrameEnum.CURRENT, current_pose=state.vehicle_pose, start_pose_abs=state.start_vehicle_pose) + + #TODO: advance agent predictions and paths to current vehicle time \ No newline at end of file diff --git a/GEMstack/onboard/perception/roadgraph_update.py b/GEMstack/onboard/perception/roadgraph_update.py new file mode 100644 index 000000000..219730de5 --- /dev/null +++ b/GEMstack/onboard/perception/roadgraph_update.py @@ -0,0 +1,24 @@ +from ...state import Roadgraph, Roadmap +from ..component import Component +from ...utils import serialization + +class StaticRoadgraphUpdater(Component): + def __init__(self, mapfn : str, vehicle_interface = None): + self.mapfn = mapfn + with open(mapfn,'r') as f: + self.roadmap = serialization.load(f) + if not isinstance(self.roadmap,(Roadmap,Roadgraph)): + raise ValueError("Invalid roadmap file "+mapfn) + + def rate(self): + return 10.0 + + def state_inputs(self): + return ['vehicle'] + + def state_outputs(self): + return ['roadgraph'] + + def update(self, vehicle): + return self.roadmap + diff --git a/GEMstack/onboard/perception/state_estimation.py b/GEMstack/onboard/perception/state_estimation.py new file mode 100644 index 000000000..c1c8f3108 --- /dev/null +++ b/GEMstack/onboard/perception/state_estimation.py @@ -0,0 +1,82 @@ +from dataclasses import replace +import math +from typing import List +from ...utils import settings +from ...mathutils import transforms +from ...state.vehicle import VehicleState,VehicleGearEnum +from ...state.physical_object import ObjectFrameEnum,ObjectPose,convert_xyhead +from ...knowledge.vehicle.geometry import front2steer,steer2front +from ..interface.gem import GEMInterface +from ..component import Component + +class GNSSStateEstimator(Component): + """Just looks at the GNSS reading to estimate the vehicle state""" + def __init__(self, vehicle_interface : GEMInterface): + self.vehicle_interface = vehicle_interface + vehicle_interface.subscribe_gnss(self.inspva_callback) + self.gnss_pose = None + self.location = settings.get('vehicle.calibration.gnss_location') + self.yaw_offset = settings.get('vehicle.calibration.gnss_yaw') + + # Get GNSS information + def inspva_callback(self, inspva_msg): + self.gnss_pose = ObjectPose(ObjectFrameEnum.GLOBAL, + x=inspva_msg.longitude, + y=inspva_msg.latitude, + z=inspva_msg.height, + yaw=inspva_msg.azimuth, #heading from north in degrees + roll=inspva_msg.roll, + pitch=inspva_msg.pitch, + ) + print("INS status",inspva_msg.status) + + def rate(self): + return 10.0 + + def state_outputs(self) -> List[str]: + return ['vehicle'] + + def healthy(self): + return self.gnss_pose is not None + + def update(self) -> VehicleState: + if self.gnss_pose is None: + return + # vehicle gnss heading (yaw) in degrees + # vehicle x, y position in fixed local frame, in meters + # reference point is located at the center of GNSS antennas + localxy = transforms.rotate2d(self.location,-self.yaw_offset) + gnss_xyhead_inv = (-localxy[0],-localxy[1],-self.yaw_offset) + center_xyhead = self.gnss_pose.apply_xyhead(gnss_xyhead_inv) + vehicle_pose_global = replace(self.gnss_pose, + t=self.vehicle_interface.time(), + x=center_xyhead[0], + y=center_xyhead[1], + yaw=center_xyhead[2]) + + readings = self.vehicle_interface.get_reading() + return readings.to_state(vehicle_pose_global) + + + +class FakeStateEstimator(Component): + def __init__(self, vehicle_interface : GEMInterface): + self.vehicle_interface = vehicle_interface + vehicle_interface.subscribe_gnss(self.fake_gnss_callback) + self.vehicle_state = None + + # Get GNSS information + def fake_gnss_callback(self, vehicle_state): + self.vehicle_state = vehicle_state + + def rate(self): + return 10.0 + + def state_outputs(self) -> List[str]: + return ['vehicle'] + + def healthy(self): + return self.vehicle_state is not None + + def update(self) -> VehicleState: + return self.vehicle_state \ No newline at end of file diff --git a/GEMstack/onboard/planning/__init__.py b/GEMstack/onboard/planning/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/GEMstack/onboard/planning/motion_planning.py b/GEMstack/onboard/planning/motion_planning.py new file mode 100644 index 000000000..cb73b2922 --- /dev/null +++ b/GEMstack/onboard/planning/motion_planning.py @@ -0,0 +1,24 @@ +from typing import List +from ..component import Component +from ...state import AllState, Trajectory, Route +from ...utils import serialization + +class RouteToTrajectoryPlanner(Component): + """Copies the route directly into the trajectory.""" + def __init__(self): + pass + + def state_inputs(self): + return ['all'] + + def state_outputs(self) -> List[str]: + return ['trajectory'] + + def rate(self): + return 10.0 + + def update(self, state : AllState): + return Trajectory(frame=state.route.frame, + points=state.route.points, + times=list(range(len(state.route.points)))) + \ No newline at end of file diff --git a/GEMstack/onboard/planning/pure_pursuit.py b/GEMstack/onboard/planning/pure_pursuit.py new file mode 100644 index 000000000..7315485ff --- /dev/null +++ b/GEMstack/onboard/planning/pure_pursuit.py @@ -0,0 +1,120 @@ +from ...mathutils.control import PID +from ...mathutils.signal import OnlineLowPassFilter +from ...utils import settings +from ...mathutils import transforms +from ...state.vehicle import VehicleState +from ...state.trajectory import Path,Trajectory,compute_headings +from ...knowledge.vehicle.geometry import front2steer +from ..interface.gem import GEMVehicleCommand +from ..component import Component +import numpy as np + +class PurePursuit(object): + """Implements a pure pursuit controller on a second-order Dubins vehicle.""" + def __init__(self, lookahead = None, lookahead_scale = None, wheelbase = None, crosstrack_gain = None): + self.look_ahead = lookahead if lookahead is not None else settings.get('control.pure_pursuit.lookahead',4.0) + self.look_ahead_scale = lookahead_scale if lookahead_scale is not None else settings.get('control.pure_pursuit.lookahead_scale',3.0) + self.crosstrack_gain = crosstrack_gain if crosstrack_gain is not None else settings.get('control.pure_pursuit.crosstrack_gain',0.41) + self.wheelbase = wheelbase if wheelbase is not None else settings.get('vehicle.geometry.wheelbase') + self.wheel_angle_range = [settings.get('vehicle.geometry.min_wheel_angle'),settings.get('vehicle.geometry.max_wheel_angle')] + self.steering_angle_range = [settings.get('vehicle.geometry.min_steering_angle'),settings.get('vehicle.geometry.max_steering_angle')] + + self.desired_speed = 1.5 # m/s, reference speed + self.max_accel = settings.get('vehicle.limits.max_accelerator_pedal') # % of acceleration + self.pid_speed = PID(0.5, 0.0, 0.1, windup_limit=20) + self.speed_filter = OnlineLowPassFilter(1.2, 30, 4) + + self.path = None + self.path_with_headings = None + self.path_progress = 0.0 + self.t_start = None + + def set_path(self, path : Path): + self.path = path + self.path_progress = 0.0 + if len(self.path.points[0]) > 2: + self.path = self.path.get_dims([0,1]) + if not isinstance(self.path,Trajectory): + self.path = self.path.arc_length_parameterize() + self.path_with_headings = compute_headings(self.path) + + def compute(self, state : VehicleState): + if self.path is None: + #just stop + accel = self.pid_speed(0.0, state.t) + + if self.t_start is None: + self.t_start = state.t + dt = state.t - self.t_start + + if self.path.frame != state.frame: + self.path = self.path.to_frame(state.frame) + self.path_with_headings = self.path_with_headings.to_frame(state.frame) + + curr_x = state.x + curr_y = state.y + curr_yaw = state.heading + speed = state.v + + + desired_x,desired_y,desired_yaw = self.path_with_headings.eval(self.path_progress + self.look_ahead) + + # finding the distance between the goal point and the vehicle + # true look-ahead distance between a waypoint and current position + L = transforms.vector_dist((curr_x, curr_y), (desired_x, desired_y)) + + # find the curvature and the angle + alpha = desired_yaw - curr_yaw + + # ----------------- tuning this part as needed ----------------- + k = self.crosstrack_gain + angle_i = np.arctan((k * 2 * self.wheelbase * np.sin(alpha)) / L) + angle = angle_i*2 + # ----------------- tuning this part as needed ----------------- + + f_delta = np.clip(angle, self.wheel_angle_range[0], self.wheel_angle_range[1]) + + steering_angle = np.clip(front2steer(f_delta), self.steering_angle_range[0], self.steering_angle_range[1]) + + print("Closest point distance: " + str(L)) + print("Forward velocity: " + str(speed)) + ct_error = np.sin(alpha) * L + print("Crosstrack Error: " + str(round(ct_error,3))) + print("Front steering angle: " + str(np.degrees(f_delta)) + " degrees") + print("Steering wheel angle: " + str(np.degrees(steering_angle)) + " degrees" ) + print("\n") + + filt_vel = self.speed_filter(speed) + output_accel = self.pid_speed.advance(state.t, self.desired_speed - filt_vel) + + if output_accel > self.max_accel: + output_accel = self.max_accel + + if output_accel < 0.3: + output_accel = 0.3 + + self.path_progress += speed * dt + + +class PurePursuitTrajectoryTracker(Component): + def __init__(self,vehicle_interface): + self.pure_pursuit = PurePursuit() + self.vehicle_interface = vehicle_interface + + def rate(self): + return 50.0 + + def state_inputs(self): + return ['vehicle','trajectory'] + + def state_outputs(self): + return [] + + def update(self, vehicle : VehicleState, trajectory: Trajectory): + self.pure_pursuit.set_path(trajectory) + res = self.pure_pursuit.compute(vehicle) + res = GEMVehicleCommand(accelerator_pedal_position=res.accel, brake_pedal_position=res.brake, steering_wheel_angle=res.steer) + self.vehicle_interface.send_command(res) + + def healthy(self): + return self.pure_pursuit.path is not None \ No newline at end of file diff --git a/GEMstack/onboard/planning/recovery.py b/GEMstack/onboard/planning/recovery.py new file mode 100644 index 000000000..dec30400d --- /dev/null +++ b/GEMstack/onboard/planning/recovery.py @@ -0,0 +1,37 @@ +from ...utils import settings +from ..component import Component +from ...state.vehicle import VehicleState +from ...state.trajectory import Path,Trajectory +from ..interface.gem import GEMVehicleCommand, GEMInterface +import copy + +class StopTrajectoryTracker(Component): + def __init__(self,vehicle_interface : GEMInterface): + self.vehicle_interface = vehicle_interface + + def rate(self): + return 50.0 + + def state_inputs(self): + return [] + + def state_outputs(self): + return [] + + def update(self): + brake_amount = settings.get('control.recovery.brake_amount') + brake_speed = settings.get('control.recovery.brake_speed') + if self.vehicle_interface.last_command is not None: + cmd = copy.copy(self.vehicle_interface.last_command) + cmd.accelerator_pedal_position = 0.0 + cmd.brake_pedal_position = brake_amount + cmd.brake_pedal_speed = brake_speed + else: + cmd = GEMVehicleCommand(brake_pedal_position=brake_amount) + if self.vehicle_interface.last_reading.speed == 0: + #shift to park + cmd.gear = -2 + self.vehicle_interface.send_command(cmd) + + def healthy(self): + return True diff --git a/GEMstack/onboard/planning/route_planning.py b/GEMstack/onboard/planning/route_planning.py new file mode 100644 index 000000000..89dae28bf --- /dev/null +++ b/GEMstack/onboard/planning/route_planning.py @@ -0,0 +1,33 @@ +from typing import List +from ..component import Component +from ...utils import serialization +from ...state import Route,ObjectFrameEnum +import os +import numpy as np + +class StaticRoutePlanner(Component): + """Reads a route from disk and returns it as the desired route.""" + def __init__(self, routefn : str): + self.routefn = routefn + base, ext = os.path.splitext(routefn) + if ext in ['.json','.yml','.yaml']: + with open(routefn,'r') as f: + self.route = serialization.load(f) + elif ext == '.csv': + waypoints = np.loadtxt(routefn,delimiter=',',dtype=float) + self.route = Route(frame=ObjectFrameEnum.START,points=waypoints.tolist()) + else: + raise ValueError("Unknown route file extension",ext) + + def state_inputs(self): + return [] + + def state_outputs(self) -> List[str]: + return ['route'] + + def rate(self): + return 1.0 + + def update(self): + return self.route + \ No newline at end of file diff --git a/GEMstack/state/__init__.py b/GEMstack/state/__init__.py new file mode 100644 index 000000000..1b957715f --- /dev/null +++ b/GEMstack/state/__init__.py @@ -0,0 +1,32 @@ +__all__ = ['PhysicalObject','ObjectPose','ObjectFrameEnum', + 'Path','Trajectory', + 'VehicleState', + 'Roadgraph', + 'Roadmap', + 'Obstacle', + 'Sign', + 'AgentState','AgentEnum','AgentActivityEnum', + 'SceneState', + 'VehicleIntent','VehicleIntentEnum', + 'AgentIntent', + 'EntityRelationEnum','EntityRelation','EntityRelationGraph', + 'MissionEnum','MissionObjective', + 'Route', + 'PredicateValues', + 'AllState'] +from .physical_object import PhysicalObject, ObjectPose, ObjectFrameEnum +from .trajectory import Path,Trajectory +from .vehicle import VehicleState +from .roadgraph import Roadgraph, RoadgraphLane, RoadgraphCurve, RoadgraphRegion, RoadgraphCurveEnum, RoadgraphLaneEnum, RoadgraphRegionEnum, RoadgraphConnectionEnum +from .obstacle import Obstacle, ObstacleMaterialEnum +from .sign import Sign, SignEnum, SignalLightEnum, SignState +from .roadmap import Roadmap +from .agent import AgentState, AgentEnum, AgentActivityEnum +from .scene import SceneState +from .intent import VehicleIntent, VehicleIntentEnum +from .agent_intent import AgentIntent +from .relations import EntityRelation, EntityRelationEnum, EntityRelationGraph +from .mission import MissionEnum,MissionObjective +from .route import Route +from .predicates import PredicateValues +from .all import AllState diff --git a/GEMstack/state/agent.py b/GEMstack/state/agent.py new file mode 100644 index 000000000..a51140f0a --- /dev/null +++ b/GEMstack/state/agent.py @@ -0,0 +1,29 @@ +from dataclasses import dataclass +from ..utils.serialization import register +from .physical_object import PhysicalObject +from enum import Enum +from typing import Tuple + +class AgentEnum(Enum): + CAR = 0 + MEDIUM_TRUCK = 1 + LARGE_TRUCK = 2 + PEDESTRIAN = 3 + BICYCLIST = 4 + + +class AgentActivityEnum(Enum): + STOPPED = 0 # standing pedestrians, parked cars, etc. No need to predict motion. + MOVING = 1 # standard motion. Predictions will be used here + FAST = 2 # indicates faster than usual motion, e.g., runners. + UNDETERMINED = 3 # unknown activity + + +@dataclass +@register +class AgentState(PhysicalObject): + type : AgentEnum + activity : AgentActivityEnum + velocity : Tuple[float,float,float] #estimated velocity in x,y,z, m/s + yaw_rate : float #estimated yaw rate, in radians/s + \ No newline at end of file diff --git a/GEMstack/state/agent_intent.py b/GEMstack/state/agent_intent.py new file mode 100644 index 000000000..163bfd2ce --- /dev/null +++ b/GEMstack/state/agent_intent.py @@ -0,0 +1,36 @@ +from dataclasses import dataclass +from ..utils.serialization import register +from .physical_object import ObjectPose +from enum import Enum +from typing import List,Optional + +class AgentIntentEnum(Enum): + IDLE = 0 + NORMAL = 1 + STOPPING = 2 # stopping at a stop sign / light / crossing + LANE_CHANGE_LEFT = 3 # performing a lane change + LANE_CHANGE_RIGHT = 4 # performing a lane change + LEFT_TURN = 5 # performing a left turn + RIGHT_TURN = 6 # performing a right turn + U_TURN = 7 # performing a u-turn + CROSSING = 8 # executing a crossing + + +@dataclass +@register +class AgentIntent: + intent : AgentIntentEnum # the class of this intent + path : Optional[List[ObjectPose]] # the predicted (x,y,heading) path associated with this intent + uncertainty_fwd : Optional[List[float]] # uncertainty in the predicted path in the forward direction + uncertainty_side : Optional[List[float]] # uncertainty in the predicted path in the sideways direction + uncertainty_heading : Optional[List[float]] # uncertainty in the predicted path's heading + + +@dataclass +@register +class AgentIntentMixture: + """A collection of intents. Each intent has an associated likelihood + (likelihoods sum to 1). + """ + predictions : List[AgentIntent] + likelihoods : List[float] diff --git a/GEMstack/state/all.py b/GEMstack/state/all.py new file mode 100644 index 000000000..2edf06388 --- /dev/null +++ b/GEMstack/state/all.py @@ -0,0 +1,53 @@ +from dataclasses import dataclass, field, fields, asdict +from ..utils.serialization import register +from .physical_object import ObjectPose +from .scene import SceneState +from .intent import VehicleIntent +from .agent_intent import AgentIntent +from .relations import EntityRelation +from .mission import MissionObjective +from .route import Route +from .trajectory import Trajectory +from .predicates import PredicateValues +from typing import Dict,List,Optional + +@dataclass +@register +class AllState(SceneState): + """Contains all items that will be generated during the computation of the + onboard behavior. + """ + # non-physical scene state + start_vehicle_pose : Optional[ObjectPose] = None + agent_intents : Dict[str,AgentIntent] = field(default_factory=dict) + relations : List[EntityRelation] = field(default_factory=list) + predicates : PredicateValues = field(default_factory=PredicateValues) + + # planner-output state + mission : MissionObjective = field(default_factory=MissionObjective) + intent : VehicleIntent = field(default_factory=VehicleIntent) + route : Optional[Route] = None + trajectory : Optional[Trajectory] = None + + # update times for perception items (time.time()) + vehicle_update_time : float = 0 + roadgraph_update_time : float = 0 + environment_update_time : float = 0 + agent_update_time : float = 0 + obstacle_update_time : float = 0 + start_vehicle_pose_update_time : float = 0 + agent_intents_update_time : float = 0 + relations_update_time : float = 0 + predicates_update_time : float = 0 + + # update times for planner items + mission_update_time : float = 0 + intent_update_time : float = 0 + route_update_time : float = 0 + trajectory_update_time : float = 0 + + @staticmethod + def zero(): + scene_zero = SceneState.zero() + keys = dict((k.name,getattr(scene_zero,k.name)) for k in fields(scene_zero)) + return AllState(**keys) \ No newline at end of file diff --git a/GEMstack/state/environment.py b/GEMstack/state/environment.py new file mode 100644 index 000000000..94e8a6785 --- /dev/null +++ b/GEMstack/state/environment.py @@ -0,0 +1,27 @@ +from dataclasses import dataclass +from ..utils.serialization import register +from enum import Enum + +class WeatherConditionEnum(Enum): + SUN = 0 + OVERCAST = 1 + RAIN = 2 + SNOW = 3 + DUST = 4 + + +class SurfaceConditionEnum(Enum): + DRY = 0 + WET = 1 + MUD = 2 + SNOW = 3 + ICE = 4 + + +@dataclass +@register +class EnvironmentState: + weather : WeatherConditionEnum = WeatherConditionEnum.SUN + surface : SurfaceConditionEnum = SurfaceConditionEnum.DRY + wind_speed : float = 0 + surface_severity : float = 0 diff --git a/GEMstack/state/intent.py b/GEMstack/state/intent.py new file mode 100644 index 000000000..da9c7d7ab --- /dev/null +++ b/GEMstack/state/intent.py @@ -0,0 +1,23 @@ +from dataclasses import dataclass +from ..utils.serialization import register +from enum import Enum + +class VehicleIntentEnum(Enum): + IDLE = 0 # stopped, parked, or waiting + DRIVING = 1 # normal driving + HALTING = 2 # terminating driving + WAIT_AT_SIGN = 3 # normal driving, deciding to wait at sign, e.g., stop sign, yellow light, or yield + PROCEED_THROUGH_SIGN = 4 # normal driving, deciding to proceed through sign, e.g., stop sign, yellow light, or yield + LANE_CHANGE_LEFT = 5 # normal driving, deciding to execute a lane change to the left + LANE_CHANGE_RIGHT = 6 # normal driving, deciding to execute a lane change to the right + MERGING = 7 # normal driving, merging into lane + PARKING = 8 # normal driving, executing parking behavior + LEAVING_PARKING = 9 # normal driving, leaving a parking spot + U_TURN = 10 # normal driving, executing U-turn outside of dedicated lane + + +@dataclass +@register +class VehicleIntent: + intent : VehicleIntentEnum = VehicleIntentEnum.IDLE + entity : str = '' # a scene entity referred to by the X_SIGN, LANE_CHANGE_X, MERGING, and XPARKING intents diff --git a/GEMstack/state/mission.py b/GEMstack/state/mission.py new file mode 100644 index 000000000..5ca1adeff --- /dev/null +++ b/GEMstack/state/mission.py @@ -0,0 +1,17 @@ +from dataclasses import dataclass +from ..utils.serialization import register +from enum import Enum + +class MissionEnum(Enum): + IDLE = 0 # not driving, no mission + DRIVE = 1 # normal driving with routing + DRIVE_ROUTE = 2 # normal driving with a fixed route + TELEOP = 3 # manual teleop control + RECOVERY_STOP = 4 # abnormal condition detected, must stop now + ESTOP = 5 # estop pressed, must stop now + +@dataclass +@register +class MissionObjective: + type : MissionEnum = MissionEnum.IDLE + \ No newline at end of file diff --git a/GEMstack/state/obstacle.py b/GEMstack/state/obstacle.py new file mode 100644 index 000000000..8fddd5cc0 --- /dev/null +++ b/GEMstack/state/obstacle.py @@ -0,0 +1,25 @@ +from dataclasses import dataclass +from ..utils.serialization import register +from .physical_object import PhysicalObject +from enum import Enum + +class ObstacleMaterialEnum(Enum): + UNKNOWN = 0 + LEAVES = 1 + BRANCHES = 2 + LITTER = 3 + ROCKS = 4 + TRAFFIC_CONE = 5 + BARRIER = 6 + MAILBOX = 7 + SIGN = 8 + SMALL_ANIMAL = 9 + ROADKILL = 10 + + +@dataclass +@register +class Obstacle(PhysicalObject): + material : ObstacleMaterialEnum + collidable : bool + diff --git a/GEMstack/state/physical_object.py b/GEMstack/state/physical_object.py new file mode 100644 index 000000000..25a7d9bd3 --- /dev/null +++ b/GEMstack/state/physical_object.py @@ -0,0 +1,307 @@ +from __future__ import annotations +from dataclasses import dataclass, replace, field +from ..mathutils import transforms +from ..utils.serialization import register +from typing import Tuple,List,Optional +from enum import Enum +import numpy as np +from klampt.math import so2,so3,se3 + +class ObjectFrameEnum(Enum): + START = 0 #position / yaw in m / radians relative to starting pose of vehicle + CURRENT = 1 #position / yaw in m / radians relative to current pose of vehicle + GLOBAL = 2 #position in longitude / latitude, yaw=heading in radians with respect to true north (used in GNSS) + ABSOLUTE_CARTESIAN = 3 #position / yaw in m / radians relative to a global cartesian reference frame (used in simulation) + + +@dataclass +@register +class ObjectPose: + """ + Represents a hypothetical object position / orientation. + + Attributes: + t: if frame=GLOBAL or ABSOLUTE_CARTESIAN, the time in s since the + epoch, i.e., time.time() Otherwise, the time since start / current + in the future, in s + x: the x position, in the object's frame. If frame=GLOBAL, this is + longitude, otherwise forward in m. + y: the y position, in the object's frame. If frame=GLOBAL, this is + latitude, otherwise left in m. + z: the optional z position, in m and in the object's frame. + yaw: the optional yaw, in radians and in the object's frame. If + frame=GLOBAL, this is heading CW from north. Otherwise, it is + CCW yaw. + pitch: the optional pitch, in radians and around left direction in the object's frame + roll: the optional roll, in radians and around forward direction in the object's frame + """ + frame : ObjectFrameEnum + t : float + x : float + y : float + z : Optional[float] = None + yaw : Optional[float] = None + pitch : Optional[float] = None + roll : Optional[float] = None + + def rotation2d(self) -> np.ndarray: + """Returns the 2x2 rotation matrix of this pose's yaw relative to the specified frame.""" + yaw = self.yaw if self.yaw is not None else 0.0 + if self.frame == ObjectFrameEnum.GLOBAL: + yaw = transforms.heading_to_yaw(yaw,False) + return so2.ndarray(yaw) + + def rotation(self) -> np.ndarray: + """Returns the 3x3 rotation matrix of this pose relative to the specified frame.""" + rpy = [(self.roll if self.roll is not None else 0.0), + (self.pitch if self.pitch is not None else 0.0), + (self.yaw if self.yaw is not None else 0.0)] + if self.frame == ObjectFrameEnum.GLOBAL: + rpy[2] = transforms.heading_to_yaw(rpy[2],False) + return so3.ndarray(so3.from_rpy(rpy)) + + def rotation(self) -> np.ndarray: + """Returns the 3x3 rotation matrix of this pose relative to the specified frame.""" + rpy = [(self.roll if self.roll is not None else 0.0), + (self.pitch if self.pitch is not None else 0.0), + (self.yaw if self.yaw is not None else 0.0)] + if self.frame == ObjectFrameEnum.GLOBAL: + rpy[2] = transforms.heading_to_yaw(rpy[2],False) + return so3.ndarray(so3.from_rpy(rpy)) + + def translation(self) -> np.ndarray: + """Returns the 3D translation of this pose relative to the specified frame.""" + if self.frame == ObjectFrameEnum.GLOBAL: + raise ValueError("Cannot get translation of GLOBAL frame") + return np.array([self.x,self.y,(self.z if self.z is not None else 0.0)]) + + def transform(self) -> np.ndarray: + """Returns the 4x4 homogeneous transform matrix of this pose.""" + return se3.ndarray((so3.from_ndarray(self.rotation()),self.translation())) + + def apply(self,point): + """Applies this pose to a local (x,y) or (x,y,z) coordinate.""" + oz = self.z if self.z is not None else 0.0 + if self.frame == ObjectFrameEnum.GLOBAL: + east_m,north_m = point[:2] + olon,olat = self.x,self.y + lat,lon = transforms.xy_to_lat_lon(east_m,north_m,olat,olon) + if len(point) == 2: + return (lon,lat) + else: + return (lon,lat) + tuple(point[2:] + oz) + if len(point) == 2: + return tuple(self.rotation2d().dot(point) + self.translation()[:2]) + else: + return tuple(self.rotation().dot(point) + self.translation()) + + def apply_inv(self,point): + """Applies the inverse of this pose to an (x,y) or (x,y,z) coordinate + specified in the same frame as this.""" + oz = self.z if self.z is not None else 0.0 + if self.frame == ObjectFrameEnum.GLOBAL: + lon,lat = point[:2] + olon,olat = self.x,self.y + east_m, north_m = transforms.lat_lon_to_xy(lat,lon,olat,olon) + return (east_m,north_m) + tuple(point[2:] + oz) + if len(point) == 2: + return tuple(self.rotation2d().T.dot(np.array(point)-self.translation()[:2])) + else: + return tuple(self.rotation().T.dot(np.array(point)-self.translation())) + + def apply_xyhead(self,xyhead): + """Applies this pose to a local (x,y,yaw) coordinate. yaw is always + specified in CCW radians.""" + newxy = self.apply(xyhead[:2]) + yaw = self.yaw if self.yaw is not None else 0.0 + if self.frame == ObjectFrameEnum.GLOBAL: + return newxy + (transforms.normalize_angle(yaw - xyhead[2]),) + else: + return newxy + (transforms.normalize_angle(yaw + xyhead[2]),) + + def apply_inv_xyhead(self,xyhead): + """Applies this pose to a (x,y,yaw) coordinate expressed in `frame`. + yaw is specified in CCW radians except for GLOBAL, in which case + yaw is CW heading.""" + newxy = self.apply_inv(xyhead[:2]) + yaw = self.yaw if self.yaw is not None else 0.0 + if self.frame == ObjectFrameEnum.GLOBAL: + return newxy + (transforms.normalize_angle(yaw - xyhead[2]),) + else: + return newxy + (transforms.normalize_angle(xyhead[2] - yaw),) + + def to_frame(self, new_frame : ObjectFrameEnum, + current_pose : ObjectPose = None, start_pose_abs : ObjectPose = None) -> ObjectPose: + """Returns a new ObjectPose representing the same pose, but with + coordinates expressed in a different frame.""" + if self.frame == new_frame: + return replace(self) + frame_chain = _get_frame_chain(self.frame,new_frame,current_pose,start_pose_abs) + if self.yaw is None: + pt = (self.x,self.y) + for (frame,pose,dir) in frame_chain[1:]: + if dir == 1: + pt = pose.apply(pt) + else: + pt = pose.apply_inv(pt) + new_x,new_y = pt + new_yaw = None + else: + xyhead = (self.x,self.y,self.yaw) + for (frame,pose,dir) in frame_chain[1:]: + if dir == 1: + xyhead = pose.apply_xyhead(xyhead) + else: + xyhead = pose.apply_inv_xyhead(xyhead) + new_x,new_y,new_yaw = xyhead + new_z = self.z + if new_z is not None: + for (frame,pose,dir) in frame_chain[1:]: + if pose.z is not None: + new_z += pose.z*dir + new_t = self.t + for (frame,pose,dir) in frame_chain[1:]: + new_t += pose.t*dir + return replace(self, frame=new_frame, t=new_t,x=new_x, y=new_y, z=new_z, yaw=new_yaw) + + +@dataclass +@register +class PhysicalObject: + """Base class for some physical possibly movble object. Assumed to be + gravity-aligned so the z-axis always points up. + + Attributes: + pose: the position / rotation coordinates of the object. + dimensions: the depth (forward), width (sideways), and height (up) + of the object. + outline: an optional list of vertices in CCW order denoting the + object's outline polygon in its local frame (x:forward, y:left). + """ + pose : ObjectPose + dimensions : Tuple[float,float,float] + outline : Optional[List[Tuple[float,float]]] + + + + +def _get_frame_chain(source_frame : ObjectFrameEnum, target_frame : ObjectFrameEnum, + current_pose : ObjectPose = None, start_pose_abs : ObjectPose = None) -> List[Tuple[ObjectFrameEnum,ObjectPose,int]]: + frame_chain = [(source_frame,None,0)] + if source_frame == target_frame: + return frame_chain + + if source_frame == ObjectFrameEnum.GLOBAL and target_frame == ObjectFrameEnum.ABSOLUTE_CARTESIAN: + raise ValueError("Cannot mix GLOBAL and ABSOLUTE_CARTESIAN frames") + elif target_frame == ObjectFrameEnum.GLOBAL and source_frame == ObjectFrameEnum.ABSOLUTE_CARTESIAN: + raise ValueError("Cannot mix GLOBAL and ABSOLUTE_CARTESIAN frames") + if current_pose is not None and current_pose.frame == ObjectFrameEnum.CURRENT: + raise ValueError("Cannot accept current_pose in CURRENT frame") + if start_pose_abs is not None and start_pose_abs.frame not in [ObjectFrameEnum.GLOBAL,ObjectFrameEnum.ABSOLUTE_CARTESIAN]: + raise ValueError("start_pose_abs must be in GLOBAL or ABSOLUTE_CARTESIAN frame") + if current_pose is not None and current_pose.frame in [ObjectFrameEnum.GLOBAL,ObjectFrameEnum.ABSOLUTE_CARTESIAN]: + if current_pose.frame != start_pose_abs.frame: + raise ValueError("Cannot mix GLOBAL and ABSOLUTE_CARTESIAN frames") + if frame_chain[-1][0] == ObjectFrameEnum.CURRENT: + if current_pose is None: + raise ValueError("current_pose must be specified when converting from CURRENT") + frame_chain.append((current_pose.frame,current_pose,1)) + if frame_chain[-1][0] == target_frame: + return frame_chain + if frame_chain[-1][0] == ObjectFrameEnum.START: + if start_pose_abs is None: + raise ValueError("start_pose_abs must be specified when converting from START") + frame_chain.append((start_pose_abs.frame,start_pose_abs,1)) + if frame_chain[-1][0] == target_frame: + return frame_chain + if target_frame == ObjectFrameEnum.START: + if start_pose_abs is None: + raise ValueError("start_pose_abs must be specified when converting to START") + frame_chain.append((ObjectFrameEnum.START,start_pose_abs,-1)) + elif target_frame == ObjectFrameEnum.CURRENT: + if current_pose.frame != frame_chain[-1][0]: #global to start + assert start_pose_abs.frame == frame_chain[-1][0] + assert current_pose.frame == ObjectFrameEnum.START + if start_pose_abs is None: + raise ValueError("start_pose_abs must be specified when converting to CURRENT and current_pose is in START frame") + frame_chain.append((ObjectFrameEnum.START,start_pose_abs,-1)) + if current_pose is None: + raise ValueError("current_pose must be specified when converting to CURRENT") + frame_chain.append((ObjectFrameEnum.CURRENT,current_pose,-1)) + return frame_chain + + +def convert_point(source_pt : tuple, source_frame : ObjectFrameEnum, target_frame : ObjectFrameEnum, + current_pose : ObjectPose = None, start_pose_abs : ObjectPose = None) -> Tuple[float,float]: + """Converts an (x,y) or (x,y,z) point from one frame to another. + + start_pose_abs must be in GLOBAL or ABSOLUTE_CARTESIAN frame. + + current_pose may be in START, GLOBAL, or ABSOLUTE_CARTESIAN frame. + + GLOBAL and ABSOLUTE_CARTESIAN are incompatible. + """ + frame_chain = _get_frame_chain(source_frame,target_frame,current_pose,start_pose_abs) + pt = source_pt + for (frame,pose,dir) in frame_chain[1:]: + if dir == 1: + pt = pose.apply(pt) + else: + pt = pose.apply_inv(pt) + return pt + + +def convert_xyhead(source_state : tuple, source_frame : ObjectFrameEnum, target_frame : ObjectFrameEnum, + current_pose : ObjectPose = None, start_pose_abs : ObjectPose = None) -> Tuple[float,float,float]: + """Converts an (x,y,heading) state from one frame to another. + + start_pose_abs must be in GLOBAL or ABSOLUTE_CARTESIAN frame. + + current_pose may be in START, GLOBAL, or ABSOLUTE_CARTESIAN frame. + + GLOBAL and ABSOLUTE_CARTESIAN are incompatible. + """ + frame_chain = _get_frame_chain(source_frame,target_frame,current_pose,start_pose_abs) + + xyhead = source_state + for (frame,pose,dir) in frame_chain[1:]: + if dir == 1: + xyhead = pose.apply_xyhead(xyhead) + else: + xyhead = pose.apply_inv_xyhead(xyhead) + return xyhead + + +def convert_points(source_pts : List[tuple], source_frame : ObjectFrameEnum, target_frame : ObjectFrameEnum, + current_pose : ObjectPose = None, start_pose_abs : ObjectPose = None) -> Tuple[float,float]: + """Converts a list of (x,y) or (x,y,z) points from one frame to + another. Faster than repeated calls to convert_point. + """ + frame_chain = _get_frame_chain(source_frame,target_frame,current_pose,start_pose_abs) + res = [] + for pt in source_pts: + for (frame,pose,dir) in frame_chain[1:]: + if dir == 1: + pt = pose.apply(pt) + else: + pt = pose.apply_inv(pt) + res.append(pt) + return res + + +def convert_xyheads(source_states : List[tuple], source_frame : ObjectFrameEnum, target_frame : ObjectFrameEnum, + current_pose : ObjectPose = None, start_pose_abs : ObjectPose = None) -> Tuple[float,float,float]: + """Converts a list of (x,y,heading) states from one frame to another. + Faster than repeated calls to convert_xyhead. + """ + frame_chain = _get_frame_chain(source_frame,target_frame,current_pose,start_pose_abs) + + res = [] + for xyhead in source_states: + for (frame,pose,dir) in frame_chain[1:]: + if dir == 1: + xyhead = pose.apply_xyhead(xyhead) + else: + xyhead = pose.apply_xyhead_inv(xyhead) + res.append(xyhead) + return res diff --git a/GEMstack/state/predicates.py b/GEMstack/state/predicates.py new file mode 100644 index 000000000..d409acbf0 --- /dev/null +++ b/GEMstack/state/predicates.py @@ -0,0 +1,16 @@ +from dataclasses import dataclass, field +from ..utils.serialization import register +from typing import Union,Dict + +@dataclass +@register +class PredicateValues: + values : Dict[str,Union[bool,int]] = field(default_factory=dict) #the current values of nonzero predicates + durations : Dict[str,float] = field(default_factory=dict) #how long the predicate has been at the current value + + def get_value(self, name : str) -> Union[bool,int]: + return self.values.get(name,False) + + def get_duration(self, name : str) -> float: + return self.durations.get(name,0) + \ No newline at end of file diff --git a/GEMstack/state/relations.py b/GEMstack/state/relations.py new file mode 100644 index 000000000..465d4e657 --- /dev/null +++ b/GEMstack/state/relations.py @@ -0,0 +1,83 @@ +from dataclasses import dataclass +from ..utils.serialization import register +from enum import Enum +from collections import defaultdict +from typing import List,Optional + + +class EntityRelationEnum(Enum): + WITHIN = 0 # obj1 is within lane / region obj2 + STOPPING_AT = 1 # obj1 is stopping / waiting at lane / curve obj2 + VISIBLE = 2 # obj1 is visible to obj2 + AWARE = 3 # obj1 is aware of obj2 + FOLLOWING = 4 # obj1 follows obj2 + PASSING = 5 # obj1 is passing obj2, intending for obj2 to yield + YIELDING = 6 # obj1 is yielding to obj2, allowing obj2 to pass + MERGING_AHEAD = 7 # obj1 is merging / lane changing ahead of a obj2 + MERGING_BEHIND = 8 # obj1 is merging / lane changing behind of obj2 + + +@dataclass +@register +class EntityRelation: + type : EntityRelationEnum + obj1 : str # Named object in the scene. '' indicates ego-vehicle + obj2 : str # Named object in the scene. '' indicates ego-vehicle + + +class EntityRelationGraph: + """A dynamic graph of relations which allows for more efficient queries + than just a list of EntityRelations. + """ + def __init__(self, scene = None): + self.scene = scene + self.relations_by_type = defaultdict(list) + self.relations_by_obj1 = defaultdict(list) + self.relations_by_obj2 = defaultdict(list) + self.relations_by_obj1_type = defaultdict(list) + self.relations_by_obj2_type = defaultdict(list) + + def add(self, relation : EntityRelation) -> None: + """Adds a relation.""" + self.relations_by_type[relation.type.value].append(relation) + self.relations_by_obj1[relation.obj1].append(relation) + self.relations_by_obj2[relation.obj2].append(relation) + if self.scene is not None: + item1 = self.scene.get_entity(relation.obj1) if relation.obj1 != '' else 'VehicleState' + item2 = self.scene.get_entity(relation.obj2) if relation.obj2 != '' else 'VehicleState' + self.relations_by_obj1_type[item1.__class__.__name__].append(relation) + self.relations_by_obj2_type[item2.__class__.__name__].append(relation) + + def update(self, relations : List[EntityRelation]) -> None: + """Adds multiple relations.""" + for r in relations: + self.add(r) + + def get(self, + relation : EntityRelationEnum = None, + obj1 : str = None, + obj2 : str = None, + obj1_type : str = None, + obj2_type : str = None) -> List[EntityRelation]: + """Query for relations. You can provide relation type, object names, + or object types, and this will return all relations matching the + specified items. + """ + if obj1 is not None: + candidates = self.relations_by_obj1.get(obj1,[]) + elif obj2 is not None: + candidates = self.relations_by_obj2.get(obj2,[]) + elif obj1_type is not None: + candidates = self.relations_by_obj1_type.get(obj1_type,[]) + elif obj2_type is not None: + candidates = self.relations_by_obj2_type.get(obj2_type,[]) + elif relation is not None: + candidates = self.relations_by_type.get(relation,[]) + else: + return sum(self.relations_by_type.values(),[]) + res = [] + for c in candidates: + if (relation is None or c.relation == relation) and (obj1 is None or c.obj1 == obj1) and (obj2 is None or c.obj2 == obj2): + res.append(c) + return res + \ No newline at end of file diff --git a/GEMstack/state/roadgraph.py b/GEMstack/state/roadgraph.py new file mode 100644 index 000000000..f7a1558bc --- /dev/null +++ b/GEMstack/state/roadgraph.py @@ -0,0 +1,221 @@ +from __future__ import annotations +from dataclasses import dataclass, replace, field +from ..utils.serialization import register +from .physical_object import ObjectFrameEnum, convert_point +from .obstacle import Obstacle +from .sign import Sign +from enum import Enum +from typing import List,Tuple,Any,Optional,Dict + + +class RoadgraphCurveEnum(Enum): + LANE_BOUNDARY = 0 + STOP_LINE = 1 + YIELD_LINE = 2 + CROSSING_BOUNDARY = 3 + PARKING_SPOT_BOUNDARY = 4 + CURB = 5 + WALL = 6 + OBSTACLES = 7 + OVERPASS_BOUNDARY = 8 + UNDERPASS_BOUNDARY = 9 + + +class RoadgraphLaneEnum(Enum): + LANE = 0 + SHOULDER = 1 + ONRAMP = 2 + OFFRAMP = 3 + DRIVEWAY = 4 + PARKING_SPOT = 5 + PARKING_ZONE = 6 + OVERPASS = 7 + UNDERPASS = 8 + CROSSING = 9 + + +class RoadgraphSurfaceEnum(Enum): + PAVEMENT = 0 + DIRT = 1 + GRAVEL = 2 + GRASS = 3 + + +class RoadgraphRegionEnum(Enum): + VIRTUAL = 0 # just a region designation, e.g., geofence + CLOSED_COURSE = 1 # open space, can drive anywhere + PARKING_LOT = 2 # parking lot, should drive at low speed + INTERSECTION = 3 # intersection, should not stop in middle + + +class RoadgraphConnectionEnum(Enum): + CONTINUES = 0 # after lane1 is complete it converts to lane2 + ADJACENT = 1 # lane1 and lane2 are going the same way, allows a lane change + ONCOMING = 2 # lane1 and lane2 are adjacent but going opposite ways + CROSSING = 3 # lane2 or curve2 crosses over lane1 + MERGE = 4 # lane1 merges into lane2 + DIVERGE = 5 # lane2 diverges from lane1 + BORDERING = 6 # lane1 is bordered by curve2 + RIGHT_TURN = 7 # lane1 passes through lane2 to perform right turn onto another lane (lane2 must have a CONTINUES relationship with another lane) + LEFT_TURN = 8 # lane1 passes through lane2 to perform left turn onto another lane (lane2 must have a CONTINUES relationship with another lane) + U_TURN = 9 # lane1 passes through lane2 to perform U-turn onto another lane (lane2 must have a CONTINUES relationship with another lane) + + +@dataclass +@register +class RoadgraphCurve: + type : RoadgraphCurveEnum + segments : List[List[Tuple[float,float,float]]] #Polyline representation of the curve. List of lists of 3D positions. Last element is height above road surface, usually 0 + crossable : bool = True + elevation : Optional[float] = None #for CURB, WALL, OBSTACLES, OVERPASS_BOUNDARY, UNDERPASS_BOUNDARY, elevation over road surface, in m + height : Optional[float] = None #for CURB, WALL, OBSTACLES, OVERPASS_BOUNDARY, UNDERPASS_BOUNDARY, height in m + + def to_frame(self, orig_frame : ObjectFrameEnum, new_frame : ObjectFrameEnum, + current_origin = None, global_origin = None) -> RoadgraphCurve: + return replace(self,segments=[[convert_point(p,orig_frame,new_frame,current_origin,global_origin) for p in seg] for seg in self.segments]) + + +@dataclass +@register +class RoadgraphLane: + type : RoadgraphLaneEnum = RoadgraphLaneEnum.LANE + surface : RoadgraphSurfaceEnum = RoadgraphSurfaceEnum.PAVEMENT + left : Optional[RoadgraphCurve] = None + right : Optional[RoadgraphCurve] = None + center : Optional[RoadgraphCurve] = None + begin : Optional[RoadgraphCurve] = None + end : Optional[RoadgraphCurve] = None + + def to_frame(self, orig_frame : ObjectFrameEnum, new_frame : ObjectFrameEnum, + current_origin = None, global_origin = None) -> RoadgraphCurve: + return replace(self,left=self.left.to_frame(orig_frame,new_frame,current_origin,global_origin) if self.left is not None else None, + right=self.right.to_frame(orig_frame,new_frame,current_origin,global_origin) if self.right is not None else None, + center=self.center.to_frame(orig_frame,new_frame,current_origin,global_origin) if self.center is not None else None, + begin=self.begin.to_frame(orig_frame,new_frame,current_origin,global_origin) if self.begin is not None else None, + end=self.end.to_frame(orig_frame,new_frame,current_origin,global_origin) if self.end is not None else None) + + +@dataclass +@register +class RoadgraphRegion: + type : RoadgraphRegionEnum + outline : List[Tuple[float,float]] + crossable : bool = True + + def to_frame(self, orig_frame : ObjectFrameEnum, new_frame : ObjectFrameEnum, + current_origin = None, global_origin = None) -> RoadgraphCurve: + return replace(self,outline=[convert_point(p,orig_frame,new_frame,current_origin,global_origin) for p in self.outline]) + + +@dataclass +@register +class RoadgraphConnection: + type : RoadgraphConnectionEnum + lane1 : str # the primary entity in this connection + lane2 : Optional[str] = None # for lane-lane connections, the second entity + curve2 : Optional[str] = None # for lane-curve connections (e.g., stopline crossing), the second entity + region2 : Optional[str] = None # for lane-region connections (e.g, intersection), the second entity + location : List[Tuple[float,float]] = field(default_factory=list) # a polyline defining when this transition occurs + + def to_frame(self, orig_frame : ObjectFrameEnum, new_frame : ObjectFrameEnum, + current_origin = None, global_origin = None) -> RoadgraphCurve: + return replace(self,location=[convert_point(p,orig_frame,new_frame,current_origin,global_origin) for p in self.location]) + + +@dataclass +@register +class Roadgraph: + frame : ObjectFrameEnum # frame of reference for the roadgraph + curves : Dict[str,RoadgraphCurve] = field(default_factory=dict) # all non-lane-bordering curves in the roadgraph, e.g., stoplines, yieldlines, parking spot boundaries, curbs, walls, obstacles, overpass boundaries, underpass boundaries + lanes : Dict[str,RoadgraphLane] = field(default_factory=dict) # all lanes in the roadgraph + regions : Dict[str,RoadgraphRegion] = field(default_factory=dict) # all regions in the roadgraph + signs : Dict[str,Sign] = field(default_factory=dict) # all signs in the roadgraph + static_obstacles : Dict[str,Obstacle] = field(default_factory=dict) # all static obstacles in the roadgraph + connections : List[RoadgraphConnection] = field(default_factory=list) # all connections between lanes, curves, and regions + + @staticmethod + def zero(): + return Roadgraph(ObjectFrameEnum.GLOBAL) + + def is_valid(self) -> bool: + keys = set() + keys.update(self.curves.keys()) + for k in self.lanes.keys(): + if k in keys: + return False + keys.add(k) + for k in self.regions.keys(): + if k in keys: + return False + keys.add(k) + for k in self.signs.keys(): + if k in keys: + return False + if self.signs[k].frame != self.frame: + return False + keys.add(k) + for k in self.static_obstacles.keys(): + if k in keys: + return False + if self.static_obstacles[k].frame != self.frame: + return False + keys.add(k) + for c in self.connections: + if c.lane1 not in self.lanes: + return False + if c.lane2 is not None and c.lane2 not in self.lanes: + return False + if c.curve2 is not None and c.curve2 not in self.curves: + return False + if c.region2 is not None and c.region2 not in self.regions: + return False + return True + + def get_entity(self, name : str) -> Any: + if name in self.curves: + return self.curves[name] + if name in self.lanes: + return self.lanes[name] + if name in self.regions: + return self.regions[name] + if name in self.signs: + return self.signs[name] + if name in self.signs: + return self.signs[name] + raise KeyError("Entity {} not found".format(name)) + + def entity_names(self) -> List[str]: + keys = set() + keys.update(self.curves.keys()) + keys.update(self.lanes.keys()) + keys.update(self.regions.keys()) + keys.update(self.signs.keys()) + keys.update(self.static_obstacles.keys()) + return list(keys) + + def to_frame(self, frame : ObjectFrameEnum, current_origin = None, global_origin = None) -> Roadgraph: + newcurves = dict() + for (k,c) in self.curves.items(): + newc = c.to_frame(self.frame,frame,current_origin,global_origin) + newcurves[k] = newc + newlanes = dict() + for (k,l) in self.lanes.items(): + newl = l.to_frame(self.frame,frame,current_origin,global_origin) + newlanes[k] = newl + newregions = dict() + for (k,r) in self.regions.items(): + newr = r.to_frame(self.frame,frame,current_origin,global_origin) + newregions[k] = newr + newsigns = dict() + for (k,s) in self.signs.items(): + news = s.to_frame(frame,current_origin,global_origin) + newsigns[k] = news + newstatic_obstacles = dict() + for (k,o) in self.static_obstacles.items(): + newo = o.to_frame(frame,current_origin,global_origin) + newstatic_obstacles[k] = newo + newconnections = [] + for c in self.connections: + newc = c.to_frame(self.frame,frame,current_origin,global_origin) + newconnections.append(newc) + return replace(self, frame = frame, curves = newcurves, lanes = newlanes, regions = newregions, signs = newsigns, static_obstacles = newstatic_obstacles, connections=newconnections) \ No newline at end of file diff --git a/GEMstack/state/roadmap.py b/GEMstack/state/roadmap.py new file mode 100644 index 000000000..267999e2f --- /dev/null +++ b/GEMstack/state/roadmap.py @@ -0,0 +1,12 @@ +from dataclasses import dataclass +from ..utils.serialization import register +from .roadgraph import Roadgraph + +@dataclass +@register +class Roadmap: + name : str + author : str + authored_date : str + graph : Roadgraph + \ No newline at end of file diff --git a/GEMstack/state/route.py b/GEMstack/state/route.py new file mode 100644 index 000000000..ce373d7a4 --- /dev/null +++ b/GEMstack/state/route.py @@ -0,0 +1,18 @@ +from dataclasses import dataclass, field +from ..utils.serialization import register +from .physical_object import ObjectFrameEnum, convert_point +from .trajectory import Path +from typing import List,Tuple,Optional + +@dataclass +@register +class Route(Path): + """A sequence of waypoints and lanes that the motion planner will attempt + to follow. Usually the path connects the centerlines of the given lanes. + + Unlike a Path, for the planner's convenience, the route should also extract + out the wait lines (stop lines, crossings) from the roadgraph. + """ + lanes : List[str] = field(default_factory=list) + wait_lines : List[str] = field(default_factory=list) + diff --git a/GEMstack/state/scene.py b/GEMstack/state/scene.py new file mode 100644 index 000000000..59d3431b5 --- /dev/null +++ b/GEMstack/state/scene.py @@ -0,0 +1,39 @@ +from dataclasses import dataclass, field +from ..utils.serialization import register +from .vehicle import VehicleState +from .agent import AgentState +from .roadgraph import Roadgraph +from .environment import EnvironmentState +from .obstacle import Obstacle +from typing import List,Dict,Optional,Any + +@dataclass +@register +class SceneState: + t : float #time, either simulation time or real time since epoch + vehicle : VehicleState #ego-vehicle state + roadgraph : Roadgraph #local roadgraph + environment : EnvironmentState #environmental conditions + vehicle_lane : Optional[str] #lane in which the vehicle is located, if known + agents : Dict[str,AgentState] #moving agents + obstacles : Dict[str,Obstacle] #dynamically determined obstacles + + def get_entity(self, name : str) -> Any: + if name =='': + return self.vehicle + elif name in self.agents: + return self.agents[name] + elif name in self.obstacles: + return self.obstacles[name] + else: + return self.roadgraph.get_entity(name) + + def entity_names(self) -> List[str]: + keys = set([''] + self.roadgraph.entity_names()) + keys.update(self.agents.keys()) + keys.update(self.obstacles.keys()) + return list(keys) + + @staticmethod + def zero(): + return SceneState(0.0,VehicleState.zero(),Roadgraph.zero(),EnvironmentState(),None,{},{}) diff --git a/GEMstack/state/sign.py b/GEMstack/state/sign.py new file mode 100644 index 000000000..db1cfd1b3 --- /dev/null +++ b/GEMstack/state/sign.py @@ -0,0 +1,95 @@ +from dataclasses import dataclass +from ..utils.serialization import register +from .physical_object import PhysicalObject +from enum import Enum +from typing import List,Optional + +class SignEnum(Enum): + #longitudinal signals + STOP_SIGN = 0 + STOP_LIGHT = 1 + SPEED_LIMIT = 2 + SPEED_ADVISORY = 3 + YIELD = 4 + #lane control + MERGE = 10 + LANE_ENDS = 11 + WRONG_WAY = 12 + DEAD_END = 13 + ONE_WAY = 14 + #crossings + PEDESTRIAN_CROSSING = 20 + ANIMAL_CROSSING = 21 + RAILROAD_CROSSING = 22 + YIELD_TO_PEDESTRIANS = 23 + #turning permission + NO_LEFT_TURN = 30 + NO_RIGHT_TURN = 31 + NO_LEFT_TURN_ON_RED = 32 + NO_RIGHT_TURN_ON_RED = 33 + NO_U_TURN = 34 + LEFT_TURN_ONLY = 35 + STRAIGHT_ONLY = 36 + RIGHT_TURN_ONLY = 37 + U_TURN_ONLY = 38 + EXIT_ONLY = 39 + #informational + DIVIDED_ROADWAY = 50 + CROSS_TRAFFIC_DOES_NOT_STOP = 51 + NO_PASSING = 52 + NO_PARKING = 53 + #construction + BEGIN_CONSTRUCTION_ZONE = 100 + END_CONSTRUCTION_ZONE = 101 + EXIT_CLOSED = 102 + LANE_CLOSED = 103 + SHOULDER_CLOSED = 104 + + +class SignalLightEnum(Enum): + GREEN = 0 + YELLOW = 1 + RED = 2 + RED_FLASHING = 3 + YELLOW_FLASHING = 4 + + +class CrossingGateEnum(Enum): + OPEN = 0 + FLASHING = 1 + CLOSING = 2 + CLOSED = 3 + OPENING = 4 + + +@dataclass +@register +class SignalLightState: + state : SignalLightEnum + duration : float + + +@dataclass +@register +class CrossingGateState: + state : CrossingGateEnum + duration : float + + +@dataclass +@register +class SignState: + signal_state : Optional[SignalLightState] = None + left_turn_signal_state : Optional[SignalLightState] = None + right_turn_signal_state : Optional[SignalLightState] = None + crossing_gate_state : Optional[CrossingGateState] = None + + +@dataclass +@register +class Sign(PhysicalObject): + type : SignEnum + entities : List[str] #the named entities to which this sign is attached, e.g., lane, intersection, onramp + speed : Optional[int] = None #for speed limit and advisory signs + state : Optional[SignState] = None #for stop lights and optional for railroad crossings + diff --git a/GEMstack/state/trajectory.py b/GEMstack/state/trajectory.py new file mode 100644 index 000000000..b49970974 --- /dev/null +++ b/GEMstack/state/trajectory.py @@ -0,0 +1,167 @@ +from __future__ import annotations +from dataclasses import dataclass,replace +from ..utils.serialization import register +from ..mathutils import transforms +from .physical_object import ObjectFrameEnum, convert_point +from typing import List,Tuple,Optional,Union + +@dataclass +@register +class Path: + """An untimed, piecewise linear path.""" + frame : ObjectFrameEnum + points : List[List[float]] + + def to_frame(self, frame : ObjectFrameEnum): + """Converts the route to a different frame.""" + new_points = [convert_point(frame,self.frame,p) for p in self.points] + return replace(self,frame=frame,points=new_points) + + def eval(self, u : float) -> List[float]: + """Evaluates the path at a given parameter. The integer part of u + indicates the segment, and the fractional part indicates the progress + along the segment""" + ind = int(u) + if ind < 0: ind = 0 + if ind >= len(self.points)-1: ind = len(self.points)-2 + u = u - ind + if u > 1: u = 1 + if u < 0: u = 0 + p1 = self.points[ind] + p2 = self.points[ind+1] + return transforms.vector_madd(p1,transforms.vector_sub(p2,p1),u) + + def eval_derivative(self, u : float) -> List[float]: + """Evaluates the derivative at a given parameter. The integer part of + u indicates the segment, and the fractional part indicates the progress + along the segment.""" + ind = int(u) + if ind < 0: ind = 0 + if ind >= len(self.points)-1: ind = len(self.points)-2 + u = u - ind + if u > 1: u = 1 + if u < 0: u = 0 + p1 = self.points[ind] + p2 = self.points[ind+1] + return transforms.vector_sub(p2,p1) + + def arc_length_parameterize(self, speed = 1.0) -> Trajectory: + """Returns a new path that is parameterized by arc length.""" + times = [0] + for i in range(len(self.points)-1): + p1 = self.points[i] + p2 = self.points[i+1] + times.append(times[-1] + transforms.vector_dist(p1,p2)/speed) + return Trajectory(frame=self.frame,points=self.points,times=times) + + def closest_point(self, x : List[float], edges = True) -> Tuple[float,float]: + """Returns the closest point on the path to the given point. If + edges=False, only computes the distances to the vertices, not the + edges. This is slightly faster but less accurate. + + Returns (distance, closest_parameter) + """ + best_dist = float('inf') + best_point = None + for i,p in enumerate(self.points): + if edges and i > 0: + p1 = self.points[i-1] + p2 = p + u,dist = transforms.point_segment_dist(x,p1,p2) + if dist < best_dist: + best_dist = dist + best_point = i-1+u + else: + dist = transforms.vector_dist(p,x) + if dist < best_dist: + best_dist = dist + best_point = i + return best_dist,best_point + + def get_dims(self, dims : List[int]) -> Path: + """Returns a new path with only the given dimensions.""" + return replace(self,points=[p[dims] for p in self.points]) + + def append_dim(self, value : Union[float,List[float]] = 0.0) -> None: + """Appends a dimension to every point. If value is a list, then it + must be the same length as the number of points. Otherwise, the value + is appended to every point.""" + if isinstance(value,(int,float)): + for p in self.points: + p.append(value) + else: + if len(self.points) != len(value): + raise ValueError("Invalid length of values to append") + for p,v in zip(self.points,value): + p.append(v) + +@dataclass +@register +class Trajectory(Path): + """A timed, piecewise linear path.""" + times : List[float] + + def eval(self, t : float) -> List[float]: + """Evaluates the trajectory at a given time.""" + ind = 0 + while ind < len(self.times) and self.times[ind] < t: + ind += 1 + if ind == 0: return self.points[0] + if ind >= len(self.times): return self.points[-1] + u = (t - self.times[ind-1])/(self.times[ind] - self.times[ind-1]) + return transforms.vector_madd(self.points[ind-1],transforms.vector_sub(self.points[ind],self.points[ind-1]),u) + + def eval_derivative(self, t : float) -> List[float]: + """Evaluates the derivative at a given time.""" + ind = 0 + while ind < len(self.times) and self.times[ind] < t: + ind += 1 + if ind == 0: return self.points[0] + if ind >= len(self.times): return self.points[-1] + return transforms.vector_sub(self.points[ind],self.points[ind-1]) + + + def closest_point(self, x : List[float], edges = True) -> Tuple[float,float]: + """Returns the closest point on the path to the given point. If + edges=False, only computes the distances to the vertices, not the + edges. This is slightly faster but less accurate. + + Returns (distance, closest_time) + """ + distance, closest_index = Path.closest_point(x,edges) + i = int(closest_index) + u = closest_index - i + closest_time = self.times[i] + u*(self.times[i+1]-self.times[i]) + return distance, closest_time + + +def compute_headings(path : Path, smoothed = False) -> Path: + """Converts a 2D (x,y) path into a 3D path (x,y,heading) or a 3D + (x,y,z) path into a 5D path (x,y,z,heading,pitch). + + If smoothed=True, then the path is smoothed using a spline to better + estimate good tangent vectors. + """ + if smoothed: + raise NotImplementedError("Smoothing not done yet") + if len(path.points) < 2: + raise ValueError("Path must have at least 2 points") + derivs = [] + derivs.append(transforms.vector_sub(path.points[1],path.points[0])) + for i in range(1,len(path.points)-1): + derivs.append(transforms.vector_sub(path.points[i+1],path.points[i-1])) + derivs[-1] = transforms.vector_sub(path.points[-1],path.points[-2]) + nd = len(path.points[0])-1 + coords = [] + for d in derivs: + if transforms.vector2_dist(d,[0,0]) < 1e-6: + coords.append([0]*nd) + else: + dunit = transforms.normalize_vector(d) + if nd == 1: + coords.append((transforms.vector2_angle(dunit,[1,0]))) + elif nd == 2: + azimuth = transforms.vector2_angle(dunit[:2],[1,0]) + elevation = transforms.vector2_angle((dunit[2],transforms.vector_norm(dunit[:2])),[0,0,1]) + coords.append((azimuth,elevation)) + return replace(path,points=[tuple(p)+c for p,c in zip(path.points,coords)]) diff --git a/GEMstack/state/vehicle.py b/GEMstack/state/vehicle.py new file mode 100644 index 000000000..158e63f9f --- /dev/null +++ b/GEMstack/state/vehicle.py @@ -0,0 +1,38 @@ +from dataclasses import dataclass +from ..utils.serialization import register +from .physical_object import ObjectFrameEnum, ObjectPose +from enum import Enum + + +class VehicleGearEnum(Enum): + PARK = -2 + REVERSE = -1 + NEUTRAL = 0 + FIRST = 1 + SECOND = 2 + THIRD = 3 + FOURTH = 4 + FIFTH = 5 + SIXTH = 6 + + +@dataclass +@register +class VehicleState: + """Represents the state of the ego-vehicle.""" + pose : ObjectPose #pose of the vehicle + v : float #forward velocity in m/s + acceleration : float #current acceleration / deceleration in m/s^2 + steering_wheel_angle : float #angle of the steering wheel, in radians + front_wheel_angle : float #angle of the front wheels, in radians. Related to steering_wheel_angle by a fixed transform + heading_rate : float #the rate at which the vehicle is turning, in radians/s. Related to v and front_wheel_angle by a fixed transform + gear : VehicleGearEnum #the current gear + left_turn_indicator : bool = False #whether left turn indicator is on + right_turn_indicator : bool = False #whether right turn indicator is on + horn_on : bool = False #whether horn is on + wiper_level : int = 0 #whether wipers are on + + @staticmethod + def zero(): + return VehicleState(ObjectPose(ObjectFrameEnum.START,0,0,0),0,0,0,0,0,VehicleGearEnum.PARK,False,False,False,0) + \ No newline at end of file diff --git a/GEMstack/utils/__init__.py b/GEMstack/utils/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/GEMstack/utils/config.py b/GEMstack/utils/config.py new file mode 100644 index 000000000..2d34d82fa --- /dev/null +++ b/GEMstack/utils/config.py @@ -0,0 +1,87 @@ +import json +import yaml +import os +from typing import Any, IO + +def save_config(fn : str, config : dict) -> None: + """Saves a configuration file.""" + if fn.endswith('yaml') or fn.endswith('yml'): + with open(fn,'w') as f: + yaml.dump(config, f, yaml.Dumper) + elif fn.endswith('json'): + with open(fn,'w') as f: + json.dump(config,f) + else: + raise IOError("Config file not specified as .yaml, .yml, or .json extension") + + +def load_config_recursive(fn : str) -> dict: + """Loads a configuration file with !include directives.""" + if fn.endswith('yaml') or fn.endswith('yml'): + with open(fn,'r') as f: + res = yaml.load(f,_Loader) + return res + elif fn.endswith('json'): + with open(fn,'r') as f: + res = json.load(f) + base,f = os.path.split(fn) + return _load_recursive(res,base) + else: + raise IOError("Config file not specified as .yaml, .yml, or .json extension") + + + + +class _Loader(yaml.SafeLoader): + """YAML Loader with `!include` constructor.""" + + def __init__(self, stream: IO) -> None: + """Initialise Loader.""" + + try: + self._root = os.path.split(stream.name)[0] + except AttributeError: + self._root = os.path.curdir + + super().__init__(stream) + + +def _construct_include(loader: _Loader, node: yaml.Node) -> Any: + """Include file referenced at node.""" + return _load_config_or_text_recursive(os.path.join(loader._root, loader.construct_scalar(node))) + +def _construct_relative_path(loader: _Loader, node: yaml.Node) -> Any: + return os.path.join(loader._root, loader.construct_scalar(node)) + +yaml.add_constructor('!include', _construct_include, _Loader) + +yaml.add_constructor('!relative_path', _construct_relative_path, _Loader) + +def _load_config_or_text_recursive(fn : str) -> dict: + """Loads a configuration file with !include directives.""" + if fn.endswith('yaml') or fn.endswith('yml'): + with open(fn,'r') as f: + res = yaml.load(f,_Loader) + return res + elif fn.endswith('json'): + with open(fn,'r') as f: + res = json.load(f) + base,f = os.path.split(fn) + return _load_recursive(res,base) + else: + return ''.join(f.readlines()) + +def _load_recursive(obj, folder : str): + if isinstance(obj,dict): + for k,v in obj.copy().items(): + obj[k] = _load_recursive(v,folder) + elif isinstance(obj,list): + for i in range(len(obj)): + obj[i] = _load_recursive(obj[i],folder) + elif isinstance(obj,str): + if obj.startswith('!include '): + fn = obj.split(' ',1)[1] + return _load_config_or_text_recursive(os.path.normpath(os.path.join(folder,fn))) + elif obj.startswith('!!include'): + return obj[1:] + return obj diff --git a/GEMstack/utils/loops.py b/GEMstack/utils/loops.py new file mode 100644 index 000000000..06f813bc0 --- /dev/null +++ b/GEMstack/utils/loops.py @@ -0,0 +1,285 @@ +import time +import asyncio + +class TimedLooper: + """A class to easily control how timed loops are run. + + Usage:: + + looper = TimedLooper(dt=0.01) + while looper: + ... do stuff ... + if need to stop: + looper.stop() + #or just call break + + Note that if dt is too small (or rate is too large), the timing will not + be accurate due to the system scheduler resolution. + + If the code within the loop takes more than dt seconds to run, then a + warning may be printed. To turn this off, set ``warnings=0`` in the + constructor. By default, this will print a warning on the first overrun, + and every ``warning_frequency`` overruns thereafter. + + Args: + dt (float, optional): the desired time between loops (in seconds) + rate (float, optional): the number of times per second to run this + loop (in Hz). dt = 1/rate. One of dt or rate must be specified. + warning_frequency (int, optional): if the elapsed time between calls + exceeds dt, a warning message will be printed at this frequency. + Set this to 0 to disable warnings. + name (str, optional): a descriptive name to be used in the warning + string. + + Warning: DO NOT attempt to save some time and call the TimedLooper() + constructor as the condition of your while loop! I.e., do not do this:: + + while TimedLooper(dt=0.01): + ... + + """ + + def __init__(self, dt=None, rate=None, warning_frequency="auto", name=None): + self.dt = dt + if dt is None: + if rate is None: + raise AttributeError("One of dt or rate must be specified") + self.dt = 1.0 / rate + if self.dt < 0: + raise ValueError("dt must be positive") + if warning_frequency == "auto": + warning_frequency = int(2.0 / self.dt) + self.warning_frequency = warning_frequency + self.name = name + self._iters = 0 + self._time_overrun_since_last_warn = 0 + self._iters_of_last_warn = 0 + self._num_overruns_since_last_warn = 0 + self._num_overruns = 0 + self._warn_count = 0 + self._tstart = None + self._tlast = None + self._tnext = None + self._exit = False + + def stop(self): + self._exit = True + + def __nonzero__(self): + return self.__bool__() + + def __bool__(self): + if self._exit: + return False + tnow = time.time() + if self._tlast is None: + self._tstart = tnow + self._tnext = tnow + self._tlast = tnow + self._iters += 1 + return True + else: + elapsed_time = tnow - self._tnext + if elapsed_time > self.dt: + self._num_overruns += 1 + self._num_overruns_since_last_warn += 1 + self._time_overrun_since_last_warn += elapsed_time - self.dt + if ( + self.warning_frequency > 0 + and self._num_overruns % self.warning_frequency == 0 + ): + ave_overrun = ( + self._time_overrun_since_last_warn + / self._num_overruns_since_last_warn + ) + self.print_warning( + "{}: exceeded loop time budget {:.4f}s on {}/{} iters, by {:4f}s on average".format( + ("TimedLooper" if self.name is None else self.name), + self.dt, + self._num_overruns_since_last_warn, + self._iters - self._iters_of_last_warn, + ave_overrun, + ) + ) + self._iters_of_last_warn = self._iters + self._time_overrun_since_last_warn = 0 + self._num_overruns_since_last_warn = 0 + self._warn_count += 1 + self._tnext = tnow + else: + self._tnext += self.dt + assert ( + self._tnext >= tnow + ), "Uh... elapsed time is > dt but tnext < tnow: %f, %f, %f" % ( + elapsed_time, + self._tnext, + tnow, + ) + self._iters += 1 + time.sleep(self._tnext - tnow) + self._tlast = time.time() + return True + + def time_elapsed(self): + """Returns the total time elapsed from the start, in seconds""" + return time.time() - self._tstart if self._tstart is not None else 0 + + def iters(self): + """Returns the total number of iters run""" + return self._iters + + def print_warning(self, s): + """Override this to change how warning strings are printed, e.g. to + add your own logger""" + print(s) + + +class TimedLooperAsync: + """A class to easily control how timed loops are run. This is more + accurate than asyncio.sleep(dt) and also maintains information about + the loop. + + Usage:: + + looper = TimedLooperAsync(dt=0.01) + while no need to stop: + await looper() + ... do stuff ... + + Note that if dt is too small (or rate is too large), the timing will not + be accurate due to the system scheduler resolution. + + If the code within the loop takes more than dt seconds to run, then a + warning may be printed. To turn this off, set ``warnings=0`` in the + constructor. By default, this will print a warning on the first overrun, + and every ``warning_frequency`` overruns thereafter. + + Args: + dt (float, optional): the desired time between loops (in seconds) + rate (float, optional): the number of times per second to run this + loop (in Hz). dt = 1/rate. One of dt or rate must be specified. + warning_frequency (int, optional): if the elapsed time between calls + exceeds dt, a warning message will be printed at this frequency. + Set this to 0 to disable warnings. + name (str, optional): a descriptive name to be used in the warning + string. + + Warning: DO NOT attempt to save some time and call the TimedLooperAsync() + constructor as the condition of your while loop! I.e., do not do this:: + + while True: + await TimedLooperAsync(dt=0.01)() + ... do stuff... + + """ + + def __init__(self, dt=None, rate=None, warning_frequency="auto", name=None): + self.dt = dt + if dt is None: + if rate is None: + raise AttributeError("One of dt or rate must be specified") + self.dt = 1.0 / rate + if self.dt < 0: + raise ValueError("dt must be positive") + if warning_frequency == "auto": + warning_frequency = int(2.0 / self.dt) + self.warning_frequency = warning_frequency + self.name = name + self._iters = 0 + self._time_overrun_since_last_warn = 0 + self._iters_of_last_warn = 0 + self._num_overruns_since_last_warn = 0 + self._num_overruns = 0 + self._warn_count = 0 + self._tstart = None + self._tlast = None + self._tnext = None + + async def __call__(self): + tnow = time.time() + if self._tlast is None: + self._tstart = tnow + self._tnext = tnow + self._iters += 1 + self._tlast = tnow + else: + elapsed_time = tnow - self._tnext + if elapsed_time > self.dt: + self._num_overruns += 1 + self._num_overruns_since_last_warn += 1 + self._time_overrun_since_last_warn += elapsed_time - self.dt + if ( + self.warning_frequency > 0 + and self._num_overruns % self.warning_frequency == 0 + ): + ave_overrun = ( + self._time_overrun_since_last_warn + / self._num_overruns_since_last_warn + ) + self.print_warning( + "{}: exceeded loop time budget {:.4f}s on {}/{} iters, by {:4f}s on average".format( + ("TimedLooperAsync" if self.name is None else self.name), + self.dt, + self._num_overruns_since_last_warn, + self._iters - self._iters_of_last_warn, + ave_overrun, + ) + ) + self._iters_of_last_warn = self._iters + self._time_overrun_since_last_warn = 0 + self._num_overruns_since_last_warn = 0 + self._warn_count += 1 + self._tnext = tnow + else: + self._tnext += self.dt + assert ( + self._tnext >= tnow + ), "Uh... elapsed time is > dt but tnext < tnow: %f, %f, %f" % ( + elapsed_time, + self._tnext, + tnow, + ) + self._iters += 1 + await asyncio.sleep(self._tnext - tnow) + self._tlast = time.time() + + def time_elapsed(self): + """Returns the total time elapsed from the start, in seconds""" + return time.time() - self._tstart if self._tstart is not None else 0 + + def iters(self): + """Returns the total number of iters run""" + return self._iters + + def print_warning(self, s): + """Override this to change how warning strings are printed, e.g. to + add your own logger""" + print(s) + + +if __name__ == "__main__": + import random + + looper = TimedLooper(0.01, warning_frequency=10) + while looper: + print("Loop: {} iters, time {:0.3f} ~= {:0.3f} execution".format(looper.iters(),looper.time_elapsed(),looper.iters() * looper.dt)) + # simulate some time-consuming operation + time.sleep(random.uniform(0,0.005)) #below threshold + # time.sleep(random.uniform(0, 0.02)) # some above threshold + # time.sleep(0.05) #all above threshold + if looper.time_elapsed() > 5: + looper.stop() + input("Press enter to start async test") + + print("Starting async test (note: on windows async timers seem to be less accurate)") + async def test_async(): + alooper = TimedLooperAsync(0.01, warning_frequency=10) + t0 = time.time() + while alooper.time_elapsed() < 5: + await alooper() + print("Loop: {} iters, time {:0.3f} ~= {:0.3f} execution".format(alooper.iters(),alooper.time_elapsed(),alooper.iters() * alooper.dt)) + time.sleep(random.uniform(0,0.005)) #below threshold + # time.sleep(random.uniform(0, 0.02)) # some above threshold + # time.sleep(0.05) #all above threshold + asyncio.run(test_async()) + \ No newline at end of file diff --git a/GEMstack/utils/serialization.py b/GEMstack/utils/serialization.py new file mode 100644 index 000000000..ec4b565aa --- /dev/null +++ b/GEMstack/utils/serialization.py @@ -0,0 +1,172 @@ +import dacite +from dataclasses import dataclass, is_dataclass, asdict +import json +from enum import Enum +import typing + +REGISTRY = dict() + +def register(klass, name=None, version=None) -> None: + """Decorator that declares a class to be serializable/deserializable. + + If you wish to have multiple versions of a class, you can provide the + `version` keyword. + """ + if name is None: + name = klass.__name__ + if version is None: + version = '' + else: + version = str(version) + if name not in REGISTRY: + REGISTRY[name] = dict() + if version in REGISTRY[name]: + raise ValueError("A data class of name {} and version '{}' already exists".format(name,version)) + REGISTRY[name][version] = klass + setattr(klass,'__SERIALIZATION_NAME__',name) + setattr(klass,'__SERIALIZATION_VERSION__',version) + return klass + + + +def _custom_asdict_factory(data): + """Converts enums to their string values""" + def convert_value(obj): + if isinstance(obj, Enum): + return obj.value + return obj + + return dict((k, convert_value(v)) for k, v in data) + + +def is_registered(obj) -> bool: + """Returns True if this is a previously registered class""" + return '__SERIALIZATION_NAME__' in obj.__class__.__dict__ + +def json_encode(obj, format=str): + if format is str: + return json.dumps(obj) + elif format is bytes: + return json.dumps(obj).encode('utf-8') + elif format is dict: + return obj + elif format == 'ros': + from std_msgs import String + res = String() + res.data = json.dumps(obj) + return res + else: + raise ValueError("Format needs to be str, bytes, dict, or 'ros'") + +def json_decode(data) -> dict: + if isinstance(data,str): + return json.loads(data) + elif isinstance(data,bytes): + return json.loads(data.decode('utf-8')) + elif isinstance(data,dict): + return data + else: + from std_msgs import String + if isinstance(data,String): + return json.loads(data.data) + else: + raise ValueError("Format needs to be str, bytes, dict, or ROS String") + + +def serialize(obj, format=str): + """Serializes an instanceof a class previously declared using + `register()`. + + `format` can be `str`, `bytes`, `dict`, or `"ros"`. + """ + if not hasattr(obj.__class__,'__SERIALIZATION_NAME__'): + raise ValueError("Provided object of class {} which was not previously registered".format(obj.__class__.__name__)) + if not is_dataclass(obj): + raise ValueError("Provided object of class {} which is not a dataclass".format(obj.__class__.__name__)) + + values = asdict(obj, dict_factory=_custom_asdict_factory) + frame = {'type':obj.__class__.__SERIALIZATION_NAME__,'data':values} + if obj.__class__.__SERIALIZATION_VERSION__: + frame['version'] = obj.__class__.__SERIALIZATION_VERSION__ + return json_encode(frame,format) + + +def deserialize(data): + """Deserializes data into an instance of a class previously declared using + `register()`. + + `data` can be a `str`, `bytes`, `dict`, or ROS std_msgs/String object. + """ + global REGISTRY + name,version,data = deserialize_raw(data) + if name not in REGISTRY: + raise IOError("Class of type {} not found in registry".format(name)) + if version not in REGISTRY[name]: + raise IOError("Version {} of type {} not found in registry".format(version,name)) + return dacite.from_dict(REGISTRY[name][version],data, config=dacite.Config(cast=[Enum,tuple,typing.Tuple])) + + +def deserialize_raw(data) -> tuple: + """Deserializes data into a tuple (name, version, dict). More error- + tolerant than deserialize. + """ + frame = json_decode(data) + if not isinstance(frame,dict): + raise IOError("Did not get a dict from JSON-encoded data") + if 'type' not in frame: + raise IOError("Data did not contain 'type' key") + if 'data' not in frame: + raise IOError("Data did not contain 'data' key") + name = frame['type'] + version = frame.get('version','') + return name,version,frame['data'] + + +def serialize_collection(objs, format=str): + """Serializes a collection of registered objects into a serialized + collection objects. + + `format` can be `str`, `bytes`, `dict`, or `"ros"`. + """ + if format is dict: + if isinstance(objs,dict): + objs = dict((k,serialize_collection(v,dict)) for k,v in objs.items()) + elif isinstance(objs,list): + objs = [serialize_collection(v,dict) for v in objs] + elif is_registered(objs): + objs = serialize(objs,dict) + return objs + return json_encode(serialize_collection(objs,dict),format) + + +def deserialize_collection(data): + """Deserializes a message into a collection of registered object instances. + + We detect registered types as dicts with "type" and "data" keys, and + optional "version" key.""" + frame = json_decode(data) + def _recurse(obj): + if isinstance(obj,dict) and 'type' in obj and 'data' in obj: + if len(obj) == 2 or (len(obj) == 3 and 'version' in obj): + return deserialize(obj) + return obj + elif isinstance(obj,dict): + for k,v in obj.items(): + obj[k] = _recurse(v) + return obj + elif isinstance(obj,list): + for i in range(len(obj)): + obj[i] = _recurse(obj[i]) + return obj + else: + return obj + return _recurse(frame) + + +def load(file): + """Loads a JSON file containing serialized data into a registered class.""" + return deserialize(file.read()) + +def save(obj,file): + """Saves a JSON file containing serialized data into a registered class.""" + file.write(serialize(obj)) \ No newline at end of file diff --git a/GEMstack/utils/settings.py b/GEMstack/utils/settings.py new file mode 100644 index 000000000..eef657800 --- /dev/null +++ b/GEMstack/utils/settings.py @@ -0,0 +1,77 @@ +import json +from ..knowledge import defaults +import copy +from typing import List,Union,Any + +SETTINGS = None + +def load_settings(): + """Loads the settings object for the first time. + + Order of operations is to look into defaults.SETTINGS, and then + look through the command line arguments to determine whether the user has + overridden any settings using --KEY=VALUE. + """ + global SETTINGS + if SETTINGS is not None: + return + import os + import sys + SETTINGS = copy.deepcopy(defaults.SETTINGS) + for arg in sys.argv: + if arg.startswith('--'): + k,v = arg.split('=',1) + k = k[2:] + v = v.strip('"') + v = json.loads(v) + if v.startswith('{'): + set(k,v,leaf_only=False) + else: + set(k,v) + + return + + +def settings(): + """Returns all global settings, loading them if necessary.""" + global SETTINGS + load_settings() + return SETTINGS + + +def get(path : Union[str,List[str]], defaultValue=KeyError) -> Any: + """Retrieves a setting by a list of keys or a '.'-separated string.""" + global SETTINGS + load_settings() + if isinstance(path,str): + path = path.split('.') + try: + val = SETTINGS + for key in path: + val = val[key] + return val + except KeyError: + if defaultValue is KeyError: + print("Available keys:",val.keys()) + raise + return defaultValue + +def set(path : Union[str,List[str]], value : Any, leaf_only=True) -> None: + """Sets a setting by a list of keys or a '.'-separated string. + + If leaf_only=True (default), we prevent inadvertently deleting parts of the + settings dictionary. + """ + global SETTINGS + load_settings() + if isinstance(path,str): + path = path.split('.') + val = SETTINGS + if len(path) == 0: + raise KeyError("Cannot set top-level settings") + for key in path[:-1]: + val = val[key] + if leaf_only: + if path[-1] in val and isinstance(val[path[-1]],dict): + raise ValueError("Can only set leaves of the settings dictionary when leaf_only=True is given") + val[path[-1]] = value diff --git a/README.md b/README.md index 72c6bb591..7a083b091 100644 --- a/README.md +++ b/README.md @@ -1,2 +1,239 @@ -# GEMstack -Educational utonomous driving stack for the Polaris GEM vehicle +# GEMstack: software structure for CS588 Autonomous Vehicle System Engineering + +## Dependencies + +Python 3.7+ + +PACMOD - low level Autonomoustuff's interface to vehicle + +ROS (Noetic?) - messaging with cameras, simulator + +Python dependencies: +- opencv-python +- numpy +- scipy +- torch +- shapely +- dacite +- pyyaml + +## Package structure + +All packages are within the `GEMstack/` folder. + +`mathutils/`: Math utilities common to onboard / offboard use. + - `transforms`: 2d and 3d rotations and rigid transforms. + - `filters`: 1d signal processing. + - `cameras`: Contains standard camera models. + - `differences`: Finite differences for derivative approximation. + - `dynamics`: Contains standard dynamics models. + - `dubins`: Contains first- and second-order Dubins car dynamics models. + - `control`: Contains standard control techniques, e.g., PID controller. + - `collisions`: Provides collision detection and proximity detection. +`utils/`: Other utilities common to onboard / offboard use. + - `logging`: Provides logging and log replay functionality. + - `simulation`: Interfaces with the Gazebo (possibly other?) simulators. + - `visualization`: Tools for converting internal data on knowledge, state, etc. to visualization apps. + - `settings`: Tools for managing settings for onboard behaviour. If you're tempted to write a magic parameter or global variable, it should be placed here instead. + - `config`: Tools for loading config files. + - `serialization`: Tools for serializing / deserializing objects. +`state/`: Representations of state of the vehicle and its environment, including internal state that persists from step to step. + - `physical_object`: A generic physical object base class. + - `trajectory`: Stores a generic path or trajectory. + - `vehicle`: Ego-vehicle state. + - `intent`: Ego-vehicle intent that may involve special logic or signaling behavior, e.g., lane change, take exit, shutting down. + - `roadgraph`: A section of the roadmap around the ego-vehicle. + - `roadmap`: A map created for offline use. + - `environment`: Environmental conditions, e.g., weather, road conditions. + - `obstacle`: A static obstacle or debris. + - `sign`: A traffic sign. + - `agent`: Another moving object, e.g., pedestrian, bicyclist, vehicle. + - `scene`: All physical items that may be relevant to the current scene, i.e., vehicle, roadgraph, environment, obstacles, and agent states. + - `agent_intent`: Maintains an estimate of agent intent. + - `entity_relation`: Maintains an estimate of a relationship between entities, e.g. VISIBLE, FOLLOWING, PASSING, YIELDING. + - `mission`: Stores the current mission objective, e.g., IDLE, DRIVE_ROUTE, ESTOP, used by routing, logic, planning, and execution. + - `predicates`: Any items predicates that are estimated to be true in the current world. + - `route`: Stores a 2d route, coming from the router. + - `all`: State or the current scene, all intent and relation estimates, and the driving logic (objective, predicates, route). +`offboard/`: Creation and management of data and knowledge. + - `calibration/`: Sensor calibration. + - `log_management/`: Provides log management, browsing, and query functionality. + - `detection_learning/`: Detection model learning. + - `prediction_learning/`: Prediction model learning. + - `heuristic_learning/`: Driving heuristic learning. +`knowledge/`: Models and parameters common to onboard / offboard use. The file "current.py" in each directory will store the current model being used. + - `vehicle/`: Vehicle geometry and physics. + - `calibration/`: Calibrated sensor parameters. + - `detection/`: Stores detection models. + - `prediction/`: Stores prediction models. + - `heuristics/`: Stores heuristic models. + - `roadmaps/`: Stores roadmap knowledge, e.g., lanes, regions, obstacles, signs. + - `routes/`: Stores precomputed routes. + - `predicates/`: Stores named predicates that may be true in a world state. + - `defaults/`: Stores the default settings. +`launch/`: Launch scripts are listed here. Specify which configuration you want to use as an argument to `main.py`. +`onboard/`: All algorithms governing onboard behavior are located here. These algorithms may make use of items in the `knowledge/` stack. + `perception/`: Perception components. + - `state_estimation`: State estimators. + - `roadgraph_update`: Roadgraph updaters. + - `lane_detection`: Lane detection. + - `sign_detection`: Sign detection. + - `obstacle_detection`: Obstacle detction. + - `agent_detection`: Agent detection. + - `environment_detection`: Environment condition detection. + - `intent_estimation`: Agent intent estimation. + - `relation_estimation`: Entity relation estimation. + - `agent_prediction`: Agent motion prediction. + `planning/`: Planning components. + - `route_planner`: Decides which route to drive from the roadgraph. + - `driving_logic`: Performs all necessary logic to develop a planning problem specification, e.g., select obstacles, design cost functions, etc. + - `heuristics`: Implements various planning heuristics. + - `motion_planning`: Implements one or more motion planners. + - `optimization`: Implements one or more trajectory optimizers. + - `selection`: Implements best-trajectory selection. + - `pure_pursuit`: Implements a pure pursuit controller. + - `recovery`: Implements recovery behavior. + `execution/`: Executes the onboard driving behavior. + - `entrypoint`: The entrypoint that launches all onboard behavior. Configured by settings in 'run' + - `executor`: Base classes for executors. + - `log_replay`: A generic component that replays from a log. + `interface/`: Defines interfaces to vehicle hardware / simulators / external signals + - `gem.py`: Base class for the Polaris GEM e2 vehicle. + - `gem_hardware.py`: Interface to the real GEM vehicle. + - `gem_simulator.py`: Interfaces to simulated GEM vehicles. + - `teleop`: Teleoperator control signals. + + +## Launching the stack + +You will launch a simulation using: + +- `python main.py GEMstack/launch/LAUNCH_FILE.yaml` where `LAUNCH_FILE.yaml` is your preferred simulation launch file. Inspect the simulator classes in `GEMstack/onboard/interface/gem_simulator/` for more information about configuring the simulator. + +To launch onboard behavior you will open four terminal windows, and in each of them run: +- `roscore` +- `roslaunch basic_launch sensor_init.launch` +- `roslaunch basic_launch visualization.launch` +- `python main.py GEMstack/launch/LAUNCH_FILE.yaml` where `LAUNCH_FILE.yaml` is your preferred launch file. + + +Note that if you try to use `import GEMstack` in a script or Jupyter notebook anywhere outside of this directory, Python will not know where the `GEMstack` module is. If you wish to import `GEMstack` from a script located in a separate directory, you can put + +```python +import sys +import os +sys.path.append(os.getcwd()) #or enter the absolute path of this directory + +import GEMstack +``` + +at the top of your script. Then, you can run the script from this directory via `python PATH/TO/SCRIPT/myscript.py`. See the scripts in `testing` for an example of how this is done. + +You can also install `GEMstack` into the system Python by calling `pip install .`, but this is not recommended because has a couple of drawbacks: +- You might make changes in this directory, e.g., via `git pull`, and then forget to reinstall, so the changes won't be reflected when you run your code. +- If you added model or roadgraph files, e.g., to the `knowledge` directory, they may not be installed. You will need to edit `pyproject.toml` to include those files. + + + +## Communication protocols + +Sending commands to the vehicle is handled by the ROS-PACMOD interface. Receiving sensor messages is handled through standard ROS sensor messages. + +Generally speaking, the only onboard components that should be reading from sensors are the Perception components. The only onboard components that should be sending commands to the vehicle are the Execution comopnents. + +For internal state messages, which changes rapidly during development, we use raw Python dictionaries, lists, and primitives. This is also known as JSON format. The `utils.serialization` library makes this easy for you. We convert strings to and from Python classes that are annotated with the `@dataclass` decorator and you can add your own classes using the `@utils.serialization.register` decorator. You can then use the `utils.serialization.serialize` and `utils.serialization.deserialize` functions to convert to/from strings or ROS `std_msgs/String` messages. + +Note that all registered class names must be unique. Also, **versioning** is a major problem if you wish to use legacy logs. If you gather some logs, change your class' attributes, and then attempt to view those logs again, you may encounter an error or missing data. The `serialization` module will do as much as it can to fail silently and enter `None` into missing fields, but it can still fail. If you wish to parse logs that contain legacy data, you can use the `version` keyword to `register`, as follows. + +```python +from utils.serialization import register +from dataclasses import dataclass + +@dataclass +@register(name="MyClass",version="1") +class MyClass_Original: + x : float + y : float + +@dataclass +@register(name="MyClass",version="2") +class MyClass: + x : float + y : float + time : float + +``` + +Keep in mind that your functions will need to distinguish between the old and new classes. It may be better in this case just to use a single class and tag `time` as having type `Optional[float]`. Then, your functions can see whether `time` is `None`, and if so, invoke the old-style behavior. + + +## Settings + +Magic parameters and global variables are a scourge and must be eliminated in production code. Instead, you will declare parameters in configuration files. In your code, you will access settings using the `utils.settings` module. For example, + +```python +from GEMutils.utils import settings +settings.get('key1.key2.attribute') +``` + +The entrypoint will consume a run launch file and a settings file. + +## Branches and submitting pull requests + +To count as a contribution to the team, you will need to check in your code via pull requests (PRs). PRs should be reviewed by at least one other approver. + +- `main`: will contain content that persists between years. Approver: Kris Hauser. +- `s2024`: is the "official class vehicle" for this semester's class. Approver: instructor, TAs. +- `s2024_teamX`: will be your team's branch. Approver: instructor, TAs, team members. + +Guidelines: +- DO NOT check in large datasets. Instead, keep these around on SSDs. +- DO check in trained models, named descriptively. In your PR, describe how you evaluated the model and its results. Choose which model you use in your tests in the settings. + +## Homework assignments + +HW1 (out 1/17, in 1/24): Distress signals +- Skills: Familiarization with ROS and GEMstack structure, Git +- Receive low-level messages from the sensors via ROS and print them +- Send low-level messages to flash distress to the vehicle via ROS +- Use Git to create a fork, create a behavior with your distress signal. Push contributions, and run your fork on GEM. + +HW2 (out 1/24, in 2/7): Stop for a pedestrian. +- Skills: Object detection, trajectory tracking, logic-based motion planning, safety driver training +- Use provided object detector to identify pedestrian from front camera. Run on the vehicle. +- Use a motion planner to create a trajectory that slows and stops at a safe distance when pedestrian appears. +- Modify the planner to resume slowly when the pedestrian disappears +- Run on the vehicle + +HW3 (out 2/7, in 2/21): Pedestrian tracking +- Sensor calibration, scene state, coordinate conversions +- Perform sensor calibration and update current calibration in the knowledge directory +- Use pedestrian detector on multiple cameras to place agents in the scene +- Visualize the sensor data and the estimated agents in `rviz` using `visualization_msgs/MarkerArray`. +- Record the agent trajectories in the START coordinate frame into a log. +- Plot agent trajectories from the log as curves in matplotlib. + +After HW3, the class will split into teams and work on different parts of the stack. Your grades will be determined by your team presentations, individual contributions, within-team peer reviews, and between-team peer reviews. + +Checkpoint 1 (out 2/21, in 3/6) +- Produce design document and present at design review on 3/6. +- Design document should: establish a list of goals. Describe plan for implementation. Assign personnel. Show timeline to implementation and evaluation. +- Peer reviews due next day. + +Checkpoint 2 (out 3/6, in 3/27) +- Progress report presentation on 3/27 +- Presentation should describe implementation progress, unit testing results (concisely describe metrics used), changes in direction, demonstrations, review of code contributions. Discuss integration plans. +- Peer reviews due next day. + +Integration checkpoint 3 (out 3/27, in 4/10) +- Progress report presentation on 4/10 +- Presentation should describe integration results (i.e., pull reviews, metrics), changes in direction, demonstrations, review of code contributions. +- Peer reviews due next day. + +Checkpoint 4 (out 4/10, in 4/24) +- Revise design document to mark achieved checkpoints, integration metrics, and changes of plans. Present at design review on 4/24. + +Final presentation (5/8) +- Pitch contribution of team to "investor" / "CEO". Describe final integration results. +- Reflect on how design has evolved. Review code contributions. + diff --git a/data/README.md b/data/README.md new file mode 100644 index 000000000..afeb3994d --- /dev/null +++ b/data/README.md @@ -0,0 +1,3 @@ +Datasets should be placed here, not within the GEMstack/GEMstack folder. + +Knowledge distilled from datasets that will affect onboard behavior, e.g., models should be placed within GEMstack/knowledge. \ No newline at end of file diff --git a/logs/README.md b/logs/README.md new file mode 100644 index 000000000..70c0a33ad --- /dev/null +++ b/logs/README.md @@ -0,0 +1,10 @@ +Default logging directory. + +Logs are placed within a timestamped folder. + +Within each folder, the file structure is: + +- meta.yaml: metadata for the run, including events, termination result, git branch and commit ID. +- settings.yaml: the entire settings dictionary for the run. +- vehicle.bag: rosbag file for vehicle messages +- behavior.json: logged messages within the behavior stack. diff --git a/main.py b/main.py new file mode 100644 index 000000000..4f0d9a6f3 --- /dev/null +++ b/main.py @@ -0,0 +1,30 @@ +from GEMstack.utils import settings,config +import sys + +if __name__=='__main__': + launch_file = None + for arg in sys.argv[1:]: + if arg.startswith('--run='): + launch_file = arg[9:] + break + elif not arg.startswith('--'): + launch_file = arg + break + if launch_file is None: + runconfig = settings.get('run',None) + if runconfig is None: + print("Usage: python3 [--key1=value1 --key2=value2] LAUNCH_FILE.yaml") + print(" Current settings are found in knowledge/defaults/current.yaml") + exit(1) + else: + print("Using default run configuration in knowledge/defaults/current.yaml") + else: + #set the run settings from command line + run_config = config.load_config_recursive(launch_file) + print(run_config) + settings.set('run',run_config) + if settings.get('run.name',None) is None: + settings.set('run.name',launch_file) + + from GEMstack.onboard.execution import entrypoint + entrypoint.main() diff --git a/pyproject.toml b/pyproject.toml new file mode 100644 index 000000000..3d6393d50 --- /dev/null +++ b/pyproject.toml @@ -0,0 +1,36 @@ +[build-system] +requires = ["setuptools >= 42.0","wheel"] +build-backend = "setuptools.build_meta" + +[tool.setuptools.packages.find] +include = ["GEMstack*"] # package names should match these glob patterns (["*"] by default) + +[tool.setuptools.package-data] +GEMstack = ["*.yaml","*.yml","*.json"] #include config files in the knowledge directory + +[project] +name = 'GEMstack' +version = '0.1' +description='GEM stack' +authors = [ + {name='Kris Hauser', email='hauser.kris@gmail.com' } +] +requires-python = ">=3.7" +readme = 'README.md' +license = {file='LICENSE'} +dependencies=['numpy', + 'shapely', + 'pyyaml', + 'klampt' + ] + +classifiers = [ + 'Development Status :: 5 - Production/Stable', + 'Intended Audience :: Developers', + 'Programming Language :: Python', + 'License :: OSI Approved :: Apache Software License', + 'Topic :: Communications', +] + +[project.urls] +Repository = "https://www.github.com/krishauser/GEMstack" diff --git a/requirements.txt b/requirements.txt new file mode 100644 index 000000000..a0d8e42f6 --- /dev/null +++ b/requirements.txt @@ -0,0 +1,8 @@ +opencv-python +numpy +scipy +torch +shapely +klampt +pyyaml +dacite diff --git a/testing/test_poses.py b/testing/test_poses.py new file mode 100644 index 000000000..a265b648d --- /dev/null +++ b/testing/test_poses.py @@ -0,0 +1,36 @@ +#needed to import GEMstack from top level directory +import sys +import os +sys.path.append(os.getcwd()) + +from GEMstack.state import PhysicalObject,ObjectPose,ObjectFrameEnum +from GEMstack.mathutils import transforms +import math +import time + +def test_poses(): + print(math.degrees(transforms.heading_to_yaw(0.0)),'== 90') + print(math.degrees(transforms.heading_to_yaw(90.0)),'== 0') + print(transforms.yaw_to_heading(math.pi,degrees=True),'== 270') + + start_pose_abs = ObjectPose(frame=ObjectFrameEnum.ABSOLUTE_CARTESIAN,t=time.time(),x=30.0,y=20.0,yaw=0.5) + current_pose_abs = ObjectPose(frame=ObjectFrameEnum.ABSOLUTE_CARTESIAN,t=time.time()+55.0,x=60.0,y=25.0,yaw=1.5) + current_pose_start = ObjectPose(frame=ObjectFrameEnum.START,t=55.0,x=60.0,y=25.0,yaw=1.0) + test_pose_start = ObjectPose(frame=ObjectFrameEnum.START,t=75.0,x=80.0,y=20.0,yaw=1.2) + test_pose_current = ObjectPose(frame=ObjectFrameEnum.CURRENT,t=20.0,x=20.0,y=00.0,yaw=0.2) + print(start_pose_abs.transform()) + print(current_pose_start.transform()) + print(start_pose_abs.apply((0.4,0.3))) + print(start_pose_abs.apply((0.4,0.3,0.2))) + test_pose_current.to_frame(ObjectFrameEnum.START,current_pose=current_pose_start,start_pose_abs=start_pose_abs) + test_pose_current.to_frame(ObjectFrameEnum.START,current_pose=current_pose_abs,start_pose_abs=start_pose_abs) + test_pose_current.to_frame(ObjectFrameEnum.ABSOLUTE_CARTESIAN,current_pose=current_pose_start,start_pose_abs=start_pose_abs) + test_pose_current.to_frame(ObjectFrameEnum.ABSOLUTE_CARTESIAN,current_pose=current_pose_abs,start_pose_abs=start_pose_abs) + test_pose_start.to_frame(ObjectFrameEnum.CURRENT,current_pose=current_pose_start,start_pose_abs=start_pose_abs) + test_pose_start.to_frame(ObjectFrameEnum.CURRENT,current_pose=current_pose_abs,start_pose_abs=start_pose_abs) + test_pose_start.to_frame(ObjectFrameEnum.ABSOLUTE_CARTESIAN,current_pose=current_pose_start,start_pose_abs=start_pose_abs) + test_pose_start.to_frame(ObjectFrameEnum.ABSOLUTE_CARTESIAN,current_pose=current_pose_abs,start_pose_abs=start_pose_abs) + print("TODO: make this more comprehensive") + +if __name__=='__main__': + test_poses() \ No newline at end of file diff --git a/testing/test_serialization.py b/testing/test_serialization.py new file mode 100644 index 000000000..2accd23c9 --- /dev/null +++ b/testing/test_serialization.py @@ -0,0 +1,23 @@ +#needed to import GEMstack from top level directory +import sys +import os +sys.path.append(os.getcwd()) + +from GEMstack.utils import serialization +from GEMstack.state import PhysicalObject,ObjectPose,ObjectFrameEnum + +def test_serialization(): + o = PhysicalObject(pose=ObjectPose(frame=ObjectFrameEnum.GLOBAL,t=0.0,x=2.0,y=4.0,yaw=0.5), + dimensions=(0.1,0.1,0.1), + outline=None) + print(serialization.serialize(o)) + o2 = serialization.deserialize(serialization.serialize(o)) + assert o == o2 + + coll = {'objects':[o]*5,'others':'hi'} + print(serialization.serialize_collection(coll)) + coll2 = serialization.deserialize_collection(serialization.serialize_collection(coll)) + assert coll == coll2 + +if __name__=='__main__': + test_serialization() \ No newline at end of file From d5289942024a3d01f7015cbde916abd4654af26e Mon Sep 17 00:00:00 2001 From: krishauser Date: Fri, 15 Dec 2023 15:25:50 -0500 Subject: [PATCH 003/232] Ignore pushing logs and data --- data/.gitignore | 5 +++++ logs/.gitignore | 5 +++++ 2 files changed, 10 insertions(+) create mode 100644 data/.gitignore create mode 100644 logs/.gitignore diff --git a/data/.gitignore b/data/.gitignore new file mode 100644 index 000000000..bdbb4f7fc --- /dev/null +++ b/data/.gitignore @@ -0,0 +1,5 @@ +* + +# track just these files +!.gitignore +!README.md diff --git a/logs/.gitignore b/logs/.gitignore new file mode 100644 index 000000000..e351385fb --- /dev/null +++ b/logs/.gitignore @@ -0,0 +1,5 @@ +# * + +# track just these files +!.gitignore +!README.md From 6b4254d39d6327cbbc2cbaab4ab827f61a1e502a Mon Sep 17 00:00:00 2001 From: krishauser Date: Fri, 15 Dec 2023 15:26:58 -0500 Subject: [PATCH 004/232] Proper spacing in readme --- README.md | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/README.md b/README.md index 7a083b091..78a68e864 100644 --- a/README.md +++ b/README.md @@ -30,6 +30,7 @@ All packages are within the `GEMstack/` folder. - `dubins`: Contains first- and second-order Dubins car dynamics models. - `control`: Contains standard control techniques, e.g., PID controller. - `collisions`: Provides collision detection and proximity detection. + `utils/`: Other utilities common to onboard / offboard use. - `logging`: Provides logging and log replay functionality. - `simulation`: Interfaces with the Gazebo (possibly other?) simulators. @@ -37,6 +38,7 @@ All packages are within the `GEMstack/` folder. - `settings`: Tools for managing settings for onboard behaviour. If you're tempted to write a magic parameter or global variable, it should be placed here instead. - `config`: Tools for loading config files. - `serialization`: Tools for serializing / deserializing objects. + `state/`: Representations of state of the vehicle and its environment, including internal state that persists from step to step. - `physical_object`: A generic physical object base class. - `trajectory`: Stores a generic path or trajectory. @@ -55,12 +57,14 @@ All packages are within the `GEMstack/` folder. - `predicates`: Any items predicates that are estimated to be true in the current world. - `route`: Stores a 2d route, coming from the router. - `all`: State or the current scene, all intent and relation estimates, and the driving logic (objective, predicates, route). + `offboard/`: Creation and management of data and knowledge. - `calibration/`: Sensor calibration. - `log_management/`: Provides log management, browsing, and query functionality. - `detection_learning/`: Detection model learning. - `prediction_learning/`: Prediction model learning. - `heuristic_learning/`: Driving heuristic learning. + `knowledge/`: Models and parameters common to onboard / offboard use. The file "current.py" in each directory will store the current model being used. - `vehicle/`: Vehicle geometry and physics. - `calibration/`: Calibrated sensor parameters. @@ -71,7 +75,9 @@ All packages are within the `GEMstack/` folder. - `routes/`: Stores precomputed routes. - `predicates/`: Stores named predicates that may be true in a world state. - `defaults/`: Stores the default settings. + `launch/`: Launch scripts are listed here. Specify which configuration you want to use as an argument to `main.py`. + `onboard/`: All algorithms governing onboard behavior are located here. These algorithms may make use of items in the `knowledge/` stack. `perception/`: Perception components. - `state_estimation`: State estimators. @@ -84,6 +90,7 @@ All packages are within the `GEMstack/` folder. - `intent_estimation`: Agent intent estimation. - `relation_estimation`: Entity relation estimation. - `agent_prediction`: Agent motion prediction. + `planning/`: Planning components. - `route_planner`: Decides which route to drive from the roadgraph. - `driving_logic`: Performs all necessary logic to develop a planning problem specification, e.g., select obstacles, design cost functions, etc. @@ -93,10 +100,12 @@ All packages are within the `GEMstack/` folder. - `selection`: Implements best-trajectory selection. - `pure_pursuit`: Implements a pure pursuit controller. - `recovery`: Implements recovery behavior. + `execution/`: Executes the onboard driving behavior. - `entrypoint`: The entrypoint that launches all onboard behavior. Configured by settings in 'run' - `executor`: Base classes for executors. - `log_replay`: A generic component that replays from a log. + `interface/`: Defines interfaces to vehicle hardware / simulators / external signals - `gem.py`: Base class for the Polaris GEM e2 vehicle. - `gem_hardware.py`: Interface to the real GEM vehicle. From 72b01e06c511e098687b036e158285b5954a3849 Mon Sep 17 00:00:00 2001 From: krishauser Date: Fri, 15 Dec 2023 15:27:36 -0500 Subject: [PATCH 005/232] Nesting lists --- README.md | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/README.md b/README.md index 78a68e864..eb9a09a3f 100644 --- a/README.md +++ b/README.md @@ -79,7 +79,7 @@ All packages are within the `GEMstack/` folder. `launch/`: Launch scripts are listed here. Specify which configuration you want to use as an argument to `main.py`. `onboard/`: All algorithms governing onboard behavior are located here. These algorithms may make use of items in the `knowledge/` stack. - `perception/`: Perception components. + - `perception/`: Perception components. - `state_estimation`: State estimators. - `roadgraph_update`: Roadgraph updaters. - `lane_detection`: Lane detection. @@ -91,7 +91,7 @@ All packages are within the `GEMstack/` folder. - `relation_estimation`: Entity relation estimation. - `agent_prediction`: Agent motion prediction. - `planning/`: Planning components. + - `planning/`: Planning components. - `route_planner`: Decides which route to drive from the roadgraph. - `driving_logic`: Performs all necessary logic to develop a planning problem specification, e.g., select obstacles, design cost functions, etc. - `heuristics`: Implements various planning heuristics. @@ -101,12 +101,12 @@ All packages are within the `GEMstack/` folder. - `pure_pursuit`: Implements a pure pursuit controller. - `recovery`: Implements recovery behavior. - `execution/`: Executes the onboard driving behavior. + - `execution/`: Executes the onboard driving behavior. - `entrypoint`: The entrypoint that launches all onboard behavior. Configured by settings in 'run' - `executor`: Base classes for executors. - `log_replay`: A generic component that replays from a log. - `interface/`: Defines interfaces to vehicle hardware / simulators / external signals + - `interface/`: Defines interfaces to vehicle hardware / simulators / external signals - `gem.py`: Base class for the Polaris GEM e2 vehicle. - `gem_hardware.py`: Interface to the real GEM vehicle. - `gem_simulator.py`: Interfaces to simulated GEM vehicles. From e2ac1b49cb330c26f702b6e9443b682de7279cc8 Mon Sep 17 00:00:00 2001 From: krishauser Date: Fri, 15 Dec 2023 15:51:04 -0500 Subject: [PATCH 006/232] Updated readme, added CODEOWNERS --- .github/CODEOWNERS | 1 + README.md | 10 +++++++++- 2 files changed, 10 insertions(+), 1 deletion(-) create mode 100644 .github/CODEOWNERS diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS new file mode 100644 index 000000000..5f54a3b91 --- /dev/null +++ b/.github/CODEOWNERS @@ -0,0 +1 @@ +* @krishauser diff --git a/README.md b/README.md index eb9a09a3f..bb237edd1 100644 --- a/README.md +++ b/README.md @@ -185,7 +185,14 @@ from GEMutils.utils import settings settings.get('key1.key2.attribute') ``` -The entrypoint will consume a run launch file and a settings file. +To override a setting temporarily (just for a few run), you can run your script with an optional `--key=value` command-line argument. For example, to set the simulation scene, you can use `--simulator.scene=PATH/TO/SCENE/FILE`. + +To create new settings or override a setting more permanently, you should dive into `GEMstack/knowledge/defaults/current.yaml`. This [YAML](https://yaml.org/) formatted configuration file specifies the entire configuration that can be accessed through the `utils.settings` module. One of these files may `!include` other configuration files, so if you are adding a large number of related settings, e.g., for some component module, it would make sense to create that module's own YAML file. For example, you may create a YAML file `mymodule_default_config.yaml` add it to `current.yaml` under the `mymodule` key, e.g.,`mymodule: !include mymodule_default_config.yaml`. (Of course, replace `mymodule` with a descriptive name of your module, duh.) + +Note that there are settings that configure **an algorithm's behavior** that persist between runs, and there are settings that configure **a particular run**. If you want to configure an algorithm, put it in `current.yaml`, a descendant configuration file, or elsewhere in `knowledge`. If you want to configure a single run, you should place those options in the launch file. The `main.py` entrypoint will consume a run launch file and a settings file, and will place all the run configurations in the `run` attribute of the global settings. So if you wish to inspect run details or specify per-run behavior, e.g., see whether we are in a simulation run or a hardware run, your algorithm can check `settings.get('run.mode')`. In general, you should try to minimize how dependent your algorithms are on run settings. + +Another way to think about this is that we are trying to **evolve the onboard software stack to generate better behavior** by changing algorithms and their settings. The evolution mechanism is implemented by commits to the repository. On a day to day level, you will be performing different types of runs, such as simulation tests, unit tests, and full integration tests. You may be testing a lot of different conditions but the software stack should remain constant for that suite of tests. If you wish to do an apples-to-apples comparison against a different version of the stack, you should git check out another commit ID, and then perform those same tests. So if you are configuring the software stack, the setting changes should go into `knowledge`. If you are configuring how the software stack works just for a single test, the setting changes should go into the launch script or a keyword argument. + ## Branches and submitting pull requests @@ -199,6 +206,7 @@ Guidelines: - DO NOT check in large datasets. Instead, keep these around on SSDs. - DO check in trained models, named descriptively. In your PR, describe how you evaluated the model and its results. Choose which model you use in your tests in the settings. + ## Homework assignments HW1 (out 1/17, in 1/24): Distress signals From 7a6705775a31cc02ce589dabf7813b35156440a2 Mon Sep 17 00:00:00 2001 From: krishauser Date: Sat, 23 Dec 2023 12:36:44 -0500 Subject: [PATCH 007/232] Updated to perform logging, fixed bugs with vehicle dynamics --- GEMstack/knowledge/calibration/gem.yaml | 5 +- .../knowledge/defaults/computation_graph.yaml | 12 +- GEMstack/knowledge/defaults/current.yaml | 3 + GEMstack/knowledge/defaults/gem_dynamics.yaml | 5 +- GEMstack/knowledge/predicates/agent_count.py | 27 ++ GEMstack/knowledge/predicates/predicate.py | 406 ++++++++++++++++++ GEMstack/knowledge/vehicle/dynamics.py | 62 ++- GEMstack/knowledge/vehicle/geometry.py | 5 + GEMstack/launch/fixed_route.yaml | 22 +- GEMstack/launch/fixed_route_sim.yaml | 23 +- GEMstack/mathutils/control.py | 1 + GEMstack/mathutils/dubins.py | 2 +- GEMstack/mathutils/signal.py | 2 +- GEMstack/mathutils/units.py | 10 + GEMstack/onboard/execution/entrypoint.py | 88 +++- GEMstack/onboard/execution/execution.py | 197 +++++++-- GEMstack/onboard/execution/log_replay.py | 78 +--- GEMstack/onboard/interface/gem.py | 65 +-- GEMstack/onboard/interface/gem_hardware.py | 2 +- GEMstack/onboard/interface/gem_simulator.py | 94 ++-- .../perception/perception_normalization.py | 8 +- .../onboard/perception/state_estimation.py | 2 +- GEMstack/onboard/planning/pure_pursuit.py | 51 ++- GEMstack/onboard/planning/recovery.py | 1 + GEMstack/onboard/planning/route_planning.py | 2 + GEMstack/state/roadgraph.py | 14 +- GEMstack/state/trajectory.py | 6 +- GEMstack/state/vehicle.py | 3 +- GEMstack/utils/config.py | 2 +- GEMstack/utils/logging.py | 193 +++++++++ GEMstack/utils/serialization.py | 5 +- logs/.gitignore | 2 +- logs/README.md | 6 +- scenes/README.md | 1 + scenes/xyhead_demo.yaml | 9 + testing/test_dynamics.py | 72 ++++ 36 files changed, 1239 insertions(+), 247 deletions(-) create mode 100644 GEMstack/knowledge/predicates/agent_count.py create mode 100644 GEMstack/knowledge/predicates/predicate.py create mode 100644 GEMstack/mathutils/units.py create mode 100644 GEMstack/utils/logging.py create mode 100644 scenes/README.md create mode 100644 scenes/xyhead_demo.yaml create mode 100644 testing/test_dynamics.py diff --git a/GEMstack/knowledge/calibration/gem.yaml b/GEMstack/knowledge/calibration/gem.yaml index c6d1a9517..4a05e9d2a 100644 --- a/GEMstack/knowledge/calibration/gem.yaml +++ b/GEMstack/knowledge/calibration/gem.yaml @@ -1,4 +1,5 @@ reference: rear_axle_center -gnss_location: [1.1,0.0] # meters +gnss_location: [1.1,0.0,0.3] # meters, taken from https://github.com/hangcui1201/POLARIS_GEM_e2_Real/blob/main/vehicle_drivers/gem_gnss_control/scripts/gem_gnss_tracker_stanley_rtk.py. Note conflict with pure pursuit location? gnss_yaw: 0.0 # radians - +front_radar_location: [1.45,0,0.07] # meters, taken from https://github.com/hangcui1201/POLARIS_GEM_e2_Real/blob/main/platform_launch/launch/white_e2/platform.launch +top_lidar_location: [-0.12,0,1.6] # meters, taken from https://github.com/hangcui1201/POLARIS_GEM_e2_Real/blob/main/platform_launch/launch/white_e2/platform.launch diff --git a/GEMstack/knowledge/defaults/computation_graph.yaml b/GEMstack/knowledge/defaults/computation_graph.yaml index 01e3d987a..d7a606326 100644 --- a/GEMstack/knowledge/defaults/computation_graph.yaml +++ b/GEMstack/knowledge/defaults/computation_graph.yaml @@ -1,7 +1,11 @@ -#lists the components in order. -#Defines the permissable inputs and outputs for each component. -#The actual implementation of the components must use a subset of these inputs -#and must generate a superset of these outputs. +# This file defines all of the possible elements of the computation +# graph for the onboard behavior stack. +# +# `components` lists the components in order, and defines their permissable inputs and outputs. +# See AllState for attributes that can be listed as inputs or outputs. +# +# The actual implementation of each component must use a subset of the specified inputs +# and must generate a superset of the specified outputs. components: - state_estimation: outputs: vehicle diff --git a/GEMstack/knowledge/defaults/current.yaml b/GEMstack/knowledge/defaults/current.yaml index 6f813513c..d8b5fd0a4 100644 --- a/GEMstack/knowledge/defaults/current.yaml +++ b/GEMstack/knowledge/defaults/current.yaml @@ -1,3 +1,5 @@ +# ********* Main settings entry point for behavior stack *********** + # Configure settings for the vehicle / vehicle model vehicle: name: GEM @@ -25,6 +27,7 @@ control: lookahead_scale: 3.0 crosstrack_gain: 0.41 +#configure the simulator, if using simulator: dt: 0.01 real_time_multiplier: 1.0 # make the simulator run faster than real time by making this > 1 diff --git a/GEMstack/knowledge/defaults/gem_dynamics.yaml b/GEMstack/knowledge/defaults/gem_dynamics.yaml index ccb878508..4b494ed8d 100644 --- a/GEMstack/knowledge/defaults/gem_dynamics.yaml +++ b/GEMstack/knowledge/defaults/gem_dynamics.yaml @@ -11,5 +11,6 @@ max_accelerator_power: #Watts. Power at max accelerator pedal, by gear - 0.0 - 10000.0 max_accelerator_power_reverse: 10000.0 #Watts. Power (backwards) in reverse gear -internal_viscous_deceleration: 0.2 #1/s: scales the current velocity to get deceleration due to internal viscous friction -aerodynamic_drag_coefficient: 0.3 #unitless +internal_dry_deceleration: 0.01 #m/s^2: deceleration due to internal dry friction (non-speed dependent) +internal_viscous_deceleration: 0.05 #1/s: scales the current velocity to get deceleration due to internal viscous friction (speed dependent) +aerodynamic_drag_coefficient: 0.01 #units in s, scaled by velocity^2 to get deceleration due to aerodynamic drag diff --git a/GEMstack/knowledge/predicates/agent_count.py b/GEMstack/knowledge/predicates/agent_count.py new file mode 100644 index 000000000..01fac3783 --- /dev/null +++ b/GEMstack/knowledge/predicates/agent_count.py @@ -0,0 +1,27 @@ +from .predicate import PredicateBase +from ...state import AllState + +class AgentCountPredicate(PredicateBase): + """Counts the number of agents in the scene. + + Args: + agent_type: If not None, only counts agents of this type. + """ + def __init__(self,agent_type = None): + self.agent_type = agent_type + + @classmethod + def name(cls): + return "AgentCount" + + def args(self): + return [self.agent_type] + + def value_type(self): + return int + + def value(self, state : AllState): + if self.agent_type is None: + return len(state.agents) + else: + return len([a for a in state.agents.values() if a.type == self.agent_type]) diff --git a/GEMstack/knowledge/predicates/predicate.py b/GEMstack/knowledge/predicates/predicate.py new file mode 100644 index 000000000..b153ecfa2 --- /dev/null +++ b/GEMstack/knowledge/predicates/predicate.py @@ -0,0 +1,406 @@ +"""Defines an abstract base class for predicates and utility functions for +working with predicates. + +The PredicateBase class is the base class for all predicates and can be +composed, serialized, and deserialized. You can compose predicates using +the and_, all_, or_, any_, and not_ functions. You can also compare numeric +predicates to one another using ==, !=, <, <=, >, and >=. + +Predicates can be placed in this folder, and they need a unique name. By +default, each predicate is named after its class name. You can override +this by implementing the name() method. + +To serialize and deserialize, use the `serialize_predicate` and +`deserialize_predciate` functions. +""" + +from __future__ import annotations +from types import UnionType +from ...state import AllState +from typing import Callable,List,Dict,Any + + +class PredicateBase: + """A predicate is a stateless function that returns a value + as a function of state. + + It may take a constructor with one or more arguments, but each + of these arguments must be JSON-serializable, e.g., a str, int, + float, list, or dict. + + It is important to implement name() as a unique and persistent + name, because it will be used to identify the predicate in logic + and planning. + """ + @classmethod + def name(cls) -> str: + return cls.__name__ + + def args(self) -> list: + """Returns a list of arguments that were passed to the constructor. + Default empty list.""" + return [] + + def value_type(self): + """Returns the type of the value returned by the predicate. + Default bool.""" + return bool + + def value(self, state: AllState) -> Any: + return NotImplementedError() + + def __eq__(self, rhs) -> PredicateBase: + return EqPredicate(self,rhs) + + def __neq__(self, rhs) -> PredicateBase: + return not_(EqPredicate(self,rhs)) + + def __gt__(self, rhs) -> PredicateBase: + return not_(GTPredicate(self,rhs)) + + def __ge__(self, rhs) -> PredicateBase: + return not_(GEPredicate(self,rhs)) + + def __lt__(self, rhs) -> PredicateBase: + return not_(LTPredicate(self,rhs)) + + def __le__(self, rhs) -> PredicateBase: + return not_(LEPredicate(self,rhs)) + + +class UpdatingPredicateBase(PredicateBase): + """A predicate that contains internal state ONLY to help make the + calculation of the predicate more efficient. The internal state + is updated by the update() method. + + Note that the value returned by value() MUST not be different + depending on the internal state. For example, you could implement + a cache. But you could not implement a predicate that returns + a different value depending on the number of times it has been + called. + """ + def __init__(self): + self._internal_value = None + + def update(self, state: AllState, internal_value : Any) -> Any: + return NotImplementedError() + + def value(self, state: AllState): + self._internal_value = self.update(state, self._internal_value) + return self._internal_value + + +class LambdaPredicate(PredicateBase): + """A predicate that calls a user-defined function. Note that + because we can't serialize functions, this predicate cannot + be serialized.""" + def __init__(self, f : Callable[[AllState],Any]): + self.f = f + + @classmethod + def name(cls) -> str: + return 'lambda' + + def args(self) -> list: + return [self.f] + + def value(self, state: AllState) -> Any: + return self.f(state) + + +class AndPredicate(PredicateBase): + """A predicate that is the logical AND of a list of predicates.""" + def __init__(self, *predicates : PredicateBase): + self.predicates = predicates + + @classmethod + def name(cls) -> str: + return 'and' + + def args(self) -> list: + return self.predicates + + def value_type(self): + return bool + + def value(self, state: AllState) -> bool: + return all(p.value(state) for p in self.predicates) + + +class OrPredicate(PredicateBase): + """A predicate that is the logical OR of a list of predicates.""" + def __init__(self, *predicates : PredicateBase): + self.predicates = predicates + + @classmethod + def name(cls) -> str: + return 'or' + + def args(self) -> list: + return self.predicates + + def value_type(self): + return bool + + def value(self, state: AllState) -> bool: + return any(p.value(state) for p in self.predicates) + + +class NotPredicate(PredicateBase): + """A predicate that is the logical NOT of another predicate.""" + def __init__(self, predicate : PredicateBase): + self.predicate = predicate + + @classmethod + def name(cls) -> str: + return 'not' + + def args(self) -> list: + return [self.predicate] + + def value_type(self): + return bool + + def value(self, state: AllState) -> bool: + return not self.predicate.value(state) + + +class EqPredicate(PredicateBase): + """A predicate that is the result of lhs == rhs.""" + def __init__(self, lhs : Any, rhs : Any): + self.lhs = lhs + self.rhs = rhs + + @classmethod + def name(cls) -> str: + return 'eq' + + def args(self) -> list: + return [self.lhs,self.rhs] + + def value_type(self): + return bool + + def value(self, state: AllState) -> bool: + if isinstance(self.lhs,PredicateBase): + lhs = self.lhs.value(state) + else: + lhs = self.lhs + if isinstance(self.rhs,PredicateBase): + rhs = self.rhs.value(state) + else: + rhs = self.rhs + return lhs == rhs + + +class GTPredicate(PredicateBase): + """A predicate that is the result of lhs > rhs.""" + def __init__(self, lhs : Any, rhs : Any): + self.lhs = lhs + self.rhs = rhs + + @classmethod + def name(cls) -> str: + return '>' + + def args(self) -> list: + return [self.lhs,self.rhs] + + def value_type(self): + return bool + + def value(self, state: AllState) -> bool: + if isinstance(self.lhs,PredicateBase): + lhs = self.lhs.value(state) + else: + lhs = self.lhs + if isinstance(self.rhs,PredicateBase): + rhs = self.rhs.value(state) + else: + rhs = self.rhs + return lhs > rhs + + +class GEPredicate(PredicateBase): + """A predicate that is the result of lhs >= rhs.""" + def __init__(self, lhs : Any, rhs : Any): + self.lhs = lhs + self.rhs = rhs + + @classmethod + def name(cls) -> str: + return '>=' + + def args(self) -> list: + return [self.lhs,self.rhs] + + def value_type(self): + return bool + + def value(self, state: AllState) -> bool: + if isinstance(self.lhs,PredicateBase): + lhs = self.lhs.value(state) + else: + lhs = self.lhs + if isinstance(self.rhs,PredicateBase): + rhs = self.rhs.value(state) + else: + rhs = self.rhs + return lhs >= rhs + + + +class LTPredicate(PredicateBase): + """A predicate that is the result of lhs < rhs.""" + def __init__(self, lhs : Any, rhs : Any): + self.lhs = lhs + self.rhs = rhs + + @classmethod + def name(cls) -> str: + return '<' + + def args(self) -> list: + return [self.lhs,self.rhs] + + def value_type(self): + return bool + + def value(self, state: AllState) -> bool: + if isinstance(self.lhs,PredicateBase): + lhs = self.lhs.value(state) + else: + lhs = self.lhs + if isinstance(self.rhs,PredicateBase): + rhs = self.rhs.value(state) + else: + rhs = self.rhs + return lhs < rhs + + +class LEPredicate(PredicateBase): + """A predicate that is the result of lhs <= rhs.""" + def __init__(self, lhs : Any, rhs : Any): + self.lhs = lhs + self.rhs = rhs + + @classmethod + def name(cls) -> str: + return '<=' + + def args(self) -> list: + return [self.lhs,self.rhs] + + def value_type(self): + return bool + + def value(self, state: AllState) -> bool: + if isinstance(self.lhs,PredicateBase): + lhs = self.lhs.value(state) + else: + lhs = self.lhs + if isinstance(self.rhs,PredicateBase): + rhs = self.rhs.value(state) + else: + rhs = self.rhs + return lhs <= rhs + + +def and_(a : PredicateBase, b : PredicateBase) -> PredicateBase: + """Returns a predicate that is the logical AND of two predicates.""" + return AndPredicate(a,b) + + +def all_(preds : List[PredicateBase]) -> PredicateBase: + """Returns a predicate that is the logical AND of one or more predicates.""" + assert len(preds) > 0 + return AndPredicate(*preds) + + +def or_(a : PredicateBase, b : PredicateBase) -> PredicateBase: + """Returns a predicate that is the logical OR of two predicates.""" + return OrPredicate(a,b) + + +def any_(preds : List[PredicateBase]) -> PredicateBase: + """Returns a predicate that is the logical OR of one or more predicates.""" + assert len(preds) > 0 + return OrPredicate(*preds) + + +def not_(a : PredicateBase) -> PredicateBase: + """Returns a predicate that is the logical NOT of a predicate.""" + return NotPredicate(a) + + + +def all_predicate_types() -> Dict[str,Any]: + """Returns a dict of all predicate types in this folder, indexed by name""" + import os + registry = dict() + folder,_ = os.path.split(__file__) + for f in os.listdir(folder): + if f.endswith('.py') and f not in ['__init__.py']: + module = __import__('GEMstack.knowledge.predicates.'+f[:-3]) + for m in vars(module): + if isinstance(m,PredicateBase) and m is not PredicateBase and m is not UpdatingPredicateBase: + name = m.name() + registry[name] = m + return registry + + +def serialize_predicate(predicate : PredicateBase) -> Dict[str,Any]: + """Serializes a predicate to a dict""" + args = predicate.args() + for i,a in enumerate(args): + if isinstance(a,PredicateBase): + args[i] = serialize_predicate(a) + return {'type':predicate.name(),'args':args} + + +def deserialize_predicate(d : Dict[str,Any], all_preds = None) -> PredicateBase: + """Instantiates a predicate from a dict""" + if all_preds is None: + all_preds = all_predicate_types() + if 'type' not in d: + return ValueError("Predicate dict must have 'type' key") + if d['type'] not in all_preds: + print("Known predicates:",list(all_preds.keys())) + return ValueError("Unknown predicate type "+d['type']) + args = d['args'] + #detect compound predicates + for i,a in enumerate(args): + if isinstance(a,dict) and 'type' in a: + args[i] = deserialize_predicate(a,all_preds) + return all_preds[d['type']](*args) + + +def deserialize_predicates(l : List[Dict[str,Any]]) -> List[PredicateBase]: + """Instantiates a list of predicates from a list of dicts. + + Slightly faster than deserializing each predicate individually. + """ + all_preds = all_predicate_types() + return [deserialize_predicate(d,all_preds) for d in l] + + +def pprint(predicate: PredicateBase) -> str: + """Pretty prints a predicate.""" + if isinstance(predicate,AndPredicate): + return 'and('+', '.join(pprint(p) for p in predicate.predicates)+')' + elif isinstance(predicate,OrPredicate): + return 'or('+', '.join(pprint(p) for p in predicate.predicates)+')' + elif isinstance(predicate,NotPredicate): + return 'not('+pprint(predicate.predicate)+')' + elif isinstance(predicate,EqPredicate): + return pprint(predicate.lhs)+' == '+pprint(predicate.rhs) + elif isinstance(predicate,GTPredicate): + return pprint(predicate.lhs)+' > '+pprint(predicate.rhs) + elif isinstance(predicate,GEPredicate): + return pprint(predicate.lhs)+' >= '+pprint(predicate.rhs) + elif isinstance(predicate,LTPredicate): + return pprint(predicate.lhs)+' < '+pprint(predicate.rhs) + elif isinstance(predicate,LEPredicate): + return pprint(predicate.lhs)+' <= '+pprint(predicate.rhs) + else: + return predicate.name()+'('+', '.join(pprint(a) for a in predicate.args())+')' \ No newline at end of file diff --git a/GEMstack/knowledge/vehicle/dynamics.py b/GEMstack/knowledge/vehicle/dynamics.py index 2954a1612..4cf4f9b80 100644 --- a/GEMstack/knowledge/vehicle/dynamics.py +++ b/GEMstack/knowledge/vehicle/dynamics.py @@ -1,7 +1,17 @@ +"""Functions to model the vehicle's steering / drivetrain dynamics. + +TODO: calibrate drivetrain dynamics. Power curves are not yet implemented. + +TODO: add functions defining steering friction limits at different speeds and on different surfaces. +""" + from ...utils import settings from typing import Tuple import math +def sign(x): + return 1 if x > 0 else -1 if x < 0 else 0 + def acceleration_to_pedal_positions(acceleration : float, velocity : float, pitch : float, gear : int) -> Tuple[float,float,int]: """Converts acceleration in m/s^2 to pedal positions in % of pedal travel. @@ -10,15 +20,21 @@ def acceleration_to_pedal_positions(acceleration : float, velocity : float, pitc brake_max = settings.get('vehicle.dynamics.max_brake_deceleration') reverse_accel_max = settings.get('vehicle.dynamics.max_accelerator_acceleration_reverse') accel_max = settings.get('vehicle.dynamics.max_accelerator_acceleration') + assert isinstance(brake_max,(int,float)) + assert isinstance(reverse_accel_max,(int,float)) + assert isinstance(accel_max,list) + assert isinstance(acceleration,(int,float)) #compute required acceleration - vsign = (velocity/abs(velocity)) + vsign = sign(velocity) gravity = settings.get('vehicle.dynamics.gravity') + internal_dry_deceleration = settings.get('vehicle.dynamics.internal_dry_deceleration') internal_viscous_deceleration = settings.get('vehicle.dynamics.internal_viscous_deceleration') aerodynamic_drag_coefficient = settings.get('vehicle.dynamics.aerodynamic_drag_coefficient') - drag = -(aerodynamic_drag_coefficient * velocity**2) * vsign - internal_viscous_deceleration * velocity + drag = -(aerodynamic_drag_coefficient * velocity**2) * vsign - internal_dry_deceleration * vsign - internal_viscous_deceleration * velocity sin_pitch = math.sin(pitch) - acceleration += drag + gravity * sin_pitch + acceleration -= drag + gravity * sin_pitch + #this is the net acceleration that should be achieved by accelerator / brake pedal #TODO: power curves to select optimal gear if velocity * acceleration < 0: @@ -52,6 +68,7 @@ def acceleration_to_pedal_positions(acceleration : float, velocity : float, pitc #stay in neutral gear return (0,1,0) + def pedal_positions_to_acceleration(accelerator_pedal_position : float, brake_pedal_position : float, velocity : float, pitch : float, gear : int) -> float: """Converts pedal positions in % of pedal travel to acceleration in m/s^2. @@ -64,19 +81,44 @@ def pedal_positions_to_acceleration(accelerator_pedal_position : float, brake_pe brake_max = settings.get('vehicle.dynamics.max_brake_deceleration') reverse_accel_max = settings.get('vehicle.dynamics.max_accelerator_acceleration_reverse') accel_max = settings.get('vehicle.dynamics.max_accelerator_acceleration') - brake_accel = brake_max * brake_pedal_position + assert isinstance(brake_max,(int,float)) + assert isinstance(reverse_accel_max,(int,float)) + assert isinstance(accel_max,list) + assert isinstance(accelerator_pedal_position,(int,float)) + assert isinstance(brake_pedal_position,(int,float)) + vsign = sign(velocity) + brake_accel = -vsign * brake_max * brake_pedal_position if gear < 0: - accel = reverse_accel_max * accelerator_pedal_position + accel = - reverse_accel_max * accelerator_pedal_position else: accel = accel_max[gear] * accelerator_pedal_position - vsign = (velocity/abs(velocity)) gravity = settings.get('vehicle.dynamics.gravity') + internal_dry_deceleration = settings.get('vehicle.dynamics.internal_dry_deceleration') internal_viscous_deceleration = settings.get('vehicle.dynamics.internal_viscous_deceleration') aerodynamic_drag_coefficient = settings.get('vehicle.dynamics.aerodynamic_drag_coefficient') - drag = -(aerodynamic_drag_coefficient * velocity**2) * vsign - internal_viscous_deceleration * velocity + drag = -(aerodynamic_drag_coefficient * velocity**2) * vsign - internal_dry_deceleration * vsign - internal_viscous_deceleration * velocity sin_pitch = math.sin(pitch) if velocity == 0: - #does gravity overcome static friction from braking? - if abs(accel - gravity * sin_pitch) < brake_accel: + #brake accel and drag will be 0 based on velocity sign, so instead, + #brake and dry friction may will counteract prevailing acceleration + drag = -sign(accel - gravity*sin_pitch)*internal_dry_deceleration + brake_accel = -sign(accel - gravity*sin_pitch) * brake_max * brake_pedal_position + + #does gravity overcome static friction from braking + dry friction? + if abs(accel - gravity * sin_pitch) < abs(brake_accel + drag): + return 0 + #does gravity push against the gear setting? + if accel - gravity * sin_pitch < 0 and gear > 0: + return 0 + if accel - gravity * sin_pitch > 0 and gear < 0: return 0 - return accel - brake_accel - drag - gravity * sin_pitch + return accel + brake_accel + drag - gravity * sin_pitch + + +def acceleration_limits(velocity : float, pitch : float, gear : int) -> Tuple[float,float]: + """Returns the min and max achievable acceleration at the given velocity, pitch, and gear.""" + vals = [] + vals.append(pedal_positions_to_acceleration(0.0,0.0,velocity,pitch,gear)) + vals.append(pedal_positions_to_acceleration(1.0,0.0,velocity,pitch,gear)) + vals.append(pedal_positions_to_acceleration(0.0,1.0,velocity,pitch,gear)) + return min(vals),max(vals) diff --git a/GEMstack/knowledge/vehicle/geometry.py b/GEMstack/knowledge/vehicle/geometry.py index 1c9bb6754..44738928f 100644 --- a/GEMstack/knowledge/vehicle/geometry.py +++ b/GEMstack/knowledge/vehicle/geometry.py @@ -1,3 +1,8 @@ +"""Functions to model the vehicle's steering geometry. + +TODO: double-check steer2front and front2steer coefficients. +""" + from ...utils import settings import math diff --git a/GEMstack/launch/fixed_route.yaml b/GEMstack/launch/fixed_route.yaml index 56e35d17d..73efb4dfe 100644 --- a/GEMstack/launch/fixed_route.yaml +++ b/GEMstack/launch/fixed_route.yaml @@ -13,13 +13,31 @@ drive: planning: route_planning: type: StaticRoutePlanner - args: [!relative_path '../routes/xyhead_demo_pp.csv'] + args: [!relative_path '../knowledge/routes/xyhead_demo_pp.csv'] motion_planning: RouteToTrajectoryPlanner trajectory_tracking: pure_pursuit.PurePursuitTrajectoryTracker log: + # Specify the top-level folder to save the log files. Default is 'logs' + #folder : 'logs' + # If prefix is specified, then the log folder will be named with the prefix followed by the date and time. Default no prefix + #prefix : 'fixed_route_' + # If suffix is specified, then logs will output to folder/prefix+suffix. Default uses date and time as the suffix + #suffix : 'test3' + # Specify which ros topics to record to vehicle.bag. Default records nothing ros_topics : [] + # Specify options to pass to rosbag record. Default is no options. + #rosbag_options : '--split --size=1024' + # If True, then record all readings / commands of the vehicle interface. Default False + vehicle_interface : True + # Specify which components to record to behavior.json. Default records nothing components : ['state_estimation','trajectory_tracking'] -replay: #add items here to set certain topics / inputs to be replayed from logs + # Specify which components of state to record to state.json. Default records nothing + #state: ['all'] + # Specify the rate in Hz at which to record state to state.json. Default records at the pipeline's rate + #state_rate: 10 +replay: # Add items here to set certain topics / inputs to be replayed from logs + # Specify which log folder to replay from + log: ros_topics : [] components : [] diff --git a/GEMstack/launch/fixed_route_sim.yaml b/GEMstack/launch/fixed_route_sim.yaml index e84278667..5a0e052ab 100644 --- a/GEMstack/launch/fixed_route_sim.yaml +++ b/GEMstack/launch/fixed_route_sim.yaml @@ -2,7 +2,7 @@ mode: simulation vehicle_interface: type: gem_simulator.GEMDoubleIntegratorSimulationInterface args: - scene: !relative_path '../scenes/xyhead_demo.yaml' + scene: !relative_path '../../scenes/xyhead_demo.yaml' mission_execution: StandardExecutor # "recovery" pipeline: Recovery behavior after a component failure @@ -18,14 +18,31 @@ drive: planning: route_planning: type: StaticRoutePlanner - args: [!relative_path '../routes/xyhead_demo_pp.csv'] + args: [!relative_path '../knowledge/routes/xyhead_demo_pp.csv'] motion_planning: RouteToTrajectoryPlanner trajectory_tracking: pure_pursuit.PurePursuitTrajectoryTracker log: + # Specify the top-level folder to save the log files. Default is 'logs' + #folder : 'logs' + # If prefix is specified, then the log folder will be named with the prefix followed by the date and time. Default no prefix + #prefix : 'fixed_route_' + # If suffix is specified, then logs will output to folder/prefix+suffix. Default uses date and time as the suffix + #suffix : 'test3' + # Specify which ros topics to record to vehicle.bag. Default records nothing ros_topics : [] + # Specify options to pass to rosbag record. Default is no options. + #rosbag_options : '--split --size=1024' + # If True, then record all readings / commands of the vehicle interface. Default False + vehicle_interface : True + # Specify which components to record to behavior.json. Default records nothing components : ['state_estimation','trajectory_tracking'] -replay: #add items here to set certain topics / inputs to be replayed from logs + # Specify which components of state to record to state.json. Default records nothing + #state: ['all'] + # Specify the rate in Hz at which to record state to state.json. Default records at the pipeline's rate + #state_rate: 10 +replay: # Add items here to set certain topics / inputs to be replayed from logs + # Specify which log folder to replay from log: ros_topics : [] components : [] diff --git a/GEMstack/mathutils/control.py b/GEMstack/mathutils/control.py index 8123d90ca..7d161f12c 100644 --- a/GEMstack/mathutils/control.py +++ b/GEMstack/mathutils/control.py @@ -75,4 +75,5 @@ def advance(self, self.last_t = t self.derror = de + print(feedforward_term,self.kp,e,self.ki,self.iterm,self.kd,de) return feedforward_term + self.kp * e + self.ki * self.iterm + self.kd * de diff --git a/GEMstack/mathutils/dubins.py b/GEMstack/mathutils/dubins.py index 0d60898ae..cdb4655ab 100644 --- a/GEMstack/mathutils/dubins.py +++ b/GEMstack/mathutils/dubins.py @@ -113,5 +113,5 @@ def derivative(self,x,u): assert len(u) == 2 v,phi = x[3:5] turn_rate = np.tan(phi)/self.wheelBase - return np.hstack(self.dubins(x[:3],[v,turn_rate]),[u[0],u[1]]) + return np.hstack((self.dubins.derivative(x[:3],[v,turn_rate]),[u[0],u[1]])) \ No newline at end of file diff --git a/GEMstack/mathutils/signal.py b/GEMstack/mathutils/signal.py index aa40cceac..def7f95cd 100644 --- a/GEMstack/mathutils/signal.py +++ b/GEMstack/mathutils/signal.py @@ -15,7 +15,7 @@ def __init__(self, cutoff : float, sampling_frequency : float, order : int): def __call__(self, data: float): filtered, self.z = signal.lfilter(self.b, self.a, [data], zi=self.z) - return filtered + return filtered[0] def reset(self) -> None: self.z = signal.lfilter_zi(self.b, self.a) diff --git a/GEMstack/mathutils/units.py b/GEMstack/mathutils/units.py new file mode 100644 index 000000000..7c58595e4 --- /dev/null +++ b/GEMstack/mathutils/units.py @@ -0,0 +1,10 @@ +M_TO_FT = 3.28084 +FT_TO_M = 1.0 / M_TO_FT +MPS_TO_MPH = 2.23694 +MPH_TO_MPS = 1.0 / MPS_TO_MPH +MPS_TO_KPH = 3.6 +KPH_TO_MPS = 1.0 / MPS_TO_KPH +KG_TO_LBS = 2.20462 +LBS_TO_KG = 1.0 / KG_TO_LBS +DEG_TO_RAD = 0.0174533 +RAD_TO_DEG = 1.0 / DEG_TO_RAD diff --git a/GEMstack/onboard/execution/entrypoint.py b/GEMstack/onboard/execution/entrypoint.py index c91f6ee30..debc36189 100644 --- a/GEMstack/onboard/execution/entrypoint.py +++ b/GEMstack/onboard/execution/entrypoint.py @@ -1,6 +1,6 @@ from ...utils import settings,config from ..component import Component -from .execution import ExecutorBase +from .execution import EXECUTION_PREFIX,ExecutorBase from .log_replay import LogReplay import importlib from typing import Dict,List,Optional @@ -18,6 +18,7 @@ def make_class(config_info, component_module, parent_module=None, extra_args = N if extra_args is None: extra_args = {} args = () + kwargs = {} if isinstance(config_info,str): if '.' in config_info: component_module,class_name = config_info.rsplit('.',1) @@ -31,16 +32,24 @@ def make_class(config_info, component_module, parent_module=None, extra_args = N component_module = config_info['module'] if 'args' in config_info: args = config_info['args'] + if isinstance(args,dict): + kwargs = args + args = () if parent_module is not None: - print("Importing",component_module,"from",parent_module,"to get",class_name) + print(EXECUTION_PREFIX,"Importing",component_module,"from",parent_module,"to get",class_name) else: - print("Importing",component_module,"to get",class_name) + print(EXECUTION_PREFIX,"Importing",component_module,"to get",class_name) module = import_module_dynamic(component_module,parent_module) klass = getattr(module,class_name) try: - return klass(*args,**extra_args) + return klass(*args,**kwargs,**extra_args) except TypeError: - return klass(*args) + try: + return klass(*args,**kwargs) + except TypeError: + print(EXECUTION_PREFIX,"Unable to launch module",component_module,"with class",class_name,"and args",args,"kwargs",kwargs) + raise + def main(): @@ -53,7 +62,7 @@ def main(): #create top-level components vehicle_interface = make_class(vehicle_interface_settings,'default','GEMstack.onboard.interface') - mission_executor = make_class(mission_executor_settings,'execution','GEMstack.onboard.execution') + mission_executor = make_class(mission_executor_settings,'execution','GEMstack.onboard.execution',{'vehicle_interface':vehicle_interface}) if not isinstance(mission_executor,ExecutorBase): raise ValueError("Mission executor must be an Executor") @@ -67,7 +76,7 @@ def main(): if isinstance(v,dict) and ('perception' in v or 'planning' in v or 'other' in v): #possible pipeline if k not in pipeline_settings: - print("Adding non-standard pipeline",k) + print(EXECUTION_PREFIX,"Adding non-standard pipeline",k) pipeline_settings[k] = v existing_components = {} @@ -101,15 +110,13 @@ def main(): other_components[k] = make_class(v,k,'GEMstack.onboard.execution', {'vehicle_interface':vehicle_interface}) existing_components[str((k,v))] = other_components[k] - #TODO: add logging and ROS topic replay - if 'replay' in runconfig: - logfolder = runconfig['replay'].get('log',None) + #configure components that would be replayed from log rather than run + if replay_settings: + logfolder = replay_settings.get('log',None) if logfolder is not None: logmeta = config.load_config_recursive(os.path.join(logfolder,'meta.yaml')) - replay_topics = runconfig['replay'].get('ros_topics',[]) - - #TODO: launch a roslog replay of the topics in replay_topics, disable in the vehicle interface - replay_components = runconfig['replay'].get('components',[]) + + replay_components = replay_settings.get('components',[]) for c in replay_components: found = False for component in (perception_components,planning_components,other_components): @@ -118,7 +125,7 @@ def main(): for o in outputs: if o not in logmeta['state_log_items']: raise ValueError("Replay component",c,"has output",o,"which is not in log") - print("Replaying component",c,"from log",logfolder,"with outputs",outputs) + print(EXECUTION_PREFIX,"Replaying component",c,"from log",logfolder,"with outputs",outputs) component[c] = LogReplay(outputs, os.path.join(logfolder,'state_log.json'), rate=component[c].rate()) @@ -129,5 +136,54 @@ def main(): mission_executor.add_pipeline(name,perception_components,planning_components,other_components) - mission_executor.run() + #TODO: ROS topic replay + if replay_settings: + logfolder = replay_settings.get('log',None) + if logfolder is not None: + logmeta = config.load_config_recursive(os.path.join(logfolder,'meta.yaml')) + replay_topics = replay_settings.get('ros_topics',[]) + + #TODO: launch a roslog replay of the topics in replay_topics, disable in the vehicle interface + + #configure logging + if log_settings: + topfolder = log_settings.get('log','logs') + prefix = log_settings.get('prefix','') + from datetime import datetime + default_suffix = datetime.now().strftime('%Y-%m-%d_%H-%M-%S') + suffix = log_settings.get('suffix',default_suffix) + logfolder = os.path.join(topfolder,prefix+suffix) + print(EXECUTION_PREFIX,"Logging to",logfolder) + os.makedirs(logfolder,exist_ok=True) + + #save settings.yaml + config.save_config(os.path.join(logfolder,'settings.yaml'),settings.settings()) + #configure logging for components + mission_executor.set_log_folder(logfolder) + #configure ROS logging + log_topics = replay_settings.get('ros_topics',[]) + rosbag_options = log_settings.get('rosbag_options','') + if log_topics: + command = 'rosbag record --output-name={} {} {}'.format(os.path.join(logfolder,'vehicle.bag'),rosbag_options,' '.join(log_topics)) + print(EXECUTION_PREFIX,"Recording ROS topics with command",command) + os.system(command) + #determine whether to log vehicle interface + log_vehicle_interface = log_settings.get('vehicle_interface',False) + mission_executor.log_vehicle_interface(log_vehicle_interface) + #determine whether to log components + log_components = log_settings.get('components',[]) + mission_executor.log_components(log_components) + #determine whether to log state + log_state_attributes = log_settings.get('state',[]) + log_state_rate = log_settings.get('state_rate',None) + if log_state_attributes: + mission_executor.log_state(log_state_attributes,log_state_rate) + + vehicle_interface.start() + try: + mission_executor.run() + except Exception as e: + raise + finally: + vehicle_interface.stop() diff --git a/GEMstack/onboard/execution/execution.py b/GEMstack/onboard/execution/execution.py index eb9753b47..0baa67440 100644 --- a/GEMstack/onboard/execution/execution.py +++ b/GEMstack/onboard/execution/execution.py @@ -3,8 +3,14 @@ from ..component import Component from ...utils.loops import TimedLooper from ...utils import settings +from ...utils.serialization import serialize +from ...utils.logging import Logfile +import json import time -from typing import Dict,Tuple,List,Optional +import os +from typing import Dict,Tuple,Set,List,Optional + +EXECUTION_PREFIX = "Execution:" # Define the computation graph @@ -61,7 +67,7 @@ def validate_components(components : Dict[str,Component], provided : List = None else: assert provided_all or i in provided, "Component {} input {} is not provided by previous components".format(k,i) if i not in state: - print("Component {} input {} does not exist in AllState object".format(k,i)) + print(EXECUTION_PREFIX,"Component {} input {} does not exist in AllState object".format(k,i)) if possible_inputs != ['all']: assert i in possible_inputs, "Component {} is not supposed to receive input {}".format(k,i) outputs = c.state_outputs() @@ -74,7 +80,7 @@ def validate_components(components : Dict[str,Component], provided : List = None if 'all' != o: provided.add(o) if o not in state: - print("Component {} output {} does not exist in AllState object".format(k,o)) + print(EXECUTION_PREFIX,"Component {} output {} does not exist in AllState object".format(k,o)) else: provided_all = True for k,c in components.items(): @@ -111,11 +117,12 @@ def update(self, t : float, state : AllState): else: self.next_update_time += self.dt if self.next_update_time < t: - print("Component {} is running behind, overran dt by {} seconds".format(self.c,self.dt,t-self.next_update_time)) + print(EXECUTION_PREFIX,"Component {} is running behind, overran dt by {} seconds".format(self.c,self.dt,t-self.next_update_time)) self.num_overruns += 1 self.overrun_amount += t - self.next_update_time self.next_update_time = t + self.dt return True + #print("Component",self.c,"not updating at time",t,", next update time is",self.next_update_time) return False def _do_update(self, *args): @@ -130,38 +137,40 @@ def update_now(self, t:float, state : AllState): if self.inputs == ['all']: args = (state,) else: - args = tuple([state[i] for i in self.inputs]) + args = tuple([getattr(state,i) for i in self.inputs]) + print(EXECUTION_PREFIX,"Updating",self.c.__class__.__name__) res = self._do_update(*args) - #write result + #write result to state if res is not None: if len(self.output) > 1: assert len(res) == len(self.output), "Component {} output {} does not match expected length {}".format(self.c,self.output,len(self.output)) for (k,v) in zip(self.output,res): - state[k] = v - state[k+'_update_time'] = t + setattr(state,k, v) + setattr(state,k+'_update_time', t) else: - state[self.output[0]] = res - state[self.output[0]+'_update_time'] = t + setattr(state,self.output[0], res) + setattr(state,self.output[0]+'_update_time', t) -def update_components(components : Dict[str,ComponentExecutor], state : AllState, now = False): - """If now = True, all components are run regardless of polling state.""" - t = state.t - for k in COMPONENT_ORDER: - if k in components: - if now: - components[k].update_now(t,state) - else: - components[k].update(t,state) class ExecutorBase: """Base class for a mission executor. Handles the computation graph setup. Subclasses should implement begin(), update(), done(), and end() methods.""" - def __init__(self): + def __init__(self, vehicle_interface): + self.vehicle_interface = vehicle_interface self.pipelines = dict() # type: Dict[str,Tuple[Dict[str,ComponentExecutor],Dict[str,ComponentExecutor],Dict[str,ComponentExecutor]]] self.current_pipeline = 'drive' # type: str self.state = None # type: Optional[AllState] + self.log_folder = None # type: Optional[str] + self.logged_components = set() # type: Set[str] + self.logged_state_attributes = [] # type: List[str] + self.log_state_rate = None # type: Optional[float] + self.state_log = None + self.behavior_log = None + self.vehicle_log_t_last = None + self.run_metadata = dict() # type: dict + self.last_loop_time = time.time() def begin(self): """Override me to do any initialization""" @@ -189,12 +198,52 @@ def add_pipeline(self,name : str, perception : Dict[str,Component], planning : D self.pipelines[name] = (perception_component_state,planning_component_state,other_component_state) #TODO: set any custom do_update functions here + def set_log_folder(self,folder): + self.log_folder = folder + #save meta.yaml + import subprocess + self.run_metadata['start_time'] = time.time() + git_commit_id = subprocess.check_output(['git','rev-parse','HEAD']) + self.run_metadata['git_commit_id'] = git_commit_id.decode('utf-8').strip() + git_branch = subprocess.check_output(['git','rev-parse','--abbrev-ref','HEAD']) + self.run_metadata['git_branch'] = git_branch.decode('utf-8').strip() + self.dump_log_metadata() + + def log_vehicle_interface(self,enabled=True): + if enabled: + if 'vehicle_interface' not in self.logged_components: + self.logged_components.add('vehicle_interface') + else: + if 'vehicle_interface' in self.logged_components: + self.logged_components.remove('vehicle_interface')\ + + def log_components(self,components : List[str]): + if 'vehicle_interface' in self.logged_components: + self.logged_components = set(components) | set(['vehicle_interface']) + else: + self.logged_components = set(components) + if components: + if self.behavior_log is None: + self.behavior_log = Logfile(os.path.join(self.log_folder,'behavior.json'),delta_format=True,mode='w') + + def log_state(self,state_attributes : List[str], rate : Optional[float]=None): + self.logged_state_attributes = state_attributes[:] + self.log_state_rate = rate + if state_attributes: + if self.state_log is None: + self.state_log = Logfile(os.path.join(self.log_folder,'state.json'),delta_format=False,mode='w') + + def dump_log_metadata(self): + import os + from ...utils import config + config.save_config(os.path.join(self.log_folder,'meta.yaml'),self.run_metadata) + def run(self): if self.current_pipeline not in self.pipelines: - print("Pipeline {} not found".format(self.current_pipeline)) + print(EXECUTION_PREFIX,"Pipeline {} not found".format(self.current_pipeline)) return if 'recovery' not in self.pipelines: - print("'recovery' pipeline not found") + print(EXECUTION_PREFIX,"'recovery' pipeline not found") return for (name,(perception_components,planning_components,other_components)) in self.pipelines.items(): @@ -214,40 +263,51 @@ def run(self): self.validate_sensors() validated = True except KeyboardInterrupt: - print("Could not validate sensors, stopping components and exiting") + print(EXECUTION_PREFIX,"Could not validate sensors, stopping components and exiting") + if time.time() - self.last_loop_time > 0.5: + print(EXECUTION_PREFIX,"A component may have hung. Traceback:") + import traceback + traceback.print_exc() if validated: self.begin() while validated: try: - print("Executing pipeline {}".format(self.current_pipeline)) + print(EXECUTION_PREFIX,"Executing pipeline {}".format(self.current_pipeline)) next = self.run_until_switch() if next is None: #done break if next not in self.pipelines: - print("Pipeline {} not found, switching to recovery".format(next)) + print(EXECUTION_PREFIX,"Pipeline {} not found, switching to recovery".format(next)) next = 'recovery' if self.current_pipeline == 'recovery' and next == 'recovery': + print(EXECUTION_PREFIX) print("************************************************") print(" Recovery pipeline is not working, exiting! ") print("************************************************") break self.current_pipeline = next if not self.validate_sensors(1): - print("Sensors in desired pipeline {} are not working, switching to recovery".format(self.current_pipeline)) + print(EXECUTION_PREFIX,"Sensors in desired pipeline {} are not working, switching to recovery".format(self.current_pipeline)) self.current_pipeline = 'recovery' except KeyboardInterrupt: if self.current_pipeline == 'recovery': + print(EXECUTION_PREFIX) print("************************************************") print(" Ctrl+C interrupt during recovery, exiting! ") print("************************************************") break self.current_pipeline = 'recovery' + print(EXECUTION_PREFIX,"Ctrl+C pressed, switching to recovery mode.") + if time.time() - self.last_loop_time > 0.5: + print(EXECUTION_PREFIX,"A component may have hung. Traceback:") + import traceback + traceback.print_exc() if validated: self.end() #done with mission - print("Done with mission execution, stopping components and exiting") + print(EXECUTION_PREFIX,"Done with mission execution, stopping components and exiting") for (name,(perception_components,planning_components,other_components)) in self.pipelines.items(): for (k,c) in perception_components.items(): @@ -256,25 +316,34 @@ def run(self): c.stop() for (k,c) in other_components.items(): c.stop() - + + if self.state_log: + self.state_log.close() + self.state_log = None + if self.behavior_log: + self.behavior_log.close() + self.behavior_log = None def validate_sensors(self,numsteps=None): #verify sensors are working (perception_components,planning_components,other_components) = self.pipelines[self.current_pipeline] dt_min = min([c.dt for c in perception_components.values()]) + if self.log_state_rate is not None: + dt_min = min(dt_min,1.0/self.log_state_rate) looper = TimedLooper(dt_min,name="main executor") sensors_working = False num_attempts = 0 t0 = time.time() next_print_time = t0 + 1.0 while looper and not sensors_working: - update_components(perception_components,self.state) + self.last_loop_time = time.time() + self.update_components(perception_components,self.state) sensors_working = all([c.c.healthy() for c in perception_components.values()]) num_attempts += 1 if numsteps is not None and num_attempts >= numsteps: return False if time.time() > next_print_time: - print("Waiting for sensors to be healthy...") + print(EXECUTION_PREFIX,"Waiting for sensors to be healthy...") next_print_time += 1.0 return True @@ -284,38 +353,88 @@ def run_until_switch(self): (perception_components,planning_components,other_components) = self.pipelines[self.current_pipeline] dt_min = min([c.dt for c in perception_components.values()] + [c.dt for c in planning_components.values()] + [c.dt for c in other_components.values()]) + if self.log_state_rate is not None: + dt_min = min(dt_min,1.0/self.log_state_rate) looper = TimedLooper(dt_min,name="main executor") while looper and not self.done(): - update_components(perception_components,self.state) + self.state.t = self.vehicle_interface.time() + self.last_loop_time = time.time() + self.update_components(perception_components,self.state) #check for faults sensors_working = all([c.c.healthy() for c in perception_components.values()]) if not sensors_working: - print("Sensors not working, entering recovery mode") + print(EXECUTION_PREFIX,"Sensors not working, entering recovery mode") return 'recovery' next_pipeline = self.update(self.state) if next_pipeline is not None and next_pipeline != self.current_pipeline: - print("update() requests to switch to pipeline {}".format(next_pipeline)) + print(EXECUTION_PREFIX,"update() requests to switch to pipeline {}".format(next_pipeline)) return next_pipeline - update_components(planning_components,self.state) + self.update_components(planning_components,self.state) #check for faults planners_working = all([c.c.healthy() for c in planning_components.values()]) if not planners_working: - print("Planners not working, entering recovery mode") + print(EXECUTION_PREFIX,"Planners not working, entering recovery mode") return 'recovery' - update_components(other_components,self.state) + self.update_components(other_components,self.state) others_working = all([c.c.healthy() for c in other_components.values()]) if not others_working: - print("Other items not working, ignoring") + print(EXECUTION_PREFIX,"Other items not working, ignoring") #self.done() returned True return None + def update_components(self, components : Dict[str,ComponentExecutor], state : AllState, now = False): + """Updates the components and performs necessary logging. + + If now = True, all components are run regardless of polling state. + """ + t = state.t + for k in COMPONENT_ORDER: + if k in components: + updated = False + if now: + components[k].update_now(t,state) + updated = True + else: + updated = components[k].update(t,state) + #log component output if necessary + if updated and k in self.logged_components: + if len(components[k].output)!=0: + self.behavior_log.log(state, components[k].output, t) + if 'vehicle_interface' in self.logged_components: + if state.t != self.vehicle_log_t_last: + collection = {'vehicle_interface_command':self.vehicle_interface.last_command, + 'vehicle_interface_reading':self.vehicle_interface.last_reading} + self.behavior_log.log(collection,t=t) + self.vehicle_log_t_last = state.t + #log state if necessary + if self.logged_state_attributes: + if self.logged_state_attributes[0] == 'all': + self.state_log.log(state) + else: + self.state_log.log(state,self.logged_state_attributes) + + class StandardExecutor(ExecutorBase): def begin(self): - import rospy - rospy.init_node('GEM executor') + try: + import rospy + rospy.init_node('GEM executor') + except (ImportError,ModuleNotFoundError): + if settings.get('run.mode','hardware') == 'simulation': + print(EXECUTION_PREFIX,"Warning, ROS not found, but simulation mode requested") + else: + print(EXECUTION_PREFIX,"Error, ROS not found on system.") + raise + def done(self): + if self.current_pipeline == 'recovery': + if self.vehicle_interface.last_reading is not None and \ + abs(self.vehicle_interface.last_reading.speed) < 1e-3: + print(EXECUTION_PREFIX,"Vehicle has stopped, exiting execution loop.") + return True + return False diff --git a/GEMstack/onboard/execution/log_replay.py b/GEMstack/onboard/execution/log_replay.py index da0944a89..47b9fbd25 100644 --- a/GEMstack/onboard/execution/log_replay.py +++ b/GEMstack/onboard/execution/log_replay.py @@ -1,21 +1,30 @@ -from ...utils import serialization +from ...utils import serialization,logging from ..component import Component from typing import List import time class LogReplay(Component): """Substitutes the output of a component with replayed data from a log file. + + There are two forms of log files supported. The first is a delta format, where + each line is a dictionary of the form ``{'time':t,ITEM1:{...},ITEM2:{...}}``. + + The second is a state format, where each line is a dictionary of the form + ``{ITEM1:VAL, ITEM2:VAL, ITEM1_update_time:t, ITEM2_update_time:t}``. + + If the `delta_format` attribute is True, then the delta format is assumed. """ - def __init__(self, vehicle_interface, outputs : List[str], log_file : str, rate : float = 10.0): + def __init__(self, vehicle_interface, outputs : List[str], + log_file : str, + delta_format=True, + rate : float = 10.0, + speed_multiplier : float = 1.0): self.vehicle_interface = vehicle_interface self.outputs = outputs self.logfn = log_file self._rate = rate - self.logfile = open(log_file,'r') - self.logfile_delta_format = True - self.log_start_time = None - self.next_item = None - self.next_item_time = None + self.speed_multiplier = speed_multiplier + self.logfile = logging.Logfile(log_file,delta_format,'r') self.start_time = None def rate(self): @@ -28,59 +37,18 @@ def update(self): t = self.vehicle_interface.time() if self.start_time == None: self.start_time = t - if self.logfile == None: + if not self.logfile: return - if self.log_start_time is None: - try: - while self.next_item is None: - self.read_next() - except IOError: - self.logfile.close() - self.logfile = None - self.log_start_time = self.next_item_time - if self.next_item_time - self.log_start_time > t - self.start_time: - #not yet the time to read the next item - return - #return the next item - res = [self.next_item.get(o,None) for o in self.outputs] - #advance to the next item in the log - try: - while self.next_item_time - self.log_start_time < t - self.start_time: - self.read_next() - except IOError: - self.logfile.close() - self.logfile = None + res,msgs = self.logfile.read(duration_from_start = (t - self.start_time)*self.speed_multiplier, cumulative = True) + #if nothing new was read, just return None + if len(msgs)==0: + return None + #convert the dict to a list of values in the same order as self.outputs + res = [res.get(o,None) for o in self.outputs] if len(self.outputs)==1: return res[0] if all(v is None for v in res): return None return res - def read_next(self): - line = self.logfile.readline() - if line == '': - raise IOError("End of log file") - msg = serialization.deserialize_collection(line[:-1]) - if self.logfile_delta_format: - #assumed to be of the form {'time':t,ITEM1:{...},ITEM2:{...}} - assert 'time' in msg - if self.next_item is None: - self.next_item = {} - for o in self.outputs: - if o in msg: - self.next_item[o] = msg[o] - self.next_item_time = msg['time'] - if self.next_item_time is None: - self.next_item = None - else: - #assumed to be state dictionaries of the form {ITEM1:VAL, ITEM2:VAL, ITEM1_update_time:t, ITEM2_update_time:t} - self.next_item = msg - self.next_item_time = None - for o in self.outputs: - if o+'_update_time' in msg: - v = msg[o+'_update_time'] - if self.next_item_time is None: - self.next_item_time = v - else: - self.next_item_time = max(self.next_item_time,v) diff --git a/GEMstack/onboard/interface/gem.py b/GEMstack/onboard/interface/gem.py index 55c44e78f..e538d6773 100644 --- a/GEMstack/onboard/interface/gem.py +++ b/GEMstack/onboard/interface/gem.py @@ -1,14 +1,15 @@ from dataclasses import dataclass -from ...utils import settings +from ...utils import settings,serialization from ...state import VehicleState, ObjectPose, ObjectFrameEnum from ...knowledge.vehicle.geometry import front2steer,steer2front,heading_rate from ...knowledge.vehicle.dynamics import pedal_positions_to_acceleration, acceleration_to_pedal_positions @dataclass +@serialization.register class GEMVehicleReading: - speed : float = 0 + speed : float = 0 # in m/s gear : int = 0 - accelerator_pedal_position : float = 0 + accelerator_pedal_position : float = 0 # in range [0,1] brake_pedal_position : float = 0 steering_wheel_angle : float = 0 left_turn_signal : bool = False @@ -37,15 +38,16 @@ def to_state(self, pose : ObjectPose = None) -> VehicleState: pitch = pose.pitch if pose.pitch is not None else 0.0 wheel_base = settings.get('vehicle.geometry.wheelbase') front_wheel_angle=front2steer(self.steering_wheel_angle) - heading_rate=heading_rate(front_wheel_angle,self.speed,wheel_base) + turn_rate=heading_rate(front_wheel_angle,self.speed,wheel_base) acc = pedal_positions_to_acceleration(self.accelerator_pedal_position, self.brake_pedal_position, self.speed, pitch, self.gear) return VehicleState(pose,v=self.speed,acceleration=acc,gear=self.gear,steering_wheel_angle=self.steering_wheel_angle, - front_wheel_angle=front_wheel_angle,turn_rate=heading_rate, + front_wheel_angle=front_wheel_angle,heading_rate=turn_rate, left_turn_indicator=self.left_turn_signal,right_turn_indicator=self.right_turn_signal, horn_on=self.horn_on,wiper_level=self.wiper_level,headlights_on=self.headlights_on) @dataclass +@serialization.register class GEMVehicleCommand: gear : int #follows convention in state.vehicle.VehicleState. -2: park, -1 reverse: 0: neutral, 1..n: forward accelerator_pedal_position : float @@ -105,27 +107,34 @@ def hardware_faults(self) -> list: """Returns a list of hardware faults (by component)""" raise NotImplementedError() - def simple_command(self, acceleration_amount : float, steering_wheel_angle : float) -> GEMVehicleCommand: - cmd = GEMVehicleCommand() - cmd.brake_pedal_speed = settings.get('vehicle.control_defaults.brake_pedal_speed') - cmd.steering_wheel_speed = settings.get('vehicle.control_defaults.steering_wheel_speed') - cmd.accelerator_pedal_speed = settings.get('vehicle.control_defaults.accelerator_pedal_speed') - cmd.gear = 1 - cmd.left_turn_signal = False - cmd.right_turn_signal = False - cmd.headlights_on = False - cmd.horn_on = False - cmd.wiper_level = 0 - - if acceleration_amount < 0: - cmd.brake_pedal_position = -acceleration_amount - if cmd.brake_pedal_position > 1: - cmd.brake_pedal_position = 1 - cmd.accelerator_pedal_position = 0 - else: - cmd.accelerator_pedal_position = acceleration_amount - if cmd.accelerator_pedal_position > 1: - cmd.accelerator_pedal_position = 1 - cmd.brake_pedal_position = 0 - cmd.steering_wheel_angle = steering_wheel_angle + def simple_command(self, acceleration_mps2 : float, steering_wheel_angle : float, state : VehicleState = None) -> GEMVehicleCommand: + """" + Returns a command according to a desired acceleration and steering angle + + Args: + acceleration_mps2: acceleration in m/s^2 + steering_wheel_angle: steering angle in radians + state: current vehicle state + """ + pitch = state.pose.pitch if state is not None and state.pose.pitch is not None else 0.0 + v = state.v if state is not None else 0.0 + gear = state.gear if state is not None else 1 + acc_pos,brake_pos,gear = acceleration_to_pedal_positions(acceleration_mps2, v, pitch, gear) + print(acc_pos,brake_pos,gear) + + cmd = GEMVehicleCommand(gear=gear, + accelerator_pedal_position=acc_pos, + brake_pedal_position=brake_pos, + steering_wheel_angle=steering_wheel_angle, + accelerator_pedal_speed=settings.get('vehicle.control_defaults.accelerator_pedal_speed'), + brake_pedal_speed = settings.get('vehicle.control_defaults.brake_pedal_speed'), + steering_wheel_speed = settings.get('vehicle.control_defaults.steering_wheel_speed')) + if state is not None: + #preserve indicators + cmd.left_turn_signal = state.left_turn_indicator + cmd.right_turn_signal = state.right_turn_indicator + cmd.headlights_on = state.headlights_on + cmd.horn_on = state.horn_on + cmd.wiper_level = state.wiper_level + return cmd diff --git a/GEMstack/onboard/interface/gem_hardware.py b/GEMstack/onboard/interface/gem_hardware.py index abfae1c11..73450cb5b 100644 --- a/GEMstack/onboard/interface/gem_hardware.py +++ b/GEMstack/onboard/interface/gem_hardware.py @@ -83,7 +83,7 @@ def speed_callback(self,msg : VehicleSpeedRpt): self.last_reading.speed = msg.vehicle_speed # forward velocity in m/s def steer_callback(self, msg): - self.last_reading.steering_wheel_angle = round(math.degrees(msg.output),1) + self.last_reading.steering_wheel_angle = msg.output def get_reading(self) -> GEMVehicleReading: return self.last_reading diff --git a/GEMstack/onboard/interface/gem_simulator.py b/GEMstack/onboard/interface/gem_simulator.py index 94210e1e0..2f2728a0f 100644 --- a/GEMstack/onboard/interface/gem_simulator.py +++ b/GEMstack/onboard/interface/gem_simulator.py @@ -3,6 +3,7 @@ from ...mathutils.dynamics import simulate from ...state import VehicleState,ObjectPose,ObjectFrameEnum,Roadgraph,AgentState,AgentEnum,AgentActivityEnum,Obstacle,Sign from ...knowledge.vehicle.geometry import front2steer,steer2front,heading_rate +from ...knowledge.vehicle.dynamics import pedal_positions_to_acceleration, acceleration_to_pedal_positions from ...utils.loops import TimedLooper from ...utils import config from threading import Thread,Lock @@ -17,7 +18,7 @@ def __init__(self, scene : str = None): wheelAngleMin=settings.get('vehicle.geometry.min_wheel_angle'), wheelAngleMax=settings.get('vehicle.geometry.max_wheel_angle'), velocityMin=-settings.get('vehicle.limits.max_reverse_speed'), - velocityMax=-settings.get('vehicle.limits.max_speed'), + velocityMax=settings.get('vehicle.limits.max_speed'), accelMin=-settings.get('vehicle.limits.max_acceleration'), accelMax=settings.get('vehicle.limits.max_deceleration'), wheelAngleRateMin=-settings.get('vehicle.limits.max_steering_rate'), @@ -31,6 +32,7 @@ def __init__(self, scene : str = None): if scene is None: scene = settings.get('simulator.scene',None) if isinstance(scene,str): + print("Loading simulator from scene",scene) scene = config.load_config_recursive(scene) if scene is None: self.simulation_time = time.time() @@ -53,6 +55,10 @@ def __init__(self, scene : str = None): self.last_reading.horn_on = False self.last_reading.wiper_level = 0 self.last_reading.headlights_on = False + #initialize last command + gear = -2 if self.cur_vehicle_state[3] == 0 else -1 if self.cur_vehicle_state[3] < 0 else 1 + steering_wheel_angle = front2steer(self.cur_vehicle_state[4]) + self.last_command = GEMVehicleCommand(gear,0,0,0,0,steering_wheel_angle,0) self.gnss_callback = None self.imu_callback = None self.thread_lock = Lock() @@ -64,13 +70,17 @@ def time(self) -> float: def start(self): assert self.thread is None + print("Running simulator thread...") self.thread_data['stop'] = False self.thread = Thread(target=self.simulate,args=(self.thread_lock,self.thread_data)) + self.thread.start() def stop(self): + print("Stopping simulator thread...") self.thread_data['stop']= True self.thread.join() self.thread = None + print("Done.") def hardware_faults(self) -> list: return [] @@ -91,45 +101,49 @@ def get_reading(self) -> GEMVehicleReading: def simulate(self,lock : Lock, data : dict): looper = TimedLooper(self.dt / self.real_time_multiplier,name="Simulation thread") while looper and not data['stop']: - lock.acquire() - x,y,theta,v,phi = self.cur_vehicle_state - #simulate actuators - acceleration = self.last_command.accelerator_pedal_position - self.last_command.brake_pedal_position - acceleration = np.clip(acceleration,*self.dubins.accelRange) - phides = steer2front(self.last_command.steering_wheel_angle) - phides = np.clip(phides,*self.dubins.wheelAngleRange) - phi_deadband = 0.01 - steering_angle_rate = self.last_command.steering_wheel_speed if phides > phi + phi_deadband else \ - (-self.last_command.steering_wheel_speed if phides < phi - phi_deadband else 0.0) - - #simulate dynamics - u = np.array([acceleration,steering_angle_rate]) #acceleration, steering angle rate - next_state = simulate(self.dubins, self.cur_vehicle_state, u, self.dt, self.dt) - x,y,theta,v,phi = next_state - v = np.clip(v,*self.dubins.velocityRange) - next_state = np.array([x,y,theta,v,phi]) + with lock: + x,y,theta,v,phi = self.cur_vehicle_state + #print("x %.2f y %.2f theta %.2f v %.2f" % (x,y,theta,v)) + #simulate actuators + accelerator_pedal_position = np.clip(self.last_command.accelerator_pedal_position,0.0,1.0) + brake_pedal_position = np.clip(self.last_command.brake_pedal_position,0.0,1.0) + acceleration = pedal_positions_to_acceleration(accelerator_pedal_position,brake_pedal_position,v,0,1) + acceleration = np.clip(acceleration,*self.dubins.accelRange) + phides = steer2front(self.last_command.steering_wheel_angle) + phides = np.clip(phides,*self.dubins.wheelAngleRange) + phi_deadband = 0.01 + steering_angle_rate = self.last_command.steering_wheel_speed if phides > phi + phi_deadband else \ + (-self.last_command.steering_wheel_speed if phides < phi - phi_deadband else 0.0) + + #simulate dynamics + u = np.array([acceleration,steering_angle_rate]) #acceleration, steering angle rate + #print("Accel %.2f, steering angle current %.2f, desired %.2f, rate %.2f" % (acceleration,phi,phides,steering_angle_rate)) + next = simulate(self.dubins, self.cur_vehicle_state, (lambda x,t: u), self.dt, self.dt) + next_state = next['x'][-1] + x,y,theta,v,phi = next_state + v = np.clip(v,*self.dubins.velocityRange) + next_state = np.array([x,y,theta,v,phi]) - #simulate sensors - reading = copy.copy(self.last_reading) - reading.steering_wheel_angle = front2steer(phi) - if acceleration > 0: - reading.brake_pedal_position = 0.0 - reading.accelerator_pedal_position = acceleration - else: - reading.brake_pedal_position = -acceleration - reading.accelerator_pedal_position = 0 - reading.speed = v - if v > 0: - reading.gear = 1 - else: - reading.gear = -1 - last_reading = reading + #simulate sensors + reading = copy.copy(self.last_reading) + reading.steering_wheel_angle = front2steer(phi) + if acceleration > 0: + reading.brake_pedal_position = 0.0 + reading.accelerator_pedal_position = acceleration + else: + reading.brake_pedal_position = -acceleration + reading.accelerator_pedal_position = 0 + reading.speed = v + if v > 0: + reading.gear = 1 + else: + reading.gear = -1 + self.last_reading = reading - if self.gnss_callback is not None: - pose = ObjectPose(frame=ObjectFrameEnum.ABSOLUTE_CARTESIAN,t=self.simulation_time,x=x,y=y,yaw=theta) - vehicle_state = last_reading.to_state(pose) - self.gnss_callback(vehicle_state) + if self.gnss_callback is not None: + pose = ObjectPose(frame=ObjectFrameEnum.ABSOLUTE_CARTESIAN,t=self.simulation_time,x=x,y=y,yaw=theta) + vehicle_state = self.last_reading.to_state(pose) + self.gnss_callback(vehicle_state) - self.cur_vehicle_state = next_state - self.simulation_time += self.dt - lock.release() + self.cur_vehicle_state = next_state + self.simulation_time += self.dt diff --git a/GEMstack/onboard/perception/perception_normalization.py b/GEMstack/onboard/perception/perception_normalization.py index 2f2ca8c99..7a5d91cb7 100644 --- a/GEMstack/onboard/perception/perception_normalization.py +++ b/GEMstack/onboard/perception/perception_normalization.py @@ -21,19 +21,19 @@ def update(self,state : AllState): state.vehicle.pose = state.vehicle.pose.to_frame(ObjectFrameEnum.START, start_pose_abs=state.start_vehicle_pose) #convert roadgraph to current frame - state.roadgraph = state.roadgraph.to_frame(ObjectFrameEnum.CURRENT, current_pose=state.vehicle_pose, start_pose_abs=state.start_vehicle_pose) + state.roadgraph = state.roadgraph.to_frame(ObjectFrameEnum.CURRENT, current_pose=state.vehicle, start_pose_abs=state.start_vehicle_pose) for k,a in state.agents.items(): - a.pose = a.pose.to_frame(ObjectFrameEnum.CURRENT, current_pose=state.vehicle_pose, start_pose_abs=state.start_vehicle_pose) + a.pose = a.pose.to_frame(ObjectFrameEnum.CURRENT, current_pose=state.vehicle, start_pose_abs=state.start_vehicle_pose) for k,o in state.obstacles.items(): - o.pose = o.pose.to_frame(ObjectFrameEnum.CURRENT, current_pose=state.vehicle_pose, start_pose_abs=state.start_vehicle_pose) + o.pose = o.pose.to_frame(ObjectFrameEnum.CURRENT, current_pose=state.vehicle, start_pose_abs=state.start_vehicle_pose) #convert predictions to current frame. for k,a in state.agent_intents.items(): for pred in a.predictions: if pred.path is not None: for i,p in enumerate(pred.path): - pred.path[i] = p.to_frame(ObjectFrameEnum.CURRENT, current_pose=state.vehicle_pose, start_pose_abs=state.start_vehicle_pose) + pred.path[i] = p.to_frame(ObjectFrameEnum.CURRENT, current_pose=state.vehicle, start_pose_abs=state.start_vehicle_pose) #TODO: advance agent predictions and paths to current vehicle time \ No newline at end of file diff --git a/GEMstack/onboard/perception/state_estimation.py b/GEMstack/onboard/perception/state_estimation.py index c1c8f3108..edc91ab71 100644 --- a/GEMstack/onboard/perception/state_estimation.py +++ b/GEMstack/onboard/perception/state_estimation.py @@ -15,7 +15,7 @@ def __init__(self, vehicle_interface : GEMInterface): self.vehicle_interface = vehicle_interface vehicle_interface.subscribe_gnss(self.inspva_callback) self.gnss_pose = None - self.location = settings.get('vehicle.calibration.gnss_location') + self.location = settings.get('vehicle.calibration.gnss_location')[:2] self.yaw_offset = settings.get('vehicle.calibration.gnss_yaw') # Get GNSS information diff --git a/GEMstack/onboard/planning/pure_pursuit.py b/GEMstack/onboard/planning/pure_pursuit.py index 7315485ff..042779d2e 100644 --- a/GEMstack/onboard/planning/pure_pursuit.py +++ b/GEMstack/onboard/planning/pure_pursuit.py @@ -2,7 +2,8 @@ from ...mathutils.signal import OnlineLowPassFilter from ...utils import settings from ...mathutils import transforms -from ...state.vehicle import VehicleState +from ...knowledge.vehicle.dynamics import acceleration_to_pedal_positions +from ...state.vehicle import VehicleState,ObjectFrameEnum from ...state.trajectory import Path,Trajectory,compute_headings from ...knowledge.vehicle.geometry import front2steer from ..interface.gem import GEMVehicleCommand @@ -18,9 +19,10 @@ def __init__(self, lookahead = None, lookahead_scale = None, wheelbase = None, c self.wheelbase = wheelbase if wheelbase is not None else settings.get('vehicle.geometry.wheelbase') self.wheel_angle_range = [settings.get('vehicle.geometry.min_wheel_angle'),settings.get('vehicle.geometry.max_wheel_angle')] self.steering_angle_range = [settings.get('vehicle.geometry.min_steering_angle'),settings.get('vehicle.geometry.max_steering_angle')] - + self.desired_speed = 1.5 # m/s, reference speed - self.max_accel = settings.get('vehicle.limits.max_accelerator_pedal') # % of acceleration + self.max_accel = settings.get('vehicle.limits.max_acceleration') # m/s^2 + self.max_decel = settings.get('vehicle.limits.max_deceleration') # m/s^2 self.pid_speed = PID(0.5, 0.0, 0.1, windup_limit=20) self.speed_filter = OnlineLowPassFilter(1.2, 30, 4) @@ -39,21 +41,24 @@ def set_path(self, path : Path): self.path_with_headings = compute_headings(self.path) def compute(self, state : VehicleState): + assert state.pose.frame != ObjectFrameEnum.CURRENT + t = state.pose.t + if self.path is None: #just stop - accel = self.pid_speed(0.0, state.t) + accel = self.pid_speed(0.0, t) if self.t_start is None: - self.t_start = state.t - dt = state.t - self.t_start + self.t_start = t + dt = t - self.t_start - if self.path.frame != state.frame: - self.path = self.path.to_frame(state.frame) - self.path_with_headings = self.path_with_headings.to_frame(state.frame) + if self.path.frame != state.pose.frame: + self.path = self.path.to_frame(state.pose.frame) + self.path_with_headings = self.path_with_headings.to_frame(state.pose.frame) - curr_x = state.x - curr_y = state.y - curr_yaw = state.heading + curr_x = state.pose.x + curr_y = state.pose.y + curr_yaw = state.pose.yaw if state.pose.yaw is not None else 0.0 speed = state.v @@ -74,26 +79,30 @@ def compute(self, state : VehicleState): f_delta = np.clip(angle, self.wheel_angle_range[0], self.wheel_angle_range[1]) - steering_angle = np.clip(front2steer(f_delta), self.steering_angle_range[0], self.steering_angle_range[1]) print("Closest point distance: " + str(L)) print("Forward velocity: " + str(speed)) ct_error = np.sin(alpha) * L print("Crosstrack Error: " + str(round(ct_error,3))) - print("Front steering angle: " + str(np.degrees(f_delta)) + " degrees") - print("Steering wheel angle: " + str(np.degrees(steering_angle)) + " degrees" ) + print("Front steering angle: " + str(round(np.degrees(f_delta),2)) + " degrees") + steering_angle = np.clip(front2steer(f_delta), self.steering_angle_range[0], self.steering_angle_range[1]) + print("Steering wheel angle: " + str(round(np.degrees(steering_angle),2)) + " degrees" ) print("\n") filt_vel = self.speed_filter(speed) - output_accel = self.pid_speed.advance(state.t, self.desired_speed - filt_vel) + print("Filtered velocity: " + str(filt_vel)) + output_accel = self.pid_speed.advance(e = self.desired_speed - filt_vel, t = t) + print(output_accel) + assert isinstance(output_accel, (int,float)) if output_accel > self.max_accel: output_accel = self.max_accel - if output_accel < 0.3: - output_accel = 0.3 + if output_accel < -self.max_decel: + output_accel = -self.max_decel self.path_progress += speed * dt + return (output_accel, f_delta) class PurePursuitTrajectoryTracker(Component): @@ -112,9 +121,9 @@ def state_outputs(self): def update(self, vehicle : VehicleState, trajectory: Trajectory): self.pure_pursuit.set_path(trajectory) - res = self.pure_pursuit.compute(vehicle) - res = GEMVehicleCommand(accelerator_pedal_position=res.accel, brake_pedal_position=res.brake, steering_wheel_angle=res.steer) - self.vehicle_interface.send_command(res) + accel,wheel_angle = self.pure_pursuit.compute(vehicle) + steering_angle = np.clip(front2steer(wheel_angle), self.pure_pursuit.steering_angle_range[0], self.pure_pursuit.steering_angle_range[1]) + self.vehicle_interface.send_command(self.vehicle_interface.simple_command(accel,steering_angle, vehicle)) def healthy(self): return self.pure_pursuit.path is not None \ No newline at end of file diff --git a/GEMstack/onboard/planning/recovery.py b/GEMstack/onboard/planning/recovery.py index dec30400d..4ce279404 100644 --- a/GEMstack/onboard/planning/recovery.py +++ b/GEMstack/onboard/planning/recovery.py @@ -19,6 +19,7 @@ def state_outputs(self): return [] def update(self): + print("StopTrajectoryTracker: Stopping, current speed %.3f m/s"%(self.vehicle_interface.last_reading.speed)) brake_amount = settings.get('control.recovery.brake_amount') brake_speed = settings.get('control.recovery.brake_speed') if self.vehicle_interface.last_command is not None: diff --git a/GEMstack/onboard/planning/route_planning.py b/GEMstack/onboard/planning/route_planning.py index 89dae28bf..b507b8dc6 100644 --- a/GEMstack/onboard/planning/route_planning.py +++ b/GEMstack/onboard/planning/route_planning.py @@ -15,6 +15,8 @@ def __init__(self, routefn : str): self.route = serialization.load(f) elif ext == '.csv': waypoints = np.loadtxt(routefn,delimiter=',',dtype=float) + if waypoints.shape[1] == 3: + waypoints = waypoints[:,:2] self.route = Route(frame=ObjectFrameEnum.START,points=waypoints.tolist()) else: raise ValueError("Unknown route file extension",ext) diff --git a/GEMstack/state/roadgraph.py b/GEMstack/state/roadgraph.py index f7a1558bc..4c5543d7f 100644 --- a/GEMstack/state/roadgraph.py +++ b/GEMstack/state/roadgraph.py @@ -193,29 +193,29 @@ def entity_names(self) -> List[str]: keys.update(self.static_obstacles.keys()) return list(keys) - def to_frame(self, frame : ObjectFrameEnum, current_origin = None, global_origin = None) -> Roadgraph: + def to_frame(self, frame : ObjectFrameEnum, current_pose = None, start_pose_abs = None) -> Roadgraph: newcurves = dict() for (k,c) in self.curves.items(): - newc = c.to_frame(self.frame,frame,current_origin,global_origin) + newc = c.to_frame(self.frame,frame,current_pose,start_pose_abs) newcurves[k] = newc newlanes = dict() for (k,l) in self.lanes.items(): - newl = l.to_frame(self.frame,frame,current_origin,global_origin) + newl = l.to_frame(self.frame,frame,current_pose,start_pose_abs) newlanes[k] = newl newregions = dict() for (k,r) in self.regions.items(): - newr = r.to_frame(self.frame,frame,current_origin,global_origin) + newr = r.to_frame(self.frame,frame,current_pose,start_pose_abs) newregions[k] = newr newsigns = dict() for (k,s) in self.signs.items(): - news = s.to_frame(frame,current_origin,global_origin) + news = s.to_frame(frame,current_pose,start_pose_abs) newsigns[k] = news newstatic_obstacles = dict() for (k,o) in self.static_obstacles.items(): - newo = o.to_frame(frame,current_origin,global_origin) + newo = o.to_frame(frame,current_pose,start_pose_abs) newstatic_obstacles[k] = newo newconnections = [] for c in self.connections: - newc = c.to_frame(self.frame,frame,current_origin,global_origin) + newc = c.to_frame(self.frame,frame,current_pose,start_pose_abs) newconnections.append(newc) return replace(self, frame = frame, curves = newcurves, lanes = newlanes, regions = newregions, signs = newsigns, static_obstacles = newstatic_obstacles, connections=newconnections) \ No newline at end of file diff --git a/GEMstack/state/trajectory.py b/GEMstack/state/trajectory.py index b49970974..1b424b3a5 100644 --- a/GEMstack/state/trajectory.py +++ b/GEMstack/state/trajectory.py @@ -80,7 +80,7 @@ def closest_point(self, x : List[float], edges = True) -> Tuple[float,float]: def get_dims(self, dims : List[int]) -> Path: """Returns a new path with only the given dimensions.""" - return replace(self,points=[p[dims] for p in self.points]) + return replace(self,points=[[p[d] for d in dims] for p in self.points]) def append_dim(self, value : Union[float,List[float]] = 0.0) -> None: """Appends a dimension to every point. If value is a list, then it @@ -159,9 +159,9 @@ def compute_headings(path : Path, smoothed = False) -> Path: else: dunit = transforms.normalize_vector(d) if nd == 1: - coords.append((transforms.vector2_angle(dunit,[1,0]))) + coords.append((transforms.vector2_angle(dunit,[1,0]),)) elif nd == 2: azimuth = transforms.vector2_angle(dunit[:2],[1,0]) elevation = transforms.vector2_angle((dunit[2],transforms.vector_norm(dunit[:2])),[0,0,1]) coords.append((azimuth,elevation)) - return replace(path,points=[tuple(p)+c for p,c in zip(path.points,coords)]) + return replace(path,points=[tuple(p)+tuple(c) for p,c in zip(path.points,coords)]) diff --git a/GEMstack/state/vehicle.py b/GEMstack/state/vehicle.py index 158e63f9f..272fc0ca0 100644 --- a/GEMstack/state/vehicle.py +++ b/GEMstack/state/vehicle.py @@ -20,7 +20,7 @@ class VehicleGearEnum(Enum): @register class VehicleState: """Represents the state of the ego-vehicle.""" - pose : ObjectPose #pose of the vehicle + pose : ObjectPose #pose of the vehicle, including time v : float #forward velocity in m/s acceleration : float #current acceleration / deceleration in m/s^2 steering_wheel_angle : float #angle of the steering wheel, in radians @@ -29,6 +29,7 @@ class VehicleState: gear : VehicleGearEnum #the current gear left_turn_indicator : bool = False #whether left turn indicator is on right_turn_indicator : bool = False #whether right turn indicator is on + headlights_on : bool = False #whether headlights are on horn_on : bool = False #whether horn is on wiper_level : int = 0 #whether wipers are on diff --git a/GEMstack/utils/config.py b/GEMstack/utils/config.py index 2d34d82fa..b283b32bf 100644 --- a/GEMstack/utils/config.py +++ b/GEMstack/utils/config.py @@ -51,7 +51,7 @@ def _construct_include(loader: _Loader, node: yaml.Node) -> Any: return _load_config_or_text_recursive(os.path.join(loader._root, loader.construct_scalar(node))) def _construct_relative_path(loader: _Loader, node: yaml.Node) -> Any: - return os.path.join(loader._root, loader.construct_scalar(node)) + return os.path.normpath(os.path.join(loader._root, loader.construct_scalar(node))) yaml.add_constructor('!include', _construct_include, _Loader) diff --git a/GEMstack/utils/logging.py b/GEMstack/utils/logging.py new file mode 100644 index 000000000..0cda2e55e --- /dev/null +++ b/GEMstack/utils/logging.py @@ -0,0 +1,193 @@ +from .serialization import deserialize,serialize,deserialize_collection,serialize_collection +import json +from typing import Union,Tuple + +class Logfile: + """A log file of serializable collections that can be read or written. + + There are two forms of log files supported. The first is a delta format, where + each line is a dictionary of the form ``{'time':t,ITEM1:{...},ITEM2:{...}}``. + + The second is a state format, where each line is a dictionary of the form + ``{ITEM1:VAL, ITEM2:VAL, ITEM1_update_time:t, ITEM2_update_time:t}``. + """ + def __init__(self, filename : str, delta_format: bool, mode='w'): + self.filename = filename + try: + self.file = open(filename,mode) + except IOError: + print("Error opening log file",filename) + self.file = None + self.delta_format = delta_format + self.mode = mode + + self.eof = False + self.next_item = None + self.cumulative_item = None + self.last_read_time = None + self.next_item_time = None + self.start_time = None + self.time_index = None + + def __nonzero__(self): + return self.file is not None and not self.eof + + def log(self, message, fields=None, t : float = None) -> None: + """Logs a message to the log file. + + Arguments: + message: a dict or instance of a serializable class registered in + the utils.serialization module. + fields (list, optional): if provided, then it specifies a list of + keys to extract from the message dict / object. If not + provided, then the entire message is logged. + t (float, optional): if provided, then it specifies the time to + log the message at. If not provided, then the message is + logged at the current time. + """ + if self.mode != 'w': + raise RuntimeError("Logfile is not open for writing") + if fields is not None: + if isinstance(message,dict): + new_message = {k:message[k] for k in fields} + if self.delta_format: + new_message['time'] = message.get('time',t) + else: + for k in fields: + new_message[k+'_update_time'] = message.get(k+'_update_time',t) + message = new_message + else: + new_message = {k:getattr(message,k) for k in fields} + if self.delta_format: + if t is None: + raise ValueError("Need to provide time for delta format") + new_message['time'] = t + else: + for k in fields: + new_message[k+'_update_time'] = getattr(message,k+'_update_time') + message = new_message + else: + if self.delta_format: + if t is None: + raise ValueError("Need to provide time for delta format") + if not isinstance(message,dict): + message = serialize(message,dict)['data'] + message['time'] = t + + if isinstance(message,dict): + self.file.write(serialize_collection(message)) + else: + self.file.write(serialize(message)['data']) + self.file.write('\n') + + def read(self, + duration_to_advance : float = None, + duration_from_start : float = None, + absolute_time : float = None, + cumulative = False) -> Union[list,Tuple[dict,list]]: + """Reads the next item(s) from the log file. + + - If `duration_to_advance` is given, then it will read this amount of + seconds from the current read time or from the start if no item has + been read yet. + - If `duration_from_start` is given, then it will read until this + amount of seconds from the start of the log file. This time cannot + be before the time of the last-read item. + - If `absolute_time` is given, then it will read the items until this + absolute time. This time cannot be before the time of the last- + read item. + + Arguments: + duration_to_advance (float, optional): the amount of time to + advance from the current read time. + duration_from_start (float, optional): the amount of time to + advance from the start of the log file. + absolute_time (float, optional): the absolute time to advance to. + cumulative (bool, optional): if True, then all of the updated + items up to the given time will be returned as a dictionary + in the first return argument. + + Returns: + list or tuple: if `cumulative` is False, then just returns a list + of the messages read from the log. If `cumulative` is True, + then returns a tuple (cumulative_item, messages) where + `cumulative_item` is a dictionary of the items that have been + updated up to the given time. + """ + if self.mode != 'r': + raise RuntimeError("Logfile is not open for reading") + if self.time_index is None: + #initialize the time index + try: + self._read_next() + except IOError: + if not self.eof: + print("WARNING: empty log file") + self.eof = True + if cumulative: + return {},[] + return [] + self.start_time = self.next_item_time + self.last_read_time = self.start_time + self.time_index = self.start_time + next_t = 0 + if duration_to_advance is not None: + if duration_to_advance < 0: + raise ValueError("Can't advance backwards in time") + next_t = self.time_index + duration_to_advance + elif duration_from_start is not None: + next_t = self.start_time + duration_from_start + if next_t < self.time_index: + raise ValueError("Can't advance backwards in time") + elif absolute_time is not None: + next_t = absolute_time + if next_t < self.time_index: + raise ValueError("Can't advance backwards in time") + else: + raise ValueError("Need to provide a time to advance to") + msgs = [] + while self.next_item_time < next_t: + self.last_read_time = self.next_item_time + msgs.append(self.next_item) + try: + self._read_next() + except IOError: + #end of file + self.eof = True + break + self.time_index = next_t + if cumulative: + return self.cumulative_item.copy(),msgs + else: + return msgs + + def _read_next(self): + line = self.file.readline() + if line == '': + raise IOError("End of log file") + msg = deserialize_collection(line[:-1]) + if self.cumulative_item is None: + self.cumulative_item = {} + if self.delta_format: + #assumed to be of the form {'time':t,ITEM1:{...},ITEM2:{...}} + assert 'time' in msg, "Invalid message read from log file" + self.next_item = msg + self.next_item_time = msg['time'] + for o in msg: + if o != 'time': + self.cumulative_item[o] = msg[o] + else: + #assumed to be state dictionaries of the form {ITEM1:VAL, ITEM2:VAL, ITEM1_update_time:t, ITEM2_update_time:t} + self.next_item = msg + self.next_item_time = None + for o,v in msg.items(): + if o.endswith('_update_time'): + if self.next_item_time is None: + self.next_item_time = v + else: + self.next_item_time = max(self.next_item_time,v) + self.cumulative_item[o] = v + + def close(self): + """Cleanly closes the log file.""" + self.file.close() \ No newline at end of file diff --git a/GEMstack/utils/serialization.py b/GEMstack/utils/serialization.py index ec4b565aa..c16228a9d 100644 --- a/GEMstack/utils/serialization.py +++ b/GEMstack/utils/serialization.py @@ -124,7 +124,7 @@ def deserialize_raw(data) -> tuple: def serialize_collection(objs, format=str): """Serializes a collection of registered objects into a serialized - collection objects. + format. `format` can be `str`, `bytes`, `dict`, or `"ros"`. """ @@ -143,7 +143,8 @@ def deserialize_collection(data): """Deserializes a message into a collection of registered object instances. We detect registered types as dicts with "type" and "data" keys, and - optional "version" key.""" + optional "version" key. + """ frame = json_decode(data) def _recurse(obj): if isinstance(obj,dict) and 'type' in obj and 'data' in obj: diff --git a/logs/.gitignore b/logs/.gitignore index e351385fb..bdbb4f7fc 100644 --- a/logs/.gitignore +++ b/logs/.gitignore @@ -1,4 +1,4 @@ -# * +* # track just these files !.gitignore diff --git a/logs/README.md b/logs/README.md index 70c0a33ad..1fd38d823 100644 --- a/logs/README.md +++ b/logs/README.md @@ -6,5 +6,7 @@ Within each folder, the file structure is: - meta.yaml: metadata for the run, including events, termination result, git branch and commit ID. - settings.yaml: the entire settings dictionary for the run. -- vehicle.bag: rosbag file for vehicle messages -- behavior.json: logged messages within the behavior stack. +- vehicle.bag: rosbag file for vehicle and sensor messages. +- vehicle.json: logged readings and commands on the vehicle object, if logging was enabled. +- behavior.json: logged messages within the behavior stack. An endline-separated sequence of JSON objects. +- state.json: logged AllState values. An endline-separated sequence of JSON objects. diff --git a/scenes/README.md b/scenes/README.md new file mode 100644 index 000000000..4c39c27e9 --- /dev/null +++ b/scenes/README.md @@ -0,0 +1 @@ +Simulation scenes should be placed here. \ No newline at end of file diff --git a/scenes/xyhead_demo.yaml b/scenes/xyhead_demo.yaml new file mode 100644 index 000000000..a5cb0f58b --- /dev/null +++ b/scenes/xyhead_demo.yaml @@ -0,0 +1,9 @@ +vehicle_state: [4.0, 5.0, 0.0, 0.0, 0.0] +agents: + ped1: + type: pedestrian + position: [12.0, 0.0] + velocity: 0.5 + target: [12.0,10.0] + behavior: loop + \ No newline at end of file diff --git a/testing/test_dynamics.py b/testing/test_dynamics.py new file mode 100644 index 000000000..64db7cc6f --- /dev/null +++ b/testing/test_dynamics.py @@ -0,0 +1,72 @@ +#needed to import GEMstack from top level directory +import sys +import os +sys.path.append(os.getcwd()) + +from GEMstack.knowledge.vehicle import dynamics +import matplotlib.pyplot as plt +import numpy as np + +def test_pedal_to_accel(): + gear = 1 + #vels = [0.0,0.01,0.1,1.0,5.0,10.0] + #pitches = [0.0] + vels = [0.0,1.0,5.0,10.0] + pitches = [0.0,-np.radians(10.0),np.radians(10.0)] + for v in vels: + for pitch in pitches: + x = np.linspace(0.0,1.0,100) + y = np.zeros(100) + for i,p in enumerate(x): + a = dynamics.pedal_positions_to_acceleration(p,0.0,v,pitch,gear) + y[i] = a + plt.plot(x,y,label="v %.2f m/s, pitch %.2f deg"%(v,np.degrees(pitch))) + plt.title("Gear=1") + plt.xlabel("Accelerator position") + plt.ylabel("Acceleration m/s^2") + plt.legend() + plt.show() + + for v in vels: + for pitch in pitches: + x = np.linspace(0.0,1.0,100) + y = np.zeros(100) + for i,p in enumerate(x): + a = dynamics.pedal_positions_to_acceleration(0.0,p,v,pitch,gear) + y[i] = a + plt.plot(x,y,label="v %.2f m/s, pitch %.2f deg"%(v,np.degrees(pitch))) + plt.title("Gear=1") + plt.xlabel("Brake position") + plt.ylabel("Acceleration m/s^2") + plt.legend() + plt.show() + +def test_accel_to_pedal(): + gear = 1 + #vels = [0.0,0.01,0.1,1.0,5.0,10.0] + #pitches = [0.0] + #vels = [0.0,1.0,5.0,10.0] + vels = [0.0,1.0] + pitches = [0.0,-np.radians(10.0),np.radians(10.0)] + for v in vels: + for pitch in pitches: + x = np.linspace(-2.5,2.5,100) + y1 = np.zeros(100) + y2 = np.zeros(100) + for i,a in enumerate(x): + acc,brake,gear_des = dynamics.acceleration_to_pedal_positions(a,v,pitch,gear) + y1[i] = acc + y2[i] = brake + if gear_des != gear: + print("For v %.2f m/s, pitch %.2f deg, a %.2f m/s^2, gear changed from %d to %d"%(v,np.degrees(pitch),a,gear,gear_des)) + plt.plot(x,y1,label="Acc v %.2f m/s, pitch %.2f deg"%(v,np.degrees(pitch))) + plt.plot(x,y2,linestyle='--',label="Brake v %.2f m/s, pitch %.2f deg"%(v,np.degrees(pitch))) + plt.title("Gear=1") + plt.ylabel("Pedal position") + plt.xlabel("Acceleration m/s^2") + plt.legend() + plt.show() + +if __name__=='__main__': + #test_pedal_to_accel() + test_accel_to_pedal() \ No newline at end of file From e2df5ac949e1a3747a5b04cfab911fa3e6f86f5b Mon Sep 17 00:00:00 2001 From: krishauser Date: Sat, 23 Dec 2023 13:10:40 -0500 Subject: [PATCH 008/232] Added readthedocs stuff --- .gitignore | 3 ++ .readthedocs.yaml | 31 ++++++++++++++++ README.md | 7 ++-- docs/Makefile | 20 +++++++++++ docs/api.rst | 7 ++++ docs/conf.py | 63 ++++++++++++++++++++++++++++++++ docs/index.rst | 20 +++++++++++ docs/requirements.in | 2 ++ docs/requirements.txt | 58 ++++++++++++++++++++++++++++++ docs/usage.rst | 84 +++++++++++++++++++++++++++++++++++++++++++ 10 files changed, 291 insertions(+), 4 deletions(-) create mode 100644 .readthedocs.yaml create mode 100644 docs/Makefile create mode 100644 docs/api.rst create mode 100644 docs/conf.py create mode 100644 docs/index.rst create mode 100644 docs/requirements.in create mode 100644 docs/requirements.txt create mode 100644 docs/usage.rst diff --git a/.gitignore b/.gitignore index 68bc17f9f..d5438b697 100644 --- a/.gitignore +++ b/.gitignore @@ -6,6 +6,9 @@ __pycache__/ # C extensions *.so +# auto-generated Sphinx api docs +/docs/generated + # Distribution / packaging .Python build/ diff --git a/.readthedocs.yaml b/.readthedocs.yaml new file mode 100644 index 000000000..44ee2f7a9 --- /dev/null +++ b/.readthedocs.yaml @@ -0,0 +1,31 @@ +# .readthedocs.yaml +# Read the Docs configuration file +# See https://docs.readthedocs.io/en/stable/config-file/v2.html for details + +# Required +version: 2 + +# Set the version of Python and other tools you might need +build: + os: ubuntu-22.04 + tools: + python: "3.10" + # You can also specify other tool versions: + # nodejs: "16" + # rust: "1.55" + # golang: "1.17" + +# Build documentation in the docs/ directory with Sphinx +sphinx: + configuration: docs/conf.py + +# If using Sphinx, optionally build your docs in additional formats such as PDF +# formats: +# - pdf + +# Optionally declare the Python requirements required to build your docs +python: + install: + - requirements: docs/requirements.txt + - method: pip + path: . diff --git a/README.md b/README.md index bb237edd1..ad4473b9b 100644 --- a/README.md +++ b/README.md @@ -2,13 +2,12 @@ ## Dependencies -Python 3.7+ +Python 3.7+ and ROS Noetic. It is possible to do some offline and simulation work without ROS, but -PACMOD - low level Autonomoustuff's interface to vehicle +In order to interface with the actual vehicle, you will need [PACMOD](http://wiki.ros.org/pacmod) - Autonomoustuff's low level interface to vehicle. If you are using the course SSDs these will be provided for you. -ROS (Noetic?) - messaging with cameras, simulator +You should also have the following Python dependencies installed, which you can install from this folder using `pip install -r requirements.txt`: -Python dependencies: - opencv-python - numpy - scipy diff --git a/docs/Makefile b/docs/Makefile new file mode 100644 index 000000000..d4bb2cbb9 --- /dev/null +++ b/docs/Makefile @@ -0,0 +1,20 @@ +# Minimal makefile for Sphinx documentation +# + +# You can set these variables from the command line, and also +# from the environment for the first two. +SPHINXOPTS ?= +SPHINXBUILD ?= sphinx-build +SOURCEDIR = . +BUILDDIR = _build + +# Put it first so that "make" without argument is like "make help". +help: + @$(SPHINXBUILD) -M help "$(SOURCEDIR)" "$(BUILDDIR)" $(SPHINXOPTS) $(O) + +.PHONY: help Makefile + +# Catch-all target: route all unknown targets to Sphinx using the new +# "make mode" option. $(O) is meant as a shortcut for $(SPHINXOPTS). +%: Makefile + @$(SPHINXBUILD) -M $@ "$(SOURCEDIR)" "$(BUILDDIR)" $(SPHINXOPTS) $(O) diff --git a/docs/api.rst b/docs/api.rst new file mode 100644 index 000000000..5b805dcb3 --- /dev/null +++ b/docs/api.rst @@ -0,0 +1,7 @@ +API +=== + +.. autosummary:: + :toctree: generated + + GEMstack diff --git a/docs/conf.py b/docs/conf.py new file mode 100644 index 000000000..a0fc05b9d --- /dev/null +++ b/docs/conf.py @@ -0,0 +1,63 @@ +# Configuration file for the Sphinx documentation builder. +# +# This file only contains a selection of the most common options. For a full +# list see the documentation: +# https://www.sphinx-doc.org/en/master/usage/configuration.html + +# -- Path setup -------------------------------------------------------------- + +# If extensions (or modules to document with autodoc) are in another directory, +# add these directories to sys.path here. If the directory is relative to the +# documentation root, use os.path.abspath to make it absolute, like shown here. +# +# import os +# import sys +# sys.path.insert(0, os.path.abspath('.')) + + +# -- Project information ----------------------------------------------------- + +project = "GEMstack autonomous vehicle behavior stack" +copyright = "2024, University of Illinois" +author = "UIUC CS 588 instructional staff" + + +# -- General configuration --------------------------------------------------- +# -- General configuration + +extensions = [ + "sphinx.ext.duration", + "sphinx.ext.doctest", + "sphinx.ext.autodoc", + "sphinx.ext.autosummary", + "sphinx.ext.intersphinx", +] + +intersphinx_mapping = { + "rtd": ("https://docs.readthedocs.io/en/stable/", None), + "python": ("https://docs.python.org/3/", None), + "sphinx": ("https://www.sphinx-doc.org/en/master/", None), +} +intersphinx_disabled_domains = ["std"] + +templates_path = ["_templates"] + +# -- Options for EPUB output +epub_show_urls = "footnote" + +# List of patterns, relative to source directory, that match files and +# directories to ignore when looking for source files. +# This pattern also affects html_static_path and html_extra_path. +exclude_patterns = ["_build", "Thumbs.db", ".DS_Store"] + +# -- Options for HTML output ------------------------------------------------- + +# The theme to use for HTML and HTML Help pages. See the documentation for +# a list of builtin themes. +# +html_theme = "sphinx_rtd_theme" + +# Add any paths that contain custom static files (such as style sheets) here, +# relative to this directory. They are copied after the builtin static files, +# so a file named "default.css" will overwrite the builtin "default.css". +html_static_path = ["_static"] diff --git a/docs/index.rst b/docs/index.rst new file mode 100644 index 000000000..c757ad172 --- /dev/null +++ b/docs/index.rst @@ -0,0 +1,20 @@ +Welcome to the GEMstack documentation! +=================================== + +Documentation coming soon. + +Check out the :doc:`usage` section for further information, including +how to :ref:`installation` the project. + +.. note:: + + This project is under active development. + +Contents +-------- + +.. toctree:: + + Home + usage + api diff --git a/docs/requirements.in b/docs/requirements.in new file mode 100644 index 000000000..acbc25d55 --- /dev/null +++ b/docs/requirements.in @@ -0,0 +1,2 @@ +Sphinx>=5,<6 +sphinx_rtd_theme diff --git a/docs/requirements.txt b/docs/requirements.txt new file mode 100644 index 000000000..c95df4dff --- /dev/null +++ b/docs/requirements.txt @@ -0,0 +1,58 @@ +# +# This file is autogenerated by pip-compile with python 3.10 +# To update, run: +# +# pip-compile docs/requirements.in +# +alabaster==0.7.12 + # via sphinx +babel==2.10.3 + # via sphinx +certifi==2022.6.15 + # via requests +charset-normalizer==2.1.0 + # via requests +docutils==0.17.1 + # via + # sphinx + # sphinx-rtd-theme +idna==3.3 + # via requests +imagesize==1.4.1 + # via sphinx +jinja2==3.1.2 + # via sphinx +markupsafe==2.1.1 + # via jinja2 +packaging==21.3 + # via sphinx +pygments==2.12.0 + # via sphinx +pyparsing==3.0.9 + # via packaging +pytz==2022.1 + # via babel +requests==2.28.1 + # via sphinx +snowballstemmer==2.2.0 + # via sphinx +sphinx==5.0.2 + # via + # -r docs/requirements.in + # sphinx-rtd-theme +sphinx-rtd-theme==1.0.0 + # via -r docs/requirements.in +sphinxcontrib-applehelp==1.0.2 + # via sphinx +sphinxcontrib-devhelp==1.0.2 + # via sphinx +sphinxcontrib-htmlhelp==2.0.0 + # via sphinx +sphinxcontrib-jsmath==1.0.1 + # via sphinx +sphinxcontrib-qthelp==1.0.3 + # via sphinx +sphinxcontrib-serializinghtml==1.1.5 + # via sphinx +urllib3==1.26.9 + # via requests diff --git a/docs/usage.rst b/docs/usage.rst new file mode 100644 index 000000000..9fc22223e --- /dev/null +++ b/docs/usage.rst @@ -0,0 +1,84 @@ +Usage +===== + +.. _installation: + +Installation +------------ + +To use GEMstack, you will need Python 3.7+ and ROS Noetic. To run it live on the GEM vehicle, you will also need `PACMOD `_, which is Autonomoustuff's low level interface to the vehicle + + +Next, clone it from the source Github repository: + +.. code-block:: console + + git clone https://github.com/krishauser/GEMstack + +Next, install the Python dependencies, running the following command from this folder + + +.. code-block:: console + + (.venv) $ pip install -r requirements.txt + +This command will install the following packages onto your system: +- opencv-python +- numpy +- scipy +- torch +- shapely +- dacite +- pyyaml + +Now, you can run the GEMstack entrypoints from the current folder (recommended). + +Alternatively, you can install GEMstack using pip (not recomended): + +.. code-block:: console + + (.venv) $ pip install . + +This is not recommended because has a couple of drawbacks: +- You will need to reinstall every time you change code in this folder. +- You might make changes in this directory, e.g., via `git pull`, and then forget to reinstall, so the changes won't be reflected when you run your code. +- If you added model or roadgraph files, e.g., to the `knowledge` directory, they may not be installed. You will need to edit `pyproject.toml` to include those files. + +If you are finding versioning errors due to an accidentally installed version of GEMstack conflicting with your work in this folder, make sure to run ``pip uninstall GEMstack``. + + + + + +Launching the stack +------------------- + +To launch a simulation using: + +.. code-block:: console + + python main.py GEMstack/launch/LAUNCH_FILE.yaml + +where ``LAUNCH_FILE.yaml`` is your preferred simulation launch file. Inspect the simulator classes in ``GEMstack/onboard/interface/gem_simulator.py`` for more information about configuring a simulator. + +To launch onboard behavior you will open four terminal windows, and in each of them run: +- ``roscore`` +- ``roslaunch basic_launch sensor_init.launch`` +- ``roslaunch basic_launch visualization.launch`` +- ``python main.py GEMstack/launch/LAUNCH_FILE.yaml`` where ``LAUNCH_FILE.yaml`` is your preferred launch file. + + +Note that if you try to use ``import GEMstack`` in a script or Jupyter notebook anywhere outside of this directory, Python will not know where the ``GEMstack`` module is. If you wish to import ``GEMstack`` from a script located in a separate directory, you can put + + +.. code-block:: python + + import sys + import os + sys.path.append(os.getcwd()) #or enter the absolute path of this directory + + import GEMstack + + +at the top of your script. Then, you can run the script from this directory via ``python PATH/TO/SCRIPT/myscript.py``. See the scripts in ``testing`` for an example of how this is done. + From ef3070a2e1a8b46424c6ca6ee49c84f4d36dbc2b Mon Sep 17 00:00:00 2001 From: krishauser Date: Sat, 23 Dec 2023 13:22:24 -0500 Subject: [PATCH 009/232] Added submodules --- docs/GEMstack.knowledge.rst | 8 ++++++++ docs/GEMstack.mathutils.rst | 8 ++++++++ docs/GEMstack.offboard.rst | 8 ++++++++ docs/GEMstack.onboard.rst | 8 ++++++++ docs/GEMstack.state.rst | 8 ++++++++ docs/GEMstack.utils.rst | 8 ++++++++ docs/api.rst | 8 +++++++- docs/index.rst | 2 +- 8 files changed, 56 insertions(+), 2 deletions(-) create mode 100644 docs/GEMstack.knowledge.rst create mode 100644 docs/GEMstack.mathutils.rst create mode 100644 docs/GEMstack.offboard.rst create mode 100644 docs/GEMstack.onboard.rst create mode 100644 docs/GEMstack.state.rst create mode 100644 docs/GEMstack.utils.rst diff --git a/docs/GEMstack.knowledge.rst b/docs/GEMstack.knowledge.rst new file mode 100644 index 000000000..f10dfd729 --- /dev/null +++ b/docs/GEMstack.knowledge.rst @@ -0,0 +1,8 @@ +GEMstack.knowledge package +========================== + +.. autosummary:: + :toctree: generated + :caption: Contents: + + GEMstack.knowledge \ No newline at end of file diff --git a/docs/GEMstack.mathutils.rst b/docs/GEMstack.mathutils.rst new file mode 100644 index 000000000..1ec603841 --- /dev/null +++ b/docs/GEMstack.mathutils.rst @@ -0,0 +1,8 @@ +GEMstack.mathutils package +========================== + +.. autosummary:: + :toctree: generated + :caption: Contents: + + GEMstack.mathutils \ No newline at end of file diff --git a/docs/GEMstack.offboard.rst b/docs/GEMstack.offboard.rst new file mode 100644 index 000000000..7b04583a2 --- /dev/null +++ b/docs/GEMstack.offboard.rst @@ -0,0 +1,8 @@ +GEMstack.offboard package +========================== + +.. autosummary:: + :toctree: generated + :caption: Contents: + + GEMstack.offboard \ No newline at end of file diff --git a/docs/GEMstack.onboard.rst b/docs/GEMstack.onboard.rst new file mode 100644 index 000000000..ed7653c82 --- /dev/null +++ b/docs/GEMstack.onboard.rst @@ -0,0 +1,8 @@ +GEMstack.onboard package +========================== + +.. autosummary:: + :toctree: generated + :caption: Contents: + + GEMstack.onboard \ No newline at end of file diff --git a/docs/GEMstack.state.rst b/docs/GEMstack.state.rst new file mode 100644 index 000000000..1c6b8a296 --- /dev/null +++ b/docs/GEMstack.state.rst @@ -0,0 +1,8 @@ +GEMstack.state package +========================== + +.. autosummary:: + :toctree: generated + :caption: Contents: + + GEMstack.state \ No newline at end of file diff --git a/docs/GEMstack.utils.rst b/docs/GEMstack.utils.rst new file mode 100644 index 000000000..9c0f1db06 --- /dev/null +++ b/docs/GEMstack.utils.rst @@ -0,0 +1,8 @@ +GEMstack.utils package +========================== + +.. autosummary:: + :toctree: generated + :caption: Contents: + + GEMstack.utils \ No newline at end of file diff --git a/docs/api.rst b/docs/api.rst index 5b805dcb3..810d47715 100644 --- a/docs/api.rst +++ b/docs/api.rst @@ -3,5 +3,11 @@ API .. autosummary:: :toctree: generated + :caption: Contents: - GEMstack + GEMstack.mathutils + GEMstack.utils + GEMstack.state + GEMstack.knowledge + GEMstack.onboard + GEMstack.offboard diff --git a/docs/index.rst b/docs/index.rst index c757ad172..ac3ecb5c2 100644 --- a/docs/index.rst +++ b/docs/index.rst @@ -1,5 +1,5 @@ Welcome to the GEMstack documentation! -=================================== +====================================== Documentation coming soon. From cae5f8cde34d7614fa5e63b8f253c6f47b8a815b Mon Sep 17 00:00:00 2001 From: krishauser Date: Sat, 23 Dec 2023 13:27:26 -0500 Subject: [PATCH 010/232] Module docstrings --- GEMstack/__init__.py | 10 ++++++++++ GEMstack/mathutils/__init__.py | 1 + 2 files changed, 11 insertions(+) diff --git a/GEMstack/__init__.py b/GEMstack/__init__.py index e69de29bb..ff43ce362 100644 --- a/GEMstack/__init__.py +++ b/GEMstack/__init__.py @@ -0,0 +1,10 @@ +"""Top level package for GEMstack. Submodules include: + +- onboard: All algorithms governing onboard behavior are located here. These algorithms may make use of items in the `knowledge/` stack. +- offboard: Creation and management of data and knowledge, running off of the vehicle. +- knowledge: Models and parameters common to onboard / offboard use. The file "current.py" in each directory will store the current model being used. +- mathutils: Math utilities common to onboard / offboard use. +- utils: Other utilities common to onboard / offboard use. +- `GEMstack/launch/`: Launch scripts are listed here. Specify which configuration you want to use as an argument to `main.py`. + +""" diff --git a/GEMstack/mathutils/__init__.py b/GEMstack/mathutils/__init__.py index e69de29bb..bdaab0a3c 100644 --- a/GEMstack/mathutils/__init__.py +++ b/GEMstack/mathutils/__init__.py @@ -0,0 +1 @@ +"""Math utilities common to onboard / offboard use.""" From 16ba77ff716c5648b19a6b2b9fd916854af15b16 Mon Sep 17 00:00:00 2001 From: krishauser Date: Sat, 23 Dec 2023 14:10:03 -0500 Subject: [PATCH 011/232] Autodoc files added --- README.md | 2 +- docs/GEMstack.knowledge.calibration.rst | 10 +++++ docs/GEMstack.knowledge.defaults.rst | 10 +++++ docs/GEMstack.knowledge.detection.rst | 10 +++++ docs/GEMstack.knowledge.heuristics.rst | 10 +++++ docs/GEMstack.knowledge.predicates.rst | 29 ++++++++++++ docs/GEMstack.knowledge.prediction.rst | 10 +++++ .../GEMstack.knowledge.roadmaps.geofences.rst | 10 +++++ docs/GEMstack.knowledge.roadmaps.rst | 18 ++++++++ docs/GEMstack.knowledge.routes.rst | 10 +++++ docs/GEMstack.knowledge.vehicle.rst | 29 ++++++++++++ docs/GEMstack.offboard.calibration.rst | 10 +++++ docs/GEMstack.offboard.detection_learning.rst | 10 +++++ docs/GEMstack.offboard.heuristic_learning.rst | 10 +++++ docs/GEMstack.offboard.log_management.rst | 10 +++++ .../GEMstack.offboard.prediction_learning.rst | 10 +++++ docs/GEMstack.onboard.execution.rst | 45 +++++++++++++++++++ docs/GEMstack.onboard.interface.rst | 37 +++++++++++++++ docs/GEMstack.onboard.perception.rst | 37 +++++++++++++++ docs/GEMstack.onboard.planning.rst | 45 +++++++++++++++++++ docs/GEMstack.rst | 23 ++++++++++ docs/api.rst | 7 +-- docs/modules.rst | 7 +++ 23 files changed, 392 insertions(+), 7 deletions(-) create mode 100644 docs/GEMstack.knowledge.calibration.rst create mode 100644 docs/GEMstack.knowledge.defaults.rst create mode 100644 docs/GEMstack.knowledge.detection.rst create mode 100644 docs/GEMstack.knowledge.heuristics.rst create mode 100644 docs/GEMstack.knowledge.predicates.rst create mode 100644 docs/GEMstack.knowledge.prediction.rst create mode 100644 docs/GEMstack.knowledge.roadmaps.geofences.rst create mode 100644 docs/GEMstack.knowledge.roadmaps.rst create mode 100644 docs/GEMstack.knowledge.routes.rst create mode 100644 docs/GEMstack.knowledge.vehicle.rst create mode 100644 docs/GEMstack.offboard.calibration.rst create mode 100644 docs/GEMstack.offboard.detection_learning.rst create mode 100644 docs/GEMstack.offboard.heuristic_learning.rst create mode 100644 docs/GEMstack.offboard.log_management.rst create mode 100644 docs/GEMstack.offboard.prediction_learning.rst create mode 100644 docs/GEMstack.onboard.execution.rst create mode 100644 docs/GEMstack.onboard.interface.rst create mode 100644 docs/GEMstack.onboard.perception.rst create mode 100644 docs/GEMstack.onboard.planning.rst create mode 100644 docs/GEMstack.rst create mode 100644 docs/modules.rst diff --git a/README.md b/README.md index ad4473b9b..097959e96 100644 --- a/README.md +++ b/README.md @@ -143,7 +143,7 @@ You can also install `GEMstack` into the system Python by calling `pip install . -## Communication protocols +## Communication and serialization protocols Sending commands to the vehicle is handled by the ROS-PACMOD interface. Receiving sensor messages is handled through standard ROS sensor messages. diff --git a/docs/GEMstack.knowledge.calibration.rst b/docs/GEMstack.knowledge.calibration.rst new file mode 100644 index 000000000..ef1dd5a16 --- /dev/null +++ b/docs/GEMstack.knowledge.calibration.rst @@ -0,0 +1,10 @@ +GEMstack.knowledge.calibration package +====================================== + +Module contents +--------------- + +.. automodule:: GEMstack.knowledge.calibration + :members: + :undoc-members: + :show-inheritance: diff --git a/docs/GEMstack.knowledge.defaults.rst b/docs/GEMstack.knowledge.defaults.rst new file mode 100644 index 000000000..eb67023a1 --- /dev/null +++ b/docs/GEMstack.knowledge.defaults.rst @@ -0,0 +1,10 @@ +GEMstack.knowledge.defaults package +=================================== + +Module contents +--------------- + +.. automodule:: GEMstack.knowledge.defaults + :members: + :undoc-members: + :show-inheritance: diff --git a/docs/GEMstack.knowledge.detection.rst b/docs/GEMstack.knowledge.detection.rst new file mode 100644 index 000000000..878e04ea4 --- /dev/null +++ b/docs/GEMstack.knowledge.detection.rst @@ -0,0 +1,10 @@ +GEMstack.knowledge.detection package +==================================== + +Module contents +--------------- + +.. automodule:: GEMstack.knowledge.detection + :members: + :undoc-members: + :show-inheritance: diff --git a/docs/GEMstack.knowledge.heuristics.rst b/docs/GEMstack.knowledge.heuristics.rst new file mode 100644 index 000000000..97693b167 --- /dev/null +++ b/docs/GEMstack.knowledge.heuristics.rst @@ -0,0 +1,10 @@ +GEMstack.knowledge.heuristics package +===================================== + +Module contents +--------------- + +.. automodule:: GEMstack.knowledge.heuristics + :members: + :undoc-members: + :show-inheritance: diff --git a/docs/GEMstack.knowledge.predicates.rst b/docs/GEMstack.knowledge.predicates.rst new file mode 100644 index 000000000..e61c8adeb --- /dev/null +++ b/docs/GEMstack.knowledge.predicates.rst @@ -0,0 +1,29 @@ +GEMstack.knowledge.predicates package +===================================== + +Submodules +---------- + +GEMstack.knowledge.predicates.agent\_count module +------------------------------------------------- + +.. automodule:: GEMstack.knowledge.predicates.agent_count + :members: + :undoc-members: + :show-inheritance: + +GEMstack.knowledge.predicates.predicate module +---------------------------------------------- + +.. automodule:: GEMstack.knowledge.predicates.predicate + :members: + :undoc-members: + :show-inheritance: + +Module contents +--------------- + +.. automodule:: GEMstack.knowledge.predicates + :members: + :undoc-members: + :show-inheritance: diff --git a/docs/GEMstack.knowledge.prediction.rst b/docs/GEMstack.knowledge.prediction.rst new file mode 100644 index 000000000..0fef4fde6 --- /dev/null +++ b/docs/GEMstack.knowledge.prediction.rst @@ -0,0 +1,10 @@ +GEMstack.knowledge.prediction package +===================================== + +Module contents +--------------- + +.. automodule:: GEMstack.knowledge.prediction + :members: + :undoc-members: + :show-inheritance: diff --git a/docs/GEMstack.knowledge.roadmaps.geofences.rst b/docs/GEMstack.knowledge.roadmaps.geofences.rst new file mode 100644 index 000000000..bab3862f6 --- /dev/null +++ b/docs/GEMstack.knowledge.roadmaps.geofences.rst @@ -0,0 +1,10 @@ +GEMstack.knowledge.roadmaps.geofences package +============================================= + +Module contents +--------------- + +.. automodule:: GEMstack.knowledge.roadmaps.geofences + :members: + :undoc-members: + :show-inheritance: diff --git a/docs/GEMstack.knowledge.roadmaps.rst b/docs/GEMstack.knowledge.roadmaps.rst new file mode 100644 index 000000000..0eac847d6 --- /dev/null +++ b/docs/GEMstack.knowledge.roadmaps.rst @@ -0,0 +1,18 @@ +GEMstack.knowledge.roadmaps package +=================================== + +Subpackages +----------- + +.. toctree:: + :maxdepth: 4 + + GEMstack.knowledge.roadmaps.geofences + +Module contents +--------------- + +.. automodule:: GEMstack.knowledge.roadmaps + :members: + :undoc-members: + :show-inheritance: diff --git a/docs/GEMstack.knowledge.routes.rst b/docs/GEMstack.knowledge.routes.rst new file mode 100644 index 000000000..fddb1c03a --- /dev/null +++ b/docs/GEMstack.knowledge.routes.rst @@ -0,0 +1,10 @@ +GEMstack.knowledge.routes package +================================= + +Module contents +--------------- + +.. automodule:: GEMstack.knowledge.routes + :members: + :undoc-members: + :show-inheritance: diff --git a/docs/GEMstack.knowledge.vehicle.rst b/docs/GEMstack.knowledge.vehicle.rst new file mode 100644 index 000000000..11148abc7 --- /dev/null +++ b/docs/GEMstack.knowledge.vehicle.rst @@ -0,0 +1,29 @@ +GEMstack.knowledge.vehicle package +================================== + +Submodules +---------- + +GEMstack.knowledge.vehicle.dynamics module +------------------------------------------ + +.. automodule:: GEMstack.knowledge.vehicle.dynamics + :members: + :undoc-members: + :show-inheritance: + +GEMstack.knowledge.vehicle.geometry module +------------------------------------------ + +.. automodule:: GEMstack.knowledge.vehicle.geometry + :members: + :undoc-members: + :show-inheritance: + +Module contents +--------------- + +.. automodule:: GEMstack.knowledge.vehicle + :members: + :undoc-members: + :show-inheritance: diff --git a/docs/GEMstack.offboard.calibration.rst b/docs/GEMstack.offboard.calibration.rst new file mode 100644 index 000000000..3e2c9405e --- /dev/null +++ b/docs/GEMstack.offboard.calibration.rst @@ -0,0 +1,10 @@ +GEMstack.offboard.calibration package +===================================== + +Module contents +--------------- + +.. automodule:: GEMstack.offboard.calibration + :members: + :undoc-members: + :show-inheritance: diff --git a/docs/GEMstack.offboard.detection_learning.rst b/docs/GEMstack.offboard.detection_learning.rst new file mode 100644 index 000000000..363254051 --- /dev/null +++ b/docs/GEMstack.offboard.detection_learning.rst @@ -0,0 +1,10 @@ +GEMstack.offboard.detection\_learning package +============================================= + +Module contents +--------------- + +.. automodule:: GEMstack.offboard.detection_learning + :members: + :undoc-members: + :show-inheritance: diff --git a/docs/GEMstack.offboard.heuristic_learning.rst b/docs/GEMstack.offboard.heuristic_learning.rst new file mode 100644 index 000000000..417ba9e43 --- /dev/null +++ b/docs/GEMstack.offboard.heuristic_learning.rst @@ -0,0 +1,10 @@ +GEMstack.offboard.heuristic\_learning package +============================================= + +Module contents +--------------- + +.. automodule:: GEMstack.offboard.heuristic_learning + :members: + :undoc-members: + :show-inheritance: diff --git a/docs/GEMstack.offboard.log_management.rst b/docs/GEMstack.offboard.log_management.rst new file mode 100644 index 000000000..7be0ffc8d --- /dev/null +++ b/docs/GEMstack.offboard.log_management.rst @@ -0,0 +1,10 @@ +GEMstack.offboard.log\_management package +========================================= + +Module contents +--------------- + +.. automodule:: GEMstack.offboard.log_management + :members: + :undoc-members: + :show-inheritance: diff --git a/docs/GEMstack.offboard.prediction_learning.rst b/docs/GEMstack.offboard.prediction_learning.rst new file mode 100644 index 000000000..1cddb7115 --- /dev/null +++ b/docs/GEMstack.offboard.prediction_learning.rst @@ -0,0 +1,10 @@ +GEMstack.offboard.prediction\_learning package +============================================== + +Module contents +--------------- + +.. automodule:: GEMstack.offboard.prediction_learning + :members: + :undoc-members: + :show-inheritance: diff --git a/docs/GEMstack.onboard.execution.rst b/docs/GEMstack.onboard.execution.rst new file mode 100644 index 000000000..f0e971761 --- /dev/null +++ b/docs/GEMstack.onboard.execution.rst @@ -0,0 +1,45 @@ +GEMstack.onboard.execution package +================================== + +Submodules +---------- + +GEMstack.onboard.execution.entrypoint module +-------------------------------------------- + +.. automodule:: GEMstack.onboard.execution.entrypoint + :members: + :undoc-members: + :show-inheritance: + +GEMstack.onboard.execution.execution module +------------------------------------------- + +.. automodule:: GEMstack.onboard.execution.execution + :members: + :undoc-members: + :show-inheritance: + +GEMstack.onboard.execution.log\_replay module +--------------------------------------------- + +.. automodule:: GEMstack.onboard.execution.log_replay + :members: + :undoc-members: + :show-inheritance: + +GEMstack.onboard.execution.multiprocess\_execution module +--------------------------------------------------------- + +.. automodule:: GEMstack.onboard.execution.multiprocess_execution + :members: + :undoc-members: + :show-inheritance: + +Module contents +--------------- + +.. automodule:: GEMstack.onboard.execution + :members: + :undoc-members: + :show-inheritance: diff --git a/docs/GEMstack.onboard.interface.rst b/docs/GEMstack.onboard.interface.rst new file mode 100644 index 000000000..af4750836 --- /dev/null +++ b/docs/GEMstack.onboard.interface.rst @@ -0,0 +1,37 @@ +GEMstack.onboard.interface package +================================== + +Submodules +---------- + +GEMstack.onboard.interface.gem module +------------------------------------- + +.. automodule:: GEMstack.onboard.interface.gem + :members: + :undoc-members: + :show-inheritance: + +GEMstack.onboard.interface.gem\_hardware module +----------------------------------------------- + +.. automodule:: GEMstack.onboard.interface.gem_hardware + :members: + :undoc-members: + :show-inheritance: + +GEMstack.onboard.interface.gem\_simulator module +------------------------------------------------ + +.. automodule:: GEMstack.onboard.interface.gem_simulator + :members: + :undoc-members: + :show-inheritance: + +Module contents +--------------- + +.. automodule:: GEMstack.onboard.interface + :members: + :undoc-members: + :show-inheritance: diff --git a/docs/GEMstack.onboard.perception.rst b/docs/GEMstack.onboard.perception.rst new file mode 100644 index 000000000..216efbf1a --- /dev/null +++ b/docs/GEMstack.onboard.perception.rst @@ -0,0 +1,37 @@ +GEMstack.onboard.perception package +=================================== + +Submodules +---------- + +GEMstack.onboard.perception.perception\_normalization module +------------------------------------------------------------ + +.. automodule:: GEMstack.onboard.perception.perception_normalization + :members: + :undoc-members: + :show-inheritance: + +GEMstack.onboard.perception.roadgraph\_update module +---------------------------------------------------- + +.. automodule:: GEMstack.onboard.perception.roadgraph_update + :members: + :undoc-members: + :show-inheritance: + +GEMstack.onboard.perception.state\_estimation module +---------------------------------------------------- + +.. automodule:: GEMstack.onboard.perception.state_estimation + :members: + :undoc-members: + :show-inheritance: + +Module contents +--------------- + +.. automodule:: GEMstack.onboard.perception + :members: + :undoc-members: + :show-inheritance: diff --git a/docs/GEMstack.onboard.planning.rst b/docs/GEMstack.onboard.planning.rst new file mode 100644 index 000000000..7c4d8df2d --- /dev/null +++ b/docs/GEMstack.onboard.planning.rst @@ -0,0 +1,45 @@ +GEMstack.onboard.planning package +================================= + +Submodules +---------- + +GEMstack.onboard.planning.motion\_planning module +------------------------------------------------- + +.. automodule:: GEMstack.onboard.planning.motion_planning + :members: + :undoc-members: + :show-inheritance: + +GEMstack.onboard.planning.pure\_pursuit module +---------------------------------------------- + +.. automodule:: GEMstack.onboard.planning.pure_pursuit + :members: + :undoc-members: + :show-inheritance: + +GEMstack.onboard.planning.recovery module +----------------------------------------- + +.. automodule:: GEMstack.onboard.planning.recovery + :members: + :undoc-members: + :show-inheritance: + +GEMstack.onboard.planning.route\_planning module +------------------------------------------------ + +.. automodule:: GEMstack.onboard.planning.route_planning + :members: + :undoc-members: + :show-inheritance: + +Module contents +--------------- + +.. automodule:: GEMstack.onboard.planning + :members: + :undoc-members: + :show-inheritance: diff --git a/docs/GEMstack.rst b/docs/GEMstack.rst new file mode 100644 index 000000000..c38e116ce --- /dev/null +++ b/docs/GEMstack.rst @@ -0,0 +1,23 @@ +GEMstack package +================ + +Subpackages +----------- + +.. toctree:: + :maxdepth: 4 + + GEMstack.knowledge + GEMstack.mathutils + GEMstack.offboard + GEMstack.onboard + GEMstack.state + GEMstack.utils + +Module contents +--------------- + +.. automodule:: GEMstack + :members: + :undoc-members: + :show-inheritance: diff --git a/docs/api.rst b/docs/api.rst index 810d47715..c45389721 100644 --- a/docs/api.rst +++ b/docs/api.rst @@ -5,9 +5,4 @@ API :toctree: generated :caption: Contents: - GEMstack.mathutils - GEMstack.utils - GEMstack.state - GEMstack.knowledge - GEMstack.onboard - GEMstack.offboard + GEMstack diff --git a/docs/modules.rst b/docs/modules.rst new file mode 100644 index 000000000..8ad77ca33 --- /dev/null +++ b/docs/modules.rst @@ -0,0 +1,7 @@ +GEMstack +======== + +.. toctree:: + :maxdepth: 4 + + GEMstack From b998a1eb1412718166abe0e62b29e8d62aec9f6a Mon Sep 17 00:00:00 2001 From: krishauser Date: Sat, 23 Dec 2023 17:20:26 -0500 Subject: [PATCH 012/232] Fixed docs to actually generate code. Added docstrings --- .gitignore | 3 - GEMstack/knowledge/__init__.py | 7 + GEMstack/knowledge/defaults/__init__.py | 6 +- GEMstack/knowledge/predicates/predicate.py | 4 +- GEMstack/mathutils/control.py | 7 +- GEMstack/mathutils/units.py | 43 ++++++ GEMstack/offboard/__init__.py | 1 + GEMstack/onboard/__init__.py | 4 + GEMstack/onboard/execution/__init__.py | 1 + GEMstack/onboard/execution/entrypoint.py | 4 +- GEMstack/onboard/execution/execution.py | 64 ++++++-- GEMstack/onboard/interface/__init__.py | 1 + GEMstack/onboard/planning/__init__.py | 1 + GEMstack/state/__init__.py | 5 + GEMstack/state/physical_object.py | 3 + GEMstack/utils/__init__.py | 1 + GEMstack/utils/settings.py | 2 +- README.md | 4 +- docs/GEMstack.knowledge.rst | 8 - docs/GEMstack.mathutils.rst | 8 - docs/GEMstack.offboard.rst | 8 - docs/GEMstack.onboard.rst | 8 - docs/GEMstack.state.rst | 8 - docs/GEMstack.utils.rst | 8 - docs/Makefile | 3 + docs/api.rst | 10 +- docs/conf.py | 11 +- .../GEMstack.knowledge.calibration.rst | 3 - .../GEMstack.knowledge.defaults.rst | 3 - .../GEMstack.knowledge.detection.rst | 3 - .../GEMstack.knowledge.heuristics.rst | 3 - .../GEMstack.knowledge.predicates.rst | 13 +- .../GEMstack.knowledge.prediction.rst | 3 - .../GEMstack.knowledge.roadmaps.geofences.rst | 3 - .../GEMstack.knowledge.roadmaps.rst | 15 +- .../GEMstack.knowledge.routes.rst | 3 - docs/source/GEMstack.knowledge.rst | 23 +++ .../GEMstack.knowledge.vehicle.rst | 13 +- docs/source/GEMstack.mathutils.rst | 74 +++++++++ .../GEMstack.offboard.calibration.rst | 3 - .../GEMstack.offboard.detection_learning.rst | 3 - .../GEMstack.offboard.heuristic_learning.rst | 3 - .../GEMstack.offboard.log_management.rst | 3 - .../GEMstack.offboard.prediction_learning.rst | 3 - docs/source/GEMstack.offboard.rst | 19 +++ .../GEMstack.onboard.execution.rst | 13 +- .../GEMstack.onboard.interface.rst | 13 +- .../GEMstack.onboard.perception.rst | 13 +- .../GEMstack.onboard.planning.rst | 13 +- docs/source/GEMstack.onboard.rst | 29 ++++ docs/{ => source}/GEMstack.rst | 15 +- docs/source/GEMstack.state.rst | 146 ++++++++++++++++++ docs/source/GEMstack.utils.rst | 50 ++++++ docs/{ => source}/modules.rst | 2 +- 54 files changed, 537 insertions(+), 183 deletions(-) delete mode 100644 docs/GEMstack.knowledge.rst delete mode 100644 docs/GEMstack.mathutils.rst delete mode 100644 docs/GEMstack.offboard.rst delete mode 100644 docs/GEMstack.onboard.rst delete mode 100644 docs/GEMstack.state.rst delete mode 100644 docs/GEMstack.utils.rst rename docs/{ => source}/GEMstack.knowledge.calibration.rst (84%) rename docs/{ => source}/GEMstack.knowledge.defaults.rst (83%) rename docs/{ => source}/GEMstack.knowledge.detection.rst (84%) rename docs/{ => source}/GEMstack.knowledge.heuristics.rst (84%) rename docs/{ => source}/GEMstack.knowledge.predicates.rst (94%) rename docs/{ => source}/GEMstack.knowledge.prediction.rst (84%) rename docs/{ => source}/GEMstack.knowledge.roadmaps.geofences.rst (85%) rename docs/{ => source}/GEMstack.knowledge.roadmaps.rst (83%) rename docs/{ => source}/GEMstack.knowledge.routes.rst (83%) create mode 100644 docs/source/GEMstack.knowledge.rst rename docs/{ => source}/GEMstack.knowledge.vehicle.rst (94%) create mode 100644 docs/source/GEMstack.mathutils.rst rename docs/{ => source}/GEMstack.offboard.calibration.rst (84%) rename docs/{ => source}/GEMstack.offboard.detection_learning.rst (85%) rename docs/{ => source}/GEMstack.offboard.heuristic_learning.rst (85%) rename docs/{ => source}/GEMstack.offboard.log_management.rst (85%) rename docs/{ => source}/GEMstack.offboard.prediction_learning.rst (86%) create mode 100644 docs/source/GEMstack.offboard.rst rename docs/{ => source}/GEMstack.onboard.execution.rst (96%) rename docs/{ => source}/GEMstack.onboard.interface.rst (95%) rename docs/{ => source}/GEMstack.onboard.perception.rst (96%) rename docs/{ => source}/GEMstack.onboard.planning.rst (96%) create mode 100644 docs/source/GEMstack.onboard.rst rename docs/{ => source}/GEMstack.rst (84%) create mode 100644 docs/source/GEMstack.state.rst create mode 100644 docs/source/GEMstack.utils.rst rename docs/{ => source}/modules.rst (73%) diff --git a/.gitignore b/.gitignore index d5438b697..68bc17f9f 100644 --- a/.gitignore +++ b/.gitignore @@ -6,9 +6,6 @@ __pycache__/ # C extensions *.so -# auto-generated Sphinx api docs -/docs/generated - # Distribution / packaging .Python build/ diff --git a/GEMstack/knowledge/__init__.py b/GEMstack/knowledge/__init__.py index e69de29bb..cbbabe345 100644 --- a/GEMstack/knowledge/__init__.py +++ b/GEMstack/knowledge/__init__.py @@ -0,0 +1,7 @@ +"""Models and parameters common to onboard / offboard use. This module does +not contain too much code, but rather stores configuration files and model +parameters. + +The file "current.yaml / "current.py" / "current.pkl" in each directory will +store the current configuration / model being used. +""" \ No newline at end of file diff --git a/GEMstack/knowledge/defaults/__init__.py b/GEMstack/knowledge/defaults/__init__.py index eb94606e6..ee5354a7c 100644 --- a/GEMstack/knowledge/defaults/__init__.py +++ b/GEMstack/knowledge/defaults/__init__.py @@ -1,3 +1,7 @@ from ...utils.config import load_config_recursive import os -SETTINGS = load_config_recursive(os.path.join(os.path.split(__file__)[0],'current.yaml')) +SETTINGS_FILE = os.path.join(os.path.split(__file__)[0],'current.yaml') +print("**************************************************************") +print("Loading default settings from",SETTINGS_FILE) +print("**************************************************************") +SETTINGS = load_config_recursive(SETTINGS_FILE) diff --git a/GEMstack/knowledge/predicates/predicate.py b/GEMstack/knowledge/predicates/predicate.py index b153ecfa2..63f04a13c 100644 --- a/GEMstack/knowledge/predicates/predicate.py +++ b/GEMstack/knowledge/predicates/predicate.py @@ -3,8 +3,8 @@ The PredicateBase class is the base class for all predicates and can be composed, serialized, and deserialized. You can compose predicates using -the and_, all_, or_, any_, and not_ functions. You can also compare numeric -predicates to one another using ==, !=, <, <=, >, and >=. +the `and_`, `all_`, `or_`, `any_`, and `not_` functions. You can also +compare numeric predicates to one another using ==, !=, <, <=, >, and >=. Predicates can be placed in this folder, and they need a unique name. By default, each predicate is named after its class name. You can override diff --git a/GEMstack/mathutils/control.py b/GEMstack/mathutils/control.py index 7d161f12c..2b76dafcb 100644 --- a/GEMstack/mathutils/control.py +++ b/GEMstack/mathutils/control.py @@ -24,6 +24,7 @@ def __init__(self, kp : float, ki : float, kd : float, windup_limit : float = No self.derror = 0.0 #differenced error, for debugging def reset(self): + """Resets the controller to its initial state.""" self.iterm = 0.0 self.last_e = 0.0 self.last_t = None @@ -34,7 +35,8 @@ def advance(self, t : float = None, dt : float = None, feedforward_term : float = 0) -> float: - """Parameters: + """ + Parameters: e (float): error de (optional, float): error derivative. If not provided, will be computed via finite differences. @@ -44,6 +46,7 @@ def advance(self, for the D or I term to have any effect. feedforward_term (optional, float): feedforward term to add to the output. Defaults to 0. + """ if de is None: if dt is None: @@ -75,5 +78,5 @@ def advance(self, self.last_t = t self.derror = de - print(feedforward_term,self.kp,e,self.ki,self.iterm,self.kd,de) + #print(feedforward_term,self.kp,e,self.ki,self.iterm,self.kd,de) return feedforward_term + self.kp * e + self.ki * self.iterm + self.kd * de diff --git a/GEMstack/mathutils/units.py b/GEMstack/mathutils/units.py index 7c58595e4..7b348b1dc 100644 --- a/GEMstack/mathutils/units.py +++ b/GEMstack/mathutils/units.py @@ -1,10 +1,53 @@ +DEFAULT_DISTANCE_UNIT = 'm' +"""Default distance unit is meters""" + +DEFAULT_TIME_UNIT = 's' +"""Default time unit is seconds""" + +DEFAULT_SPEED_UNIT = 'm/s' +"""Default speed unit is meters per second""" + +DEFAULT_ANGLE_UNIT = 'rad' +"""Default angle unit is radians""" + +DEFAULT_ANGLE_RATE_UNIT = 'rad/s' +"""Default angle rate unit is radians per second""" + +DEFAULT_WEIGHT_UNIT = 'kg' +"""Default weight unit is kilograms""" + +DEFAULT_FORCE_UNIT = 'N' +"""Default force unit is Newtons""" + + M_TO_FT = 3.28084 +"""Meters to feet conversion factor""" + FT_TO_M = 1.0 / M_TO_FT +"""Feet to meters conversion factor""" + MPS_TO_MPH = 2.23694 +"""Meters per second to miles per hour conversion factor""" + MPH_TO_MPS = 1.0 / MPS_TO_MPH +"""Miles per hour to meters per second conversion factor""" + MPS_TO_KPH = 3.6 +"""Meters per second to km per hour conversion factor""" + KPH_TO_MPS = 1.0 / MPS_TO_KPH +"""Km per hour to meters per second conversion factor""" + KG_TO_LBS = 2.20462 +"""Kilograms to pounds conversion factor""" + LBS_TO_KG = 1.0 / KG_TO_LBS +"""Pounds to kilograms conversion factor""" + DEG_TO_RAD = 0.0174533 +"""Degrees to radians conversion factor""" + RAD_TO_DEG = 1.0 / DEG_TO_RAD +"""Radians to degrees conversion factor""" + + diff --git a/GEMstack/offboard/__init__.py b/GEMstack/offboard/__init__.py index e69de29bb..4cd8b0dac 100644 --- a/GEMstack/offboard/__init__.py +++ b/GEMstack/offboard/__init__.py @@ -0,0 +1 @@ +"""Programs for creation and management of data and knowledge.""" \ No newline at end of file diff --git a/GEMstack/onboard/__init__.py b/GEMstack/onboard/__init__.py index e69de29bb..5f5d44fbe 100644 --- a/GEMstack/onboard/__init__.py +++ b/GEMstack/onboard/__init__.py @@ -0,0 +1,4 @@ +"""All algorithms governing onboard behavior are located here. + +These algorithms may make use of items in the `GEMstack/knowledge/` folder. +""" \ No newline at end of file diff --git a/GEMstack/onboard/execution/__init__.py b/GEMstack/onboard/execution/__init__.py index e69de29bb..1a98fc783 100644 --- a/GEMstack/onboard/execution/__init__.py +++ b/GEMstack/onboard/execution/__init__.py @@ -0,0 +1 @@ +"""Executes the onboard driving behavior.""" \ No newline at end of file diff --git a/GEMstack/onboard/execution/entrypoint.py b/GEMstack/onboard/execution/entrypoint.py index debc36189..b5f8de62b 100644 --- a/GEMstack/onboard/execution/entrypoint.py +++ b/GEMstack/onboard/execution/entrypoint.py @@ -1,6 +1,6 @@ from ...utils import settings,config from ..component import Component -from .execution import EXECUTION_PREFIX,ExecutorBase +from .execution import EXECUTION_PREFIX,ExecutorBase,load_computation_graph from .log_replay import LogReplay import importlib from typing import Dict,List,Optional @@ -53,12 +53,14 @@ def make_class(config_info, component_module, parent_module=None, extra_args = N def main(): + """The main entrypoint for the execution stack.""" runconfig = settings.get('run') mode = settings.get('run.mode') vehicle_interface_settings = settings.get('run.vehicle_interface') mission_executor_settings = settings.get('run.mission_execution') log_settings = settings.get('run.log',{}) replay_settings = settings.get('run.replay',{}) + load_computation_graph() #create top-level components vehicle_interface = make_class(vehicle_interface_settings,'default','GEMstack.onboard.interface') diff --git a/GEMstack/onboard/execution/execution.py b/GEMstack/onboard/execution/execution.py index 0baa67440..39f0029fe 100644 --- a/GEMstack/onboard/execution/execution.py +++ b/GEMstack/onboard/execution/execution.py @@ -40,9 +40,17 @@ def normalize_computation_graph(components : list) -> List[Dict]: normalized_components.append({k:v}) return normalized_components -COMPONENTS = normalize_computation_graph(settings.get('run.computation_graph.components')) -COMPONENT_ORDER = [list(c.keys())[0] for c in COMPONENTS] -COMPONENT_SETTINGS = dict(list(c.items())[0] for c in COMPONENTS) +COMPONENTS = None +COMPONENT_ORDER = None +COMPONENT_SETTINGS = None + +def load_computation_graph(): + """Loads the computation graph from settings[run.computation_graph.components] + and sets global variables COMPONENTS, COMPONENT_ORDER, and COMPONENT_SETTINGS.""" + global COMPONENTS, COMPONENT_ORDER, COMPONENT_SETTINGS + COMPONENTS = normalize_computation_graph(settings.get('run.computation_graph.components')) + COMPONENT_ORDER = [list(c.keys())[0] for c in COMPONENTS] + COMPONENT_SETTINGS = dict(list(c.items())[0] for c in COMPONENTS) def validate_components(components : Dict[str,Component], provided : List = None): @@ -170,10 +178,14 @@ def __init__(self, vehicle_interface): self.behavior_log = None self.vehicle_log_t_last = None self.run_metadata = dict() # type: dict + self.run_metadata['pipelines'] = [] + self.run_metadata['events'] = [] + self.run_metadata['exit_reason'] = 'unknown' self.last_loop_time = time.time() def begin(self): - """Override me to do any initialization""" + """Override me to do any initialization. The vehicle will have + already been started and sensors will have been validated.""" pass def update(self, state : AllState) -> Optional[str]: @@ -183,9 +195,12 @@ def update(self, state : AllState) -> Optional[str]: return None def done(self): + """Override me to implement mission completion logic.""" return False def end(self): + """Override me to do any mission cleanup. This will be called before + the vehicle is stopped.""" pass def add_pipeline(self,name : str, perception : Dict[str,Component], planning : Dict[str,Component], other : Dict[str,Component]): @@ -234,11 +249,27 @@ def log_state(self,state_attributes : List[str], rate : Optional[float]=None): self.state_log = Logfile(os.path.join(self.log_folder,'state.json'),delta_format=False,mode='w') def dump_log_metadata(self): + if not self.log_folder: + return import os from ...utils import config config.save_config(os.path.join(self.log_folder,'meta.yaml'),self.run_metadata) + + def event(self,event_description : str, event_print_string : str = None): + """Logs an event to the metadata and prints a message to the console.""" + if event_print_string is None: + event_print_string = event_description if event_description.endswith('.') else event_description + '.' + self.run_metadata['events'].append({'time':time.time(),'vehicle_time':self.state.t,'description':event_description}) + print(EXECUTION_PREFIX,event_print_string) + self.dump_log_metadata() + + def set_exit_reason(self, description): + """Sets a main loop exit reason""" + self.run_metadata['exit_reason'] = description + self.dump_log_metadata() def run(self): + """Main entry point. Runs the mission execution loop.""" if self.current_pipeline not in self.pipelines: print(EXECUTION_PREFIX,"Pipeline {} not found".format(self.current_pipeline)) return @@ -260,10 +291,13 @@ def run(self): validated = False try: - self.validate_sensors() - validated = True + validated = self.validate_sensors() + if not validated: + self.event("Sensor validation failed","Could not validate sensors, stopping components and exiting") + self.set_exit_reason("Sensor validation failed") except KeyboardInterrupt: - print(EXECUTION_PREFIX,"Could not validate sensors, stopping components and exiting") + self.event("Ctrl+C interrupt during sensor validation","Could not validate sensors, stopping components and exiting") + self.set_exit_reason("Sensor validation failed") if time.time() - self.last_loop_time > 0.5: print(EXECUTION_PREFIX,"A component may have hung. Traceback:") import traceback @@ -272,11 +306,15 @@ def run(self): if validated: self.begin() while validated: + self.run_metadata['pipelines'].append({'time':time.time(),'vehicle_time':self.state.t,'name':self.current_pipeline}) + self.dump_log_metadata() try: print(EXECUTION_PREFIX,"Executing pipeline {}".format(self.current_pipeline)) next = self.run_until_switch() if next is None: #done + if self.run_metadata['exit_reason'] == 'unknown': + self.set_exit_reason("normal exit") break if next not in self.pipelines: print(EXECUTION_PREFIX,"Pipeline {} not found, switching to recovery".format(next)) @@ -286,10 +324,11 @@ def run(self): print("************************************************") print(" Recovery pipeline is not working, exiting! ") print("************************************************") + self.set_exit_reason("recovery pipeline not working") break self.current_pipeline = next if not self.validate_sensors(1): - print(EXECUTION_PREFIX,"Sensors in desired pipeline {} are not working, switching to recovery".format(self.current_pipeline)) + self.event("Sensors in desired pipeline {} are not working, switching to recovery".format(self.current_pipeline)) self.current_pipeline = 'recovery' except KeyboardInterrupt: if self.current_pipeline == 'recovery': @@ -297,9 +336,10 @@ def run(self): print("************************************************") print(" Ctrl+C interrupt during recovery, exiting! ") print("************************************************") + self.set_exit_reason("Ctrl+C interrupt during recovery") break self.current_pipeline = 'recovery' - print(EXECUTION_PREFIX,"Ctrl+C pressed, switching to recovery mode.") + self.event("Ctrl+C pressed, switching to recovery mode") if time.time() - self.last_loop_time > 0.5: print(EXECUTION_PREFIX,"A component may have hung. Traceback:") import traceback @@ -307,7 +347,7 @@ def run(self): if validated: self.end() #done with mission - print(EXECUTION_PREFIX,"Done with mission execution, stopping components and exiting") + self.event("Mission execution ended","Done with mission execution, stopping components and exiting") for (name,(perception_components,planning_components,other_components)) in self.pipelines.items(): for (k,c) in perception_components.items(): @@ -323,9 +363,10 @@ def run(self): if self.behavior_log: self.behavior_log.close() self.behavior_log = None + def validate_sensors(self,numsteps=None): - #verify sensors are working + """Verifies sensors are working""" (perception_components,planning_components,other_components) = self.pipelines[self.current_pipeline] dt_min = min([c.dt for c in perception_components.values()]) if self.log_state_rate is not None: @@ -348,6 +389,7 @@ def validate_sensors(self,numsteps=None): return True def run_until_switch(self): + """Runs a pipeline until a switch is requested.""" if self.current_pipeline == 'recovery': self.state.mission.type = MissionEnum.RECOVERY_STOP diff --git a/GEMstack/onboard/interface/__init__.py b/GEMstack/onboard/interface/__init__.py index e69de29bb..83982aa32 100644 --- a/GEMstack/onboard/interface/__init__.py +++ b/GEMstack/onboard/interface/__init__.py @@ -0,0 +1 @@ +"""Defines interfaces to vehicle hardware and simulators.""" \ No newline at end of file diff --git a/GEMstack/onboard/planning/__init__.py b/GEMstack/onboard/planning/__init__.py index e69de29bb..a1e3a0f2c 100644 --- a/GEMstack/onboard/planning/__init__.py +++ b/GEMstack/onboard/planning/__init__.py @@ -0,0 +1 @@ +"""Planning components.""" \ No newline at end of file diff --git a/GEMstack/state/__init__.py b/GEMstack/state/__init__.py index 1b957715f..1aa764123 100644 --- a/GEMstack/state/__init__.py +++ b/GEMstack/state/__init__.py @@ -1,3 +1,8 @@ +"""Representations of state of the vehicle and its environment. + +Most significant is the :class:`AllState` object, which declares all internal +state of the behavior stack that persists from step to step. +""" __all__ = ['PhysicalObject','ObjectPose','ObjectFrameEnum', 'Path','Trajectory', 'VehicleState', diff --git a/GEMstack/state/physical_object.py b/GEMstack/state/physical_object.py index 25a7d9bd3..fa245429d 100644 --- a/GEMstack/state/physical_object.py +++ b/GEMstack/state/physical_object.py @@ -21,6 +21,7 @@ class ObjectPose: Represents a hypothetical object position / orientation. Attributes: + frame: the frame of reference for the pose. t: if frame=GLOBAL or ABSOLUTE_CARTESIAN, the time in s since the epoch, i.e., time.time() Otherwise, the time since start / current in the future, in s @@ -34,6 +35,7 @@ class ObjectPose: CCW yaw. pitch: the optional pitch, in radians and around left direction in the object's frame roll: the optional roll, in radians and around forward direction in the object's frame + """ frame : ObjectFrameEnum t : float @@ -177,6 +179,7 @@ class PhysicalObject: of the object. outline: an optional list of vertices in CCW order denoting the object's outline polygon in its local frame (x:forward, y:left). + """ pose : ObjectPose dimensions : Tuple[float,float,float] diff --git a/GEMstack/utils/__init__.py b/GEMstack/utils/__init__.py index e69de29bb..c2a292489 100644 --- a/GEMstack/utils/__init__.py +++ b/GEMstack/utils/__init__.py @@ -0,0 +1 @@ +"""Other utilities common to onboard / offboard use.""" \ No newline at end of file diff --git a/GEMstack/utils/settings.py b/GEMstack/utils/settings.py index eef657800..3845de515 100644 --- a/GEMstack/utils/settings.py +++ b/GEMstack/utils/settings.py @@ -52,7 +52,7 @@ def get(path : Union[str,List[str]], defaultValue=KeyError) -> Any: return val except KeyError: if defaultValue is KeyError: - print("Available keys:",val.keys()) + print("settings.py: Unable to get",path,"available keys:",val.keys()) raise return defaultValue diff --git a/README.md b/README.md index 097959e96..13632ec94 100644 --- a/README.md +++ b/README.md @@ -57,7 +57,7 @@ All packages are within the `GEMstack/` folder. - `route`: Stores a 2d route, coming from the router. - `all`: State or the current scene, all intent and relation estimates, and the driving logic (objective, predicates, route). -`offboard/`: Creation and management of data and knowledge. +`offboard/`: Programs for creation and management of data and knowledge. - `calibration/`: Sensor calibration. - `log_management/`: Provides log management, browsing, and query functionality. - `detection_learning/`: Detection model learning. @@ -105,7 +105,7 @@ All packages are within the `GEMstack/` folder. - `executor`: Base classes for executors. - `log_replay`: A generic component that replays from a log. - - `interface/`: Defines interfaces to vehicle hardware / simulators / external signals + - `interface/`: Defines interfaces to vehicle hardware and simulators. - `gem.py`: Base class for the Polaris GEM e2 vehicle. - `gem_hardware.py`: Interface to the real GEM vehicle. - `gem_simulator.py`: Interfaces to simulated GEM vehicles. diff --git a/docs/GEMstack.knowledge.rst b/docs/GEMstack.knowledge.rst deleted file mode 100644 index f10dfd729..000000000 --- a/docs/GEMstack.knowledge.rst +++ /dev/null @@ -1,8 +0,0 @@ -GEMstack.knowledge package -========================== - -.. autosummary:: - :toctree: generated - :caption: Contents: - - GEMstack.knowledge \ No newline at end of file diff --git a/docs/GEMstack.mathutils.rst b/docs/GEMstack.mathutils.rst deleted file mode 100644 index 1ec603841..000000000 --- a/docs/GEMstack.mathutils.rst +++ /dev/null @@ -1,8 +0,0 @@ -GEMstack.mathutils package -========================== - -.. autosummary:: - :toctree: generated - :caption: Contents: - - GEMstack.mathutils \ No newline at end of file diff --git a/docs/GEMstack.offboard.rst b/docs/GEMstack.offboard.rst deleted file mode 100644 index 7b04583a2..000000000 --- a/docs/GEMstack.offboard.rst +++ /dev/null @@ -1,8 +0,0 @@ -GEMstack.offboard package -========================== - -.. autosummary:: - :toctree: generated - :caption: Contents: - - GEMstack.offboard \ No newline at end of file diff --git a/docs/GEMstack.onboard.rst b/docs/GEMstack.onboard.rst deleted file mode 100644 index ed7653c82..000000000 --- a/docs/GEMstack.onboard.rst +++ /dev/null @@ -1,8 +0,0 @@ -GEMstack.onboard package -========================== - -.. autosummary:: - :toctree: generated - :caption: Contents: - - GEMstack.onboard \ No newline at end of file diff --git a/docs/GEMstack.state.rst b/docs/GEMstack.state.rst deleted file mode 100644 index 1c6b8a296..000000000 --- a/docs/GEMstack.state.rst +++ /dev/null @@ -1,8 +0,0 @@ -GEMstack.state package -========================== - -.. autosummary:: - :toctree: generated - :caption: Contents: - - GEMstack.state \ No newline at end of file diff --git a/docs/GEMstack.utils.rst b/docs/GEMstack.utils.rst deleted file mode 100644 index 9c0f1db06..000000000 --- a/docs/GEMstack.utils.rst +++ /dev/null @@ -1,8 +0,0 @@ -GEMstack.utils package -========================== - -.. autosummary:: - :toctree: generated - :caption: Contents: - - GEMstack.utils \ No newline at end of file diff --git a/docs/Makefile b/docs/Makefile index d4bb2cbb9..6df2745b0 100644 --- a/docs/Makefile +++ b/docs/Makefile @@ -18,3 +18,6 @@ help: # "make mode" option. $(O) is meant as a shortcut for $(SPHINXOPTS). %: Makefile @$(SPHINXBUILD) -M $@ "$(SOURCEDIR)" "$(BUILDDIR)" $(SPHINXOPTS) $(O) + +module_source: + sphinx-apidoc -o source/ -M -d 2 ../GEMstack diff --git a/docs/api.rst b/docs/api.rst index c45389721..264f2fc5c 100644 --- a/docs/api.rst +++ b/docs/api.rst @@ -1,8 +1,4 @@ -API -=== +API Documentation +================= -.. autosummary:: - :toctree: generated - :caption: Contents: - - GEMstack +See :doc:`source/GEMstack` \ No newline at end of file diff --git a/docs/conf.py b/docs/conf.py index a0fc05b9d..06f60d2cf 100644 --- a/docs/conf.py +++ b/docs/conf.py @@ -13,7 +13,9 @@ # import os # import sys # sys.path.insert(0, os.path.abspath('.')) - +import os +import sys +sys.path.insert(0, os.path.abspath('../')) # -- Project information ----------------------------------------------------- @@ -31,8 +33,9 @@ "sphinx.ext.autodoc", "sphinx.ext.autosummary", "sphinx.ext.intersphinx", + 'sphinx.ext.napoleon', ] - + intersphinx_mapping = { "rtd": ("https://docs.readthedocs.io/en/stable/", None), "python": ("https://docs.python.org/3/", None), @@ -40,6 +43,10 @@ } intersphinx_disabled_domains = ["std"] +napoleon_google_docstring = True +napoleon_use_param = False +napoleon_use_ivar = True + templates_path = ["_templates"] # -- Options for EPUB output diff --git a/docs/GEMstack.knowledge.calibration.rst b/docs/source/GEMstack.knowledge.calibration.rst similarity index 84% rename from docs/GEMstack.knowledge.calibration.rst rename to docs/source/GEMstack.knowledge.calibration.rst index ef1dd5a16..5ad29d6ea 100644 --- a/docs/GEMstack.knowledge.calibration.rst +++ b/docs/source/GEMstack.knowledge.calibration.rst @@ -1,9 +1,6 @@ GEMstack.knowledge.calibration package ====================================== -Module contents ---------------- - .. automodule:: GEMstack.knowledge.calibration :members: :undoc-members: diff --git a/docs/GEMstack.knowledge.defaults.rst b/docs/source/GEMstack.knowledge.defaults.rst similarity index 83% rename from docs/GEMstack.knowledge.defaults.rst rename to docs/source/GEMstack.knowledge.defaults.rst index eb67023a1..b62fac731 100644 --- a/docs/GEMstack.knowledge.defaults.rst +++ b/docs/source/GEMstack.knowledge.defaults.rst @@ -1,9 +1,6 @@ GEMstack.knowledge.defaults package =================================== -Module contents ---------------- - .. automodule:: GEMstack.knowledge.defaults :members: :undoc-members: diff --git a/docs/GEMstack.knowledge.detection.rst b/docs/source/GEMstack.knowledge.detection.rst similarity index 84% rename from docs/GEMstack.knowledge.detection.rst rename to docs/source/GEMstack.knowledge.detection.rst index 878e04ea4..c8d2c9d88 100644 --- a/docs/GEMstack.knowledge.detection.rst +++ b/docs/source/GEMstack.knowledge.detection.rst @@ -1,9 +1,6 @@ GEMstack.knowledge.detection package ==================================== -Module contents ---------------- - .. automodule:: GEMstack.knowledge.detection :members: :undoc-members: diff --git a/docs/GEMstack.knowledge.heuristics.rst b/docs/source/GEMstack.knowledge.heuristics.rst similarity index 84% rename from docs/GEMstack.knowledge.heuristics.rst rename to docs/source/GEMstack.knowledge.heuristics.rst index 97693b167..66943e8ee 100644 --- a/docs/GEMstack.knowledge.heuristics.rst +++ b/docs/source/GEMstack.knowledge.heuristics.rst @@ -1,9 +1,6 @@ GEMstack.knowledge.heuristics package ===================================== -Module contents ---------------- - .. automodule:: GEMstack.knowledge.heuristics :members: :undoc-members: diff --git a/docs/GEMstack.knowledge.predicates.rst b/docs/source/GEMstack.knowledge.predicates.rst similarity index 94% rename from docs/GEMstack.knowledge.predicates.rst rename to docs/source/GEMstack.knowledge.predicates.rst index e61c8adeb..a16d08456 100644 --- a/docs/GEMstack.knowledge.predicates.rst +++ b/docs/source/GEMstack.knowledge.predicates.rst @@ -1,6 +1,11 @@ GEMstack.knowledge.predicates package ===================================== +.. automodule:: GEMstack.knowledge.predicates + :members: + :undoc-members: + :show-inheritance: + Submodules ---------- @@ -19,11 +24,3 @@ GEMstack.knowledge.predicates.predicate module :members: :undoc-members: :show-inheritance: - -Module contents ---------------- - -.. automodule:: GEMstack.knowledge.predicates - :members: - :undoc-members: - :show-inheritance: diff --git a/docs/GEMstack.knowledge.prediction.rst b/docs/source/GEMstack.knowledge.prediction.rst similarity index 84% rename from docs/GEMstack.knowledge.prediction.rst rename to docs/source/GEMstack.knowledge.prediction.rst index 0fef4fde6..08def0489 100644 --- a/docs/GEMstack.knowledge.prediction.rst +++ b/docs/source/GEMstack.knowledge.prediction.rst @@ -1,9 +1,6 @@ GEMstack.knowledge.prediction package ===================================== -Module contents ---------------- - .. automodule:: GEMstack.knowledge.prediction :members: :undoc-members: diff --git a/docs/GEMstack.knowledge.roadmaps.geofences.rst b/docs/source/GEMstack.knowledge.roadmaps.geofences.rst similarity index 85% rename from docs/GEMstack.knowledge.roadmaps.geofences.rst rename to docs/source/GEMstack.knowledge.roadmaps.geofences.rst index bab3862f6..400cac519 100644 --- a/docs/GEMstack.knowledge.roadmaps.geofences.rst +++ b/docs/source/GEMstack.knowledge.roadmaps.geofences.rst @@ -1,9 +1,6 @@ GEMstack.knowledge.roadmaps.geofences package ============================================= -Module contents ---------------- - .. automodule:: GEMstack.knowledge.roadmaps.geofences :members: :undoc-members: diff --git a/docs/GEMstack.knowledge.roadmaps.rst b/docs/source/GEMstack.knowledge.roadmaps.rst similarity index 83% rename from docs/GEMstack.knowledge.roadmaps.rst rename to docs/source/GEMstack.knowledge.roadmaps.rst index 0eac847d6..4c5bd4935 100644 --- a/docs/GEMstack.knowledge.roadmaps.rst +++ b/docs/source/GEMstack.knowledge.roadmaps.rst @@ -1,18 +1,15 @@ GEMstack.knowledge.roadmaps package =================================== +.. automodule:: GEMstack.knowledge.roadmaps + :members: + :undoc-members: + :show-inheritance: + Subpackages ----------- .. toctree:: - :maxdepth: 4 + :maxdepth: 2 GEMstack.knowledge.roadmaps.geofences - -Module contents ---------------- - -.. automodule:: GEMstack.knowledge.roadmaps - :members: - :undoc-members: - :show-inheritance: diff --git a/docs/GEMstack.knowledge.routes.rst b/docs/source/GEMstack.knowledge.routes.rst similarity index 83% rename from docs/GEMstack.knowledge.routes.rst rename to docs/source/GEMstack.knowledge.routes.rst index fddb1c03a..e0ad57e7c 100644 --- a/docs/GEMstack.knowledge.routes.rst +++ b/docs/source/GEMstack.knowledge.routes.rst @@ -1,9 +1,6 @@ GEMstack.knowledge.routes package ================================= -Module contents ---------------- - .. automodule:: GEMstack.knowledge.routes :members: :undoc-members: diff --git a/docs/source/GEMstack.knowledge.rst b/docs/source/GEMstack.knowledge.rst new file mode 100644 index 000000000..ae64e7409 --- /dev/null +++ b/docs/source/GEMstack.knowledge.rst @@ -0,0 +1,23 @@ +GEMstack.knowledge package +========================== + +.. automodule:: GEMstack.knowledge + :members: + :undoc-members: + :show-inheritance: + +Subpackages +----------- + +.. toctree:: + :maxdepth: 2 + + GEMstack.knowledge.calibration + GEMstack.knowledge.defaults + GEMstack.knowledge.detection + GEMstack.knowledge.heuristics + GEMstack.knowledge.predicates + GEMstack.knowledge.prediction + GEMstack.knowledge.roadmaps + GEMstack.knowledge.routes + GEMstack.knowledge.vehicle diff --git a/docs/GEMstack.knowledge.vehicle.rst b/docs/source/GEMstack.knowledge.vehicle.rst similarity index 94% rename from docs/GEMstack.knowledge.vehicle.rst rename to docs/source/GEMstack.knowledge.vehicle.rst index 11148abc7..b6e9c7ef0 100644 --- a/docs/GEMstack.knowledge.vehicle.rst +++ b/docs/source/GEMstack.knowledge.vehicle.rst @@ -1,6 +1,11 @@ GEMstack.knowledge.vehicle package ================================== +.. automodule:: GEMstack.knowledge.vehicle + :members: + :undoc-members: + :show-inheritance: + Submodules ---------- @@ -19,11 +24,3 @@ GEMstack.knowledge.vehicle.geometry module :members: :undoc-members: :show-inheritance: - -Module contents ---------------- - -.. automodule:: GEMstack.knowledge.vehicle - :members: - :undoc-members: - :show-inheritance: diff --git a/docs/source/GEMstack.mathutils.rst b/docs/source/GEMstack.mathutils.rst new file mode 100644 index 000000000..63ed538c5 --- /dev/null +++ b/docs/source/GEMstack.mathutils.rst @@ -0,0 +1,74 @@ +GEMstack.mathutils package +========================== + +.. automodule:: GEMstack.mathutils + :members: + :undoc-members: + :show-inheritance: + +Submodules +---------- + +GEMstack.mathutils.collisions module +------------------------------------ + +.. automodule:: GEMstack.mathutils.collisions + :members: + :undoc-members: + :show-inheritance: + +GEMstack.mathutils.control module +--------------------------------- + +.. automodule:: GEMstack.mathutils.control + :members: + :undoc-members: + :show-inheritance: + +GEMstack.mathutils.differences module +------------------------------------- + +.. automodule:: GEMstack.mathutils.differences + :members: + :undoc-members: + :show-inheritance: + +GEMstack.mathutils.dubins module +-------------------------------- + +.. automodule:: GEMstack.mathutils.dubins + :members: + :undoc-members: + :show-inheritance: + +GEMstack.mathutils.dynamics module +---------------------------------- + +.. automodule:: GEMstack.mathutils.dynamics + :members: + :undoc-members: + :show-inheritance: + +GEMstack.mathutils.signal module +-------------------------------- + +.. automodule:: GEMstack.mathutils.signal + :members: + :undoc-members: + :show-inheritance: + +GEMstack.mathutils.transforms module +------------------------------------ + +.. automodule:: GEMstack.mathutils.transforms + :members: + :undoc-members: + :show-inheritance: + +GEMstack.mathutils.units module +------------------------------- + +.. automodule:: GEMstack.mathutils.units + :members: + :undoc-members: + :show-inheritance: diff --git a/docs/GEMstack.offboard.calibration.rst b/docs/source/GEMstack.offboard.calibration.rst similarity index 84% rename from docs/GEMstack.offboard.calibration.rst rename to docs/source/GEMstack.offboard.calibration.rst index 3e2c9405e..2097d5d87 100644 --- a/docs/GEMstack.offboard.calibration.rst +++ b/docs/source/GEMstack.offboard.calibration.rst @@ -1,9 +1,6 @@ GEMstack.offboard.calibration package ===================================== -Module contents ---------------- - .. automodule:: GEMstack.offboard.calibration :members: :undoc-members: diff --git a/docs/GEMstack.offboard.detection_learning.rst b/docs/source/GEMstack.offboard.detection_learning.rst similarity index 85% rename from docs/GEMstack.offboard.detection_learning.rst rename to docs/source/GEMstack.offboard.detection_learning.rst index 363254051..c645421c2 100644 --- a/docs/GEMstack.offboard.detection_learning.rst +++ b/docs/source/GEMstack.offboard.detection_learning.rst @@ -1,9 +1,6 @@ GEMstack.offboard.detection\_learning package ============================================= -Module contents ---------------- - .. automodule:: GEMstack.offboard.detection_learning :members: :undoc-members: diff --git a/docs/GEMstack.offboard.heuristic_learning.rst b/docs/source/GEMstack.offboard.heuristic_learning.rst similarity index 85% rename from docs/GEMstack.offboard.heuristic_learning.rst rename to docs/source/GEMstack.offboard.heuristic_learning.rst index 417ba9e43..4d5778513 100644 --- a/docs/GEMstack.offboard.heuristic_learning.rst +++ b/docs/source/GEMstack.offboard.heuristic_learning.rst @@ -1,9 +1,6 @@ GEMstack.offboard.heuristic\_learning package ============================================= -Module contents ---------------- - .. automodule:: GEMstack.offboard.heuristic_learning :members: :undoc-members: diff --git a/docs/GEMstack.offboard.log_management.rst b/docs/source/GEMstack.offboard.log_management.rst similarity index 85% rename from docs/GEMstack.offboard.log_management.rst rename to docs/source/GEMstack.offboard.log_management.rst index 7be0ffc8d..c8e258a9c 100644 --- a/docs/GEMstack.offboard.log_management.rst +++ b/docs/source/GEMstack.offboard.log_management.rst @@ -1,9 +1,6 @@ GEMstack.offboard.log\_management package ========================================= -Module contents ---------------- - .. automodule:: GEMstack.offboard.log_management :members: :undoc-members: diff --git a/docs/GEMstack.offboard.prediction_learning.rst b/docs/source/GEMstack.offboard.prediction_learning.rst similarity index 86% rename from docs/GEMstack.offboard.prediction_learning.rst rename to docs/source/GEMstack.offboard.prediction_learning.rst index 1cddb7115..b2a57947c 100644 --- a/docs/GEMstack.offboard.prediction_learning.rst +++ b/docs/source/GEMstack.offboard.prediction_learning.rst @@ -1,9 +1,6 @@ GEMstack.offboard.prediction\_learning package ============================================== -Module contents ---------------- - .. automodule:: GEMstack.offboard.prediction_learning :members: :undoc-members: diff --git a/docs/source/GEMstack.offboard.rst b/docs/source/GEMstack.offboard.rst new file mode 100644 index 000000000..08fcfe3d5 --- /dev/null +++ b/docs/source/GEMstack.offboard.rst @@ -0,0 +1,19 @@ +GEMstack.offboard package +========================= + +.. automodule:: GEMstack.offboard + :members: + :undoc-members: + :show-inheritance: + +Subpackages +----------- + +.. toctree:: + :maxdepth: 2 + + GEMstack.offboard.calibration + GEMstack.offboard.detection_learning + GEMstack.offboard.heuristic_learning + GEMstack.offboard.log_management + GEMstack.offboard.prediction_learning diff --git a/docs/GEMstack.onboard.execution.rst b/docs/source/GEMstack.onboard.execution.rst similarity index 96% rename from docs/GEMstack.onboard.execution.rst rename to docs/source/GEMstack.onboard.execution.rst index f0e971761..a30f8706f 100644 --- a/docs/GEMstack.onboard.execution.rst +++ b/docs/source/GEMstack.onboard.execution.rst @@ -1,6 +1,11 @@ GEMstack.onboard.execution package ================================== +.. automodule:: GEMstack.onboard.execution + :members: + :undoc-members: + :show-inheritance: + Submodules ---------- @@ -35,11 +40,3 @@ GEMstack.onboard.execution.multiprocess\_execution module :members: :undoc-members: :show-inheritance: - -Module contents ---------------- - -.. automodule:: GEMstack.onboard.execution - :members: - :undoc-members: - :show-inheritance: diff --git a/docs/GEMstack.onboard.interface.rst b/docs/source/GEMstack.onboard.interface.rst similarity index 95% rename from docs/GEMstack.onboard.interface.rst rename to docs/source/GEMstack.onboard.interface.rst index af4750836..ec1b218ee 100644 --- a/docs/GEMstack.onboard.interface.rst +++ b/docs/source/GEMstack.onboard.interface.rst @@ -1,6 +1,11 @@ GEMstack.onboard.interface package ================================== +.. automodule:: GEMstack.onboard.interface + :members: + :undoc-members: + :show-inheritance: + Submodules ---------- @@ -27,11 +32,3 @@ GEMstack.onboard.interface.gem\_simulator module :members: :undoc-members: :show-inheritance: - -Module contents ---------------- - -.. automodule:: GEMstack.onboard.interface - :members: - :undoc-members: - :show-inheritance: diff --git a/docs/GEMstack.onboard.perception.rst b/docs/source/GEMstack.onboard.perception.rst similarity index 96% rename from docs/GEMstack.onboard.perception.rst rename to docs/source/GEMstack.onboard.perception.rst index 216efbf1a..bfdcfd294 100644 --- a/docs/GEMstack.onboard.perception.rst +++ b/docs/source/GEMstack.onboard.perception.rst @@ -1,6 +1,11 @@ GEMstack.onboard.perception package =================================== +.. automodule:: GEMstack.onboard.perception + :members: + :undoc-members: + :show-inheritance: + Submodules ---------- @@ -27,11 +32,3 @@ GEMstack.onboard.perception.state\_estimation module :members: :undoc-members: :show-inheritance: - -Module contents ---------------- - -.. automodule:: GEMstack.onboard.perception - :members: - :undoc-members: - :show-inheritance: diff --git a/docs/GEMstack.onboard.planning.rst b/docs/source/GEMstack.onboard.planning.rst similarity index 96% rename from docs/GEMstack.onboard.planning.rst rename to docs/source/GEMstack.onboard.planning.rst index 7c4d8df2d..2005e99a8 100644 --- a/docs/GEMstack.onboard.planning.rst +++ b/docs/source/GEMstack.onboard.planning.rst @@ -1,6 +1,11 @@ GEMstack.onboard.planning package ================================= +.. automodule:: GEMstack.onboard.planning + :members: + :undoc-members: + :show-inheritance: + Submodules ---------- @@ -35,11 +40,3 @@ GEMstack.onboard.planning.route\_planning module :members: :undoc-members: :show-inheritance: - -Module contents ---------------- - -.. automodule:: GEMstack.onboard.planning - :members: - :undoc-members: - :show-inheritance: diff --git a/docs/source/GEMstack.onboard.rst b/docs/source/GEMstack.onboard.rst new file mode 100644 index 000000000..c264f8718 --- /dev/null +++ b/docs/source/GEMstack.onboard.rst @@ -0,0 +1,29 @@ +GEMstack.onboard package +======================== + +.. automodule:: GEMstack.onboard + :members: + :undoc-members: + :show-inheritance: + +Subpackages +----------- + +.. toctree:: + :maxdepth: 2 + + GEMstack.onboard.execution + GEMstack.onboard.interface + GEMstack.onboard.perception + GEMstack.onboard.planning + +Submodules +---------- + +GEMstack.onboard.component module +--------------------------------- + +.. automodule:: GEMstack.onboard.component + :members: + :undoc-members: + :show-inheritance: diff --git a/docs/GEMstack.rst b/docs/source/GEMstack.rst similarity index 84% rename from docs/GEMstack.rst rename to docs/source/GEMstack.rst index c38e116ce..eb5c482bb 100644 --- a/docs/GEMstack.rst +++ b/docs/source/GEMstack.rst @@ -1,11 +1,16 @@ GEMstack package ================ +.. automodule:: GEMstack + :members: + :undoc-members: + :show-inheritance: + Subpackages ----------- .. toctree:: - :maxdepth: 4 + :maxdepth: 2 GEMstack.knowledge GEMstack.mathutils @@ -13,11 +18,3 @@ Subpackages GEMstack.onboard GEMstack.state GEMstack.utils - -Module contents ---------------- - -.. automodule:: GEMstack - :members: - :undoc-members: - :show-inheritance: diff --git a/docs/source/GEMstack.state.rst b/docs/source/GEMstack.state.rst new file mode 100644 index 000000000..6deffbd28 --- /dev/null +++ b/docs/source/GEMstack.state.rst @@ -0,0 +1,146 @@ +GEMstack.state package +====================== + +.. automodule:: GEMstack.state + :members: + :undoc-members: + :show-inheritance: + +Submodules +---------- + +GEMstack.state.agent module +--------------------------- + +.. automodule:: GEMstack.state.agent + :members: + :undoc-members: + :show-inheritance: + +GEMstack.state.agent\_intent module +----------------------------------- + +.. automodule:: GEMstack.state.agent_intent + :members: + :undoc-members: + :show-inheritance: + +GEMstack.state.all module +------------------------- + +.. automodule:: GEMstack.state.all + :members: + :undoc-members: + :show-inheritance: + +GEMstack.state.environment module +--------------------------------- + +.. automodule:: GEMstack.state.environment + :members: + :undoc-members: + :show-inheritance: + +GEMstack.state.intent module +---------------------------- + +.. automodule:: GEMstack.state.intent + :members: + :undoc-members: + :show-inheritance: + +GEMstack.state.mission module +----------------------------- + +.. automodule:: GEMstack.state.mission + :members: + :undoc-members: + :show-inheritance: + +GEMstack.state.obstacle module +------------------------------ + +.. automodule:: GEMstack.state.obstacle + :members: + :undoc-members: + :show-inheritance: + +GEMstack.state.physical\_object module +-------------------------------------- + +.. automodule:: GEMstack.state.physical_object + :members: + :undoc-members: + :show-inheritance: + +GEMstack.state.predicates module +-------------------------------- + +.. automodule:: GEMstack.state.predicates + :members: + :undoc-members: + :show-inheritance: + +GEMstack.state.relations module +------------------------------- + +.. automodule:: GEMstack.state.relations + :members: + :undoc-members: + :show-inheritance: + +GEMstack.state.roadgraph module +------------------------------- + +.. automodule:: GEMstack.state.roadgraph + :members: + :undoc-members: + :show-inheritance: + +GEMstack.state.roadmap module +----------------------------- + +.. automodule:: GEMstack.state.roadmap + :members: + :undoc-members: + :show-inheritance: + +GEMstack.state.route module +--------------------------- + +.. automodule:: GEMstack.state.route + :members: + :undoc-members: + :show-inheritance: + +GEMstack.state.scene module +--------------------------- + +.. automodule:: GEMstack.state.scene + :members: + :undoc-members: + :show-inheritance: + +GEMstack.state.sign module +-------------------------- + +.. automodule:: GEMstack.state.sign + :members: + :undoc-members: + :show-inheritance: + +GEMstack.state.trajectory module +-------------------------------- + +.. automodule:: GEMstack.state.trajectory + :members: + :undoc-members: + :show-inheritance: + +GEMstack.state.vehicle module +----------------------------- + +.. automodule:: GEMstack.state.vehicle + :members: + :undoc-members: + :show-inheritance: diff --git a/docs/source/GEMstack.utils.rst b/docs/source/GEMstack.utils.rst new file mode 100644 index 000000000..769ad29e2 --- /dev/null +++ b/docs/source/GEMstack.utils.rst @@ -0,0 +1,50 @@ +GEMstack.utils package +====================== + +.. automodule:: GEMstack.utils + :members: + :undoc-members: + :show-inheritance: + +Submodules +---------- + +GEMstack.utils.config module +---------------------------- + +.. automodule:: GEMstack.utils.config + :members: + :undoc-members: + :show-inheritance: + +GEMstack.utils.logging module +----------------------------- + +.. automodule:: GEMstack.utils.logging + :members: + :undoc-members: + :show-inheritance: + +GEMstack.utils.loops module +--------------------------- + +.. automodule:: GEMstack.utils.loops + :members: + :undoc-members: + :show-inheritance: + +GEMstack.utils.serialization module +----------------------------------- + +.. automodule:: GEMstack.utils.serialization + :members: + :undoc-members: + :show-inheritance: + +GEMstack.utils.settings module +------------------------------ + +.. automodule:: GEMstack.utils.settings + :members: + :undoc-members: + :show-inheritance: diff --git a/docs/modules.rst b/docs/source/modules.rst similarity index 73% rename from docs/modules.rst rename to docs/source/modules.rst index 8ad77ca33..8901960be 100644 --- a/docs/modules.rst +++ b/docs/source/modules.rst @@ -2,6 +2,6 @@ GEMstack ======== .. toctree:: - :maxdepth: 4 + :maxdepth: 2 GEMstack From e2a27556a031cf9dc2d234b9d8bf011b270689e6 Mon Sep 17 00:00:00 2001 From: krishauser Date: Sun, 24 Dec 2023 12:30:27 -0500 Subject: [PATCH 013/232] Added folder documentation to readme --- LICENSE | 2 +- README.md | 21 +++++++++++++++++++++ 2 files changed, 22 insertions(+), 1 deletion(-) diff --git a/LICENSE b/LICENSE index 79cdf2ea5..32638a4a1 100644 --- a/LICENSE +++ b/LICENSE @@ -1,6 +1,6 @@ MIT License -Copyright (c) 2023 krishauser +Copyright (c) 2023 University of Illinois Trustees Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal diff --git a/README.md b/README.md index 13632ec94..59e46a78d 100644 --- a/README.md +++ b/README.md @@ -16,6 +16,27 @@ You should also have the following Python dependencies installed, which you can - dacite - pyyaml + +## In this folder + +Your work will be typically confined to the `GEMstack/` folder, and you may use the `testing/`, `logs/`, `data/`, and `scenes/` folders. + +- `GEMstack/`: the software package (see [below](#package-structure)). +- `main.py`: the standard entry point to running onboard behavior (see [below](#launching-the-stack)). +- `logs/`: logs will be placed here. These will not be committed to the Github repo. +- `data/`: standard location to place datasets for training, i.e., downloaded or curated from other sources. These will not be committed to the Github repo. +- `scenes/`: standard location to place scenes for simulation. +- `testing/`: test scripts to check whether GEMstack components are functioning. +- `README.md`: this file. +- `LICENSE`: MIT license. +- `.gitignore`: Git ignore file. All files that match these patterns will not be added to Git. +- `docs/`: ReadTheDocs documentation source files are placed here. Used by automated tools to build the [online documentation](https://gemstack.readthedocs.org). +- `.readthedocs.yaml`: ReadTheDocs configuration file. +- `pyproject.toml`: Describes the GEMstack Python package for pip install. +- `requirements.txt`: A list of Python dependencies for the software stack, used via `pip install -r requirements.txt`. + +In addition, some tools (e.g., pip) will build temporary folders, such as `build` and `GEMstack.egg-info`. You can ignore these. + ## Package structure All packages are within the `GEMstack/` folder. From e7a6b63c5019669a20a9dca834406059e5fbb9da Mon Sep 17 00:00:00 2001 From: krishauser Date: Sun, 24 Dec 2023 12:39:39 -0500 Subject: [PATCH 014/232] Fixing up readme --- README.md | 25 +++++++++++++++---------- 1 file changed, 15 insertions(+), 10 deletions(-) diff --git a/README.md b/README.md index 59e46a78d..98f731a77 100644 --- a/README.md +++ b/README.md @@ -1,10 +1,16 @@ # GEMstack: software structure for CS588 Autonomous Vehicle System Engineering +[📖 Online documentation](https://gemstack.readthedocs.org) + +[🚗 About the GEM e2 vehicle](https://publish.illinois.edu/robotics-autonomy-resources/gem/) + +[🗎 ROS code for launching vehicle](https://github.com/hangcui1201/POLARIS_GEM_e2_Real/tree/main) + ## Dependencies -Python 3.7+ and ROS Noetic. It is possible to do some offline and simulation work without ROS, but +Python 3.7+ and ROS Noetic. (It is possible to do some offline and simulation work without ROS, but it is highly recommended to install it if you are working on any onboard behavior.) -In order to interface with the actual vehicle, you will need [PACMOD](http://wiki.ros.org/pacmod) - Autonomoustuff's low level interface to vehicle. If you are using the course SSDs these will be provided for you. +In order to interface with the actual vehicle, you will need [PACMOD](http://wiki.ros.org/pacmod) - Autonomoustuff's low level interface to vehicle. You should also have the following Python dependencies installed, which you can install from this folder using `pip install -r requirements.txt`: @@ -16,7 +22,6 @@ You should also have the following Python dependencies installed, which you can - dacite - pyyaml - ## In this folder Your work will be typically confined to the `GEMstack/` folder, and you may use the `testing/`, `logs/`, `data/`, and `scenes/` folders. @@ -41,7 +46,7 @@ In addition, some tools (e.g., pip) will build temporary folders, such as `build All packages are within the `GEMstack/` folder. -`mathutils/`: Math utilities common to onboard / offboard use. +`mathutils/`: 🧮 Math utilities common to onboard / offboard use. - `transforms`: 2d and 3d rotations and rigid transforms. - `filters`: 1d signal processing. - `cameras`: Contains standard camera models. @@ -51,7 +56,7 @@ All packages are within the `GEMstack/` folder. - `control`: Contains standard control techniques, e.g., PID controller. - `collisions`: Provides collision detection and proximity detection. -`utils/`: Other utilities common to onboard / offboard use. +`utils/`: 🛠️ Other utilities common to onboard / offboard use. - `logging`: Provides logging and log replay functionality. - `simulation`: Interfaces with the Gazebo (possibly other?) simulators. - `visualization`: Tools for converting internal data on knowledge, state, etc. to visualization apps. @@ -59,7 +64,7 @@ All packages are within the `GEMstack/` folder. - `config`: Tools for loading config files. - `serialization`: Tools for serializing / deserializing objects. -`state/`: Representations of state of the vehicle and its environment, including internal state that persists from step to step. +`state/`: 💾 Representations of state of the vehicle and its environment, including internal state that persists from step to step. - `physical_object`: A generic physical object base class. - `trajectory`: Stores a generic path or trajectory. - `vehicle`: Ego-vehicle state. @@ -78,14 +83,14 @@ All packages are within the `GEMstack/` folder. - `route`: Stores a 2d route, coming from the router. - `all`: State or the current scene, all intent and relation estimates, and the driving logic (objective, predicates, route). -`offboard/`: Programs for creation and management of data and knowledge. +`offboard/`: 💻 Programs for creation and management of data and knowledge. - `calibration/`: Sensor calibration. - `log_management/`: Provides log management, browsing, and query functionality. - `detection_learning/`: Detection model learning. - `prediction_learning/`: Prediction model learning. - `heuristic_learning/`: Driving heuristic learning. -`knowledge/`: Models and parameters common to onboard / offboard use. The file "current.py" in each directory will store the current model being used. +`knowledge/`: 🧠 Models and parameters common to onboard / offboard use. The file "current.py" in each directory will store the current model being used. - `vehicle/`: Vehicle geometry and physics. - `calibration/`: Calibrated sensor parameters. - `detection/`: Stores detection models. @@ -96,9 +101,9 @@ All packages are within the `GEMstack/` folder. - `predicates/`: Stores named predicates that may be true in a world state. - `defaults/`: Stores the default settings. -`launch/`: Launch scripts are listed here. Specify which configuration you want to use as an argument to `main.py`. +`launch/`: 🚀 Launch scripts are listed here. Specify which configuration you want to use as an argument to `main.py`. -`onboard/`: All algorithms governing onboard behavior are located here. These algorithms may make use of items in the `knowledge/` stack. +`onboard/`: 🚗 All algorithms governing onboard behavior are located here. These algorithms may make use of items in the `knowledge/` stack. - `perception/`: Perception components. - `state_estimation`: State estimators. - `roadgraph_update`: Roadgraph updaters. From aded805c7f46886e0b5c874285cd58c23c1449d1 Mon Sep 17 00:00:00 2001 From: krishauser Date: Sun, 24 Dec 2023 12:43:46 -0500 Subject: [PATCH 015/232] Cross link from RTD docs --- README.md | 10 +++++----- docs/index.rst | 5 +++-- 2 files changed, 8 insertions(+), 7 deletions(-) diff --git a/README.md b/README.md index 98f731a77..3cd7e2056 100644 --- a/README.md +++ b/README.md @@ -1,14 +1,14 @@ -# GEMstack: software structure for CS588 Autonomous Vehicle System Engineering +# GEMstack: software for CS588 Autonomous Vehicle System Engineering -[📖 Online documentation](https://gemstack.readthedocs.org) +📖 [Online documentation](https://gemstack.readthedocs.org) -[🚗 About the GEM e2 vehicle](https://publish.illinois.edu/robotics-autonomy-resources/gem/) +🚗 [About the GEM e2 vehicle](https://publish.illinois.edu/robotics-autonomy-resources/gem/) -[🗎 ROS code for launching vehicle](https://github.com/hangcui1201/POLARIS_GEM_e2_Real/tree/main) +🗎 [ROS code for launching vehicle](https://github.com/hangcui1201/POLARIS_GEM_e2_Real/tree/main) ## Dependencies -Python 3.7+ and ROS Noetic. (It is possible to do some offline and simulation work without ROS, but it is highly recommended to install it if you are working on any onboard behavior.) +GEMstack uses Python 3.7+ and ROS Noetic. (It is possible to do some offline and simulation work without ROS, but it is highly recommended to install it if you are working on any onboard behavior.) In order to interface with the actual vehicle, you will need [PACMOD](http://wiki.ros.org/pacmod) - Autonomoustuff's low level interface to vehicle. diff --git a/docs/index.rst b/docs/index.rst index ac3ecb5c2..969ac3ef7 100644 --- a/docs/index.rst +++ b/docs/index.rst @@ -1,10 +1,11 @@ Welcome to the GEMstack documentation! ====================================== -Documentation coming soon. +The `Github repository is found here `_ and the README has helpful information to get started. +More substantial ReadTheDocs documentation is pending. Check out the :doc:`usage` section for further information, including -how to :ref:`installation` the project. +:ref:`installation` of the project. .. note:: From 722969eba66c6733251352509075753fa20867aa Mon Sep 17 00:00:00 2001 From: krishauser Date: Sun, 24 Dec 2023 13:01:52 -0500 Subject: [PATCH 016/232] Added stability indicators --- README.md | 148 ++++++++++++++++++++++++++++-------------------------- 1 file changed, 78 insertions(+), 70 deletions(-) diff --git a/README.md b/README.md index 3cd7e2056..ff51469bc 100644 --- a/README.md +++ b/README.md @@ -46,96 +46,104 @@ In addition, some tools (e.g., pip) will build temporary folders, such as `build All packages are within the `GEMstack/` folder. +Legend: +- 🟥: TODO +- 🟧: early development (not usable) +- 🟨: in development (usable, but many features not complete or tested) +- 🟩: stable (most features complete and tested) +- 🟦: mature + `mathutils/`: 🧮 Math utilities common to onboard / offboard use. - - `transforms`: 2d and 3d rotations and rigid transforms. - - `filters`: 1d signal processing. - - `cameras`: Contains standard camera models. - - `differences`: Finite differences for derivative approximation. - - `dynamics`: Contains standard dynamics models. - - `dubins`: Contains first- and second-order Dubins car dynamics models. - - `control`: Contains standard control techniques, e.g., PID controller. - - `collisions`: Provides collision detection and proximity detection. + - 🟩 `transforms`: 2d and 3d rotations and rigid transforms. + - 🟩 `filters`: 1d signal processing. + - 🟥 `cameras`: Contains standard camera models. + - 🟦 `differences`: Finite differences for derivative approximation. + - 🟦 `dynamics`: Contains standard dynamics models. + - 🟦 `dubins`: Contains first- and second-order Dubins car dynamics models. + - 🟩 `control`: Contains standard control techniques, e.g., PID controller. + - 🟧 `collisions`: Provides collision detection and proximity detection. `utils/`: 🛠️ Other utilities common to onboard / offboard use. - - `logging`: Provides logging and log replay functionality. - - `simulation`: Interfaces with the Gazebo (possibly other?) simulators. - - `visualization`: Tools for converting internal data on knowledge, state, etc. to visualization apps. - - `settings`: Tools for managing settings for onboard behaviour. If you're tempted to write a magic parameter or global variable, it should be placed here instead. - - `config`: Tools for loading config files. - - `serialization`: Tools for serializing / deserializing objects. + - 🟩 `logging`: Provides logging and log replay functionality. + - 🟧 `visualization`: Tools for converting internal data on knowledge, state, etc. to visualization apps. + - 🟦 `settings`: Tools for managing settings for onboard behaviour. If you're tempted to write a magic parameter or global variable, it should be [placed in settings instead](#settings). + - 🟦 `config`: Tools for loading config files. + - 🟦 `serialization`: Tools for serializing / deserializing objects. + - 🟦 `loops`: Tools for writing timed loops. `state/`: 💾 Representations of state of the vehicle and its environment, including internal state that persists from step to step. - - `physical_object`: A generic physical object base class. - - `trajectory`: Stores a generic path or trajectory. - - `vehicle`: Ego-vehicle state. - - `intent`: Ego-vehicle intent that may involve special logic or signaling behavior, e.g., lane change, take exit, shutting down. - - `roadgraph`: A section of the roadmap around the ego-vehicle. - - `roadmap`: A map created for offline use. - - `environment`: Environmental conditions, e.g., weather, road conditions. - - `obstacle`: A static obstacle or debris. - - `sign`: A traffic sign. - - `agent`: Another moving object, e.g., pedestrian, bicyclist, vehicle. - - `scene`: All physical items that may be relevant to the current scene, i.e., vehicle, roadgraph, environment, obstacles, and agent states. - - `agent_intent`: Maintains an estimate of agent intent. - - `entity_relation`: Maintains an estimate of a relationship between entities, e.g. VISIBLE, FOLLOWING, PASSING, YIELDING. - - `mission`: Stores the current mission objective, e.g., IDLE, DRIVE_ROUTE, ESTOP, used by routing, logic, planning, and execution. - - `predicates`: Any items predicates that are estimated to be true in the current world. - - `route`: Stores a 2d route, coming from the router. - - `all`: State or the current scene, all intent and relation estimates, and the driving logic (objective, predicates, route). + - 🟩 `physical_object`: A generic physical object base class. + - 🟩 `trajectory`: Stores a generic path or trajectory. + - 🟩 `vehicle`: Ego-vehicle state. + - 🟨 `intent`: Ego-vehicle intent that may involve special logic or signaling behavior, e.g., lane change, take exit, shutting down. + - 🟨 `roadgraph`: A section of the roadmap around the ego-vehicle. + - 🟨 `roadmap`: A map created for offline use. + - 🟨 `environment`: Environmental conditions, e.g., weather, road conditions. + - 🟨 `obstacle`: A static obstacle or debris. + - 🟨 `sign`: A traffic sign. + - 🟨 `agent`: Another moving object, e.g., pedestrian, bicyclist, vehicle. + - 🟩 `scene`: All physical items that may be relevant to the current scene, i.e., vehicle, roadgraph, environment, obstacles, and agent states. + - 🟨 `agent_intent`: Maintains an estimate of agent intent. + - 🟨 `entity_relation`: Maintains an estimate of a relationship between entities, e.g. VISIBLE, FOLLOWING, PASSING, YIELDING. + - 🟨 `mission`: Stores the current mission objective, e.g., IDLE, DRIVE_ROUTE, ESTOP, used by routing, logic, planning, and execution. + - 🟩 `predicates`: Any items predicates that are estimated to be true in the current world. + - 🟩 `route`: Stores a 2d route, coming from the router. + - 🟩 `all`: State or the current scene, all intent and relation estimates, and the driving logic (objective, predicates, route). `offboard/`: 💻 Programs for creation and management of data and knowledge. - - `calibration/`: Sensor calibration. - - `log_management/`: Provides log management, browsing, and query functionality. - - `detection_learning/`: Detection model learning. - - `prediction_learning/`: Prediction model learning. - - `heuristic_learning/`: Driving heuristic learning. + - 🟥 `calibration/`: Sensor calibration. + - 🟥 `log_management/`: Provides log management, browsing, and query functionality. + - 🟥 `detection_learning/`: Detection model learning. + - 🟥 `prediction_learning/`: Prediction model learning. + - 🟥 `heuristic_learning/`: Driving heuristic learning. `knowledge/`: 🧠 Models and parameters common to onboard / offboard use. The file "current.py" in each directory will store the current model being used. - - `vehicle/`: Vehicle geometry and physics. - - `calibration/`: Calibrated sensor parameters. - - `detection/`: Stores detection models. - - `prediction/`: Stores prediction models. - - `heuristics/`: Stores heuristic models. - - `roadmaps/`: Stores roadmap knowledge, e.g., lanes, regions, obstacles, signs. - - `routes/`: Stores precomputed routes. - - `predicates/`: Stores named predicates that may be true in a world state. - - `defaults/`: Stores the default settings. + - 🟨 `vehicle/`: Vehicle geometry and physics. (needs testing) + - 🟨 `calibration/`: Calibrated sensor parameters. + - 🟥 `detection/`: Stores detection models. + - 🟥 `prediction/`: Stores prediction models. + - 🟥 `heuristics/`: Stores heuristic models. + - 🟥 `roadmaps/`: Stores roadmap knowledge, e.g., lanes, regions, obstacles, signs. + - 🟨 `routes/`: Stores precomputed routes. + - 🟥 `predicates/`: Stores named predicates that may be true in a world state. + - 🟩 `defaults/`: Stores the default settings. `launch/`: 🚀 Launch scripts are listed here. Specify which configuration you want to use as an argument to `main.py`. `onboard/`: 🚗 All algorithms governing onboard behavior are located here. These algorithms may make use of items in the `knowledge/` stack. - `perception/`: Perception components. - - `state_estimation`: State estimators. - - `roadgraph_update`: Roadgraph updaters. - - `lane_detection`: Lane detection. - - `sign_detection`: Sign detection. - - `obstacle_detection`: Obstacle detction. - - `agent_detection`: Agent detection. - - `environment_detection`: Environment condition detection. - - `intent_estimation`: Agent intent estimation. - - `relation_estimation`: Entity relation estimation. - - `agent_prediction`: Agent motion prediction. + - 🟨 `state_estimation`: State estimators. + - 🟨 `roadgraph_update`: Roadgraph updaters. + - 🟨 `perception_normalization`: Normalizes the scene before planning. + - 🟥 `lane_detection`: Lane detection. + - 🟥 `sign_detection`: Sign detection. + - 🟥 `obstacle_detection`: Obstacle detction. + - 🟥 `agent_detection`: Agent detection. + - 🟥 `environment_detection`: Environment condition detection. + - 🟥 `intent_estimation`: Agent intent estimation. + - 🟥 `relation_estimation`: Entity relation estimation. + - 🟥 `agent_prediction`: Agent motion prediction. - `planning/`: Planning components. - - `route_planner`: Decides which route to drive from the roadgraph. - - `driving_logic`: Performs all necessary logic to develop a planning problem specification, e.g., select obstacles, design cost functions, etc. - - `heuristics`: Implements various planning heuristics. - - `motion_planning`: Implements one or more motion planners. - - `optimization`: Implements one or more trajectory optimizers. - - `selection`: Implements best-trajectory selection. - - `pure_pursuit`: Implements a pure pursuit controller. - - `recovery`: Implements recovery behavior. + - 🟨 `route_planner`: Decides which route to drive from the roadgraph. + - 🟥 `driving_logic`: Performs all necessary logic to develop a planning problem specification, e.g., select obstacles, design cost functions, etc. + - 🟥 `heuristics`: Implements various planning heuristics. + - 🟥 `motion_planning`: Implements one or more motion planners. + - 🟥 `optimization`: Implements one or more trajectory optimizers. + - 🟥 `selection`: Implements best-trajectory selection. + - 🟨 `pure_pursuit`: Implements a pure pursuit controller. + - 🟨 `recovery`: Implements recovery behavior. - `execution/`: Executes the onboard driving behavior. - - `entrypoint`: The entrypoint that launches all onboard behavior. Configured by settings in 'run' - - `executor`: Base classes for executors. - - `log_replay`: A generic component that replays from a log. + - 🟩 `entrypoint`: The entrypoint that launches all onboard behavior. Configured by settings in 'run'. + - 🟩 `executor`: Base classes for executors. + - 🟩 `log_replay`: A generic component that replays from a log. + - 🟧 `multiprocess_execution`: Component executors that work in separate process - `interface/`: Defines interfaces to vehicle hardware and simulators. - - `gem.py`: Base class for the Polaris GEM e2 vehicle. - - `gem_hardware.py`: Interface to the real GEM vehicle. - - `gem_simulator.py`: Interfaces to simulated GEM vehicles. - - `teleop`: Teleoperator control signals. + - 🟩 `gem`: Base class for the Polaris GEM e2 vehicle. + - 🟨 `gem_hardware`: Interface to the real GEM vehicle. + - 🟨 `gem_simulator`: Interfaces to simulated GEM vehicles. ## Launching the stack From 4dc8dda8c9b4d58d4aabb19add5f97f87c4803e4 Mon Sep 17 00:00:00 2001 From: krishauser Date: Sun, 24 Dec 2023 13:03:57 -0500 Subject: [PATCH 017/232] Tabs to spaces --- README.md | 58 +++++++++++++++++++++++++++---------------------------- 1 file changed, 29 insertions(+), 29 deletions(-) diff --git a/README.md b/README.md index ff51469bc..e23ae2450 100644 --- a/README.md +++ b/README.md @@ -112,38 +112,38 @@ Legend: `onboard/`: 🚗 All algorithms governing onboard behavior are located here. These algorithms may make use of items in the `knowledge/` stack. - `perception/`: Perception components. - - 🟨 `state_estimation`: State estimators. - - 🟨 `roadgraph_update`: Roadgraph updaters. + - 🟨 `state_estimation`: State estimators. + - 🟨 `roadgraph_update`: Roadgraph updaters. - 🟨 `perception_normalization`: Normalizes the scene before planning. - - 🟥 `lane_detection`: Lane detection. - - 🟥 `sign_detection`: Sign detection. - - 🟥 `obstacle_detection`: Obstacle detction. - - 🟥 `agent_detection`: Agent detection. - - 🟥 `environment_detection`: Environment condition detection. - - 🟥 `intent_estimation`: Agent intent estimation. - - 🟥 `relation_estimation`: Entity relation estimation. - - 🟥 `agent_prediction`: Agent motion prediction. + - 🟥 `lane_detection`: Lane detection. + - 🟥 `sign_detection`: Sign detection. + - 🟥 `obstacle_detection`: Obstacle detction. + - 🟥 `agent_detection`: Agent detection. + - 🟥 `environment_detection`: Environment condition detection. + - 🟥 `intent_estimation`: Agent intent estimation. + - 🟥 `relation_estimation`: Entity relation estimation. + - 🟥 `agent_prediction`: Agent motion prediction. - `planning/`: Planning components. - - 🟨 `route_planner`: Decides which route to drive from the roadgraph. - - 🟥 `driving_logic`: Performs all necessary logic to develop a planning problem specification, e.g., select obstacles, design cost functions, etc. - - 🟥 `heuristics`: Implements various planning heuristics. - - 🟥 `motion_planning`: Implements one or more motion planners. - - 🟥 `optimization`: Implements one or more trajectory optimizers. - - 🟥 `selection`: Implements best-trajectory selection. - - 🟨 `pure_pursuit`: Implements a pure pursuit controller. - - 🟨 `recovery`: Implements recovery behavior. + - 🟨 `route_planner`: Decides which route to drive from the roadgraph. + - 🟥 `driving_logic`: Performs all necessary logic to develop a planning problem specification, e.g., select obstacles, design cost functions, etc. + - 🟥 `heuristics`: Implements various planning heuristics. + - 🟥 `motion_planning`: Implements one or more motion planners. + - 🟥 `optimization`: Implements one or more trajectory optimizers. + - 🟥 `selection`: Implements best-trajectory selection. + - 🟨 `pure_pursuit`: Implements a pure pursuit controller. + - 🟨 `recovery`: Implements recovery behavior. - `execution/`: Executes the onboard driving behavior. - - 🟩 `entrypoint`: The entrypoint that launches all onboard behavior. Configured by settings in 'run'. - - 🟩 `executor`: Base classes for executors. - - 🟩 `log_replay`: A generic component that replays from a log. + - 🟩 `entrypoint`: The entrypoint that launches all onboard behavior. Configured by settings in 'run'. + - 🟩 `executor`: Base classes for executors. + - 🟩 `log_replay`: A generic component that replays from a log. - 🟧 `multiprocess_execution`: Component executors that work in separate process - `interface/`: Defines interfaces to vehicle hardware and simulators. - - 🟩 `gem`: Base class for the Polaris GEM e2 vehicle. - - 🟨 `gem_hardware`: Interface to the real GEM vehicle. - - 🟨 `gem_simulator`: Interfaces to simulated GEM vehicles. + - 🟩 `gem`: Base class for the Polaris GEM e2 vehicle. + - 🟨 `gem_hardware`: Interface to the real GEM vehicle. + - 🟨 `gem_simulator`: Interfaces to simulated GEM vehicles. ## Launching the stack @@ -194,15 +194,15 @@ from dataclasses import dataclass @dataclass @register(name="MyClass",version="1") class MyClass_Original: - x : float - y : float + x : float + y : float @dataclass @register(name="MyClass",version="2") class MyClass: - x : float - y : float - time : float + x : float + y : float + time : float ``` From 396b14ca874924fa23dedb967736ffd684a24bf5 Mon Sep 17 00:00:00 2001 From: krishauser Date: Sun, 31 Dec 2023 12:03:39 -0500 Subject: [PATCH 018/232] Got logging to work, multiprocessing works, visualization works --- GEMstack/knowledge/defaults/gem_geometry.yaml | 7 +- GEMstack/knowledge/vehicle/geometry.py | 4 +- GEMstack/launch/fixed_route_sim.yaml | 21 +- GEMstack/mathutils/collisions.py | 253 +++++++++- GEMstack/mathutils/transforms.py | 20 + GEMstack/onboard/component.py | 8 + GEMstack/onboard/execution/entrypoint.py | 137 ++---- GEMstack/onboard/execution/execution.py | 452 +++++++++++++----- .../execution/{log_replay.py => logging.py} | 59 ++- .../execution/multiprocess_execution.py | 106 +++- GEMstack/onboard/interface/gem.py | 2 +- GEMstack/onboard/other/__init__.py | 1 + .../perception/perception_normalization.py | 2 +- .../onboard/perception/state_estimation.py | 2 +- GEMstack/onboard/planning/motion_planning.py | 4 +- GEMstack/onboard/planning/pure_pursuit.py | 67 +-- GEMstack/onboard/planning/recovery.py | 2 +- GEMstack/onboard/visualization/__init__.py | 1 + .../visualization/mpl_visualization.py | 66 +++ GEMstack/state/agent.py | 23 +- GEMstack/state/agent_intent.py | 15 +- GEMstack/state/all.py | 18 +- GEMstack/state/physical_object.py | 54 ++- GEMstack/state/roadgraph.py | 124 ++++- GEMstack/state/scene.py | 10 +- GEMstack/state/trajectory.py | 107 ++++- GEMstack/state/vehicle.py | 33 +- GEMstack/utils/gazebo_visualization.py | 0 GEMstack/utils/mpl_visualization.py | 144 ++++++ README.md | 10 +- testing/test_geometry.py | 34 ++ 31 files changed, 1424 insertions(+), 362 deletions(-) rename GEMstack/onboard/execution/{log_replay.py => logging.py} (53%) create mode 100644 GEMstack/onboard/other/__init__.py create mode 100644 GEMstack/onboard/visualization/__init__.py create mode 100644 GEMstack/onboard/visualization/mpl_visualization.py create mode 100644 GEMstack/utils/gazebo_visualization.py create mode 100644 GEMstack/utils/mpl_visualization.py create mode 100644 testing/test_geometry.py diff --git a/GEMstack/knowledge/defaults/gem_geometry.yaml b/GEMstack/knowledge/defaults/gem_geometry.yaml index 1c307ab70..fc847db5f 100644 --- a/GEMstack/knowledge/defaults/gem_geometry.yaml +++ b/GEMstack/knowledge/defaults/gem_geometry.yaml @@ -1,5 +1,10 @@ +height: 1.8 #meters +width: 1.7 #widest distance from left to right, meters +length: 2.2 #distance from front to rear bumper, meters +bounds: [[-0.4,1.8],[-0.85,0.85],[0,1.7]] #meters, [[x_min,x_max],[y_min,y_max],[z_min,z_max]] with origin at rear axle center wheelbase: 1.4 #distance from rear to front axle, meters min_wheel_angle: -0.6108 #radians, 35 degrees max_wheel_angle: 0.6108 #radians, 35 degrees min_steering_angle: -11.0 #radians, 630 degrees -max_steering_angle: 11.0 #radians, 630 degrees \ No newline at end of file +max_steering_angle: 11.0 #radians, 630 degrees + diff --git a/GEMstack/knowledge/vehicle/geometry.py b/GEMstack/knowledge/vehicle/geometry.py index 44738928f..de9ebc7c5 100644 --- a/GEMstack/knowledge/vehicle/geometry.py +++ b/GEMstack/knowledge/vehicle/geometry.py @@ -46,11 +46,11 @@ def steer2front_degrees(s_angle : float) -> float: if (s_angle > 0): a = -0.1084 b = 21.775 - front_angle = -b + math.sqrt(b**2 - 4*a*(-s_angle)) / (2*a) + front_angle = (-b + math.sqrt(b**2 - 4*a*(-s_angle))) / (2*a) else: a = 0.1084 b = 21.775 - front_angle = -b - math.sqrt(b**2 - 4*a*(-s_angle)) / (2*a) + front_angle = (-b + math.sqrt(b**2 - 4*a*(-s_angle))) / (2*a) return front_angle def steer2front(s_angle : float): diff --git a/GEMstack/launch/fixed_route_sim.yaml b/GEMstack/launch/fixed_route_sim.yaml index 5a0e052ab..73b1bf0e2 100644 --- a/GEMstack/launch/fixed_route_sim.yaml +++ b/GEMstack/launch/fixed_route_sim.yaml @@ -8,7 +8,9 @@ mission_execution: StandardExecutor # "recovery" pipeline: Recovery behavior after a component failure recovery: planning: - trajectory_tracking : recovery.StopTrajectoryTracker + trajectory_tracking : + type: recovery.StopTrajectoryTracker + print: False # "drive" pipeline: Driving behavior for the GEM vehicle following a fixed route drive: @@ -20,7 +22,19 @@ drive: type: StaticRoutePlanner args: [!relative_path '../knowledge/routes/xyhead_demo_pp.csv'] motion_planning: RouteToTrajectoryPlanner - trajectory_tracking: pure_pursuit.PurePursuitTrajectoryTracker + trajectory_tracking: + type: pure_pursuit.PurePursuitTrajectoryTracker + print: False + +#visualization methods +visualization: + type: mpl_visualization.MPLVisualization + args: + rate: 10 + #Don't include save_as if you don't want to save the video + #save_as: + save_as: "fixed_route_sim.mp4" + multiprocess: True log: # Specify the top-level folder to save the log files. Default is 'logs' @@ -35,12 +49,13 @@ log: #rosbag_options : '--split --size=1024' # If True, then record all readings / commands of the vehicle interface. Default False vehicle_interface : True - # Specify which components to record to behavior.json. Default records nothing + # Specify which component's output to record to behavior.json. Default records nothing components : ['state_estimation','trajectory_tracking'] # Specify which components of state to record to state.json. Default records nothing #state: ['all'] # Specify the rate in Hz at which to record state to state.json. Default records at the pipeline's rate #state_rate: 10 + replay: # Add items here to set certain topics / inputs to be replayed from logs # Specify which log folder to replay from log: diff --git a/GEMstack/mathutils/collisions.py b/GEMstack/mathutils/collisions.py index 3ee293c3f..e893c953a 100644 --- a/GEMstack/mathutils/collisions.py +++ b/GEMstack/mathutils/collisions.py @@ -1,9 +1,256 @@ +"""Implements several collision detection primitives. + +Uses the `shapely` package for all 2D collision detection. + +The `CollisionDetector2D` class provides a convenience wrapper to store +multiple objects in a scene and perform collision queries. + +TODO: collision acceleration? +""" + +from .transforms import vector2_dist import shapely +import math +from typing import Tuple, List, Iterator, Optional -def point_in_polygon_2d(point, polygon): - """Returns true if the given point is inside the given polygon. +def point_in_circle_2d(point : Tuple[float,float], center : Tuple[float,float], radius : float) -> bool: + """Returns true if the given point is inside a circle. + """ + return (point[0]-center[0])**2 + (point[1]-center[1])**2 <= radius**2 - Faster to create a CollisionDetector object if you will be doing +def point_in_polygon_2d(point : Tuple[float,float], polygon : List[Tuple[float,float]]) -> bool: + """Returns true if the given point is inside a polygon. + + Faster to create a CollisionDetector2D object if you will be doing multiple queries. """ return shapely.Polygon(polygon).contains(shapely.Point(point[0], point[1])) + +def point_circle_signed_distance_2d(point : Tuple[float,float], center : Tuple[float,float], radius : float) -> float: + """Returns the signed distance from the given point to a circle. + """ + return vector2_dist(point,center) - radius + +def point_circle_distance_2d(point : Tuple[float,float], center : Tuple[float,float], radius : float) -> float: + """Returns the distance from the given point to a circle. + """ + return max(point_circle_signed_distance_2d(point,center,radius),0) + +def point_line_distance_2d(point : Tuple[float,float], vertices : List[Tuple[float,float]]) -> float: + """Returns distance from the given point to a line string. + + Faster to create a CollisionDetector2D object if you will be doing + multiple queries. + """ + return shapely.LineString(vertices).distance(shapely.Point(point[0], point[1])) + +def point_polygon_distance_2d(point : Tuple[float,float], polygon : List[Tuple[float,float]]) -> float: + """Returns distance from the given point to a polygon. + + Faster to create a CollisionDetector2D object if you will be doing + multiple queries. + """ + return shapely.Polygon(polygon).distance(shapely.Point(point[0], point[1])) + +def circle_in_circle_2d(center1 : Tuple[float,float], radius1: float, center2 : Tuple[float,float], radius2: float) -> bool: + """Returns whether a circle is contained within another circle. + """ + d = vector2_dist(center1,center2) + return d + radius1 <= radius2 + +def circle_in_polygon_2d(center : Tuple[float,float], radius: float, polygon : List[Tuple[float,float]]) -> bool: + """Returns whether a circle is contained within a polygon. + + Faster to create a CollisionDetector2D object if you will be doing + multiple queries. + """ + return shapely.Polygon(polygon).contains(shapely.Point(center[0], center[1]).buffer(radius)) + +def circle_intersects_circle_2d(center1 : Tuple[float,float], radius1: float, center2 : Tuple[float,float], radius2: float) -> bool: + """Returns whether a circle overlaps another circle. + """ + d = vector2_dist(center1,center2) + return d <= radius1 + radius2 + +def circle_intersects_line_2d(center : Tuple[float,float], radius: float, vertices : List[Tuple[float,float]]) -> bool: + """Returns whether a circle intersects a line string. + + Faster to create a CollisionDetector2D object if you will be doing + multiple queries. + """ + return shapely.LineString(vertices).intersects(shapely.Point(center[0], center[1]).buffer(radius)) + +def circle_intersects_polygon_2d(center : Tuple[float,float], radius: float, polygon : List[Tuple[float,float]]) -> bool: + """Returns whether a circle intersects a polygon. + + Faster to create a CollisionDetector2D object if you will be doing + multiple queries. + """ + return shapely.Polygon(polygon).intersects(shapely.Point(center[0], center[1]).buffer(radius)) + +def circle_circle_signed_distance_2d(center1 : Tuple[float,float], radius1: float, center2 : Tuple[float,float], radius2: float) -> bool: + """Returns signed distance between circles + """ + return vector2_dist(center1,center2) - (radius1 + radius2) + +def circle_circle_distance_2d(center1 : Tuple[float,float], radius1: float, center2 : Tuple[float,float], radius2: float) -> bool: + """Returns distance between circles + """ + return max(circle_circle_signed_distance_2d(center1,radius1,center2,radius2),0) + +def circle_line_signed_distance_2d(center : Tuple[float,float], radius: float, vertices : List[Tuple[float,float]]) -> float: + """Returns signed distance from circle to a line string. + """ + return shapely.LineString(vertices).distance(shapely.Point(center[0], center[1])) - radius + +def circle_line_distance_2d(center : Tuple[float,float], radius: float, vertices : List[Tuple[float,float]]) -> float: + """Returns distance from the given circle to a line string. + + Faster to create a CollisionDetector2D object if you will be doing + multiple queries. + """ + return shapely.LineString(vertices).distance(shapely.Point(center[0], center[1]).buffer(radius)) + +def circle_polygon_distance_2d(center : Tuple[float,float], radius: float, polygon : List[Tuple[float,float]]) -> float: + """Returns distance from the given point to a polygon. + + Faster to create a CollisionDetector2D object if you will be doing + multiple queries. + """ + return shapely.Polygon(polygon).distance(shapely.Point(center[0], center[1]).buffer(radius)) + +def line_intersects_line_2d(vertices1 : List[Tuple[float,float]], vertices2 : List[Tuple[float,float]]) -> bool: + """Returns whether a line intersects a line. + + Faster to create a CollisionDetector2D object if you will be doing + multiple queries. + """ + return shapely.LineString(vertices1).intersects(shapely.LineString(vertices2)) + +def line_intersects_polygon_2d(vertices : List[Tuple[float,float]], polygon : List[Tuple[float,float]]) -> bool: + """Returns whether a line intersects a polygon. + + Faster to create a CollisionDetector2D object if you will be doing + multiple queries. + """ + return shapely.Polygon(polygon).intersects(shapely.LineString(vertices)) + +def line_intersects_line_2d(vertices1 : List[Tuple[float,float]], vertices2 : List[Tuple[float,float]]) -> bool: + """Returns distance from a line to a line + + Faster to create a CollisionDetector2D object if you will be doing + multiple queries. + """ + return shapely.LineString(vertices1).distance(shapely.LineString(vertices2)) + +def line_polygon_distance_2d(vertices : List[Tuple[float,float]], polygon : List[Tuple[float,float]]) -> bool: + """Returns distance from a line to a polygon. + + Faster to create a CollisionDetector2D object if you will be doing + multiple queries. + """ + return shapely.Polygon(polygon).intersects(shapely.LineString(vertices)) + + +class CollisionDetector2D: + """A class for detecting collisions between many types of objects. + Simply provides a convenience wrapper around shapely objects. + + Does not implement any acceleration data structures, so this may be + best combined with a grid for faster collision detection. + """ + def __init__(self): + self.objects = dict() + self.collision_pairs = set() + + def add_polygon(self, name : str, polygon : List[Tuple[float,float]]) -> None: + """Adds an object to the collision detector.""" + if name in self.objects: + raise ValueError("Object named "+name+" already exists") + for name2 in self.objects.keys(): + if name < name2: + self.collision_pairs.add((name,name2)) + else: + self.collision_pairs.add((name2,name)) + self.objects[name] = shapely.Polygon(polygon) + + def add_circle(self, name : str, center : Tuple[float,float], radius : float) -> None: + """Adds an object to the collision detector.""" + if name in self.objects: + raise ValueError("Object named "+name+" already exists") + for name2 in self.objects.keys(): + if name < name2: + self.collision_pairs.add((name,name2)) + else: + self.collision_pairs.add((name2,name)) + self.objects[name] = shapely.Point(center[0], center[1]).buffer(radius) + + def add_line(self, name : str, vertices : List[Tuple[float,float]]) -> None: + """Adds an object to the collision detector.""" + if name in self.objects: + raise ValueError("Object named "+name+" already exists") + for name2 in self.objects.keys(): + if name < name2: + self.collision_pairs.add((name,name2)) + else: + self.collision_pairs.add((name2,name)) + self.objects[name] = shapely.LineString(vertices) + + def ignore_collisions(self, name1 : str, name2 : str) -> None: + """Ignores collisions between two objects.""" + if name1 < name2: + self.collision_pairs.discard((name1,name2)) + else: + self.collision_pairs.discard((name2,name1)) + + def distance(self, name1 : str, name2 : Optional[str] = None) -> float: + """Returns the distance between two objects. If name2 is None, then + this returns the minimum distance from name1 to any other object.""" + if name2 is None: + d = min(self.objects[name1].distance(self.objects[name2]) for name2 in self.collision_pairs[name1]) + for name2,olist in self.collision_pairs.items(): + if name1 in olist: + d = min(d,self.objects[name1].distance(self.objects[name2])) + return d + return self.objects[name1].distance(self.objects[name2]) + + def items_colliding(self, name : Optional[str] = None) -> Iterator: + """Returns an iterator over pairs of objects that are colliding. + + If `name` is provided, then this returns an iterator over objects + that are colliding with the named object. + """ + if name is None: + for name1, name2 in self.collision_pairs: + if self.objects[name1].intersects(self.objects[name2]): + yield (name1,name2) + else: + o = self.objects[name] + for name2 in self.collision_pairs[name]: + if o.intersects(self.objects[name2]): + yield (name,name2) + for name2,olist in self.collision_pairs.items(): + if name in olist: + if o.intersects(self.objects[name2]): + yield (name2,name) + + def items_containing(self, point : Tuple[float,float]) -> Iterator: + """Returns an iterator over objects that contain the given point.""" + pt = shapely.Point(point[0], point[1]) + for name,obj in self.objects.items(): + if obj.contains(pt): + yield name + + def items_within_circle(self, center : Tuple[float,float], radius : float) -> Iterator: + """Returns an iterator over objects that are within the given circle.""" + circle = shapely.Point(center[0], center[1]).buffer(radius) + for name,obj in self.objects.items(): + if circle.contains(obj): + yield name + + def items_within_box(self, lower : Tuple[float,float], upper : Tuple[float,float]) -> Iterator: + """Returns an iterator over objects that are within the given box.""" + box = shapely.box(lower[0], lower[1], upper[0], upper[1]) + for name,obj in self.objects.items(): + if box.contains(obj): + yield name \ No newline at end of file diff --git a/GEMstack/mathutils/transforms.py b/GEMstack/mathutils/transforms.py index beb2f286f..151ab9836 100644 --- a/GEMstack/mathutils/transforms.py +++ b/GEMstack/mathutils/transforms.py @@ -2,6 +2,7 @@ import numpy as np from klampt.math import vectorops as vo from klampt.math import so2 +from typing import Tuple def normalize_angle(angle : float) -> float: """Normalizes an angle to be in the range [0,2pi]""" @@ -45,6 +46,25 @@ def vector2_dist(v1, v2) -> float: """Euclidean distance between two 2D vectors""" return np.linalg.norm([v1[0] - v2[0], v1[1] - v2[1]]) +def point_segment_distance(x,a,b) -> Tuple[float,float]: + """Computes the distance from point x to segment ab. Returns + a tuple (distance, parameter) where parameter is the parameter + value on the segment in the range [0,1] indicating the closest + point. + """ + v = vector_sub(b,a) + u = vector_sub(x,a) + vnorm = vector_norm(v) + if vnorm < 1e-6: + return vector_norm(u),0 + udotv = np.dot(u,v) + if udotv < 0: + return vector_norm(u),0 + elif udotv > vnorm: + return vector_norm(vector_sub(x,b)),1 + else: + return vector_norm(vector_sub(u,vector_madd(v,u,udotv/vnorm))),udotv/vnorm + def rotate2d(point, angle : float, origin=None): """Rotates a point about the origin by an angle""" if origin is None: diff --git a/GEMstack/onboard/component.py b/GEMstack/onboard/component.py index 25dbc5549..da6a8e11c 100644 --- a/GEMstack/onboard/component.py +++ b/GEMstack/onboard/component.py @@ -14,6 +14,14 @@ def state_outputs(self) -> List[str]: def healthy(self): """Returns True if the element is in a stable state.""" return True + def initialize(self): + """Initialize the component. This is called once before the first + update.""" + pass + def cleanup(self): + """Cleans up resources used by the component. This is called once after + the last update.""" + pass def update(self, *args, **kwargs): """Update the component.""" raise NotImplementedError() diff --git a/GEMstack/onboard/execution/entrypoint.py b/GEMstack/onboard/execution/entrypoint.py index b5f8de62b..3ef495f78 100644 --- a/GEMstack/onboard/execution/entrypoint.py +++ b/GEMstack/onboard/execution/entrypoint.py @@ -1,56 +1,9 @@ from ...utils import settings,config from ..component import Component -from .execution import EXECUTION_PREFIX,ExecutorBase,load_computation_graph -from .log_replay import LogReplay -import importlib +from .execution import EXECUTION_PREFIX,ExecutorBase,ComponentExecutor,load_computation_graph,make_class from typing import Dict,List,Optional import os -def import_module_dynamic(module_name, parent_module=None): - if parent_module is not None: - full_path = parent_module + '.' + module_name - else: - full_path = module_name - return importlib.import_module(full_path) - - -def make_class(config_info, component_module, parent_module=None, extra_args = None): - if extra_args is None: - extra_args = {} - args = () - kwargs = {} - if isinstance(config_info,str): - if '.' in config_info: - component_module,class_name = config_info.rsplit('.',1) - else: - class_name = config_info - else: - class_name = config_info['type'] - if '.' in class_name: - component_module,class_name = class_name.rsplit('.',1) - if 'module' in config_info: - component_module = config_info['module'] - if 'args' in config_info: - args = config_info['args'] - if isinstance(args,dict): - kwargs = args - args = () - if parent_module is not None: - print(EXECUTION_PREFIX,"Importing",component_module,"from",parent_module,"to get",class_name) - else: - print(EXECUTION_PREFIX,"Importing",component_module,"to get",class_name) - module = import_module_dynamic(component_module,parent_module) - klass = getattr(module,class_name) - try: - return klass(*args,**kwargs,**extra_args) - except TypeError: - try: - return klass(*args,**kwargs) - except TypeError: - print(EXECUTION_PREFIX,"Unable to launch module",component_module,"with class",class_name,"and args",args,"kwargs",kwargs) - raise - - def main(): """The main entrypoint for the execution stack.""" @@ -70,6 +23,7 @@ def main(): drive_pipeline_settings = settings.get('run.drive') recovery_pipeline_settings = settings.get('run.recovery') + visualization_settings = settings.get('run.visualization',None) #create pipelines and add to executor pipeline_settings = {'drive':drive_pipeline_settings, @@ -81,72 +35,47 @@ def main(): print(EXECUTION_PREFIX,"Adding non-standard pipeline",k) pipeline_settings[k] = v - existing_components = {} + visualizers = [] + if isinstance(visualization_settings,dict): + #one visualizer + visualizers.append(mission_executor.make_component(visualization_settings,'visualization','GEMstack.onboard.visualization',{'vehicle_interface':vehicle_interface})) + else: + #multiple visualizers + for v in visualization_settings: + visualizers.append(mission_executor.make_component(v,'visualization','GEMstack.onboard.visualization',{'vehicle_interface':vehicle_interface})) + for v in visualizers: + mission_executor.always_run(v.c.__class__.__name__,v) + + #mark the components that will be replayed rather than run + if replay_settings: + logfolder = replay_settings.get('log',None) + if logfolder is not None: + replay_components = replay_settings.get('components',[]) + mission_executor.replay_components(replay_components,logfolder) + + #TODO: ROS topic replay + logmeta = config.load_config_recursive(os.path.join(logfolder,'meta.yaml')) + replay_topics = replay_settings.get('ros_topics',[]) + + #TODO: launch a roslog replay of the topics in ros_topics, disable in the vehicle interface + for (name,s) in pipeline_settings.items(): perception_settings = s.get('perception',{}) planning_settings = s.get('planning',{}) other_settings = s.get('other',{}) - perception_components = {} #type: Dict[str,Component] + perception_components = {} #type: Dict[str,ComponentExecutor] for (k,v) in perception_settings.items(): - if str((k,v)) in existing_components: - perception_components[k] = existing_components[(k,v)] - else: - perception_components[k] = make_class(v,k,'GEMstack.onboard.perception', {'vehicle_interface':vehicle_interface}) - existing_components[str((k,v))] = perception_components[k] - planning_components = {} #type: Dict[str,Component] + perception_components[k] = mission_executor.make_component(v,k,'GEMstack.onboard.perception', {'vehicle_interface':vehicle_interface}) + planning_components = {} #type: Dict[str,ComponentExecutor] for (k,v) in planning_settings.items(): - if str((k,v)) in existing_components: - planning_components[k] = existing_components[(k,v)] - else: - if k == 'trajectory_tracking': - planning_components[k] = make_class(v,k,'GEMstack.onboard.planning', {'vehicle_interface':vehicle_interface}) - else: - planning_components[k] = make_class(v,k,'GEMstack.onboard.planning') - existing_components[str((k,v))] = planning_components[k] - other_components = {} #type: Dict[str,Component] + planning_components[k] = mission_executor.make_component(v,k,'GEMstack.onboard.planning', {'vehicle_interface':vehicle_interface}) + other_components = {} #type: Dict[str,ComponentExecutor] for (k,v) in other_settings.items(): - if str((k,v)) in existing_components: - other_components[k] = existing_components[(k,v)] - else: - other_components[k] = make_class(v,k,'GEMstack.onboard.execution', {'vehicle_interface':vehicle_interface}) - existing_components[str((k,v))] = other_components[k] - - #configure components that would be replayed from log rather than run - if replay_settings: - logfolder = replay_settings.get('log',None) - if logfolder is not None: - logmeta = config.load_config_recursive(os.path.join(logfolder,'meta.yaml')) - - replay_components = replay_settings.get('components',[]) - for c in replay_components: - found = False - for component in (perception_components,planning_components,other_components): - if c in component: - outputs = component[c].state_outputs() - for o in outputs: - if o not in logmeta['state_log_items']: - raise ValueError("Replay component",c,"has output",o,"which is not in log") - print(EXECUTION_PREFIX,"Replaying component",c,"from log",logfolder,"with outputs",outputs) - component[c] = LogReplay(outputs, - os.path.join(logfolder,'state_log.json'), - rate=component[c].rate()) - found = True - if not found: - raise ValueError("Replay component",c,"not found in pipeline",name) - + other_components[k] = mission_executor.make_component(v,k,'GEMstack.onboard.other', {'vehicle_interface':vehicle_interface}) + mission_executor.add_pipeline(name,perception_components,planning_components,other_components) - - #TODO: ROS topic replay - if replay_settings: - logfolder = replay_settings.get('log',None) - if logfolder is not None: - logmeta = config.load_config_recursive(os.path.join(logfolder,'meta.yaml')) - replay_topics = replay_settings.get('ros_topics',[]) - - #TODO: launch a roslog replay of the topics in replay_topics, disable in the vehicle interface - #configure logging if log_settings: topfolder = log_settings.get('log','logs') diff --git a/GEMstack/onboard/execution/execution.py b/GEMstack/onboard/execution/execution.py index 39f0029fe..5ad3b3535 100644 --- a/GEMstack/onboard/execution/execution.py +++ b/GEMstack/onboard/execution/execution.py @@ -1,18 +1,28 @@ +from __future__ import annotations from dataclasses import asdict from ...state import AllState, MissionEnum from ..component import Component from ...utils.loops import TimedLooper -from ...utils import settings +from ...utils import settings,config from ...utils.serialization import serialize from ...utils.logging import Logfile +from .logging import VehicleBehaviorLogger,AllStateLogger,LogReplay import json import time +import datetime import os +import importlib +import io +import contextlib from typing import Dict,Tuple,Set,List,Optional EXECUTION_PREFIX = "Execution:" +EXECUTION_VERBOSITY = 1 # Define the computation graph +COMPONENTS = None +COMPONENT_ORDER = None +COMPONENT_SETTINGS = None def normalize_computation_graph(components : list) -> List[Dict]: normalized_components = [] @@ -40,10 +50,6 @@ def normalize_computation_graph(components : list) -> List[Dict]: normalized_components.append({k:v}) return normalized_components -COMPONENTS = None -COMPONENT_ORDER = None -COMPONENT_SETTINGS = None - def load_computation_graph(): """Loads the computation graph from settings[run.computation_graph.components] and sets global variables COMPONENTS, COMPONENT_ORDER, and COMPONENT_SETTINGS.""" @@ -52,8 +58,66 @@ def load_computation_graph(): COMPONENT_ORDER = [list(c.keys())[0] for c in COMPONENTS] COMPONENT_SETTINGS = dict(list(c.items())[0] for c in COMPONENTS) +def import_module_dynamic(module_name, parent_module=None): + if parent_module is not None: + full_path = parent_module + '.' + module_name + else: + full_path = module_name + return importlib.import_module(full_path) + -def validate_components(components : Dict[str,Component], provided : List = None): +def make_class(config_info, component_module, parent_module=None, extra_args = None): + """Creates an object from a config_info dictionary or string. + + Args: + config_info: either a str with format module.classname or a dict + with keys 'type', 'args' (optional), and 'module' (optional). + component_module: name of the the module to import classes + of this type from. + parent_module: if not None, the parent module to import from. + extra_args: if provided, a dict of arguments to send to the component's + constructor. + + Returns: + Component: instance of named class + """ + if extra_args is None: + extra_args = {} + args = () + kwargs = {} + if isinstance(config_info,str): + if '.' in config_info: + component_module,class_name = config_info.rsplit('.',1) + else: + class_name = config_info + else: + class_name = config_info['type'] + if '.' in class_name: + component_module,class_name = class_name.rsplit('.',1) + if 'module' in config_info: + component_module = config_info['module'] + if 'args' in config_info: + args = config_info['args'] + if isinstance(args,dict): + kwargs = args + args = () + if parent_module is not None: + print(EXECUTION_PREFIX,"Importing",component_module,"from",parent_module,"to get",class_name) + else: + print(EXECUTION_PREFIX,"Importing",component_module,"to get",class_name) + module = import_module_dynamic(component_module,parent_module) + klass = getattr(module,class_name) + try: + return klass(*args,**kwargs,**extra_args) + except TypeError: + try: + return klass(*args,**kwargs) + except TypeError: + print(EXECUTION_PREFIX,"Unable to launch module",component_module,"with class",class_name,"and args",args,"kwargs",kwargs) + raise + + +def validate_components(components : Dict[str,ComponentExecutor], provided : List = None): """Checks whether the defined components match the known computation graph""" state = asdict(AllState.zero()) if provided is None: @@ -68,7 +132,7 @@ def validate_components(components : Dict[str,Component], provided : List = None required_outputs = COMPONENT_SETTINGS[k]['outputs'] c = components[k] - inputs = c.state_inputs() + inputs = c.c.state_inputs() for i in inputs: if i == 'all': assert possible_inputs == ['all'], "Component {} inputs are not provided by previous components".format(k) @@ -78,7 +142,7 @@ def validate_components(components : Dict[str,Component], provided : List = None print(EXECUTION_PREFIX,"Component {} input {} does not exist in AllState object".format(k,i)) if possible_inputs != ['all']: assert i in possible_inputs, "Component {} is not supposed to receive input {}".format(k,i) - outputs = c.state_outputs() + outputs = c.c.state_outputs() for o in required_outputs: if o == 'all': assert outputs == ['all'], "Component {} outputs are not provided by previous components".format(k) @@ -92,6 +156,7 @@ def validate_components(components : Dict[str,Component], provided : List = None else: provided_all = True for k,c in components.items(): + print(k,c.c.__class__.__name__) assert k in COMPONENT_SETTINGS, "Component {} is not known".format(k) return list(provided) @@ -99,22 +164,37 @@ def validate_components(components : Dict[str,Component], provided : List = None class ComponentExecutor: """Polls for whether a component should be updated, and reads/writes inputs / outputs to the AllState object.""" - def __init__(self,c : Component): + def __init__(self,c : Component, essential : bool = True): self.c = c + self.essential = essential + self.print_stdout = True + self.print_stderr = False + self.stdout_log_file = None + self.stderr_log_file = None self.inputs = c.state_inputs() self.output = c.state_outputs() self.last_update_time = None self.next_update_time = None - self.dt = 1.0/c.rate() + rate = c.rate() + self.dt = 1.0/rate if rate is not None else 0.0 self.num_overruns = 0 self.overrun_amount = 0.0 self.do_update = None + def healthy(self): + return self.c.healthy() + def start(self): - pass + self.c.initialize() def stop(self): - pass + self.c.cleanup() + if isinstance(self.stdout_log_file,io.TextIOWrapper): + self.stdout_log_file.close() + self.stdout_log_file = None + if isinstance(self.stderr_log_file,io.TextIOWrapper): + self.stderr_log_file.close() + self.stderr_log_file = None def update(self, t : float, state : AllState): if self.next_update_time is None or t >= self.next_update_time: @@ -124,20 +204,27 @@ def update(self, t : float, state : AllState): self.next_update_time = t + self.dt else: self.next_update_time += self.dt - if self.next_update_time < t: - print(EXECUTION_PREFIX,"Component {} is running behind, overran dt by {} seconds".format(self.c,self.dt,t-self.next_update_time)) + if self.next_update_time < t and self.dt > 0: + if EXECUTION_VERBOSITY >= 1: + print(EXECUTION_PREFIX,"Component {} is running behind, overran dt by {} seconds".format(self.c,self.dt,t-self.next_update_time)) self.num_overruns += 1 self.overrun_amount += t - self.next_update_time self.next_update_time = t + self.dt return True - #print("Component",self.c,"not updating at time",t,", next update time is",self.next_update_time) + if EXECUTION_VERBOSITY >= 3: + print(EXECUTION_PREFIX,"Component",self.c,"not updating at time",t,", next update time is",self.next_update_time) return False - def _do_update(self, *args): - if self.do_update is not None: - res = self.do_update(*args) - else: - res = self.c.update(*args) + def _do_update(self, t:float, *args): + f = io.StringIO() + g = io.StringIO() + with contextlib.redirect_stdout(f): + with contextlib.redirect_stderr(g): + if self.do_update is not None: + res = self.do_update(*args) + else: + res = self.c.update(*args) + self.log_output(t, f.getvalue(),g.getvalue()) return res def update_now(self, t:float, state : AllState): @@ -146,8 +233,11 @@ def update_now(self, t:float, state : AllState): args = (state,) else: args = tuple([getattr(state,i) for i in self.inputs]) - print(EXECUTION_PREFIX,"Updating",self.c.__class__.__name__) - res = self._do_update(*args) + if EXECUTION_VERBOSITY >= 2: + print(EXECUTION_PREFIX,"Updating",self.c.__class__.__name__) + #capture stdout/stderr + + res = self._do_update(t, *args) #write result to state if res is not None: if len(self.output) > 1: @@ -159,6 +249,33 @@ def update_now(self, t:float, state : AllState): setattr(state,self.output[0], res) setattr(state,self.output[0]+'_update_time', t) + def log_output(self,t,stdout,stderr): + timestr = datetime.datetime.fromtimestamp(t).strftime("%H:%M:%S.%f")[:-3] + if stdout: + lines = stdout.split('\n') + if self.print_stdout: + print("------ Component",self.c.__class__.__name__,"stdout ---------") + for l in lines: + print(" ",l) + print("-------------------------------------------") + if isinstance(self.stdout_log_file,str): + self.stdout_log_file = open(self.stdout_log_file,'w') + if isinstance(self.stdout_log_file,io.TextIOWrapper): + for l in lines: + self.stdout_log_file.write(timestr + ': ' + l + '\n') + if stderr: + lines = stderr.split('\n') + if self.print_stderr: + print("------ Component",self.c.__class__.__name__,"stderr ---------") + for l in lines: + print(" ",l) + print("-------------------------------------------") + if isinstance(self.stderr_log_file,str): + self.stderr_log_file = open(self.stderr_log_file,'w') + if isinstance(self.stderr_log_file,io.TextIOWrapper): + for l in lines: + self.stderr_log_file.write(timestr + ': ' + l + '\n') + @@ -167,16 +284,15 @@ class ExecutorBase: Subclasses should implement begin(), update(), done(), and end() methods.""" def __init__(self, vehicle_interface): self.vehicle_interface = vehicle_interface + self.all_components = dict() # type: Dict[str,ComponentExecutor] + self.always_run_components = dict() # type: Dict[str,ComponentExecutor] self.pipelines = dict() # type: Dict[str,Tuple[Dict[str,ComponentExecutor],Dict[str,ComponentExecutor],Dict[str,ComponentExecutor]]] self.current_pipeline = 'drive' # type: str self.state = None # type: Optional[AllState] + self.replayed_components = dict() # type Dict[str,str] self.log_folder = None # type: Optional[str] self.logged_components = set() # type: Set[str] - self.logged_state_attributes = [] # type: List[str] - self.log_state_rate = None # type: Optional[float] - self.state_log = None self.behavior_log = None - self.vehicle_log_t_last = None self.run_metadata = dict() # type: dict self.run_metadata['pipelines'] = [] self.run_metadata['events'] = [] @@ -203,17 +319,76 @@ def end(self): the vehicle is stopped.""" pass - def add_pipeline(self,name : str, perception : Dict[str,Component], planning : Dict[str,Component], other : Dict[str,Component]): + def make_component(self, config_info, component_name, parent_module=None, extra_args = None) -> ComponentExecutor: + """Creates a component, caching the result. See arguments of :func:`make_class`. + + If the component was marked as being a replayed component, will return an executor of a + LogReplay object. + """ + identifier = str((component_name,config_info)) + if identifier in self.all_components: + return self.all_components[identifier] + else: + component = make_class(config_info,component_name,parent_module,extra_args) + if not isinstance(component,Component): + raise RuntimeError("Component {} is not a subclass of Component".format(component_name)) + if component_name in self.replayed_components: + #replace behavior of class with the LogReplay class + replay_folder = self.replayed_components[component_name] + outputs = component.state_outputs() + rate = component.rate() + assert rate is not None and rate > 0, "Replayed component {} must have a positive rate".format(component_name) + if EXECUTION_VERBOSITY >= 1: + print(EXECUTION_PREFIX,"Replaying component",component_name,"from log",replay_folder,"with outputs",outputs) + component = LogReplay(outputs, + os.path.join(replay_folder,'behavior_log.json'), + rate=rate) + if isinstance(config_info,dict) and config_info.get('multiprocess',False): + #wrap component in a multiprocess executor. TODO: not tested yet + from .multiprocess_execution import MPComponentExecutor + executor = MPComponentExecutor(component) + else: + executor = ComponentExecutor(component) + if isinstance(config_info,dict): + executor.essential = config_info.get('essential',True) + if 'rate' in config_info: + executor.dt = 1.0/config_info['rate'] + executor.print_stderr = executor.print_stdout = config_info.get('print',True) + if self.log_folder: + executor.stdout_log_file = os.path.join(self.log_folder,component.__class__.__name__+'.stdout.log') + executor.stderr_log_file = os.path.join(self.log_folder,component.__class__.__name__+'.stderr.log') + self.all_components[identifier] = executor + return executor + + def always_run(self, component_name, component: ComponentExecutor): + """Adds a component the always-run set.""" + self.always_run_components[component_name] = component + + def add_pipeline(self,name : str, perception : Dict[str,ComponentExecutor], planning : Dict[str,ComponentExecutor], other : Dict[str,ComponentExecutor]): output = validate_components(perception) output = validate_components(planning, output) validate_components(other, output) - perception_component_state = dict((k,ComponentExecutor(c)) for (k,c) in perception.items()) - planning_component_state = dict((k,ComponentExecutor(c)) for (k,c) in planning.items()) - other_component_state = dict((k,ComponentExecutor(c)) for (k,c) in other.items()) - self.pipelines[name] = (perception_component_state,planning_component_state,other_component_state) + self.pipelines[name] = (perception,planning,other) #TODO: set any custom do_update functions here - def set_log_folder(self,folder): + def replay_components(self, replayed_components : list, replay_folder : str): + """Declare that the given components should be replayed from a log folder. + + Further make_component calls to this component will be replaced with + LogReplay objects. + """ + #sanity check: was this item logged? + settings = config.load_config_recursive(os.path.join(replay_folder,'settings.yaml')) + try: + logged_components = settings['run']['log']['components'] + except KeyError: + logged_components = [] + for c in replayed_components: + if c not in logged_components: + raise ValueError("Replay component",c,"was not logged in",replay_folder,"(see settings.yaml)") + self.replayed_components[c] = replay_folder + + def set_log_folder(self,folder : str): self.log_folder = folder #save meta.yaml import subprocess @@ -222,31 +397,28 @@ def set_log_folder(self,folder): self.run_metadata['git_commit_id'] = git_commit_id.decode('utf-8').strip() git_branch = subprocess.check_output(['git','rev-parse','--abbrev-ref','HEAD']) self.run_metadata['git_branch'] = git_branch.decode('utf-8').strip() + for k,c in self.all_components.items(): + c.stdout_log_file = os.path.join(self.log_folder,c.c.__class__.__name__+'.stdout.log') + c.stderr_log_file = os.path.join(self.log_folder,c.c.__class__.__name__+'.stderr.log') self.dump_log_metadata() def log_vehicle_interface(self,enabled=True): if enabled: - if 'vehicle_interface' not in self.logged_components: - self.logged_components.add('vehicle_interface') + if self.behavior_log is None: + self.behavior_log = Logfile(os.path.join(self.log_folder,'behavior.json'),delta_format=True,mode='w') + self.always_run('vehicle_behavior_logger',ComponentExecutor(VehicleBehaviorLogger(self.behavior_log,self.vehicle_interface))) else: - if 'vehicle_interface' in self.logged_components: - self.logged_components.remove('vehicle_interface')\ + raise NotImplementedError("Disabling vehicle interface logging not supported yet") def log_components(self,components : List[str]): - if 'vehicle_interface' in self.logged_components: - self.logged_components = set(components) | set(['vehicle_interface']) - else: - self.logged_components = set(components) if components: if self.behavior_log is None: self.behavior_log = Logfile(os.path.join(self.log_folder,'behavior.json'),delta_format=True,mode='w') + self.logged_components = set(components) def log_state(self,state_attributes : List[str], rate : Optional[float]=None): - self.logged_state_attributes = state_attributes[:] - self.log_state_rate = rate - if state_attributes: - if self.state_log is None: - self.state_log = Logfile(os.path.join(self.log_folder,'state.json'),delta_format=False,mode='w') + log_fn = os.path.join(self.log_folder,'state.json') + self.always_run('state_logger',ComponentExecutor(AllStateLogger(state_attributes,rate,log_fn,self.vehicle_interface))) def dump_log_metadata(self): if not self.log_folder: @@ -260,7 +432,8 @@ def event(self,event_description : str, event_print_string : str = None): if event_print_string is None: event_print_string = event_description if event_description.endswith('.') else event_description + '.' self.run_metadata['events'].append({'time':time.time(),'vehicle_time':self.state.t,'description':event_description}) - print(EXECUTION_PREFIX,event_print_string) + if EXECUTION_VERBOSITY >= 1: + print(EXECUTION_PREFIX,event_print_string) self.dump_log_metadata() def set_exit_reason(self, description): @@ -270,20 +443,27 @@ def set_exit_reason(self, description): def run(self): """Main entry point. Runs the mission execution loop.""" + #sanity checking if self.current_pipeline not in self.pipelines: - print(EXECUTION_PREFIX,"Pipeline {} not found".format(self.current_pipeline)) + print(EXECUTION_PREFIX,"Initial pipeline {} not found".format(self.current_pipeline)) return + #must have recovery pipeline if 'recovery' not in self.pipelines: print(EXECUTION_PREFIX,"'recovery' pipeline not found") return + #did we ask to replay any components that don't exist in any pipelines? + for c in self.replayed_components.keys(): + found = False + for (name,(perception_components,planning_components,other_components)) in self.pipelines.items(): + if c in perception_components or c in planning_components or c in other_components: + found = True + break + if not found: + raise ValueError("Replay component",c,"not found in any pipeline") - for (name,(perception_components,planning_components,other_components)) in self.pipelines.items(): - for (k,c) in perception_components.items(): - c.start() - for (k,c) in planning_components.items(): - c.start() - for (k,c) in other_components.items(): - c.start() + #start running components + for k,c in self.all_components.items(): + c.start() #start running mission self.state = AllState.zero() @@ -309,7 +489,8 @@ def run(self): self.run_metadata['pipelines'].append({'time':time.time(),'vehicle_time':self.state.t,'name':self.current_pipeline}) self.dump_log_metadata() try: - print(EXECUTION_PREFIX,"Executing pipeline {}".format(self.current_pipeline)) + if EXECUTION_VERBOSITY >= 1: + print(EXECUTION_PREFIX,"Executing pipeline {}".format(self.current_pipeline)) next = self.run_until_switch() if next is None: #done @@ -317,13 +498,15 @@ def run(self): self.set_exit_reason("normal exit") break if next not in self.pipelines: - print(EXECUTION_PREFIX,"Pipeline {} not found, switching to recovery".format(next)) + if EXECUTION_VERBOSITY >= 1: + print(EXECUTION_PREFIX,"Pipeline {} not found, switching to recovery".format(next)) next = 'recovery' if self.current_pipeline == 'recovery' and next == 'recovery': - print(EXECUTION_PREFIX) - print("************************************************") - print(" Recovery pipeline is not working, exiting! ") - print("************************************************") + if EXECUTION_VERBOSITY >= 1: + print(EXECUTION_PREFIX) + print("************************************************") + print(" Recovery pipeline is not working, exiting! ") + print("************************************************") self.set_exit_reason("recovery pipeline not working") break self.current_pipeline = next @@ -332,16 +515,18 @@ def run(self): self.current_pipeline = 'recovery' except KeyboardInterrupt: if self.current_pipeline == 'recovery': - print(EXECUTION_PREFIX) - print("************************************************") - print(" Ctrl+C interrupt during recovery, exiting! ") - print("************************************************") + if EXECUTION_VERBOSITY >= 1: + print(EXECUTION_PREFIX) + print("************************************************") + print(" Ctrl+C interrupt during recovery, exiting! ") + print("************************************************") self.set_exit_reason("Ctrl+C interrupt during recovery") break self.current_pipeline = 'recovery' self.event("Ctrl+C pressed, switching to recovery mode") if time.time() - self.last_loop_time > 0.5: - print(EXECUTION_PREFIX,"A component may have hung. Traceback:") + if EXECUTION_VERBOSITY >= 1: + print(EXECUTION_PREFIX,"A component may have hung. Traceback:") import traceback traceback.print_exc() if validated: @@ -349,28 +534,22 @@ def run(self): #done with mission self.event("Mission execution ended","Done with mission execution, stopping components and exiting") - for (name,(perception_components,planning_components,other_components)) in self.pipelines.items(): - for (k,c) in perception_components.items(): - c.stop() - for (k,c) in planning_components.items(): - c.stop() - for (k,c) in other_components.items(): - c.stop() + for k,c in self.all_components.items(): + if EXECUTION_VERBOSITY >= 2: + print("Stopping",k) + c.stop() - if self.state_log: - self.state_log.close() - self.state_log = None if self.behavior_log: self.behavior_log.close() self.behavior_log = None - + print("Done with execution loop") + def validate_sensors(self,numsteps=None): """Verifies sensors are working""" (perception_components,planning_components,other_components) = self.pipelines[self.current_pipeline] - dt_min = min([c.dt for c in perception_components.values()]) - if self.log_state_rate is not None: - dt_min = min(dt_min,1.0/self.log_state_rate) + components = list(perception_components.values()) + list(self.always_run_components.values()) + dt_min = min([c.dt for c in components if c.dt != 0.0]) looper = TimedLooper(dt_min,name="main executor") sensors_working = False num_attempts = 0 @@ -379,12 +558,20 @@ def validate_sensors(self,numsteps=None): while looper and not sensors_working: self.last_loop_time = time.time() self.update_components(perception_components,self.state) - sensors_working = all([c.c.healthy() for c in perception_components.values()]) + sensors_working = all([c.healthy() for c in perception_components.values()]) + + self.update_components(self.always_run_components,self.state,force=True) + always_run_working = all([c.healthy() for c in self.always_run_components.values()]) + if not always_run_working: + if EXECUTION_VERBOSITY >= 1: + print(EXECUTION_PREFIX,"Always-run components not working, ignoring") + num_attempts += 1 if numsteps is not None and num_attempts >= numsteps: return False if time.time() > next_print_time: - print(EXECUTION_PREFIX,"Waiting for sensors to be healthy...") + if EXECUTION_VERBOSITY >= 1: + print(EXECUTION_PREFIX,"Waiting for sensors to be healthy...") next_print_time += 1.0 return True @@ -394,19 +581,23 @@ def run_until_switch(self): self.state.mission.type = MissionEnum.RECOVERY_STOP (perception_components,planning_components,other_components) = self.pipelines[self.current_pipeline] - dt_min = min([c.dt for c in perception_components.values()] + [c.dt for c in planning_components.values()] + [c.dt for c in other_components.values()]) - if self.log_state_rate is not None: - dt_min = min(dt_min,1.0/self.log_state_rate) + components = list(perception_components.values()) + list(planning_components.values()) + list(other_components.values()) + list(self.always_run_components.values()) + dt_min = min([c.dt for c in components if c.dt != 0.0]) looper = TimedLooper(dt_min,name="main executor") while looper and not self.done(): self.state.t = self.vehicle_interface.time() self.last_loop_time = time.time() self.update_components(perception_components,self.state) #check for faults - sensors_working = all([c.c.healthy() for c in perception_components.values()]) - if not sensors_working: - print(EXECUTION_PREFIX,"Sensors not working, entering recovery mode") - return 'recovery' + for name,c in perception_components.items(): + if not c.healthy(): + if c.essential and self.current_pipeline != 'recovery': + if EXECUTION_VERBOSITY >= 1: + print(EXECUTION_PREFIX,"Sensor %s not working, entering recovery mode"%(name,)) + return 'recovery' + else: + if EXECUTION_VERBOSITY >= 1: + print(EXECUTION_PREFIX,"Warning, sensor %s not working, ignoring"%(name,)) next_pipeline = self.update(self.state) if next_pipeline is not None and next_pipeline != self.current_pipeline: @@ -415,50 +606,70 @@ def run_until_switch(self): self.update_components(planning_components,self.state) #check for faults - planners_working = all([c.c.healthy() for c in planning_components.values()]) - if not planners_working: - print(EXECUTION_PREFIX,"Planners not working, entering recovery mode") - return 'recovery' + for name,c in planning_components.items(): + if not c.healthy(): + if c.essential and self.current_pipeline != 'recovery': + if EXECUTION_VERBOSITY >= 1: + print(EXECUTION_PREFIX,"Planner %s not working, entering recovery mode"%(name,)) + return 'recovery' + else: + if EXECUTION_VERBOSITY >= 1: + print(EXECUTION_PREFIX,"Warning, planner %s not working, ignoring"%(name,)) self.update_components(other_components,self.state) - others_working = all([c.c.healthy() for c in other_components.values()]) - if not others_working: - print(EXECUTION_PREFIX,"Other items not working, ignoring") + for name,c in other_components.items(): + if not c.healthy(): + if c.essential and self.current_pipeline != 'recovery': + if EXECUTION_VERBOSITY >= 1: + print(EXECUTION_PREFIX,"Other component %s not working, entering recovery mode"%(name,)) + return 'recovery' + else: + if EXECUTION_VERBOSITY >= 1: + print(EXECUTION_PREFIX,"Warning, other component %s not working"%(name,)) + + self.update_components(self.always_run_components,self.state,force=True) + for name,c in self.always_run_components.items(): + if not c.healthy(): + if c.essential and self.current_pipeline != 'recovery': + if EXECUTION_VERBOSITY >= 1: + print(EXECUTION_PREFIX,"Always-run component %s not working, entering recovery mode"%(name,)) + return 'recovery' + else: + if EXECUTION_VERBOSITY >= 1: + print(EXECUTION_PREFIX,"Warning, always-run component %s not working"%(name,)) + #self.done() returned True return None - def update_components(self, components : Dict[str,ComponentExecutor], state : AllState, now = False): + def update_components(self, components : Dict[str,ComponentExecutor], state : AllState, now = False, force = False): """Updates the components and performs necessary logging. If now = True, all components are run regardless of polling state. + + If force = False, only components listed in COMPONENT_ORDER are run. + Otherwise, all components in `components` are run in arbitrary order. """ t = state.t - for k in COMPONENT_ORDER: - if k in components: - updated = False - if now: - components[k].update_now(t,state) - updated = True - else: - updated = components[k].update(t,state) - #log component output if necessary - if updated and k in self.logged_components: - if len(components[k].output)!=0: - self.behavior_log.log(state, components[k].output, t) - if 'vehicle_interface' in self.logged_components: - if state.t != self.vehicle_log_t_last: - collection = {'vehicle_interface_command':self.vehicle_interface.last_command, - 'vehicle_interface_reading':self.vehicle_interface.last_reading} - self.behavior_log.log(collection,t=t) - self.vehicle_log_t_last = state.t - #log state if necessary - if self.logged_state_attributes: - if self.logged_state_attributes[0] == 'all': - self.state_log.log(state) + if force: + order = list(components.keys()) + else: + order = [] + for k in COMPONENT_ORDER: + if k in components: + order.append(k) + for k in order: + updated = False + if now: + components[k].update_now(t,state) + updated = True else: - self.state_log.log(state,self.logged_state_attributes) + updated = components[k].update(t,state) + #log component output if necessary + if updated and k in self.logged_components: + if len(components[k].output)!=0: + self.behavior_log.log(state, components[k].output, t) class StandardExecutor(ExecutorBase): @@ -477,6 +688,7 @@ def done(self): if self.current_pipeline == 'recovery': if self.vehicle_interface.last_reading is not None and \ abs(self.vehicle_interface.last_reading.speed) < 1e-3: - print(EXECUTION_PREFIX,"Vehicle has stopped, exiting execution loop.") + if EXECUTION_VERBOSITY >= 1: + print(EXECUTION_PREFIX,"Vehicle has stopped, exiting execution loop.") return True return False diff --git a/GEMstack/onboard/execution/log_replay.py b/GEMstack/onboard/execution/logging.py similarity index 53% rename from GEMstack/onboard/execution/log_replay.py rename to GEMstack/onboard/execution/logging.py index 47b9fbd25..2a93dcba6 100644 --- a/GEMstack/onboard/execution/log_replay.py +++ b/GEMstack/onboard/execution/logging.py @@ -1,5 +1,5 @@ -from ...utils import serialization,logging from ..component import Component +from ...utils import serialization,logging from typing import List import time @@ -52,3 +52,60 @@ def update(self): return None return res + def cleanup(self): + self.logfile.close() + + + +class VehicleBehaviorLogger(Component): + def __init__(self,behavior_log, vehicle_interface): + if isinstance(behavior_log,str): + behavior_log = logging.Logfile(behavior_log,delta_format=True,mode='w') + self.behavior_log = behavior_log + self.vehicle_interface = vehicle_interface + self.vehicle_log_t_last = None + + def rate(self): + return None + + def state_inputs(self): + return ['all'] + + def state_outputs(self): + return [] + + def update(self,state): + if state.t != self.vehicle_log_t_last: + collection = {'vehicle_interface_command':self.vehicle_interface.last_command, + 'vehicle_interface_reading':self.vehicle_interface.last_reading} + self.behavior_log.log(collection,t=state.t) + self.vehicle_log_t_last = state.t + + +class AllStateLogger(Component): + def __init__(self,attributes,rate,log_fn,vehicle_interface): + self._rate = rate + self.attributes = attributes + self.vehicle_interface = vehicle_interface + self.state_log = logging.Logfile(log_fn,delta_format=False,mode='w') + + def rate(self): + return self._rate + + def state_inputs(self): + return ['all'] + + def state_outputs(self): + return [] + + def cleanup(self): + if self.state_log: + self.state_log.close() + self.state_log = None + + def update(self,state): + if self.attributes: + if self.attributes[0] == 'all': + self.state_log.log(state) + else: + self.state_log.log(state,self.attributes) diff --git a/GEMstack/onboard/execution/multiprocess_execution.py b/GEMstack/onboard/execution/multiprocess_execution.py index 4590b72fc..14fde6da4 100644 --- a/GEMstack/onboard/execution/multiprocess_execution.py +++ b/GEMstack/onboard/execution/multiprocess_execution.py @@ -1,56 +1,124 @@ from multiprocessing import Process, Queue +import queue +from ..component import Component from .execution import ComponentExecutor import time +import sys +import traceback MAX_QUEUE_SIZE = 10 +#wait this many seconds before timing out on a queue get +UPDATE_TIMEOUT = 5.0 class MPComponentExecutor(ComponentExecutor): - def __init__(self, component, *args, **kwargs): + def __init__(self, component : Component, *args, **kwargs): super(MPComponentExecutor, self).__init__(component, *args, **kwargs) self._in_queue = Queue() self._out_queue = Queue() - self._process = Process(target=self._run, args=(self.c, self._in_queue, self._out_queue)) + self._process = None self.do_update = self._do_update self._times_put = [] self._delay_count = 0 self._num_delayed = 0 self._amount_delayed = 0.0 + + def __str__(self): + return "MPComponentExecutor(%s)"%self.c.__class__.__name__ def start(self): + print("STARTING",self) + config = { + 'print_stdout': self.print_stdout, + 'print_stderr': self.print_stderr, + 'stdout_log_file': self.stdout_log_file, + 'stderr_log_file': self.stderr_log_file, + } + self._process = Process(target=self._run, args=(self.c, self._in_queue, self._out_queue, config)) self._process.start() def stop(self): - self._process.terminate() - self._in_queue.put('stop') - self._process.join() - self._process = None + if self._process and self._process.is_alive(): + print("STOPPING",self) + self._in_queue.put('stop') + self._process.join() + self._process.close() + self._process = None - def _run(self, component, inqueue, outqueue): + def _run(self, component : Component, inqueue : Queue, outqueue : Queue, config): + #let parent process handle SIGINT + import signal + signal.signal(signal.SIGINT, signal.SIG_IGN) + #initialize + try: + component.initialize() + except Exception as e: + print("Error initializing",component.__class__.__name__) + outqueue.put((e,traceback.format_tb(e.__traceback__))) + return while True: - if not inqueue.empty(): - data = inqueue.get() - if data == 'stop': - break - res = component.update(data) + #update + try: + data = inqueue.get(UPDATE_TIMEOUT) + except queue.Empty: + print("Timeout waiting for data from parent process",component.__class__.__name__) + break + + if data == 'stop': + print("Parent process requested stop",component.__class__.__name__) + break + + try: + res = component.update(*data) outqueue.put(res) + except KeyboardInterrupt: + return + except Exception as e: + print("Error updating",component.__class__.__name__) + outqueue.put((e,traceback.format_tb(e.__traceback__))) + break - def _do_update(self, *args): - if len(self._in_queue) < MAX_QUEUE_SIZE: + try: + component.cleanup() + except Exception as e: + print("Error cleaning up",component.__class__.__name__) + outqueue.put((e,traceback.format_tb(e.__traceback__))) + print("Exiting process",component.__class__.__name__) + + def _do_update(self, t, *args): + if not self.healthy(): + return None + if self._in_queue.qsize() < MAX_QUEUE_SIZE: self._in_queue.put(args) self._times_put.append(time.time()) else: - print("Warning: queue is full, dropping data") + print(self,"Warning: queue is full, dropping data") if not self._out_queue.empty(): t_put = self._times_put.pop(0) if self._delay_count > 1: self._num_delayed += 1 self._amount_delayed += time.time() - t_put self._delay_count = 0 - return self._out_queue.get() + res = self._out_queue.get() + if isinstance(res,tuple) and isinstance(res[0],Exception): + print("Error in",self.c.__class__.__name__) + print("Traceback:") + for line in res[1]: + print(line) + print("Exception:",res[0]) + + self._process.join() + self._process.close() + self._process = None + return None + return res else: self._delay_count += 1 + if self._delay_count*max(self.dt,0.1) > UPDATE_TIMEOUT: + print("ERROR:",self,"seems to be frozen") + self._process.terminate() + self._process.close() + self._process = None return None - def __del__(self): - if self._process is not None: - self.stop() \ No newline at end of file + def healthy(self): + return self._process is not None and self._process.is_alive() diff --git a/GEMstack/onboard/interface/gem.py b/GEMstack/onboard/interface/gem.py index e538d6773..dfd3aa822 100644 --- a/GEMstack/onboard/interface/gem.py +++ b/GEMstack/onboard/interface/gem.py @@ -37,7 +37,7 @@ def to_state(self, pose : ObjectPose = None) -> VehicleState: pose = ObjectPose(frame = ObjectFrameEnum.CURRENT,t=0,x=0,y=0,yaw=0) pitch = pose.pitch if pose.pitch is not None else 0.0 wheel_base = settings.get('vehicle.geometry.wheelbase') - front_wheel_angle=front2steer(self.steering_wheel_angle) + front_wheel_angle=steer2front(self.steering_wheel_angle) turn_rate=heading_rate(front_wheel_angle,self.speed,wheel_base) acc = pedal_positions_to_acceleration(self.accelerator_pedal_position, self.brake_pedal_position, self.speed, pitch, self.gear) return VehicleState(pose,v=self.speed,acceleration=acc,gear=self.gear,steering_wheel_angle=self.steering_wheel_angle, diff --git a/GEMstack/onboard/other/__init__.py b/GEMstack/onboard/other/__init__.py new file mode 100644 index 000000000..f8a7d3d6d --- /dev/null +++ b/GEMstack/onboard/other/__init__.py @@ -0,0 +1 @@ +"""Other components that might run on board the vehicle.""" \ No newline at end of file diff --git a/GEMstack/onboard/perception/perception_normalization.py b/GEMstack/onboard/perception/perception_normalization.py index 7a5d91cb7..b8f0031a7 100644 --- a/GEMstack/onboard/perception/perception_normalization.py +++ b/GEMstack/onboard/perception/perception_normalization.py @@ -5,7 +5,7 @@ class StandardPerceptionNormalizer(Component): """Updates the start pose and converts all objects to the current vehicle frame, in preparation for planning.""" def rate(self): - return 10.0 + return None def state_inputs(self): return ['all'] def state_outputs(self): diff --git a/GEMstack/onboard/perception/state_estimation.py b/GEMstack/onboard/perception/state_estimation.py index edc91ab71..96c2fc647 100644 --- a/GEMstack/onboard/perception/state_estimation.py +++ b/GEMstack/onboard/perception/state_estimation.py @@ -70,7 +70,7 @@ def fake_gnss_callback(self, vehicle_state): self.vehicle_state = vehicle_state def rate(self): - return 10.0 + return 50.0 def state_outputs(self) -> List[str]: return ['vehicle'] diff --git a/GEMstack/onboard/planning/motion_planning.py b/GEMstack/onboard/planning/motion_planning.py index cb73b2922..7dfd53c03 100644 --- a/GEMstack/onboard/planning/motion_planning.py +++ b/GEMstack/onboard/planning/motion_planning.py @@ -18,7 +18,5 @@ def rate(self): return 10.0 def update(self, state : AllState): - return Trajectory(frame=state.route.frame, - points=state.route.points, - times=list(range(len(state.route.points)))) + return state.route.arc_length_parameterize() \ No newline at end of file diff --git a/GEMstack/onboard/planning/pure_pursuit.py b/GEMstack/onboard/planning/pure_pursuit.py index 042779d2e..bf2e57348 100644 --- a/GEMstack/onboard/planning/pure_pursuit.py +++ b/GEMstack/onboard/planning/pure_pursuit.py @@ -27,46 +27,56 @@ def __init__(self, lookahead = None, lookahead_scale = None, wheelbase = None, c self.speed_filter = OnlineLowPassFilter(1.2, 30, 4) self.path = None - self.path_with_headings = None - self.path_progress = 0.0 - self.t_start = None + self.current_path_parameter = 0.0 + self.t_last = None def set_path(self, path : Path): + if path == self.path: + return self.path = path - self.path_progress = 0.0 if len(self.path.points[0]) > 2: self.path = self.path.get_dims([0,1]) if not isinstance(self.path,Trajectory): self.path = self.path.arc_length_parameterize() - self.path_with_headings = compute_headings(self.path) + self.current_path_parameter = 0.0 def compute(self, state : VehicleState): assert state.pose.frame != ObjectFrameEnum.CURRENT t = state.pose.t + if self.t_last is None: + self.t_last = t + dt = t - self.t_last + + curr_x = state.pose.x + curr_y = state.pose.y + curr_yaw = state.pose.yaw if state.pose.yaw is not None else 0.0 + speed = state.v + + filt_vel = self.speed_filter(speed) + if self.path is None: #just stop - accel = self.pid_speed(0.0, t) - - if self.t_start is None: - self.t_start = t - dt = t - self.t_start + accel = self.pid_speed.advance(0.0, t) + # TODO if self.path.frame != state.pose.frame: + print("Transforming path from",self.path.frame.name,"to",state.pose.frame.name) self.path = self.path.to_frame(state.pose.frame) - self.path_with_headings = self.path_with_headings.to_frame(state.pose.frame) - - curr_x = state.pose.x - curr_y = state.pose.y - curr_yaw = state.pose.yaw if state.pose.yaw is not None else 0.0 - speed = state.v - - desired_x,desired_y,desired_yaw = self.path_with_headings.eval(self.path_progress + self.look_ahead) + closest_dist,closest_parameter = self.path.closest_point_local((curr_x,curr_y),[self.current_path_parameter-5.0,self.current_path_parameter+5.0]) + #TODO: calculate parameter that is look_ahead distance away from the closest point + #(rather than just advancing the parameter) + des_parameter = closest_parameter + self.look_ahead + self.look_ahead_scale * filt_vel + self.current_path_parameter = closest_parameter + print("Closest parameter: " + str(closest_parameter),"distance to path",closest_dist) + print("Closest point",self.path.eval(closest_parameter),"vs",(curr_x,curr_y)) + desired_x,desired_y = self.path.eval(des_parameter) + desired_yaw = np.arctan2(desired_y-curr_y,desired_x-curr_x) + print("Current yaw",curr_yaw,"desired yaw",desired_yaw) - # finding the distance between the goal point and the vehicle - # true look-ahead distance between a waypoint and current position - L = transforms.vector_dist((curr_x, curr_y), (desired_x, desired_y)) + # distance between the desired point and the vehicle + L = transforms.vector2_dist((desired_x,desired_y),(curr_x,curr_y)) # find the curvature and the angle alpha = desired_yaw - curr_yaw @@ -78,8 +88,7 @@ def compute(self, state : VehicleState): # ----------------- tuning this part as needed ----------------- f_delta = np.clip(angle, self.wheel_angle_range[0], self.wheel_angle_range[1]) - - + print("Closest point distance: " + str(L)) print("Forward velocity: " + str(speed)) ct_error = np.sin(alpha) * L @@ -87,21 +96,17 @@ def compute(self, state : VehicleState): print("Front steering angle: " + str(round(np.degrees(f_delta),2)) + " degrees") steering_angle = np.clip(front2steer(f_delta), self.steering_angle_range[0], self.steering_angle_range[1]) print("Steering wheel angle: " + str(round(np.degrees(steering_angle),2)) + " degrees" ) - print("\n") - - filt_vel = self.speed_filter(speed) - print("Filtered velocity: " + str(filt_vel)) + output_accel = self.pid_speed.advance(e = self.desired_speed - filt_vel, t = t) - print(output_accel) - assert isinstance(output_accel, (int,float)) + print("Output acceleration",output_accel) if output_accel > self.max_accel: output_accel = self.max_accel if output_accel < -self.max_decel: output_accel = -self.max_decel - - self.path_progress += speed * dt + + self.t_last = t return (output_accel, f_delta) diff --git a/GEMstack/onboard/planning/recovery.py b/GEMstack/onboard/planning/recovery.py index 4ce279404..e2733e2cd 100644 --- a/GEMstack/onboard/planning/recovery.py +++ b/GEMstack/onboard/planning/recovery.py @@ -19,7 +19,7 @@ def state_outputs(self): return [] def update(self): - print("StopTrajectoryTracker: Stopping, current speed %.3f m/s"%(self.vehicle_interface.last_reading.speed)) + print("Stopping, current speed %.3f m/s"%(self.vehicle_interface.last_reading.speed)) brake_amount = settings.get('control.recovery.brake_amount') brake_speed = settings.get('control.recovery.brake_speed') if self.vehicle_interface.last_command is not None: diff --git a/GEMstack/onboard/visualization/__init__.py b/GEMstack/onboard/visualization/__init__.py new file mode 100644 index 000000000..4d49b0ff2 --- /dev/null +++ b/GEMstack/onboard/visualization/__init__.py @@ -0,0 +1 @@ +"""Visualization components.""" \ No newline at end of file diff --git a/GEMstack/onboard/visualization/mpl_visualization.py b/GEMstack/onboard/visualization/mpl_visualization.py new file mode 100644 index 000000000..dd0d743a6 --- /dev/null +++ b/GEMstack/onboard/visualization/mpl_visualization.py @@ -0,0 +1,66 @@ +from ...utils import mpl_visualization +from ..component import Component +import matplotlib.pyplot as plt +import matplotlib.animation as animation +import time + +class MPLVisualization(Component): + """Runs a matplotlib visualization at 10Hz. + + If save_as is not None, saves the visualization to a file. + """ + def __init__(self, rate : float = 10.0, save_as : str = None): + self._rate = rate + self.save_as = save_as + self.anim = None + self.writer = None + self.fig = None + self.num_updates = 0 + + def rate(self) -> float: + return self._rate + + def state_inputs(self): + return ['all'] + + def initialize(self): + if self.save_as is not None: + print("Saving Matplotlib visualization to",self.save_as) + if self.save_as.endswith('.gif'): + self.writer = animation.PillowWriter(fps=int(self._rate)) + else: + self.writer = animation.FFMpegWriter(fps=int(self._rate)) + self.writer.setup(plt.gcf(), self.save_as, dpi=100) + plt.ion() + # to run GUI event loop + self.fig = plt.gcf() + self.fig.canvas.mpl_connect('close_event', self.on_close) + plt.show(block=False) + + def on_close(self,event): + print("PLOT CLOSED") + plt.ioff() + + def update(self, state): + if not plt.fignum_exists(self.fig.number): + #plot closed + return + self.num_updates += 1 + time_str = time.strftime("%Y-%m-%d %H:%M:%S", time.localtime(state.t)) + #frame=ObjectFrameEnum.CURRENT + #state = state.to_frame(frame) + xrange = [state.vehicle.pose.x - 10, state.vehicle.pose.x + 10] + yrange = [state.vehicle.pose.y - 10, state.vehicle.pose.y + 10] + mpl_visualization.plot(state,title="Scene %d at %s"%(self.num_updates,time_str),xrange=xrange,yrange=yrange,show=False) + self.fig.canvas.draw_idle() + self.fig.canvas.flush_events() + + if self.save_as is not None: + self.writer.grab_frame() + + def cleanup(self): + if self.writer: + print("Saved Matplotlib visualization to",self.save_as) + self.writer.finish() + self.writer = None + diff --git a/GEMstack/state/agent.py b/GEMstack/state/agent.py index a51140f0a..063f293c0 100644 --- a/GEMstack/state/agent.py +++ b/GEMstack/state/agent.py @@ -1,6 +1,7 @@ -from dataclasses import dataclass +from __future__ import annotations +from dataclasses import dataclass, replace from ..utils.serialization import register -from .physical_object import PhysicalObject +from .physical_object import ObjectFrameEnum,ObjectPose,PhysicalObject,convert_vector from enum import Enum from typing import Tuple @@ -24,6 +25,20 @@ class AgentActivityEnum(Enum): class AgentState(PhysicalObject): type : AgentEnum activity : AgentActivityEnum - velocity : Tuple[float,float,float] #estimated velocity in x,y,z, m/s + velocity : Tuple[float,float,float] #estimated velocity in x,y,z, m/s and in agent's local frame yaw_rate : float #estimated yaw rate, in radians/s - \ No newline at end of file + + def velocity_local(self) -> Tuple[float,float,float]: + """Returns velocity in m/s in the agent's local frame.""" + return self.velocity + + def velocity_parent(self) -> Tuple[float,float,float]: + """Returns velocity in m/s in the agent pose's parent frame. + I.e., if the pose frame is CURRENT, then will return the velocity in + the CURRENT frame.""" + return self.pose.rotation().dot(self.velocity).tolist() + + def to_frame(self, frame : ObjectFrameEnum, current_pose = None, start_pose_abs = None) -> AgentState: + newpose = self.pose.to_frame(frame,current_pose,start_pose_abs) + newvelocity = convert_vector(self.velocity,frame,current_pose,start_pose_abs) + return replace(self,pose=newpose,velocity=newvelocity) \ No newline at end of file diff --git a/GEMstack/state/agent_intent.py b/GEMstack/state/agent_intent.py index 163bfd2ce..266afd88e 100644 --- a/GEMstack/state/agent_intent.py +++ b/GEMstack/state/agent_intent.py @@ -1,6 +1,7 @@ -from dataclasses import dataclass +from __future__ import annotations +from dataclasses import dataclass, replace from ..utils.serialization import register -from .physical_object import ObjectPose +from .physical_object import ObjectFrameEnum,ObjectPose from enum import Enum from typing import List,Optional @@ -25,6 +26,12 @@ class AgentIntent: uncertainty_side : Optional[List[float]] # uncertainty in the predicted path in the sideways direction uncertainty_heading : Optional[List[float]] # uncertainty in the predicted path's heading + def to_frame(self, frame : ObjectFrameEnum, current_pose = None, start_pose_abs = None) -> AgentIntent: + if self.path is None: + return self + new_path = [p.to_frame(frame,current_pose,start_pose_abs) for p in self.path] + return replace(self, path = new_path) + @dataclass @register @@ -34,3 +41,7 @@ class AgentIntentMixture: """ predictions : List[AgentIntent] likelihoods : List[float] + + def to_frame(self, frame : ObjectFrameEnum, current_pose = None, start_pose_abs = None) -> AgentIntentMixture: + new_predictions = [p.to_frame(frame) for p in self.predictions] + return replace(self, predictions = new_predictions) \ No newline at end of file diff --git a/GEMstack/state/all.py b/GEMstack/state/all.py index 2edf06388..e23f54e76 100644 --- a/GEMstack/state/all.py +++ b/GEMstack/state/all.py @@ -1,9 +1,10 @@ -from dataclasses import dataclass, field, fields, asdict +from __future__ import annotations +from dataclasses import dataclass, field, fields, asdict, replace from ..utils.serialization import register -from .physical_object import ObjectPose +from .physical_object import ObjectFrameEnum,ObjectPose from .scene import SceneState from .intent import VehicleIntent -from .agent_intent import AgentIntent +from .agent_intent import AgentIntent,AgentIntentMixture from .relations import EntityRelation from .mission import MissionObjective from .route import Route @@ -19,7 +20,7 @@ class AllState(SceneState): """ # non-physical scene state start_vehicle_pose : Optional[ObjectPose] = None - agent_intents : Dict[str,AgentIntent] = field(default_factory=dict) + agent_intents : Dict[str,AgentIntentMixture] = field(default_factory=dict) relations : List[EntityRelation] = field(default_factory=list) predicates : PredicateValues = field(default_factory=PredicateValues) @@ -50,4 +51,11 @@ class AllState(SceneState): def zero(): scene_zero = SceneState.zero() keys = dict((k.name,getattr(scene_zero,k.name)) for k in fields(scene_zero)) - return AllState(**keys) \ No newline at end of file + return AllState(**keys) + + def to_frame(self, frame : ObjectFrameEnum) -> AllState: + scene_to_frame = SceneState.to_frame(self,frame,current_pose=self.vehicle.pose,start_pose_abs=self.start_vehicle_pose) + new_intents = None if self.agent_intents is None else dict((k,v.to_frame(frame,current_pose=self.vehicle.pose,start_pose_abs=self.start_vehicle_pose)) for k,v in self.agent_intents.items()) + new_route = None if self.route is None else self.route.to_frame(frame,current_pose=self.vehicle.pose,start_pose_abs=self.start_vehicle_pose) + new_trajectory = None if self.trajectory is None else self.trajectory.to_frame(frame,current_pose=self.vehicle.pose,start_pose_abs=self.start_vehicle_pose) + return replace(scene_to_frame, agent_intents = new_intents, route = new_route, trajectory = new_trajectory) \ No newline at end of file diff --git a/GEMstack/state/physical_object.py b/GEMstack/state/physical_object.py index fa245429d..bb49cbf80 100644 --- a/GEMstack/state/physical_object.py +++ b/GEMstack/state/physical_object.py @@ -62,15 +62,6 @@ def rotation(self) -> np.ndarray: rpy[2] = transforms.heading_to_yaw(rpy[2],False) return so3.ndarray(so3.from_rpy(rpy)) - def rotation(self) -> np.ndarray: - """Returns the 3x3 rotation matrix of this pose relative to the specified frame.""" - rpy = [(self.roll if self.roll is not None else 0.0), - (self.pitch if self.pitch is not None else 0.0), - (self.yaw if self.yaw is not None else 0.0)] - if self.frame == ObjectFrameEnum.GLOBAL: - rpy[2] = transforms.heading_to_yaw(rpy[2],False) - return so3.ndarray(so3.from_rpy(rpy)) - def translation(self) -> np.ndarray: """Returns the 3D translation of this pose relative to the specified frame.""" if self.frame == ObjectFrameEnum.GLOBAL: @@ -170,13 +161,16 @@ def to_frame(self, new_frame : ObjectFrameEnum, @dataclass @register class PhysicalObject: - """Base class for some physical possibly movble object. Assumed to be - gravity-aligned so the z-axis always points up. + """Base class for some physical possibly movable object. + + The origin is at the object's center in the x-y plane but at the bottom + in the z axis. I.e., if l,w,h are the dimensions, then the object is + contained in a bounding box [-l/2,l/2] x [-w/2,w/2] x [0,h]. Attributes: pose: the position / rotation coordinates of the object. - dimensions: the depth (forward), width (sideways), and height (up) - of the object. + dimensions: the length (forward), width (sideways), and height (up) + of the object, in the object's local frame. outline: an optional list of vertices in CCW order denoting the object's outline polygon in its local frame (x:forward, y:left). @@ -185,6 +179,14 @@ class PhysicalObject: dimensions : Tuple[float,float,float] outline : Optional[List[Tuple[float,float]]] + def bounds(self) -> Tuple[Tuple[float,float],Tuple[float,float],Tuple[float,float]]: + """Returns the bounding box of the object in its local frame.""" + l,w,h = self.dimensions + return [[-l/2,l/2],[-w/2,w/2],[0,h]] + + def to_frame(self, frame : ObjectFrameEnum, current_pose = None, start_pose_abs = None): + newpose = self.pose.to_frame(frame,current_pose,start_pose_abs) + return replace(self,pose=newpose) @@ -235,7 +237,7 @@ def _get_frame_chain(source_frame : ObjectFrameEnum, target_frame : ObjectFrameE def convert_point(source_pt : tuple, source_frame : ObjectFrameEnum, target_frame : ObjectFrameEnum, - current_pose : ObjectPose = None, start_pose_abs : ObjectPose = None) -> Tuple[float,float]: + current_pose : ObjectPose = None, start_pose_abs : ObjectPose = None) -> tuple: """Converts an (x,y) or (x,y,z) point from one frame to another. start_pose_abs must be in GLOBAL or ABSOLUTE_CARTESIAN frame. @@ -253,8 +255,30 @@ def convert_point(source_pt : tuple, source_frame : ObjectFrameEnum, target_fram pt = pose.apply_inv(pt) return pt +def convert_vector(source_vec : tuple, source_frame : ObjectFrameEnum, target_frame : ObjectFrameEnum, + current_pose : ObjectPose = None, start_pose_abs : ObjectPose = None) -> tuple: + """Converts an (x,y) or (x,y,z) vector from one frame to another. + + start_pose_abs must be in GLOBAL or ABSOLUTE_CARTESIAN frame. + + current_pose may be in START, GLOBAL, or ABSOLUTE_CARTESIAN frame. + + GLOBAL and ABSOLUTE_CARTESIAN are incompatible. + """ + frame_chain = _get_frame_chain(source_frame,target_frame,current_pose,start_pose_abs) + vec = source_vec + for (frame,pose,dir) in frame_chain[1:]: + if len(vec) == 2: + R = pose.rotation2d() + else: + R = pose.rotation() + if dir == 1: + vec = R.dot(vec) + else: + vec = R.T.dot(vec) + return tuple(vec) -def convert_xyhead(source_state : tuple, source_frame : ObjectFrameEnum, target_frame : ObjectFrameEnum, +def convert_xyhead(source_state : Tuple[float,float,float], source_frame : ObjectFrameEnum, target_frame : ObjectFrameEnum, current_pose : ObjectPose = None, start_pose_abs : ObjectPose = None) -> Tuple[float,float,float]: """Converts an (x,y,heading) state from one frame to another. diff --git a/GEMstack/state/roadgraph.py b/GEMstack/state/roadgraph.py index 4c5543d7f..276acd5f4 100644 --- a/GEMstack/state/roadgraph.py +++ b/GEMstack/state/roadgraph.py @@ -1,10 +1,11 @@ from __future__ import annotations -from dataclasses import dataclass, replace, field from ..utils.serialization import register from .physical_object import ObjectFrameEnum, convert_point from .obstacle import Obstacle from .sign import Sign from enum import Enum +from collections import defaultdict +from dataclasses import dataclass, replace, field, asdict from typing import List,Tuple,Any,Optional,Dict @@ -17,8 +18,9 @@ class RoadgraphCurveEnum(Enum): CURB = 5 WALL = 6 OBSTACLES = 7 - OVERPASS_BOUNDARY = 8 - UNDERPASS_BOUNDARY = 9 + CLIFF = 8 + OVERPASS_BOUNDARY = 9 + UNDERPASS_BOUNDARY = 10 class RoadgraphLaneEnum(Enum): @@ -50,9 +52,9 @@ class RoadgraphRegionEnum(Enum): class RoadgraphConnectionEnum(Enum): CONTINUES = 0 # after lane1 is complete it converts to lane2 - ADJACENT = 1 # lane1 and lane2 are going the same way, allows a lane change + ADJACENT = 1 # lane2 is to the left of lane1 and are going the same way, allows a lane change ONCOMING = 2 # lane1 and lane2 are adjacent but going opposite ways - CROSSING = 3 # lane2 or curve2 crosses over lane1 + CROSSING = 3 # lane1 is crossed by lane2, curve2, or region2 MERGE = 4 # lane1 merges into lane2 DIVERGE = 5 # lane2 diverges from lane1 BORDERING = 6 # lane1 is bordered by curve2 @@ -64,10 +66,12 @@ class RoadgraphConnectionEnum(Enum): @dataclass @register class RoadgraphCurve: + """Any curve in the roadgraph, whether a stopline, lane boundary, crossing, + wall, etc.""" type : RoadgraphCurveEnum - segments : List[List[Tuple[float,float,float]]] #Polyline representation of the curve. List of lists of 3D positions. Last element is height above road surface, usually 0 - crossable : bool = True - elevation : Optional[float] = None #for CURB, WALL, OBSTACLES, OVERPASS_BOUNDARY, UNDERPASS_BOUNDARY, elevation over road surface, in m + segments : List[List[Tuple[float,float,float]]] #Polyline representation of the curve. List of lists of 3D positions. 3rd element is height above road surface, usually 0 + crossable : bool = True #Whether the curve is crossable by ego vehicle + elevation : Optional[float] = None #for CURB, WALL, OBSTACLES, OVERPASS_BOUNDARY, UNDERPASS_BOUNDARY, elevation over road surface, in m height : Optional[float] = None #for CURB, WALL, OBSTACLES, OVERPASS_BOUNDARY, UNDERPASS_BOUNDARY, height in m def to_frame(self, orig_frame : ObjectFrameEnum, new_frame : ObjectFrameEnum, @@ -78,13 +82,14 @@ def to_frame(self, orig_frame : ObjectFrameEnum, new_frame : ObjectFrameEnum, @dataclass @register class RoadgraphLane: - type : RoadgraphLaneEnum = RoadgraphLaneEnum.LANE - surface : RoadgraphSurfaceEnum = RoadgraphSurfaceEnum.PAVEMENT - left : Optional[RoadgraphCurve] = None - right : Optional[RoadgraphCurve] = None - center : Optional[RoadgraphCurve] = None - begin : Optional[RoadgraphCurve] = None - end : Optional[RoadgraphCurve] = None + type : RoadgraphLaneEnum = RoadgraphLaneEnum.LANE # type of lane + surface : RoadgraphSurfaceEnum = RoadgraphSurfaceEnum.PAVEMENT # surface of lane + route_name : str = '' # name of the route (e.g., street name) that this lane is on + left : Optional[RoadgraphCurve] = None # left boundary of lane + right : Optional[RoadgraphCurve] = None # right boundary of lane + center : Optional[RoadgraphCurve] = None # centerline of lane + begin : Optional[RoadgraphCurve] = None # Optional curve that begins at the start of the lane + end : Optional[RoadgraphCurve] = None # Optional curve that ends at the end of the lane def to_frame(self, orig_frame : ObjectFrameEnum, new_frame : ObjectFrameEnum, current_origin = None, global_origin = None) -> RoadgraphCurve: @@ -95,6 +100,7 @@ def to_frame(self, orig_frame : ObjectFrameEnum, new_frame : ObjectFrameEnum, end=self.end.to_frame(orig_frame,new_frame,current_origin,global_origin) if self.end is not None else None) + @dataclass @register class RoadgraphRegion: @@ -135,9 +141,12 @@ class Roadgraph: @staticmethod def zero(): + """Returns an empty roadgraph.""" return Roadgraph(ObjectFrameEnum.GLOBAL) def is_valid(self) -> bool: + """Returns true if the roadgraph is valid, i.e., all entities are in + the roadgraph, all keys are unique, and all connections are valid.""" keys = set() keys.update(self.curves.keys()) for k in self.lanes.keys(): @@ -172,6 +181,7 @@ def is_valid(self) -> bool: return True def get_entity(self, name : str) -> Any: + """Returns a named entity in the roadgraph.""" if name in self.curves: return self.curves[name] if name in self.lanes: @@ -185,6 +195,7 @@ def get_entity(self, name : str) -> Any: raise KeyError("Entity {} not found".format(name)) def entity_names(self) -> List[str]: + """Returns names of all entities in the roadgraph.""" keys = set() keys.update(self.curves.keys()) keys.update(self.lanes.keys()) @@ -218,4 +229,85 @@ def to_frame(self, frame : ObjectFrameEnum, current_pose = None, start_pose_abs for c in self.connections: newc = c.to_frame(self.frame,frame,current_pose,start_pose_abs) newconnections.append(newc) - return replace(self, frame = frame, curves = newcurves, lanes = newlanes, regions = newregions, signs = newsigns, static_obstacles = newstatic_obstacles, connections=newconnections) \ No newline at end of file + return replace(self, frame = frame, curves = newcurves, lanes = newlanes, regions = newregions, signs = newsigns, static_obstacles = newstatic_obstacles, connections=newconnections) + + + +class RoadgraphNetwork(Roadgraph): + """Stores all of the items within a Roadgraph but also allows for fast + lookup of connections. This is used in routing. + + NOT TESTED YET. + """ + def __init__(self, roadgraph = None): + if roadgraph is not None: + Roadgraph.__init__(self,**asdict(roadgraph)) + else: + Roadgraph.__init__(self,ObjectFrameEnum.GLOBAL) + + self.connections_by_name = defaultdict(list) + self.update_network() + + def update_network(self): + self.connections_by_name = defaultdict(list) + for c in self.connections: + self.connections_by_name[c.lane1].append(c) + if c.lane2 is not None: + self.connections_by_name[c.lane2].append(c) + if c.curve2 is not None: + self.connections_by_name[c.curve2].append(c) + if c.region2 is not None: + self.connections_by_name[c.region2].append(c) + + def get_connections(self, name : str) -> List[RoadgraphConnection]: + return self.connections_by_name[name] + + def continuations(self, name : str) -> List[str]: + """Returns the names of all lanes that continue from the given lane.""" + if name not in self.lanes: + return [] + conns = self.connections_by_name[name] + return [c.lane2 for c in conns if c.type == RoadgraphConnectionEnum.CONTINUES and c.lane1 == name] + + def extend(self, name : str, maximum = None) -> List[str]: + """Returns a sequence of lanes that extend from the current lane + without taking any options, e.g., diverging, turning, etc.""" + if maximum is None: + maximum = len(self.lanes) + result = [name] + for i in range(maximum): + cont = self.continuations(result[-1]) + if len(cont) != 1: + break + result.append(cont[0]) + if cont[0] == name: #loop + break + return result + + def left_adjacent(self, name : str) -> Optional[str]: + """Returns the name of the lane to the left of the given lane, if it exists.""" + if name not in self.lanes: + return None + lane = self.lanes[name] + if lane.left is None: + # no left curve? + return None + conns = self.connections_by_name[name] + for c in conns: + if c.type == RoadgraphConnectionEnum.ADJACENT and c.lane1 == name: + return c.lane2 + return None + + def right_adjacent(self, name : str) -> Optional[str]: + """Returns the name of the lane to the right of the given lane, if it exists.""" + if name not in self.lanes: + return None + lane = self.lanes[name] + if lane.right is None: + # no left curve? + return None + conns = self.connections_by_name[name] + for c in conns: + if c.type == RoadgraphConnectionEnum.ADJACENT and c.lane2 == name: + return c.lane1 + return None \ No newline at end of file diff --git a/GEMstack/state/scene.py b/GEMstack/state/scene.py index 59d3431b5..8abbfdc4c 100644 --- a/GEMstack/state/scene.py +++ b/GEMstack/state/scene.py @@ -1,5 +1,7 @@ -from dataclasses import dataclass, field +from __future__ import annotations +from dataclasses import dataclass, field, replace from ..utils.serialization import register +from .physical_object import ObjectFrameEnum,ObjectPose from .vehicle import VehicleState from .agent import AgentState from .roadgraph import Roadgraph @@ -37,3 +39,9 @@ def entity_names(self) -> List[str]: @staticmethod def zero(): return SceneState(0.0,VehicleState.zero(),Roadgraph.zero(),EnvironmentState(),None,{},{}) + + def to_frame(self, frame : ObjectFrameEnum, current_pose = None, start_pose_abs = None) -> SceneState: + return replace(self, vehicle=self.vehicle.to_frame(frame,current_pose,start_pose_abs), + roadgraph=self.roadgraph.to_frame(frame,current_pose,start_pose_abs), + agents={k:v.to_frame(frame,current_pose,start_pose_abs) for k,v in self.agents.items()}, + obstacles={k:v.to_frame(frame,current_pose,start_pose_abs) for k,v in self.obstacles.items()}) \ No newline at end of file diff --git a/GEMstack/state/trajectory.py b/GEMstack/state/trajectory.py index 1b424b3a5..e520dba02 100644 --- a/GEMstack/state/trajectory.py +++ b/GEMstack/state/trajectory.py @@ -1,8 +1,9 @@ from __future__ import annotations from dataclasses import dataclass,replace from ..utils.serialization import register -from ..mathutils import transforms +from ..mathutils import transforms,collisions from .physical_object import ObjectFrameEnum, convert_point +import math from typing import List,Tuple,Optional,Union @dataclass @@ -12,9 +13,9 @@ class Path: frame : ObjectFrameEnum points : List[List[float]] - def to_frame(self, frame : ObjectFrameEnum): + def to_frame(self, frame : ObjectFrameEnum, current_pose : None, start_pose_abs : None) -> Path: """Converts the route to a different frame.""" - new_points = [convert_point(frame,self.frame,p) for p in self.points] + new_points = [convert_point(p,self.frame,frame,current_pose,start_pose_abs) for p in self.points] return replace(self,frame=frame,points=new_points) def eval(self, u : float) -> List[float]: @@ -67,7 +68,42 @@ def closest_point(self, x : List[float], edges = True) -> Tuple[float,float]: if edges and i > 0: p1 = self.points[i-1] p2 = p - u,dist = transforms.point_segment_dist(x,p1,p2) + dist,u = transforms.point_segment_distance(x,p1,p2) + if dist < best_dist: + best_dist = dist + best_point = i-1+u + else: + dist = transforms.vector_dist(p,x) + if dist < best_dist: + best_dist = dist + best_point = i + return best_dist,best_point + + def closest_point_local(self, x : List[float], param_range=Tuple[float,float], edges = True) -> Tuple[float,float]: + """Returns the closest point on the path to the given point within + the given parameter range. + + If edges=False, only computes the distances to the vertices, not the + edges. This is slightly faster but less accurate. + + Returns (distance, closest_parameter) + """ + best_dist = float('inf') + param_range = [max(param_range[0],0),min(param_range[1],len(self.points))] + imin = int(math.floor(param_range[0])) + imax = int(math.floor(param_range[1])) + if imax == len(self.points): + imax -= 1 + + umin = param_range[0] - imin + umax = param_range[1] - imax + best_point = None + for i in range(imin,imax+1): + p = self.points[i] + if edges and i > 0: + p1 = self.points[i-1] + p2 = p + dist,u = transforms.point_segment_distance(x,p1,p2) if dist < best_dist: best_dist = dist best_point = i-1+u @@ -101,26 +137,41 @@ class Trajectory(Path): """A timed, piecewise linear path.""" times : List[float] - def eval(self, t : float) -> List[float]: - """Evaluates the trajectory at a given time.""" + def time_to_index(self, t : float) -> Tuple[int,float]: + """Converts a time to an (edge index, parameter) tuple.""" ind = 0 while ind < len(self.times) and self.times[ind] < t: ind += 1 - if ind == 0: return self.points[0] - if ind >= len(self.times): return self.points[-1] + if ind == 0: return 0,0.0 + if ind >= len(self.times): return len(self.points)-2,1.0 u = (t - self.times[ind-1])/(self.times[ind] - self.times[ind-1]) - return transforms.vector_madd(self.points[ind-1],transforms.vector_sub(self.points[ind],self.points[ind-1]),u) + return ind-1,u + + def time_to_parameter(self, t : float) -> float: + """Converts a time to a parameter.""" + ind,u = self.time_to_index(t) + return ind+u + + def parameter_to_time(self, u : float) -> float: + """Converts a parameter to a time""" + ind = int(math.floor(u)) + if ind < 0: ind = 0 + if ind >= len(self.times)-1: ind = len(self.times)-2 + u = u - ind + if u > 1: u = 1 + if u < 0: u = 0 + return self.times[ind] + u*(self.times[ind+1]-self.times[ind]) + + def eval(self, t : float) -> List[float]: + """Evaluates the trajectory at a given time.""" + ind,u = self.time_to_index(t) + return transforms.vector_madd(self.points[ind],transforms.vector_sub(self.points[ind+1],self.points[ind]),u) def eval_derivative(self, t : float) -> List[float]: """Evaluates the derivative at a given time.""" - ind = 0 - while ind < len(self.times) and self.times[ind] < t: - ind += 1 - if ind == 0: return self.points[0] - if ind >= len(self.times): return self.points[-1] - return transforms.vector_sub(self.points[ind],self.points[ind-1]) - - + ind,u = self.time_to_index(t) + return transforms.vector_sub(self.points[ind+1],self.points[ind]) + def closest_point(self, x : List[float], edges = True) -> Tuple[float,float]: """Returns the closest point on the path to the given point. If edges=False, only computes the distances to the vertices, not the @@ -128,12 +179,26 @@ def closest_point(self, x : List[float], edges = True) -> Tuple[float,float]: Returns (distance, closest_time) """ - distance, closest_index = Path.closest_point(x,edges) - i = int(closest_index) - u = closest_index - i - closest_time = self.times[i] + u*(self.times[i+1]-self.times[i]) + distance, closest_index = Path.closest_point(self,x,edges) + closest_time = self.parameter_to_time(closest_index) return distance, closest_time + def closest_point_local(self, x : List[float], time_range=Tuple[float,float], edges = True) -> Tuple[float,float]: + """Returns the closest point on the path to the given point within + the given time range. + + If edges=False, only computes the distances to the vertices, not the + edges. This is slightly faster but less accurate. + + Returns (distance, closest_time) + """ + param_range = [self.time_to_parameter(time_range[0]),self.time_to_parameter(time_range[1])] + print("Searching within range",param_range) + distance, closest_index = Path.closest_point_local(self,x,param_range,edges) + closest_time = self.parameter_to_time(closest_index) + return distance, closest_time + + def compute_headings(path : Path, smoothed = False) -> Path: """Converts a 2D (x,y) path into a 3D path (x,y,heading) or a 3D diff --git a/GEMstack/state/vehicle.py b/GEMstack/state/vehicle.py index 272fc0ca0..e4c37e58a 100644 --- a/GEMstack/state/vehicle.py +++ b/GEMstack/state/vehicle.py @@ -1,6 +1,7 @@ -from dataclasses import dataclass +from __future__ import annotations +from dataclasses import dataclass,replace from ..utils.serialization import register -from .physical_object import ObjectFrameEnum, ObjectPose +from .physical_object import ObjectFrameEnum, ObjectPose, PhysicalObject from enum import Enum @@ -20,7 +21,7 @@ class VehicleGearEnum(Enum): @register class VehicleState: """Represents the state of the ego-vehicle.""" - pose : ObjectPose #pose of the vehicle, including time + pose : ObjectPose #pose of the vehicle with origin at rear axle center. Includes time v : float #forward velocity in m/s acceleration : float #current acceleration / deceleration in m/s^2 steering_wheel_angle : float #angle of the steering wheel, in radians @@ -36,4 +37,28 @@ class VehicleState: @staticmethod def zero(): return VehicleState(ObjectPose(ObjectFrameEnum.START,0,0,0),0,0,0,0,0,VehicleGearEnum.PARK,False,False,False,0) - \ No newline at end of file + + def to_object(self) -> PhysicalObject: + """Extracts out the geometry of the object using the vehicle's + current geometry in settings. The object's origin will be in the + middle of the vehicle. + """ + from ..utils import settings + xbounds,ybounds,zbounds = settings.get('vehicle.geometry.bounds') + height = settings.get('vehicle.geometry.height') + center = [0.5*(xbounds[0]+xbounds[1]),0.5*(ybounds[0]+ybounds[1]),0.0] #z needs to be on base + dims = [xbounds[1]-xbounds[0],ybounds[1]-ybounds[0],zbounds[1]-zbounds[0]] + center_new = self.pose.apply(center) + c_x = center_new[0] + c_y = center_new[1] + if self.pose.z is not None: + c_z = center_new.z + else: + c_z = None + center_pose = replace(self.pose,x=c_x,y=c_y,z=c_z) + return PhysicalObject(pose = center_pose, + dimensions = dims, + outline = None) + + def to_frame(self, frame : ObjectFrameEnum, current_pose = None, start_pose_abs = None) -> VehicleState: + return replace(self,pose=self.pose.to_frame(frame,current_pose,start_pose_abs)) diff --git a/GEMstack/utils/gazebo_visualization.py b/GEMstack/utils/gazebo_visualization.py new file mode 100644 index 000000000..e69de29bb diff --git a/GEMstack/utils/mpl_visualization.py b/GEMstack/utils/mpl_visualization.py new file mode 100644 index 000000000..7b2f1c5b4 --- /dev/null +++ b/GEMstack/utils/mpl_visualization.py @@ -0,0 +1,144 @@ +import matplotlib.pyplot as plt +import matplotlib.patches as patches +import numpy as np +from . import settings +from ..state import ObjectFrameEnum,ObjectPose,PhysicalObject,VehicleState,Path,Obstacle,AgentState,Roadgraph,RoadgraphLane,RoadgraphCurve,Trajectory,Route,SceneState,AllState + +def plot_pose(pose : ObjectPose, axis_len=0.1, ax=None): + """Plots the pose in the given axes. The coordinates + of the pose are plotted in the pose's indicated frame.""" + if ax is None: + ax = plt.gca() + R = pose.rotation2d() + t = [pose.x,pose.y] + x_ax = R.dot([axis_len,0])+t + y_ax = R.dot([0,axis_len])+t + ax.plot([pose.x,x_ax[0]],[pose.y,x_ax[1]],'r-') + ax.plot([pose.x,y_ax[0]],[pose.y,y_ax[1]],'g-') + if pose.frame == ObjectFrameEnum.START: + ax.plot(pose.x,pose.y,'bo') + elif pose.frame == ObjectFrameEnum.CURRENT: + ax.plot(pose.x,pose.y,'ro') + elif pose.frame in [ObjectFrameEnum.GLOBAL,ObjectFrameEnum.ABSOLUTE_CARTESIAN]: + ax.plot(pose.x,pose.y,'go') + else: + raise ValueError("Unknown frame %s" % pose.frame) + +def plot_object(obj : PhysicalObject, axis_len=None, outline=True, bbox=True, ax=None): + """Shows an object in a 2D plot in the given axes. + + If axis_len is given, shows the object's pose with + a coordinate frame of the given length. + + If outline is True, shows the object's outline. + + If bbox is True, shows the object's bounding box. + """ + if ax is None: + ax = plt.gca() + if axis_len: + plot_pose(obj.pose, axis_len, ax) + #plot bounding box + R = obj.pose.rotation2d() + t = [obj.pose.x,obj.pose.y] + if bbox or (outline and obj.outline is None): + bounds = obj.bounds() + (xmin,xmax),(ymin,ymax),(zmin,zmax) = bounds + corners = [[xmin,ymin],[xmin,ymax],[xmax,ymax],[xmax,ymin]] + corners = [R.dot(c)+t for c in corners] + corners.append(corners[0]) + xs = [c[0] for c in corners] + ys = [c[1] for c in corners] + if not bbox: + ax.plot(xs,ys,'r-') + else: + ax.plot(xs,ys,'b-') + #plot outline + if outline and obj.outline: + outline = [R.dot(p)+t for p in obj.outline] + outline.append(outline[0]) + xs = [c[0] for c in outline] + ys = [c[1] for c in outline] + ax.plot(xs,ys,'r-') + +def plot_vehicle(vehicle : VehicleState, axis_len=0.1, ax=None): + """Plots the vehicle in the given axes. The coordinates + of the vehicle are plotted in the vehicle's indicated frame.""" + if ax is None: + ax = plt.gca() + plot_object(vehicle.to_object(), axis_len, ax=ax) + + #plot velocity arrow + R = vehicle.pose.rotation2d() + t = np.array([vehicle.pose.x,vehicle.pose.y]) + v = R.dot([vehicle.v,0]) + ax.arrow(t[0],t[1],v[0],v[1],head_width=0.05,head_length=0.1,color='g') + + #plot front wheel angles + wheelbase = settings.get('vehicle.geometry.wheelbase') + wheel_spacing = 0.8*settings.get('vehicle.geometry.width') / 2 + phi = vehicle.front_wheel_angle + left_wheel_origin = t + R.dot([wheelbase,wheel_spacing]) + right_wheel_origin = t + R.dot([wheelbase,-wheel_spacing]) + wheel_width = 0.5 #meters + wheel_offset = R.dot(np.array([np.cos(phi),np.sin(phi)]))*wheel_width*0.5 + ax.plot([left_wheel_origin[0]-wheel_offset[0],left_wheel_origin[0]+wheel_offset[0]], + [left_wheel_origin[1]-wheel_offset[1],left_wheel_origin[1]+wheel_offset[1]],'k-',linewidth=2) + ax.plot([right_wheel_origin[0]-wheel_offset[0],right_wheel_origin[0]+wheel_offset[0]], + [right_wheel_origin[1]-wheel_offset[1],right_wheel_origin[1]+wheel_offset[1]],'k-',linewidth=2) + + #plot gear + if vehicle.gear <= 0: + if vehicle.gear == 0: + gear = 'N' + elif vehicle.gear == -1: + gear = 'R' + else: + gear = 'P' + ax.text(t[0],t[1],gear,ha='center',va='center',color='k') + +def plot_path(path : Path, color='k', linewidth=1, linestyle='-', ax=None): + if ax is None: + ax = plt.gca() + xs = [p[0] for p in path.points] + ys = [p[1] for p in path.points] + ax.plot(xs,ys,color=color,linewidth=linewidth,linestyle=linestyle) + +def plot_scene(scene : SceneState, xrange=None, yrange=None, ax=None, title = None, show=True): + if ax is None: + ax = plt.gca() + ax.cla() + ax.set_aspect('equal') + ax.set_xlabel('x (m)') + ax.set_ylabel('y (m)') + if xrange is not None: + if isinstance(xrange,(tuple,list)): + ax.set_xlim(xrange[0],xrange[1]) + else: + ax.set_xlim(-xrange*0.2,xrange*0.8) + if yrange is not None: + if isinstance(yrange,(tuple,list)): + ax.set_ylim(yrange[0],yrange[1]) + else: + ax.set_ylim(-yrange*0.5,yrange*0.5) + plot_vehicle(scene.vehicle) + for k,a in scene.agents.items(): + plot_object(a) + for k,o in scene.obstacles.items(): + plot_object(o) + if title is None: + if show: + ax.set_title("Scene at t = %.2f" % scene.t) + else: + ax.set_title(title) + if show: + plt.show(block=False) + +def plot(state : AllState, xrange=None, yrange=None,ax=None, title=None, show=True): + if ax is None: + ax = plt.gca() + plot_scene(state, xrange=xrange, yrange=yrange, ax=ax, title=title, show=show) + if state.route is not None: + plot_path(state.route,color='k',linestyle='--',ax=ax) + if state.trajectory is not None: + plot_path(state.trajectory,color='r',linestyle='--',linewidth=2,ax=ax) diff --git a/README.md b/README.md index e23ae2450..74d8e7214 100644 --- a/README.md +++ b/README.md @@ -61,11 +61,12 @@ Legend: - 🟦 `dynamics`: Contains standard dynamics models. - 🟦 `dubins`: Contains first- and second-order Dubins car dynamics models. - 🟩 `control`: Contains standard control techniques, e.g., PID controller. - - 🟧 `collisions`: Provides collision detection and proximity detection. + - 🟨 `collisions`: Provides collision detection and proximity detection. `utils/`: 🛠️ Other utilities common to onboard / offboard use. - 🟩 `logging`: Provides logging and log replay functionality. - - 🟧 `visualization`: Tools for converting internal data on knowledge, state, etc. to visualization apps. + - 🟨 `mpl_visualization`: Tools for plotting data on knowledge, state, etc. in Matplotlib. + - 🟥 `gazebo_visualization`: Tools for converting data on knowledge, state, etc. to ROS messages used in Gazebo. - 🟦 `settings`: Tools for managing settings for onboard behaviour. If you're tempted to write a magic parameter or global variable, it should be [placed in settings instead](#settings). - 🟦 `config`: Tools for loading config files. - 🟦 `serialization`: Tools for serializing / deserializing objects. @@ -138,7 +139,10 @@ Legend: - 🟩 `entrypoint`: The entrypoint that launches all onboard behavior. Configured by settings in 'run'. - 🟩 `executor`: Base classes for executors. - 🟩 `log_replay`: A generic component that replays from a log. - - 🟧 `multiprocess_execution`: Component executors that work in separate process + - 🟨 `multiprocess_execution`: Component executors that work in separate process. (Stdout logging not done yet. Still hangs on exception.) + + - `visualization/`: Visualization components on-board the vehicle + - 🟨 `mpl_visualization`: Matplotlib visualization - `interface/`: Defines interfaces to vehicle hardware and simulators. - 🟩 `gem`: Base class for the Polaris GEM e2 vehicle. diff --git a/testing/test_geometry.py b/testing/test_geometry.py new file mode 100644 index 000000000..afe5d530a --- /dev/null +++ b/testing/test_geometry.py @@ -0,0 +1,34 @@ +#needed to import GEMstack from top level directory +import sys +import os +sys.path.append(os.getcwd()) + +from GEMstack.knowledge.vehicle import geometry +from GEMstack.utils import settings +import matplotlib.pyplot as plt +import numpy as np + +def test_steering_conversions(): + min_wheel_angle = settings.get('vehicle.geometry.min_wheel_angle') + max_wheel_angle = settings.get('vehicle.geometry.max_wheel_angle') + min_steering_angle = settings.get('vehicle.geometry.min_steering_angle') + max_steering_angle = settings.get('vehicle.geometry.max_steering_angle') + fig,axs = plt.subplots(1,2,figsize=(10,5)) + wheel = np.linspace(min_wheel_angle,max_wheel_angle,100) + steer = [geometry.front2steer(w) for w in wheel] + axs[0].plot(np.degrees(wheel),np.degrees(steer)) + axs[0].set_xlabel('wheel angle (deg)') + axs[0].set_ylabel('steer angle (deg)') + axs[0].set_title('front2steer') + axs[0].grid(True) + steer = np.linspace(min_steering_angle,max_steering_angle,100) + wheel = [geometry.steer2front(s) for s in steer] + axs[1].plot(np.degrees(steer),np.degrees(wheel)) + axs[1].set_xlabel('steer angle (deg)') + axs[1].set_ylabel('wheel angle (deg)') + axs[1].set_title('steer2front') + axs[1].grid(True) + plt.show() + +if __name__=='__main__': + test_steering_conversions() \ No newline at end of file From 5c11d3bf5fc8e63138942181042c1a5ee6692768 Mon Sep 17 00:00:00 2001 From: krishauser Date: Sun, 31 Dec 2023 12:21:08 -0500 Subject: [PATCH 019/232] Renamed gem settings to gem_e2 --- .../calibration/{gem.yaml => gem_e2.yaml} | 2 +- GEMstack/knowledge/defaults/current.yaml | 15 +++++++-------- GEMstack/knowledge/defaults/gem_geometry.yaml | 10 ---------- .../gem_e2_control_defaults.yaml} | 0 .../gem_e2_dynamics.yaml} | 0 GEMstack/knowledge/vehicle/gem_e2_geometry.yaml | 11 +++++++++++ .../gem_e2_slow_limits.yaml} | 0 7 files changed, 19 insertions(+), 19 deletions(-) rename GEMstack/knowledge/calibration/{gem.yaml => gem_e2.yaml} (89%) delete mode 100644 GEMstack/knowledge/defaults/gem_geometry.yaml rename GEMstack/knowledge/{defaults/gem_control_defaults.yaml => vehicle/gem_e2_control_defaults.yaml} (100%) rename GEMstack/knowledge/{defaults/gem_dynamics.yaml => vehicle/gem_e2_dynamics.yaml} (100%) create mode 100644 GEMstack/knowledge/vehicle/gem_e2_geometry.yaml rename GEMstack/knowledge/{defaults/gem_slow_limits.yaml => vehicle/gem_e2_slow_limits.yaml} (100%) diff --git a/GEMstack/knowledge/calibration/gem.yaml b/GEMstack/knowledge/calibration/gem_e2.yaml similarity index 89% rename from GEMstack/knowledge/calibration/gem.yaml rename to GEMstack/knowledge/calibration/gem_e2.yaml index 4a05e9d2a..14a09a87b 100644 --- a/GEMstack/knowledge/calibration/gem.yaml +++ b/GEMstack/knowledge/calibration/gem_e2.yaml @@ -1,4 +1,4 @@ -reference: rear_axle_center +reference: rear_axle_center # ground point below rear axle center gnss_location: [1.1,0.0,0.3] # meters, taken from https://github.com/hangcui1201/POLARIS_GEM_e2_Real/blob/main/vehicle_drivers/gem_gnss_control/scripts/gem_gnss_tracker_stanley_rtk.py. Note conflict with pure pursuit location? gnss_yaw: 0.0 # radians front_radar_location: [1.45,0,0.07] # meters, taken from https://github.com/hangcui1201/POLARIS_GEM_e2_Real/blob/main/platform_launch/launch/white_e2/platform.launch diff --git a/GEMstack/knowledge/defaults/current.yaml b/GEMstack/knowledge/defaults/current.yaml index d8b5fd0a4..46ab092cc 100644 --- a/GEMstack/knowledge/defaults/current.yaml +++ b/GEMstack/knowledge/defaults/current.yaml @@ -7,17 +7,16 @@ vehicle: max_gear : 1 num_wiper_settings : 1 #using !include directives helps maintain reuse of common settings - geometry: !include gem_geometry.yaml - dynamics: !include gem_dynamics.yaml - limits: !include gem_slow_limits.yaml - control_defaults: !include gem_control_defaults.yaml - calibration: !include ../calibration/gem.yaml + geometry: !include ../vehicle/gem_e2_geometry.yaml + dynamics: !include ../vehicle/gem_e2_dynamics.yaml + limits: !include ../vehicle/gem_e2_slow_limits.yaml + control_defaults: !include ../vehicle/gem_e2_control_defaults.yaml + calibration: !include ../calibration/gem_e2.yaml #arguments for algorithm components here -mission_executor: - frequency: 0.5 model_predictive_controller: - frequency: 0.1 + dt: 0.1 + lookahead: 20 control: recovery: brake_amount : 0.5 diff --git a/GEMstack/knowledge/defaults/gem_geometry.yaml b/GEMstack/knowledge/defaults/gem_geometry.yaml deleted file mode 100644 index fc847db5f..000000000 --- a/GEMstack/knowledge/defaults/gem_geometry.yaml +++ /dev/null @@ -1,10 +0,0 @@ -height: 1.8 #meters -width: 1.7 #widest distance from left to right, meters -length: 2.2 #distance from front to rear bumper, meters -bounds: [[-0.4,1.8],[-0.85,0.85],[0,1.7]] #meters, [[x_min,x_max],[y_min,y_max],[z_min,z_max]] with origin at rear axle center -wheelbase: 1.4 #distance from rear to front axle, meters -min_wheel_angle: -0.6108 #radians, 35 degrees -max_wheel_angle: 0.6108 #radians, 35 degrees -min_steering_angle: -11.0 #radians, 630 degrees -max_steering_angle: 11.0 #radians, 630 degrees - diff --git a/GEMstack/knowledge/defaults/gem_control_defaults.yaml b/GEMstack/knowledge/vehicle/gem_e2_control_defaults.yaml similarity index 100% rename from GEMstack/knowledge/defaults/gem_control_defaults.yaml rename to GEMstack/knowledge/vehicle/gem_e2_control_defaults.yaml diff --git a/GEMstack/knowledge/defaults/gem_dynamics.yaml b/GEMstack/knowledge/vehicle/gem_e2_dynamics.yaml similarity index 100% rename from GEMstack/knowledge/defaults/gem_dynamics.yaml rename to GEMstack/knowledge/vehicle/gem_e2_dynamics.yaml diff --git a/GEMstack/knowledge/vehicle/gem_e2_geometry.yaml b/GEMstack/knowledge/vehicle/gem_e2_geometry.yaml new file mode 100644 index 000000000..11e3fca1f --- /dev/null +++ b/GEMstack/knowledge/vehicle/gem_e2_geometry.yaml @@ -0,0 +1,11 @@ +length: 2.45 #distance from front to rear bumper, meters +width: 1.7 #widest distance from left to right, meters +height: 2.08 #meters +bounds: [[-0.35,2.10],[-0.85,0.85],[0,2.08]] #meters, [[x_min,x_max],[y_min,y_max],[z_min,z_max]] with origin the ground point below rear axle center +wheel_radius: 0.28 #meters +wheelbase: 1.75 #distance from rear to front axle, meters +min_wheel_angle: -0.6108 #radians, 35 degrees +max_wheel_angle: 0.6108 #radians, 35 degrees +min_steering_angle: -11.0 #radians, 630 degrees +max_steering_angle: 11.0 #radians, 630 degrees + diff --git a/GEMstack/knowledge/defaults/gem_slow_limits.yaml b/GEMstack/knowledge/vehicle/gem_e2_slow_limits.yaml similarity index 100% rename from GEMstack/knowledge/defaults/gem_slow_limits.yaml rename to GEMstack/knowledge/vehicle/gem_e2_slow_limits.yaml From cff0b6cc00137908c4d2f3a9d18977381af8abdf Mon Sep 17 00:00:00 2001 From: krishauser Date: Sun, 31 Dec 2023 12:23:55 -0500 Subject: [PATCH 020/232] Calibration date added --- GEMstack/knowledge/calibration/gem_e2.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/GEMstack/knowledge/calibration/gem_e2.yaml b/GEMstack/knowledge/calibration/gem_e2.yaml index 14a09a87b..9cfdaf5f3 100644 --- a/GEMstack/knowledge/calibration/gem_e2.yaml +++ b/GEMstack/knowledge/calibration/gem_e2.yaml @@ -1,3 +1,4 @@ +calibration_date: "2023-08-31" # Date of calibration YYYY-MM-DD reference: rear_axle_center # ground point below rear axle center gnss_location: [1.1,0.0,0.3] # meters, taken from https://github.com/hangcui1201/POLARIS_GEM_e2_Real/blob/main/vehicle_drivers/gem_gnss_control/scripts/gem_gnss_tracker_stanley_rtk.py. Note conflict with pure pursuit location? gnss_yaw: 0.0 # radians From 5187c3338fa05375e0484518c26f71c27009c706 Mon Sep 17 00:00:00 2001 From: krishauser Date: Wed, 3 Jan 2024 15:48:50 -0500 Subject: [PATCH 021/232] Renamed courses to more descriptive names. Changed interface to allow for variable sensors --- GEMstack/knowledge/defaults/current.yaml | 1 + ...pp.csv => xyhead_highbay_backlot_oval.csv} | 0 ...anley.csv => xyhead_highbay_backlot_p.csv} | 0 .../knowledge/vehicle/gem_e2_fast_limits.yaml | 8 ++++ .../knowledge/vehicle/gem_e2_slow_limits.yaml | 4 +- GEMstack/launch/fixed_route_sim.yaml | 4 +- GEMstack/onboard/execution/execution.py | 7 +++- GEMstack/onboard/interface/gem.py | 39 ++++++++++--------- GEMstack/onboard/interface/gem_hardware.py | 19 +++++++-- GEMstack/onboard/interface/gem_simulator.py | 19 ++++++--- .../onboard/perception/state_estimation.py | 9 ++++- GEMstack/onboard/planning/pure_pursuit.py | 2 +- 12 files changed, 76 insertions(+), 36 deletions(-) rename GEMstack/knowledge/routes/{xyhead_demo_pp.csv => xyhead_highbay_backlot_oval.csv} (100%) rename GEMstack/knowledge/routes/{xyhead_demo_stanley.csv => xyhead_highbay_backlot_p.csv} (100%) create mode 100644 GEMstack/knowledge/vehicle/gem_e2_fast_limits.yaml diff --git a/GEMstack/knowledge/defaults/current.yaml b/GEMstack/knowledge/defaults/current.yaml index 46ab092cc..e592150c0 100644 --- a/GEMstack/knowledge/defaults/current.yaml +++ b/GEMstack/knowledge/defaults/current.yaml @@ -25,6 +25,7 @@ control: lookahead: 4.0 lookahead_scale: 3.0 crosstrack_gain: 0.41 + desired_speed: 2.0 #m/s #configure the simulator, if using simulator: diff --git a/GEMstack/knowledge/routes/xyhead_demo_pp.csv b/GEMstack/knowledge/routes/xyhead_highbay_backlot_oval.csv similarity index 100% rename from GEMstack/knowledge/routes/xyhead_demo_pp.csv rename to GEMstack/knowledge/routes/xyhead_highbay_backlot_oval.csv diff --git a/GEMstack/knowledge/routes/xyhead_demo_stanley.csv b/GEMstack/knowledge/routes/xyhead_highbay_backlot_p.csv similarity index 100% rename from GEMstack/knowledge/routes/xyhead_demo_stanley.csv rename to GEMstack/knowledge/routes/xyhead_highbay_backlot_p.csv diff --git a/GEMstack/knowledge/vehicle/gem_e2_fast_limits.yaml b/GEMstack/knowledge/vehicle/gem_e2_fast_limits.yaml new file mode 100644 index 000000000..59150d0c3 --- /dev/null +++ b/GEMstack/knowledge/vehicle/gem_e2_fast_limits.yaml @@ -0,0 +1,8 @@ +max_steering_rate: 4.0 #radians/s +max_speed: 10.0 #m/s, approx 20 mph +max_reverse_speed: 2.5 #m/s, approx 5 mph +max_acceleration: 3.0 #m/s^2 +max_deceleration: 5.0 #m/s^2 +max_accelerator_pedal: 1.0 #0-1 +max_brake_pedal: 1.0 #0-1 + diff --git a/GEMstack/knowledge/vehicle/gem_e2_slow_limits.yaml b/GEMstack/knowledge/vehicle/gem_e2_slow_limits.yaml index ae7aaf77c..c1c5f93a3 100644 --- a/GEMstack/knowledge/vehicle/gem_e2_slow_limits.yaml +++ b/GEMstack/knowledge/vehicle/gem_e2_slow_limits.yaml @@ -1,6 +1,6 @@ max_steering_rate: 2.0 #radians/s -max_speed: 0.5 #m/s -max_reverse_speed: 0.1 #m/s +max_speed: 2.5 #m/s, approx 5pmh +max_reverse_speed: 0.25 #m/s, approx 1mph max_acceleration: 1.0 #m/s^2 max_deceleration: 2.0 #m/s^2 max_accelerator_pedal: 0.5 #0-1 diff --git a/GEMstack/launch/fixed_route_sim.yaml b/GEMstack/launch/fixed_route_sim.yaml index 73b1bf0e2..337746e2d 100644 --- a/GEMstack/launch/fixed_route_sim.yaml +++ b/GEMstack/launch/fixed_route_sim.yaml @@ -20,11 +20,11 @@ drive: planning: route_planning: type: StaticRoutePlanner - args: [!relative_path '../knowledge/routes/xyhead_demo_pp.csv'] + args: [!relative_path '../knowledge/routes/xyhead_highbay_backlot_p.csv'] motion_planning: RouteToTrajectoryPlanner trajectory_tracking: type: pure_pursuit.PurePursuitTrajectoryTracker - print: False + print: True #visualization methods visualization: diff --git a/GEMstack/onboard/execution/execution.py b/GEMstack/onboard/execution/execution.py index 5ad3b3535..ac65360b8 100644 --- a/GEMstack/onboard/execution/execution.py +++ b/GEMstack/onboard/execution/execution.py @@ -253,6 +253,8 @@ def log_output(self,t,stdout,stderr): timestr = datetime.datetime.fromtimestamp(t).strftime("%H:%M:%S.%f")[:-3] if stdout: lines = stdout.split('\n') + if len(lines) > 0 and len(lines[-1])==0: + lines = lines[:-1] if self.print_stdout: print("------ Component",self.c.__class__.__name__,"stdout ---------") for l in lines: @@ -265,6 +267,8 @@ def log_output(self,t,stdout,stderr): self.stdout_log_file.write(timestr + ': ' + l + '\n') if stderr: lines = stderr.split('\n') + if len(lines) > 0 and len(lines[-1])==0: + lines = lines[:-1] if self.print_stderr: print("------ Component",self.c.__class__.__name__,"stderr ---------") for l in lines: @@ -391,8 +395,9 @@ def replay_components(self, replayed_components : list, replay_folder : str): def set_log_folder(self,folder : str): self.log_folder = folder #save meta.yaml - import subprocess self.run_metadata['start_time'] = time.time() + self.run_metadata['start_time_human_readable'] = datetime.datetime.now().strftime("%Y-%m-%d %H:%M:%S") + import subprocess git_commit_id = subprocess.check_output(['git','rev-parse','HEAD']) self.run_metadata['git_commit_id'] = git_commit_id.decode('utf-8').strip() git_branch = subprocess.check_output(['git','rev-parse','--abbrev-ref','HEAD']) diff --git a/GEMstack/onboard/interface/gem.py b/GEMstack/onboard/interface/gem.py index dfd3aa822..14b380487 100644 --- a/GEMstack/onboard/interface/gem.py +++ b/GEMstack/onboard/interface/gem.py @@ -3,20 +3,25 @@ from ...state import VehicleState, ObjectPose, ObjectFrameEnum from ...knowledge.vehicle.geometry import front2steer,steer2front,heading_rate from ...knowledge.vehicle.dynamics import pedal_positions_to_acceleration, acceleration_to_pedal_positions +from typing import List,Optional,Callable @dataclass @serialization.register class GEMVehicleReading: + """All items that the vehicle reports directly from its internal sensors.""" speed : float = 0 # in m/s - gear : int = 0 + gear : int = 0 # 0 neutral, -1 reverse, -2 park, > 0 forward accelerator_pedal_position : float = 0 # in range [0,1] - brake_pedal_position : float = 0 - steering_wheel_angle : float = 0 + brake_pedal_position : float = 0 # in range [0,1] + steering_wheel_angle : float = 0 # in radians left_turn_signal : bool = False right_turn_signal : bool = False headlights_on : bool = False horn_on : bool = False wiper_level : int = 0 + battery_level : Optional[float] = None # in range [0,1] + fuel_level : Optional[float] = None # in liters + driving_range : Optional[float] = None # remaining range left, in km def from_state(self, state: VehicleState): self.speed = state.v @@ -49,6 +54,7 @@ def to_state(self, pose : ObjectPose = None) -> VehicleState: @dataclass @serialization.register class GEMVehicleCommand: + """All items that can be directly commanded to the vehicle's actuators.""" gear : int #follows convention in state.vehicle.VehicleState. -2: park, -1 reverse: 0: neutral, 1..n: forward accelerator_pedal_position : float accelerator_pedal_speed : float @@ -87,24 +93,20 @@ def get_reading(self) -> GEMVehicleReading: def send_command(cmd : GEMVehicleCommand): """Sends a command to the vehicle""" raise NotImplementedError() - - def subscribe_gnss(self, callback): - raise NotImplementedError() - - def subscribe_imu(self, callback): - raise NotImplementedError() - def subscribe_lidar(self, callback): - raise NotImplementedError() + def sensors(self) -> List[str]: + """Returns all available sensors""" + return ['gnss','imu','top_lidar','top_stereo','front_radar'] - def subscribe_stereo(self, callback): + def subscribe_sensor(self, name : str, callback : Callable) -> None: + """Subscribes to a sensor with a given callback.""" raise NotImplementedError() - def subscribe_radar(self, callback): - raise NotImplementedError() - - def hardware_faults(self) -> list: - """Returns a list of hardware faults (by component)""" + def hardware_faults(self) -> List[str]: + """Returns a list of hardware faults, naming the failed component. + + Can be any sensor, actuator, or other component. + """ raise NotImplementedError() def simple_command(self, acceleration_mps2 : float, steering_wheel_angle : float, state : VehicleState = None) -> GEMVehicleCommand: @@ -120,8 +122,7 @@ def simple_command(self, acceleration_mps2 : float, steering_wheel_angle : float v = state.v if state is not None else 0.0 gear = state.gear if state is not None else 1 acc_pos,brake_pos,gear = acceleration_to_pedal_positions(acceleration_mps2, v, pitch, gear) - print(acc_pos,brake_pos,gear) - + cmd = GEMVehicleCommand(gear=gear, accelerator_pedal_position=acc_pos, brake_pedal_position=brake_pos, diff --git a/GEMstack/onboard/interface/gem_hardware.py b/GEMstack/onboard/interface/gem_hardware.py index 73450cb5b..a641ffb87 100644 --- a/GEMstack/onboard/interface/gem_hardware.py +++ b/GEMstack/onboard/interface/gem_hardware.py @@ -5,7 +5,9 @@ import rospy from ackermann_msgs.msg import AckermannDrive from std_msgs.msg import String, Bool, Float32, Float64 +from sensor_msgs import PointCloud2 from novatel_gps_msgs.msg import NovatelPosition, NovatelXYZ, Inspva +from radar_msgs import RadarTracks from tf.transformations import euler_from_quaternion, quaternion_from_euler # GEM PACMod Headers @@ -31,6 +33,10 @@ def __init__(self): self.speed_sub = rospy.Subscriber("/pacmod/parsed_tx/vehicle_speed_rpt", VehicleSpeedRpt, self.speed_callback) self.steer_sub = rospy.Subscriber("/pacmod/parsed_tx/steer_rpt", SystemRptFloat, self.steer_callback) self.gnss_sub = None + self.imu_sub = None + self.front_radar_sub = None + self.lidar_sub = None + self.stereo_sub = None # -------------------- PACMod setup -------------------- @@ -79,6 +85,8 @@ def __init__(self): /pacmod/as_rx/wiper_cmd """ + #TODO: publish TwistStamped to /front_radar/front_radar/vehicle_motion to get better radar tracks + def speed_callback(self,msg : VehicleSpeedRpt): self.last_reading.speed = msg.vehicle_speed # forward velocity in m/s @@ -88,12 +96,15 @@ def steer_callback(self, msg): def get_reading(self) -> GEMVehicleReading: return self.last_reading - def subscribe_gnss(self, callback): - self.gnss_sub = rospy.Subscriber("/novatel/inspva", Inspva, callback) - + def subscribe_sensor(self, name, callback): + if name == 'gnss': + self.gnss_sub = rospy.Subscriber("/novatel/inspva", Inspva, callback) + elif name == 'lidar': + self.lidar_sub = rospy.Subscriber("/lidar1/velodyne_points", PointCloud2, callback) + elif name == 'front_radar': + self.front_radar_sub = rospy.Subscriber("/front_radar/front_radar/radar_tracks", RadarTracks, callback) - # PACMod enable callback function def pacmod_enable_callback(self, msg): self.pacmod_enable = msg.data diff --git a/GEMstack/onboard/interface/gem_simulator.py b/GEMstack/onboard/interface/gem_simulator.py index 2f2728a0f..1ead2c876 100644 --- a/GEMstack/onboard/interface/gem_simulator.py +++ b/GEMstack/onboard/interface/gem_simulator.py @@ -1,3 +1,4 @@ +from typing import List from .gem import * from ...mathutils.dubins import SecondOrderDubinsCar from ...mathutils.dynamics import simulate @@ -85,11 +86,15 @@ def stop(self): def hardware_faults(self) -> list: return [] - def subscribe_gnss(self, callback): - self.gnss_callback = callback - - def subscribe_imu(self, callback): - self.imu_callback = callback + def sensors(self): + #TODO: simulate other sensors? + return ['gnss','imu'] + + def subscribe_sensor(self, name, callback): + if name == 'gnss': + self.gnss_callback = callback + elif name == 'imu': + self.imu_callback = callback def send_command(self, command : GEMVehicleCommand): self.last_command = command @@ -144,6 +149,10 @@ def simulate(self,lock : Lock, data : dict): pose = ObjectPose(frame=ObjectFrameEnum.ABSOLUTE_CARTESIAN,t=self.simulation_time,x=x,y=y,yaw=theta) vehicle_state = self.last_reading.to_state(pose) self.gnss_callback(vehicle_state) + if self.imu_callback is not None: + pose = ObjectPose(frame=ObjectFrameEnum.CURRENT,t=self.simulation_time,x=0,y=0,yaw=theta) + vehicle_state = self.last_reading.to_state(pose) + self.imu_callback(vehicle_state) self.cur_vehicle_state = next_state self.simulation_time += self.dt diff --git a/GEMstack/onboard/perception/state_estimation.py b/GEMstack/onboard/perception/state_estimation.py index 96c2fc647..1ad4576d6 100644 --- a/GEMstack/onboard/perception/state_estimation.py +++ b/GEMstack/onboard/perception/state_estimation.py @@ -13,7 +13,9 @@ class GNSSStateEstimator(Component): """Just looks at the GNSS reading to estimate the vehicle state""" def __init__(self, vehicle_interface : GEMInterface): self.vehicle_interface = vehicle_interface - vehicle_interface.subscribe_gnss(self.inspva_callback) + if 'gnss' not in vehicle_interface.sensors(): + raise RuntimeError("GNSS sensor not available") + vehicle_interface.subscribe_sensor('gnss',self.inspva_callback) self.gnss_pose = None self.location = settings.get('vehicle.calibration.gnss_location')[:2] self.yaw_offset = settings.get('vehicle.calibration.gnss_yaw') @@ -28,6 +30,7 @@ def inspva_callback(self, inspva_msg): roll=inspva_msg.roll, pitch=inspva_msg.pitch, ) + #TODO: figure out what this status means print("INS status",inspva_msg.status) def rate(self): @@ -62,7 +65,9 @@ def update(self) -> VehicleState: class FakeStateEstimator(Component): def __init__(self, vehicle_interface : GEMInterface): self.vehicle_interface = vehicle_interface - vehicle_interface.subscribe_gnss(self.fake_gnss_callback) + if 'gnss' not in vehicle_interface.sensors(): + raise RuntimeError("GNSS sensor not available") + vehicle_interface.subscribe_sensor('gnss',self.fake_gnss_callback) self.vehicle_state = None # Get GNSS information diff --git a/GEMstack/onboard/planning/pure_pursuit.py b/GEMstack/onboard/planning/pure_pursuit.py index bf2e57348..9de08b65e 100644 --- a/GEMstack/onboard/planning/pure_pursuit.py +++ b/GEMstack/onboard/planning/pure_pursuit.py @@ -20,7 +20,7 @@ def __init__(self, lookahead = None, lookahead_scale = None, wheelbase = None, c self.wheel_angle_range = [settings.get('vehicle.geometry.min_wheel_angle'),settings.get('vehicle.geometry.max_wheel_angle')] self.steering_angle_range = [settings.get('vehicle.geometry.min_steering_angle'),settings.get('vehicle.geometry.max_steering_angle')] - self.desired_speed = 1.5 # m/s, reference speed + self.desired_speed = settings.get('control.pure_pursuit.desired_speed',2.5) #approximately 5 mph self.max_accel = settings.get('vehicle.limits.max_acceleration') # m/s^2 self.max_decel = settings.get('vehicle.limits.max_deceleration') # m/s^2 self.pid_speed = PID(0.5, 0.0, 0.1, windup_limit=20) From bb77bdf557c3659a857872d110c5d92771ecbcbe Mon Sep 17 00:00:00 2001 From: krishauser Date: Wed, 3 Jan 2024 15:49:21 -0500 Subject: [PATCH 022/232] Ignoring movie files --- .gitignore | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/.gitignore b/.gitignore index 68bc17f9f..823b26898 100644 --- a/.gitignore +++ b/.gitignore @@ -3,6 +3,10 @@ __pycache__/ *.py[cod] *$py.class +#movie output +*.mp4 +*.gif + # C extensions *.so From ee7e2446863b72c5c98d77dbb4037bc290672aa2 Mon Sep 17 00:00:00 2001 From: krishauser Date: Thu, 4 Jan 2024 15:27:03 -0500 Subject: [PATCH 023/232] Moved most logging functions functions to logging.py. Added descriptions in readme. --- GEMstack/onboard/execution/entrypoint.py | 9 +- GEMstack/onboard/execution/execution.py | 158 +++++----------- GEMstack/onboard/execution/logging.py | 177 +++++++++++++++++- .../execution/multiprocess_execution.py | 10 +- README.md | 27 +++ 5 files changed, 259 insertions(+), 122 deletions(-) diff --git a/GEMstack/onboard/execution/entrypoint.py b/GEMstack/onboard/execution/entrypoint.py index 3ef495f78..4eb92676c 100644 --- a/GEMstack/onboard/execution/entrypoint.py +++ b/GEMstack/onboard/execution/entrypoint.py @@ -87,17 +87,12 @@ def main(): print(EXECUTION_PREFIX,"Logging to",logfolder) os.makedirs(logfolder,exist_ok=True) - #save settings.yaml - config.save_config(os.path.join(logfolder,'settings.yaml'),settings.settings()) #configure logging for components mission_executor.set_log_folder(logfolder) #configure ROS logging - log_topics = replay_settings.get('ros_topics',[]) + log_topics = log_settings.get('ros_topics',[]) rosbag_options = log_settings.get('rosbag_options','') - if log_topics: - command = 'rosbag record --output-name={} {} {}'.format(os.path.join(logfolder,'vehicle.bag'),rosbag_options,' '.join(log_topics)) - print(EXECUTION_PREFIX,"Recording ROS topics with command",command) - os.system(command) + mission_executor.log_ros_topics(log_topics, rosbag_options) #determine whether to log vehicle interface log_vehicle_interface = log_settings.get('vehicle_interface',False) mission_executor.log_vehicle_interface(log_vehicle_interface) diff --git a/GEMstack/onboard/execution/execution.py b/GEMstack/onboard/execution/execution.py index ac65360b8..e4945d68d 100644 --- a/GEMstack/onboard/execution/execution.py +++ b/GEMstack/onboard/execution/execution.py @@ -3,14 +3,11 @@ from ...state import AllState, MissionEnum from ..component import Component from ...utils.loops import TimedLooper -from ...utils import settings,config +from ...utils import settings from ...utils.serialization import serialize -from ...utils.logging import Logfile -from .logging import VehicleBehaviorLogger,AllStateLogger,LogReplay +from .logging import LoggingManager import json import time -import datetime -import os import importlib import io import contextlib @@ -169,8 +166,7 @@ def __init__(self,c : Component, essential : bool = True): self.essential = essential self.print_stdout = True self.print_stderr = False - self.stdout_log_file = None - self.stderr_log_file = None + self.logging_manager = None # Optional[LoggingManager] self.inputs = c.state_inputs() self.output = c.state_outputs() self.last_update_time = None @@ -189,12 +185,6 @@ def start(self): def stop(self): self.c.cleanup() - if isinstance(self.stdout_log_file,io.TextIOWrapper): - self.stdout_log_file.close() - self.stdout_log_file = None - if isinstance(self.stderr_log_file,io.TextIOWrapper): - self.stderr_log_file.close() - self.stderr_log_file = None def update(self, t : float, state : AllState): if self.next_update_time is None or t >= self.next_update_time: @@ -250,7 +240,6 @@ def update_now(self, t:float, state : AllState): setattr(state,self.output[0]+'_update_time', t) def log_output(self,t,stdout,stderr): - timestr = datetime.datetime.fromtimestamp(t).strftime("%H:%M:%S.%f")[:-3] if stdout: lines = stdout.split('\n') if len(lines) > 0 and len(lines[-1])==0: @@ -260,11 +249,8 @@ def log_output(self,t,stdout,stderr): for l in lines: print(" ",l) print("-------------------------------------------") - if isinstance(self.stdout_log_file,str): - self.stdout_log_file = open(self.stdout_log_file,'w') - if isinstance(self.stdout_log_file,io.TextIOWrapper): - for l in lines: - self.stdout_log_file.write(timestr + ': ' + l + '\n') + if self.logging_manager is not None: + self.logging_manager.log_component_stdout(self.c.__class__.__name__, t, lines) if stderr: lines = stderr.split('\n') if len(lines) > 0 and len(lines[-1])==0: @@ -274,11 +260,8 @@ def log_output(self,t,stdout,stderr): for l in lines: print(" ",l) print("-------------------------------------------") - if isinstance(self.stderr_log_file,str): - self.stderr_log_file = open(self.stderr_log_file,'w') - if isinstance(self.stderr_log_file,io.TextIOWrapper): - for l in lines: - self.stderr_log_file.write(timestr + ': ' + l + '\n') + if self.logging_manager is not None: + self.logging_manager.log_component_stderr(self.c.__class__.__name__, t, lines) @@ -293,14 +276,7 @@ def __init__(self, vehicle_interface): self.pipelines = dict() # type: Dict[str,Tuple[Dict[str,ComponentExecutor],Dict[str,ComponentExecutor],Dict[str,ComponentExecutor]]] self.current_pipeline = 'drive' # type: str self.state = None # type: Optional[AllState] - self.replayed_components = dict() # type Dict[str,str] - self.log_folder = None # type: Optional[str] - self.logged_components = set() # type: Set[str] - self.behavior_log = None - self.run_metadata = dict() # type: dict - self.run_metadata['pipelines'] = [] - self.run_metadata['events'] = [] - self.run_metadata['exit_reason'] = 'unknown' + self.logging_manager = LoggingManager() self.last_loop_time = time.time() def begin(self): @@ -336,17 +312,11 @@ def make_component(self, config_info, component_name, parent_module=None, extra_ component = make_class(config_info,component_name,parent_module,extra_args) if not isinstance(component,Component): raise RuntimeError("Component {} is not a subclass of Component".format(component_name)) - if component_name in self.replayed_components: - #replace behavior of class with the LogReplay class - replay_folder = self.replayed_components[component_name] - outputs = component.state_outputs() - rate = component.rate() - assert rate is not None and rate > 0, "Replayed component {} must have a positive rate".format(component_name) + replacement = self.logging_manager.component_replayer(component_name, component) + if replacement is not None: if EXECUTION_VERBOSITY >= 1: - print(EXECUTION_PREFIX,"Replaying component",component_name,"from log",replay_folder,"with outputs",outputs) - component = LogReplay(outputs, - os.path.join(replay_folder,'behavior_log.json'), - rate=rate) + print(EXECUTION_PREFIX,"Replaying component",component_name,"from log",replacement.logfn,"with outputs",component.state_outputs()) + component = replacement if isinstance(config_info,dict) and config_info.get('multiprocess',False): #wrap component in a multiprocess executor. TODO: not tested yet from .multiprocess_execution import MPComponentExecutor @@ -358,9 +328,7 @@ def make_component(self, config_info, component_name, parent_module=None, extra_ if 'rate' in config_info: executor.dt = 1.0/config_info['rate'] executor.print_stderr = executor.print_stdout = config_info.get('print',True) - if self.log_folder: - executor.stdout_log_file = os.path.join(self.log_folder,component.__class__.__name__+'.stdout.log') - executor.stderr_log_file = os.path.join(self.log_folder,component.__class__.__name__+'.stderr.log') + executor.logging_manager = self.logging_manager self.all_components[identifier] = executor return executor @@ -369,82 +337,59 @@ def always_run(self, component_name, component: ComponentExecutor): self.always_run_components[component_name] = component def add_pipeline(self,name : str, perception : Dict[str,ComponentExecutor], planning : Dict[str,ComponentExecutor], other : Dict[str,ComponentExecutor]): + """Creates a new pipeline with the given components. The pipeline will be + executed in the order perception, planning, other. + """ output = validate_components(perception) output = validate_components(planning, output) validate_components(other, output) self.pipelines[name] = (perception,planning,other) - #TODO: set any custom do_update functions here - - def replay_components(self, replayed_components : list, replay_folder : str): - """Declare that the given components should be replayed from a log folder. - - Further make_component calls to this component will be replaced with - LogReplay objects. - """ - #sanity check: was this item logged? - settings = config.load_config_recursive(os.path.join(replay_folder,'settings.yaml')) - try: - logged_components = settings['run']['log']['components'] - except KeyError: - logged_components = [] - for c in replayed_components: - if c not in logged_components: - raise ValueError("Replay component",c,"was not logged in",replay_folder,"(see settings.yaml)") - self.replayed_components[c] = replay_folder def set_log_folder(self,folder : str): - self.log_folder = folder - #save meta.yaml - self.run_metadata['start_time'] = time.time() - self.run_metadata['start_time_human_readable'] = datetime.datetime.now().strftime("%Y-%m-%d %H:%M:%S") - import subprocess - git_commit_id = subprocess.check_output(['git','rev-parse','HEAD']) - self.run_metadata['git_commit_id'] = git_commit_id.decode('utf-8').strip() - git_branch = subprocess.check_output(['git','rev-parse','--abbrev-ref','HEAD']) - self.run_metadata['git_branch'] = git_branch.decode('utf-8').strip() - for k,c in self.all_components.items(): - c.stdout_log_file = os.path.join(self.log_folder,c.c.__class__.__name__+'.stdout.log') - c.stderr_log_file = os.path.join(self.log_folder,c.c.__class__.__name__+'.stderr.log') - self.dump_log_metadata() + self.logging_manager.set_log_folder(folder) def log_vehicle_interface(self,enabled=True): + """Indicates that the vehicle interface should be logged""" if enabled: - if self.behavior_log is None: - self.behavior_log = Logfile(os.path.join(self.log_folder,'behavior.json'),delta_format=True,mode='w') - self.always_run('vehicle_behavior_logger',ComponentExecutor(VehicleBehaviorLogger(self.behavior_log,self.vehicle_interface))) + logger = self.logging_manager.log_vehicle_behavior(self.vehicle_interface) + self.always_run('vehicle_behavior_logger',ComponentExecutor(logger)) else: raise NotImplementedError("Disabling vehicle interface logging not supported yet") def log_components(self,components : List[str]): - if components: - if self.behavior_log is None: - self.behavior_log = Logfile(os.path.join(self.log_folder,'behavior.json'),delta_format=True,mode='w') - self.logged_components = set(components) + """Indicates that the designated component outputs should be logged.""" + self.logging_manager.log_components(components) def log_state(self,state_attributes : List[str], rate : Optional[float]=None): - log_fn = os.path.join(self.log_folder,'state.json') - self.always_run('state_logger',ComponentExecutor(AllStateLogger(state_attributes,rate,log_fn,self.vehicle_interface))) + """Indicates that the designated state attributes should be logged at the given rate.""" + logger = self.logging_manager.log_state(state_attributes,rate) + self.always_run('state_logger',ComponentExecutor(logger)) + + def log_ros_topics(self, topics : List[str], rosbag_options : str = '') -> Optional[str]: + """Indicates that the designated ros topics should be logged with the given options.""" + command = self.logging_manager.log_ros_topics(topics,rosbag_options) + if command: + print(EXECUTION_PREFIX,"Recording ROS topics with command",command) + + def replay_components(self, replayed_components : list, replay_folder : str): + """Declare that the given components should be replayed from a log folder. + + Further make_component calls to this component will be replaced with + LogReplay objects. + """ + self.logging_manager.replay_components(replayed_components,replay_folder) - def dump_log_metadata(self): - if not self.log_folder: - return - import os - from ...utils import config - config.save_config(os.path.join(self.log_folder,'meta.yaml'),self.run_metadata) - def event(self,event_description : str, event_print_string : str = None): """Logs an event to the metadata and prints a message to the console.""" - if event_print_string is None: - event_print_string = event_description if event_description.endswith('.') else event_description + '.' - self.run_metadata['events'].append({'time':time.time(),'vehicle_time':self.state.t,'description':event_description}) + self.logging_manager.event(self.state.t,event_description) if EXECUTION_VERBOSITY >= 1: + if event_print_string is None: + event_print_string = event_description if event_description.endswith('.') else event_description + '.' print(EXECUTION_PREFIX,event_print_string) - self.dump_log_metadata() def set_exit_reason(self, description): """Sets a main loop exit reason""" - self.run_metadata['exit_reason'] = description - self.dump_log_metadata() + self.logging_manager.exit_event(description) def run(self): """Main entry point. Runs the mission execution loop.""" @@ -457,7 +402,7 @@ def run(self): print(EXECUTION_PREFIX,"'recovery' pipeline not found") return #did we ask to replay any components that don't exist in any pipelines? - for c in self.replayed_components.keys(): + for c in self.logging_manager.replayed_components.keys(): found = False for (name,(perception_components,planning_components,other_components)) in self.pipelines.items(): if c in perception_components or c in planning_components or c in other_components: @@ -491,16 +436,14 @@ def run(self): if validated: self.begin() while validated: - self.run_metadata['pipelines'].append({'time':time.time(),'vehicle_time':self.state.t,'name':self.current_pipeline}) - self.dump_log_metadata() + self.logging_manager.pipeline_start_event(self.state.t,self.current_pipeline) try: if EXECUTION_VERBOSITY >= 1: print(EXECUTION_PREFIX,"Executing pipeline {}".format(self.current_pipeline)) next = self.run_until_switch() if next is None: #done - if self.run_metadata['exit_reason'] == 'unknown': - self.set_exit_reason("normal exit") + self.set_exit_reason("normal exit") break if next not in self.pipelines: if EXECUTION_VERBOSITY >= 1: @@ -544,9 +487,7 @@ def run(self): print("Stopping",k) c.stop() - if self.behavior_log: - self.behavior_log.close() - self.behavior_log = None + self.logging_manager.close() print("Done with execution loop") @@ -672,9 +613,8 @@ def update_components(self, components : Dict[str,ComponentExecutor], state : Al else: updated = components[k].update(t,state) #log component output if necessary - if updated and k in self.logged_components: - if len(components[k].output)!=0: - self.behavior_log.log(state, components[k].output, t) + if updated: + self.logging_manager.log_component_update(k, t, state, components[k].output) class StandardExecutor(ExecutorBase): diff --git a/GEMstack/onboard/execution/logging.py b/GEMstack/onboard/execution/logging.py index 2a93dcba6..f2b7646aa 100644 --- a/GEMstack/onboard/execution/logging.py +++ b/GEMstack/onboard/execution/logging.py @@ -1,7 +1,177 @@ +from __future__ import annotations from ..component import Component -from ...utils import serialization,logging -from typing import List +from ...utils import serialization,logging,config,settings +from typing import List,Optional,Dict,Set,Any import time +import datetime +import os +import io + +class LoggingManager: + """A top level manager of the logging process. This is responsible for + creating log folders, log metadata files, and for replaying components from log + files.""" + def __init__(self): + self.log_folder = None # type: Optional[str] + self.replayed_components = dict() # type Dict[str,str] + self.logged_components = set() # type: Set[str] + self.component_output_loggers = dict() # type: Dict[str,list] + self.behavior_log = None + self.run_metadata = dict() # type: dict + self.run_metadata['pipelines'] = [] + self.run_metadata['events'] = [] + self.run_metadata['exit_reason'] = 'unknown' + + def logging(self) -> bool: + return self.log_folder is not None + + def set_log_folder(self, folder : str) -> None: + self.log_folder = folder + + #save settings.yaml + config.save_config(os.path.join(folder,'settings.yaml'),settings.settings()) + + #save meta.yaml + self.run_metadata['start_time'] = time.time() + self.run_metadata['start_time_human_readable'] = datetime.datetime.now().strftime("%Y-%m-%d %H:%M:%S") + import subprocess + git_commit_id = subprocess.check_output(['git','rev-parse','HEAD']) + self.run_metadata['git_commit_id'] = git_commit_id.decode('utf-8').strip() + git_branch = subprocess.check_output(['git','rev-parse','--abbrev-ref','HEAD']) + self.run_metadata['git_branch'] = git_branch.decode('utf-8').strip() + self.dump_log_metadata() + + def close(self): + if self.behavior_log is not None: + self.behavior_log.close() + self.behavior_log = None + for k,(stdout,stderr) in self.component_output_loggers.items(): + if stdout is not None: + stdout.close() + if stderr is not None: + stderr.close() + self.component_output_loggers = dict() + + def replay_components(self, replayed_components : list, replay_folder : str): + """Declare that the given components should be replayed from a log folder. + + Further make_component calls to this component will be replaced with + LogReplay objects. + """ + #sanity check: was this item logged? + settings = config.load_config_recursive(os.path.join(replay_folder,'settings.yaml')) + try: + logged_components = settings['run']['log']['components'] + except KeyError: + logged_components = [] + for c in replayed_components: + if c not in logged_components: + raise ValueError("Replay component",c,"was not logged in",replay_folder,"(see settings.yaml)") + self.replayed_components[c] = replay_folder + + def component_replayer(self, component_name : str, component : Component) -> Optional[LogReplay]: + if component_name in self.replayed_components: + #replace behavior of class with the LogReplay class + replay_folder = self.replayed_components[component_name] + outputs = component.state_outputs() + rate = component.rate() + assert rate is not None and rate > 0, "Replayed component {} must have a positive rate".format(component_name) + return LogReplay(outputs, + os.path.join(replay_folder,'behavior_log.json'), + rate=rate) + return None + + def dump_log_metadata(self): + if not self.log_folder: + return + from ...utils import config + config.save_config(os.path.join(self.log_folder,'meta.yaml'),self.run_metadata) + + def load_log_metadata(self): + if not self.log_folder: + return + from ...utils import config + self.run_metadata = config.load_config_recursive(os.path.join(self.log_folder,'meta.yaml')) + + def component_stdout_file(self,component_name : str) -> str: + return os.path.join(self.log_folder,component_name+'.stdout.log') + + def component_stderr_file(self,component_name : str) -> str: + return os.path.join(self.log_folder,component_name+'.stderr.log') + + def log_vehicle_behavior(self,vehicle_interface) -> VehicleBehaviorLogger: + if not self.log_folder: + return + if self.behavior_log is None: + self.behavior_log = logging.Logfile(os.path.join(self.log_folder,'behavior.json'),delta_format=True,mode='w') + return VehicleBehaviorLogger(self.behavior_log,vehicle_interface) + + def log_state(self,state_attributes : List[str], rate : Optional[float]=None) -> AllStateLogger: + if not self.log_folder: + return + log_fn = os.path.join(self.log_folder,'state.json') + return AllStateLogger(state_attributes,rate,log_fn) + + def log_components(self,components : List[str]) -> None: + """Indicate that the state output of these components should be logged""" + if not self.log_folder: + return + if components: + if self.behavior_log is None: + self.behavior_log = logging.Logfile(os.path.join(self.log_folder,'behavior.json'),delta_format=True,mode='w') + self.logged_components = set(components) + + def log_ros_topics(self, topics : List[str], rosbag_options : str = '') -> Optional[str]: + if topics: + command = 'rosbag record --output-name={} {} {}'.format(os.path.join(self.logfolder,'vehicle.bag'),rosbag_options,' '.join(topics)) + os.system(command) + return command + return None + + def event(self, vehicle_time : float, event_description : str): + """Logs an event to the metadata.""" + self.run_metadata['events'].append({'time':time.time(),'vehicle_time':vehicle_time,'description':event_description}) + self.dump_log_metadata() + + def pipeline_start_event(self, vehicle_time : float, pipeline_name : str) -> None: + """Logs a pipeline start event to the metadata.""" + self.run_metadata['pipelines'].append({'time':time.time(),'vehicle_time':vehicle_time,'name':pipeline_name}) + self.dump_log_metadata() + + def exit_event(self, description, force = False): + """Exit main loop event. If a prior reason was given, this does nothing + unless force = True.""" + if self.run_metadata['exit_reason'] == 'unknown' or force: + self.run_metadata['exit_reason'] = description + self.dump_log_metadata() + + def log_component_update(self, component : str, vehicle_time : float, state : Any, outputs : List[str]) -> None: + """Component update""" + if component in self.logged_components and len(outputs)!=0: + self.behavior_log.log(state, outputs, vehicle_time) + + def log_component_stdout(self, component : str, vehicle_time: float, msg : List[str]) -> None: + if not self.log_folder: + return + if component not in self.component_output_loggers: + self.component_output_loggers[component] = [None,None] + if self.component_output_loggers[component][0] is None: + self.component_output_loggers[component][0] = open(self.component_stdout_file(component),'w') + timestr = datetime.datetime.fromtimestamp(vehicle_time).strftime("%H:%M:%S.%f")[:-3] + for l in msg: + self.component_output_loggers[component][0].write(timestr + ': ' + l + '\n') + + def log_component_stderr(self, component : str, vehicle_time: float, msg : List[str]) -> None: + if not self.log_folder: + return + if component not in self.component_output_loggers: + self.component_output_loggers[component] = [None,None] + if self.component_output_loggers[component][1] is None: + self.component_output_loggers[component][1] = open(self.component_stderr_file(component),'w') + timestr = datetime.datetime.fromtimestamp(vehicle_time).strftime("%H:%M:%S.%f")[:-3] + for l in msg: + self.component_output_loggers[component][1].write(timestr + ': ' + l + '\n') + class LogReplay(Component): """Substitutes the output of a component with replayed data from a log file. @@ -83,10 +253,9 @@ def update(self,state): class AllStateLogger(Component): - def __init__(self,attributes,rate,log_fn,vehicle_interface): + def __init__(self,attributes,rate,log_fn): self._rate = rate self.attributes = attributes - self.vehicle_interface = vehicle_interface self.state_log = logging.Logfile(log_fn,delta_format=False,mode='w') def rate(self): diff --git a/GEMstack/onboard/execution/multiprocess_execution.py b/GEMstack/onboard/execution/multiprocess_execution.py index 14fde6da4..33a57c68e 100644 --- a/GEMstack/onboard/execution/multiprocess_execution.py +++ b/GEMstack/onboard/execution/multiprocess_execution.py @@ -11,6 +11,11 @@ UPDATE_TIMEOUT = 5.0 class MPComponentExecutor(ComponentExecutor): + """A component executor that uses a subprocess. + + TODO: print stdout / stderr according to the print config and + logging settings. + """ def __init__(self, component : Component, *args, **kwargs): super(MPComponentExecutor, self).__init__(component, *args, **kwargs) self._in_queue = Queue() @@ -30,11 +35,12 @@ def start(self): config = { 'print_stdout': self.print_stdout, 'print_stderr': self.print_stderr, - 'stdout_log_file': self.stdout_log_file, - 'stderr_log_file': self.stderr_log_file, } + old_manager = self.logging_manager + self.logging_manager = None #can't be pickled? self._process = Process(target=self._run, args=(self.c, self._in_queue, self._out_queue, config)) self._process.start() + self.logging_manager = old_manager def stop(self): if self._process and self._process.is_alive(): diff --git a/README.md b/README.md index 74d8e7214..53ef79784 100644 --- a/README.md +++ b/README.md @@ -231,6 +231,33 @@ Note that there are settings that configure **an algorithm's behavior** that per Another way to think about this is that we are trying to **evolve the onboard software stack to generate better behavior** by changing algorithms and their settings. The evolution mechanism is implemented by commits to the repository. On a day to day level, you will be performing different types of runs, such as simulation tests, unit tests, and full integration tests. You may be testing a lot of different conditions but the software stack should remain constant for that suite of tests. If you wish to do an apples-to-apples comparison against a different version of the stack, you should git check out another commit ID, and then perform those same tests. So if you are configuring the software stack, the setting changes should go into `knowledge`. If you are configuring how the software stack works just for a single test, the setting changes should go into the launch script or a keyword argument. +## Launch files, pipeline state machine, and the computation graph + +Onboard behavior begins by launching an executor, which maintains a *pipeline state machine* that can switch between different top-level behaviors. Pipelines are usually switched depending on the health state of the system, and are not appropriate for handling driving logic. For example, the `recovery` pipeline is a mandatory fallback pipeline in case an essential component fails on the vehicle. For most cases, `drive` and `recovery` are sufficient. + +Each pipeline defines a *computation graph* consisting of `Component` subclasses (see `GEMstack.onboard.component`), such as state estimators, object detectors, routing, planners, etc. Each component operates in a loop on attributes of the `AllState` object (see `GEMstack.state.allstate`). Each component defines a *rate* at which its loop should be executed, a set of *state inputs* (part or all of the `AllState`), a set of *state outputs*, and *initialize*, *update*, and *cleanup* callbacks. The basic idea is that all components in the computation graph will be run in a loop as follows: + +```python +state = [SHARED_STATE] +component = MyComponent() +component.initialize() +for every 1/component.rate() seconds, and while still active: + inputs = [state.X for X in component.state_inputs()] + outputs = component.update(*inputs) + for Y,outY in zip(component.state_outputs(),outputs) + state.Y = outY +component.cleanup() +``` + +The computation graph defines an execution order of components and a set of allowable inputs and outputs for each component. This structure is defined in the `run.computation_graph` setting and by default uses `GEMstack/knowledge/defaults/computation_graph.yaml`. + +You should think of `AllState` as a strictly typed blackboard architecture in which items can be read from and written to. If you need to pass data between components, you should add it to the state rather than use alternative techniques, e.g., global variables. This will allow the logging / replay to save and restore system state. Over a long development period, it would be best to be disciplined at versioning. + +It is generally assumed that components will not maintain significant internal state. If you implement a component that does update internal state, then the executor will not be able to reproduce prior behavior from logs. This causes headaches with replay tools and A/B testing. + +If you wish to override the executor to add more pipelines, you will need to create a new executor by subclassing from `ExecutorBase`. This will need to implement the pipeline switching and termination logic as detailed in the `begin`, `update`, `done`, and `end` callbacks. + + ## Branches and submitting pull requests To count as a contribution to the team, you will need to check in your code via pull requests (PRs). PRs should be reviewed by at least one other approver. From 5f94f5879217738140f67772b25307cb4d741857 Mon Sep 17 00:00:00 2001 From: krishauser Date: Thu, 4 Jan 2024 15:58:21 -0500 Subject: [PATCH 024/232] Simulator now split into deterministic and threaded parts --- GEMstack/onboard/interface/gem_simulator.py | 160 ++++++++++++++------ 1 file changed, 111 insertions(+), 49 deletions(-) diff --git a/GEMstack/onboard/interface/gem_simulator.py b/GEMstack/onboard/interface/gem_simulator.py index 1ead2c876..6db392b6c 100644 --- a/GEMstack/onboard/interface/gem_simulator.py +++ b/GEMstack/onboard/interface/gem_simulator.py @@ -2,19 +2,25 @@ from .gem import * from ...mathutils.dubins import SecondOrderDubinsCar from ...mathutils.dynamics import simulate -from ...state import VehicleState,ObjectPose,ObjectFrameEnum,Roadgraph,AgentState,AgentEnum,AgentActivityEnum,Obstacle,Sign +from ...state import VehicleState,ObjectPose,ObjectFrameEnum,Roadgraph,AgentState,AgentEnum,AgentActivityEnum,Obstacle,Sign,AllState from ...knowledge.vehicle.geometry import front2steer,steer2front,heading_rate from ...knowledge.vehicle.dynamics import pedal_positions_to_acceleration, acceleration_to_pedal_positions from ...utils.loops import TimedLooper from ...utils import config +from dataclasses import replace from threading import Thread,Lock import time import numpy as np import copy -class GEMDoubleIntegratorSimulationInterface(GEMInterface): +class GEMDoubleIntegratorSimulation: + """Standard simulation of a second-order Dubins car with a double + integrator controller. The simulation is deterministic and accepts + GEMVehicleReading and GEMVehicleCommand objects. + + Gear switching is instantaneous. Signals are activated instantly. + """ def __init__(self, scene : str = None): - GEMInterface.__init__(self) self.dubins = SecondOrderDubinsCar( wheelAngleMin=settings.get('vehicle.geometry.min_wheel_angle'), wheelAngleMax=settings.get('vehicle.geometry.max_wheel_angle'), @@ -27,7 +33,6 @@ def __init__(self, scene : str = None): wheelBase=settings.get('vehicle.geometry.wheelbase')) self.dt = settings.get('simulator.dt',0.01) - self.real_time_multiplier = settings.get('simulator.real_time_multiplier',1.0) self.roadgraph = None self.agents = [] if scene is None: @@ -60,6 +65,102 @@ def __init__(self, scene : str = None): gear = -2 if self.cur_vehicle_state[3] == 0 else -1 if self.cur_vehicle_state[3] < 0 else 1 steering_wheel_angle = front2steer(self.cur_vehicle_state[4]) self.last_command = GEMVehicleCommand(gear,0,0,0,0,steering_wheel_angle,0) + + def time(self) -> float: + return self.simulation_time + + def simulate(self, T : float, command : Optional[GEMVehicleCommand]): + if command is not None: + self.last_command = command + x,y,theta,v,phi = self.cur_vehicle_state + #print("x %.2f y %.2f theta %.2f v %.2f" % (x,y,theta,v)) + #simulate actuators + accelerator_pedal_position = np.clip(self.last_command.accelerator_pedal_position,0.0,1.0) + brake_pedal_position = np.clip(self.last_command.brake_pedal_position,0.0,1.0) + acceleration = pedal_positions_to_acceleration(accelerator_pedal_position,brake_pedal_position,v,0,1) + acceleration = np.clip(acceleration,*self.dubins.accelRange) + phides = steer2front(self.last_command.steering_wheel_angle) + phides = np.clip(phides,*self.dubins.wheelAngleRange) + phi_deadband = 0.01 + steering_angle_rate = self.last_command.steering_wheel_speed if phides > phi + phi_deadband else \ + (-self.last_command.steering_wheel_speed if phides < phi - phi_deadband else 0.0) + + #simulate dynamics + u = np.array([acceleration,steering_angle_rate]) #acceleration, steering angle rate + #print("Accel %.2f, steering angle current %.2f, desired %.2f, rate %.2f" % (acceleration,phi,phides,steering_angle_rate)) + next = simulate(self.dubins, self.cur_vehicle_state, (lambda x,t: u), T, self.dt) + next_state = next['x'][-1] + x,y,theta,v,phi = next_state + v = np.clip(v,*self.dubins.velocityRange) + next_state = np.array([x,y,theta,v,phi]) + + #simulate sensors + reading = copy.copy(self.last_reading) + reading.steering_wheel_angle = front2steer(phi) + if acceleration > 0: + reading.brake_pedal_position = 0.0 + reading.accelerator_pedal_position = acceleration + else: + reading.brake_pedal_position = -acceleration + reading.accelerator_pedal_position = 0 + reading.speed = v + if v > 0: + reading.gear = 1 + else: + reading.gear = -1 + #copy signals + reading.left_turn_signal = self.last_command.left_turn_signal + reading.right_turn_signal = self.last_command.right_turn_signal + reading.headlights_on = self.last_command.headlights_on + reading.horn_on = self.last_command.horn_on + reading.wiper_level = self.last_command.wiper_level + self.last_reading = reading + + self.cur_vehicle_state = next_state + self.simulation_time += self.dt + + def pose(self) -> ObjectPose: + x,y,theta,v,phi = self.cur_vehicle_state + return ObjectPose(frame=ObjectFrameEnum.ABSOLUTE_CARTESIAN,t=self.simulation_time,x=x,y=y,yaw=theta) + + def state(self) -> VehicleState: + return self.last_reading.to_state(self.pose()) + + def set_pose(self,pose : ObjectPose): + self.cur_vehicle_state[0] = pose.x + self.cur_vehicle_state[1] = pose.y + self.cur_vehicle_state[2] = pose.yaw + + def set_state(self,state : VehicleState): + self.set_pose(state.pose) + self.cur_vehicle_state[3] = state.v + self.cur_vehicle_state[4] = state.front_wheel_angle + + def advance_state(self, state : AllState, command : GEMVehicleCommand, T : float) -> AllState: + """Advances the vehicle state by the given amount of time T + under the given command. Agents are not touched. + """ + self.simulation_time = state.t + abs_pose = state.vehicle.to_frame(ObjectFrameEnum.ABSOLUTE_CARTESIAN, state.vehicle.pose, state.start_vehicle_pose) + self.set_state(abs_pose) + self.simulate(T, command) + return replace(state,t=self.simulation_time,vehicle=self.state()) + + + +class GEMDoubleIntegratorSimulationInterface(GEMInterface): + """Standard GEMInterface for a second-order Dubins car model. + The simulator is run in a separate thread so it acts like a real + vehicle interface. + + TODO: agent simulation? + """ + def __init__(self, scene : str = None): + GEMInterface.__init__(self) + self.simulator = GEMDoubleIntegratorSimulation(scene) + self.real_time_multiplier = settings.get('simulator.real_time_multiplier',1.0) + self.last_reading = self.simulator.last_reading + self.last_command = self.simulator.last_command self.gnss_callback = None self.imu_callback = None self.thread_lock = Lock() @@ -67,7 +168,7 @@ def __init__(self, scene : str = None): self.thread = None def time(self) -> float: - return self.simulation_time + return self.simulator.time() def start(self): assert self.thread is None @@ -104,55 +205,16 @@ def get_reading(self) -> GEMVehicleReading: return self.last_reading def simulate(self,lock : Lock, data : dict): - looper = TimedLooper(self.dt / self.real_time_multiplier,name="Simulation thread") + looper = TimedLooper(self.simulator.dt / self.real_time_multiplier,name="Simulation thread") while looper and not data['stop']: with lock: - x,y,theta,v,phi = self.cur_vehicle_state - #print("x %.2f y %.2f theta %.2f v %.2f" % (x,y,theta,v)) - #simulate actuators - accelerator_pedal_position = np.clip(self.last_command.accelerator_pedal_position,0.0,1.0) - brake_pedal_position = np.clip(self.last_command.brake_pedal_position,0.0,1.0) - acceleration = pedal_positions_to_acceleration(accelerator_pedal_position,brake_pedal_position,v,0,1) - acceleration = np.clip(acceleration,*self.dubins.accelRange) - phides = steer2front(self.last_command.steering_wheel_angle) - phides = np.clip(phides,*self.dubins.wheelAngleRange) - phi_deadband = 0.01 - steering_angle_rate = self.last_command.steering_wheel_speed if phides > phi + phi_deadband else \ - (-self.last_command.steering_wheel_speed if phides < phi - phi_deadband else 0.0) - - #simulate dynamics - u = np.array([acceleration,steering_angle_rate]) #acceleration, steering angle rate - #print("Accel %.2f, steering angle current %.2f, desired %.2f, rate %.2f" % (acceleration,phi,phides,steering_angle_rate)) - next = simulate(self.dubins, self.cur_vehicle_state, (lambda x,t: u), self.dt, self.dt) - next_state = next['x'][-1] - x,y,theta,v,phi = next_state - v = np.clip(v,*self.dubins.velocityRange) - next_state = np.array([x,y,theta,v,phi]) - - #simulate sensors - reading = copy.copy(self.last_reading) - reading.steering_wheel_angle = front2steer(phi) - if acceleration > 0: - reading.brake_pedal_position = 0.0 - reading.accelerator_pedal_position = acceleration - else: - reading.brake_pedal_position = -acceleration - reading.accelerator_pedal_position = 0 - reading.speed = v - if v > 0: - reading.gear = 1 - else: - reading.gear = -1 - self.last_reading = reading + self.simulator.simulate(self.simulator.dt, self.last_command) + self.last_reading = self.simulator.last_reading if self.gnss_callback is not None: - pose = ObjectPose(frame=ObjectFrameEnum.ABSOLUTE_CARTESIAN,t=self.simulation_time,x=x,y=y,yaw=theta) - vehicle_state = self.last_reading.to_state(pose) + vehicle_state = self.simulator.state() self.gnss_callback(vehicle_state) if self.imu_callback is not None: - pose = ObjectPose(frame=ObjectFrameEnum.CURRENT,t=self.simulation_time,x=0,y=0,yaw=theta) + pose = ObjectPose(frame=ObjectFrameEnum.CURRENT,t=self.simulation_time,x=0,y=0,yaw=0) vehicle_state = self.last_reading.to_state(pose) self.imu_callback(vehicle_state) - - self.cur_vehicle_state = next_state - self.simulation_time += self.dt From efded9d77faad1f4a6c353d619873d3d970c5b92 Mon Sep 17 00:00:00 2001 From: krishauser Date: Thu, 4 Jan 2024 15:58:32 -0500 Subject: [PATCH 025/232] Removed homework assignments section --- README.md | 50 +------------------------------------------------- 1 file changed, 1 insertion(+), 49 deletions(-) diff --git a/README.md b/README.md index 53ef79784..90df39f21 100644 --- a/README.md +++ b/README.md @@ -264,57 +264,9 @@ To count as a contribution to the team, you will need to check in your code via - `main`: will contain content that persists between years. Approver: Kris Hauser. - `s2024`: is the "official class vehicle" for this semester's class. Approver: instructor, TAs. -- `s2024_teamX`: will be your team's branch. Approver: instructor, TAs, team members. +- `s2024_groupX`: will be your group's branch. Approver: instructor, TAs, team members. Guidelines: - DO NOT check in large datasets. Instead, keep these around on SSDs. - DO check in trained models, named descriptively. In your PR, describe how you evaluated the model and its results. Choose which model you use in your tests in the settings. - -## Homework assignments - -HW1 (out 1/17, in 1/24): Distress signals -- Skills: Familiarization with ROS and GEMstack structure, Git -- Receive low-level messages from the sensors via ROS and print them -- Send low-level messages to flash distress to the vehicle via ROS -- Use Git to create a fork, create a behavior with your distress signal. Push contributions, and run your fork on GEM. - -HW2 (out 1/24, in 2/7): Stop for a pedestrian. -- Skills: Object detection, trajectory tracking, logic-based motion planning, safety driver training -- Use provided object detector to identify pedestrian from front camera. Run on the vehicle. -- Use a motion planner to create a trajectory that slows and stops at a safe distance when pedestrian appears. -- Modify the planner to resume slowly when the pedestrian disappears -- Run on the vehicle - -HW3 (out 2/7, in 2/21): Pedestrian tracking -- Sensor calibration, scene state, coordinate conversions -- Perform sensor calibration and update current calibration in the knowledge directory -- Use pedestrian detector on multiple cameras to place agents in the scene -- Visualize the sensor data and the estimated agents in `rviz` using `visualization_msgs/MarkerArray`. -- Record the agent trajectories in the START coordinate frame into a log. -- Plot agent trajectories from the log as curves in matplotlib. - -After HW3, the class will split into teams and work on different parts of the stack. Your grades will be determined by your team presentations, individual contributions, within-team peer reviews, and between-team peer reviews. - -Checkpoint 1 (out 2/21, in 3/6) -- Produce design document and present at design review on 3/6. -- Design document should: establish a list of goals. Describe plan for implementation. Assign personnel. Show timeline to implementation and evaluation. -- Peer reviews due next day. - -Checkpoint 2 (out 3/6, in 3/27) -- Progress report presentation on 3/27 -- Presentation should describe implementation progress, unit testing results (concisely describe metrics used), changes in direction, demonstrations, review of code contributions. Discuss integration plans. -- Peer reviews due next day. - -Integration checkpoint 3 (out 3/27, in 4/10) -- Progress report presentation on 4/10 -- Presentation should describe integration results (i.e., pull reviews, metrics), changes in direction, demonstrations, review of code contributions. -- Peer reviews due next day. - -Checkpoint 4 (out 4/10, in 4/24) -- Revise design document to mark achieved checkpoints, integration metrics, and changes of plans. Present at design review on 4/24. - -Final presentation (5/8) -- Pitch contribution of team to "investor" / "CEO". Describe final integration results. -- Reflect on how design has evolved. Review code contributions. - From bc71b63e41b919414ac04223f346ab25e87d244b Mon Sep 17 00:00:00 2001 From: krishauser Date: Sat, 6 Jan 2024 17:39:22 -0500 Subject: [PATCH 026/232] Tentative methods for drawing roadgraph in matplotlib --- GEMstack/state/__init__.py | 2 +- GEMstack/state/roadgraph.py | 40 ++++++++++- GEMstack/utils/mpl_visualization.py | 100 ++++++++++++++++++++++++++-- requirements.txt | 1 + 4 files changed, 136 insertions(+), 7 deletions(-) diff --git a/GEMstack/state/__init__.py b/GEMstack/state/__init__.py index 1aa764123..f84f60669 100644 --- a/GEMstack/state/__init__.py +++ b/GEMstack/state/__init__.py @@ -22,7 +22,7 @@ from .physical_object import PhysicalObject, ObjectPose, ObjectFrameEnum from .trajectory import Path,Trajectory from .vehicle import VehicleState -from .roadgraph import Roadgraph, RoadgraphLane, RoadgraphCurve, RoadgraphRegion, RoadgraphCurveEnum, RoadgraphLaneEnum, RoadgraphRegionEnum, RoadgraphConnectionEnum +from .roadgraph import Roadgraph, RoadgraphLane, RoadgraphCurve, RoadgraphRegion, RoadgraphCurveEnum, RoadgraphLaneEnum, RoadgraphRegionEnum, RoadgraphSurfaceEnum, RoadgraphConnectionEnum from .obstacle import Obstacle, ObstacleMaterialEnum from .sign import Sign, SignEnum, SignalLightEnum, SignState from .roadmap import Roadmap diff --git a/GEMstack/state/roadgraph.py b/GEMstack/state/roadgraph.py index 276acd5f4..3fff54dfc 100644 --- a/GEMstack/state/roadgraph.py +++ b/GEMstack/state/roadgraph.py @@ -6,6 +6,7 @@ from enum import Enum from collections import defaultdict from dataclasses import dataclass, replace, field, asdict +import itertools from typing import List,Tuple,Any,Optional,Dict @@ -67,7 +68,11 @@ class RoadgraphConnectionEnum(Enum): @register class RoadgraphCurve: """Any curve in the roadgraph, whether a stopline, lane boundary, crossing, - wall, etc.""" + wall, etc. + + A curve can consist of multiple segments which may include gaps, e.g. a curb + broken by driveways. These proceed in back to forward order. + """ type : RoadgraphCurveEnum segments : List[List[Tuple[float,float,float]]] #Polyline representation of the curve. List of lists of 3D positions. 3rd element is height above road surface, usually 0 crossable : bool = True #Whether the curve is crossable by ego vehicle @@ -78,10 +83,20 @@ def to_frame(self, orig_frame : ObjectFrameEnum, new_frame : ObjectFrameEnum, current_origin = None, global_origin = None) -> RoadgraphCurve: return replace(self,segments=[[convert_point(p,orig_frame,new_frame,current_origin,global_origin) for p in seg] for seg in self.segments]) + def polyline(self) -> List[Tuple[float,float,float]]: + """Returns a contiguous polyline representation of the curve.""" + return sum(self.segments,[]) + @dataclass @register class RoadgraphLane: + """A lane in the roadgraph. + + By convention, the left and right boundaries are oriented in back to + forward order. The end boundary is from right to left, and the start + boundary is from left to right. + """ type : RoadgraphLaneEnum = RoadgraphLaneEnum.LANE # type of lane surface : RoadgraphSurfaceEnum = RoadgraphSurfaceEnum.PAVEMENT # surface of lane route_name : str = '' # name of the route (e.g., street name) that this lane is on @@ -99,13 +114,34 @@ def to_frame(self, orig_frame : ObjectFrameEnum, new_frame : ObjectFrameEnum, begin=self.begin.to_frame(orig_frame,new_frame,current_origin,global_origin) if self.begin is not None else None, end=self.end.to_frame(orig_frame,new_frame,current_origin,global_origin) if self.end is not None else None) + def outline(self) -> List[Tuple[float,float,float]]: + """Produces a 2D outline of the lane, including elevation. + + The first point is the beginning-right of the lane, and the points + proceed CCW around the lane. + + If the begin and end are None, then straight lines are used to connect + the left and right boundaries. Otherwise, the begin and end curves + are used to connect the boundaries. + """ + if self.left is None or self.right is None: + raise RuntimeError("Cannot produce outline of lane with missing left or right boundary") + points = self.right.polyline() + if self.end is not None: + points += self.end.polyline() + points += self.left.polyline()[::-1] + if self.begin is not None: + points += self.begin.polyline()[::-1] + return [key for key, _group in itertools.groupby(points)] + + @dataclass @register class RoadgraphRegion: type : RoadgraphRegionEnum - outline : List[Tuple[float,float]] + outline : List[Tuple[float,float]] # a list of 2D points defining the outline of the region in CCW order crossable : bool = True def to_frame(self, orig_frame : ObjectFrameEnum, new_frame : ObjectFrameEnum, diff --git a/GEMstack/utils/mpl_visualization.py b/GEMstack/utils/mpl_visualization.py index 7b2f1c5b4..6ddf72fb4 100644 --- a/GEMstack/utils/mpl_visualization.py +++ b/GEMstack/utils/mpl_visualization.py @@ -2,7 +2,33 @@ import matplotlib.patches as patches import numpy as np from . import settings -from ..state import ObjectFrameEnum,ObjectPose,PhysicalObject,VehicleState,Path,Obstacle,AgentState,Roadgraph,RoadgraphLane,RoadgraphCurve,Trajectory,Route,SceneState,AllState +from ..state import ObjectFrameEnum,ObjectPose,PhysicalObject,VehicleState,Path,Obstacle,AgentState,Roadgraph,RoadgraphLane,RoadgraphLaneEnum,RoadgraphCurve,RoadgraphCurveEnum,RoadgraphRegion,RoadgraphRegionEnum,RoadgraphSurfaceEnum,Trajectory,Route,SceneState,AllState + +CURVE_TO_STYLE = { + RoadgraphCurveEnum.LANE_BOUNDARY : {'color':'k','linewidth':1,'linestyle':'-'}, + RoadgraphCurveEnum.CURB : {'color':'k','linewidth':2,'linestyle':'-'}, + RoadgraphCurveEnum.CLIFF : {'color':'r','linewidth':2,'linestyle':'-'}, + RoadgraphCurveEnum.CROSSING_BOUNDARY : {'color':'k','linewidth':1,'linestyle':'--'}, + RoadgraphCurveEnum.PARKING_SPOT_BOUNDARY : {'color':'k','linewidth':1,'linestyle':'-'}, + RoadgraphCurveEnum.STOP_LINE : {'color':'k','linewidth':1,'linestyle':':'}, + RoadgraphCurveEnum.WALL : {'color':'b','linewidth':2,'linestyle':'-'}, + None : {'color':'k','linewidth':1,'linestyle':'-'}, +} + +SURFACE_TO_STYLE = { + RoadgraphSurfaceEnum.PAVEMENT : {'color':(0.5,0.5,0.5,0.2)}, + RoadgraphSurfaceEnum.DIRT : {'color':(160/255.0,82/255.0,45/255.0,0.2)}, + RoadgraphSurfaceEnum.GRASS : {'color':(50/255.0,255/255.0,50/255.0,0.2)}, + RoadgraphSurfaceEnum.GRAVEL : {'color':(0.7,0.7,0.7,0.2),'hatch':'oo'}, + None: {'color':(1,0,0,0.2)}, +} + +REGION_TO_STYLE = { + RoadgraphRegionEnum.INTERSECTION : {'color':'g','linewidth':1,'linestyle':':'}, + RoadgraphRegionEnum.PARKING_LOT : {'color':'b','linewidth':1,'linestyle':':'}, + RoadgraphRegionEnum.CLOSED_COURSE : {'color':'r','linewidth':1,'linestyle':':'}, + RoadgraphRegionEnum.VIRTUAL : {'color':'k','linewidth':1,'linestyle':':'}, +} def plot_pose(pose : ObjectPose, axis_len=0.1, ax=None): """Plots the pose in the given axes. The coordinates @@ -104,6 +130,68 @@ def plot_path(path : Path, color='k', linewidth=1, linestyle='-', ax=None): ys = [p[1] for p in path.points] ax.plot(xs,ys,color=color,linewidth=linewidth,linestyle=linestyle) +def plot_curve(curve : RoadgraphCurve, color=None, linewidth=None, linestyle=None, ax=None): + if ax is None: + ax = plt.gca() + style = CURVE_TO_STYLE.get(curve.type,CURVE_TO_STYLE[None]) + if curve.crossable and curve.type == RoadgraphCurveEnum.LANE_BOUNDARY: + style['linestyle'] = '--' + if color is not None: + style['color'] = color + if linewidth is not None: + style['linewidth'] = linewidth + if linestyle is not None: + style['linestyle'] = linestyle + for seg in curve.segments: + xs = [p[0] for p in seg] + ys = [p[1] for p in seg] + ax.plot(xs,ys,**style) + +def plot_lane(lane : RoadgraphLane, on_route=False, ax=None): + if lane.surface != RoadgraphSurfaceEnum.PAVEMENT: + style = SURFACE_TO_STYLE.get(lane.surface,SURFACE_TO_STYLE[None]) + outline = lane.outline() + x = [p[0] for p in outline] + y = [p[1] for p in outline] + ax.fill(x,y,**style) + if lane.left is not None: + plot_curve(lane.left,ax=ax) + if lane.right is not None: + plot_curve(lane.right,ax=ax) + +def plot_region(region : RoadgraphRegion, color=None, linewidth=None, linestyle=None, ax=None): + if ax is None: + ax = plt.gca() + style = REGION_TO_STYLE.get(region.type,REGION_TO_STYLE[None]) + points = region.outline() + xs = [p[0] for p in points] + [points[0][0]] + ys = [p[1] for p in points] + [points[0][1]] + if color is not None: + style['color'] = color + if linewidth is not None: + style['linewidth'] = linewidth + if linestyle is not None: + style['linestyle'] = linestyle + ax.plot(xs,ys,**style) + +def plot_roadgraph(roadgraph : Roadgraph, route : Route = None, ax=None): + if ax is None: + ax = plt.gca() + #plot lanes + for k,l in roadgraph.lanes.items(): + if route is not None and k in route.lanes: + plot_lane(l,on_route=True,ax=ax) + else: + plot_lane(l,ax=ax) + for c in roadgraph.curves.values(): + plot_curve(c,color='k',ax=ax) + #plot intersections + for r in roadgraph.regions.values(): + plot_region(r,ax=ax) + #plot + for k,o in roadgraph.static_obstacles.items(): + plot_object(o,ax=ax) + def plot_scene(scene : SceneState, xrange=None, yrange=None, ax=None, title = None, show=True): if ax is None: ax = plt.gca() @@ -111,6 +199,7 @@ def plot_scene(scene : SceneState, xrange=None, yrange=None, ax=None, title = No ax.set_aspect('equal') ax.set_xlabel('x (m)') ax.set_ylabel('y (m)') + #set plot range if xrange is not None: if isinstance(xrange,(tuple,list)): ax.set_xlim(xrange[0],xrange[1]) @@ -121,11 +210,14 @@ def plot_scene(scene : SceneState, xrange=None, yrange=None, ax=None, title = No ax.set_ylim(yrange[0],yrange[1]) else: ax.set_ylim(-yrange*0.5,yrange*0.5) - plot_vehicle(scene.vehicle) + #plot roadgraph + plot_roadgraph(scene.roadgraph,scene.route,ax=ax) + #plot vehicle and objects + plot_vehicle(scene.vehicle,ax=ax) for k,a in scene.agents.items(): - plot_object(a) + plot_object(a,ax=ax) for k,o in scene.obstacles.items(): - plot_object(o) + plot_object(o,ax=ax) if title is None: if show: ax.set_title("Scene at t = %.2f" % scene.t) diff --git a/requirements.txt b/requirements.txt index a0d8e42f6..94db8ba43 100644 --- a/requirements.txt +++ b/requirements.txt @@ -1,6 +1,7 @@ opencv-python numpy scipy +matplotlib torch shapely klampt From 038b2c9c877e2fa358a6e62cbf03931e55f50934 Mon Sep 17 00:00:00 2001 From: krishauser Date: Sun, 7 Jan 2024 18:44:50 -0500 Subject: [PATCH 027/232] Added some information about installing hardware drivers --- README.md | 51 ++++++++++++++++++++++++++++++++++++++++++++++----- 1 file changed, 46 insertions(+), 5 deletions(-) diff --git a/README.md b/README.md index 90df39f21..6362f4462 100644 --- a/README.md +++ b/README.md @@ -8,20 +8,61 @@ ## Dependencies -GEMstack uses Python 3.7+ and ROS Noetic. (It is possible to do some offline and simulation work without ROS, but it is highly recommended to install it if you are working on any onboard behavior.) - -In order to interface with the actual vehicle, you will need [PACMOD](http://wiki.ros.org/pacmod) - Autonomoustuff's low level interface to vehicle. +GEMstack uses Python 3.7+ and ROS Noetic. (It is possible to do some offline and simulation work without ROS, but it is highly recommended to install it if you are working on any onboard behavior.) You should also have the following Python dependencies installed, which you can install from this folder using `pip install -r requirements.txt`: -- opencv-python - numpy - scipy +- matplotlib +- opencv-python - torch - shapely - dacite - pyyaml + +In order to interface with the actual GEM e2 vehicle, you will need [PACMOD2](https://github.com/astuff/pacmod2) - Autonomoustuff's low level interface to vehicle. You will also need Autonomoustuff's [sensor message packages](https://github.com/astuff/astuff_sensor_msgs). The onboard computer uses Ubuntu 20.04 with Python 3.8, CUDA 11.6, and NVIDIA driver 515, so to minimize compatibility issues you should ensure that these are installed on your development system. + +From a fresh Ubuntu 20.04 with ROS Noetic and [CUDA 11.6 installed](https://gist.github.com/ksopyla/bf74e8ce2683460d8de6e0dc389fc7f5), you can install these dependencies using: + +```console +sudo apt update +sudo apt-get install git python3 python3-pip wget zstd +source /opt/ros/noetic/setup.bash + +#install Zed SDK +wget https://download.stereolabs.com/zedsdk/4.0/cu121/ubuntu20 -O ZED_SDK_Ubuntu20_cuda11.8_v4.0.8.zstd.run +chmod +x ZED_SDK_Ubuntu20_cuda11.8_v4.0.8.zstd.run +./ZED_SDK_Ubuntu20_cuda11.8_v4.0.8.zstd.run -- silent + +#create ROS Catkin workspace +mkdir catkin_ws +mkdir catkin_ws/src + +#install ROS dependencies and packages +cd catkin_ws/src +git clone https://github.com/hangcui1201/POLARIS_GEM_e2_Real.git +git clone https://github.com/astuff/pacmod2.git +git clone https://github.com/astuff/astuff_sensor_msgs.git +git clone https://github.com/ros-perception/radar_msgs.git +cd radar_msgs; git checkout noetic; cd .. + +cd .. +rosdep install --from-paths src --ignore-src -r -y +catkin_make -DCMAKE_BUILD_TYPE=Release +source devel/setup.bash + +#install GEMstack Python dependencies +cd .. +git clone https://github.com/krishauser/GEMstack.git +cd GEMstack +python3 -m pip install -r requirements.txt +``` + +To build a Docker container with all these prerequisites, you can use the provided Dockerfile by running `docker build -t gem_stack .`. + + ## In this folder Your work will be typically confined to the `GEMstack/` folder, and you may use the `testing/`, `logs/`, `data/`, and `scenes/` folders. @@ -224,7 +265,7 @@ settings.get('key1.key2.attribute') To override a setting temporarily (just for a few run), you can run your script with an optional `--key=value` command-line argument. For example, to set the simulation scene, you can use `--simulator.scene=PATH/TO/SCENE/FILE`. -To create new settings or override a setting more permanently, you should dive into `GEMstack/knowledge/defaults/current.yaml`. This [YAML](https://yaml.org/) formatted configuration file specifies the entire configuration that can be accessed through the `utils.settings` module. One of these files may `!include` other configuration files, so if you are adding a large number of related settings, e.g., for some component module, it would make sense to create that module's own YAML file. For example, you may create a YAML file `mymodule_default_config.yaml` add it to `current.yaml` under the `mymodule` key, e.g.,`mymodule: !include mymodule_default_config.yaml`. (Of course, replace `mymodule` with a descriptive name of your module, duh.) +To create new settings or override a setting more permanently, you should dive into `GEMstack/knowledge/defaults/current.yaml`. This [YAML](https://yaml.org/) formatted configuration file specifies the entire configuration that can be accessed through the `utils.settings` module. One of these files may `!include` other configuration files, so if you are adding a large number of related settings, e.g., for some component module, it would make sense to create that module's own YAML file. For example, you may create a YAML file `mymodule_default_config.yaml` add it to `current.yaml` under the `mymodule` key, e.g., `mymodule: !include mymodule_default_config.yaml`. (Of course, replace `mymodule` with a descriptive name of your module, duh.) Note that there are settings that configure **an algorithm's behavior** that persist between runs, and there are settings that configure **a particular run**. If you want to configure an algorithm, put it in `current.yaml`, a descendant configuration file, or elsewhere in `knowledge`. If you want to configure a single run, you should place those options in the launch file. The `main.py` entrypoint will consume a run launch file and a settings file, and will place all the run configurations in the `run` attribute of the global settings. So if you wish to inspect run details or specify per-run behavior, e.g., see whether we are in a simulation run or a hardware run, your algorithm can check `settings.get('run.mode')`. In general, you should try to minimize how dependent your algorithms are on run settings. From 2ec29e9324ba814c2fc54e7d95b0a19f4b3e25c6 Mon Sep 17 00:00:00 2001 From: Kris Hauser Date: Mon, 8 Jan 2024 12:14:28 -0500 Subject: [PATCH 028/232] Added docker file --- Dockerfile | 49 +++++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 49 insertions(+) create mode 100644 Dockerfile diff --git a/Dockerfile b/Dockerfile new file mode 100644 index 000000000..b35c3b85d --- /dev/null +++ b/Dockerfile @@ -0,0 +1,49 @@ +FROM nvidia/cuda:11.8.0-cudnn8-devel-ubuntu20.04 +#use bash instead of sh +RUN rm /bin/sh && ln -s /bin/bash /bin/sh +RUN apt-get update && apt-get install -y git python3 python3-pip wget zstd +# Install ROS Noetic +RUN apt-get update && apt-get install -y lsb-release gnupg2 +RUN sh -c 'echo "deb http://packages.ros.org/ros/ubuntu focal main" > /etc/apt/sources.list.d/ros-latest.list' +RUN wget https://raw.githubusercontent.com/ros/rosdistro/master/ros.asc +RUN apt-key add ros.asc +RUN apt-get update +RUN DEBIAN_FRONTEND=noninteractive apt-get install -y ros-noetic-desktop +RUN apt-get install -y python3-rosdep python3-rosinstall python3-rosinstall-generator python3-wstool build-essential python3-catkin-tools +RUN rosdep init +RUN rosdep update + +#Install Cuda 11.8 +#RUN wget https://developer.download.nvidia.com/compute/cuda/repos/ubuntu2004/x86_64/cuda-ubuntu2004.pin +#RUN sudo mv cuda-ubuntu2004.pin /etc/apt/preferences.d/cuda-repository-pin-600 +##add public keys +#RUN sudo apt-key adv --fetch-keys https://developer.download.nvidia.com/compute/cuda/repos/ubuntu2004/x86_64/3bf863cc.pub +#RUN sudo add-apt-repository "deb http://developer.download.nvidia.com/compute/cuda/repos/ubuntu2004/x86_64/ /" +#RUN install cuda-toolkit-11-8 + + +# install Zed SDK +RUN wget https://download.stereolabs.com/zedsdk/4.0/cu118/ubuntu20 -O zed_sdk.run +RUN chmod +x zed_sdk.run +RUN ./zed_sdk.run -- silent + +# create ROS Catkin workspace +RUN mkdir -p /catkin_ws/src + +# install ROS dependencies and packages +RUN cd /catkin_ws/src && git clone https://github.com/krishauser/POLARIS_GEM_e2.git +RUN cd /catkin_ws/src && git clone --recurse-submodules https://github.com/stereolabs/zed-ros-wrapper.git +RUN cd /catkin_ws/src && git clone https://github.com/astuff/pacmod2.git + #for some reason the ibeo messages don't work? +RUN cd /catkin_ws/src && git clone https://github.com/astuff/astuff_sensor_msgs.git && rm -rf astuff_sensor_msgs/ibeo_msgs +RUN cd /catkin_ws/src && git clone https://github.com/ros-perception/radar_msgs.git \ + && cd radar_msgs && git checkout noetic + +RUN source /opt/ros/noetic/setup.bash && cd /catkin_ws && rosdep install --from-paths src --ignore-src -r -y +RUN source /opt/ros/noetic/setup.bash && cd /catkin_ws && catkin_make -DCMAKE_BUILD_TYPE=Release + +# install GEMstack Python dependencies +RUN git clone https://github.com/krishauser/GEMstack.git +RUN cd GEMstack && pip3 install -r requirements.txt + +RUN echo /catkin_ws/devel/setup.sh From f35fc389d7f5a8b6efdb356f714221a7ea3172bf Mon Sep 17 00:00:00 2001 From: Kris Hauser Date: Mon, 8 Jan 2024 14:27:25 -0500 Subject: [PATCH 029/232] Corrected PointCloud2 location --- GEMstack/onboard/interface/gem_hardware.py | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/GEMstack/onboard/interface/gem_hardware.py b/GEMstack/onboard/interface/gem_hardware.py index a641ffb87..18186c2ef 100644 --- a/GEMstack/onboard/interface/gem_hardware.py +++ b/GEMstack/onboard/interface/gem_hardware.py @@ -3,9 +3,8 @@ # ROS Headers import rospy -from ackermann_msgs.msg import AckermannDrive from std_msgs.msg import String, Bool, Float32, Float64 -from sensor_msgs import PointCloud2 +from sensor_msgs.msg import PointCloud2 from novatel_gps_msgs.msg import NovatelPosition, NovatelXYZ, Inspva from radar_msgs import RadarTracks from tf.transformations import euler_from_quaternion, quaternion_from_euler From be5237577fdc5992170fe6acb48c5fa39c58de63 Mon Sep 17 00:00:00 2001 From: Kris Hauser Date: Mon, 8 Jan 2024 14:28:29 -0500 Subject: [PATCH 030/232] Moved things to setup/ folder. added catkin_ws to gitignore --- Dockerfile => setup/Dockerfile | 0 setup/get_nvidia_container.sh | 9 +++++++++ setup/setup_this_machine.sh | 30 ++++++++++++++++++++++++++++++ 3 files changed, 39 insertions(+) rename Dockerfile => setup/Dockerfile (100%) create mode 100755 setup/get_nvidia_container.sh create mode 100644 setup/setup_this_machine.sh diff --git a/Dockerfile b/setup/Dockerfile similarity index 100% rename from Dockerfile rename to setup/Dockerfile diff --git a/setup/get_nvidia_container.sh b/setup/get_nvidia_container.sh new file mode 100755 index 000000000..466b1989e --- /dev/null +++ b/setup/get_nvidia_container.sh @@ -0,0 +1,9 @@ +#!/bin/bash + +curl -s -L https://nvidia.github.io/nvidia-container-runtime/gpgkey | \ + sudo apt-key add - +distribution=$(. /etc/os-release;echo $ID$VERSION_ID) +curl -s -L https://nvidia.github.io/nvidia-container-runtime/$distribution/nvidia-container-runtime.list | \ + sudo tee /etc/apt/sources.list.d/nvidia-container-runtime.list +sudo apt-get update +sudo apt-get install nvidia-container-runtime \ No newline at end of file diff --git a/setup/setup_this_machine.sh b/setup/setup_this_machine.sh new file mode 100644 index 000000000..c8de4cfaa --- /dev/null +++ b/setup/setup_this_machine.sh @@ -0,0 +1,30 @@ +#!/bin/bash +sudo apt update +sudo apt-get install git python3 python3-pip wget zstd +source /opt/ros/noetic/setup.bash + +#install Zed SDK +wget https://download.stereolabs.com/zedsdk/4.0/cu121/ubuntu20 -O ZED_SDK_Ubuntu20_cuda11.8_v4.0.8.zstd.run +chmod +x ZED_SDK_Ubuntu20_cuda11.8_v4.0.8.zstd.run +./ZED_SDK_Ubuntu20_cuda11.8_v4.0.8.zstd.run -- silent + +#create ROS Catkin workspace +mkdir catkin_ws +mkdir catkin_ws/src + +#install ROS dependencies and packages +cd catkin_ws/src +git clone https://github.com/hangcui1201/POLARIS_GEM_e2_Real.git +git clone https://github.com/astuff/pacmod2.git +git clone https://github.com/astuff/astuff_sensor_msgs.git +git clone https://github.com/ros-perception/radar_msgs.git +cd radar_msgs; git checkout noetic; cd .. + +cd .. #back to catkin_ws +rosdep install --from-paths src --ignore-src -r -y +catkin_make -DCMAKE_BUILD_TYPE=Release +source devel/setup.bash +cd .. #back to GEMstack + +#install GEMstack Python dependencies +python3 -m pip install -r requirements.txt \ No newline at end of file From f59b9974b3f0220dce5000be218621bc02b33be6 Mon Sep 17 00:00:00 2001 From: Kris Hauser Date: Mon, 8 Jan 2024 14:28:29 -0500 Subject: [PATCH 031/232] Moved things to setup/ folder. added catkin_ws to gitignore --- Dockerfile => setup/Dockerfile | 0 setup/get_nvidia_container.sh | 9 +++++++++ setup/setup_this_machine.sh | 30 ++++++++++++++++++++++++++++++ 3 files changed, 39 insertions(+) rename Dockerfile => setup/Dockerfile (100%) create mode 100755 setup/get_nvidia_container.sh create mode 100644 setup/setup_this_machine.sh diff --git a/Dockerfile b/setup/Dockerfile similarity index 100% rename from Dockerfile rename to setup/Dockerfile diff --git a/setup/get_nvidia_container.sh b/setup/get_nvidia_container.sh new file mode 100755 index 000000000..466b1989e --- /dev/null +++ b/setup/get_nvidia_container.sh @@ -0,0 +1,9 @@ +#!/bin/bash + +curl -s -L https://nvidia.github.io/nvidia-container-runtime/gpgkey | \ + sudo apt-key add - +distribution=$(. /etc/os-release;echo $ID$VERSION_ID) +curl -s -L https://nvidia.github.io/nvidia-container-runtime/$distribution/nvidia-container-runtime.list | \ + sudo tee /etc/apt/sources.list.d/nvidia-container-runtime.list +sudo apt-get update +sudo apt-get install nvidia-container-runtime \ No newline at end of file diff --git a/setup/setup_this_machine.sh b/setup/setup_this_machine.sh new file mode 100644 index 000000000..c8de4cfaa --- /dev/null +++ b/setup/setup_this_machine.sh @@ -0,0 +1,30 @@ +#!/bin/bash +sudo apt update +sudo apt-get install git python3 python3-pip wget zstd +source /opt/ros/noetic/setup.bash + +#install Zed SDK +wget https://download.stereolabs.com/zedsdk/4.0/cu121/ubuntu20 -O ZED_SDK_Ubuntu20_cuda11.8_v4.0.8.zstd.run +chmod +x ZED_SDK_Ubuntu20_cuda11.8_v4.0.8.zstd.run +./ZED_SDK_Ubuntu20_cuda11.8_v4.0.8.zstd.run -- silent + +#create ROS Catkin workspace +mkdir catkin_ws +mkdir catkin_ws/src + +#install ROS dependencies and packages +cd catkin_ws/src +git clone https://github.com/hangcui1201/POLARIS_GEM_e2_Real.git +git clone https://github.com/astuff/pacmod2.git +git clone https://github.com/astuff/astuff_sensor_msgs.git +git clone https://github.com/ros-perception/radar_msgs.git +cd radar_msgs; git checkout noetic; cd .. + +cd .. #back to catkin_ws +rosdep install --from-paths src --ignore-src -r -y +catkin_make -DCMAKE_BUILD_TYPE=Release +source devel/setup.bash +cd .. #back to GEMstack + +#install GEMstack Python dependencies +python3 -m pip install -r requirements.txt \ No newline at end of file From 288b033e6c3477ba648971ae184977d785667961 Mon Sep 17 00:00:00 2001 From: Kris Hauser Date: Mon, 8 Jan 2024 14:49:47 -0500 Subject: [PATCH 032/232] ignoring catkin_ws --- .gitignore | 3 +++ 1 file changed, 3 insertions(+) diff --git a/.gitignore b/.gitignore index 823b26898..0c36d682f 100644 --- a/.gitignore +++ b/.gitignore @@ -7,6 +7,9 @@ __pycache__/ *.mp4 *.gif +# ROS Catkin build +catkin_ws/ + # C extensions *.so From 9bb689b280ab324e97ccedfed5907be0bce1ff0a Mon Sep 17 00:00:00 2001 From: Kris Hauser Date: Mon, 8 Jan 2024 14:50:05 -0500 Subject: [PATCH 033/232] Using more recent package --- setup/setup_this_machine.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) mode change 100644 => 100755 setup/setup_this_machine.sh diff --git a/setup/setup_this_machine.sh b/setup/setup_this_machine.sh old mode 100644 new mode 100755 index c8de4cfaa..e30b3aa23 --- a/setup/setup_this_machine.sh +++ b/setup/setup_this_machine.sh @@ -14,7 +14,7 @@ mkdir catkin_ws/src #install ROS dependencies and packages cd catkin_ws/src -git clone https://github.com/hangcui1201/POLARIS_GEM_e2_Real.git +git clone https://github.com/krishauser/POLARIS_GEM_e2.git git clone https://github.com/astuff/pacmod2.git git clone https://github.com/astuff/astuff_sensor_msgs.git git clone https://github.com/ros-perception/radar_msgs.git From b73b49c67654b9bfcf635f48a536574592e69acf Mon Sep 17 00:00:00 2001 From: krishauser Date: Fri, 12 Jan 2024 16:02:41 -0500 Subject: [PATCH 034/232] Added data gathering mode, info about enabling GEM --- .../defaults/standard_ros_topics.yaml | 12 +++++ GEMstack/launch/fixed_route.yaml | 3 +- GEMstack/launch/fixed_route_sim.yaml | 1 + GEMstack/launch/gather_data.yaml | 45 +++++++++++++++++++ GEMstack/onboard/interface/gem_hardware.py | 20 ++++++--- 5 files changed, 73 insertions(+), 8 deletions(-) create mode 100644 GEMstack/knowledge/defaults/standard_ros_topics.yaml create mode 100644 GEMstack/launch/gather_data.yaml diff --git a/GEMstack/knowledge/defaults/standard_ros_topics.yaml b/GEMstack/knowledge/defaults/standard_ros_topics.yaml new file mode 100644 index 000000000..487efa62b --- /dev/null +++ b/GEMstack/knowledge/defaults/standard_ros_topics.yaml @@ -0,0 +1,12 @@ +#indicates which ROS topics to log in the bag file +- /game_control/joy +- /front_radar/front_radar/objects +- /front_radar/front_radar/radar_tracks +- /lidar1/velodyne_points +- /novatel/inspva +- /zed2/zed_node/depth/camera_info +- /zed2/zed_node/depth/depth_registered +- /zed2/zed_node/left/camera_info +- /zed2/zed_node/left/image_rect_color +- /zed2/zed_node/right/camera_info +- /zed2/zed_node/right/image_rect_color diff --git a/GEMstack/launch/fixed_route.yaml b/GEMstack/launch/fixed_route.yaml index 73efb4dfe..0cb3c990d 100644 --- a/GEMstack/launch/fixed_route.yaml +++ b/GEMstack/launch/fixed_route.yaml @@ -1,3 +1,4 @@ +description: "Drive the GEM vehicle along a fixed route (currently xyhead_highbay_backlot_p.csv)" mode: hardware vehicle_interface: gem_hardware.GEMHardwareInterface mission_execution: StandardExecutor @@ -13,7 +14,7 @@ drive: planning: route_planning: type: StaticRoutePlanner - args: [!relative_path '../knowledge/routes/xyhead_demo_pp.csv'] + args: [!relative_path '../knowledge/routes/xyhead_highbay_backlot_p.csv'] motion_planning: RouteToTrajectoryPlanner trajectory_tracking: pure_pursuit.PurePursuitTrajectoryTracker log: diff --git a/GEMstack/launch/fixed_route_sim.yaml b/GEMstack/launch/fixed_route_sim.yaml index 337746e2d..3f5432e51 100644 --- a/GEMstack/launch/fixed_route_sim.yaml +++ b/GEMstack/launch/fixed_route_sim.yaml @@ -1,3 +1,4 @@ +description: "Drive the GEM vehicle along a fixed route (currently xyhead_highbay_backlot_p.csv) in simulation." mode: simulation vehicle_interface: type: gem_simulator.GEMDoubleIntegratorSimulationInterface diff --git a/GEMstack/launch/gather_data.yaml b/GEMstack/launch/gather_data.yaml new file mode 100644 index 000000000..f7e055808 --- /dev/null +++ b/GEMstack/launch/gather_data.yaml @@ -0,0 +1,45 @@ +description: "Gather data from the GEM vehicle as the operator is driving it manually" +mode: hardware +vehicle_interface: gem_hardware.GEMHardwareInterface +mission_execution: StandardExecutor +# Recovery behavior after a component failure +recovery: + planning: + trajectory_tracking : recovery.StopTrajectoryTracker +# Driving behavior for the GEM vehicle following a fixed route +drive: + perception: + state_estimation : GNSSStateEstimator + perception_normalization : StandardPerceptionNormalizer + planning: + route_planning: + type: StaticRoutePlanner + args: [!relative_path '../knowledge/routes/xyhead_demo_pp.csv'] + motion_planning: RouteToTrajectoryPlanner +log: + # Specify the top-level folder to save the log files. Default is 'logs' + #folder : 'logs' + # If prefix is specified, then the log folder will be named with the prefix followed by the date and time. Default no prefix + #prefix : 'fixed_route_' + # If suffix is specified, then logs will output to folder/prefix+suffix. Default uses date and time as the suffix + #suffix : 'test3' + # Specify which ros topics to record to vehicle.bag. Default records nothing + ros_topics : !include "../knowledge/defaults/standard_ros_topics.yaml" + # Specify options to pass to rosbag record. Default is no options. + #rosbag_options : '--split --size=1024' + # If True, then record all readings / commands of the vehicle interface. Default False + vehicle_interface : True + # Specify which components to record to behavior.json. Default records nothing + components : ['state_estimation'] + # Specify which components of state to record to state.json. Default records nothing + #state: ['all'] + # Specify the rate in Hz at which to record state to state.json. Default records at the pipeline's rate + #state_rate: 10 +replay: # Add items here to set certain topics / inputs to be replayed from logs + # Specify which log folder to replay from + log: + ros_topics : [] + components : [] + +#usually can keep this constant +computation_graph: !include "../knowledge/defaults/computation_graph.yaml" \ No newline at end of file diff --git a/GEMstack/onboard/interface/gem_hardware.py b/GEMstack/onboard/interface/gem_hardware.py index a641ffb87..fe8eeebe8 100644 --- a/GEMstack/onboard/interface/gem_hardware.py +++ b/GEMstack/onboard/interface/gem_hardware.py @@ -39,13 +39,10 @@ def __init__(self): self.stereo_sub = None # -------------------- PACMod setup -------------------- - - self.pacmod_enable = False - # GEM vehicle enable - self.enable_sub = rospy.Subscriber('/pacmod/as_rx/enable', Bool, self.pacmod_enable_callback) - # self.enable_cmd = Bool() - # self.enable_cmd.data = False + self.enable_sub = rospy.Subscriber('/pacmod/as_tx/enable', Bool, self.pacmod_enable_callback) + self.enable_pub = rospy.Publisher('/pacmod/as_rx/enable', Bool, queue_size=1) + self.pacmod_enable = False # GEM vehicle gear control, neutral, forward and reverse, publish once self.gear_pub = rospy.Publisher('/pacmod/as_rx/shift_cmd', PacmodCmd, queue_size=1) @@ -80,13 +77,18 @@ def __init__(self): """TODO: other commands /pacmod/as_rx/headlight_cmd /pacmod/as_rx/horn_cmd - /pacmod/as_rx/shift_cmd /pacmod/as_rx/turn_cmd /pacmod/as_rx/wiper_cmd """ #TODO: publish TwistStamped to /front_radar/front_radar/vehicle_motion to get better radar tracks + def start(self): + print("ENABLING PACMOD") + enable_cmd = Bool() + enable_cmd.data = True + self.enable_pub.publish(enable_cmd) + def speed_callback(self,msg : VehicleSpeedRpt): self.last_reading.speed = msg.vehicle_speed # forward velocity in m/s @@ -107,6 +109,10 @@ def subscribe_sensor(self, name, callback): # PACMod enable callback function def pacmod_enable_callback(self, msg): + if self.pacmod_enable == False and msg.data == True: + print("PACMod enabled") + elif self.pacmod_enable == True and msg.data == False: + print("PACMod disabled") self.pacmod_enable = msg.data def send_first_command(self): From 3526374ad64cfb6900a48a2a9bb0084604e76c65 Mon Sep 17 00:00:00 2001 From: Kris Hauser Date: Mon, 15 Jan 2024 13:57:16 -0500 Subject: [PATCH 035/232] Fixed message location --- GEMstack/onboard/interface/gem_hardware.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/GEMstack/onboard/interface/gem_hardware.py b/GEMstack/onboard/interface/gem_hardware.py index 18186c2ef..f9733566a 100644 --- a/GEMstack/onboard/interface/gem_hardware.py +++ b/GEMstack/onboard/interface/gem_hardware.py @@ -6,7 +6,7 @@ from std_msgs.msg import String, Bool, Float32, Float64 from sensor_msgs.msg import PointCloud2 from novatel_gps_msgs.msg import NovatelPosition, NovatelXYZ, Inspva -from radar_msgs import RadarTracks +from radar_msgs.msg import RadarTracks from tf.transformations import euler_from_quaternion, quaternion_from_euler # GEM PACMod Headers From 528c4d08cf7bbef30a9b17b88ced63bb50fff88a Mon Sep 17 00:00:00 2001 From: Kris Hauser Date: Tue, 16 Jan 2024 13:14:44 -0500 Subject: [PATCH 036/232] Changed ros topics logged by default --- .../defaults/standard_ros_topics.yaml | 28 ++++++++++++++++--- .../defaults/standard_sensor_ros_topics.yaml | 15 ++++++++++ 2 files changed, 39 insertions(+), 4 deletions(-) create mode 100644 GEMstack/knowledge/defaults/standard_sensor_ros_topics.yaml diff --git a/GEMstack/knowledge/defaults/standard_ros_topics.yaml b/GEMstack/knowledge/defaults/standard_ros_topics.yaml index 487efa62b..44aa311f9 100644 --- a/GEMstack/knowledge/defaults/standard_ros_topics.yaml +++ b/GEMstack/knowledge/defaults/standard_ros_topics.yaml @@ -4,9 +4,29 @@ - /front_radar/front_radar/radar_tracks - /lidar1/velodyne_points - /novatel/inspva +- /novatel/imu +- /novatel/bestpos - /zed2/zed_node/depth/camera_info - /zed2/zed_node/depth/depth_registered -- /zed2/zed_node/left/camera_info -- /zed2/zed_node/left/image_rect_color -- /zed2/zed_node/right/camera_info -- /zed2/zed_node/right/image_rect_color +- /zed2/zed_node/rgb/camera_info +- /zed2/zed_node/rgb/image_rect_color +- /zed2/zed_node/imu/data +- /zed2/zed_node/imu/data_raw +- /zed2/zed_node/imu/mag +- /pacmod/as_rx/enable +- /pacmod/as_rx/accel_cmd +- /pacmod/as_rx/brake_cmd +- /pacmod/as_rx/shift_cmd +- /pacmod/as_rx/steer_cmd +- /pacmod/as_rx/turn_cmd +- /pacmod/as_rx/turn_signal_cmd +- /pacmod/as_rx/vehicle_speed_cmd +- /pacmod/as_tx/enable +- /pacmod/as_tx/global_rpt +- /pacmod/as_tx/accel_rpt +- /pacmod/as_tx/brake_rpt +- /pacmod/as_tx/shift_rpt +- /pacmod/as_tx/steer_rpt +- /pacmod/as_tx/turn_rpt +- /pacmod/as_tx/vehicle_speed_rpt + diff --git a/GEMstack/knowledge/defaults/standard_sensor_ros_topics.yaml b/GEMstack/knowledge/defaults/standard_sensor_ros_topics.yaml new file mode 100644 index 000000000..a43c0d536 --- /dev/null +++ b/GEMstack/knowledge/defaults/standard_sensor_ros_topics.yaml @@ -0,0 +1,15 @@ +#indicates which ROS topics to log in the bag file +- /game_control/joy +- /front_radar/front_radar/objects +- /front_radar/front_radar/radar_tracks +- /lidar1/velodyne_points +- /novatel/inspva +- /novatel/imu +- /novatel/bestpos +- /zed2/zed_node/depth/camera_info +- /zed2/zed_node/depth/depth_registered +- /zed2/zed_node/rgb/camera_info +- /zed2/zed_node/rgb/image_rect_color +- /zed2/zed_node/imu/data +- /zed2/zed_node/imu/data_raw +- /zed2/zed_node/imu/mag From a19d0ff4b0b4552e31cb2f901878ddccb6356582 Mon Sep 17 00:00:00 2001 From: Kris Hauser Date: Tue, 16 Jan 2024 13:15:37 -0500 Subject: [PATCH 037/232] Added instructions for setting up a machine with script. Added TODO list --- README.md | 59 ++++++++++++++++++------------------------------------- 1 file changed, 19 insertions(+), 40 deletions(-) diff --git a/README.md b/README.md index 6362f4462..5b6d2da61 100644 --- a/README.md +++ b/README.md @@ -24,43 +24,10 @@ You should also have the following Python dependencies installed, which you can In order to interface with the actual GEM e2 vehicle, you will need [PACMOD2](https://github.com/astuff/pacmod2) - Autonomoustuff's low level interface to vehicle. You will also need Autonomoustuff's [sensor message packages](https://github.com/astuff/astuff_sensor_msgs). The onboard computer uses Ubuntu 20.04 with Python 3.8, CUDA 11.6, and NVIDIA driver 515, so to minimize compatibility issues you should ensure that these are installed on your development system. -From a fresh Ubuntu 20.04 with ROS Noetic and [CUDA 11.6 installed](https://gist.github.com/ksopyla/bf74e8ce2683460d8de6e0dc389fc7f5), you can install these dependencies using: - -```console -sudo apt update -sudo apt-get install git python3 python3-pip wget zstd -source /opt/ros/noetic/setup.bash - -#install Zed SDK -wget https://download.stereolabs.com/zedsdk/4.0/cu121/ubuntu20 -O ZED_SDK_Ubuntu20_cuda11.8_v4.0.8.zstd.run -chmod +x ZED_SDK_Ubuntu20_cuda11.8_v4.0.8.zstd.run -./ZED_SDK_Ubuntu20_cuda11.8_v4.0.8.zstd.run -- silent - -#create ROS Catkin workspace -mkdir catkin_ws -mkdir catkin_ws/src - -#install ROS dependencies and packages -cd catkin_ws/src -git clone https://github.com/hangcui1201/POLARIS_GEM_e2_Real.git -git clone https://github.com/astuff/pacmod2.git -git clone https://github.com/astuff/astuff_sensor_msgs.git -git clone https://github.com/ros-perception/radar_msgs.git -cd radar_msgs; git checkout noetic; cd .. - -cd .. -rosdep install --from-paths src --ignore-src -r -y -catkin_make -DCMAKE_BUILD_TYPE=Release -source devel/setup.bash - -#install GEMstack Python dependencies -cd .. -git clone https://github.com/krishauser/GEMstack.git -cd GEMstack -python3 -m pip install -r requirements.txt -``` +From a fresh Ubuntu 20.04 with ROS Noetic and [CUDA 11.6 installed](https://gist.github.com/ksopyla/bf74e8ce2683460d8de6e0dc389fc7f5), you can install these dependencies by running `setup/setup_this_machine.sh` from the top-level GEMstack folder. + +To build a Docker container with all these prerequisites, you can use the provided Dockerfile by running `docker build -t gem_stack setup/`. For GPU support you will need the NVidia Container Runtime (run `setup/get_nvidia_container.sh` from this directory to install, or see [this tutorial](https://collabnix.com/introducing-new-docker-cli-api-support-for-nvidia-gpus-under-docker-engine-19-03-0-beta-release/) to install) and run `docker run -it --gpus all gem_stack /bin/bash`. -To build a Docker container with all these prerequisites, you can use the provided Dockerfile by running `docker build -t gem_stack .`. ## In this folder @@ -83,6 +50,13 @@ Your work will be typically confined to the `GEMstack/` folder, and you may use In addition, some tools (e.g., pip) will build temporary folders, such as `build` and `GEMstack.egg-info`. You can ignore these. +## TODO list + +- Linux Matplotlib visualizer doesn't play nicely with Ctrl+C +- Test ROS logging and replay +- Test behavior replay +- More sophisticated simulator with sensor messages + ## Package structure All packages are within the `GEMstack/` folder. @@ -198,10 +172,15 @@ You will launch a simulation using: - `python main.py GEMstack/launch/LAUNCH_FILE.yaml` where `LAUNCH_FILE.yaml` is your preferred simulation launch file. Inspect the simulator classes in `GEMstack/onboard/interface/gem_simulator/` for more information about configuring the simulator. To launch onboard behavior you will open four terminal windows, and in each of them run: -- `roscore` -- `roslaunch basic_launch sensor_init.launch` -- `roslaunch basic_launch visualization.launch` -- `python main.py GEMstack/launch/LAUNCH_FILE.yaml` where `LAUNCH_FILE.yaml` is your preferred launch file. + +- `source /opt/ros/noetic/setup.bash` +- `source GEMstack/catkin_ws/devel/setup.bash` to get all of the appropriate ROS environment variables. + +Then run: +- (window 1) `roscore` +- (window 2) `roslaunch basic_launch sensor_init.launch` +- (window 3) `roslaunch basic_launch visualization.launch` +- (window 4) `python main.py GEMstack/launch/LAUNCH_FILE.yaml` where `LAUNCH_FILE.yaml` is your preferred launch file. Note that if you try to use `import GEMstack` in a script or Jupyter notebook anywhere outside of this directory, Python will not know where the `GEMstack` module is. If you wish to import `GEMstack` from a script located in a separate directory, you can put From 7a80d4571a55b56e7a048f1cc7fb2222f126e85a Mon Sep 17 00:00:00 2001 From: Kris Hauser Date: Tue, 16 Jan 2024 13:15:59 -0500 Subject: [PATCH 038/232] Added ROS topics to log --- GEMstack/launch/fixed_route.yaml | 5 +++-- GEMstack/launch/fixed_route_sim.yaml | 1 + GEMstack/launch/gather_data.yaml | 2 +- 3 files changed, 5 insertions(+), 3 deletions(-) diff --git a/GEMstack/launch/fixed_route.yaml b/GEMstack/launch/fixed_route.yaml index 0cb3c990d..7882c9f5d 100644 --- a/GEMstack/launch/fixed_route.yaml +++ b/GEMstack/launch/fixed_route.yaml @@ -24,8 +24,8 @@ log: #prefix : 'fixed_route_' # If suffix is specified, then logs will output to folder/prefix+suffix. Default uses date and time as the suffix #suffix : 'test3' - # Specify which ros topics to record to vehicle.bag. Default records nothing - ros_topics : [] + # Specify which ros topics to record to vehicle.bag. Default records nothing. This records the "standard" ROS topics. + ros_topics : !include "../knowledge/defaults/standard_ros_topics.yaml" # Specify options to pass to rosbag record. Default is no options. #rosbag_options : '--split --size=1024' # If True, then record all readings / commands of the vehicle interface. Default False @@ -39,6 +39,7 @@ log: replay: # Add items here to set certain topics / inputs to be replayed from logs # Specify which log folder to replay from log: + # For replaying sensor data, try !include "../knowledge/defaults/standard_sensor_ros_topics.yaml" ros_topics : [] components : [] diff --git a/GEMstack/launch/fixed_route_sim.yaml b/GEMstack/launch/fixed_route_sim.yaml index 3f5432e51..aad9c71f1 100644 --- a/GEMstack/launch/fixed_route_sim.yaml +++ b/GEMstack/launch/fixed_route_sim.yaml @@ -60,6 +60,7 @@ log: replay: # Add items here to set certain topics / inputs to be replayed from logs # Specify which log folder to replay from log: + # For replaying sensor data, try !include "../knowledge/defaults/standard_sensor_ros_topics.yaml" ros_topics : [] components : [] diff --git a/GEMstack/launch/gather_data.yaml b/GEMstack/launch/gather_data.yaml index f7e055808..872750b42 100644 --- a/GEMstack/launch/gather_data.yaml +++ b/GEMstack/launch/gather_data.yaml @@ -23,7 +23,7 @@ log: #prefix : 'fixed_route_' # If suffix is specified, then logs will output to folder/prefix+suffix. Default uses date and time as the suffix #suffix : 'test3' - # Specify which ros topics to record to vehicle.bag. Default records nothing + # Specify which ros topics to record to vehicle.bag. Default records nothing. This records the "standard" ROS topics. ros_topics : !include "../knowledge/defaults/standard_ros_topics.yaml" # Specify options to pass to rosbag record. Default is no options. #rosbag_options : '--split --size=1024' From 6bd7606a68b3b1c96b99ef79b1bb947092dd1d7f Mon Sep 17 00:00:00 2001 From: Kris Hauser Date: Tue, 16 Jan 2024 13:16:31 -0500 Subject: [PATCH 039/232] Using spawn method to make multiprocessing faster --- GEMstack/onboard/execution/entrypoint.py | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/GEMstack/onboard/execution/entrypoint.py b/GEMstack/onboard/execution/entrypoint.py index 4eb92676c..399b540bf 100644 --- a/GEMstack/onboard/execution/entrypoint.py +++ b/GEMstack/onboard/execution/entrypoint.py @@ -1,12 +1,16 @@ from ...utils import settings,config from ..component import Component from .execution import EXECUTION_PREFIX,ExecutorBase,ComponentExecutor,load_computation_graph,make_class +import multiprocessing from typing import Dict,List,Optional import os def main(): """The main entrypoint for the execution stack.""" + + multiprocessing.set_start_method('spawn') + runconfig = settings.get('run') mode = settings.get('run.mode') vehicle_interface_settings = settings.get('run.vehicle_interface') From d3fbac5e841264ed5682cd1352658bdb997e0683 Mon Sep 17 00:00:00 2001 From: Kris Hauser Date: Tue, 16 Jan 2024 13:16:59 -0500 Subject: [PATCH 040/232] Checking for vehicle faults --- GEMstack/onboard/execution/execution.py | 17 ++++++++++++++++- 1 file changed, 16 insertions(+), 1 deletion(-) diff --git a/GEMstack/onboard/execution/execution.py b/GEMstack/onboard/execution/execution.py index e4945d68d..e7a24e265 100644 --- a/GEMstack/onboard/execution/execution.py +++ b/GEMstack/onboard/execution/execution.py @@ -503,6 +503,11 @@ def validate_sensors(self,numsteps=None): next_print_time = t0 + 1.0 while looper and not sensors_working: self.last_loop_time = time.time() + + for f in self.vehicle_interface.hardware_faults(): + if EXECUTION_VERBOSITY >= 1: + print(EXECUTION_PREFIX,"Hardware fault",f) + self.update_components(perception_components,self.state) sensors_working = all([c.healthy() for c in perception_components.values()]) @@ -533,6 +538,12 @@ def run_until_switch(self): while looper and not self.done(): self.state.t = self.vehicle_interface.time() self.last_loop_time = time.time() + + #check for vehicle faults + for f in self.vehicle_interface.hardware_faults(): + if EXECUTION_VERBOSITY >= 1: + print(EXECUTION_PREFIX,"Hardware fault",f) + self.update_components(perception_components,self.state) #check for faults for name,c in perception_components.items(): @@ -621,7 +632,7 @@ class StandardExecutor(ExecutorBase): def begin(self): try: import rospy - rospy.init_node('GEM executor') + rospy.init_node('GEM_executor') except (ImportError,ModuleNotFoundError): if settings.get('run.mode','hardware') == 'simulation': print(EXECUTION_PREFIX,"Warning, ROS not found, but simulation mode requested") @@ -636,4 +647,8 @@ def done(self): if EXECUTION_VERBOSITY >= 1: print(EXECUTION_PREFIX,"Vehicle has stopped, exiting execution loop.") return True + if 'disengaged' in self.vehicle_interface.hardware_faults(): + if EXECUTION_VERBOSITY >= 1: + print(EXECUTION_PREFIX,"Vehicle has disengaged, exiting execution loop.") + return True return False From ef42a4e5b3f61d961c03707b5ada9dc91b6a7d1f Mon Sep 17 00:00:00 2001 From: Kris Hauser Date: Tue, 16 Jan 2024 13:17:42 -0500 Subject: [PATCH 041/232] Added GlobalRpt, hardware faults --- GEMstack/onboard/interface/gem_hardware.py | 31 +++++++++++++++++++--- 1 file changed, 28 insertions(+), 3 deletions(-) diff --git a/GEMstack/onboard/interface/gem_hardware.py b/GEMstack/onboard/interface/gem_hardware.py index 17e4f6266..8be71f175 100644 --- a/GEMstack/onboard/interface/gem_hardware.py +++ b/GEMstack/onboard/interface/gem_hardware.py @@ -10,11 +10,11 @@ from tf.transformations import euler_from_quaternion, quaternion_from_euler # GEM PACMod Headers -from pacmod_msgs.msg import PositionWithSpeed, PacmodCmd, SystemRptFloat, VehicleSpeedRpt +from pacmod_msgs.msg import PositionWithSpeed, PacmodCmd, SystemRptFloat, VehicleSpeedRpt, GlobalRpt class GEMHardwareInterface(GEMInterface): - """Interface for interfacing with the physical GEM vehicle.""" + """Interface for connnecting to the physical GEM e2 vehicle.""" def __init__(self): GEMInterface.__init__(self) self.last_reading = GEMVehicleReading() @@ -31,11 +31,13 @@ def __init__(self): self.speed_sub = rospy.Subscriber("/pacmod/parsed_tx/vehicle_speed_rpt", VehicleSpeedRpt, self.speed_callback) self.steer_sub = rospy.Subscriber("/pacmod/parsed_tx/steer_rpt", SystemRptFloat, self.steer_callback) + self.global_sub = rospy.Subscriber("/pacmod/parsed_tx/global_rpt", GlobalRpt, self.global_callback) self.gnss_sub = None self.imu_sub = None self.front_radar_sub = None self.lidar_sub = None self.stereo_sub = None + self.faults = [] # -------------------- PACMod setup -------------------- # GEM vehicle enable @@ -93,6 +95,25 @@ def speed_callback(self,msg : VehicleSpeedRpt): def steer_callback(self, msg): self.last_reading.steering_wheel_angle = msg.output + + def global_callback(self, msg): + self.faults = [] + if msg.override_active: + self.faults.append("override_active") + if msg.config_fault_active: + self.faults.append("config_fault_active") + if msg.user_can_timeout: + self.faults.append("user_can_timeout") + if msg.user_can_read_errors: + self.faults.append("user_can_read_errors") + if msg.brake_can_timeout: + self.faults.append("brake_can_timeout") + if msg.steering_can_timeout: + self.faults.append("steering_can_timeout") + if msg.vehicle_can_timeout: + self.faults.append("vehicle_can_timeout") + if msg.subsystem_can_timeout: + self.faults.append("subsystem_can_timeout") def get_reading(self) -> GEMVehicleReading: return self.last_reading @@ -105,7 +126,6 @@ def subscribe_sensor(self, name, callback): elif name == 'front_radar': self.front_radar_sub = rospy.Subscriber("/front_radar/front_radar/radar_tracks", RadarTracks, callback) - # PACMod enable callback function def pacmod_enable_callback(self, msg): if self.pacmod_enable == False and msg.data == True: @@ -114,6 +134,11 @@ def pacmod_enable_callback(self, msg): print("PACMod disabled") self.pacmod_enable = msg.data + def hardware_faults(self) -> List[str]: + if self.pacmod_enable == False: + return self.faults + ["disengaged"] + return self.faults + def send_first_command(self): # ---------- Enable PACMod ---------- From 85cfb7e98bc8016e829c8c20850bb75c8e27f670 Mon Sep 17 00:00:00 2001 From: Kris Hauser Date: Tue, 16 Jan 2024 13:57:04 -0500 Subject: [PATCH 042/232] Added image extraction script --- GEMstack/offboard/rosbag_to_images.py | 62 +++++++++++++++++++++++++++ 1 file changed, 62 insertions(+) create mode 100644 GEMstack/offboard/rosbag_to_images.py diff --git a/GEMstack/offboard/rosbag_to_images.py b/GEMstack/offboard/rosbag_to_images.py new file mode 100644 index 000000000..02dbd0a89 --- /dev/null +++ b/GEMstack/offboard/rosbag_to_images.py @@ -0,0 +1,62 @@ +#!/usr/bin/env python +# -*- coding: utf-8 -*- + +# Copyright 2016 Massachusetts Institute of Technology + +# 1-16-2024: Kris Hauser: Modified to extract multiple images from multiple topics + +"""Extract images from a rosbag. +""" + +import os +import argparse + +import cv2 + +import rosbag +from sensor_msgs.msg import Image +from cv_bridge import CvBridge + +def main(): + """Extract a folder of images from a rosbag. + """ + parser = argparse.ArgumentParser(description="Extract images from a ROS bag.") + parser.add_argument("bag_file", help="Input ROS bag.") + parser.add_argument("output_dir", help="Output directory.") + parser.add_argument("image_topics", help="Image topic.", default="/zed2/zed_node/depth/depth_registered,/zed2/zed_node/rgb/image_rect_color") + parser.add_argument("output_prefix", help="Output prefix(es).", default="") + + args = parser.parse_args() + topics = args.image_topics.split(',') + output_prefixes = args.output_prefix.split(',') + if len(output_prefixes) == 0: + output_prefixes = [topic.split('/')[-1] for topic in topics] + if len(set(output_prefixes)) != len(output_prefixes): + print("Got multiple topics with the same name, but no output prefixes specified.") + return 1 + if len(topics) != len(output_prefixes): + print("Got %i topics but %i output prefixes." % (len(topics), len(output_prefixes))) + return + + print("Extract images from %s on topics %s into %s" % (args.bag_file, + ', '.join(topics), args.output_dir)) + + bag = rosbag.Bag(args.bag_file, "r") + bridge = CvBridge() + count = 0 + for topic, msg, t in bag.read_messages(topics=topics): + cv_img = bridge.imgmsg_to_cv2(msg, desired_encoding="passthrough") + + i = topics.index(topic) + prefix = output_prefixes[i] + cv2.imwrite(os.path.join(args.output_dir, "%s%06i.png" % (prefix,count)), cv_img) + print("Wrote image %s %i" % (prefix,count)) + + count += 1 + + bag.close() + + return 0 + +if __name__ == '__main__': + exit(main()) \ No newline at end of file From e67263669eec4d47f2fd98d4b38d0a2d6dc3217c Mon Sep 17 00:00:00 2001 From: Kris Hauser Date: Tue, 16 Jan 2024 16:20:54 -0500 Subject: [PATCH 043/232] Added log clearing utility --- clear_logs.sh | 3 +++ 1 file changed, 3 insertions(+) create mode 100755 clear_logs.sh diff --git a/clear_logs.sh b/clear_logs.sh new file mode 100755 index 000000000..6011f73bc --- /dev/null +++ b/clear_logs.sh @@ -0,0 +1,3 @@ +#!/bin/bash +rm -r logs/20* +#only valid until the year 2100! \ No newline at end of file From 51d1fffda3b6ae2c4560806ab32a5216c4146e11 Mon Sep 17 00:00:00 2001 From: Kris Hauser Date: Tue, 16 Jan 2024 16:21:21 -0500 Subject: [PATCH 044/232] Cleaned up Ctrl+C exit on linux while movie is being saved --- .../onboard/visualization/mpl_visualization.py | 14 ++++++++++++-- 1 file changed, 12 insertions(+), 2 deletions(-) diff --git a/GEMstack/onboard/visualization/mpl_visualization.py b/GEMstack/onboard/visualization/mpl_visualization.py index dd0d743a6..ea311c88c 100644 --- a/GEMstack/onboard/visualization/mpl_visualization.py +++ b/GEMstack/onboard/visualization/mpl_visualization.py @@ -1,5 +1,6 @@ from ...utils import mpl_visualization from ..component import Component +import matplotlib import matplotlib.pyplot as plt import matplotlib.animation as animation import time @@ -24,6 +25,7 @@ def state_inputs(self): return ['all'] def initialize(self): + matplotlib.use('TkAgg') if self.save_as is not None: print("Saving Matplotlib visualization to",self.save_as) if self.save_as.endswith('.gif'): @@ -55,8 +57,16 @@ def update(self, state): self.fig.canvas.draw_idle() self.fig.canvas.flush_events() - if self.save_as is not None: - self.writer.grab_frame() + if self.save_as is not None and self.writer is not None: + try: + self.writer.grab_frame() + except IOError as e: + if e.errno == 32: #broken pipe + self.writer = None + print("Movie write process terminated, saved Matplotlib visualization to",self.save_as) + return + print(e) + pass def cleanup(self): if self.writer: From ed6ac2f574d8cb4de54d5b8dd17cf3f40e6b4bce Mon Sep 17 00:00:00 2001 From: Kris Hauser Date: Tue, 16 Jan 2024 16:21:37 -0500 Subject: [PATCH 045/232] Less verbose defaults --- GEMstack/launch/fixed_route_sim.yaml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/GEMstack/launch/fixed_route_sim.yaml b/GEMstack/launch/fixed_route_sim.yaml index aad9c71f1..3df702184 100644 --- a/GEMstack/launch/fixed_route_sim.yaml +++ b/GEMstack/launch/fixed_route_sim.yaml @@ -25,13 +25,13 @@ drive: motion_planning: RouteToTrajectoryPlanner trajectory_tracking: type: pure_pursuit.PurePursuitTrajectoryTracker - print: True + print: False #visualization methods visualization: type: mpl_visualization.MPLVisualization args: - rate: 10 + rate: 8 #Don't include save_as if you don't want to save the video #save_as: save_as: "fixed_route_sim.mp4" From c39bb79f1b8edfe72fbb64709345bdb0b3b9a4fb Mon Sep 17 00:00:00 2001 From: Kris Hauser Date: Tue, 16 Jan 2024 16:22:09 -0500 Subject: [PATCH 046/232] Fixed loop overrun message --- GEMstack/onboard/execution/execution.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/GEMstack/onboard/execution/execution.py b/GEMstack/onboard/execution/execution.py index e7a24e265..002ac43d4 100644 --- a/GEMstack/onboard/execution/execution.py +++ b/GEMstack/onboard/execution/execution.py @@ -196,7 +196,7 @@ def update(self, t : float, state : AllState): self.next_update_time += self.dt if self.next_update_time < t and self.dt > 0: if EXECUTION_VERBOSITY >= 1: - print(EXECUTION_PREFIX,"Component {} is running behind, overran dt by {} seconds".format(self.c,self.dt,t-self.next_update_time)) + print(EXECUTION_PREFIX,"Component {} is running behind, overran dt {} by {} seconds".format(self.c,self.dt,t-self.next_update_time)) self.num_overruns += 1 self.overrun_amount += t - self.next_update_time self.next_update_time = t + self.dt @@ -502,6 +502,7 @@ def validate_sensors(self,numsteps=None): t0 = time.time() next_print_time = t0 + 1.0 while looper and not sensors_working: + self.state.t = self.vehicle_interface.time() self.last_loop_time = time.time() for f in self.vehicle_interface.hardware_faults(): From 9f1386ebd14cbc5e5e147fdbd658f151ed9e8179 Mon Sep 17 00:00:00 2001 From: Kris Hauser Date: Tue, 16 Jan 2024 16:22:44 -0500 Subject: [PATCH 047/232] start() Pauses for initialization in subprocess --- .../onboard/execution/multiprocess_execution.py | 14 ++++++++++++++ 1 file changed, 14 insertions(+) diff --git a/GEMstack/onboard/execution/multiprocess_execution.py b/GEMstack/onboard/execution/multiprocess_execution.py index 33a57c68e..69064be57 100644 --- a/GEMstack/onboard/execution/multiprocess_execution.py +++ b/GEMstack/onboard/execution/multiprocess_execution.py @@ -41,6 +41,19 @@ def start(self): self._process = Process(target=self._run, args=(self.c, self._in_queue, self._out_queue, config)) self._process.start() self.logging_manager = old_manager + res = self._out_queue.get() + if isinstance(res,tuple) and isinstance(res[0],Exception): + print("Traceback:") + for line in res[1]: + print(line) + print("Exception:",res[0]) + + self._process.join() + self._process.close() + self._process = None + raise RuntimeError("Error initializng "+self.c.__class__.__name__) + if res !='initialized': + raise RuntimeError("Uh... didn't hear back from subprocess? "+self.c.__class__.__name__) def stop(self): if self._process and self._process.is_alive(): @@ -61,6 +74,7 @@ def _run(self, component : Component, inqueue : Queue, outqueue : Queue, config) print("Error initializing",component.__class__.__name__) outqueue.put((e,traceback.format_tb(e.__traceback__))) return + outqueue.put('initialized') while True: #update try: From cb75fb55c7491f12c145809b31dd64903998944e Mon Sep 17 00:00:00 2001 From: krishauser Date: Tue, 16 Jan 2024 23:47:16 -0500 Subject: [PATCH 048/232] More specific README --- README.md | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/README.md b/README.md index 6362f4462..bb6a4d92e 100644 --- a/README.md +++ b/README.md @@ -8,7 +8,7 @@ ## Dependencies -GEMstack uses Python 3.7+ and ROS Noetic. (It is possible to do some offline and simulation work without ROS, but it is highly recommended to install it if you are working on any onboard behavior.) +GEMstack uses Python 3.7+ and ROS Noetic. (It is possible to do some offline and simulation work without ROS, but it is highly recommended to install it if you are working on any onboard behavior or training for rosbag files.) You should also have the following Python dependencies installed, which you can install from this folder using `pip install -r requirements.txt`: @@ -17,6 +17,7 @@ You should also have the following Python dependencies installed, which you can - matplotlib - opencv-python - torch +- klampt - shapely - dacite - pyyaml From f4dc00eafd9e1f9d9e8276a7390392101d2ee460 Mon Sep 17 00:00:00 2001 From: gem Date: Wed, 17 Jan 2024 13:46:26 -0600 Subject: [PATCH 049/232] Fixed rosbag tools --- GEMstack/offboard/rosbag_size_by_topic.py | 28 +++++++++++++++++++++++ 1 file changed, 28 insertions(+) create mode 100644 GEMstack/offboard/rosbag_size_by_topic.py diff --git a/GEMstack/offboard/rosbag_size_by_topic.py b/GEMstack/offboard/rosbag_size_by_topic.py new file mode 100644 index 000000000..e1d360c8a --- /dev/null +++ b/GEMstack/offboard/rosbag_size_by_topic.py @@ -0,0 +1,28 @@ +#!/usr/bin/env python +# Prints total cumulative serialized msg size in bytes per topic +# Calculation takes approximately 1sec/GB +# Usage: python rosbag_size_by_topic.py BAG_FILE_PATH +# +#from https://answers.ros.org/question/318667/using-rosbag-to-get-size-of-each-topic/ + +import rosbag +import sys + +topic_size_dict = {} +for topic, msg, time in rosbag.Bag(sys.argv[1], "r").read_messages(raw=True): + topic_size_dict[topic] = topic_size_dict.get(topic, 0) + len(msg[1]) + +topic_size = list(topic_size_dict.items()) +topic_size.sort(key=lambda x: x[1], reverse=False) + +for topic, size in topic_size: + if size < 1000: + print("{:7d}B {}".format(size, topic)) + elif size >= 1000000000000: + print("{:7.2f}T {}".format(size/1000000000000, topic)) + elif size >= 1000000000: + print("{:7.2f}G {}".format(size/1000000000, topic)) + elif size >= 1000000: + print("{:7.2f}M {}".format(size/1000000, topic)) + elif size >= 1000: + print("{:7.2f}K {}".format(size/1000, topic)) \ No newline at end of file From b07f2ec5e2aeaddfe2c50bf2c641f7914d7628ae Mon Sep 17 00:00:00 2001 From: gem Date: Wed, 17 Jan 2024 13:47:04 -0600 Subject: [PATCH 050/232] Fixed gather data launch --- GEMstack/launch/gather_data.yaml | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/GEMstack/launch/gather_data.yaml b/GEMstack/launch/gather_data.yaml index 872750b42..93c56636f 100644 --- a/GEMstack/launch/gather_data.yaml +++ b/GEMstack/launch/gather_data.yaml @@ -2,11 +2,12 @@ description: "Gather data from the GEM vehicle as the operator is driving it man mode: hardware vehicle_interface: gem_hardware.GEMHardwareInterface mission_execution: StandardExecutor +require_engaged: False # Recovery behavior after a component failure recovery: planning: trajectory_tracking : recovery.StopTrajectoryTracker -# Driving behavior for the GEM vehicle following a fixed route +# Driving behavior for the GEM vehicle. Runs perception and planner but doesn't execute anything (no controller). drive: perception: state_estimation : GNSSStateEstimator @@ -14,7 +15,7 @@ drive: planning: route_planning: type: StaticRoutePlanner - args: [!relative_path '../knowledge/routes/xyhead_demo_pp.csv'] + args: [!relative_path '../knowledge/routes/xyhead_highbay_backlot_p.csv'] motion_planning: RouteToTrajectoryPlanner log: # Specify the top-level folder to save the log files. Default is 'logs' From 1b62daf21bd0d07ca09e7fad5fdf8217ea924385 Mon Sep 17 00:00:00 2001 From: gem Date: Wed, 17 Jan 2024 13:47:09 -0600 Subject: [PATCH 051/232] Fixed rosbag tools --- GEMstack/offboard/rosbag_to_images.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/GEMstack/offboard/rosbag_to_images.py b/GEMstack/offboard/rosbag_to_images.py index 02dbd0a89..a6c1ff557 100644 --- a/GEMstack/offboard/rosbag_to_images.py +++ b/GEMstack/offboard/rosbag_to_images.py @@ -23,13 +23,13 @@ def main(): parser = argparse.ArgumentParser(description="Extract images from a ROS bag.") parser.add_argument("bag_file", help="Input ROS bag.") parser.add_argument("output_dir", help="Output directory.") - parser.add_argument("image_topics", help="Image topic.", default="/zed2/zed_node/depth/depth_registered,/zed2/zed_node/rgb/image_rect_color") - parser.add_argument("output_prefix", help="Output prefix(es).", default="") + parser.add_argument('-t',"--topics", help="Image topic.", default="/zed2/zed_node/depth/depth_registered,/zed2/zed_node/rgb/image_rect_color") + parser.add_argument('-o','--output_prefix', help="Output prefix(es).", default="") args = parser.parse_args() - topics = args.image_topics.split(',') + topics = args.topics.split(',') output_prefixes = args.output_prefix.split(',') - if len(output_prefixes) == 0: + if args.output_prefix=='': output_prefixes = [topic.split('/')[-1] for topic in topics] if len(set(output_prefixes)) != len(output_prefixes): print("Got multiple topics with the same name, but no output prefixes specified.") From 988e88f2643b5d8b73b0d442027d6cc0d0a60050 Mon Sep 17 00:00:00 2001 From: gem Date: Wed, 17 Jan 2024 13:47:26 -0600 Subject: [PATCH 052/232] fixed bugs --- GEMstack/onboard/execution/entrypoint.py | 2 +- GEMstack/onboard/execution/execution.py | 7 ++++- GEMstack/onboard/execution/logging.py | 26 ++++++++++++++++--- GEMstack/onboard/interface/gem_hardware.py | 4 +++ .../onboard/perception/state_estimation.py | 1 + GEMstack/state/physical_object.py | 9 +++++-- 6 files changed, 42 insertions(+), 7 deletions(-) diff --git a/GEMstack/onboard/execution/entrypoint.py b/GEMstack/onboard/execution/entrypoint.py index 399b540bf..68ef899a3 100644 --- a/GEMstack/onboard/execution/entrypoint.py +++ b/GEMstack/onboard/execution/entrypoint.py @@ -43,7 +43,7 @@ def main(): if isinstance(visualization_settings,dict): #one visualizer visualizers.append(mission_executor.make_component(visualization_settings,'visualization','GEMstack.onboard.visualization',{'vehicle_interface':vehicle_interface})) - else: + elif isinstance(visualization_settings,list): #multiple visualizers for v in visualization_settings: visualizers.append(mission_executor.make_component(v,'visualization','GEMstack.onboard.visualization',{'vehicle_interface':vehicle_interface})) diff --git a/GEMstack/onboard/execution/execution.py b/GEMstack/onboard/execution/execution.py index 002ac43d4..69c30e49b 100644 --- a/GEMstack/onboard/execution/execution.py +++ b/GEMstack/onboard/execution/execution.py @@ -506,6 +506,8 @@ def validate_sensors(self,numsteps=None): self.last_loop_time = time.time() for f in self.vehicle_interface.hardware_faults(): + if f == 'disengaged' and not settings.get('run.require_engaged',False): + continue if EXECUTION_VERBOSITY >= 1: print(EXECUTION_PREFIX,"Hardware fault",f) @@ -542,6 +544,8 @@ def run_until_switch(self): #check for vehicle faults for f in self.vehicle_interface.hardware_faults(): + if f == 'disengaged' and not settings.get('run.require_engaged',False): + continue if EXECUTION_VERBOSITY >= 1: print(EXECUTION_PREFIX,"Hardware fault",f) @@ -630,7 +634,8 @@ def update_components(self, components : Dict[str,ComponentExecutor], state : Al class StandardExecutor(ExecutorBase): - def begin(self): + def __init__(self, vehicle_interface): + ExecutorBase.__init__(self,vehicle_interface) try: import rospy rospy.init_node('GEM_executor') diff --git a/GEMstack/onboard/execution/logging.py b/GEMstack/onboard/execution/logging.py index f2b7646aa..db5262010 100644 --- a/GEMstack/onboard/execution/logging.py +++ b/GEMstack/onboard/execution/logging.py @@ -5,6 +5,7 @@ import time import datetime import os +import subprocess import io class LoggingManager: @@ -17,6 +18,7 @@ def __init__(self): self.logged_components = set() # type: Set[str] self.component_output_loggers = dict() # type: Dict[str,list] self.behavior_log = None + self.rosbag_process = None self.run_metadata = dict() # type: dict self.run_metadata['pipelines'] = [] self.run_metadata['events'] = [] @@ -123,9 +125,11 @@ def log_components(self,components : List[str]) -> None: def log_ros_topics(self, topics : List[str], rosbag_options : str = '') -> Optional[str]: if topics: - command = 'rosbag record --output-name={} {} {}'.format(os.path.join(self.logfolder,'vehicle.bag'),rosbag_options,' '.join(topics)) - os.system(command) - return command + command = ['rosbag','record','--output-name={}'.format(os.path.join(self.log_folder,'vehicle.bag'))] + command += rosbag_options.split() + command += topics + self.rosbag_process = subprocess.Popen(command, stdin=subprocess.PIPE, stdout=subprocess.PIPE) + return ' '.join(command) return None def event(self, vehicle_time : float, event_description : str): @@ -172,6 +176,22 @@ def log_component_stderr(self, component : str, vehicle_time: float, msg : List[ for l in msg: self.component_output_loggers[component][1].write(timestr + ': ' + l + '\n') + def close(self): + if self.rosbag_process is not None: + out,err = self.rosbag_process.communicate() # Will block + print('-------------------------------------------') + print("rosbag output:") + print(out) + print() + loginfo = os.stat(os.path.join(self.log_folder,'vehicle.bag')) + print("Logged to",os.path.join(self.log_folder,'vehicle.bag')) + print('Log file size in MegaBytes is {}'.format(loginfo.st_size / (1024 * 1024))) + print('-------------------------------------------') + self.rosbag_process = None + + def __del__(self): + self.close() + class LogReplay(Component): """Substitutes the output of a component with replayed data from a log file. diff --git a/GEMstack/onboard/interface/gem_hardware.py b/GEMstack/onboard/interface/gem_hardware.py index 8be71f175..1a25a4893 100644 --- a/GEMstack/onboard/interface/gem_hardware.py +++ b/GEMstack/onboard/interface/gem_hardware.py @@ -89,6 +89,10 @@ def start(self): enable_cmd = Bool() enable_cmd.data = True self.enable_pub.publish(enable_cmd) + + def time(self): + seconds = rospy.get_time() + return seconds def speed_callback(self,msg : VehicleSpeedRpt): self.last_reading.speed = msg.vehicle_speed # forward velocity in m/s diff --git a/GEMstack/onboard/perception/state_estimation.py b/GEMstack/onboard/perception/state_estimation.py index 1ad4576d6..1a09d8924 100644 --- a/GEMstack/onboard/perception/state_estimation.py +++ b/GEMstack/onboard/perception/state_estimation.py @@ -23,6 +23,7 @@ def __init__(self, vehicle_interface : GEMInterface): # Get GNSS information def inspva_callback(self, inspva_msg): self.gnss_pose = ObjectPose(ObjectFrameEnum.GLOBAL, + t=self.vehicle_interface.time(), x=inspva_msg.longitude, y=inspva_msg.latitude, z=inspva_msg.height, diff --git a/GEMstack/state/physical_object.py b/GEMstack/state/physical_object.py index bb49cbf80..8d3455cfe 100644 --- a/GEMstack/state/physical_object.py +++ b/GEMstack/state/physical_object.py @@ -74,6 +74,7 @@ def transform(self) -> np.ndarray: def apply(self,point): """Applies this pose to a local (x,y) or (x,y,z) coordinate.""" + assert len(point) in [2,3],"Must provide a 2D or 3D point" oz = self.z if self.z is not None else 0.0 if self.frame == ObjectFrameEnum.GLOBAL: east_m,north_m = point[:2] @@ -82,7 +83,7 @@ def apply(self,point): if len(point) == 2: return (lon,lat) else: - return (lon,lat) + tuple(point[2:] + oz) + return (lon,lat, point[2] + oz) if len(point) == 2: return tuple(self.rotation2d().dot(point) + self.translation()[:2]) else: @@ -91,12 +92,16 @@ def apply(self,point): def apply_inv(self,point): """Applies the inverse of this pose to an (x,y) or (x,y,z) coordinate specified in the same frame as this.""" + assert len(point) in [2,3],"Must provide a 2D or 3D point" oz = self.z if self.z is not None else 0.0 if self.frame == ObjectFrameEnum.GLOBAL: lon,lat = point[:2] olon,olat = self.x,self.y east_m, north_m = transforms.lat_lon_to_xy(lat,lon,olat,olon) - return (east_m,north_m) + tuple(point[2:] + oz) + if len(point) == 2: + return (east_m, north_m) + else: + return (east_m, north_m, point[2] - oz) if len(point) == 2: return tuple(self.rotation2d().T.dot(np.array(point)-self.translation()[:2])) else: From cd8927f8287d26bb451b6ed1e9e913f36e46b3a5 Mon Sep 17 00:00:00 2001 From: krishauser Date: Thu, 18 Jan 2024 10:43:19 -0500 Subject: [PATCH 053/232] Fixed ROS node execution --- GEMstack/onboard/execution/entrypoint.py | 20 ++++++++++++++++++-- GEMstack/onboard/execution/execution.py | 9 --------- 2 files changed, 18 insertions(+), 11 deletions(-) diff --git a/GEMstack/onboard/execution/entrypoint.py b/GEMstack/onboard/execution/entrypoint.py index 68ef899a3..f66fb727e 100644 --- a/GEMstack/onboard/execution/entrypoint.py +++ b/GEMstack/onboard/execution/entrypoint.py @@ -9,8 +9,7 @@ def main(): """The main entrypoint for the execution stack.""" - multiprocessing.set_start_method('spawn') - + multiprocessing.set_start_method('spawn') runconfig = settings.get('run') mode = settings.get('run.mode') vehicle_interface_settings = settings.get('run.vehicle_interface') @@ -19,6 +18,19 @@ def main(): replay_settings = settings.get('run.replay',{}) load_computation_graph() + #initialize ros node + has_ros = False + try: + import rospy + rospy.init_node('GEM_executor',disable_signals=True) + has_ros = True + except (ImportError,ModuleNotFoundError): + if mode == 'simulation': + print(EXECUTION_PREFIX,"Warning, ROS not found, but simulation mode requested") + else: + print(EXECUTION_PREFIX,"Error, ROS not found on system.") + raise + #create top-level components vehicle_interface = make_class(vehicle_interface_settings,'default','GEMstack.onboard.interface') mission_executor = make_class(mission_executor_settings,'execution','GEMstack.onboard.execution',{'vehicle_interface':vehicle_interface}) @@ -117,3 +129,7 @@ def main(): finally: vehicle_interface.stop() + if has_ros: + #need manual ros node shutdown due to disable_signals=True + rospy.signal_shutdown('GEM_executor finished') + diff --git a/GEMstack/onboard/execution/execution.py b/GEMstack/onboard/execution/execution.py index 69c30e49b..7518deedd 100644 --- a/GEMstack/onboard/execution/execution.py +++ b/GEMstack/onboard/execution/execution.py @@ -636,15 +636,6 @@ def update_components(self, components : Dict[str,ComponentExecutor], state : Al class StandardExecutor(ExecutorBase): def __init__(self, vehicle_interface): ExecutorBase.__init__(self,vehicle_interface) - try: - import rospy - rospy.init_node('GEM_executor') - except (ImportError,ModuleNotFoundError): - if settings.get('run.mode','hardware') == 'simulation': - print(EXECUTION_PREFIX,"Warning, ROS not found, but simulation mode requested") - else: - print(EXECUTION_PREFIX,"Error, ROS not found on system.") - raise def done(self): if self.current_pipeline == 'recovery': From acfc371cf53a385ca515826a6d294740807556ef Mon Sep 17 00:00:00 2001 From: krishauser Date: Thu, 18 Jan 2024 15:28:44 -0500 Subject: [PATCH 054/232] Added light visualization, fixed gear problem --- GEMstack/utils/mpl_visualization.py | 25 +++++++++++++++++++++---- 1 file changed, 21 insertions(+), 4 deletions(-) diff --git a/GEMstack/utils/mpl_visualization.py b/GEMstack/utils/mpl_visualization.py index 6ddf72fb4..09d078a02 100644 --- a/GEMstack/utils/mpl_visualization.py +++ b/GEMstack/utils/mpl_visualization.py @@ -2,7 +2,7 @@ import matplotlib.patches as patches import numpy as np from . import settings -from ..state import ObjectFrameEnum,ObjectPose,PhysicalObject,VehicleState,Path,Obstacle,AgentState,Roadgraph,RoadgraphLane,RoadgraphLaneEnum,RoadgraphCurve,RoadgraphCurveEnum,RoadgraphRegion,RoadgraphRegionEnum,RoadgraphSurfaceEnum,Trajectory,Route,SceneState,AllState +from ..state import ObjectFrameEnum,ObjectPose,PhysicalObject,VehicleState,VehicleGearEnum,Path,Obstacle,AgentState,Roadgraph,RoadgraphLane,RoadgraphLaneEnum,RoadgraphCurve,RoadgraphCurveEnum,RoadgraphRegion,RoadgraphRegionEnum,RoadgraphSurfaceEnum,Trajectory,Route,SceneState,AllState CURVE_TO_STYLE = { RoadgraphCurveEnum.LANE_BOUNDARY : {'color':'k','linewidth':1,'linestyle':'-'}, @@ -114,14 +114,31 @@ def plot_vehicle(vehicle : VehicleState, axis_len=0.1, ax=None): [right_wheel_origin[1]-wheel_offset[1],right_wheel_origin[1]+wheel_offset[1]],'k-',linewidth=2) #plot gear - if vehicle.gear <= 0: - if vehicle.gear == 0: + if vehicle.gear in [VehicleGearEnum.NEUTRAL,VehicleGearEnum.REVERSE,VehicleGearEnum.PARK]: + if vehicle.gear == VehicleGearEnum.NEUTRAL: gear = 'N' - elif vehicle.gear == -1: + elif vehicle.gear == VehicleGearEnum.REVERSE: gear = 'R' else: gear = 'P' ax.text(t[0],t[1],gear,ha='center',va='center',color='k') + + #plot lights + light_size = 0.15 + light_color = 'y' + xbounds,ybounds,zbounds = settings.get('vehicle.geometry.bounds') + if vehicle.left_turn_indicator: + lp = vehicle.pose.apply([xbounds[0]+light_size,ybounds[0]+light_size]) + ax.add_patch(patches.Circle(lp,radius=light_size,fc=light_color,ec=light_color,fill=True,zorder=10)) + if vehicle.right_turn_indicator: + lp = vehicle.pose.apply([xbounds[0]+light_size,ybounds[1]-light_size]) + ax.add_patch(patches.Circle(lp,radius=light_size,fc=light_color,ec=light_color,fill=True,zorder=10)) + if vehicle.headlights_on: + lp = vehicle.pose.apply([xbounds[1],ybounds[0]+light_size*2]) + ax.add_patch(patches.Circle(lp,radius=light_size,fc=light_color,ec=light_color,fill=True,zorder=10)) + lp = vehicle.pose.apply([xbounds[1],ybounds[1]-light_size*2]) + ax.add_patch(patches.Circle(lp,radius=light_size,fc=light_color,ec=light_color,fill=True,zorder=10)) + def plot_path(path : Path, color='k', linewidth=1, linestyle='-', ax=None): if ax is None: From dba5f3ce13ad3046cb086245436e55dc48d2e356 Mon Sep 17 00:00:00 2001 From: krishauser Date: Thu, 18 Jan 2024 15:29:03 -0500 Subject: [PATCH 055/232] Added hazard lights, used enum properly --- GEMstack/onboard/interface/gem_hardware.py | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/GEMstack/onboard/interface/gem_hardware.py b/GEMstack/onboard/interface/gem_hardware.py index 1a25a4893..1b88730a0 100644 --- a/GEMstack/onboard/interface/gem_hardware.py +++ b/GEMstack/onboard/interface/gem_hardware.py @@ -169,12 +169,14 @@ def send_first_command(self): # Start PACMod interface def send_command(self, command : GEMVehicleCommand): - if command.left_turn_signal: - self.turn_cmd.ui16_cmd = 2 # left turn signal + if command.left_turn_signal and command.right_turn_signal: + self.turn_cmd.ui16_cmd = PacmodCmd.TURN_HAZARDS + elif command.left_turn_signal: + self.turn_cmd.ui16_cmd = PacmodCmd.TURN_LEFT elif command.right_turn_signal: - self.turn_cmd.ui16_cmd = 0 # right turn signal + self.turn_cmd.ui16_cmd = PacmodCmd.TURN_RIGHT else: - self.turn_cmd.ui16_cmd = 1 + self.turn_cmd.ui16_cmd = PacmodCmd.TURN_NONE self.accel_cmd.f64_cmd = command.accelerator_pedal_position if command.brake_pedal_position > 0.0: From d2fc8517d5efa893453e4907c77749e6a48bd77c Mon Sep 17 00:00:00 2001 From: krishauser Date: Thu, 18 Jan 2024 15:29:22 -0500 Subject: [PATCH 056/232] Added utility to maintain current readings --- GEMstack/onboard/interface/gem.py | 22 ++++++++++++++++++++++ 1 file changed, 22 insertions(+) diff --git a/GEMstack/onboard/interface/gem.py b/GEMstack/onboard/interface/gem.py index 14b380487..27353b99f 100644 --- a/GEMstack/onboard/interface/gem.py +++ b/GEMstack/onboard/interface/gem.py @@ -139,3 +139,25 @@ def simple_command(self, acceleration_mps2 : float, steering_wheel_angle : float cmd.wiper_level = state.wiper_level return cmd + + def command_from_reading(self, reading: GEMVehicleReading = None) -> GEMVehicleCommand: + """Returns a command that maintains all the current elements in the + provided vehicle reading. If reading=None, then the last reading + is used. + """ + if reading is None: + reading = self.last_reading + if reading is None: + raise RuntimeError("Can't get command from reading, no reading available") + return GEMVehicleCommand(gear=reading.gear, + accelerator_pedal_position=reading.accelerator_pedal_position, + brake_pedal_position=reading.brake_pedal_position, + steering_wheel_angle=reading.steering_wheel_angle, + accelerator_pedal_speed=settings.get('vehicle.control_defaults.accelerator_pedal_speed'), + brake_pedal_speed = settings.get('vehicle.control_defaults.brake_pedal_speed'), + steering_wheel_speed = settings.get('vehicle.control_defaults.steering_wheel_speed'), + left_turn_signal = reading.left_turn_signal, + right_turn_signal = reading.right_turn_signal, + headlights_on = reading.headlights_on, + horn_on = reading.horn_on, + wiper_level = reading.wiper_level) \ No newline at end of file From 10e709736ff45c3c1ee925d00f801611c25c8ac6 Mon Sep 17 00:00:00 2001 From: krishauser Date: Thu, 18 Jan 2024 15:29:59 -0500 Subject: [PATCH 057/232] minor fixes --- GEMstack/launch/gather_data.yaml | 1 + GEMstack/onboard/execution/execution.py | 2 ++ GEMstack/state/__init__.py | 2 +- 3 files changed, 4 insertions(+), 1 deletion(-) diff --git a/GEMstack/launch/gather_data.yaml b/GEMstack/launch/gather_data.yaml index 93c56636f..265062ce5 100644 --- a/GEMstack/launch/gather_data.yaml +++ b/GEMstack/launch/gather_data.yaml @@ -17,6 +17,7 @@ drive: type: StaticRoutePlanner args: [!relative_path '../knowledge/routes/xyhead_highbay_backlot_p.csv'] motion_planning: RouteToTrajectoryPlanner + #note no trajectory_tracking item here log: # Specify the top-level folder to save the log files. Default is 'logs' #folder : 'logs' diff --git a/GEMstack/onboard/execution/execution.py b/GEMstack/onboard/execution/execution.py index 7518deedd..817c0d3ee 100644 --- a/GEMstack/onboard/execution/execution.py +++ b/GEMstack/onboard/execution/execution.py @@ -494,6 +494,8 @@ def run(self): def validate_sensors(self,numsteps=None): """Verifies sensors are working""" (perception_components,planning_components,other_components) = self.pipelines[self.current_pipeline] + if len(perception_components) == 0: + return True components = list(perception_components.values()) + list(self.always_run_components.values()) dt_min = min([c.dt for c in components if c.dt != 0.0]) looper = TimedLooper(dt_min,name="main executor") diff --git a/GEMstack/state/__init__.py b/GEMstack/state/__init__.py index f84f60669..8ddc0c5b0 100644 --- a/GEMstack/state/__init__.py +++ b/GEMstack/state/__init__.py @@ -21,7 +21,7 @@ 'AllState'] from .physical_object import PhysicalObject, ObjectPose, ObjectFrameEnum from .trajectory import Path,Trajectory -from .vehicle import VehicleState +from .vehicle import VehicleState,VehicleGearEnum from .roadgraph import Roadgraph, RoadgraphLane, RoadgraphCurve, RoadgraphRegion, RoadgraphCurveEnum, RoadgraphLaneEnum, RoadgraphRegionEnum, RoadgraphSurfaceEnum, RoadgraphConnectionEnum from .obstacle import Obstacle, ObstacleMaterialEnum from .sign import Sign, SignEnum, SignalLightEnum, SignState From f061023b6bb6ce613b8a12ef0938082194663e19 Mon Sep 17 00:00:00 2001 From: krishauser Date: Thu, 18 Jan 2024 15:46:22 -0500 Subject: [PATCH 058/232] Moved launch files to top-level directory --- README.md | 36 +++++++++---------- {GEMstack/launch => launch}/README.md | 0 {GEMstack/launch => launch}/fixed_route.yaml | 6 ++-- .../launch => launch}/fixed_route_sim.yaml | 6 ++-- {GEMstack/launch => launch}/gather_data.yaml | 6 ++-- 5 files changed, 25 insertions(+), 29 deletions(-) rename {GEMstack/launch => launch}/README.md (100%) rename {GEMstack/launch => launch}/fixed_route.yaml (89%) rename {GEMstack/launch => launch}/fixed_route_sim.yaml (91%) rename {GEMstack/launch => launch}/gather_data.yaml (88%) diff --git a/README.md b/README.md index 996a22aad..714c09834 100644 --- a/README.md +++ b/README.md @@ -36,15 +36,16 @@ To build a Docker container with all these prerequisites, you can use the provid Your work will be typically confined to the `GEMstack/` folder, and you may use the `testing/`, `logs/`, `data/`, and `scenes/` folders. - `GEMstack/`: the software package (see [below](#package-structure)). -- `main.py`: the standard entry point to running onboard behavior (see [below](#launching-the-stack)). -- `logs/`: logs will be placed here. These will not be committed to the Github repo. -- `data/`: standard location to place datasets for training, i.e., downloaded or curated from other sources. These will not be committed to the Github repo. -- `scenes/`: standard location to place scenes for simulation. -- `testing/`: test scripts to check whether GEMstack components are functioning. +- `main.py` ⏯️: the standard entry point to running onboard behavior (see [below](#launching-the-stack)). +- `launch/` 🚀 Launch configuration files are listed here. Specify these as an argument to `main.py`. +- `logs/` 🪵: logs will be placed here. These will not be committed to the Github repo. +- `data/` 💽: standard location to place datasets for training, i.e., downloaded or curated from other sources. These will not be committed to the Github repo. +- `scenes/` 🌎: standard location to place scenes for simulation. +- `testing/` 🧪: test scripts to check whether GEMstack components are functioning. +- `docs/` 📖: ReadTheDocs documentation source files are placed here. Used by automated tools to build the [online documentation](https://gemstack.readthedocs.org). - `README.md`: this file. - `LICENSE`: MIT license. - `.gitignore`: Git ignore file. All files that match these patterns will not be added to Git. -- `docs/`: ReadTheDocs documentation source files are placed here. Used by automated tools to build the [online documentation](https://gemstack.readthedocs.org). - `.readthedocs.yaml`: ReadTheDocs configuration file. - `pyproject.toml`: Describes the GEMstack Python package for pip install. - `requirements.txt`: A list of Python dependencies for the software stack, used via `pip install -r requirements.txt`. @@ -53,8 +54,7 @@ In addition, some tools (e.g., pip) will build temporary folders, such as `build ## TODO list -- Linux Matplotlib visualizer doesn't play nicely with Ctrl+C -- Test ROS logging and replay +- Test ROS replay - Test behavior replay - More sophisticated simulator with sensor messages @@ -125,8 +125,6 @@ Legend: - 🟥 `predicates/`: Stores named predicates that may be true in a world state. - 🟩 `defaults/`: Stores the default settings. -`launch/`: 🚀 Launch scripts are listed here. Specify which configuration you want to use as an argument to `main.py`. - `onboard/`: 🚗 All algorithms governing onboard behavior are located here. These algorithms may make use of items in the `knowledge/` stack. - `perception/`: Perception components. - 🟨 `state_estimation`: State estimators. @@ -170,19 +168,17 @@ Legend: You will launch a simulation using: -- `python main.py GEMstack/launch/LAUNCH_FILE.yaml` where `LAUNCH_FILE.yaml` is your preferred simulation launch file. Inspect the simulator classes in `GEMstack/onboard/interface/gem_simulator/` for more information about configuring the simulator. +- `python3 main.py launch/LAUNCH_FILE.yaml` where `LAUNCH_FILE.yaml` is your preferred simulation launch file. Inspect the simulator classes in `GEMstack/onboard/interface/gem_simulator.py` for more information about configuring the simulator. -To launch onboard behavior you will open four terminal windows, and in each of them run: +To launch onboard behavior you will open Terminator / tmux and split it into three terminal windows. In each of them run: -- `source /opt/ros/noetic/setup.bash` -- `source GEMstack/catkin_ws/devel/setup.bash` to get all of the appropriate ROS environment variables. +- `cd GEMstack` +- `source catkin_ws/devel/setup.bash` to get all of the appropriate ROS environment variables. Then run: -- (window 1) `roscore` -- (window 2) `roslaunch basic_launch sensor_init.launch` -- (window 3) `roslaunch basic_launch visualization.launch` -- (window 4) `python main.py GEMstack/launch/LAUNCH_FILE.yaml` where `LAUNCH_FILE.yaml` is your preferred launch file. - +- (window 1) `roslaunch basic_launch sensor_init.launch` +- (window 2) `roslaunch basic_launch dbw_joystick.launch` (TODO: switch this to `dbw_no_joystick.launch`) +- (window 3) `python3 main.py launch/LAUNCH_FILE.yaml` where `LAUNCH_FILE.yaml` is your preferred launch file. Note that if you try to use `import GEMstack` in a script or Jupyter notebook anywhere outside of this directory, Python will not know where the `GEMstack` module is. If you wish to import `GEMstack` from a script located in a separate directory, you can put @@ -194,7 +190,7 @@ sys.path.append(os.getcwd()) #or enter the absolute path of this directory import GEMstack ``` -at the top of your script. Then, you can run the script from this directory via `python PATH/TO/SCRIPT/myscript.py`. See the scripts in `testing` for an example of how this is done. +at the top of your script. Then, you can run the script from this directory via `python3 PATH/TO/SCRIPT/myscript.py`. See the scripts in `testing` for an example of how this is done. You can also install `GEMstack` into the system Python by calling `pip install .`, but this is not recommended because has a couple of drawbacks: - You might make changes in this directory, e.g., via `git pull`, and then forget to reinstall, so the changes won't be reflected when you run your code. diff --git a/GEMstack/launch/README.md b/launch/README.md similarity index 100% rename from GEMstack/launch/README.md rename to launch/README.md diff --git a/GEMstack/launch/fixed_route.yaml b/launch/fixed_route.yaml similarity index 89% rename from GEMstack/launch/fixed_route.yaml rename to launch/fixed_route.yaml index 7882c9f5d..6ccbb3050 100644 --- a/GEMstack/launch/fixed_route.yaml +++ b/launch/fixed_route.yaml @@ -14,7 +14,7 @@ drive: planning: route_planning: type: StaticRoutePlanner - args: [!relative_path '../knowledge/routes/xyhead_highbay_backlot_p.csv'] + args: [!relative_path '../GEMstack/knowledge/routes/xyhead_highbay_backlot_p.csv'] motion_planning: RouteToTrajectoryPlanner trajectory_tracking: pure_pursuit.PurePursuitTrajectoryTracker log: @@ -25,7 +25,7 @@ log: # If suffix is specified, then logs will output to folder/prefix+suffix. Default uses date and time as the suffix #suffix : 'test3' # Specify which ros topics to record to vehicle.bag. Default records nothing. This records the "standard" ROS topics. - ros_topics : !include "../knowledge/defaults/standard_ros_topics.yaml" + ros_topics : !include "../GEMstack/knowledge/defaults/standard_ros_topics.yaml" # Specify options to pass to rosbag record. Default is no options. #rosbag_options : '--split --size=1024' # If True, then record all readings / commands of the vehicle interface. Default False @@ -44,4 +44,4 @@ replay: # Add items here to set certain topics / inputs to be replayed from log components : [] #usually can keep this constant -computation_graph: !include "../knowledge/defaults/computation_graph.yaml" \ No newline at end of file +computation_graph: !include "../GEMstack/knowledge/defaults/computation_graph.yaml" \ No newline at end of file diff --git a/GEMstack/launch/fixed_route_sim.yaml b/launch/fixed_route_sim.yaml similarity index 91% rename from GEMstack/launch/fixed_route_sim.yaml rename to launch/fixed_route_sim.yaml index 3df702184..c34fd6a83 100644 --- a/GEMstack/launch/fixed_route_sim.yaml +++ b/launch/fixed_route_sim.yaml @@ -3,7 +3,7 @@ mode: simulation vehicle_interface: type: gem_simulator.GEMDoubleIntegratorSimulationInterface args: - scene: !relative_path '../../scenes/xyhead_demo.yaml' + scene: !relative_path '../scenes/xyhead_demo.yaml' mission_execution: StandardExecutor # "recovery" pipeline: Recovery behavior after a component failure @@ -21,7 +21,7 @@ drive: planning: route_planning: type: StaticRoutePlanner - args: [!relative_path '../knowledge/routes/xyhead_highbay_backlot_p.csv'] + args: [!relative_path '../GEMstack/knowledge/routes/xyhead_highbay_backlot_p.csv'] motion_planning: RouteToTrajectoryPlanner trajectory_tracking: type: pure_pursuit.PurePursuitTrajectoryTracker @@ -65,5 +65,5 @@ replay: # Add items here to set certain topics / inputs to be replayed from log components : [] #usually can keep this constant -computation_graph: !include "../knowledge/defaults/computation_graph.yaml" +computation_graph: !include "../GEMstack/knowledge/defaults/computation_graph.yaml" diff --git a/GEMstack/launch/gather_data.yaml b/launch/gather_data.yaml similarity index 88% rename from GEMstack/launch/gather_data.yaml rename to launch/gather_data.yaml index 265062ce5..465f9abb6 100644 --- a/GEMstack/launch/gather_data.yaml +++ b/launch/gather_data.yaml @@ -15,7 +15,7 @@ drive: planning: route_planning: type: StaticRoutePlanner - args: [!relative_path '../knowledge/routes/xyhead_highbay_backlot_p.csv'] + args: [!relative_path '../GEMstack/knowledge/routes/xyhead_highbay_backlot_p.csv'] motion_planning: RouteToTrajectoryPlanner #note no trajectory_tracking item here log: @@ -26,7 +26,7 @@ log: # If suffix is specified, then logs will output to folder/prefix+suffix. Default uses date and time as the suffix #suffix : 'test3' # Specify which ros topics to record to vehicle.bag. Default records nothing. This records the "standard" ROS topics. - ros_topics : !include "../knowledge/defaults/standard_ros_topics.yaml" + ros_topics : !include "../GEMstack/knowledge/defaults/standard_ros_topics.yaml" # Specify options to pass to rosbag record. Default is no options. #rosbag_options : '--split --size=1024' # If True, then record all readings / commands of the vehicle interface. Default False @@ -44,4 +44,4 @@ replay: # Add items here to set certain topics / inputs to be replayed from log components : [] #usually can keep this constant -computation_graph: !include "../knowledge/defaults/computation_graph.yaml" \ No newline at end of file +computation_graph: !include "../GEMstack/knowledge/defaults/computation_graph.yaml" \ No newline at end of file From 8c08913e9592f2b7955eeab4bfc5c66648e3d414 Mon Sep 17 00:00:00 2001 From: krishauser Date: Fri, 19 Jan 2024 12:21:46 -0500 Subject: [PATCH 059/232] Moved hardware fault printing / logging into its own function --- GEMstack/onboard/execution/execution.py | 44 +++++++++++++++++++------ 1 file changed, 34 insertions(+), 10 deletions(-) diff --git a/GEMstack/onboard/execution/execution.py b/GEMstack/onboard/execution/execution.py index 817c0d3ee..9f4d34034 100644 --- a/GEMstack/onboard/execution/execution.py +++ b/GEMstack/onboard/execution/execution.py @@ -278,6 +278,7 @@ def __init__(self, vehicle_interface): self.state = None # type: Optional[AllState] self.logging_manager = LoggingManager() self.last_loop_time = time.time() + self.last_hardware_faults = set() def begin(self): """Override me to do any initialization. The vehicle will have @@ -490,6 +491,36 @@ def run(self): self.logging_manager.close() print("Done with execution loop") + def check_for_hardware_faults(self): + """Handles vehicle fault checking / logging""" + faults = self.vehicle_interface.hardware_faults() + new_faults = [] + printed_faults = [] + for f in faults: + if f == 'disengaged': + if not settings.get('run.require_engaged',False): + continue + if not f in self.last_hardware_faults: + self.event("Vehicle disengaged") + new_faults.append(f) + printed_faults.append(f) + else: + if not f in self.last_hardware_faults: + self.event("Hardware fault {}".format(f)) + new_faults.append(f) + printed_faults.append(f) + if printed_faults: + if EXECUTION_VERBOSITY >= 1: + print(EXECUTION_PREFIX,"Hardware faults:") + for f in printed_faults: + if f in new_faults: + print(" ",f,"(new)") + else: + print(" ",f) + elif new_faults: + print(EXECUTION_PREFIX,"Hardware fault:",", ".join(new_faults)) + + self.last_hardware_faults = set(faults) def validate_sensors(self,numsteps=None): """Verifies sensors are working""" @@ -507,11 +538,8 @@ def validate_sensors(self,numsteps=None): self.state.t = self.vehicle_interface.time() self.last_loop_time = time.time() - for f in self.vehicle_interface.hardware_faults(): - if f == 'disengaged' and not settings.get('run.require_engaged',False): - continue - if EXECUTION_VERBOSITY >= 1: - print(EXECUTION_PREFIX,"Hardware fault",f) + #check for vehicle faults + self.check_for_hardware_faults() self.update_components(perception_components,self.state) sensors_working = all([c.healthy() for c in perception_components.values()]) @@ -545,11 +573,7 @@ def run_until_switch(self): self.last_loop_time = time.time() #check for vehicle faults - for f in self.vehicle_interface.hardware_faults(): - if f == 'disengaged' and not settings.get('run.require_engaged',False): - continue - if EXECUTION_VERBOSITY >= 1: - print(EXECUTION_PREFIX,"Hardware fault",f) + self.check_for_hardware_faults() self.update_components(perception_components,self.state) #check for faults From 53e39c5c76ed91e3598f102f5cc7f7eb1430d651 Mon Sep 17 00:00:00 2001 From: krishauser Date: Wed, 24 Jan 2024 00:07:50 -0500 Subject: [PATCH 060/232] Fixed pure pursuit to be more accurate. Speed filter added to state estimator --- GEMstack/knowledge/defaults/current.yaml | 8 +++-- .../onboard/perception/state_estimation.py | 9 ++++- GEMstack/onboard/planning/pure_pursuit.py | 33 ++++++++++++++----- 3 files changed, 39 insertions(+), 11 deletions(-) diff --git a/GEMstack/knowledge/defaults/current.yaml b/GEMstack/knowledge/defaults/current.yaml index e592150c0..600b0ed08 100644 --- a/GEMstack/knowledge/defaults/current.yaml +++ b/GEMstack/knowledge/defaults/current.yaml @@ -22,10 +22,14 @@ control: brake_amount : 0.5 brake_speed : 2.0 pure_pursuit: - lookahead: 4.0 + lookahead: 2.0 lookahead_scale: 3.0 - crosstrack_gain: 0.41 + crosstrack_gain: 2.0 desired_speed: 2.0 #m/s + longitudinal_control: + pid_p: 3.0 + pid_i: 0.1 + pid_d: 0.0 #configure the simulator, if using simulator: diff --git a/GEMstack/onboard/perception/state_estimation.py b/GEMstack/onboard/perception/state_estimation.py index 1a09d8924..56591ac94 100644 --- a/GEMstack/onboard/perception/state_estimation.py +++ b/GEMstack/onboard/perception/state_estimation.py @@ -6,6 +6,7 @@ from ...state.vehicle import VehicleState,VehicleGearEnum from ...state.physical_object import ObjectFrameEnum,ObjectPose,convert_xyhead from ...knowledge.vehicle.geometry import front2steer,steer2front +from ...mathutils.signal import OnlineLowPassFilter from ..interface.gem import GEMInterface from ..component import Component @@ -19,6 +20,7 @@ def __init__(self, vehicle_interface : GEMInterface): self.gnss_pose = None self.location = settings.get('vehicle.calibration.gnss_location')[:2] self.yaw_offset = settings.get('vehicle.calibration.gnss_yaw') + self.speed_filter = OnlineLowPassFilter(1.2, 30, 4) # Get GNSS information def inspva_callback(self, inspva_msg): @@ -59,8 +61,13 @@ def update(self) -> VehicleState: yaw=center_xyhead[2]) readings = self.vehicle_interface.get_reading() - return readings.to_state(vehicle_pose_global) + raw = readings.to_state(vehicle_pose_global) + #filtering speed + filt_vel = self.speed_filter(raw.v) + raw.v = filt_vel + return raw + class FakeStateEstimator(Component): diff --git a/GEMstack/onboard/planning/pure_pursuit.py b/GEMstack/onboard/planning/pure_pursuit.py index 9de08b65e..8d81e3627 100644 --- a/GEMstack/onboard/planning/pure_pursuit.py +++ b/GEMstack/onboard/planning/pure_pursuit.py @@ -1,5 +1,4 @@ from ...mathutils.control import PID -from ...mathutils.signal import OnlineLowPassFilter from ...utils import settings from ...mathutils import transforms from ...knowledge.vehicle.dynamics import acceleration_to_pedal_positions @@ -21,10 +20,11 @@ def __init__(self, lookahead = None, lookahead_scale = None, wheelbase = None, c self.steering_angle_range = [settings.get('vehicle.geometry.min_steering_angle'),settings.get('vehicle.geometry.max_steering_angle')] self.desired_speed = settings.get('control.pure_pursuit.desired_speed',2.5) #approximately 5 mph + self.path_is_timed = False + self.desired_speed_from_path = True #turn this to True to use the input trajectory to determine the desired speed self.max_accel = settings.get('vehicle.limits.max_acceleration') # m/s^2 self.max_decel = settings.get('vehicle.limits.max_deceleration') # m/s^2 - self.pid_speed = PID(0.5, 0.0, 0.1, windup_limit=20) - self.speed_filter = OnlineLowPassFilter(1.2, 30, 4) + self.pid_speed = PID(settings.get('control.longitudinal_control.pid_p',0.5), settings.get('control.longitudinal_control.pid_d',0.0), settings.get('control.longitudinal_control.pid_i',0.1), windup_limit=20) self.path = None self.current_path_parameter = 0.0 @@ -38,6 +38,12 @@ def set_path(self, path : Path): self.path = self.path.get_dims([0,1]) if not isinstance(self.path,Trajectory): self.path = self.path.arc_length_parameterize() + self.path_is_timed = False + self.desired_speed_from_path = False + if self.desired_speed_from_path: + raise ValueError("Can't provide an untimed path to PurePursuit and expect it to use the path velocity") + else: + self.path_is_timed = True self.current_path_parameter = 0.0 def compute(self, state : VehicleState): @@ -53,8 +59,6 @@ def compute(self, state : VehicleState): curr_yaw = state.pose.yaw if state.pose.yaw is not None else 0.0 speed = state.v - filt_vel = self.speed_filter(speed) - if self.path is None: #just stop accel = self.pid_speed.advance(0.0, t) @@ -67,7 +71,7 @@ def compute(self, state : VehicleState): closest_dist,closest_parameter = self.path.closest_point_local((curr_x,curr_y),[self.current_path_parameter-5.0,self.current_path_parameter+5.0]) #TODO: calculate parameter that is look_ahead distance away from the closest point #(rather than just advancing the parameter) - des_parameter = closest_parameter + self.look_ahead + self.look_ahead_scale * filt_vel + des_parameter = closest_parameter + self.look_ahead + self.look_ahead_scale * speed self.current_path_parameter = closest_parameter print("Closest parameter: " + str(closest_parameter),"distance to path",closest_dist) print("Closest point",self.path.eval(closest_parameter),"vs",(curr_x,curr_y)) @@ -84,7 +88,7 @@ def compute(self, state : VehicleState): # ----------------- tuning this part as needed ----------------- k = self.crosstrack_gain angle_i = np.arctan((k * 2 * self.wheelbase * np.sin(alpha)) / L) - angle = angle_i*2 + angle = angle_i*2.0 # ----------------- tuning this part as needed ----------------- f_delta = np.clip(angle, self.wheel_angle_range[0], self.wheel_angle_range[1]) @@ -97,7 +101,20 @@ def compute(self, state : VehicleState): steering_angle = np.clip(front2steer(f_delta), self.steering_angle_range[0], self.steering_angle_range[1]) print("Steering wheel angle: " + str(round(np.degrees(steering_angle),2)) + " degrees" ) - output_accel = self.pid_speed.advance(e = self.desired_speed - filt_vel, t = t) + desired_speed = self.desired_speed + feedforward_accel = 0.0 + if self.desired_speed_from_path: + #determine desired speed from trajectory + deriv = self.path.eval_derivative(self.current_path_parameter) + desired_speed = np.linalg.norm(deriv) + feedforward_accel = (desired_speed - speed)/dt + feedforward_accel= np.clip(feedforward_accel, -self.max_decel, self.max_accel) + print("Desired speed",desired_speed,"m/s") + print("Feedforward accel: " + str(feedforward_accel) + " m/s^2") + else: + #decay speed when crosstrack error is high + desired_speed *= np.exp(-ct_error*0.1) + output_accel = self.pid_speed.advance(e = desired_speed - speed, t = t, feedforward_term=feedforward_accel) print("Output acceleration",output_accel) if output_accel > self.max_accel: From e43f3792f46cd0017c76b2a299d089d20241b73d Mon Sep 17 00:00:00 2001 From: krishauser Date: Wed, 24 Jan 2024 00:08:04 -0500 Subject: [PATCH 061/232] Added forward drive route --- GEMstack/knowledge/routes/forward_15m.csv | 16 ++++++++++++++++ 1 file changed, 16 insertions(+) create mode 100644 GEMstack/knowledge/routes/forward_15m.csv diff --git a/GEMstack/knowledge/routes/forward_15m.csv b/GEMstack/knowledge/routes/forward_15m.csv new file mode 100644 index 000000000..0d02ce2aa --- /dev/null +++ b/GEMstack/knowledge/routes/forward_15m.csv @@ -0,0 +1,16 @@ +0.0,0,0 +1.0,0,0 +2.0,0,0 +3.0,0,0 +4,0,0 +5,0,0 +6,0,0 +7,0,0 +8,0,0 +9,0,0 +10,0,0 +11,0,0 +12,0,0 +13,0,0 +14,0,0 +15,0,0 From 245fcbd9f91a16be8b536a9dd5f94cf96a772fc2 Mon Sep 17 00:00:00 2001 From: krishauser Date: Wed, 24 Jan 2024 00:08:38 -0500 Subject: [PATCH 062/232] Fixed some corner cases in trajectory evaluation. Added trim function --- GEMstack/state/trajectory.py | 57 ++++++++++++++++++++++++++++++------ 1 file changed, 48 insertions(+), 9 deletions(-) diff --git a/GEMstack/state/trajectory.py b/GEMstack/state/trajectory.py index e520dba02..62efa35c7 100644 --- a/GEMstack/state/trajectory.py +++ b/GEMstack/state/trajectory.py @@ -18,16 +18,25 @@ def to_frame(self, frame : ObjectFrameEnum, current_pose : None, start_pose_abs new_points = [convert_point(p,self.frame,frame,current_pose,start_pose_abs) for p in self.points] return replace(self,frame=frame,points=new_points) - def eval(self, u : float) -> List[float]: - """Evaluates the path at a given parameter. The integer part of u - indicates the segment, and the fractional part indicates the progress - along the segment""" - ind = int(u) + def parameter_to_index(self, t : float) -> Tuple[int,float]: + """Converts a path parameter to an (edge index, edge parameter) tuple.""" + if len(self.points) < 2: + return 0,0.0 + ind = int(t) if ind < 0: ind = 0 if ind >= len(self.points)-1: ind = len(self.points)-2 - u = u - ind + u = t - ind if u > 1: u = 1 if u < 0: u = 0 + return ind,u + + def eval(self, u : float) -> List[float]: + """Evaluates the path at a given parameter. The integer part of u + indicates the segment, and the fractional part indicates the progress + along the segment""" + if len(self.points) < 2: + return self.points[0] + ind,u = self.parameter_to_index(u) p1 = self.points[ind] p2 = self.points[ind+1] return transforms.vector_madd(p1,transforms.vector_sub(p2,p1),u) @@ -49,10 +58,14 @@ def eval_derivative(self, u : float) -> List[float]: def arc_length_parameterize(self, speed = 1.0) -> Trajectory: """Returns a new path that is parameterized by arc length.""" times = [0] + points = [self.points[0]] for i in range(len(self.points)-1): p1 = self.points[i] p2 = self.points[i+1] - times.append(times[-1] + transforms.vector_dist(p1,p2)/speed) + d = transforms.vector_dist(p1,p2) + if d > 0: + points.append(p2) + times.append(times[-1] + d/speed) return Trajectory(frame=self.frame,points=self.points,times=times) def closest_point(self, x : List[float], edges = True) -> Tuple[float,float]: @@ -130,6 +143,15 @@ def append_dim(self, value : Union[float,List[float]] = 0.0) -> None: raise ValueError("Invalid length of values to append") for p,v in zip(self.points,value): p.append(v) + + def trim(self, start : float, end : float) -> Path: + """Returns a copy of this path but trimmed to the given parameter range.""" + sind,su = self.parameter_to_index(start) + eind,eu = self.parameter_to_index(end) + s = self.eval(start) + e = self.eval(end) + return replace(self,points=[s]+self.points[sind+1:eind]+[e]) + @dataclass @register @@ -138,7 +160,9 @@ class Trajectory(Path): times : List[float] def time_to_index(self, t : float) -> Tuple[int,float]: - """Converts a time to an (edge index, parameter) tuple.""" + """Converts a time to an (edge index, edge parameter) tuple.""" + if len(self.points) < 2: + return 0,0.0 ind = 0 while ind < len(self.times) and self.times[ind] < t: ind += 1 @@ -154,6 +178,8 @@ def time_to_parameter(self, t : float) -> float: def parameter_to_time(self, u : float) -> float: """Converts a parameter to a time""" + if len(self.points) < 2: + return self.times[0] ind = int(math.floor(u)) if ind < 0: ind = 0 if ind >= len(self.times)-1: ind = len(self.times)-2 @@ -164,13 +190,17 @@ def parameter_to_time(self, u : float) -> float: def eval(self, t : float) -> List[float]: """Evaluates the trajectory at a given time.""" + if len(self.points) < 2: + return self.points[0] ind,u = self.time_to_index(t) return transforms.vector_madd(self.points[ind],transforms.vector_sub(self.points[ind+1],self.points[ind]),u) def eval_derivative(self, t : float) -> List[float]: """Evaluates the derivative at a given time.""" + if len(self.points) < 2: + return transforms.vector_mul(self.points[0],0.0) ind,u = self.time_to_index(t) - return transforms.vector_sub(self.points[ind+1],self.points[ind]) + return transforms.vector_mul(transforms.vector_sub(self.points[ind+1],self.points[ind]),1.0/(self.times[ind+1]-self.times[ind])) def closest_point(self, x : List[float], edges = True) -> Tuple[float,float]: """Returns the closest point on the path to the given point. If @@ -197,6 +227,15 @@ def closest_point_local(self, x : List[float], time_range=Tuple[float,float], ed distance, closest_index = Path.closest_point_local(self,x,param_range,edges) closest_time = self.parameter_to_time(closest_index) return distance, closest_time + + def trim(self, start : float, end : float) -> Trajectory: + """Returns a copy of this trajectory but trimmed to the given time range.""" + sind,su = self.time_to_index(start) + eind,eu = self.time_to_index(end) + s = self.eval(start) + e = self.eval(end) + return replace(self,points=[s]+self.points[sind+1:eind]+[e],times=[start]+self.times[sind+1:eind]+[end]) + From 768502770e766b8bad85ca8a3b3a56d3beabdbb0 Mon Sep 17 00:00:00 2001 From: krishauser Date: Wed, 24 Jan 2024 00:08:52 -0500 Subject: [PATCH 063/232] Added frame argument to StaticRoutePlanner --- GEMstack/onboard/planning/route_planning.py | 11 +++++++++-- 1 file changed, 9 insertions(+), 2 deletions(-) diff --git a/GEMstack/onboard/planning/route_planning.py b/GEMstack/onboard/planning/route_planning.py index b507b8dc6..e88f43553 100644 --- a/GEMstack/onboard/planning/route_planning.py +++ b/GEMstack/onboard/planning/route_planning.py @@ -7,7 +7,7 @@ class StaticRoutePlanner(Component): """Reads a route from disk and returns it as the desired route.""" - def __init__(self, routefn : str): + def __init__(self, routefn : str, frame : str = 'start'): self.routefn = routefn base, ext = os.path.splitext(routefn) if ext in ['.json','.yml','.yaml']: @@ -17,7 +17,14 @@ def __init__(self, routefn : str): waypoints = np.loadtxt(routefn,delimiter=',',dtype=float) if waypoints.shape[1] == 3: waypoints = waypoints[:,:2] - self.route = Route(frame=ObjectFrameEnum.START,points=waypoints.tolist()) + if frame == 'start': + self.route = Route(frame=ObjectFrameEnum.START,points=waypoints.tolist()) + elif frame == 'global': + self.route = Route(frame=ObjectFrameEnum.GLOBAL,points=waypoints.tolist()) + elif frame == 'cartesian': + self.route = Route(frame=ObjectFrameEnum.ABSOLUTE_CARTESIAN,points=waypoints.tolist()) + else: + raise ValueError("Unknown route frame {} must be start, global, or cartesian".format(frame)) else: raise ValueError("Unknown route file extension",ext) From 9f7f2c694a1a2b2967e3d608afe1bc95ae0dc9c9 Mon Sep 17 00:00:00 2001 From: krishauser Date: Wed, 24 Jan 2024 00:09:04 -0500 Subject: [PATCH 064/232] Added vector_mul function --- GEMstack/mathutils/transforms.py | 12 ++++++++---- 1 file changed, 8 insertions(+), 4 deletions(-) diff --git a/GEMstack/mathutils/transforms.py b/GEMstack/mathutils/transforms.py index 151ab9836..679d5063a 100644 --- a/GEMstack/mathutils/transforms.py +++ b/GEMstack/mathutils/transforms.py @@ -16,14 +16,18 @@ def vector_add(v1, v2): """Adds v1 + v2 between two vectors""" return vo.add(v1,v2) -def vector_madd(v1, v2, s:float): - """Returns v1 + v2*s""" - return vo.madd(v1,v2,s) - def vector_sub(v1, v2): """Subtracts v1 - v2 between two vectors""" return vo.sub(v1,v2) +def vector_mul(v, s:float): + """Returns v*s""" + return vo.mul(v,s) + +def vector_madd(v1, v2, s:float): + """Returns v1 + v2*s""" + return vo.madd(v1,v2,s) + def vector_norm(v) -> float: """Norm of a vector""" return vo.norm(v) From 4ac745dc9b489857fea468556a31ca304b6a9563 Mon Sep 17 00:00:00 2001 From: krishauser Date: Wed, 24 Jan 2024 00:09:48 -0500 Subject: [PATCH 065/232] Added sensor callback error checking, zed image topic. --- GEMstack/onboard/interface/gem.py | 8 ++++-- GEMstack/onboard/interface/gem_hardware.py | 27 ++++++++++++++++++--- GEMstack/onboard/interface/gem_simulator.py | 6 ++++- 3 files changed, 35 insertions(+), 6 deletions(-) diff --git a/GEMstack/onboard/interface/gem.py b/GEMstack/onboard/interface/gem.py index 27353b99f..12db0d714 100644 --- a/GEMstack/onboard/interface/gem.py +++ b/GEMstack/onboard/interface/gem.py @@ -98,8 +98,12 @@ def sensors(self) -> List[str]: """Returns all available sensors""" return ['gnss','imu','top_lidar','top_stereo','front_radar'] - def subscribe_sensor(self, name : str, callback : Callable) -> None: - """Subscribes to a sensor with a given callback.""" + def subscribe_sensor(self, name : str, callback : Callable, type = None) -> None: + """Subscribes to a sensor with a given callback. + + If type is not None, it should be the expected type of the message produced + by the sensor callback. + """ raise NotImplementedError() def hardware_faults(self) -> List[str]: diff --git a/GEMstack/onboard/interface/gem_hardware.py b/GEMstack/onboard/interface/gem_hardware.py index 1b88730a0..0bb42e3c5 100644 --- a/GEMstack/onboard/interface/gem_hardware.py +++ b/GEMstack/onboard/interface/gem_hardware.py @@ -4,7 +4,7 @@ # ROS Headers import rospy from std_msgs.msg import String, Bool, Float32, Float64 -from sensor_msgs.msg import PointCloud2 +from sensor_msgs.msg import Image,PointCloud2 from novatel_gps_msgs.msg import NovatelPosition, NovatelXYZ, Inspva from radar_msgs.msg import RadarTracks from tf.transformations import euler_from_quaternion, quaternion_from_euler @@ -12,6 +12,9 @@ # GEM PACMod Headers from pacmod_msgs.msg import PositionWithSpeed, PacmodCmd, SystemRptFloat, VehicleSpeedRpt, GlobalRpt +# OpenCV and cv2 bridge +import cv2 +from cv_bridge import CvBridge class GEMHardwareInterface(GEMInterface): """Interface for connnecting to the physical GEM e2 vehicle.""" @@ -35,6 +38,7 @@ def __init__(self): self.gnss_sub = None self.imu_sub = None self.front_radar_sub = None + self.front_camera_sub = None self.lidar_sub = None self.stereo_sub = None self.faults = [] @@ -122,14 +126,31 @@ def global_callback(self, msg): def get_reading(self) -> GEMVehicleReading: return self.last_reading - def subscribe_sensor(self, name, callback): + def subscribe_sensor(self, name, callback, type = None): if name == 'gnss': + if type is not None and type is not Inspva: + raise ValueError("GEMHardwareInterface only supports Inspva for GNSS") self.gnss_sub = rospy.Subscriber("/novatel/inspva", Inspva, callback) elif name == 'lidar': + if type is not None and type is not PointCloud2: + raise ValueError("GEMHardwareInterface only supports PointCloud2 for lidar") self.lidar_sub = rospy.Subscriber("/lidar1/velodyne_points", PointCloud2, callback) elif name == 'front_radar': + if type is not None and type is not RadarTracks: + raise ValueError("GEMHardwareInterface only supports RadarTracks for front radar") self.front_radar_sub = rospy.Subscriber("/front_radar/front_radar/radar_tracks", RadarTracks, callback) - + elif name == 'front_camera': + if type is not None and (type is not Image and type is not cv2.Mat): + raise ValueError("GEMHardwareInterface only supports Image or OpenCV for front camera") + if type is None or type is Image: + self.front_camera_sub = rospy.Subscriber("/zed2/zed_node/rgb/image_rect_color", Image, callback) + else: + self.bridge = CvBridge() + def callback_with_cv2(msg : Image): + cv_image = self.bridge.imgmsg_to_cv2(msg, desired_encoding="passthrough") + callback(cv_image) + self.front_camera_sub = rospy.Subscriber("/zed2/zed_node/rgb/image_rect_color", Image, callback_with_cv2) + # PACMod enable callback function def pacmod_enable_callback(self, msg): if self.pacmod_enable == False and msg.data == True: diff --git a/GEMstack/onboard/interface/gem_simulator.py b/GEMstack/onboard/interface/gem_simulator.py index 6db392b6c..119a3d9c1 100644 --- a/GEMstack/onboard/interface/gem_simulator.py +++ b/GEMstack/onboard/interface/gem_simulator.py @@ -191,10 +191,14 @@ def sensors(self): #TODO: simulate other sensors? return ['gnss','imu'] - def subscribe_sensor(self, name, callback): + def subscribe_sensor(self, name, callback, type = None): if name == 'gnss': + if type is not None and type is not VehicleState: + raise ValueError("GEMDoubleIntegratorSimulationInterface only supports VehicleState for GNSS") self.gnss_callback = callback elif name == 'imu': + if type is not None and type is not VehicleState: + raise ValueError("GEMDoubleIntegratorSimulationInterface only supports VehicleState for IMU") self.imu_callback = callback def send_command(self, command : GEMVehicleCommand): From cc5a5e85ed43580241d3af3b93f39e4e4d9f9a83 Mon Sep 17 00:00:00 2001 From: krishauser Date: Wed, 24 Jan 2024 00:10:27 -0500 Subject: [PATCH 066/232] Fixed exception handling in executor --- GEMstack/onboard/execution/entrypoint.py | 3 ++- GEMstack/onboard/execution/execution.py | 26 ++++++++++++++++-------- 2 files changed, 20 insertions(+), 9 deletions(-) diff --git a/GEMstack/onboard/execution/entrypoint.py b/GEMstack/onboard/execution/entrypoint.py index f66fb727e..cf6f74af3 100644 --- a/GEMstack/onboard/execution/entrypoint.py +++ b/GEMstack/onboard/execution/entrypoint.py @@ -111,7 +111,8 @@ def main(): mission_executor.log_ros_topics(log_topics, rosbag_options) #determine whether to log vehicle interface log_vehicle_interface = log_settings.get('vehicle_interface',False) - mission_executor.log_vehicle_interface(log_vehicle_interface) + if log_vehicle_interface: + mission_executor.log_vehicle_interface(log_vehicle_interface) #determine whether to log components log_components = log_settings.get('components',[]) mission_executor.log_components(log_components) diff --git a/GEMstack/onboard/execution/execution.py b/GEMstack/onboard/execution/execution.py index 9f4d34034..4a03e1d50 100644 --- a/GEMstack/onboard/execution/execution.py +++ b/GEMstack/onboard/execution/execution.py @@ -11,6 +11,7 @@ import importlib import io import contextlib +import sys from typing import Dict,Tuple,Set,List,Optional EXECUTION_PREFIX = "Execution:" @@ -172,13 +173,14 @@ def __init__(self,c : Component, essential : bool = True): self.last_update_time = None self.next_update_time = None rate = c.rate() + self.had_exception = False self.dt = 1.0/rate if rate is not None else 0.0 self.num_overruns = 0 self.overrun_amount = 0.0 self.do_update = None def healthy(self): - return self.c.healthy() + return self.c.healthy() and not self.had_exception def start(self): self.c.initialize() @@ -196,13 +198,13 @@ def update(self, t : float, state : AllState): self.next_update_time += self.dt if self.next_update_time < t and self.dt > 0: if EXECUTION_VERBOSITY >= 1: - print(EXECUTION_PREFIX,"Component {} is running behind, overran dt {} by {} seconds".format(self.c,self.dt,t-self.next_update_time)) + print(EXECUTION_PREFIX,"Component {} is running behind, overran dt {} by {} seconds".format(self.c.__class__.__name__,self.dt,t-self.next_update_time)) self.num_overruns += 1 self.overrun_amount += t - self.next_update_time self.next_update_time = t + self.dt return True if EXECUTION_VERBOSITY >= 3: - print(EXECUTION_PREFIX,"Component",self.c,"not updating at time",t,", next update time is",self.next_update_time) + print(EXECUTION_PREFIX,"Component",self.c.__class__.__name__,"not updating at time",t,", next update time is",self.next_update_time) return False def _do_update(self, t:float, *args): @@ -210,10 +212,18 @@ def _do_update(self, t:float, *args): g = io.StringIO() with contextlib.redirect_stdout(f): with contextlib.redirect_stderr(g): - if self.do_update is not None: - res = self.do_update(*args) - else: - res = self.c.update(*args) + try: + if self.do_update is not None: + res = self.do_update(*args) + else: + res = self.c.update(*args) + except Exception as e: + print(EXECUTION_PREFIX,"Exception in component",self.c.__class__.__name__,":",e) + import traceback + print(traceback.format_exc(),file=sys.stderr) + print(traceback.format_exc(),file=sys.stdout) + self.had_exception = True + res = None self.log_output(t, f.getvalue(),g.getvalue()) return res @@ -231,7 +241,7 @@ def update_now(self, t:float, state : AllState): #write result to state if res is not None: if len(self.output) > 1: - assert len(res) == len(self.output), "Component {} output {} does not match expected length {}".format(self.c,self.output,len(self.output)) + assert len(res) == len(self.output), "Component {} output {} does not match expected length {}".format(self.c.__class__.__name__,self.output,len(self.output)) for (k,v) in zip(self.output,res): setattr(state,k, v) setattr(state,k+'_update_time', t) From 25b3e79253d102d6b5cf9b994a18fff2f1f83f12 Mon Sep 17 00:00:00 2001 From: krishauser Date: Wed, 24 Jan 2024 00:10:59 -0500 Subject: [PATCH 067/232] Implementation of IDM. Not tested. --- .../mathutils/intelligent_driver_model.py | 40 +++++++++++++++++++ 1 file changed, 40 insertions(+) create mode 100644 GEMstack/mathutils/intelligent_driver_model.py diff --git a/GEMstack/mathutils/intelligent_driver_model.py b/GEMstack/mathutils/intelligent_driver_model.py new file mode 100644 index 000000000..5d56ce3be --- /dev/null +++ b/GEMstack/mathutils/intelligent_driver_model.py @@ -0,0 +1,40 @@ +class IntelligentDriverModel: + """An implementation of the IDM model for car-following behavior.""" + def __init__(self): + self.v0 = 3. # desired velocity (m/s) + self.s0 = 5. # minimum spacing (m) + self.T = 5. # desired time headway (s) + self.a = 1.5 # acceleration (m/s^2) + self.b = 0.5 # comfortable braking deceleration (m/s^2) + self.delta = 4 # velocity ratio exponent (keep at 4) + + def set_desired_velocity(self,v0): + self.v0 = v0 + + def set_minimum_spacing(self,s0): + self.s0 = s0 + + def set_desired_time_headway(self,T): + self.T = T + + def set_accelerations(self,a,b): + self.a = a + self.b = b + + def __eval__(self,velocity,d_lead,v_lead=0): + """Returns the desired acceleration from the IDM model. + + Args: + velocity: current vehicle velocity in m/s + d_lead: the distance to the lead vehicle in m + v_lead: the velocity of the lead vehicle in m/s + + Returns: + The desired acceleration in m/s^2 + """ + va = velocity + dva = velocity - v_lead + sstar = self.s0 + va * self.T + (va * dva) / (2 * (self.a * self.b)**0.5) + accel = self.a * (1 - (va / self.v0)**self.delta - (sstar / d_lead)**2) + return accel + From e452ebffde130963b4fe1ef9389757f3d16ae38c Mon Sep 17 00:00:00 2001 From: krishauser Date: Fri, 26 Jan 2024 14:27:40 -0500 Subject: [PATCH 068/232] Fixed typo with method prototype --- GEMstack/onboard/interface/gem.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/GEMstack/onboard/interface/gem.py b/GEMstack/onboard/interface/gem.py index 12db0d714..f24309dc6 100644 --- a/GEMstack/onboard/interface/gem.py +++ b/GEMstack/onboard/interface/gem.py @@ -90,7 +90,7 @@ def get_reading(self) -> GEMVehicleReading: """Returns current read state of the vehicle""" raise NotImplementedError() - def send_command(cmd : GEMVehicleCommand): + def send_command(self, cmd : GEMVehicleCommand): """Sends a command to the vehicle""" raise NotImplementedError() From 57ffc1d261d6afe217a5afcf59175b1775e660a6 Mon Sep 17 00:00:00 2001 From: krishauser Date: Fri, 26 Jan 2024 14:29:56 -0500 Subject: [PATCH 069/232] A vehicle interface that doesn't drive the vehicle but uses live sensor data (except for GNSS) --- GEMstack/onboard/interface/gem_mixed.py | 42 +++++++++++++++++++++++++ 1 file changed, 42 insertions(+) create mode 100644 GEMstack/onboard/interface/gem_mixed.py diff --git a/GEMstack/onboard/interface/gem_mixed.py b/GEMstack/onboard/interface/gem_mixed.py new file mode 100644 index 000000000..fb2ea85f4 --- /dev/null +++ b/GEMstack/onboard/interface/gem_mixed.py @@ -0,0 +1,42 @@ +from .gem import GEMInterface, GEMVehicleCommand, GEMVehicleReading +from .gem_hardware import GEMHardwareInterface +from .gem_simulator import GEMDoubleIntegratorSimulationInterface +from typing import Callable, List + +class GEMRealSensorsWithSimMotionInterface(GEMInterface): + """Class that uses sensors from the physical GEM vehicle but + commands and readings go to a simulation. Just the + GEMDoubleIntegratorSimulationInterface is supported for sim now. + """ + def __init__(self, scene:str = None): + self.sim = GEMDoubleIntegratorSimulationInterface(scene) + self.real = GEMHardwareInterface() + + def start(self): + self.sim.start() + self.real.start() + + def stop(self): + self.sim.stop() + self.real.stop() + + def time(self) -> float: + return self.sim.time() + + def get_reading(self) -> GEMVehicleReading: + return self.sim.get_reading() + + def send_command(self, cmd : GEMVehicleCommand): + self.sim.send_command(cmd) + + def sensors(self): + return self.real.sensors() + + def subscribe_sensor(self, name : str, callback : Callable, type = None) -> None: + if name in ['gnss','imu']: + return self.sim.subscribe_sensor(name,callback,type) + return self.real.subscribe_sensor(name,callback,type) + + def hardware_faults(self) -> List[str]: + return self.real.hardware_faults() + self.sim.hardware_faults() + From 7486c82407ff696017a37cc0ba646c7ae92c3fcc Mon Sep 17 00:00:00 2001 From: krishauser Date: Fri, 26 Jan 2024 14:30:09 -0500 Subject: [PATCH 070/232] Warning message on invalid sensor --- GEMstack/onboard/interface/gem_simulator.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/GEMstack/onboard/interface/gem_simulator.py b/GEMstack/onboard/interface/gem_simulator.py index 119a3d9c1..3c19596a7 100644 --- a/GEMstack/onboard/interface/gem_simulator.py +++ b/GEMstack/onboard/interface/gem_simulator.py @@ -200,6 +200,8 @@ def subscribe_sensor(self, name, callback, type = None): if type is not None and type is not VehicleState: raise ValueError("GEMDoubleIntegratorSimulationInterface only supports VehicleState for IMU") self.imu_callback = callback + else: + print("Warning, GEM simulator doesn't provide sensor",name) def send_command(self, command : GEMVehicleCommand): self.last_command = command From ff394322439d402a1502dc820d184942170c0a41 Mon Sep 17 00:00:00 2001 From: krishauser Date: Tue, 30 Jan 2024 09:56:08 -0500 Subject: [PATCH 071/232] Added global pose test --- testing/test_poses.py | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/testing/test_poses.py b/testing/test_poses.py index a265b648d..d3bf4d86b 100644 --- a/testing/test_poses.py +++ b/testing/test_poses.py @@ -13,6 +13,16 @@ def test_poses(): print(math.degrees(transforms.heading_to_yaw(90.0)),'== 0') print(transforms.yaw_to_heading(math.pi,degrees=True),'== 270') + start_pose_global = ObjectPose(frame=ObjectFrameEnum.GLOBAL,t=time.time(),x=40.09286250064475,y=-88.23565755734872,yaw=90.0) + current_pose_global = ObjectPose(frame=ObjectFrameEnum.GLOBAL,t=time.time()+55.0,x=40.09287891579668, y=-88.23588822731645,yaw=90.0) + current_pose_start = current_pose_global.to_frame(ObjectFrameEnum.START,start_pose_abs=start_pose_global) + print(current_pose_start.x,current_pose_start.y,current_pose_start.yaw,"(should be <0, ~=0, ~=0)") + + start_pose_global = ObjectPose(frame=ObjectFrameEnum.GLOBAL,t=time.time(),x=40.09286250064475,y=-88.23565755734872,yaw=270.0) + current_pose_global = ObjectPose(frame=ObjectFrameEnum.GLOBAL,t=time.time()+55.0,x=40.09287891579668, y=-88.23588822731645,yaw=270.0) + current_pose_start = current_pose_global.to_frame(ObjectFrameEnum.START,start_pose_abs=start_pose_global) + print(current_pose_start.x,current_pose_start.y,current_pose_start.yaw,"(should be >0, ~=0, ~=0)") + start_pose_abs = ObjectPose(frame=ObjectFrameEnum.ABSOLUTE_CARTESIAN,t=time.time(),x=30.0,y=20.0,yaw=0.5) current_pose_abs = ObjectPose(frame=ObjectFrameEnum.ABSOLUTE_CARTESIAN,t=time.time()+55.0,x=60.0,y=25.0,yaw=1.5) current_pose_start = ObjectPose(frame=ObjectFrameEnum.START,t=55.0,x=60.0,y=25.0,yaw=1.0) From f050c63ed2bc8e21855daeefedbd0c3cb410c1d1 Mon Sep 17 00:00:00 2001 From: Kris Hauser Date: Tue, 30 Jan 2024 11:19:09 -0500 Subject: [PATCH 072/232] Fixed test fixtures to account for convention in google maps, yaw in ObjectPose --- testing/test_poses.py | 21 +++++++++++++++++---- 1 file changed, 17 insertions(+), 4 deletions(-) diff --git a/testing/test_poses.py b/testing/test_poses.py index d3bf4d86b..6e6a93afc 100644 --- a/testing/test_poses.py +++ b/testing/test_poses.py @@ -4,6 +4,7 @@ sys.path.append(os.getcwd()) from GEMstack.state import PhysicalObject,ObjectPose,ObjectFrameEnum +from GEMstack.state.physical_object import _get_frame_chain from GEMstack.mathutils import transforms import math import time @@ -13,14 +14,26 @@ def test_poses(): print(math.degrees(transforms.heading_to_yaw(90.0)),'== 0') print(transforms.yaw_to_heading(math.pi,degrees=True),'== 270') - start_pose_global = ObjectPose(frame=ObjectFrameEnum.GLOBAL,t=time.time(),x=40.09286250064475,y=-88.23565755734872,yaw=90.0) - current_pose_global = ObjectPose(frame=ObjectFrameEnum.GLOBAL,t=time.time()+55.0,x=40.09287891579668, y=-88.23588822731645,yaw=90.0) + #google maps gives latitude,longitude, ugh... + #ObjectPose yaw expects radians, heading CW from north + start_pose_global = ObjectPose(frame=ObjectFrameEnum.GLOBAL,t=time.time(),y=40.09286250064475,x=-88.23565755734872,yaw=math.radians(90.0)) + current_pose_global = ObjectPose(frame=ObjectFrameEnum.GLOBAL,t=time.time()+55.0,y=40.09287891579668, x=-88.23588822731645,yaw=math.radians(90.0)) current_pose_start = current_pose_global.to_frame(ObjectFrameEnum.START,start_pose_abs=start_pose_global) print(current_pose_start.x,current_pose_start.y,current_pose_start.yaw,"(should be <0, ~=0, ~=0)") - start_pose_global = ObjectPose(frame=ObjectFrameEnum.GLOBAL,t=time.time(),x=40.09286250064475,y=-88.23565755734872,yaw=270.0) - current_pose_global = ObjectPose(frame=ObjectFrameEnum.GLOBAL,t=time.time()+55.0,x=40.09287891579668, y=-88.23588822731645,yaw=270.0) + start_pose_global = ObjectPose(frame=ObjectFrameEnum.GLOBAL,t=time.time(),y=40.09286250064475,x=-88.23565755734872,yaw=math.radians(270.0)) + current_pose_global = ObjectPose(frame=ObjectFrameEnum.GLOBAL,t=time.time()+55.0,y=40.09287891579668, x=-88.23588822731645,yaw=math.radians(270.0)) current_pose_start = current_pose_global.to_frame(ObjectFrameEnum.START,start_pose_abs=start_pose_global) + # frame_chain = _get_frame_chain(ObjectFrameEnum.GLOBAL,ObjectFrameEnum.START,current_pose_global,start_pose_abs=start_pose_global) + # xyhead = (current_pose_global.x,current_pose_global.y,current_pose_global.yaw) + # print(xyhead) + # for (frame,pose,dir) in frame_chain[1:]: + # print("Frame change:",frame,pose,dir) + # if dir == 1: + # xyhead = pose.apply_xyhead(xyhead) + # else: + # xyhead = pose.apply_inv_xyhead(xyhead) + # print(xyhead) print(current_pose_start.x,current_pose_start.y,current_pose_start.yaw,"(should be >0, ~=0, ~=0)") start_pose_abs = ObjectPose(frame=ObjectFrameEnum.ABSOLUTE_CARTESIAN,t=time.time(),x=30.0,y=20.0,yaw=0.5) From 2431c353a1380167b63fa5f217cbbcc0e7e7f054 Mon Sep 17 00:00:00 2001 From: Kris Hauser Date: Tue, 30 Jan 2024 11:19:34 -0500 Subject: [PATCH 073/232] Setting radians as expected by ObjectPose --- GEMstack/onboard/perception/state_estimation.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/GEMstack/onboard/perception/state_estimation.py b/GEMstack/onboard/perception/state_estimation.py index 56591ac94..e9e0eb2a9 100644 --- a/GEMstack/onboard/perception/state_estimation.py +++ b/GEMstack/onboard/perception/state_estimation.py @@ -29,9 +29,9 @@ def inspva_callback(self, inspva_msg): x=inspva_msg.longitude, y=inspva_msg.latitude, z=inspva_msg.height, - yaw=inspva_msg.azimuth, #heading from north in degrees - roll=inspva_msg.roll, - pitch=inspva_msg.pitch, + yaw=math.radians(inspva_msg.azimuth), #heading from north in degrees + roll=math.radians(inspva_msg.inspva_msg.roll), + pitch=math.radians(inspva_msg.inspva_msg.pitch), ) #TODO: figure out what this status means print("INS status",inspva_msg.status) @@ -48,7 +48,7 @@ def healthy(self): def update(self) -> VehicleState: if self.gnss_pose is None: return - # vehicle gnss heading (yaw) in degrees + # vehicle gnss heading (yaw) in radians # vehicle x, y position in fixed local frame, in meters # reference point is located at the center of GNSS antennas localxy = transforms.rotate2d(self.location,-self.yaw_offset) From 0cb30949e3436b063ff23373e294fbe48662508c Mon Sep 17 00:00:00 2001 From: Kris Hauser Date: Tue, 30 Jan 2024 11:23:09 -0500 Subject: [PATCH 074/232] Fixed rotation component of GLOBAL frame conversions, added directional methods --- GEMstack/state/physical_object.py | 67 +++++++++++++++++++++++++++---- 1 file changed, 59 insertions(+), 8 deletions(-) diff --git a/GEMstack/state/physical_object.py b/GEMstack/state/physical_object.py index 8d3455cfe..e21381b5c 100644 --- a/GEMstack/state/physical_object.py +++ b/GEMstack/state/physical_object.py @@ -73,11 +73,14 @@ def transform(self) -> np.ndarray: return se3.ndarray((so3.from_ndarray(self.rotation()),self.translation())) def apply(self,point): - """Applies this pose to a local (x,y) or (x,y,z) coordinate.""" + """Applies this pose to a local (x,y) or (x,y,z) coordinate. + + If point is 2D, then the pitch and roll are ignored. + """ assert len(point) in [2,3],"Must provide a 2D or 3D point" oz = self.z if self.z is not None else 0.0 if self.frame == ObjectFrameEnum.GLOBAL: - east_m,north_m = point[:2] + east_m,north_m = self.rotation2d().dot(point[:2]) olon,olat = self.x,self.y lat,lon = transforms.xy_to_lat_lon(east_m,north_m,olat,olon) if len(point) == 2: @@ -91,25 +94,70 @@ def apply(self,point): def apply_inv(self,point): """Applies the inverse of this pose to an (x,y) or (x,y,z) coordinate - specified in the same frame as this.""" + specified in the same frame as this. + + If point is 2D, then the pitch and roll are ignored. Otherwise, they + are taken into account. + """ assert len(point) in [2,3],"Must provide a 2D or 3D point" oz = self.z if self.z is not None else 0.0 if self.frame == ObjectFrameEnum.GLOBAL: lon,lat = point[:2] olon,olat = self.x,self.y east_m, north_m = transforms.lat_lon_to_xy(lat,lon,olat,olon) + px,py = self.rotation2d().T.dot((east_m,north_m)) if len(point) == 2: - return (east_m, north_m) + return (px,py) else: - return (east_m, north_m, point[2] - oz) + return (px,py, point[2] - oz) if len(point) == 2: return tuple(self.rotation2d().T.dot(np.array(point)-self.translation()[:2])) else: return tuple(self.rotation().T.dot(np.array(point)-self.translation())) + def apply_dir(self,vec): + """Applies this pose to a local (x,y) or (x,y,z) directional quantity. + + If direction is 2D, then the pitch and roll are ignored. + """ + assert len(vec) in [2,3],"Must provide a 2D or 3D direction" + oz = self.z if self.z is not None else 0.0 + if self.frame == ObjectFrameEnum.GLOBAL: + east_m,north_m = self.rotation2d().dot(vec[:2]) + if len(vec) == 2: + return (east_m,north_m) + else: + return (east_m,north_m, vec[2] + oz) + if len(vec) == 2: + return tuple(self.rotation2d().dot(vec)) + else: + return tuple(self.rotation().dot(vec)) + + def apply_dir_inv(self,vec): + """Applies the inverse of this pose to an (x,y) or (x,y,z) directional + quantity specified in the same frame as this. + + If direction is 2D, then the pitch and roll are ignored. Otherwise, they + are taken into account. + """ + assert len(vec) in [2,3],"Must provide a 2D or 3D direction" + oz = self.z if self.z is not None else 0.0 + if self.frame == ObjectFrameEnum.GLOBAL: + east_m, north_m = vec[:2] + px,py = self.rotation2d().T.dot((east_m,north_m)) + if len(vec) == 2: + return (px,py) + else: + return (px,py, vec[2] - oz) + if len(vec) == 2: + return tuple(self.rotation2d().T.dot(vec)) + else: + return tuple(self.rotation().T.dot(vec)) + def apply_xyhead(self,xyhead): """Applies this pose to a local (x,y,yaw) coordinate. yaw is always - specified in CCW radians.""" + specified in CCW radians. Pitch and roll are ignored. + """ newxy = self.apply(xyhead[:2]) yaw = self.yaw if self.yaw is not None else 0.0 if self.frame == ObjectFrameEnum.GLOBAL: @@ -120,7 +168,7 @@ def apply_xyhead(self,xyhead): def apply_inv_xyhead(self,xyhead): """Applies this pose to a (x,y,yaw) coordinate expressed in `frame`. yaw is specified in CCW radians except for GLOBAL, in which case - yaw is CW heading.""" + yaw is CW heading. Pitch and roll are ignored.""" newxy = self.apply_inv(xyhead[:2]) yaw = self.yaw if self.yaw is not None else 0.0 if self.frame == ObjectFrameEnum.GLOBAL: @@ -131,7 +179,10 @@ def apply_inv_xyhead(self,xyhead): def to_frame(self, new_frame : ObjectFrameEnum, current_pose : ObjectPose = None, start_pose_abs : ObjectPose = None) -> ObjectPose: """Returns a new ObjectPose representing the same pose, but with - coordinates expressed in a different frame.""" + coordinates expressed in a different frame. + + Note that pitch and roll will be preserved! + """ if self.frame == new_frame: return replace(self) frame_chain = _get_frame_chain(self.frame,new_frame,current_pose,start_pose_abs) From c214700074cbe05a15529a65014d0cd05fa36105 Mon Sep 17 00:00:00 2001 From: krishauser Date: Tue, 30 Jan 2024 15:01:37 -0500 Subject: [PATCH 075/232] Added Hang's pedal dynamic model, hardware limits, rate limitations in Pacmod --- GEMstack/knowledge/defaults/current.yaml | 2 + GEMstack/knowledge/vehicle/dynamics.py | 116 +++++++++++------- .../knowledge/vehicle/gem_e2_dynamics.yaml | 11 +- .../knowledge/vehicle/gem_e2_slow_limits.yaml | 2 +- GEMstack/onboard/interface/gem.py | 15 ++- GEMstack/onboard/interface/gem_hardware.py | 66 ++++++++-- GEMstack/onboard/interface/gem_mixed.py | 5 +- 7 files changed, 152 insertions(+), 65 deletions(-) diff --git a/GEMstack/knowledge/defaults/current.yaml b/GEMstack/knowledge/defaults/current.yaml index 600b0ed08..533c56b14 100644 --- a/GEMstack/knowledge/defaults/current.yaml +++ b/GEMstack/knowledge/defaults/current.yaml @@ -6,6 +6,8 @@ vehicle: version: e2 max_gear : 1 num_wiper_settings : 1 + enable_through_joystick : true #turn this to false to have GEMstack enable control + max_command_rate : 10.0 #for hardware, max rate of commands to send to vehicle over Pacmod #using !include directives helps maintain reuse of common settings geometry: !include ../vehicle/gem_e2_geometry.yaml dynamics: !include ../vehicle/gem_e2_dynamics.yaml diff --git a/GEMstack/knowledge/vehicle/dynamics.py b/GEMstack/knowledge/vehicle/dynamics.py index 4cf4f9b80..e5db54d49 100644 --- a/GEMstack/knowledge/vehicle/dynamics.py +++ b/GEMstack/knowledge/vehicle/dynamics.py @@ -17,56 +17,78 @@ def acceleration_to_pedal_positions(acceleration : float, velocity : float, pitc Returns tuple (accelerator_pedal_position, brake_pedal_position, desired_gear) """ - brake_max = settings.get('vehicle.dynamics.max_brake_deceleration') - reverse_accel_max = settings.get('vehicle.dynamics.max_accelerator_acceleration_reverse') - accel_max = settings.get('vehicle.dynamics.max_accelerator_acceleration') - assert isinstance(brake_max,(int,float)) - assert isinstance(reverse_accel_max,(int,float)) - assert isinstance(accel_max,list) - assert isinstance(acceleration,(int,float)) - - #compute required acceleration - vsign = sign(velocity) - gravity = settings.get('vehicle.dynamics.gravity') - internal_dry_deceleration = settings.get('vehicle.dynamics.internal_dry_deceleration') - internal_viscous_deceleration = settings.get('vehicle.dynamics.internal_viscous_deceleration') - aerodynamic_drag_coefficient = settings.get('vehicle.dynamics.aerodynamic_drag_coefficient') - drag = -(aerodynamic_drag_coefficient * velocity**2) * vsign - internal_dry_deceleration * vsign - internal_viscous_deceleration * velocity - sin_pitch = math.sin(pitch) - acceleration -= drag + gravity * sin_pitch - #this is the net acceleration that should be achieved by accelerator / brake pedal - - #TODO: power curves to select optimal gear - if velocity * acceleration < 0: - accel_pos = 0 - brake_pos = -acceleration / brake_max - if brake_pos > 1.0: - brake_pos = 1.0 - return (accel_pos,brake_pos,gear) - else: - #may want to switch gear? - if velocity == 0: - if acceleration < 0: - gear = -1 + model = settings.get('vehicle.dynamics.acceleration_model','v1_hang') + if model == 'v1_hang': + if gear != 1: + print("WARNING can't handle gears other than 1 yet") + max_accel = settings.get('vehicle.dynamics.max_accelerator_acceleration') # m/s^2 + max_brake = settings.get('vehicle.dynamics.max_brake_deceleration') # m/s^2 + dry_decel = settings.get('vehicle.dynamics.internal_dry_deceleration') # m/s^2 + accel_active_range = settings.get('vehicle.dynamics.accelerator_active_range') # pedal position fraction + brake_active_range = settings.get('vehicle.dynamics.brake_active_range') # pedal position fraction + #linear curves + if acceleration > -dry_decel: + if acceleration < -dry_decel*0.5 or (acceleration <= 0 and velocity < 0.1): # a little deadband to avoid oscillation + throttle_percent = 0.0 #drift to stop else: - #forward gear - gear = 1 - if gear < 0: - #reverse gear - accel_pos = -acceleration / reverse_accel_max - brake_pos = 0 - if accel_pos > 1.0: - accel_pos = 1.0 - return (accel_pos,brake_pos,-1) - elif gear > 0: - accel_pos = acceleration / accel_max[gear] - brake_pos = 0 - if accel_pos > 1.0: - accel_pos = 1.0 + throttle_percent = accel_active_range[0] + (acceleration+dry_decel)/max_accel * (accel_active_range[1]-accel_active_range[0]) + brake_percent = 0 + else: + brake_percent = brake_active_range[0] + -(acceleration+dry_decel)/max_brake * (brake_active_range[1]-brake_active_range[0]) + throttle_percent = 0 + return (max(throttle_percent,0.0),max(brake_percent,0.0),1) + + elif model == 'v1_kris': + brake_max = settings.get('vehicle.dynamics.max_brake_deceleration') + reverse_accel_max = settings.get('vehicle.dynamics.max_accelerator_acceleration_reverse') + accel_max = settings.get('vehicle.dynamics.max_accelerator_acceleration') + assert isinstance(brake_max,(int,float)) + assert isinstance(reverse_accel_max,(int,float)) + assert isinstance(accel_max,list) + assert isinstance(acceleration,(int,float)) + + #compute required acceleration + vsign = sign(velocity) + gravity = settings.get('vehicle.dynamics.gravity') + internal_dry_deceleration = settings.get('vehicle.dynamics.internal_dry_deceleration') + internal_viscous_deceleration = settings.get('vehicle.dynamics.internal_viscous_deceleration') + aerodynamic_drag_coefficient = settings.get('vehicle.dynamics.aerodynamic_drag_coefficient') + drag = -(aerodynamic_drag_coefficient * velocity**2) * vsign - internal_dry_deceleration * vsign - internal_viscous_deceleration * velocity + sin_pitch = math.sin(pitch) + acceleration -= drag + gravity * sin_pitch + #this is the net acceleration that should be achieved by accelerator / brake pedal + + #TODO: power curves to select optimal gear + if velocity * acceleration < 0: + accel_pos = 0 + brake_pos = -acceleration / brake_max + if brake_pos > 1.0: + brake_pos = 1.0 return (accel_pos,brake_pos,gear) else: - #stay in neutral gear - return (0,1,0) + #may want to switch gear? + if velocity == 0: + if acceleration < 0: + gear = -1 + else: + #forward gear + gear = 1 + if gear < 0: + #reverse gear + accel_pos = -acceleration / reverse_accel_max + brake_pos = 0 + if accel_pos > 1.0: + accel_pos = 1.0 + return (accel_pos,brake_pos,-1) + elif gear > 0: + accel_pos = acceleration / accel_max[gear] + brake_pos = 0 + if accel_pos > 1.0: + accel_pos = 1.0 + return (accel_pos,brake_pos,gear) + else: + #stay in neutral gear + return (0,1,0) def pedal_positions_to_acceleration(accelerator_pedal_position : float, brake_pedal_position : float, velocity : float, pitch : float, gear : int) -> float: diff --git a/GEMstack/knowledge/vehicle/gem_e2_dynamics.yaml b/GEMstack/knowledge/vehicle/gem_e2_dynamics.yaml index 4b494ed8d..dfff67b00 100644 --- a/GEMstack/knowledge/vehicle/gem_e2_dynamics.yaml +++ b/GEMstack/knowledge/vehicle/gem_e2_dynamics.yaml @@ -2,15 +2,20 @@ mass: 200.0 #kg gravity: 9.81 #m/s^2 longitudinal_friction : 1.0 # unitless lateral_friction : 1.0 # unitless -max_brake_deceleration: 2.0 #m/s^2. Deceleration at max brake pedal +max_brake_deceleration: 8.0 #m/s^2. Deceleration at max brake pedal max_accelerator_acceleration: #m/s^2. Acceleration at max accelerator pedal, by gear - 0.0 - - 2.5 + - 5.0 max_accelerator_acceleration_reverse: 2.5 #m/s^2. Acceleration (backwards) in reverse gear max_accelerator_power: #Watts. Power at max accelerator pedal, by gear - 0.0 - 10000.0 max_accelerator_power_reverse: 10000.0 #Watts. Power (backwards) in reverse gear -internal_dry_deceleration: 0.01 #m/s^2: deceleration due to internal dry friction (non-speed dependent) + +acceleration_model : hang_v1 +accelerator_active_range : [0.32, 1.0] #range of accelerator pedal where output acceleration is not flat +brake_active_range : [0,1] #range of brake pedal where output deceleration is not flat + +internal_dry_deceleration: 0.2 #m/s^2: deceleration due to internal dry friction (non-speed dependent) internal_viscous_deceleration: 0.05 #1/s: scales the current velocity to get deceleration due to internal viscous friction (speed dependent) aerodynamic_drag_coefficient: 0.01 #units in s, scaled by velocity^2 to get deceleration due to aerodynamic drag diff --git a/GEMstack/knowledge/vehicle/gem_e2_slow_limits.yaml b/GEMstack/knowledge/vehicle/gem_e2_slow_limits.yaml index c1c5f93a3..8720ae250 100644 --- a/GEMstack/knowledge/vehicle/gem_e2_slow_limits.yaml +++ b/GEMstack/knowledge/vehicle/gem_e2_slow_limits.yaml @@ -4,5 +4,5 @@ max_reverse_speed: 0.25 #m/s, approx 1mph max_acceleration: 1.0 #m/s^2 max_deceleration: 2.0 #m/s^2 max_accelerator_pedal: 0.5 #0-1 -max_brake_pedal: 1.0 #0-1 +max_brake_pedal: 0.5 #0-1 diff --git a/GEMstack/onboard/interface/gem.py b/GEMstack/onboard/interface/gem.py index f24309dc6..0af1e64cd 100644 --- a/GEMstack/onboard/interface/gem.py +++ b/GEMstack/onboard/interface/gem.py @@ -23,7 +23,14 @@ class GEMVehicleReading: fuel_level : Optional[float] = None # in liters driving_range : Optional[float] = None # remaining range left, in km - def from_state(self, state: VehicleState): + def from_state(self, state: VehicleState) -> None: + """Sets the readings that would be approximately sensed at the given + VehicleState. + + Approximates the pedal positions using the current dynamics model. + + Does not change the battery_level, fuel_level, or driving_range values. + """ self.speed = state.v self.steering_wheel_angle = state.steering_wheel_angle pitch = state.pose.pitch if state.pose.pitch is not None else 0.0 @@ -38,6 +45,12 @@ def from_state(self, state: VehicleState): self.headlights_on = state.headlights_on def to_state(self, pose : ObjectPose = None) -> VehicleState: + """Returns a VehicleState representing the vehicle's current state given + these readings. + + Note: the acceleration attribute is totally bogus, and should be ignored + until the dynamics are calibrated better. + """ if pose is None: pose = ObjectPose(frame = ObjectFrameEnum.CURRENT,t=0,x=0,y=0,yaw=0) pitch = pose.pitch if pose.pitch is not None else 0.0 diff --git a/GEMstack/onboard/interface/gem_hardware.py b/GEMstack/onboard/interface/gem_hardware.py index 0bb42e3c5..6e99814e1 100644 --- a/GEMstack/onboard/interface/gem_hardware.py +++ b/GEMstack/onboard/interface/gem_hardware.py @@ -1,4 +1,5 @@ from .gem import * +from ...utils import settings import math # ROS Headers @@ -20,6 +21,8 @@ class GEMHardwareInterface(GEMInterface): """Interface for connnecting to the physical GEM e2 vehicle.""" def __init__(self): GEMInterface.__init__(self) + self.max_send_rate = settings.get('vehicle.max_command_rate',10.0) + self.last_command_time = 0.0 self.last_reading = GEMVehicleReading() self.last_reading.speed = 0.0 self.last_reading.steering_wheel_angle = 0.0 @@ -52,7 +55,8 @@ def __init__(self): # GEM vehicle gear control, neutral, forward and reverse, publish once self.gear_pub = rospy.Publisher('/pacmod/as_rx/shift_cmd', PacmodCmd, queue_size=1) self.gear_cmd = PacmodCmd() - self.gear_cmd.ui16_cmd = 2 # SHIFT_NEUTRAL + self.gear_cmd.enable = True + self.gear_cmd.ui16_cmd = PacmodCmd.SHIFT_NEUTRAL # GEM vehicle brake control self.brake_pub = rospy.Publisher('/pacmod/as_rx/brake_cmd', PacmodCmd, queue_size=1) @@ -82,17 +86,20 @@ def __init__(self): """TODO: other commands /pacmod/as_rx/headlight_cmd /pacmod/as_rx/horn_cmd - /pacmod/as_rx/turn_cmd /pacmod/as_rx/wiper_cmd """ #TODO: publish TwistStamped to /front_radar/front_radar/vehicle_motion to get better radar tracks def start(self): - print("ENABLING PACMOD") - enable_cmd = Bool() - enable_cmd.data = True - self.enable_pub.publish(enable_cmd) + if settings.get('vehicle.enable_through_joystick',True): + pass + else: + print("ENABLING PACMOD") + enable_cmd = Bool() + enable_cmd.data = True + self.enable_pub.publish(enable_cmd) + #this doesn't seem to work super well, need to send enable command multiple times def time(self): seconds = rospy.get_time() @@ -147,14 +154,16 @@ def subscribe_sensor(self, name, callback, type = None): else: self.bridge = CvBridge() def callback_with_cv2(msg : Image): - cv_image = self.bridge.imgmsg_to_cv2(msg, desired_encoding="passthrough") + #print("received image with size",msg.width,msg.height,"encoding",msg.encoding) + cv_image = self.bridge.imgmsg_to_cv2(msg, desired_encoding="bgr8") callback(cv_image) self.front_camera_sub = rospy.Subscriber("/zed2/zed_node/rgb/image_rect_color", Image, callback_with_cv2) # PACMod enable callback function def pacmod_enable_callback(self, msg): if self.pacmod_enable == False and msg.data == True: - print("PACMod enabled") + print("PACMod enabled, enabling gear, brake, accel, steer, and turn") + self.send_first_command() elif self.pacmod_enable == True and msg.data == False: print("PACMod disabled") self.pacmod_enable = msg.data @@ -168,13 +177,16 @@ def send_first_command(self): # ---------- Enable PACMod ---------- # enable forward gear - self.gear_cmd.ui16_cmd = 3 + self.gear_cmd.enable = True + self.gear_cmd.ui16_cmd = PacmodCmd.SHIFT_FORWARD + #helps debug whether gear command is being sent since you'll hear the backup beep + #self.gear_cmd.ui16_cmd = PacmodCmd.SHIFT_REVERSE # enable brake self.brake_cmd.enable = True self.brake_cmd.clear = False self.brake_cmd.ignore = False - self.brake_cmd.f64_cmd = 1.0 + self.brake_cmd.f64_cmd = 0.0 # enable gas self.accel_cmd.enable = True @@ -186,10 +198,16 @@ def send_first_command(self): self.turn_pub.publish(self.turn_cmd) self.brake_pub.publish(self.brake_cmd) self.accel_pub.publish(self.accel_cmd) + self.last_command_time = self.time() - - # Start PACMod interface def send_command(self, command : GEMVehicleCommand): + #throttle rate at which we send commands + t = self.time() + if t < self.last_command_time + 1.0/self.max_send_rate: + #skip command, PACMod can't handle commands this fast + return + self.last_command_time = t + if command.left_turn_signal and command.right_turn_signal: self.turn_cmd.ui16_cmd = PacmodCmd.TURN_HAZARDS elif command.left_turn_signal: @@ -205,6 +223,30 @@ def send_command(self, command : GEMVehicleCommand): self.brake_cmd.f64_cmd = command.brake_pedal_position self.steer_cmd.angular_position = command.steering_wheel_angle self.steer_cmd.angular_velocity_limit = command.steering_wheel_speed + print("**************************") + print("Steer cmd angular position {} velocity limit {}".format(self.steer_cmd.angular_position,self.steer_cmd.angular_velocity_limit)) + print("Accel pedal position {} brake position {}".format(self.accel_cmd.f64_cmd,self.brake_cmd.f64_cmd)) + maxacc = settings.get('vehicle.limits.max_accelerator_pedal') + maxbrake = settings.get('vehicle.limits.max_brake_pedal') + if self.accel_cmd.f64_cmd > maxacc: + print("Warning: commanded acceleration exceeded accel pedal limit") + self.accel_cmd.f64_cmd = maxacc + if self.brake_cmd.f64_cmd > maxbrake: + print("Warning: commanded braking exceeded brake pedal limit") + self.brake_cmd.f64_cmd = maxbrake + print("**************************") + + self.brake_cmd.enable = True + self.brake_cmd.clear = False + self.brake_cmd.ignore = False + + self.accel_cmd.enable = True + self.accel_cmd.clear = False + self.accel_cmd.ignore = False + + self.gear_cmd.ui16_cmd = PacmodCmd.SHIFT_FORWARD + self.gear_cmd.enable = True + self.gear_pub.publish(self.gear_cmd) self.accel_pub.publish(self.accel_cmd) self.brake_pub.publish(self.brake_cmd) self.steer_pub.publish(self.steer_cmd) diff --git a/GEMstack/onboard/interface/gem_mixed.py b/GEMstack/onboard/interface/gem_mixed.py index fb2ea85f4..be37be41f 100644 --- a/GEMstack/onboard/interface/gem_mixed.py +++ b/GEMstack/onboard/interface/gem_mixed.py @@ -11,6 +11,7 @@ class GEMRealSensorsWithSimMotionInterface(GEMInterface): def __init__(self, scene:str = None): self.sim = GEMDoubleIntegratorSimulationInterface(scene) self.real = GEMHardwareInterface() + GEMInterface.__init__(self) def start(self): self.sim.start() @@ -24,9 +25,11 @@ def time(self) -> float: return self.sim.time() def get_reading(self) -> GEMVehicleReading: - return self.sim.get_reading() + self.last_reading = self.sim.get_reading() + return self.last_reading def send_command(self, cmd : GEMVehicleCommand): + self.last_command = cmd self.sim.send_command(cmd) def sensors(self): From c4b6bd99b369a0db9a9a59dccd4b08f4a56af740 Mon Sep 17 00:00:00 2001 From: krishauser Date: Tue, 30 Jan 2024 18:42:55 -0500 Subject: [PATCH 076/232] Added angle wrapping check --- GEMstack/onboard/planning/pure_pursuit.py | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/GEMstack/onboard/planning/pure_pursuit.py b/GEMstack/onboard/planning/pure_pursuit.py index 8d81e3627..dde99b592 100644 --- a/GEMstack/onboard/planning/pure_pursuit.py +++ b/GEMstack/onboard/planning/pure_pursuit.py @@ -83,7 +83,9 @@ def compute(self, state : VehicleState): L = transforms.vector2_dist((desired_x,desired_y),(curr_x,curr_y)) # find the curvature and the angle - alpha = desired_yaw - curr_yaw + alpha = transforms.normalize_angle(desired_yaw - curr_yaw) + if alpha > np.pi: + alpha -= np.pi*2 # ----------------- tuning this part as needed ----------------- k = self.crosstrack_gain @@ -144,7 +146,9 @@ def state_outputs(self): def update(self, vehicle : VehicleState, trajectory: Trajectory): self.pure_pursuit.set_path(trajectory) accel,wheel_angle = self.pure_pursuit.compute(vehicle) + #print("Desired wheel angle",wheel_angle) steering_angle = np.clip(front2steer(wheel_angle), self.pure_pursuit.steering_angle_range[0], self.pure_pursuit.steering_angle_range[1]) + #print("Desired steering angle",steering_angle) self.vehicle_interface.send_command(self.vehicle_interface.simple_command(accel,steering_angle, vehicle)) def healthy(self): From 276dca5e51ea95b67f7088e9e9a54aedb0dea0d5 Mon Sep 17 00:00:00 2001 From: krishauser Date: Wed, 31 Jan 2024 18:45:55 -0500 Subject: [PATCH 077/232] Added new queries --- GEMstack/state/trajectory.py | 35 +++++++++++++++++++++++++++++++++-- 1 file changed, 33 insertions(+), 2 deletions(-) diff --git a/GEMstack/state/trajectory.py b/GEMstack/state/trajectory.py index 62efa35c7..50b31a751 100644 --- a/GEMstack/state/trajectory.py +++ b/GEMstack/state/trajectory.py @@ -18,6 +18,10 @@ def to_frame(self, frame : ObjectFrameEnum, current_pose : None, start_pose_abs new_points = [convert_point(p,self.frame,frame,current_pose,start_pose_abs) for p in self.points] return replace(self,frame=frame,points=new_points) + def domain(self) -> Tuple[float,float]: + """Returns the parameter domain""" + return (0.0,len(self.points)-1) + def parameter_to_index(self, t : float) -> Tuple[int,float]: """Converts a path parameter to an (edge index, edge parameter) tuple.""" if len(self.points) < 2: @@ -159,6 +163,10 @@ class Trajectory(Path): """A timed, piecewise linear path.""" times : List[float] + def domain(self) -> Tuple[float,float]: + """Returns the time parameter domain""" + return (self.times[0],self.times[-1]) + def time_to_index(self, t : float) -> Tuple[int,float]: """Converts a time to an (edge index, edge parameter) tuple.""" if len(self.points) < 2: @@ -196,12 +204,35 @@ def eval(self, t : float) -> List[float]: return transforms.vector_madd(self.points[ind],transforms.vector_sub(self.points[ind+1],self.points[ind]),u) def eval_derivative(self, t : float) -> List[float]: - """Evaluates the derivative at a given time.""" + """Evaluates the derivative (velocity) at a given time.""" if len(self.points) < 2: return transforms.vector_mul(self.points[0],0.0) ind,u = self.time_to_index(t) return transforms.vector_mul(transforms.vector_sub(self.points[ind+1],self.points[ind]),1.0/(self.times[ind+1]-self.times[ind])) - + + def eval_tangent(self, t : float) -> List[float]: + """Evaluates the tangent of the curve at a given time. This is related + to the velocity but normalized; at cusp points the previous tangent (or + next tangent, if the point is at the start) is returned. """ + if len(self.points) < 2: + raise ValueError("Trajectory has no tangent: only 1 point") + ind,u = self.time_to_index(t) + d = transforms.vector_sub(self.points[ind+1],self.points[ind]) + l = transforms.vector_norm(d) + pos = (ind == 0) + while l == 0: + if ind == 0: + if not pos: + raise ValueError("Trajectory has no tangent: all points are coincident") + ind+=1 + else: + if pos: + raise ValueError("Trajectory has no tangent: all points are coincident") + ind-=1 + d = transforms.vector_sub(self.points[ind+1],self.points[ind]) + l = transforms.vector_norm(d) + return transforms.vector_mul(d,1.0/l) + def closest_point(self, x : List[float], edges = True) -> Tuple[float,float]: """Returns the closest point on the path to the given point. If edges=False, only computes the distances to the vertices, not the From e4c7325cdcf5b7ab43d052628d4c61ea376027b6 Mon Sep 17 00:00:00 2001 From: krishauser Date: Wed, 31 Jan 2024 18:46:18 -0500 Subject: [PATCH 078/232] Fixed typo in model order --- GEMstack/knowledge/vehicle/dynamics.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/GEMstack/knowledge/vehicle/dynamics.py b/GEMstack/knowledge/vehicle/dynamics.py index e5db54d49..8c19221c8 100644 --- a/GEMstack/knowledge/vehicle/dynamics.py +++ b/GEMstack/knowledge/vehicle/dynamics.py @@ -18,10 +18,10 @@ def acceleration_to_pedal_positions(acceleration : float, velocity : float, pitc Returns tuple (accelerator_pedal_position, brake_pedal_position, desired_gear) """ model = settings.get('vehicle.dynamics.acceleration_model','v1_hang') - if model == 'v1_hang': + if model == 'hang_v1': if gear != 1: print("WARNING can't handle gears other than 1 yet") - max_accel = settings.get('vehicle.dynamics.max_accelerator_acceleration') # m/s^2 + max_accel = settings.get('vehicle.dynamics.max_accelerator_acceleration')[1] # m/s^2 max_brake = settings.get('vehicle.dynamics.max_brake_deceleration') # m/s^2 dry_decel = settings.get('vehicle.dynamics.internal_dry_deceleration') # m/s^2 accel_active_range = settings.get('vehicle.dynamics.accelerator_active_range') # pedal position fraction @@ -38,7 +38,7 @@ def acceleration_to_pedal_positions(acceleration : float, velocity : float, pitc throttle_percent = 0 return (max(throttle_percent,0.0),max(brake_percent,0.0),1) - elif model == 'v1_kris': + elif model == 'kris_v1': brake_max = settings.get('vehicle.dynamics.max_brake_deceleration') reverse_accel_max = settings.get('vehicle.dynamics.max_accelerator_acceleration_reverse') accel_max = settings.get('vehicle.dynamics.max_accelerator_acceleration') From ced1d5cc591969641b3eabb0eaea30f0871dc79e Mon Sep 17 00:00:00 2001 From: gem Date: Mon, 5 Feb 2024 23:43:24 -0600 Subject: [PATCH 079/232] Better naming of sensors, added depth subscribing --- GEMstack/onboard/interface/gem.py | 2 +- GEMstack/onboard/interface/gem_hardware.py | 22 ++++++++++++++++++---- 2 files changed, 19 insertions(+), 5 deletions(-) diff --git a/GEMstack/onboard/interface/gem.py b/GEMstack/onboard/interface/gem.py index 0af1e64cd..65cf77902 100644 --- a/GEMstack/onboard/interface/gem.py +++ b/GEMstack/onboard/interface/gem.py @@ -109,7 +109,7 @@ def send_command(self, cmd : GEMVehicleCommand): def sensors(self) -> List[str]: """Returns all available sensors""" - return ['gnss','imu','top_lidar','top_stereo','front_radar'] + return ['gnss','imu','top_lidar','front_camera','front_depth','front_radar'] def subscribe_sensor(self, name : str, callback : Callable, type = None) -> None: """Subscribes to a sensor with a given callback. diff --git a/GEMstack/onboard/interface/gem_hardware.py b/GEMstack/onboard/interface/gem_hardware.py index 6e99814e1..fb01e5b47 100644 --- a/GEMstack/onboard/interface/gem_hardware.py +++ b/GEMstack/onboard/interface/gem_hardware.py @@ -42,7 +42,8 @@ def __init__(self): self.imu_sub = None self.front_radar_sub = None self.front_camera_sub = None - self.lidar_sub = None + self.front_depth_sub = None + self.top_lidar_sub = None self.stereo_sub = None self.faults = [] @@ -138,10 +139,10 @@ def subscribe_sensor(self, name, callback, type = None): if type is not None and type is not Inspva: raise ValueError("GEMHardwareInterface only supports Inspva for GNSS") self.gnss_sub = rospy.Subscriber("/novatel/inspva", Inspva, callback) - elif name == 'lidar': + elif name == 'top_lidar': if type is not None and type is not PointCloud2: - raise ValueError("GEMHardwareInterface only supports PointCloud2 for lidar") - self.lidar_sub = rospy.Subscriber("/lidar1/velodyne_points", PointCloud2, callback) + raise ValueError("GEMHardwareInterface only supports PointCloud2 for top lidar") + self.top_lidar_sub = rospy.Subscriber("/lidar1/velodyne_points", PointCloud2, callback) elif name == 'front_radar': if type is not None and type is not RadarTracks: raise ValueError("GEMHardwareInterface only supports RadarTracks for front radar") @@ -158,6 +159,19 @@ def callback_with_cv2(msg : Image): cv_image = self.bridge.imgmsg_to_cv2(msg, desired_encoding="bgr8") callback(cv_image) self.front_camera_sub = rospy.Subscriber("/zed2/zed_node/rgb/image_rect_color", Image, callback_with_cv2) + elif name == 'front_depth': + if type is not None and (type is not Image and type is not cv2.Mat): + raise ValueError("GEMHardwareInterface only supports Image or OpenCV for front depth") + if type is None or type is Image: + self.front_depth_sub = rospy.Subscriber("/zed2/zed_node/depth/depth_registered", Image, callback) + else: + self.bridge = CvBridge() + def callback_with_cv2(msg : Image): + #print("received image with size",msg.width,msg.height,"encoding",msg.encoding) + cv_image = self.bridge.imgmsg_to_cv2(msg, desired_encoding="passthrough") + callback(cv_image) + self.front_depth_sub = rospy.Subscriber("/zed2/zed_node/depth/depth_registered", Image, callback_with_cv2) + # PACMod enable callback function def pacmod_enable_callback(self, msg): From 91637b94db88757c1a159c6d8f5c866d0660c29b Mon Sep 17 00:00:00 2001 From: gem Date: Mon, 5 Feb 2024 23:46:09 -0600 Subject: [PATCH 080/232] Added image /lidar saving and viewing utilities --- .../offboard/calibration/capture_lidar_zed.py | 108 ++++++++++++++++++ .../calibration/klampt_lidar_zed_show.py | 100 ++++++++++++++++ 2 files changed, 208 insertions(+) create mode 100644 GEMstack/offboard/calibration/capture_lidar_zed.py create mode 100644 GEMstack/offboard/calibration/klampt_lidar_zed_show.py diff --git a/GEMstack/offboard/calibration/capture_lidar_zed.py b/GEMstack/offboard/calibration/capture_lidar_zed.py new file mode 100644 index 000000000..21814b793 --- /dev/null +++ b/GEMstack/offboard/calibration/capture_lidar_zed.py @@ -0,0 +1,108 @@ +# ROS Headers +import rospy +from sensor_msgs.msg import Image,PointCloud2 +import sensor_msgs.point_cloud2 as pc2 +import ctypes +import struct + +# OpenCV and cv2 bridge +import cv2 +from cv_bridge import CvBridge +import numpy as np +import os + +lidar_points = None +camera_image = None +depth_image = None +bridge = CvBridge() + +def lidar_callback(lidar : PointCloud2): + global lidar_points + lidar_points = lidar + +def camera_callback(img : Image): + global camera_image + camera_image = img + +def depth_callback(img : Image): + global depth_image + depth_image = img + +def pc2_to_numpy(pc2_msg, want_rgb = False): + gen = pc2.read_points(pc2_msg, skip_nans=True) + if want_rgb: + xyzpack = np.array(list(gen),dtype=np.float32) + if xyzpack.shape[1] != 4: + raise ValueError("PointCloud2 does not have points") + xyzrgb = np.empty((xyzpack.shape[0],6)) + xyzrgb[:,:3] = xyzpack[:,:3] + for i,x in enumerate(xyzpack): + rgb = x[3] + # cast float32 to int so that bitwise operations are possible + s = struct.pack('>f' ,rgb) + i = struct.unpack('>l',s)[0] + # you can get back the float value by the inverse operations + pack = ctypes.c_uint32(i).value + r = (pack & 0x00FF0000)>> 16 + g = (pack & 0x0000FF00)>> 8 + b = (pack & 0x000000FF) + #r,g,b values in the 0-255 range + xyzrgb[i,3:] = (r,g,b) + return xyzrgb + else: + return np.array(list(gen),dtype=np.float32)[:,:3] + +def save_scan(lidar_fn,color_fn,depth_fn): + print("Saving scan to",lidar_fn,color_fn,depth_fn) + pc = pc2_to_numpy(lidar_points,want_rgb=False) + np.savez(lidar_fn,pc) + cv2.imwrite(color_fn,bridge.imgmsg_to_cv2(camera_image)) + dimage = bridge.imgmsg_to_cv2(depth_image) + dimage_non_nan = dimage[np.isfinite(dimage)] + print("Depth range",np.min(dimage_non_nan),np.max(dimage_non_nan)) + dimage = np.nan_to_num(dimage,nan=0,posinf=0,neginf=0) + dimage = (dimage/4000*0xffff) + print("Depth pixel range",np.min(dimage),np.max(dimage)) + dimage = dimage.astype(np.uint16) + cv2.imwrite(depth_fn,dimage) + +def main(folder='data',start_index=1): + rospy.init_node("capture_lidar_zed",disable_signals=True) + lidar_sub = rospy.Subscriber("/lidar1/velodyne_points", PointCloud2, lidar_callback) + camera_sub = rospy.Subscriber("/zed2/zed_node/rgb/image_rect_color", Image, camera_callback) + depth_sub = rospy.Subscriber("/zed2/zed_node/depth/depth_registered", Image, depth_callback) + index = start_index + print("Press any key to:") + print(" store lidar point clouds as npz") + print(" store color images as png") + print(" store depth images (m scaled by 0xffff/4000) as 16-bit tif") + print("Press Escape or Ctrl+C to quit") + while True: + if camera_image: + cv2.imshow("result",bridge.imgmsg_to_cv2(camera_image)) + key = cv2.waitKey(30) + if key == -1: + #nothing + pass + elif key == 27: + #escape + break + else: + if lidar_points is None or camera_image is None or depth_image is None: + print("Missing some messages?") + else: + files = [os.path.join(folder,'lidar{}.npz'.format(index)), + os.path.join(folder,'color{}.png'.format(index)), + os.path.join(folder,'depth{}.tif'.format(index))] + save_scan(*files) + index += 1 + +if __name__ == '__main__': + import sys + folder = 'data' + start_index = 1 + if len(sys.argv) >= 2: + folder = sys.argv[1] + if len(sys.argv) >= 3: + start_index = int(sys.argv[2]) + main(folder,start_index) diff --git a/GEMstack/offboard/calibration/klampt_lidar_zed_show.py b/GEMstack/offboard/calibration/klampt_lidar_zed_show.py new file mode 100644 index 000000000..6ac51c48d --- /dev/null +++ b/GEMstack/offboard/calibration/klampt_lidar_zed_show.py @@ -0,0 +1,100 @@ +from klampt import vis +from klampt.math import so3,se3 +from klampt.vis.colorize import colorize +from klampt import PointCloud,Geometry3D +from klampt.io import numpy_convert +from klampt.model.sensing import image_to_points +import cv2 +import os +import numpy as np +import math +import time + +#uncalibrated values -- TODO: load these from a calibration file +zed_K = np.array([[550, 0.0, 640], + [0.0, 550, 360], + [0.0, 0.0, 1.0]]) +zed_intrinsics = [zed_K[0,0],zed_K[1,1],zed_K[0,2],zed_K[1,2]] +zed_w = 1280 +zed_h = 720 + + +def main(folder): + lidar_xform = se3.identity() + zed_xform = (so3.from_ndarray(np.array([[0,0,1],[-1,0,0],[0,-1,0]])),[0,0,0]) + lidar_pattern = os.path.join(folder,"lidar{}.npz") + color_pattern = os.path.join(folder,"color{}.png") + depth_pattern = os.path.join(folder,"depth{}.tif") + data = {} + def load_and_show_scan(idx): + arr_compressed = np.load(lidar_pattern.format(idx)) + arr = arr_compressed['arr_0'] + arr_compressed.close() + pc = numpy_convert.from_numpy(arr,'PointCloud') + pc = colorize(pc,'z','plasma') + data['lidar'] = Geometry3D(pc) + + color = cv2.imread(color_pattern.format(idx)) + depth = cv2.imread(depth_pattern.format(idx),cv2.IMREAD_UNCHANGED) + depth = depth.astype(np.float32) + print("depth range",np.min(depth),np.max(depth)) + zed_xfov = 2*np.arctan(zed_w/(2*zed_intrinsics[0])) + zed_yfov = 2*np.arctan(zed_h/(2*zed_intrinsics[1])) + print("estimated zed horizontal FOV",math.degrees(zed_xfov),"deg") + pc = image_to_points(depth,color,zed_xfov,zed_yfov,depth_scale=4000.0/0xffff, points_format='PointCloud') + + data['zed'] = Geometry3D(pc) + data['lidar'].setCurrentTransform(*lidar_xform) + data['zed'].setCurrentTransform(*zed_xform) + vis.add('lidar',data['lidar']) + vis.add('zed',data['zed']) + + data['index'] = 1 + def increment_index(): + data['index'] += 1 + try: + load_and_show_scan(data['index']) + except Exception: + data['index'] -= 1 + return + def decrement_index(): + data['index'] -= 1 + try: + load_and_show_scan(data['index']) + except Exception: + data['index'] += 1 + return + def print_xforms(): + print("lidar:") + print("rotation:",so3.ndarray(lidar_xform[0])) + print("position:",lidar_xform[1]) + print("zed:") + print("rotation:",so3.ndarray(zed_xform[0])) + print("position:",zed_xform[1]) + + + vis.addAction(increment_index,"Increment index",'=') + vis.addAction(decrement_index,"Decrement index",'-') + vis.addAction(print_xforms,'Print transforms','p') + load_and_show_scan(1) + vis.add('zed_xform',zed_xform) + vis.add('lidar_xform',lidar_xform) + vis.edit('zed_xform') + vis.edit('lidar_xform') + vis.show() + while vis.shown(): + lidar_xform = vis.getItemConfig('lidar_xform') + lidar_xform = lidar_xform[:9],lidar_xform[9:] + zed_xform = vis.getItemConfig('zed_xform') + zed_xform = zed_xform[:9],zed_xform[9:] + data['lidar'].setCurrentTransform(*lidar_xform) + data['zed'].setCurrentTransform(*zed_xform) + time.sleep(0.02) + vis.kill() + +if __name__ == '__main__': + import sys + folder = 'data' + if len(sys.argv) >= 2: + folder = sys.argv[1] + main(folder) From ee415386352963b9425517c9d26b69aeb9ad573d Mon Sep 17 00:00:00 2001 From: gem Date: Mon, 5 Feb 2024 23:50:42 -0600 Subject: [PATCH 081/232] Can now load calib config file --- GEMstack/offboard/calibration/klampt_lidar_zed_show.py | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/GEMstack/offboard/calibration/klampt_lidar_zed_show.py b/GEMstack/offboard/calibration/klampt_lidar_zed_show.py index 6ac51c48d..e3e7de4ce 100644 --- a/GEMstack/offboard/calibration/klampt_lidar_zed_show.py +++ b/GEMstack/offboard/calibration/klampt_lidar_zed_show.py @@ -97,4 +97,13 @@ def print_xforms(): folder = 'data' if len(sys.argv) >= 2: folder = sys.argv[1] + if len(sys.argv) >= 3: + calib = sys.argv[2] + import yaml + with open(calib,'r') as f: + config = yaml.load(f,yaml.SafeLoader) + zed_K = np.array(config['K']).reshape((3,3)) + zed_intrinsics = [zed_K[0,0],zed_K[1,1],zed_K[0,2],zed_K[1,2]] + zed_w = config['width'] + zed_height = config['height'] main(folder) From b2de34b24fdab117458f6abde6030f77f6061072 Mon Sep 17 00:00:00 2001 From: Kris Hauser Date: Tue, 6 Feb 2024 13:42:03 -0500 Subject: [PATCH 082/232] Added URDF --- GEMstack/knowledge/vehicle/model/gem.urdf | 1473 +++++++++++++++++ .../vehicle/model/meshes/base_link.STL | Bin 0 -> 387484 bytes .../vehicle/model/meshes/chair_link.STL | Bin 0 -> 181384 bytes .../vehicle/model/meshes/door_link.STL | Bin 0 -> 58784 bytes .../model/meshes/front_camera_link.STL | Bin 0 -> 15284 bytes .../front_left_emergency_button_link.STL | Bin 0 -> 38684 bytes .../meshes/front_left_head_light_link.STL | Bin 0 -> 61484 bytes .../meshes/front_left_turn_light_link.STL | Bin 0 -> 66884 bytes .../model/meshes/front_left_wheel_link.STL | Bin 0 -> 476284 bytes .../vehicle/model/meshes/front_rack_link.STL | Bin 0 -> 12684 bytes .../front_right_emergency_button_link.STL | Bin 0 -> 38684 bytes .../meshes/front_right_head_light_link.STL | Bin 0 -> 61484 bytes .../meshes/front_right_turn_light_link.STL | Bin 0 -> 66884 bytes .../model/meshes/front_right_wheel_link.STL | Bin 0 -> 476284 bytes .../vehicle/model/meshes/left_I_link.STL | Bin 0 -> 2284 bytes .../model/meshes/left_antenna_link.STL | Bin 0 -> 50684 bytes .../model/meshes/left_blue_outer_link.STL | Bin 0 -> 4884 bytes .../model/meshes/left_fixed_hinge_link.STL | Bin 0 -> 23484 bytes .../model/meshes/left_steering_hinge_link.STL | Bin 0 -> 26584 bytes .../rear_left_emergency_button_link.STL | Bin 0 -> 38684 bytes .../model/meshes/rear_left_light_link.STL | Bin 0 -> 8084 bytes .../meshes/rear_left_stop_light_link.STL | Bin 0 -> 45484 bytes .../model/meshes/rear_left_wheel_link.STL | Bin 0 -> 476284 bytes .../model/meshes/rear_light_bar_link.STL | Bin 0 -> 13484 bytes .../vehicle/model/meshes/rear_rack_link.STL | Bin 0 -> 12684 bytes .../rear_right_emergency_button_link.STL | Bin 0 -> 38684 bytes .../model/meshes/rear_right_light_link.STL | Bin 0 -> 8084 bytes .../meshes/rear_right_stop_light_link.STL | Bin 0 -> 45484 bytes .../model/meshes/rear_right_wheel_link.STL | Bin 0 -> 476284 bytes .../vehicle/model/meshes/right_I_link.STL | Bin 0 -> 2284 bytes .../model/meshes/right_antenna_link.STL | Bin 0 -> 50684 bytes .../model/meshes/right_blue_outer_link.STL | Bin 0 -> 4884 bytes .../model/meshes/right_fixed_hinge_link.STL | Bin 0 -> 23384 bytes .../meshes/right_steering_hinge_link.STL | Bin 0 -> 26484 bytes .../vehicle/model/meshes/top_rack_link.STL | Bin 0 -> 5484 bytes 35 files changed, 1473 insertions(+) create mode 100644 GEMstack/knowledge/vehicle/model/gem.urdf create mode 100755 GEMstack/knowledge/vehicle/model/meshes/base_link.STL create mode 100755 GEMstack/knowledge/vehicle/model/meshes/chair_link.STL create mode 100755 GEMstack/knowledge/vehicle/model/meshes/door_link.STL create mode 100755 GEMstack/knowledge/vehicle/model/meshes/front_camera_link.STL create mode 100755 GEMstack/knowledge/vehicle/model/meshes/front_left_emergency_button_link.STL create mode 100755 GEMstack/knowledge/vehicle/model/meshes/front_left_head_light_link.STL create mode 100755 GEMstack/knowledge/vehicle/model/meshes/front_left_turn_light_link.STL create mode 100755 GEMstack/knowledge/vehicle/model/meshes/front_left_wheel_link.STL create mode 100755 GEMstack/knowledge/vehicle/model/meshes/front_rack_link.STL create mode 100755 GEMstack/knowledge/vehicle/model/meshes/front_right_emergency_button_link.STL create mode 100755 GEMstack/knowledge/vehicle/model/meshes/front_right_head_light_link.STL create mode 100755 GEMstack/knowledge/vehicle/model/meshes/front_right_turn_light_link.STL create mode 100755 GEMstack/knowledge/vehicle/model/meshes/front_right_wheel_link.STL create mode 100755 GEMstack/knowledge/vehicle/model/meshes/left_I_link.STL create mode 100755 GEMstack/knowledge/vehicle/model/meshes/left_antenna_link.STL create mode 100755 GEMstack/knowledge/vehicle/model/meshes/left_blue_outer_link.STL create mode 100755 GEMstack/knowledge/vehicle/model/meshes/left_fixed_hinge_link.STL create mode 100755 GEMstack/knowledge/vehicle/model/meshes/left_steering_hinge_link.STL create mode 100755 GEMstack/knowledge/vehicle/model/meshes/rear_left_emergency_button_link.STL create mode 100755 GEMstack/knowledge/vehicle/model/meshes/rear_left_light_link.STL create mode 100755 GEMstack/knowledge/vehicle/model/meshes/rear_left_stop_light_link.STL create mode 100755 GEMstack/knowledge/vehicle/model/meshes/rear_left_wheel_link.STL create mode 100755 GEMstack/knowledge/vehicle/model/meshes/rear_light_bar_link.STL create mode 100755 GEMstack/knowledge/vehicle/model/meshes/rear_rack_link.STL create mode 100755 GEMstack/knowledge/vehicle/model/meshes/rear_right_emergency_button_link.STL create mode 100755 GEMstack/knowledge/vehicle/model/meshes/rear_right_light_link.STL create mode 100755 GEMstack/knowledge/vehicle/model/meshes/rear_right_stop_light_link.STL create mode 100755 GEMstack/knowledge/vehicle/model/meshes/rear_right_wheel_link.STL create mode 100755 GEMstack/knowledge/vehicle/model/meshes/right_I_link.STL create mode 100755 GEMstack/knowledge/vehicle/model/meshes/right_antenna_link.STL create mode 100755 GEMstack/knowledge/vehicle/model/meshes/right_blue_outer_link.STL create mode 100755 GEMstack/knowledge/vehicle/model/meshes/right_fixed_hinge_link.STL create mode 100755 GEMstack/knowledge/vehicle/model/meshes/right_steering_hinge_link.STL create mode 100755 GEMstack/knowledge/vehicle/model/meshes/top_rack_link.STL diff --git a/GEMstack/knowledge/vehicle/model/gem.urdf b/GEMstack/knowledge/vehicle/model/gem.urdf new file mode 100644 index 000000000..1989feab6 --- /dev/null +++ b/GEMstack/knowledge/vehicle/model/gem.urdf @@ -0,0 +1,1473 @@ + + + + + + + + Gazebo/Red + + + Gazebo/Red + + + 10000 + 100000000 + 1000000 + 1e8 + 0.001 + 100.0 + Gazebo/Blue + + + 10000 + 100000000 + 1000000 + 1e8 + 0.001 + 100.0 + Gazebo/Blue + + + 0.9 + 1000000 + 0.005 + 1e8 + Gazebo/Black + + + 0.9 + 1000000 + 0.005 + 1e8 + Gazebo/Black + + + 0.9 + 1000000 + 0.005 + 1e8 + Gazebo/Black + + + 0.9 + 1000000 + 0.005 + 1e8 + Gazebo/Black + + + + + Gazebo/White + + + Gazebo/Grey + + + Gazebo/White + + + + Gazebo/Black + + + Gazebo/Black + + + Gazebo/Black + + + Gazebo/Red + + + Gazebo/Red + + + Gazebo/Red + + + Gazebo/Red + + + Gazebo/Red + + + Gazebo/Red + + + Gazebo/Red + + + Gazebo/White + + + Gazebo/White + + + Gazebo/Orange + + + Gazebo/Orange + + + Gazebo/Orange + + + Gazebo/Orange + + + Gazebo/Blue + + + Gazebo/Blue + + + Gazebo/Grey + + + Gazebo/Grey + + + Gazebo/Red + + + Gazebo/Red + + + Gazebo/Red + + + Gazebo/Red + + + Gazebo/Orange + + + Gazebo/Orange + + + Gazebo/Red + + + + true + gazebo_ros_control/DefaultRobotHWSim + + + + + + 30.0 + + + 1.5707963 + + 640 + 480 + + R8G8B8 + + + 0.02 + 300 + + + gaussian + 0.0 + 0.007 + + + + true + 0.0 + front_single_camera + image_raw + camera_info + front_single_camera_link + 0.07 + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + + + + + + + true + IMU_link + IMU_link + imu + imu_service + 0.0 + 50.0 + + + + + + 20.0 + GPS_link + GPS_link + /gps/fix + /gps/fix_velocity + 40.09302494 + -88.23575484 + 90 + 220 + 0 0 0 + 0.001 0.001 0.001 + 0.05 0.05 0.05 + 0.001 0.001 0.001 + 0.5 0.5 0.5 + + + + + + + + + + true + 20 + 0 0 0 0 0 0 + false + + + + 2 + 1 + -28 + 28 + + + 2 + 1 + -28 + 28 + + + + 0.3 + 5 + 0.01 + + + + 0.005 + /front_sonar_distance + front_sonar_link + + + + + + + true + 20 + 0 0 0 0 0 0 + false + + + + 2 + 1 + -28 + 28 + + + 2 + 1 + -28 + 28 + + + + 0.3 + 5 + 0.01 + + + + 0.005 + /rear_sonar_distance + rear_sonar_link + + + + + + + 30.0 + + 1.5707963 + + 800 + 600 + R8G8B8 + + + 0.02 + 300 + + + gaussian + 0.0 + 0.007 + + + + 0 -0.07 0 0 0 0 + 1.5707963 + + 800 + 600 + R8G8B8 + + + 0.02 + 300 + + + gaussian + 0.0 + 0.007 + + + + true + 0.0 + stereo/camera + image_raw + camera_info + stereo_camera_link + + + 0.5 + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + hardware_interface/EffortJointInterface + 1 + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + hardware_interface/EffortJointInterface + 1 + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + hardware_interface/EffortJointInterface + 1 + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + hardware_interface/EffortJointInterface + 1 + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + hardware_interface/EffortJointInterface + 1 + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + hardware_interface/EffortJointInterface + 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/GEMstack/knowledge/vehicle/model/meshes/base_link.STL b/GEMstack/knowledge/vehicle/model/meshes/base_link.STL new file mode 100755 index 0000000000000000000000000000000000000000..9c17ee41709e6565273fbeed9dccedd37e883612 GIT binary patch literal 387484 zcmb@PS5y^C7p+?*DF~uq1VKSS5p#xKg;@j?B^Uq`B8s9Y0tQ6PSy3@!4j7KvV`f*G zG3ST@b5=ymiCev2{@G`Yd!MdPjxpy)?Y+Bu)v8sY73Kf$zcy7BB{elsD9Wpi*`D)h zkgYwvzcrO^)v{ofdNiUlW7BBW%Id6R&-#=#Xa@P(JG1{gfvzRYj%u7rr?}DP{~=I8 z;{BDn)N9g0$~sf^|3RRuOL;r;w9BMvVgGFd6(o*6u1h_>ucXJf{@Vr;=vwV-N3n&g zDPYWh+du`0$+PN{b@9#gnEv})A%U)?ZyHej^lfw~rrLkLc_jHz*6sK7Psf_fJD1Va z;Rd?dtv0jW$;kcG2MTRi`#%IKNIb6HhI}@2npsr$|3RQ@OVif$xoti*toL666(nYw zbR>~$pxPfB$u`O#wow~eq_Tdc3)O^hZz{ZQpojKN7`iHqXl(pcZOhk}#A>SwK0O|c zXA#4Sd{99G+f$Sp?L7^>8;)b0u9e|PpsV+qy0l?KHf^b;{Z=u(Mj6hR8^b(`b>*la zfxnxgWaX_jRLf0dJ04Eg5$G~q)X8{lD!25MZR{MM#C_VDvwlN@M5lJX#=F7I!-@6V z*wT2Ni-Me4K~6Nie7uY9wQ-WfE=hPxB1#g6uT(b@nW5F#y}}ws*N)#VOn;ZGKRbty zI}^@xPYn}`6Z#pS&YB|~*nwGOe2U)fc4W=p^fCT_o_iJ9Mx_0GKD)BDVRQFHfeI2c zSCH}fa69TKi7ol*-0R{%^<_mpfiA0GeT>A}##$S1ZRYSz&xh0bSwjUXNZ>D`D33#D zaEttnG=c`|2y|W9(9igboL%W4+Zg6CjxXEwlP;GI6R04e|8*B!8o?JtT8UPHfdV5A zMz}{CYtZ-DG~$O{WE*YLqIef;Cs9AbSD=E#({ini@$uPI?WxUhO5=NveB{wvyX%PY ztE(HY%`eYt|B0fFy3gc|JTkd|;UL|oLc*ndHRBcRo2T6+c+K&9pbMj&{+gqL#8J;2|9r%ZjWje0 z94o@wdh`B6x>BKCe_EJUhix|PLZ8<4rFJtMm3Iis|=f5GqI{KWSkk7VOm8 zu)qAlXYYnoasTaE6$y0VZz%7QE0cXrXN(sG%lfFOAd#8hlp24FqM-T>weJz`nB6~j zya+CBs=FTO!e3h7NFJp z=9eAGhB{?%B+!L@m!fQneQ&T@Gl-4jXLNlO5)VCMX+Zt~+VH))Y-4!5HIFLSo8{+y z)Dh@96H?1aB<<2ZmHGMR+~QCh)}*4NKm`eX+)arMCb{|KrauKiZFCG7Yip9ql{@KZ;i>+Oj_Mxw)d?RtdnChlz6 zQk?RsCQv~Fdm=@-|GEqJy^WP?o)ZalVfLXYb!w;ah66wHe?@m)UV?<3y|1xPocdSG!m%I3zlAQ$Q53~( zPa8wCz!cFa$W8a_zBo717^$0l^<)_H^|1sMB=($0Hb$S+(OP7{c!dPIEW39%#ze=7 zTD*F?+*4gyZ=7(bWJ{ z0$sMr0Y>7_>^73vvoD=0R$i|@+CP$^g2cSjQ^>mQIvU$ZYvY0CJla324xM~4Tt}eG z{E)wq==4te9)p`tr?+2r(ZI+73>73Eubxakul}K$t+eZLxy&Tm;C7!pHbm+Obp12f z&q)0Gp9f7WY54SZE zKXbMFs{Y1C6cO8j-y?AOG(Ud&b{!-mr)MX?3`p~_3#c0x- zI_&whCRDtP3AO)TQ+{*y&rs%`vWWLy-jm<`?MDs~g>>w>I~#D(kKQ;HQvdhv?4fsi z+T;9*n*3Ws5&;{=v!x{lXSW^~q}tVXqUf|$bn$5kw#>l= zbmbLvrh_^8YSVlzPaM)XgvGTsV^zzx=iRpiQ0(Sk>Xn9G?A*0LT2bzYI>fBJ6iOKmUsknRFD|x*NLvI{HES3>m`YLq0#Jovy;>;a)6FN*LdEU zrXT*OPAk+tRjj-!;Z<6)u&Iv>H@bJER&^Ef>gUDEn)p*tP?1^?;>9YpZ%^^P6q++v z`&70|?b)okomhimyLAM*TAyl9-xn665gFR2T9f}Tg^eA?I-CA!zW-%gT06KnZ9VA4 zp8VU6+PfF0##_8t=%iN0`)ZcGc3<^cmqzo~C$phXN~%bp%lCFmI$%1biipt75PSpP2Rb>051Z&maiT3VWL+Nj| zJ8`3jAFID)t0CdJ13PlE68Yw=rg}Tg*yx-pw0G@lYS`F}-Eyf)n+|Uz<+Q0JtmcQX zUMtraDyyY+3KIU!9OzcYYN}kuOcM8Y+cTH(mkj^dbYj1(D^iIktErErIlFeCB0bDq zO>aM#G2v604vpAI8Rq7a*!TW7JsWb#(3Q4SYY9enptG{DYNg(a@>1I9_X`?aC@FunQye`E7Ly5*c4BlE zzT6zbwtIb3&viIR;XY2(Pn||Lmz%O~FRId=dei9LT~oGmT~%6WHI-V{*S@*Muz_sL z=Hk>k>H?vHg!AC4)YWYoWtG(k+k=s;i>)nHPxzuE&{gHG1N|;BjSijHh?|=enCJ3x ze8ZZV+^t^_Eu8h4I?a~P$4MDg>wKZacrVtkP6+M2{f$bO(Q>$ReM8uZ!s22?^=Mvc zUm*3pSwN@D*I~D6cc!#UpJ>cIFE)KfFs{-H7UVY^VjtUZ`GCGrJ zR7h`5YfqHPOLx|~kB|5}x;CF(Hh>bIex$A;b(s6n0Q%XWfa26TZ2zbrTKl4aR)%P8 zv{-4!e%A^VmHo@<2y~sZ_oMvJ`DFf&_C$G2JV+0J#0iH9s|=&>w5N|-^Xbm{I_$}= z4wQT|pOW|2VQVJ&Qw6h+^m4b>M*lyPsD^E_=ojvzBhaxebM~d^)qhgC#h(qS13d(B(@Wtji5X*H^r!jaS?xF}mk1YIrV2jM+U; zMFojlb}cEs?FU-+Qj1rATskpR3wyEUzzf6mksat_YysVH^49|i?q>?vT8r784kYsi->B-w zTH2@DlF0haS!BqpIE$l##Fy}n6gcrS%{`~}QQ=E(QMcs2Z1cUo+(LAs=TnPO+L(rH zdzBFK&M!gEUz@Tcjb!!9OQ9TJZN%bR&YZ1$AIL_Xp2bl?;x6k!UwjnGI@(kcd~PLn zzH%#e?B+xrfvy_Yy3pX>MXI&2iW8OT&TM`*Vu`<}b5xLcH8q%W#{W|HDcYxM8rzgD zpYFmO=gi}%AhBpp2*r5*P}e@y`t$fo{>&}bjGa5QlB0rz)#3Ij((=1%_aD zx!5;)y>_9FK-ZZcAryV#oBHXd)<(d-cott&i<&%N!spM7r0{aDRfnHVS*`hDWd1c@ z4PDZJAuY$8w_{k}%FF3Q!BUP25@Qp?s8{MobxEeyM)OI%*{!V8lvZ^5pwa70lH5}T9Q zwx|v|0$ut~HE>+K8Zdqwv!7p#qk_cZ`yJ@Qui}*dMQbC$zXtbclEQ}A4ly8sF8oF0 zH@B_KiM{8r>%i`i`a3g}qf#K>|OmqBw605~EG5*~6S# zgao=4&i6GwQQkMSHq0mY7WDlgH6PN4P(ecfJp!x~g!S0^)W~A0jzCu+`5K?JNv_(+ zOKG)>LW*}H%TuxJkX1$Uyg!w8=9)8{wa%zyPrmb~60dI|i7gjxY5DO$n(a7>p@PJC zgS9b}2@ckXFNJc{IVg^p*=QYsuBsi%P~}Ub=+Byxl88J%hbN}R)1s+E87fG$=~9Zk zRwPrXt44J4y}|$4I)e_U_tFvQ>ObF#+}}k}vZbXY8ko6>N~I&{bAAhk3K9#;ThQe> zeQAB!Qj!=p%~vcg=TG%tIqL{?%`Iz5(Y-oR=29z3I4v9?R^)9`DKVE&L8ARDIR^UE zkv8~jgCN9&-GU1vY;8&n`kWwN9z>9R#o6`3%H6367TDkrpreg z$-KR^Bu-sQ76V45@#gbq9YF$J%d%{#>^K)XSj<)up1FNRgHLyPnV*3i6(j;K+tH8m z&UEdSjU?RFK=F5ON#SocRY#z!sHO4SkJ`z~`-kT`7bM5%qO z=|w_0N#weI<)dG=5g!)Z))DA(I_*l~7ZnO^T~QKlrcvCqW0=OYhpwQ9%NKX*r^A)RR@L{V%Uu z=CqDLSIA6n>T&J6`uLl6Uw!{kkJ((c73Qm-a#WDOJ4R6~z00wGZn+AjPBDQ5x{f`p zNB$*C(Chu$^Ks|>7Mj+hofsfW3RIB5J6}E@Q(6#Tykc^!eS{f%oFpYx)kva*eL zKaU$M*UH|rTUmh$68HowO7`Yd{x!Uf*fpqvjzCw%XO-xvtZii3Xz{B5fMQ~_XG0NN zub4mu35-OtSNl{=c%82zUa~J733OGbGF1JPj1E>>Z?HSFi)h#EGasC>o}+>UMpQ+4 z-9B2xFE;R%5h*$XT`Ap4(y?Rh$@7=i4?e#-TI3Fh>1?sXfaNFsZ?aR zbAFYI1iDPGnNr%#UNn+x{rT(fBSfp$^?kOuuO(EFz#dN4849Dt`r#AQ>boB52y|^Z zX-dQHCQ_1v)<%C>aw$KiGL8OQgQ0>1_SAAc!*Ew&_*R8d{d{!e>yE+rnPZ5y0drh1=VTv z(G-RX5|}wD%5*~mHps6LYjvaq#~LD5Jh4(JXMX+!u{MuNvv&R6I4Vf!BV4J-D3)HB zD>IeaIs#plEZR_42Zd~lw0QM!(Mb0Dp%1iFS- zBl`KZ7+DY2)<&6)ieUrlM)8-=4s%qHz^EiM0M?CJ+5N-EmCn@>=sLEkF}1I1P9}e~ zcvYuSZFcvnj8%oj1S&d07vWAmD9yHft0dNREvF+e+CA{~G-fi+-?Vtu#(E|FuG376 zoa`h}K?38LqLiNIOqbU+6H$k2>j-q&nK&EcmB`exzBZZP4Y@)Uy-U;-s33t+Nm0h! zoyA*jt1FJlIYK1R^`x~u)pV&x;ci+kYAA0mmcFeje#hAfRFJ?prYP0!x{2fnb8)1; zrH(+?*8nSO;oX+L?bn|3<8h(l?X#=A%Mb%c1qqBwigKdyK+$vlDn9M+d>w(V${uF4 z+B<@>{j_JW+LW=P)v+f0M`%w2Do9`)Q17{?T)^SEg7qkjW+)P=`70$uJkOvp233RO2~ZS?%8idV6h z)!SQZGE|VjI3`Ei16{<4sJ$vX(^^NMEBApp9h{v`H*B@v>hhn9+(~dX%WV)tMMvl& z+_Z`_cv`Uv>gG{NIs&6ztAnL!Zlz3$Ptw|WUST}*zTcrmOrvco&RXHzlzs-wYvg$L z=6o+7@0^J$DoE&Ou%`A&WqtcS@ix2s+<*kSR=szmqVAcrvR-ldspfwf$2#<`W*Fl7 zMK?Er^AR}9Axrw5Q`z6x_1RszzciqN#FL3tDQs01UEiU#vH5N?n{j{K;VT|#90_!- zzT-sxyLQv*%i8=$udqlK8kVTK#uaf?kSOl&Kxb3;kmqczjfFXWY-3QN8nCFcKmuL9 zaaHNeYy*|*sm;m+^S9xT&7)$L|qY0Hr1lyI!8jzHJz z;tmw!eU_e<)9&51_Xkn5#|5(N9VJjfV%8~pntlH)1%A@zam?*6s_j?(q%X%Jbp*OP zBvhi>6>iW%Yc2QLROrbc7Fn_8fn5YDNCX6zGZJGaYQ(||8N7OgBdc}LTSuVFW@`m1 z8uNg*cxhwj^+o0)sX-OCb3z4y3KD56%97>s`}EaHi`3H{tBE<+sBio!hj2ut$D^_>{Oz&N2I{s30+Pc|~fx`6X3bqm7+!i)8VmZf8>E-$4Rhx2spB z`2O$dSfJLQ4;VL6wAf{0xc+o8p@Kx*QYQ*de?tYIG-Bw*A!1EuSN)r+^XAL^=Yng53KBh@c+j`-ceMYvMpyM)V4~soSs33uNzMRcyI#S%U{+<2v@KPOtu3@R=DDToE^6I43$i@sFElR#o z=~I4jLInwYf)(Z8{z;;)m`QiShxj0Yu2K_h$f78hEbD6{;osBxiqQ7=$#QeQ{bPwV{)n73x-{cTyJaqBII z1mfbw+6h6eXSUfe*jVwUGej&l=i!x&6>e%%LPFo~2OIkGLd5WIs{L{9`On1(K`nn* z;_=Gg=QJ8GZ*xqr@x$}ZYEzOE?&*qHYRy^UZS4*#@6+Id6l#rNp?K;gL{B>$^)+uZDA*kg(9KWw9$%(P^!FI40r!4uO zVvh&EQ(ScCVZ-c^v>lX?*!0*&b64HxYwR*PJ0B#d#q*Td=o~Wf@vAe z@3MbL9JKU*inDc%eeuD=M$_IUK`mYj$w=MASnJG};Jco?CB|d510!`pP^<1Yf0LDr z)J;lAU_2Iqkvbu$g%MQ*M(QRdBrqO}z(}1C)WV1=0wZ;k5)$b-$4H$J)Z!JBJkMLN zZ*hAVk^jB=)Dq9#@|X>;DNfMSd7%T&l~v zsI}Z@7Ya|f&%Jm{W`hzEX*)d6l_j5-_8Iq0F3w%xtm5kPE)G2!XGmG^lJGp&V}{z$ z_RQEbWX+V@{=3Ir|Gm-3iCRL!Gh@$?HKXlAP>XF!ZBWazVb6*+2Ttlcr38;f!t-1| zOEjZZ@3I{vsCC&=BgLnlJGVIROV4ElC7um?6xAHKPw&zO3D1%}Th<&nvq6GdJhP2P z`R;$i{A#`b?$+WNGpjLEy1%&g4}p07 zxUVDxwZ63f)L`TKbDe#5++Ozw;*Yx>)S`rh=ef3_F;lwl{^A#b*!GTt6M|X`+;@Jk z@#s1qm+q!d+!~0VO+2hc2?@`0Z9`+Gbcd&15r}=;MW7b{@;3M@$LC zY4aV^qJ)I!xwfIvRJz-(dukwFIP%zppq798POAvdjD6E;F4y!7*fU|x<#aWS<@`)M zaQ97K*!|nZq=z5S-$|sBF~YR(c|D6W!gFblmYTD*J(u>JS~F#NO`0|+A>p~S=hT`5 zi|$2G%X8_m>xu*=BzpH132L#YQ?J;&p4<9~qgm{LEhll)8&?e9_{VdKQ~x@5pO#aL zy&k*@Bel=D=eZu$H1AD3@vPOOsOGAbjV_T&#?G30q)d8uT!LDjgL<6T%rmn=2?_OX zu+hDCyEaHr%fFMWy-Tp=zu0J=^0DH=V#&@5NiU>*#Ve77*9RWkHM`B)L4sPI^Lo_Q zj5Z@E@v6n6vu3Wz{n*z3`ilHa#-@W$FQ~ zyEoLnM;bFa+ppjD+_pZ?_bvOQ@b_&_Tu1GgaP{+n*kH<+Ta=K{I3MWhdA{kI)t4MI zj@>gMsO8`F%%IWO{ng3A#&4EArp0s1bN;)hjt|6%pYXVQ`p`vzIN+kAT9lB`h#I`A zM(VrvxGoT%d*<+jpcZ?i(U`cvj6huS=R=deBB3Wkuu(m69^d=^K%Apz6puwM_FI@U zw0u51zw*r3BeiC+e(Hzg`rj27pIRP&pT6aMZ-&mfW*J?A5)%Gh&(2bUHas)-c%^x7 zVlO3lToRrcd(77yIP;1GwLAy)lR-1jc4~uH1FsU#jQupw>^37PAwk=z4HDFP?3mli z$F`eVys}engAx*HJACGR0)1ZAT5d|Y?9FEuZ+!fW(4+M^AYGm7n(!Ut`_66fZ{HLC zed(`PX|H(BMaACp-L2lG4N5$hj&GdkRmz4A!cXk2s2fq^*o>4y@6TI`WVV@HjizCUK|bAQrTBs|{QhDTQI zLaPzl#QF=)NC;}N->R9h3C$Nfo*Bn?#eQcM#$D&_zO~EazUYiHatI!??MxMsSO^Ngy-1t{dM(@tZRb=weDDXLi<{M-M0D7{_>1oQR4Y} zd>5W&FO#4R5}vQeci}o8y$EX6XVWvml%Rw}dhOB%32O1mPi(Y2Gxivz`C?el_*(K= z^UT;|qUOW;->}i5guMXUeF$oKW*lb7(}y#H5)x=fAA(xwg^Xa!zqRy)_Qr3VSDb&^ zqr+@d+Hy)rcxD{mq*w3s>nqVwneJUgEzgYO+u@9$#4}@$wVL-1=oN|UcYeJ5vhLai zA9-3|C-4l?D{A@gV|Oh^QOBd|(K4*8<5*i@JXY^wq;6Bf^MTPv1fB*7K`o4lA~3?W zDItN;PQ;XZt5Njy!|zQ9YGDKyG3TY#Nd3%{549;FQD2oB+eP4MkPy_ub4A2~YgA91 zy}$b}$5QJjPIxO6pBdq;pnq!~Bm#4Wj^~>3t!$V@dc4wXtiUrkBPj8_vnD*F^mwIN zVIP88c*11_B_uXo=ELnDAAM1=*ZR(CWIISui#?JOUK98krTKf(+WR!)TvId7)i!Xv zmNqD1FZg$ymu3WQcuf%Bo+tKF8$2$F5zWY6(2VTPd7TYNuSigfXEvF)H$5AUE5)YX z2#0qI{@TKS_f?`k)3}3GQ6eF+=E!a3lZu_+Hf=&5f?D)8wLu99y;}}%STrBbY*38rp7H)cy^A*!9ZE=GwJqX;`1a$usRtwkwXkj%ffap+ z5)xS5i&%Bf+x7qTnbhTnCIq$c#zMNo@y)~m&m7*NgaqC>i1^>Jw;u^XEzj_M-{>hM zLSI(|uN=dpBqw}FRfK28Zik+rZN23jjqi|kZpW&TOn!FN(G{1TQarlA^ZGl9R5C`G z_Bq!xHzR06??p%Bn^bvCnl>mQq4%Pr@olu|UIevXerKL?XuS)Ie=fITMo^;n)ZzVw zzX74`-Zn_+4Rm;yp&4yvgU6y4-jQYmB_w!eQ?E!+%fFLz9@bGl=bP@d`zCiQKJdO@ zJ`m3N*jdZYN0-pCiuzdoU0;2AiyI<;{uUv4H7-Fdc^i(Tc|=A~Lc;U)_-4Bgk!tm7 z2erIDh;Pz$++GAFB=mN8IKD&9ydpuZZC|}&_*_K+-h9qGjqBR&_7x?1pFAAjG!N(% z3D2wJ8|dmD?AoAL)Jm@f#G^cxbk8%-KO$T55HYU~B_uQwg>$YMt%zbQu9gtgLWE8P zVs{-%NN7Y2HZ-FZQO5_jx#Qr3pcW#HA`pY@P(s2pW8VeUwTn1sLQo44Q`tZ)wL=LB zJ>i0lYVL!0Z9-7Xzw234m;rP=wrghQ*-}?R!ZYLe?p0nPw%w$Jgr4WYEC1V@pjMc> zS8s$f8ZFpuJ-=2H+()DEG{gaEk_0_^RFK|5>wu2H9{yjD?Awe5@ z7aqPZ@mC|HQyY|!ICYtkVzRyiICt;oGOtKbD{VQd6tIp@=}dKJtSbXMRBrN>sI2mK zQrCdBo7yCtsqTz*<)rr^sD-TmjBuv9GuD-R+;*nAGuD-p-bRjcnR-PnXR146U3utz z2p)@sGu553uAKDDD-zUVFQi^MQ{B0*$|^5OJ5$}cugXu)+Cd2k|Be~!89^J)RCn&H z^3W4|saHHM31_N1_fi51A0Zmnd;71 zS5A7L^Fb|MJ!#A7uQS!1`>H(j0lgyOOm*kJDknW_Is1xQ?2#mozT+xi&P!DduhKQU zoX@H1T$xwM)$h;-30D|%KBww=$*W!jwOohH`JAfrl@X{XQMzWEvv5_BtwjBaaR`qY zx~~($HQSu~s#*E!*Tujh>&%&~s$@2xS0r5P%$cmJYL?lcSJZN?GiS1@!dXU8;#z0UWK|`z0lgyOT4&B= zRaLXh2EC$|Yn?fhRTa)Mf)dv{b0(`QnGNU_3D-JvCabENWi}G8pygU;u6d>kXBk0> zYn{2~nJSqL=oJaqI&;l4RW-|O&?{=W)|qRbslr)CP~uu=u6d?PW&?Uf!nMv^^GsFE zG8^=YTCR2GnrEu>l@YFW=9*`!WLCP?nQNY@Mp+-PNYI{Zow??jszGHocwE;ybImhV zGV5c5$0gxfXRdj++`X=#-0NvTEgxxYmO+Aj;#y~}d8SHc1A0Zmwa#4gOjXVLcttJO zI&;l4RXEECN?hyAHP2MZY(TF_xYn6#o~f!?W`n&;E!R48%`;Uv%Lqzb>&!LJRLN{W zuSmGonQNY@s##`(UQx@n&Rp|M70xn(64yF&%`;Up8_+8fu65>`XR2zJ*`Qa{O0Ra* z@oF7ERue2)bD&z6W__p?)}jQJzXI)5YPDiP<*$T5O|Ld>CzZbvuSlTsm%KvFvxJ}) zYN3fh?Y0)@SDaI!rki>f_2F8SkVtKy+FL?U3w7LN1J&MIl#pPXsya)41)%yLZP!+E zzbm&k{Pqmczg=g^>p@jlQp;VLsU|2v9qBeITK6HSe3SCFcM({`OD zuOL-LNm^q&C8SHyqZ*fq|62hYSF{g1|=k1XUS{MS<{@;z`i0ut==tnoh7e1 zRTC*`t?Mj#&8g~2nT=G!{%K72(?I#@x=QF3ZMe>o*PN=Nl-NrN_7w@&S@N1w6_qlt zNKnglmb~Uv9ixnJoh7e1Rb{B{I!j)2s*2KpUXgH}C9gSEQ7N-Quc+m^UiI~sww(UD z&XU)hs-iTYS0r3#$!ktkRO;guwb&!UtMKN|cdf3g`c0$n+VI>nwR)t9nIAYh7o_Yc*9@%50>Pu`7|@rZz}W%XOB#=2Ug1%myVS*uK;T z+u=G(UZ1OqQqrcB;8jAxb(Xw7S4E}FD-zUloh7f&Rb43~C~=)7uToV-X+WnwSdswzqYdPTx@mb^+; zMWxIJy`q-uEP0ix8bcZ3I!j)qs)|zSI!j)qsynwSds!BAO4IbBZmb^+; z6{S8lcw7>$v*cB(Dk^0*NTgcXyrg@TuuoiP$*WXVQ5w)I60WlpDs%7sQXj9VnwSdswzqYdPTx@ zmb^+;MWxIJy`q-uEP0ix>Pi_wiR&zRm8vRA1A0Zmb(XwJRYj%D2EC$IdbPXGk~CdQ zsD-_$lQoX(EP3vu8bcc4TxZFI>J_yp;Tp%k$7V~evt&ZmhZ4edmaL_^LT%b^G+bxN zgsKlEUXf@tR=mozst?JlvHwm=2x@t6T(8?yyQpeM;M@+*?)D^1hv=;saK9~#>(7@CysB%%G{X^N@&l&lQ)pvGe{ebZ^p{piM`Y-9+!mUo3S!? z<`oHQIldVyb7zF(n_hD&x>q{B87p%S=oJaaH)Cb)%m%%p7O$SP<@DF_%~+XxK(9zR zz8NcX_wkBa?2+o;^F63{$xX*M-T)K`qBO zObi=M046oe4oLx6A7*+Y0g8K)5}eUvcK-7P}p8XVpjUEB6^CBvKo0u?hD8 z32M3Zw&Avg2yY-1?`%;*f^Dkeo3^3YSI5y2AIoc6|8{Hr+wo1W2Nl&UQi2i^b%vv( z54{O$Ilk!?tD=4x;rM2VJ573G*zrxTAQioI9r`ePRbH}ogm%QIZU-d^p(u@4lZs0! zzqS|QC}^!k4^x5?5{_?r&8bLc)(#TX>fLh3H{-rCNoyV7jQh%D?VyCc;NN~4%-&bD z;rM3US0=HSww%W$;rM3US0?j{1hpLBjQh%DgyWlDb1J$w?D%HfS7t!3NI1UfHK!t( znGJeHEnaVF%jvJ8?-#(iZ*QyY|!ptrpVYB|0c_m#=KqJ#w7m)c-E9N&!l$|P+{3HnaL z@y)oeOxAJ|)N*_??kkfKlsLW__mvsYD-w=x#(iZn8}y1=j&H_&Wio;i$2a4?G6Q-= z!tu?xuS{lxUQx^OO|McF)yxP=9N&!l$_(fg3CB0%zA~8&dPObAH{-rC89|BTn{i*6 z0lgyO_-5Q!CbL1WsO9)(+*c+eC~?)yG)N*{&t5iibGlCMwH@!+#^zvssQtzvTgyWlDr7Dt{+2FCLm0scUK9sB1=eMwxoHrrp7j#b>QiFI@{B`6`GOwI89 zuJ;)3O;F26^7+skii}W3Ug=e;_mWknW*PH2n|P0+vxxU_&id?XDLb?Dn$!CV_a-PI zp-j#2ZLRkhPHm8&7JDHjlxrE{oZcmvw6ZosoYVUarvxP={5!sZ%m~_0c4mlkdS7AE zsSQd3w&Vof+bs-dC8mQ-Tr_%G4}lK4+iv zK`mZAsSWz8?9347^uEHhof4FgP^M;xb9#^A-UPMSBT4kNrOd*x9#rJ5PP1jXxr<>PrPy9Z;Jsm?e9o}?RrE5%Jw4{@?j47y zB_x!08P=SNOZFkC#rE}X2MJ|rhPAUInVAh9i(2gU)CT)R*_mMlsp#c^=YxbYHA9?J zk<30`QA=5yA=R{Yh83iumwj4J8zhve8CH;rWcKljTFTlCD@a8(GlCLjXNDD| zqL%}DMM9aHVFjs3W@dx!pq8>W!wOPS&5WQ#*_mMlsp#c^UXf6yW>`Tgl9}0{SJYD0 zW>`Tgs+kd#C_6K(AQinF&?^$k)C?;~MKUuR^om;P)$VAeXEM%iv1H} zgfl1+acd${**tzMqA0>KR1?mJqzxW7B@iF%P(lJxK-q9a)Ha+CNrGDRHi_4EIKT4m zdgg>Uu6h?S;SMDv*b7yB(_T5Fl?1gAyOj;cH%+KL9ZE=~?Qne4gra^;$27f))0#H? zc02sr@y(deslFmX3BLGkBD<;&K`qBOV?Jk2D83o<>za;l#(Yj`J+g{D)VmI~oL*5v z!tqV7CKZ>=Y>=Q9Jxpy-Lc;OQn9rHnAVIC(EmyAPaLngSTC1$h;h4{v*+?bqpGQ{l z(_r?#q77wd4##}X#9rER_7w?bY7WPI&de(k)KY%raLnh-2*)?Q=2UdAsqD<*n9n(& zS0o(YjQO0I4SGc_<#Tqgx3uN-SJ|1vF`siluSh6Ub2#R6_VJ2Z?2+JAxX*pp>beT? zent9x*M{G|Yn9a)zGzj{ud>l4C?VnB_5GjPn50bTn9rHCRymlXF`qNDkxIs{M0%Ur zAVDolS zy%tqeGb1QbcIIfz=N!;063WyZjrp9J4SGc_Wo?eee9nxZMA@06F`siluSh6Ub2R32 zW;W;*wUo6v8uK|bf)ZtCj>de>0lgxjOwG}l&zaevSJZNRGv;$vPv`FFLy6;?F`rXf zW1~dxdys_Vn=zj=v%zCg%kj;a&zTXFIKCP4IS2HLgyWkrpEI*Tuc+ntX3Xcz2*)>L zK4*w;#(d5`UXh?Z$2Vg>XJ*53)B3o|&b&S5bM~>p=YU?3aC|f7b7nT!SJZNRGv;$<1SO7d z#(d5Jy&~cGX3XczY|txeIldY5IWvM1$2Vg>=YU?3aC|f7b7nT^6}8f<-O);~aTN9I zaFycU^?V1piyGm^{yVADXxzApwG?@4DmpsqHHRW{{#|EIia;J@VuQy`3FJX`C?SDt zN7-;h)Sf9$m=LMfn72t@s=eyY?)(|8m$G$H}p8NMF>p8V!!?xG8UFp{ZC9$sp5!>Y0 zaOM>WYUOPj^NJD@`W<>u zk(BQ)_DT0q`0YMB;l0hn@4a3;RnhS3zv>K9LLx@SOZP@^f?7Dza8IKCA|V_X^kBp= z+83^K+o{?S_x34W!5req zMPfo;U-Mt6zD%!Zy+9`qS$3(dLyl+vg{_eXrBWQ!i_0{2) z`%I=bC?R1j6B&EcI3v#TWTX%QqT5mu>X^(K{PkVKr91}%?;J-vct?6|Ur zztaYfMJ@GuAZDM*P(nie76?64W2RcR z?~ks8gs$W8_i^u!EDsphlh(IUpeO8uK%C6tiRZVbVOcV$TX ziUhS{WGjr|DM1Mdc@}I`yLs>`(YPCY_ZY76G5q#e%l4%ZmYmq)gs`ZJhe9ryuDQ$V9F(yfgP$AZy2x_U<1L3D$+73!csNVwNXJc=IS~{D7&{{1cC?Uc3OsNfB z;oTPM?&|*boX36Tr(Q~QZRo1*{+1`b2}(%l$`3ZQy31^kpccJNz0ye5w7(uL>)#$N zG}?u~d#p(b{UuoUc&PCz{Pt+7=VSQo=VVGyLPBF@AUtOFCaBfhD@sVnv(OHYtf>tW z)T(=7_U8xBGkcUhlG>nzgvQ{|a;=K8Gf0A3?6=egB_uR62sX63%WROKmY(gQul)Q? zZBRl&GlM{AP2Go}mW~|=&m&SBl#t-LNeN0wXl4*>Xmy{Ra}w0*ea>r%?}_@iuMFMa z!G`X*%myVSG%pQ=)=_;3YH4;J2;KV`K?w=XuLmHgrSUcpe(I&Yt8q0*{Cv{dApCZ0 zO6%S5d-muOB_te^^cZu%AFs{gQ6#8^zh}`U9M`d;+QR~LMo>bcw+;3W?1hM^+cA4z zu@_0eUe>!Ls8wGvo*|^?gOc$GKjV87HEk`w*L6FjeN{?OLc;HL|NjKFYT7e|)W&#P zey;Z>D5-y&KrduAYAsu*7J5A+C?SEf*@vJO?#+y#gaod)J_NNe#$*H~Brr^{e(B#lweBEq}jp%%ktN!`aFD z3cB>Zvd(kX_taq@Thgfw64Y|mvc8Tky#s4X@VL&a)_3TocW@=05|of|MzOwDFTEFR zZ-QFATkfo0eK%ctZ&v37>#OV1ySdVKZyO|>kE}1gOYa`ro1j+jzEZ8?Lf=i7-ka4q z!TRdD^lq+$c}2qc$ok^D^zN~}y`mO-Bqf}$t1qHU@2=_$UwuPedY{(bUXh@db9eQ1 zbm?7JQyV<4^N#gpcj+BtNv8xQB%JfCugXjBP}`fJ7JEGI`3fLtT0Y zSK97PP|JC|`ck^|uB$1*<2nafUwN0_F_v^nP(s3a&iazP^lr7i32OB|AI|XAH`Jx~ zV|7ljzPc{Gvny@)wn4%<$ok5=^zN~}32OE3E9bfDOXAYIk~$|?UtO2p-*hmqNH_;s zUwN0_J+`-3)MAg!PAEI8v=`3s)i>0o_huc;D-x=WT{mP%gdmsWWl)t#j#pQ+sgwDu+_A>oW-eY0J9FWA&864c_E zO$le*>YL`$d!;&eS6@e$-f5LbN(o9xI6qilV3*$IwKqX6_F+n}-$M@i@{>#N7);wK zK?w=xo$Jf~(mSp8CaC3XUwuzqdY{&mpu`!)`ewWI{;#y15|of|*0R0}FTM9{Z-QDp zPt`2Rvn9`(JkRkA$+H;OBvLMFsp>-oXR@;szS?ub^^lZhTB^>Eyz)$pHfn-eY+p)H zLc-OClmS|*u25!!1hrhp+*D6x}XsNnF z*%@TZ=@kiAG*XsnsX9iP4HDGy-|KNK?JKrW``9#Lkn{m!9!tLBX2nxKS)s+)%~*t%EIpf)Z8#4kM>`JLZv6 zf)WzW>h~zBZ2ZyQ1hx2nE+r^YW$vcOUGGG!y53EXyWYn*B`8tt@TSLI@0H9Wr357; zRI9w{ao2k@_a><2BYE7_dDB}?om9CXJ0tM^lZ2{&hjG`t9rq@vrP|?P z-1T0`DM5*9k~cl>dJpEoydvTH03LUh9iQ3Yv8bim;Z2Xb-YYrviW1c%Z+hJI9?U#a zN>D;V_0XFhcfJ2}Z-QF9#zL*hFz&{>oOKMsRW`d(0B37?WN@}vmD%RIHrD0rN=V=i z)>xwIl)*-<%h@HIq2=Q`r;P8;s;o2Hh;=!;UXgH)oN1|DZQbhYIsf9ZsD;0)ubiQ0 z?O2yH9Lr-A+TkjqwYMUir)ENZ<+_|*35nDOS{`!VVlTQbXWb^(9>R46I)f~n|?d!U9{t z+d=Qz-J75m&r?dcnu6aBhCQ(_nb7pxLGPkX+bKbb>dQB~Fr*6_I zK?w;}&2RecpsGq_Hb_vb_xVs=`0#en`(UfWe0V$P9kqF+-d>SV75ngZ(7Sf`CaBfB zuT&j9ydCsz(5kZ@-VUk`!GK|cF?D_rxBouSlpS zeRwsKqmz5~|rA-VSZwI}@HII}Ml#o!h`S5noyKDC* zsKq`^3HJNLhdf!R21u#O9vjhiN>D;V72m_#LGN(go1m8J#fP_ps;7_AKngn&+py@wRoO%m2UL?uu3hKJF3Ij_J0>zxOv&T7nU#V{nI?+4uTPP z68n8^sQK$}UsP^2+0~6{g9Nqwch4Uk`%VdZ<=@xMd#1m*FLqh~nqp}G$>oIo&&>!* z7Fp-^;=PBalrvVITJT7{ZIIaf8^0`$yyxt4j;9<2U^{p$YOQtXtYY3N=arw>{;G_i zN%@aO&L3z>&*A3_ui4%5SsCkIq`wjoo5tCkCQH$rM(eSwz7fAQF$1C^0fBPKx z_no)hR!rP$YI%Emg07EV1hv>BDM1N|&%Jm{vF)7~mdky1q09yeYR%m1s^Zmi&MW7> zWR_Y^uT0ce2I-0SPcH6W;H>hS7dYdP1SKT?z53MRV-HU$U*F>PjG*;Xml-K0KX-0< z?%vO3XOK2{ToUg*c}cOWuB#1oeWhNJpjPTt`R;$)K7s4~cef7D8qelYzbnJpTzf57 zdpmggKLYXgMtgTCA%SmIMf~F0KLq0Std4qYjz)vaW`)JnBt%+I^F|cmHpWd6n>UGasE(7P(p&ekhYuzwZ8uRB8A7q zH(y*ivyn>1`s%{1?iuz-z4^WiX9Um37Q0Ly_7h;sWBpCZ7@c}W35jiAy<+&>Kk6%s z=jP6Akf7FVUWJj`SIHM1Tcq@8*?QJ39P{Mn1C}m5QvY?%RVy1^B9)90>gm#BzSr-e z9pe(z()llwYqv{Kk`uPkz1q73+wt-{^OQsDU0D8exfPQ(rCzbMB(}QZo>4yyzW?=j z2D>&$P-~4{CXagD-87s{-5*_ol9MmreAG{Xnd_$aV{flWOn!FN(G{1TQa-xC^VMD3 zwLz~^E#9>ke)CcFMWgYTsRwlK-f(K@_s;g~yQ)U_tlhWlkHX)#IdL87PPqE{Kx{DO z%NQxn~Yf2x_rM8jXny%m~CKe?BznD-!)4bBMXpgwE#He4NDLibqPcaDx(Y`V;c+dn?~qH?eG@Af*X?JLoL zpPi^BBsBYOdu;ctxi>+r-d<5lGw!yZC1Gxj>o~Q+W0BD8yY#s0`EYN7S|f8kT)yzD zv&%c@^_Mm5T}m_?EplK?w=X*GrGuo+DyP|A+Ns8d2LEa==m3Djd~*f{=hN8#`=q& zkr34KZ(ltX@#K&93dB+~UupBY;#EVvjT$JMMN+AZG1zf6`YZG~Naqo|!iqU-|Q)fmnaR83{ox_FI@4 z>)x&AS(+J#ao005XRZ2ParL$9cYeJ5^6h7p3qJC+-V|w;)Fmh(;orW4tJ-ZOXhXBT zw#Qx1$tzo!Hx zBqnU9S)jY!_p_y?Q zMLi!*Y;-6gfj0FasD<;C5tQVFuVc@LQm@#KJ64|1zE%UpT8^UezMtCzPqriE2}sEgtr^=N^W zw|e)qv3CG1N=(-T-VKNtj_&{tc;@hgpcdBZB39k=_Tbgkmmk`qgalUlBJd6%A*h9S z03z^CrbP(}ym=9UcQOen-I^3QyY|!V2|`BsHK^4cqilea7v_- zv2!q6Uxk&IR}~Wv+LNnvx_zpSqiUhT8dgF@W8}&~A)W6Q1 z5tL~DJRILN59k#M&8vsw8|dmD?4A#LMXmJAA|BDWh;t?c zwT>E#rOF0ksVz!KXao;7s(A_GwFyBj{~jCL5k+qMTY~r=H^lto8``XT5(z!GgLOZ@ z{gpsX_-l^%=2q?KMNo?#rUWG<{LM#v_nO%tL9N~`_g5S7eY@v7-8P+Z-{j(4MfI;f z&sCt<4oXP)_t;E^1a0^`kNCblv6tH5aYi@ev zEq@ac-_RzWXlC4uZ-iyTF^QU>g!Xg=Hhs0Lm-`UZ@^4>>vlH~{g>~j=?z;E|IrEAHwfwC_d^?;Gl=!QS_!f9TuSguT;Wfnx`le{11J2EC&?{>B z?_<~1FN-}oJ|8b$^p@XDbbFD#`@-Ko68`?nDL2c;k^5CK$Te1bsYwY5J!8We^vtu- zIP&e~M4>ta;I7_4Px?)}S>a9KRZ&E@+<883v8FZs@>n(=_;^M{H z2|=xAw%IV)Sn(yVQWu-^@XE#tH#I3Cq31@h;gx`9`oB3c5cmA&;)I}s|0&LX z@H^!fA9PLwZO|+Ku08SB74dDY?2w>@M15{NckE42Ynkt^(>&$1sb#U#ni)X}34f0f z-|uDwB_w+H6$xtjdyM#gH?zTB^w$;fefxmtgM`1}i0|98^FdFj)zhmMT3g_Jgx?+$ zJs(QWM+@h?n04(s%^&=AYI)WvYZg3GN>D<=UvPMA_w2SeK`pi~C8*^uM*J-Cytg+& z2?>8)5#J#Xr#47X%U@T-cgPt*$&@AkQ|zI;=%PCh8|IOE+aTd@Gd#|F4&0ldmTh>X zuI_V;)Q+o#JJs_LjM@dpW1SC-)CobY`pkMJn2gkIN=RTl7J-pEA*h8BRRl)rHYFr5 z9*e+8oeKTUIp*GOt{>pq98gfwN^*d!VH4-t8da>IBY~RULxN29HH8|2&ma7xEN`Yz;WCSIyPT*`=)gBnIuSmE$fwN^*hahV? zTSzTeCvdi`Y7%4wC9Y23Y+2PF7|<&cu1?@=S=AxPY|txe@fu4q?_0=(ZzJ=*L`J@B zAiKXs2?_u9-K=T_B9N<}5XjFD`)&DdK0efYy=snTnDr@FKk64fQ~a5)y1vQYobKzu#RhWW}mNUZ`(Zp97wo{)Eqg&zdXZIrmj{@N@=I@uWiu zkIU<=H$g2|#B;W+>cnL>ToKP1vZ{9%D&jf!Rh8_r`-5JQpbb~VbKb40zGXHx-gLfZ zeOy<>bB3(y-Sx4-J|yp(37hUsdmJK(AawuO?g( z&$+Lveb>h;YW40bSHyGft7^4{ig?a_RlU0by>bn`ns7xt=f0};T_3Ng#U4qoD_6vG z?yKtEg^GC2eN`p9K3*iwE?I zge&5?GM;MR_3?^YOU<|>TSmAdo-5<2x?8A-=gN4heb>h;*UhW7ToKQe@l@}w z55en-ge&5?GM;MRWnPh>7SC+jyRL}m%6O{07AoSoGM?()4d|6?=+%TP;<+-OYTxzo zidyW$)GPM8E8;o#RrT%$^ooQl;<+-OYTxzoidwFS=gN4hgO?GMxFVh_3P#(tQ9R#Km5}h;vnBs_Ehqn7>vzq_T>YsgC^20V zuI1zvtEx8jA*khAPF|&|f>TCN;#y8#XU>|o+JIh>a4jdVIaS9fv%z+xT4TGpq%Btu zba!oWEhn#1Rd=WDT25Yzs)AEygA&(r@+wu8nxr*$q~112xR#SwsjAwP+2FBKt)EZ# z$fw+DT_rq&Y^`fKd6lY4O#^yG!nK^dN>$aSK3-AFwVb?4RRyPvpv1MDyh>H2rUAVo z;aW~!rK)OEW`li2E!T4LDpeJnGJ+DdPMJ--qRb?h= zy24S*m4I;9hWM%PTGw*&{ir%d_OSckNxplpvP4ye+T61`-F4daq711fQeuP0O$k?j zGNGDCElNnZ5|nML@{x}2>Q5$~yXM4%NVUeit!g=$h%N7qI2^lVZ*;8XuH|IH?VyAN zd!f-#I|>tS2MKDqmQ&J>K)4;0kkA3Uy&mqtu&#~cZuhM5Y`T_{YdWcdlln?`ZI_^g zgvPOOEp$ifaS3XcB)YOOIu}HX18 zC8M@$IeC?;N=*Z{oP=vRd0nfjO_^70IkkA6(w2u>PFmNh%23<2oV-d^rKSPBBH>z2 zUe~H>Qy;IW#U4q$axEvXYgOB+?OIM=f2sykAFoKT7hKE9>sr+k%Dm!nUCYVqT2*T5 zV}r*f;aW~!*Q#n$W`hK^*z0M_UCYVqTGe(6wVb@JRSl*-UXh?Z*K+c@R`rTB;&Lo; zji~y#uI1!)ttvJ3vBBe#a4jdVYgM(WPs^#*`+T^Tlh?JXWK_DAlUJ##)a0i{cixq@ zgAx+1<>Ym(sy1aUCqb>=edStCUe~GuQ0ZDuUZtv1(|}%)a4jdVYgM(Wk5|-UkIdfk zdUoepPF~llQqzE5k#H?1uWMDcsgGCGaxEuUd{>R3jBqU{uWMD8sB|qSuUJ*JsgGCG zaxEvXYgMVK55Y4?!nK@2#rM5m%Df^$EuPu5cU{ZL>sr+eDqYLTt5j8L8qg~euI1!) zt*SQl@rqjP!_+JGyK6alU8_n>1A0ZmwVb@JRn?|GUQx@noV>181*eRl#I>Bfu2rR` z0lgyOT25Zqs%leagJ+OhJWt^rKvSBIce>_s+jBL)$9D`hR(ubU()#`W>_jag;TUSH z_%5&XzCE!~6V%cwJglAlZ%R-?!ZFlX@x2d0Eyqw}#rHmhW2mv>dx)WWm8!^TMmV}! zOB_Ru72o}4Vt{s#a11q8e9vs~Sk&_0>-TeMU$KRbp~i~u1A0ZmG1OS`y^mMaatt+A ze9s6<97By2-v{)Hgkz|&;(KO;eMK$DP-DgSjG)9Z)L8L-K(9zRh8iorXEx{+wRnw% zh+@n4pdzG>D2D6D_o9FMe)Mm}4a09mPBmw6w9R36FG+p~hXtk~7F& zug2S6gj??RIEET`8B_1l1|>W$ueaU=wH!l@yNqQv97Bz}jI|v@^_o+$Pk)zz5sqGw zpq68(ahI{o29N6)YTRY4j}0D|gkz|2m$A$S32OCjxnrntm$48-^_o)=(rjd4%W1<= z*P3t)HSRLj$17^}?kmSo<1S+%hUzt^BBTR)<)~{-IEET`8PnC?s~yy0kEDcSsBxFE z5JUBvQ?buJUXftGIffc{8OywKY_>kGW2kYLu|76W3%;f9Yc+~jP7tQP-Mq3^ndD*2gPq_3kUjP~$FRA%+@v85__mM_p^eG1R!rSRb#b#U4qo z68COBS91(C?lLx@S0o%mjk}EX@rqiGp~hXtGQu&`xXW0Gp~hXt`gr9?YpvxNYTRY4 z55en-gkz|2m$A$%64c_EO?%fd)VRx7h@r+^#s>7tQP-Mq3^ndD*2gPqu@6(P*zb;^ zdd;Z_>4095a11r>GSlrWnAZpcekFzH$uJ+TP~}{)X|Y9=qVJ2**%OI5tcPT2608 zpyljE?*>%&^f1~a!ZB3a2s;Cf^-n^uP02mzeaY&vHhjAh+Yw@@aeo~37sjiWqpP(9 z?Fe7H#F4rWfzd9+P~-kM8R6(^Eg|6;YTO?uBOF7G`{Rr{h8p+B8Ra#dwu4%Zp?Y1b z2x%XJ$0FevYTO@ZG_^s3T5MBFP(s2n)VM!RW`hK^diRxMsBwRsQO8idN>zk(z?PG6 z3^neLlX=CKQ;X**ZMkEpaetgq$56dWRfKdvuShtC8u!QP;}x~oBdJ%8p~n4jMjb=- z`ctvbK3kCWLTK`r)r+H%KGy{=V+bks3a zuRj(0?Bf*)+H(xm>srMLGp~4D$57+`IDKsJxFj4yjr-$dHb_vb_xW%P)$3YC5NA4u z>Q$;Dq%(P>w67>3;TWpdwThPZ@rqi#`^qs?uWJ=~o9P&;SE-7S4(JsL$56elRkU^MtD>cS`ifePp?Y1b2x%XJEhM3xZ^F7((b7J>OD&$+wB?SWdR?nn-On6D z^(s{n(gD39;TWpdwThPZ@rqjP!_+JGyJM(vf1KOdBPl@%3CB>qu2r=3XT1q(Ifm+W ztszlI^ zzCZNlKOvMq8ou~d?6VI+Ev&+e)CMIalyMrq7xw$cQ|$o z)vHwRm7Ut4L|LXGmg+sR>1|3-LP8m*A(ra>v3nEL@{!{Exr|^7m1SDSywoOb_qIVo z8K-5;OYPHF)Kd0o8S_#zf)Zt!hFGfi#2(Bm63RFYu~hGm-MbysQub+xrFyUIl%Pae zrXiNc% zUJ;InnsAmT3B(Eu+D;;hiB}{LQPep{gf}6mg&3;{$58E+^K3oJ*k6w&9B~l46@i$r zcLA^C%L$R%KukCxsD)^+Y#=7wp@an6lzh+7QeJ9Ub1J4<@Eq{m^d~%``m8DYG^{KY zIn^1&7bz`DcwAm@y$Nb5J2R|O6A3 z29K*O)37pCgtU(h9+!kNPQ#j0(bCKY32OCjxw0@rEL9Q2!ZB2@ITaxt&?^$kI1Ot~ zMN9j5MXla_rM%P-OI38Qa17OJPDMxu^ooQsPD3nJ(b7I%QHwp2URTO84Y5>3NDIeM zz2;QxvyWFKcy5#j8Dgo5;bmU&xXLmOu~bD!``F-dNhsqq#8MS4&1{fJw9xBm%avss z)|`rv7LK8M&8gUDAFoKzo^mb2np1JY%qt#OS*9VDst9Qx8$2!vWt@gss-mTt4HDGq zeLj?h8P=SNAQs9p4QozCNC)(agfdRUnp4rzK3-9)cV8)cF|0Wic`KA<8rGbOkPhe- z31ysyHK(GbeY~O;dnCO|+`IK$OR zdl{je%CP2CJg`v4X;^bATH41eYAMS!tT`1S?L*Kj63RFYYfeQ=Gp|Tci)S`%x$+&u znp3g5LRqF^&8Z0KfL@VM#%Wk{Dq7mdD{8S1Q?JfP;cs+$hy&t z3^@&n#B@zKh8puy`w-M}3^nGZW&|aUp~k$_#CC75NK9AmQp`)uY_Nr?)+4KU2B`JB zdY3J4G{z*#861vzsZGaFy-HQ&G_yg8vP_3#UaGXlj?~)*31yrP$Gp_c29K3${a_W3 ze6zQMt#u4F=A{nk6$xdW4#&LIK3-AFG1Qosnh}&J%XB#Ar4Hy731yrP$Gp_c2K$Oy z%03;Ad8rveiLy+GV_xcjUXf77>2Spc=A~v{k)Rgal=dzq zB$RPF8uL;!8ziXJyRVdmIU4g)n~tG+U8@M`fGsDXjMLGWmzsISmQ#!8DQ&qjBu5=f zRdlcE7^>H`ijWTI6$xdWj>f#yK3-9aJ(7B*EYs1Lm)dj;)$3ZtKKpn@g1w+T$kCXW znt8?JD$8^<=B4(r!Q+xp#_4FxOU-PMpcZ>QZMkEpF)y`n4Atve#XkFZMS}JmLydW< z)l8;)5AwLmG98V1seNqlxFnQuIvVp*`?Q=|z0ZeZs4*|Ka11r(rONkSV+kcB97BzH zsaeZOP^))eIffeZQVYjWV_xcjUXgGNHRh%E@rqjPk@PBYJL=h;W2iANbwIC3DC6|@ zn3vkeD{4808uL;!!ZFmCms&W68uL>7cttJ8P-9+dAA)C)gkz{NFE#Uu1hsf()82Iq zHRh!jj-kf9)B(LB;TUSnOYP$owb+NLSL}CXncg1rQU~;kgkz{NFSU{=jhJIR$FWIu*FU-cUrJf#NUN~|8C|}GyV6* zr{>Z*pL6@K2V!KCuXQLHhbSuI*^jOfh#U7kAt53iw634;6T!xISG->~wqEIdfjI0h z-{?>>4pCIZJ~td8PO-1aCniLsqgJEgcFeiPJknk4f>(!4Z1(39!rgTdQB=fXyHvYpzqaI22@&a_wa9v(2{ukV?Jb>&*U!8z z*qHJ7;T=lGA&QFl>P2@1;wS$-I3Xe(v`&0@+hF6fKYUX*R{F&+0&)Bu2X`nLhbSVk z?Qa5c*X{c!M5Ke(il?0tY^>OxB^$p!@cBUOf613Sl#D|Z6>bLD+xci%D)Gk07eAtD{L zp4{M>U}MJI7s;-9kdSL`^{kEzVo-0jWg~#AQ0!>^hleMafqTK z-j2J(v?jC@BGN%?@q^wCHn!euST@dl;?Q8@w`iL|`V95SV3*ViqN0rLoyki;{5&&zww* z&Bzi0v!zkY21Q`j*P>(`!ZSb-m{}$SW__cW)oScLd~EjGqGTMxGg%RsAtwZ8uO;T% zA}|YYQ8EtU8Mz3|^b-QJ@Di&G5m-&MC>e+F%0dKIED3?tL>X5vrB+2EuqtX%Lc&ib zJ-hrw5`mRhLQo5z#{*ajfrbM7Kl0C*}p}}I7Cqq?|ka-fw*<*-U$)u zp!L9K&j~hm{O(_5V~sf)Ew_A)n|EtbG7eEx#M#SC2*j6O*e)R=9kia_@tR;`g;|fv z#(mpY)svQ$NBuhbSsyp9`9S_|2@< z6C%<<>(*y}8*FSi|A=h-^rN2dj4+@fS0qNs@VkN$ihc3Jxa2@&a_wcp(@1RDn) zccyIYJ8`E#eCq!BTa=7L6cw?}zIz4Y$va+cl8C>9)`k22C)oJVYhRR&_s_jwAa*RD zX;Lx{QB*`Z??Hk1{>u*}M5Ke(_fB{-*f{7G&-y-oZ$&JB#Jx>Q#vzJ|*zb(Pf{mlD zxg{YY9kh1Ye2&uh`I;|Gl#LfYdqf~MT5Ecfl5vQlBBp-t*g&)wKP4d|9kh0uZ|-2@ zge^Lng&+Ucae>(7fiE>F8HXq;;_WF_hV)(QE|d_F4qC&1e}AxX%<>J{xbWvyZuqo+ z-(OHN4pCIZV-Hms(tA9%QbI&JXw^sZ2%_`xuZr0HvCD@k8HXrlBSyy~tX2PAUTxB7 zz^jsy+6D-FC;}}Xm#`LkT?Bf!O-XG7gnL>9&R{~IcQ?V+Gu&v@S4n5_Q`(e_L->jj zfh#c~aFq<>E)apMy-mqDgs*%NxT6vRSNkyTW)Zk++mwt$_zo6)*A8Qh5mApm zPu%fpo04$|k3=Fc!gWYs^clwJDxw}mzqs}XI+Tn4khCd zelm!dD?V{{*>Jstz|&wDPdgEKs&yzChwu|l1fHA;fv4Iqp4uYtbnZ|x4&f)Y2+RNy z0#D~*%sxb5meHYP9KtgW5tzv&1ZEk-m_>=eY^g)ZID}_TA}}LM2+Wp-F&h+tSzm{e zaR|=rW(v=~`=#jjFzSZ1T@Vyl;nZb~c&#?Mas^3y+eV zFkKPfx#5J)b8GG}Y5iiTNy5Ktt?QrJH1zJFlUiD_Z2s%7cfP&mdXql%`>mUl&p zcyW_sI}4w?#H3e#b6P@}uC;!(W;58h_}W8d<2u#lJnhlDhDMh>yGcn-n68LV%{Zd7 z#<`uL2k*QhAxzg=!?$c4Y<%@n$Kdu^@~fS7KfmatiR)h5q$DRySHzB|9n?8s%UvgJ zeBFHsVY=3O+ zU3VM`Hh%HMv$9csW~a{Hx4ks9)5-IhN~wEW*U zZ&8vHrYquW?=IchbMdbaow?~Y31Pa{(wPf3)Z?;IY_ddWqx(KKw9y=&Yf+LDrYqw0 zU(egQV|4CGm+rQ6LYS_#bd?7ix;ka!jCbE_pT6(Zq3_(XTZ@vMFkKOkKm51$PcHuA z&{sP9B!uZ&>-uYM2sSR5e?8ea=9=f)XY4d%=-!9E+@d5WOjpGGi~PF1==WY2x@Gu) zgfLxeX+#J%bSKNkRlFkKOo?mMCV@7=c>y6*#DO9<1omPY7cLnEtf zd}!9!+Fw~~<)L-A`&x^VoG=}U-*4Ui>&NyV(o-QJOxId^(hU3B)f2+)D2CcE{eGcI zdh)a=$qCaHv1IGs^4ZU|CQZEmn+ajM*80(LD+L?>H(?9en113#<@AjvPWtNBC$=cb z3DXtv`K{+K*E@Qbp)3B75~gddyN){l2Dd{q1ljof*54kzWzUs|e)Rf@ElNn-BEob< zEcCmfVwtDT9D3n_l%SS893AVc1%EeEeDLW#hW1$FM7O*v$%(ob^tSZPxtm)Y^2wne zKlF`+FkNd+{pKs-NV|OSQ)56!D-Hn>xYEK*5^xoqW z!gQ^rvstZjW2-CIJX__n8Mm55DuJHOhmt3j2 zLyMA}FkKPXF8pTmx5cMNX8d@MgfLxeUH9i-1smJ1=3TAcd*7U`;d36k^8VAm)S@IO zOjpDcdSkc3H4BW)r8jsa{JYk=Q*#Bkqk0-Vw8Fxz^?$JcmEWDULyMA}FkKNJynmV2 zcTb)B%Ap@^oe-vLEj{7dwoyGf7x>#st^aIs%axaWW^+F|yONwRT@m}dvqtNi4{tH@ zwP{5{n69<9`_g>jNIyPxQT5f~AN@${qtCuH^7!{QX;G3BrYqtn-&?1A_I|Jh+5 zO9<1omc4O1d=#zjZrr%F*UR%v|NZJ~wk<~wx5ThNC?xlmd~8qp(nO% zJo?S;T3+OxIez%56hWY}xQ!;o!!#BbqyS zhTN6pgz1V{;wSsIe*2MgMt=5zXA{D7t#!gW8-ye6xWT2eapRQzTW_7Y!t})!{%wr1aKKYf{1?@S2OwU$Q&w?j{C*;sagLtB%-_Oa<7*>lvZiLN9kOjpEj zesx6ahl|ZKeXdDYB!uZ&>jpi?ZNsCU)*pX4y0zL4uZ`Su*ms(g&pcw)!nT1VXb z^2iDw+CL#o*IK7+v01RO-jo$(IbpgYh88=a_2LWnjVwB2 z-Gne*Yx&9VcK9jOXzai4H(D?L^rVr8mS4)N)UG5aOjm@Tm^ZHW@`#_HB>cP9T0+lp z+o;|e_^JG%i|-lnQ<{>TFg-@x`GsYsizrF>cdZ56!;OZ$n&;}hr^~A_8;UI)&WY%u z2)F!?bL=zy!R41~^H}g|7`-mf+`GSg?$qh(-8LmTVH-LhB76pKcx&zHI)e#;-YszT zi11ai;~OhZ*HzM{BqwY`*OdrgiI<=D6JLo5fvY4uG2J7c(dr8bUG2ZRb+hSnPr9Ow z`y+T#9~alL2;Wg}KeC$dsDz*v?q(6bYxn-vR=#W7l;ni%={^_Xk>Q=oXN_oNNC@1u z;i>F)c!kkuc=Y+lsec-|{R7XoFSPle{Yk7z|*g~YJR>{inU_W` znzchhV7Ao6+)jjNeGkv^x#^nqbtuUR+t55w#D6ujyzdKJPk-R_FC_$KeND`2MR@jl z=|+>LYxdfqBqwY`cYp}bkZ*kULnD5>Mgp_fCT8a%JPTiK(mzK029J`Qunpb&B0ST7 z<$d!_*GxYlFbi*Dl_A2bi8p^R=X9+mI+WyuZD{==!Yh_{Z@A=2tymHQtBIzc%D%3& zDiYyU(a%r##g$qWbtuUR+o*`;wDS7vmMe{D<&_YoYb~t$WFxHZj^B1ftGf;*IbmAs zK@na-9=X)zBU(Ww1Xg!VKb74MJ%vPgmAc`}OHbD-wL?ix*hWS8Ilk?mUmMXAG$Bma zT3Ch4hM(h$JUYj8J=Z&wkia@xgje)GopADqR`dx$Exb(##Qf!kw=OqbZw)$>q_tP+dG_m*2;djPf1RguC6P;DOzpbEmqc>qJ%JAYvC=GTJE<|@4frp z%6c2sp(H0v>;0984fMuq`Q>j|S#P`&0&k<5o-4Q=)m`hiYI`sB_7!@o)}bUPY@;I1 z(wn;*cW8|0&0Rv6uC?&iP+s}%;IB9P)5>}~*r6mROzVB32)}{+*D^o!8_0yf+rg%v z{BB1z!u?KfIsbC@G{5ESP?8h2Q4yXiY;^T2D{JnM5T^Kty%==$|rp|XxRdsb$olxD^tZB(;AFYW>Ni{*bOfaH&{l(4NZ~u?E zjv$>&Ni-8W7`1$JO5^s3S|(ajO^`;M69glp3(x$Ckx@rT)Y4{Xwu3V(EH6Y~-#qf` z8bn_c&fR%QH9;L^f~&xl&op6#*Ab+1DXz-=C$13i$zY{9>9u7w^zCa&H9@*eFjBqx zX68s1^pyc$HqT^>L+LAsndz=->)Gk>kQbkUuTkZ5>OqVLG2 zVy?l@TkOC*0GFMh1oH!^1N$DF4rZ>w5x2I(7k}p0=zpn{{GR0+oVCNTmTRCTN{GG^ zEa8JkNA1>ZF#Fo%?%?(Hr-u9AJ1}V6v$#*rG`@QU$ceFX$HXYA4ei=Fr ze(KVw(|T=Y*A1MSXh}6ex=d_+*CkP}OSYeV?16I}K{}T@!ic`;w`hL`G_Wv$g;Rw>XRHFySnvUUO>L>go+sEvY6*mx=3J z9u*C3y5a1N`flL}(z(>=jfR+xEqWdV9V>U}7d`OzFZIpdZqk7XlOssyQaheI$aDq;sjgujpes z?%4Je=!kdSEBfoSU+Y)StWC9~njl>!PJ4crXyJQ5)c+cEa|G#J>V-4+GaY;O8wwpG zzTGK$qWw4Z_pRueYDqOgx=i%CZ_DV4D_7LNdj1iPAe~Ef_;-!z*!A*}(DBK@&7w^w ze^Ebw@X@K3R1>7j#7moO9R1m9dHwtUI^GeabE%+dE7S4Io7X_c_s!Rjg6lu6KktZ> zQZ1<_NSBFiCaela9lWIew=QQmf^;tR+HJoCTvtBsaRYSR7Jm|6+Vze4W3N6Z)skw0 zbeS0W#2ewG+dos^?7s6HK{}V3(|eWa`129!_#k~f?0nLD^<6$bFV&K2f^?a<{rqRb zL+^U4e!X{xID&L8HTckZreo=&w?IeJWOn$(h{g4L9WXT2l4^o@ob?p!eKs>vtS@RjMV`1nDwy^*Of%8}4~&eV@ZeJA!mB_34-!O~-o+sbgw# zU9j-{G4)?ugtuQvNi{*bOq|_#M)9cY>gw<38#aXCbuNYL65CNBO4sjla!yoAs)?LN zo_=y&e00C<@>(fT%B4_4`@PcgxZ?pUXJsv~l&~gB@Ve5w@d4>yv$Ec;5d7az58bEyY= zuQDB#nISoUlgHX}X3&yqf^=o}NsbtEe_PHzO7J?D!c1g3Dl=TNXzF)uvl*^ZQcaMq z%%aK5zni(u)>*+%F3C}{C?Y-Y~`$! zR1>5tt8*G{(z7O8oht7)NVriQyEC3u}nVdrEzDm${YX7yz? z*^aDIQcaMq?E2CH!^hWTyS@s+|IMYa1GL{OJInOk%Wtd6c9xZrYJzlS_nK~he|=51 zd#w=s-(2d1Ge+9)l^t^W#`}-gaEGiV)dcCvEW4jo+7QGHaqj@PBhDSQhqs#bQY>IqHR)%wnmOR1>5tR#Dn)$E7uy zRa7DPzq!=uKiy=%S1hk|P~+EXXnAQ#H9@*e+|cThbi!F5)Xau;rv$HasZXB0*>qGa z$aKTM-l(AksU_6}>57$_e*F4RHMCNd;B_vw=Fdr{qhblCFWvE54J~0UsU}EQtnKvK z`&ZY{+E#+sxfCpK(^0YL)6JT$uE{L=N=Y?Ay5coRFC6<<&9-H)L51M|=2Gw=*zfS2 zz;=dbBK>N>dhIjMM5UyfAYCTl{Yc@HX`gvNDg^&GmkOFrv)?NomJ~jj_Vlo5Ni{)w z9RZ&Vi9iWn=Tg#+zT{K)@%H!Y9)nGn^x2_6cR) z1p%K-3ZG1S%%ZNOnxGEMyCC3`N#T=ekC{5s|B_iWlsO*+d@?C~GVQS%L|Rf!PzTlz z5b(*Q@X55tisJ}b4MJH5LBJ=I!Y9L3Ez*)|f;zAcf`CsZg-?bnrz2!l3uQeA0iR3? zpA1*$NK2{->cDyq0zR1(J{j%+93iW7D0>O&c&T#=pA2^yk(N{w)Pa2o2>4`D_++?~ zafIwLLfKz|fKMicPo@SwnMg~j3F^T93Iu#IDSR^AkvT$kOQGx&LBJ=I!Y9LBU!*0~ z1a)Aa2m(Ht6h0a5EFB@czEJk4AmEcp;ghMs?lsbqYJxhj-vt4mObVY&4R*+mklkx2 zduTR(voU|I$#fifKMiYPo@SIq$9+-3&j=%0iR3)pG*y`)JRLJ3F?4d3j#iw z1U{J>Si+7FD>W3G8U%bY34Ag&u(l&DsV1lc_BjanWD@vfYT%P`gjn05_!&UJClkXb zQvR60zR1-KA9SLCLAGNgHZe>AmEdU;ghL>PbSimYJxi8VF3Z3ObI@j z8u(-!A>I$_C}uvHGEsz2CMPN-)xgqeKbus)gb;gbw&* zLil9baU^OSMRarSB_+%K(;L2GksV1nSOfX^s zp9~`=jv$>&VWqZzs_XzF_+%KB;SQiuQcaL96Y$AI@X6G}C*ugxxs*hm&{vEu!6(D$ zQlur-1nKhLhY>9JWEjD6ghZFPhqKyNc4QHJGK`XOM^-7RCa9xKFcJr!3?p%lAe~EL z2WbCP*;z*L$uQc-on@t@njl>!7*T{zh7m7jwicDAn8^X3Og(%u^Z`@|UguKqAlUEB zXDMfkz$e3O5qc&nCDjD!GSTtA(sR9^7#-D>x(E9WA5&`FVOkKhyeXWIQ@FgoVp93K z&(zz4ao1mg=i`Re-!=3AaoqfF!GONqV@ln#$As{-u^ZdLl?mD|ZX88E<)bB5hNj%yA5)hxXn^NioV)tu02WNcq zsY&g*;OcOrw-?%VpHs(%Z4a4m#P6q{3u4i6Nogk#J#Oe2JTRa|!dmV7?xo?7TN~T; zK~Iecr~Lhm5l?S65X7t>zb-WgF>lv4!J2n=GpUVVJtJ)QQ5(BnwZY)aBcQ5@f9Ere06;Bqg7)~ zYW)Ab5cEE^e7)h@3j_435j!6;AH)|oc8QM!v0}4>i%&i>-iV$Pt_hAFUcSbic?!=33G_g0qa?^iNeQFGq%cZiK6@n4%Q2rl66j?R z7$reAN=g_dCWTQF^Z6#h=luyh-z0D+L12^w*(hoFd-9DYg;5f74k5ug1*60Wj1uJa z^*>}nZC^aKotxTxRiqT>t5Y$acukVyi8{)&&(w2<2FZ=1qoqfm+3?P($0T>0Gc}mf z`>kS|RRipreq+pR2?<_fqyNYtBYrz>V)4)^7@_BN>-H~BSQxN{r3K5BW3M4ofpk9&vzx5!!@zVQ(OC0Q$yt(PpY>(4I? z5}B_+^get~BcAwSNH7kyA;H?AEhS#Rjkd|W3j!^VvzFJQG|XCFLd)%%Z5@j_-L>2Z zw7i7>HYv0`*k$8hc8!+vNiw25Goa;0pyl!K&Gt4av?oBz?HVl)W$cF5@>16FcmgD| zmWSIdSzy;_c__~yh}*_IUHoJ8RnfM$eiZ9z7i8YX%qnHZtn>(o12&i$d<$aUAJbwz zKZacPgaq@=<=%jJBxoM@`{z~B4_~|+$jOI9PADX7J!{KxP$;}u^JrWPqS2hOf#iZG zlC!Nng3-P#eJ8#dwYp@FEo03j*34z?Y1qy??GbMT9Z&E6My%%;q*kHS3hn5;=#z#T z5RJcCW_iYJEwg>~n=M z_ot7$JE(-7R=_*9wmvo<_}W#`%*ppVLZ$TnBWHWTDe(l5;R3RFaP${9Y_ZhhR>(=u2Ej#I5 z)4Lfxa9Ixa6zbZ8poE+C;{2BBK)X)xN);XT*PoHQ4zM5*Q(gJW+`}=OEhS z&hZ&s@Z(2z0)Yg2Hj&e330DV>E3QO^!s;)k*OJ(>(Q><6IU#5J5}AEK{Qkn=;<31c zE${u<5xT0$oDbstrq>pC#T{(6#mj+~C?Tr>h}*OEW4l{Fa)e6BS_0y+9)A|kKsyS< z-?w)>upJnYi4rf%8*k88xN~ed?qnb*WD_~bnw)`s!@BjO*LlYWCA56x0WUa0cK~vp z7q!~vx&A?Gw0zQ>If0fap?e8@#rK@y!BFVvf9W%hP$@Z=3>}BvHO|`6@`(9?mMDSM z(^gTgriB8>6I+h)W#fr`g*lgVmq}rK#kwcLDCzW6&;_;HuIEU%TT((!uVb`NJZ464 z3|hX&e=l@|O38YTTCGkV3NAyfT3tDTdy$0w&Rv)ivKs(#V76y?_>XChP$}6$uUmUE7hH#)?8E~uOPM?8Z|mjq{^<>Ov@)$J^mkheR4z`Pr9<;1+} z2$j-(Dc)0<&wVJZ?I7g_I^jlCU z99?|hYPDVcYWN!}Ep%_ckoy7RtB)529np@n$L}9=F3iTRd(VXQE{OWh6HLeUKRy)8 z^I`8YAkCc<#~FK_^KYThZrWMFZqV_@_&AoC!QL7`g6{y3rwhcAV51^?x9#L*vCN!y z9-IXFFO=C1#HGy+Dveu?_jzxzx+FGoDAsS)K5^;$4;wM0<-(HKuk>Ho?w>ogMd2>nW5IpDK{P3ZjzT^n!?oSD^$UwjYS(|$x)$WHk z(tH5)MrsWUg;PchsXY&U^=j>dMJ-W6pBua*zVDybSDWnDC{{wHw1&vVnf`y)S3mtW zDAp1sysh^6h~=g3=&NasQ%9(jZ~6SpN?rNIyRnuip|&CHkL5cT=`U$Fy$ijymHrX0 zTBtQ#=ZAY9-dZhDLi}^M9|tynrFIZ{chiR1MI}^9XCmZAEv+jahFYC=)xq=~&>+1lIuo5aIK0pw6b=)oPh~B-S+Y`=q*1l595^w9NTVQvv>-3YI1*wGU zE)-6WhuNIidb^b+{V$dBzKlOQZd^PAeO2FVMo~+Y@a_1#~=?}l)g=%P#F3ZB(ZYRI?@s)#6m)? zF4}5w@c{Jh2a|ST+`#&ZaRc%1G74bpRXGYU^T)4qk1&0!l@cYyQw$v|-tAjF2EE&* zZUR@F3ZYWE?jlcS>;DvYL#^Ivx-C7vMsP(|Lj1|lAzo)ksFZl4LG)~Li}h~HR^y%b zL;FfBND%!`+r#eQt?PG;wL}T6Exw>U_Z1r@?It{0QbMJ?cd*3|7ZeXiU)}e}sG^oA z;oEW6F)e~t=&ShTCV>(vC7yJ&15ugW-yUd*_};60mL0DeTZ~Yvy$h$iS}CD>BHZ(t z|FV|1yx_Ky)=H(+qf;nscT0ck-L8$-l(a+%zrULJ!b9;snBjWf)k{5%ZWrb~MO*fN zDei-{cH_QB##*BPt6n2y{La}vSP#9sYV4|_wpJnyq1F&j)W_{CHt`%HSX!cl#4K<> zmcDmOabNWAl5Slcp;Efb#G69i>kzC!bgAc$3yWH!ghV!=M9Gv;DT#|< zr~mh1Puug+r1N&_hjG0tJ{b_-7f-f3xJSE%B`wk3Ro%#rUi7DplJyryj!-G@Z-2bc zoy8jT)rre?ENY1oz8xRjyI=4&`s&fT8IDjXiRqvnh!5tGpQ4sX6sRf+F#hFP#Vt{* zYcBn*R%@k%S^$N@X0H^?Hu&|C^-4;plzIx0XZgYq>)ip%_I9xeCA>9p)_E`69o%ib zD;%Lxw57P?EWcqx{E4(VD9D15dqN>i9h zgS63TtHEY-wNfeRHxRVZ7*}JQP)n4MCn|*ihcusA|ySLmRJh5qD_2ld@uj*y5V2-z)_WWSThZmBBwLv~~( zt-BJkw@VO}fgQ-cf?cTlt5~Ic%V`I4T){5X*rp@IW`K^{v*_!F>(@C#r6ei~;?Q*w zUKgWRLhL~hvfnMqjx~|JZ&hZE*aqqsb%a;|&_SOo`-+}O?H`rW8scpWu(;S)u)xf# zOb;EbE|(P~Rv2{9s^i=aE6))sB^EM>onF5=uE*T|ecw4QqNs#K_(6!}6^k8}h~?#K z2v6!d>rSmAM~I~d9kd+TS0~PWMJ+FvL8UdsX(wc&u&;(ACr3;4f5kHa9V_p?G~Nb% z_5GLA9idXb<&psrXo(UUSH+isGK>D*rrXA1lP6-)yEZwmK}qYbgm@Fs4%(XRE7+bz zB~(glh`AlMCi@DuXP_lYh+hjjmh|Xh56qZy76FBNnY5XE3$(YLRyRVl3@&K1F`V_(6_3$#QD@f1Rbcpx32QoiMR zzRxqezY%DO65`*54)G4g;_FMqJ6M&`C>}`l+&MzLk9j=uSA67b$2woQBUDN}-XJ7y;4-$9kVpdv@jA!iH%`Rs?Aqi!+a;~L65{cO z4%)NqE7-T{r*@gET0^`u6ZS0o3id6d#FcCc{a=Z_KnLwv&h4;o9idXRXR}x#h>3ge zR+^8w{n5*pnWdYTC?OeQAS7-Oi|0R)7=mk)i?L`7(h(9#feyw6*;kB~X=_zVYls~g zEJyYgEJ@4Z%pz5Z5VvRLP0+4|6$>45 z7Qhkw-&_iGentQUqWMLRL`L_S`H+t*?JL~DN`5MQeMg^J%R9)dTrE+;w}TciM+q$A z|BuMqWED3sO2+%4gi6WzhVnhnPeH_5g8Lt{uMmT* z%Emx>_lr5p0V=TFYVI23jkX(u^dFK^ED&uy0+Cuo6BC>9k+g6#L)~zA~ZY z2$k}gPOtr^bh$ARa)9cYOXn)PIJNhym#^7*LrkDUKVw1yUgv=bwULB?951ms|@i43^0O3k(EekahAt%FPEs;}VRVPN^XDDScNLMQ*G&{*+kk)e8g+;BEO8Lx8+JSsNU>6p( zL*QG#LJsIqP-aUP88_h{{*=CZT2!hrr?;xzzqLygyYHckBX`=*Io+DHW zzFvDiU;{x1JgKED21!q9r9=te4#XhiEC%Tam6Fqk&>?3OOIiY7xb+WDqN#54g_p7z zWP_F{p}BY#gABNG!e*m?x6%%kLUh397+7Yg6>T*3E^IbN0V*X*_`E*aXna0kvpGVg zBp()WoOY9!S%xXIK(#~(&AGL>L7c@Pc~Y;^KXN)V)*4z2GC$8*(h^6kJLid(BPvtM zVvr3=ASz?}c+L;e8tX&YCuj#EKXDd=ENO`nhzJ?Y9ke?$%E(XUzf?-jl7cw>nQ~U~ z*87}Ut9_z<%)fr-bUZ7^IC7#2^n+LZ$rqK}7pXSq!p4OO){K zKnya@Vvvqdsmo!baV}wPEe4qrwOS&CWy^9^D-%+yTCJ55Qp2LfAg$$=H!3G2RZ98| z1kWb&`9KU(^II8%&hMr^1*qBd<6a8d;Q8p(d#WSk=?Z+7x8%@kroEj&;XZ*r6v=gm z4jG9>8B2kTMCK${YUoBgBZ`$0CFCi94%%p(OPDw62sst4ZL%1o^%e6*wM73{W^m|e ze00g?lKDsc?Fg09ymyz`&m0!pi_(9ngsipDff!^ymlS0-2xMNVI_ZrVWIpd|uCpU# zc7+baAZ^8A*1EPlDg&1V4gi6W21O!eR+PwQPP9AEB z5^_QX1Y(f3sv!nhlr<`lRgHNvHhSnibStN>IF6826a=k0jw@!G>VK(}*3e>*)>nu@ zmb63(+1o(}PGwqO@sy?#D&<=)CwTOnkL~~iIcWnOh(YGNrK0S2LfI`<(09HCOa<#G}!))FP;j1hFm zezzz))=>7oRquch+dxk!I6^D{=-}xGjw_x6(blSz*3e>*)>q5|)e*4#G3#ev^CjR%zsrvrL=|?gEWs9^Ix?@3Gr(| z2W?I6sbPCMLZ$Si72coNyl8X#rZ_3BB}$0T5<0{uV{g-7U*TC~4!!jibHufVh{~+< zUooO+eT65>5#ptS4#Xg>uXwUb36;_sS`5q7CRYIkF%f-JN zYl#x#_k|Ae4w|LQzQP#l@& zyrF~kEc=Q%wo0g!*3e>*)>q82)e3-w|k3+5)wlKff!^S zH?Vida9lAjPGSgE?~Rfei=GB_ghW!H12IU8vGA;-wpOLIh8Bag2o|$hwL}StW|H7dvPQl6-orF>aAReC|Z<^=Lfa! zO6Vy;JDqtD#}%`3l~5_Ip+);FUONSEqR|p1(1&v3kmrNhSBNM&LZu|Ojh6p4YNEZR zpwM|~tR+fF9sr0BYL8EUI)81j%h4OS_iXDMwBOygE_v|A5y1}!@U7XMKHM=~Gj?r| zMu)n$G~*qON&dFT>n7}LM8h6@gV`>H&BJuq+FNJK|s zEl;wR^9x5M68xTzyze(b%j2x&Akgw8YdODz6_eoCVC1dP30iKwi zwaV{DBKHHt>(94~4tQXzsLOSKC#9p#u@+80q-*l+foF#I?tVjX^_(!-VDaU4edS+m zK`d>$G+eOTanUIg9&%DWu0JJg*LiZV$#VxMH$5@bt`C~I6Nu-3YY{9vt}gm^wOk@=L&>uYrKdq$d+jdavz_Xqx4(Yhb{A|p zdjR&J>EK)PWxt!86K$TbRv0B9FiPTVl8zqUxyu?;ZZabl;5f~*PFiMhal*D2QCt?XF7$rvVd9+cIWTS-dwzFEX z2gGZ@r`Cw_Q;SiOWTPY&FAnp=Oc_k7;4t-~)4 zsEgJ=`mb0^l#qD^I$rqaKf~v@7#1yjy^H%Vm6Evx#5td|4WonVqGyBU?j4OXcU7$h zM}1inUba_V^huwkvHq75GIv484)z*s~)k?_xh_SoJ&y&NAejOU^zg{EvUn(VYB8V$S z9Tc8~d3Up2Z{kyAHL<5?-5eZyqWj6U;o4Sp(bRV1U5U)v?o3Oe@a2bhghzZfG}^aQ z$q_PB$2$(V$=Y|!nsKOA-vM32J2AKK-RcncUwYEU6WzBuBwW!HPwjUHx&KlE5dmu- z<6n5M+Ospld9M$RuKe*FN2t_)54pu^^}*L0g4p2kL&KTP>!OGLe5a%(O6a*M*lG_P z65bD@VdS2SVC32Zsk^-ellLDhQh>LGHlG=eoIW(_FydraqJ-!s(W_T@+nNzkn}bS> zn3xX!mrBXmH4xv9y*J$9$)VAvo6Ra}i4x~T6RqXtc+{ZLhlS_=H6nU+>w{{QP$@lK zhcBjgoE6@IcEq1eC~1ijq7S|M!iZksRnYN6<5`YSDbWo=T3*r;C8S3{oW9|I8h*#z zzR7moXl>;OVr4NBQ+KqAklbZ=0W9RLWd2646;I9pcs525S;NbEKx&Q=5G zTaf)jC_4ZUSPkNAHE@0y**}D`0|0^5AkJ0;=jD?9Lnu1{5LgY8Y&CFRN7+AwvI78t z)gZ}M1LvWY{R8)jNwyk*z)YQFGqro?vg{wYPc#BM01%i(lWZ0ZWSH-o8R3%nBD)DgtqfRZ(kn|=r`G}?~9wDuR0&ILG&<)k2ZP1+0MET^49hvbt}!< z?z+W9XNN1H`xQhp?%gzEt?qyQ9!IFu?bnYri+=Z=Hc0SZ=V$+CIu`dBoM?#>eqXZw z->s}2lb;^x2$eedWLWj+g|%P5hL%SQ8%OjS+!*bdXo(WC?t+-wcSmc-?-%Un2$j08 z|1GA2J&i2yA2u=_f4{gq))FOfH$%>e3SG2WuoOkAXj!>y%`%N|-zDV?6Qt|-%TiLi4vkOC=}N0Rbzd1 zR_kJ*gi48S5Y6{%V(qx#npuICC?Wj@0;Ap9fzj>=m6BdB>qvReFT7@!dp`7;fWCZA zjIA9hpN}(J7h^3^qDB8H3CC5XuS^H}iu=UMf2owt5_UiAsU6&XWl>9%5Pi^tdu}># z&jTe?N_2z3xUzO&Tybxh*D6p#W(g1&yQZVjOUoUhQZj3U!1H14!1EDmi4p@(o?v~2 zXAlIQLDPX}&=D%-SLc7eG%)?)rQgCrY4=3_H-5M0B=b7L7aITPh+FM?`Q6RpLIHME zlG{=0DUdw_ttIP`ve%&3qMMR^uzT%!bz4`WgzQT&UtROruL;N1!b8S7LZvW|S#SW zJowv0OOz1rIS5$7Np1ZM{oxbfGYJ*w#tz%TOr7&9|(t*8BG} zj!-GBAz~~Su1q*z)ok@O*YirBD6z{;z3ulao<9yc_UX2r^;O?3o25#qlyCWUYultN z@C@#y5-Fv2KC)E;lAYJ2il}sqW{}-qkcwo z*<=!k7Z)Fy@EP3m&t8sDsi!WRYY~&d>)!%mzqMTw&R2u(Iw{o>C47vf)u`=@pTM7Z zz_#7&4XWJH^VFYMtn^bCxo0T*sn1<+vmiNiSk&swyIqMA-e>v5;zNU1Fkda(t!b+N zrBdgv9$#c%E#71b+R?Q8g8}>Mvjf|uTA~En6p$$QRg>{|2JEZBi~2c2r7r$>LXpv> zt+t#B9Ygm0DPUjKetJr(B}zyn4#YX*8U^);<4k@oavoZVQ+--i4xvV-Qk^1A^U3S#Kx)qmr7|3F;fp39CBPWTd{4bB})AG=L+kq zKlZ#Hckran#cYKfa)v&*hOtnOb#T|dLzIwLF4bXAZ6)yxEAQHFm zfe!AALlTLr^0y!T>Rw^z{f0$-J{sprl<@xc83#_XzS?oY4~|f&P5N&c@`<|W;(wx6 ze@u9$+*kcKPPIgdC)(^|#5F4~1hM9%W!6`pY__)}R7xV%Bo0|?eKq3EgHkO~!bg$& zPUswQH8|?9##{|TKF?esu~J)2xO>5hYQG~!4;`0}*vBHgV_#k3N|aEm59bYT>K<{l zzdm@WBUI|10b-|%k2f6?;$e zuqHw!R7!dsghXXrbXuY^^gxDOoncLcc+1VAo5IYRa3xBJ?*s&_37Z*UO*lfOWE_Kl zHDQ)8tcg%dl#r(j1gr_`D_9ebP$_wCK){-?zJfIoYKao^oP&_K8ojk4cQTCqOI(fq zUF)l|e;3w7m{}99L<#KrjX*>ZI$%v$U%{Gigi2`*&6+UJ1gwcrOO(Jq*yb)+6VL%` z!ukrN5=*Vh z>uV76?`d=#LTMlc&<||ke zk(MX{Yr^IdSQF48I~hhy^4*Ke&a4SnqJ-F@&;e^A z&a8<@|4XH`hGtEeMGtEt(h?=adW8;H6G>)GI6|d-%VA9eFbYG(h?=!@A#9AD_9fI0c#@8tO;fUS_F%$zhrDx#cN?rB$+kgN|f;N zT38d-SFk1=p;E9JlFXVwtzb=*`>OxOk(Ma&WSf1AfHeUE)`ayHtO-Y`lw^OBIApE$ z6|9L!OO%l8PY~i&bEkyF!^X8MSr8SW`ZO$YOPbN@2B2GHVG0>?rf9!H(iOSSe8g zdkOo!oa>DJuIa#jH&$ObcCseL-M#qtW7|`we9p0_b|p$+uWfW?-)=g_4p>>z|57Q9 zQ{epI1E*O#U>gKlqJ-$fp8Apv`kRgyTV3l2l@i?`VB?q$*f^n?fIVnBU=KP%r8KgET16w$j-%HG|C_s4f-iqt zMl`-C?jjg#{+wjL<7?(|p|IY7Vd;#Cqrx6LbxE{DTJB;Y$bi^-c*;!j)9)GQ2x&+B z$+I_`4t$jzI=1e5QF`4$YlB6vKA4>T(@j=_Z^An%X%mQ>Z@VDfW8A3l%+IILuFd?t#^-Ue!U}9O8N>qzU$u0dbja`0~0M#LhciYUz+V;PwknVdpJU+B)SA* zr*Ai~cvSxtnPN?QvO2D z-L1&ElbjNl1FN-#eco$o(u+}<(+aK~lEYG!DLdn}g0=kV9r`&!BV*d@h|zc3+M+Uj z23_lVR|(jnHYb*2UK?NAC8eL?sO5J$LZx){6bgI(r;m-2IbS~GMu`#{*(wyCdi3mc zCZ3O-_h@j0O6iz}*WkoK=?S;34Q_ewT{qg5IB)f}_7uD@X``f2`1s~M(|;VeHrVj$ zgLu-yN_f)Zl|KFLdit{`B|iS~;@JJulc3}Ar}jy;M2Q{G9c1*tj@_VR;s*z$_n;j+ z{BsvasFbV{AU>GcJzdmgZO~y!8yA&PV)RBsOve^I4+8PP2R+hLMvV#|x??LxsFbWY zAex+dL|T8=+F(|{&0UmC2|1esV)?E}+YlGd>?;N30{tn71p;S+z=-rfk33SAlwN2l;epLAP;M!D6 zl+ZhiHv-LTVPkjWJN9yfO36M5I$qwqiOq0ZH{U+h5+yXohIO#`j_u)s|NWIHp;EG+ zgO1rhJ#BlRKOTGA<@_t5u|k|_n0ZvP29dZXKVInwm6EJL=qR<_FxkFKUG&Q-o4WG` zO6W;~LgC7t8>cJ!tPS3pbV90UiS)#f>>r`yhb=Zv!x5vxuTSkyKeeqmJaMFi-lsz0 zmT!Kxz39+S0!OHn?1Q0WMvIlU-@WhK-RV8InT(!zCA8P^-j9PHwfoWc>86fQDap)) zj!~2Ew)?Ss_Lqs4DB{AqJM*K2Sb89i>3UoI?2&cRI~VWk zP6kPiu+xoiR0W^KAEQpln^T%I`-K9@q|0%t9lP| zgi7g{#;W#ReZtlG(L*nGqg{#f4xMLD!O}+=)o5t&8xOs!>Nu? zDe>q*$2T3mG0$DE$NDl4Aol{glcnO<0`cRe*TsyVZ_!}61{Ff3#Loy~T8F#MtF}Ym zCd_B3oZ(YKylo(U3%7|EJzCP$^^Dy6-ST6Jn(G~esg z8h1ac2+95UsK?aOf!MeAoZa6M_}_|@jvja*U%#MePwnE<+$gCcB=_U2t7ew?L@io< zxg+qu6)7Flm`hHYTI5rE%^E-2s|Y*K&8NUtwJ=}RwH`w}ftLho#$@PC8f37O9@FzV?tAXEywfpA@3Mvt|RhI~Hm zez2CizDkJ_nrnj0<@=_EdfAo5W`*cG2ejAmPT4ul zqM=u<4Zhmv7}vW>boh5o$mem_%SWPCunnTzHqif4DIE)DpGUcU{&JuG_FuHg^{oi7 zsce*#^Alm+MY(mSB}!=f;J-S)r9~|Ve$;{XdF8)UN+OtO$BIuIMf3>Yx>eg$OO((o z8`x^Ud}yQO>JwHcN~n}XVxi-~JLcLbId;E)xwE=TVAmhgdtN^2eZ#6g;ZM5{i@yH% za7U;VYy*qkm)}nfYa+<42`y1VPZ^s%7>Ye;|HYhFdFO!BT`0VD*}37uorXoTKO5*u zl#rM=THfLQm#yWuKlYL%R7(30k?Ko+vEF_7$xmGGDj^YU=s4h=mUajC{C;zH2USYP z0?yrSzDq=ZdpNC?8zo9e%o{q+{BCc1q9!ld(-A7AV;ZC6&)SIV;3uE$o@$8_@B!IV zQ1&gszZ>QL-A|vr*-Gg7J>#dF?3%t__~C3!mouIEwmjc-%$xW;y=s*bCE#H(y6hwC z_1Njwj-F4v=?ImQEE2RFUYscR;%JEy@aUM1vfrom+T)_3qeq2zeEO@)*itFUzJLzA zPbT8~WOhAz1A3#Z9n48n;`lR0nvSpjVy@a#KOAQ5IBVn09HCO$(|B*x$A?GJHEV;r zzT1XgHPgX-I3?gOGaY3=96WcCcc(lWIk%!fzgag zi4urYSo_MEXMZiKiw5*s8?=6BLr198>+4Uoe`?&bIdmLy$mJ3DC7tiTGu9F%G+PYO zrT0hK*nOtBvm;b0Y&y+!lw)33|Lbz=t2J9~9cYOXqA!5AwpUrlaSz?;2$hoBfc^8qNP)n51j6I9|SUwygKaNl-Ip+r*i2Ov{ zUm@}nYKanhuFN7oVHWvuZ<i=pMVxfS@k7bx5^5Y1V z($Qm)9~&iz{J2q~gsc*wMSg5%K;*{}Dy3uEB0o_U`EjFN30Zxh1CgJ6XBo-fFqCyS zlpO#FM1E}cLF6aW5+!7A2Z6|s%|3|yI6|dlT>&BM2Qvrq^&?b5))Eki{6tyg#}O(e z>mvw6exfY$6KRPOvciEtaT%sc$Vv?zvS)CFO8Gk|Z%K>9 z<_Ps}%8nd5#5RbuL|Q}2@?*PKM1Ddg zR7!T_AQ1Vn9Wo+6p_V8i)&vMde!?vB;|P_Kw*!Gd5c#qDfyhs&B}(XhLT1f2`-NHL#}O(emKSu0t>)e+r-ayWAQ1Vl)Rw}I^GEwKS37xakUc9jmv?y$d8RgM1CUuFU@<_Ubo1PjdnzST<dZp;Eq9i2UT9)JQz0p?Fe5@vuS%B0oVE`H8ed z32mQ6e(ZE6B0r8$De><^2O>Xq0u+%S=4|J&f=~%WXzXks&WwUUfqFO2@QCeo9&7$Bp(X zB9DJUhvYNxjlFU9-r7*&z@fyQK_K#zWRagpOO%l4D+ok>k}UG$2$hnUFbG6`k}UG$ zGRc*YXfFsvev&Nm;|P_))0M}gK_K#zWRV}vSCtYaBnAxvkspg~Bl6=2mC~NJ$WNR_ zes~8fcTEY*D|SEdeqrc90=s@Hr$s#}8^;Jrgkemq+i2Nj3eNKp^syWRV|7sFb{476c+cmS2L%k9(t>5|TLr0+F9Ii~K~A4;4x_9rx{(Ubo0k znniwG?s=-El!rxr><%LGFBY@Pnt!3+$d23z8V{E zhz_8y5c#nu3Xva2sFaRri~OWn}F4q*>(0 zl_;U@!=C!4?sh-$1_4K?lw_4d2i{U(+3MH6x`ZdBZEi;%d#Hq-&9V2~*?EKeUcbi? zDka(R(1Ca9+1SOq^mx+So=%<`S3=Ji*_($GzIphIW^EmzQu5{|=#Y0hxp!tNA#ZB} zA#cpGZ$$H{rL`(=&kD4*_U7Rvd-JfXl@fA70lsj&;m=zBUXQ_!P$}(od{^f0R@S?C z!=LM2CFFzxbl@Ej_SE7X5ROnOKd$f&2pc7M2ZS3XO2AKTPeJ+258|BmL?O=U2$j+? zjdNZt&$p-cp^4AC(XND?P(V8n$4MnhX3qp8ZiwC3H6vq)G+C|6aW%xFOb6mou0)BT z=`^D&F)wQeVqT6=DLuhuaW&I{xEkNjVA}a#N{BwR1F<_hyR`rPcRE6)q#eHHj9}$0 z43t1LEAJ5yh(V@V4AK!QB`1bJAkLXSQI2zlTB3xUv;uKKql>H^ohOZTgi7h%gr9oo z&@_wJGB!~eKT60MEa;FkSdLIBKT0~@S30=&6Qk3*QulyXV?1?!8PB* z%NUgO=OA-)h>ByrC(mw}l0R{vrV zM7lBvc=Dc7cyExMyyrEeTBm(~VL$@kiv;mWyD7y^Aa=i|b3p$UrS@EKwfV1j&A1f5 zxJUwDO$34O(HD0D(c^}W0exYV;+HQt1M!;vvdMpcV+6h(2x8WcUl*H$n73=2fZj|> z@e676h4LD+8@~V+QU|~DW#2y!et&#)I%3@B0sYaG;+HSz&E_@tDEKCt5&UMHeFZ%D z7{q-a7VP~Dlxn(ge|tXzuSwnuN$Mbpx3_-WE{H)iJh-gLw_i{yfBOZmS-W3R8xpJ? zPG^48DYy&7En}Z3@@?#t;+HSjVqUWco)Nhup8F)b5HVU*Z6 zG!*T+ck3zIfVO4%rhxv!-ZGn%+# z5^&FiPx93$K~O#4qQO;I|cRl*HL6iFy8*QWz!n4Gms% z4@^lCByE)N`{x`bC9d0);&;wj8(y<^tPKg)&PEBpP0mqL;`&M{zO$b#<~2r1!WNUj zD2Xdy=;kP~uTE2nU%udJKwe{%Sg(>Oe>WVXgkPQJC@JwQBBl7=e4b?FHSZ+v90`mP z=xDQ|dz_6DdxJ8iFiPwl&%9>FG{3e>qWsnA>^oQ~zk|i>Xi9Ouq9m_5zWD7b66M)v zD!xsHZ#AY%k3O^E?Ng5lkC}fjztUCYSGjo2)n_bbHWIwXE(2ebBk|jD6Zth`lj8Tm zciFg?U7!B!G@Erulv_Rw-+?5-??MjWY;Tj|w+`_gO}pkdBIP;9{ovPINgTfM5y6B_ zehpX?exY=`B@68O^9zGS<|`2V<}wL>gPGqzCc*Ctvn{+v+Y*^~L7?UQN+nxf%kMZ- z3eqKh<(k)QE58)&T5bedZeJj#6m{_nySzrrIWrhho*B?`BhYfIKc&#}fL{>hHCk@p z=cJDE42PEUTXbx>ech2#XnDx57xEe{x33A3D9_Z71kK}q|GX;w;fr_Ur<(T)E>C8} zJ9g?C@=M3O#+Q#n){Hc28X|sP^JrWPqS2hO@gb+T3MsYepN&F%<<_oWT=s?Dr=U<+ zmcA3;Jo>8il0CKz7IzFy>dv`C?7vAvm%IP?66Q{O#2Z1!)4RVBJpAAzR+A}B_f4c$ ziPQ@BIx9?sXijGipps!YcF}-#I+OcJ$ z<@~;y)e7IGw^g6?mJj!|Yu1X-Org-eWhZ`ZGab15>-M!xO5uyjA-^WcYu*ojk#XJq z=yl%lK?&^`dB6*f(0k5rnUX%bLkH;C=DGes>({PIC(W4?Yl#wk!l;9zr}DkjwEv~g zI6|fPg;na{IKX$q?;2dFcB9bRhZbEkxi7!U_$z;oF|G+)}e21AOj1H?Wzs7e>&qM5b z-<#Ul7uuI{>FKDu+c`p|_{DS*0}i+g#8!=#n+`rFTRq&< zN;q@sEGj)xDirW-Lu&`Vby(CAC3HS66t@3vY48#HYRb;z9HCOuZ!z8)QGDNOwO##c z?5!&;jHTr^hh+By#8)3L3OeEro;`m5fZso73o&+MX|47Mi2BYGOvm;=J`~84lgKlX zaAl(oj!1mZYuZ`CZqV_@_&DHqc&UTBo9?eZ;w>?c`+v?FFp z5!Ju{UVf!A-DdWSftDztYjB~^<;^9fLvRPb`QbxHsFbW-(9!%K zwe$Hqx6yA_lg@YVkm$~!P}u#ltK+fIaew-_+cPM^8HoSH`32EeeDR&_;1}Tazf?+h z9EHNX1*gQkAFFpx11(X4GahyD&K3%(>QZf>Bo?bl-(<%Vs-(#&gCxLZ!G0P&e9! z(f;&}&&93K@)Hgp!uh;XqQo|5?`6O5G5G}$o8W8H?5igD`ZU)({ulQNTnl;4r;EE8 zwu$Q&zOFL&y?7@OYX>)SyA0h~Vgwq^72D=SyMve$i&~f%WAGktZsYXA?yG z5%c)P+jIf$q|9*K!{u{SDDw)4OPd{3#Fu;1!WOGbVk6s^rn!%%HSc$1OW%Lkh#@T( z+PBFmMK6a~ruNNy-Ve5iU#VPC*0I}&lGv7^SdGCKuv)Uwj=sV-mjl)c-(YSKyN`B% zZqXHGg~KSB|K%WlfjGq%hy$_Wl7;I$P*rm~T3*UpUKAfvLhB@JdDSi)EjI!!FN%MM zHo4h=w6wW<%37XS%gZ|OJ$LcFB;r-6dd~T^>8$0o;uoPUYdUDl%5#H}2tV9&xgSn_ zZ))RuKV0^G=X5^4@2n+CNFU-3KKJe={1$e)Xiei-36+wy76fcgv(;d8n&rqoVZD{` z)(a!Z-3Du3fjCh#MiLJL=S zJj-^Jd~&!tE8*?hi?&)^Ism=pSFkH!CTkw=)49>Xl-#eW9}<9O4?0$w50!~ zQsUW$jut;$P&yoab>AbSidv$CZ^v23w1``wui}%N1WKqBeeUcl##@}fop~jd67juP z`7AqLHMSI?R(lstcePSN_e8koGyi2RZ+XFOC9Rc8c~8-HxAeE(?b>)vNlTRQ`>Q)2 zm}}3+k{&&rr%0t}qwy)AHHP*4=LNxQcs~AnbvLu#@)9M)9{}RuIorqUp?6n}T~*Z9 zN~9sw8Wsu{ecaAs6VD-nr6o#8%mVjg>3g@7_C@b5>DJW|Dy6$joN0KkL%af!hMqqz zENY1o64`)`Z@=ke@sFDkB~wDBBrbxM&;H+&!47ynPM_OGeI#y=>%CFm7f-f3xJSE% zB`wk3Ro#f!F8b3($@+^UN2rwdw?E$J&QcBf>cnL`7PUkP-;NLN-7kI{ef4PF3`eMx z#B|W|Eyo-b=kY-;;aep66fst)x(kKzFV8A%iCSHA>2I}KqJ&xig~Dd96wEgG^^x^T zN~jcl;GBKR{=^Sn7-GFUVAj3H1RY58&U$cs^rZ*9>ATwbDNl^9r_6 z>;76LB*x}!DtNYMc8hODt^RtXc~Pw`CHM_c-c3egT_mnn36RZ5hQwHAcTB_){+?CrhmD@Nb7hHl^$B_v`7;=^oJd#r9oN!F-XRyBIP>=`V_=w;>96~_^>ib4mhI_oQ1dHP=} zr8O)R7|rK1$QZYlC?R`0=%8nw9(s7{b!VabIrHUnjVk-8C8DTtM@LBH4?1MGRFeHp zBD&_7>B~~8@v7KG6ff8bEgAmKhvYI$Y(cToxt153vtUI-e93hq-bii`7zB&<> zq_$S2w1)U{7IJX-3=T(Tik2uLo(bsaJp4j?1|Pa+h9gu;Lwqup$;Q6ovnc+Vs+>FVUuiVM5#ptS zjskr7d3Goy{N0ZLmSzrBq*wc|;gm{FZ zL%f5Q!^ghj953F%s*FbQK&t1?5#o)64p^twSF~2OwJN1G#A#V%&hZ(1_mM$?mM9@U za_A6WxFb}`xBT%e)2T50{Xk2UkhlSKh}St5zp;H=nEl3VQ>~%%Y?rh|{M1!Bsjz3Q zuV~*YA)fTA952|j)>pJ|weCttR0i#k7>grRN@6S^etThX@mTnMTHgDy%REzpv0&~p zXc4=(f#q$of0%(QF@&m?ON>QhkdBb340IqaXfYPX3AME#tkFTS3O59cNr;4Xs(HiN5$Gd5}Qi2 zhVY~wGNGX_ylVS5?XJ-!dqXgLnpU^O@lY#?_LcO%R7#_yE}|G~Ni{)z{8F?L`B?x* zkj|w*=Vt^!Aj8S>WSH?Jk!lyCMXy)#Q{n4F7B24~b5pfMdsk~~QOkxbYUv1-@_Dbl z=gc_x0{BZF9X+?CB}({q;C|HR_d^MllJgB{xtxNCwFLJ+U|%5yS(S~8=cD#K)Cw_3 zS1Tnnf^9KKYdP&(t(8hi9sp_ud$z>hrG2X?_VITElfGMi7Iv^8{H$F;N0@u+f~gZKkdr zgx*CAvZVi|QkoNBt3fe~LE0$?>Y$aU1W!V+hCE5I?oRYIkFCOLKh#ViI{(h?Xbkk)eA zp88)ZC7CrKU~9&FK4^Pti4w3GLaraQvn&P~bNxUJ(h({pc|ahBA~T5lU1SQmygnr) zTL=X9yTvR9$x|tn{y{|1uDSQs8d?l8Kf7e7fbu?30(OGY<@fKxnkZ&5NbZm;y{J;K z8SHo3Sr&sVW-&<1+@}tfD8YCd?<_4DcRtDyDh1on2%d;RCSa3Wtan?s8t*azwXbj= z?0(=k5U_yl4$>ml5+!^)5QDT)LQ7H!mGWmZV5Jtb7-UIHl<@6i?xJb@ud{c|L8wqb-rqBF^fUES}CE~Nfv{&meVfO|57QVg<8Qzv)-l6rX@=FygtMr z?G7Ra=?ImQtXafyB)67l0qi-TZKj0JVny5_$YPK@sb{^&Sb?0*jJ1XqgUru!mb63( z#9Qp27@@JKOfic=HYlM|h`rcYz+M&YKnya-Vvr>*QG%!Sc+Y7mxih1T{8au+rT(5= zCU{EFWfj+IpJ-pf4zxR1j>N%ov^z*kQcILj-4=tiQNr9*B~;3vA4IgTn8hF)v_uKt z4#XgXEC%TamEuWk_EotZh(YE=t(FK8sBXOZYhA5swL}T2VbNlc)^fxkU9D6~`V9p0 zM7h7>Sw$^TLY|ud=e%aWXwL^vTqvPZnv-5AB#Sf)6@mBo<{X z1u_yDKhMV-+JT6BKH3>ktduArPXTl=Pn2^BVvss^iz=lxv>2rI6>T;xQ9|Zp=-A-% zIBtctcFW^_bc9OzmM>p-sxj6QC1hQJ4w*}eG8+UkuT-7%mU&lmogE>wD|9eRoqfgJ zZEdYeX$>s~X?=wlWJybukQEL(5QDUFg&3rs+YD4nb{QbHTDLE8X91Lu{R#-gAZ=Ac z46-O|R3NJw^JHxF(6(|br>;1TkW~}}GfUZ5wDR=7R7z`TF-Yqxo-o!DC1h_09kPeh zeVgv*bf*SF&dS8vC;Go~h6V&;koj(@DEpmIc1u-nDL@P|-;ouy?n=nsF0>e=^%Y`} zy1xokN^1z;5^_;FU(qhq5+%fDfR5X zQ$nT0b_TK2>o>>snA^YaJI9@_Q9@3;fe_0p5Ic(R3bWOc@8{4OT83$E-KkaN2(k2_ zgW0R>E5snx^5R(;d$wT}Gs8Id8i3$wc#bQ?AT4(`^Cvh${0|^j-hFAj4d(Xmznty} zmGUi@(}1y-D4}PJECy*7Jz|i7*yN#D^sa`Mxtx0q7*VXWRtfPYpdHM2WnUo%$*5(8 zP${jU#URb&McY$Lln}obbTHqQJ{iOy9idWk`VfSiQFLdpl#nxuAjBsVh*u>P{|xiO zt$pxDfe`-{BZ`$0CB#bw0x?MIE5snxC*$5zqcyY`r1cf8JT1}x6;B~_hzHUUD&s~X?=wlq@4-pGl*;?M~IJ{?O5jvcZ5ob#~Xy4`gL!nP(n}bIj?gde&bNQ&aQ^e zvt86aQ9?Z4s1H+dqbmh%6Wj~fKy`RA#vJci)fWaqr{7>k|;bc94wpo3=< z*;hQVr>#{ft)ayrErLZ$QcINhe|24VyjI1vJ+Xs;*sv=BEZDmu_sqcxMoLt$qLNsU zXpDj-azza)7HkM1c^Z4eLSBrqa?gyK#1em&;4>Oyi?I+zpD|J66ZEaMzxfVp^E3aQ z-<`d_xwH2^XU>^fvzP23;OVnhDG+>?k^fTFFi|5T7pD+h$(1_ppN^WH%fLD6Dq8en@B9Wt}~& zvI)Pc`3znM1wdq7fb`^?fv(P(&N$QvAmZYg zoj_z|hXhS;SLaOUbE-TL0i{16vNlJ8D!Z$5rteqO=^$d_aGpfEds3h9)-IiCxdXp) zZ)E!RO0_&9dOgf4X{a?BPT#sSy*~VvQr~y=O&@h94Ke7(jetO{$?#(T&a^_GdrSSA z&@V6Q3b7AX#zYmtmL^jAY5$8${Z`ZOS}HgZ@z#BhgPmejW#+{r9)JNd|xni<1AVPr{71hOPrmee^*T%9vyi6OYRNnLCrkR?E5O>bt2 zt8=D&AJ$(c0$Bn?)(vNtxH@OZlF0vxJ8`TXO$4$8h+MIkS>o!PAxjLw9VJ%pC8DJV znJe}(OI)2ZWQifT+rx^zL?BDh2eKsQEOFdHYO1<48c`ZRt_Zs zSyEe;#P_>*GE01&vn3}u>J7$RW(Z^n5F4F*2z7qqrS+shov^W|&aMYNcTq`QvQ@6U zxZY;&C8n0f>sGbUANM&et$WtudfW{c1XgmqW2e({M^7(VgR+e_-K7NG zrTXTPt5&R_ODopdW&K@VL#5Cv(h|W+zNR?Ex}0@ZoU-3yt!vf}CIU*RREDzaR#jlA zS|#YE)+_vEkkt`xTd|@sf0t<1!{*;vLAxk6DOQbX(&GB=lR7KbY-bBAyR+guub+>z zsPa$~4FzH#vI21p1>%Z27PNwzvFT9{?P*eIDXuM#rDTBx2&B{QO_uuH`;Ubl2cvsxPS%9KglR*FVm83JBM zAIPha^D0q^gb3tSq*e;Akyq4>Z)XV*S>J$pm8fYzE2?BmCYsVbz24Ho&dLtVtHe6} zIWr=a9f+n1I29Op-O}_%UPb7JGp~|bDVnMRL{Nd+@+vJle=+ka$(<8f>z-D~tH|o_ zIj?{~UL`1#GOrS=SksCsr*fY&9)_S|X;Vj-c@;#g&zZdEL@vg%YMc z8K{KGioHZ|4}ukYX~k<+*5!4hw#iDj5fytKLakVrm%r2~da_n=O+`;_Q3NaNvX4eJ zlofj;RYMh_R`N{5f0--x^8Se0q6m4S0+B2BMpW!|2(?llHWhnoDy(XYBIF5nHeIhwDXs! zIoniYuLr)=H))F^WHtcew$BHr!!Uom20dX#sFlnmK*;>TCxi9QCxcq)T|f@x%ITD| z7uWAV1zhh5DmySUsQgX!2#%wrSwPyG--<>s0BgvC(lg9e>G>+hw=E!7uR#I z9p?~g_19>Kd$OQXtsr7en(*%{;Lw%`_OZPoYeb8=FITFKlFgv{qj=J2Ri zGM@thm6*_uxwcSQu$>vmp1^T5c|~>kc3w3tilDL}(JejtS;wzlbw6Nnz2n;>leWk^ zLzH(0{8#dpk+ek-ejdzxU=*pPR$w9mO=VIdVQ@ z8tqJb`cQ|n-J%G2F9G7T!^TrDwZ8I&Kf2#iD|xGFJrk>o1}$zs6Ri&_imMfsg6Unp zui(F`CR63OhRU(2PO}B?JGHzAu|B>1QZwUFL%KcVG%bq2>|=ejX0@!=T<7Ze4MMG` z`^>&MC))f$wPwyArq)bf@$FvTua`7Bt;BCYWc5=< z(9}yy*qWrGRI?d8DOEBAHleiy|Z|(Ff*_D$gGd zp;q$F2!y;RR`PCWs=AB;zgXn{00Q$zmFEvraitaC)#ZLP)lhl__c;(*XO#CjwS;Vh zY*B>V^FUz!Xg^CFLapQ(0|e%e06i~06HT{|y<`4xUn%l@1OoF%ndgs6p1Y>o$1(An z3bRD}2@VA24=Vlf*=}lS>;p54L&$R;2+SWHdH!$+wZe6K#sLEJ2i3XSeY9tVn zc@GNmZ2$!3kM`GuX>G9&evK+Z-miej8a$jocn{it#rs*_;dswSj<2QKgZU%n`NOR( z$or@1o3L-pALt{i_Sn-$-d;_$hri1wj=aeNf%zll`NRE|TFD!7>zSDH{K03Ujf3CL zY9;U2d?r?tQ=UJ9ysMY;ZBWWr1`t_Yh4V+y7DdR{3lLddh4Y8|Ew$2bD(j;?M+KQ> z_+Q!6nP2xZtDz6*m{j?zi2s#6uQ1;^gnZEhacYkvE2!7SyMNl#A=K)ikuzbANY z5TD$=A62K*n1}lXZBc}-YvHc_alZ=soauz4Unmu!R{yu>m4T~jFTS$^`oJ0)6?NkD zdXoDpx^>i*F|U`^`VD9Q6;*rEK@azH-)f2&GjgV(F^<|sPDM73+#%FTA`8UCw(Uh!>05j{uEvOZdG0KMjnvvFM2tEG>_`+x|w(r@absAi0^ahyM9VTZOT zLi&TRdhFP(g3@0)aq7*rc()dh*0N5GaV);IyCLQ-nBH|j4$?2h%a@b=2CT2<_X(VOfH4bSXluFh0xBRv%brsQ9F&GLXJUY36$bl!5I1Dk}pu zzoiJh3&28}GtROd@t~GagHS8|Z=qMT{3sj8V{1(-wM7v!Cd6aAlLuI~AHUba4n?Sy zdL2x_U0U%ttXD^=Es79NqYvCsRJBS!IQoTJGaObi-$gDft&hYkK_9L~5yw_D4Bd(c z#$kP699@!ewOVObT3%Tn$g2)*QH1n|aUic!&Z|-pY9)OGfo!)vknN?mC_>iTfyi20 zaoBI3acd+p`?zOJQDi-@2t6;?q6lhx@kzA!oj=s5#y)dzyK5g<_gsfiD~%JhIYw+~ zBmeZo9iz4=LdJnUj`(0j8~N9dz2;)BR^kO9CO>q2ocr{|bmoW0@oCUxh9a<=Wjh-! zmiO}a?h|k9(V6c0{P`|Ls1^1-4bkFkXHC6$^&9_;GV8llNA(+Wx235Up{eKAuXLS~ z8gBG1l=EVv$d;hU<`8P7err_U(yRy0irS(GzmHQrxvY8j(rPP*P%HIYQM~o1tK)ay zoS1gnrpxW{C_?v*iemVf-QzXubf#_B+S4J_O6&eK%8T*nm3q6CJ9#^Ep2qs_^qp;1 zJ8<7+lX_GU)Cr__&-|(%yi3JG&Yb5z@sj&3wNk%f<@csl?8yMd!l*5Z@cU|6w=d1# zdxAr#mHG{}?mwPMZNRkCGT(~Yq6po`!*0fuLGkd7J5%pXFLQfzYNeHe8tu#o?aZXB zj=CDDerxnOWBA!xZk1CJ)as;ne{x5Fcb|Twzj=4agj{J1ZialNMD<%yJb%dQmb=i%bt}S(pe8H5`{PFrhIe;)es%NimVaN>A=FC! zhI4nPd=fcx&b{yTs4a@{`_8X)e}$Tp>B#AKIfPoN--_aqbI*;BtTrh<`ScLCBdrMC z=LU1&^?tD$)S2d$uhsfnYNgePzzTzsGW5^m0mlz_YvJ-Wxzt|KqCFQ!zEe+rW>8X( zDuTMd^zPJ!KZJL)0&$wXWM02ssAyBL#UP1fyKzP3V2*}(@{yj^`q|HsoxqE@Hn;_ z>h=v3L9K6k_eUq6i#`?|{%YiN_x0Y}I)qxO-@uxj{vZ{I)5@b(O4_0b&&$aA&I$U? zQ4wmTenVY@mcDa(=O3pz#)cx42Lk@ps>{WrhjpeW#`Sgxwc?pqvM*ZagtO*-EYlB? ztiwcE(Q%$GitFkdEO#e;y}#RiRRopI>D|w^x(MFQ8tdu0I|n<2TB+X}jrDZOI;$mZ zQH1BoT(|30mb)7~{y|iPTB+agp7_MpapxT;r4cV*;21QDP+m?^OxyD9ddHESX^Uew zbO^N~3x?k169T6ozL*f7>6{V|?skgX+ZJYp^EBqcKOAA+y?DW)ZU;*d!w1}H-tE4| z<>=$^oiDK5z5C(4973(sZ#X?LeuCw0kN4L}+M)>0TY4A@_P@t-_s&hfjEYbz^;@H0 zpEh53xnndbLU~e{YY(gIR}bh+(}r&D5NgHQjNaw!h7-9vtQh&+z2g4U+}@q;%BkP* z^x5H~n$O*iH;zo&qKKg@jx_HM>2($QxMZ)b%)57ddq0OzEA<<`4G!yTv)XgFZj`h| z5uQgj@cC^lcVC&YtVamjO#N0A5AOeRz3uLk(idyZj@qKXtGqREQa77bk3Fa}4S#zF zhfpi6!-UfuXW!UC?>_a#8A(=}xf|ME&0cC}^rELv?BXiU;q%A2ol!*`|HZ{!d@{`M zH4EPDcJVbepSu&D8tD*frG7&Nv%T)D`P_YT*ZxUc6ybS&ul4*}&3A@lo?Ou()Jpw^ zQz`4rsNddeQtGq!HIDJ82;~vNyW1U5-*-r7x_HCE4xv_}*?^H>u=aCh=5#&b`1 zJQ-wV!;MkDK|gBzy(M#Zvw26+S4|8Q0WWkc@$Soe&+gb2-W_`DD2Grh^&8l@+w|x% z@6H~Ov_%nM<92af18iK3<2Up7srh7hb+hgcp;qd*qBwq;-gVq(Qd;Zi>l_195n%te z)kM+92~T~}wct?j`rfP@LansElVcS}VGl=P6`PI?pCzq&Oa0c{KQP;`I(4GkKi7S3 z^>k6}xOhllJjP#pIG+qn)D(dXEg6s2v*f*j@0QH=VZR>X5Nf5KE{YFNy|CmP@@n(? z)4NS<6`|uRim6wh*uiXH?kdUNbQb_~Fg;RTEo9Xw@n6Zdc}P zJA_(kY#e8s5iFTMWZep9I|@@CG2deSd&3Qg$JzUhPs$ch7J+&i?+ht1MakVv}Vr7=Iv?ZExgS8YUKFX$}PDV>S^p?ZSz~ZKQ5i|9moAp#D|~1Z$50jC-!-5 zw#8%2`MW!WTB)atV(`a@SUj$suwK#@MdbLaj9O!GYZU=jB8DccwprNiOFKTumoAhk$r| zu-Zyh3C`U+M~!kE7GUdqfpT*=?c(lH}X1usd#rb1{b2mxCTZvdhw9F?L zOFdl_7cTB=`%#;Gu|C(Y%!(XHMQnW8e&&(Zir4Q}?N)LA=+na^)Ji>#ea?>OEgt2U zUqx+EgpLpUA2YABc)Wh=-yA}%)YI5kTYJaw5#n*{xQkrwD#H8fuD?EB{&GZTdSHdk z973%$^W90LC?}3sJKAEvGbVDX84;ZG;@;H}Q>MhbuU^x!)s>;Ho-T@2`)+Ud$BVmm zzpg)Ji>#FUTJ*w0QJi^PQ+IiqP?4Rqdk(EFPcz z`ZkyCo z?>V;O_s6%lm=}d3Sc5ZTo+jr~J&kevd$`5pj=w$VVxS1@2$>ICdv~{OxwFNi+j&no zgj%VmQAO~So)zcwb-q7`yBSSv6`|uRiYafrW$}3Cm)ARlTB)b;B|P@LumR$6z=?Zs zMYzdbMR;HJAHR0^YS+&6>|tNHY*#DIe0N5XJ0{i#Pnlsq%AQv|eI{oY5s%A%eqy!7 z1ykbp|2oT^#}Q_Yiw$;6zI%|xV|0&;xbNIVO%X>NG2MLF+NoY~+7OG!fv;WT5Nf5K zE{YfS=wtC1K7Jba?wZ&tLdS>i!8iYD@pydC^BqF1)YGT~`P5}$JH%t?Px^7kq{&@H zcwbGMwn=yh`%%xm^FJ=z)k-tpodB)nq$jmfEFL`DCnrO(f4_( zrOrp4``fYALVOPvU7JUZfg*(UggzGRHO%6%?5<-SLao%(cqXpAfyLwKo%fE~q6i&d zQC$CrqT=_*0~?HV2(?mAWBwR6I}AfSMvp7FKiK51L%4c(@WeA=FCq7`&xn!@|!OO-_9Wb-9{nTI~%C4~uMzbNA@vVd3nr zCZ`XUy}3hM6rq*o@Vwgc=5RH}QNKCeA=FCwOhqyNoPEOy=;NL~gXU?ABBVcz{JryU z3LD%vF|E@3X2(@iEBSAMIC;s)$zf@auvUarfdk@4J#GwVVH^V|AK_SYYNfFOM|jSj z;dbz3=AE^bO)ZbDoi4zdu zErrZmDz!xs;x{0`TMC)CZBc|g zOV9^+OCj@?973%mcY(P7gMBS`!CP`CM&z5ydD?hO_9YD7Ql%bMguD&HyWlOEcfnh7 zzok~{H{>cfnf<+M)=V?a&8!OZFxM-jYM8mHN$iOCj@?g0?6^=0W%hyrqzNOQj;z zN@h_Yj$W{>c^AB;O3%c|3PMo78E?sQ7rZ4h`)wX1vtJSN?Sqknw`AT0Z^`|ZTB+ZR zw`AT0Zz*VtBIMl;eSo)Q-UV;TA=FC!X1t~Fr)4LRw-mHR5%SiDKEPWFnYUCbLapST z5eQjTbEo@d&C>bJcuSVM;4M|^QANm?KKcM}$-E2Rl0&GK`ptMtw#o_KQqUGf$d?TI z0B^~>3*M4LsFnK7cuOJkmV&k@LcVd(2Y5>%^Oj0QsFi#n0Ri5UeRG1hhMyv z6Tn-tHDvIXD)p!$WL*n=fVX7c1#ihA)Jpwkyd_(c0dFa2iz4KU9({nfWZngD$syEA z{bszS@Z?65$Xg29q6qn-M<3uVh0I%W2(^;+03c+?geQ^OJ0?MPNtQa{cEyC}TRT|Q z&`Le32w9UwAK)$7iZFOf4xv`+H{>cfnh#v_%oJeuX~3TQcv0w-gkiR_Zt7ErpLZ zpG4kL&=y6=`W5;BZz*Knl0&GKtbPFj-jeMPg11!3`Qspag3i;%Te92*Z^>07QH1PS zpbzkt0{73sTXG1sQok8*$-E2RQl%}5kkwlB0p5~%7rdpQ2(?nb8E+|M-cryOMaXI` z`T%dK%)BLsP%ByM1p>UKka3C3j|2SRJgr(`FO^0p5~vKfqh6v_%oJ9}NU}OXgkhmK;K@)NjUHvRMth zrAk{AAv;^Oz&=YK$&?<4xv`EYYhZ=OLgWgxw=uv%9xP%HJDv5@M_LZYvlNGSqdXfub<2Utj5nT6yKYNdWd?yffV zVS4xd@z)1!QG{@c(8u>y`1jyX5A967*4@J))QYt&Gsg=EsR_t<)R~3E%8~7wfI)a< zK!Al5GYhHGGv~r2U+PpmSV%FmklYz}MF=YteSn1&GYiQf)Ji>VETouONPIFhu~meQ z&sa#tfdmW5A=FAeZ7ifZvykZBCbo+3z5)xWE3=RsLaj75#zJaWTnxg%Wc}TC#l;}3 zN%%_60=U!tcw3Hq`tU@*dfHe>c7K3{ISP62DlQs3`*P!7;Ot&<9vZ77wtH973(s)5bzF1~yno zm9{8C$7d`giw9Up4xv`+X=5SPnT6zXR}tP z)Ji>VEF`->z(V3zQ4?E5==h9Yq7eC--6B=`y}q?B1ml~(S+x}U`(ulqHzF&2`Yy8{b} zt5HphBIGm|`Tz?lWfqb{sFix!SV$HRu#kebC_=|)EF_BuSV#_`R_bYEA;ru>a=EJr z?<=s7>dZoN2({A8Hx^P{e@Lg*Lza_MRFAM2P;UaO26m0pPVg02NGY?BTrF0ta+{}F z?^8W(EF`->z(V3`Z4)&`U=7eR6f7k40Tz)Ji>VETouONI_c^;e7=bQp_wQhfpicd{?EJE5a5J*6hZ5 zyWJD0(j4R@D|`hOlAUA)3n^%Y9_($Jr&+m2J#8!`iw9UpE^3Ov{*L(&EF|;+7LvsS zEF_0eEA_OokWywLx!5W~$7d`giw9Up4xv`+X=5S9%tGS&Zj-x;@V){IDP|Uu%XYQW z%y%`gx&L8(fQ1yWyJYbI3yBrf?V2k_#zIP&h2*MDOT8Udt!rXqEF_BuSV-JOZdw!} zRT!{?1s0OU11uzmP%HJcv5+htU?FiQu8FN8bbQ7_vUq@nAzP z2=6PfkYZ*bxolS}&3sp3yp*~IR7+z*EF`O@3l@^AO$9!Sd7AZ|)YC-) z7E;PAq@XQ|keVat11uzq2UtiBp;qc?V8>qo8fwfRkcX(@!Zd;`MJ d9LKo{a~t~j)qrp4!~SY8;S0^Y1D+4eh6guJ^?M%+ASEdNfl~!X#}e-zCf!@ThD*y{^$A6oqM0; zgMq-|p7Wb?=A1KkX701j{eS;m@WXBI-~Z6&$B%Lrp%B|dcKN>-^M`+WaYZ_!M)i0nmAp^H4&q_&lG7YLq~?x7H(S)QWk_>!BJY(8tX_YDBcMXrr8E*K3enS|Ouar<72Q z5|r~?H4(6~e)GP=ZlE<+jgH$sb0yS@a=znOuKYSj-XSBSl=aQ9J??5GaE_`IgL<4R zcKde~=3}v!9LtDI4mDRoePHH7$7r2vA~2Q`m^tZoLai8KV^ltNXp}J7KMyC%T2x9z zE6s@YfSi!wU1|_%J`a7>L_njlQ|5Ws_ph&sX$s^7^Pp8F$ND3xlo%FO$d%PPsX6yM z-8m`e#AV0#`hD=n5C7uSct6PNKlB97*KvOwM8v*=53E#Vl>XWY)hN*(l@e-Y&kOoX zqf(6$Cig((Ge^I29!m2$?o_D{)hKas9~eumDCa(~7a^)@$MJHtp3(w!eR6$JEW&2KmIF zw@$sVEyxF+-f8z*?RM2DLEqs%*hZ+;uZ{#CmcyD4)hIzZui#^Q!wi3Nbotp&BLTT@#2rDkap)R)_fD8c#V-L8aMSv|aue4VRC3Eh3td3^JW zVJuW_&-a6jYR-)XIj@Iml(2sDQROvPLal7Acp|T$YLuXyua738S}QF+w10G5&0Cr) zCDe*?m^tpV*vs*43A-B4YLI!Fq#XL{Vg#%}=-oN>L5+?J8J*wkLkU`u2%T7+mO40@ zsYdr#Jm*OMcolDWs!;;65`%fr3a1HLQAUJ}Dkq?+6N!&L_9=YdH7ozUq#Df-edZijBXmv)Mg<>6mqNs7n+Zgs1Uiv)JE2xXqwtw2yg4a{ce}n5p}}`*d{-w;ncuH-AJo(dM3sNprVo52C&38U zzGGg|92GTn0&|K)thrhFZm4GKt5*5&&)W%TKr?p8^zCP!_<&WFpZIHr(#-@Tkxa+m zMJ`TMc}t@5yC?g~$BzEN$%&nzCmi@l31qQOfaY`O?iqh>V)S#r>#lj=>wWCb7O;p;E1ZLwk&Gyyfp^X5 zrBzS~%bOnwnNEG^SZalvesff~FGKTDkX-l!5EcVX-3lQYHf`uFrBHA>)pMY^3(D_v>M_0F&8 z{AaS06f-TH%Dl`K3D!>QUeO&`WrZ-_=83=^mvT%TGeX z$HfU+A=*|SQ3D?&P!G!4Jd}u5@WJ`z1T{J?WIp$u==buGWjiN17IuBgm@SF$w+1{_ zf>2Ep5pty!#J3FT3_o*prB$N#g>mzEE(2NY~fgO~QAd8d{73UYS%X)xNO%o9+xPIjE>AgSyOlS6O+xnVa z&1iat`}?llC93$Bk8a8cp4-xS9Jp|zT=~@Hoqyi_W!yhXwStT{LrOfda%um_^{-zw zvtdnNHIPZ9U%X&x!~{qs)GDn9qOqtZ5uIw3Kn~$AoZDZzc1!=NhsTUqo)BsUnZ4kg z61(@x*Qdf(#${EyOvkplXyz&+W*O z<*I`WD4|w*PjK$p4QqOTxcpn)^EbY?Uq2fnSNLYBCqSR8-Vc{v(H(#7IL=f)UYwmF zlR)P~4qxsp8Y3RMVf?ja387YyG4pUPvGvjY(s!Qk9(-_Xa{s{YTvZUiv3LUKVCUA4 ztSok3cDDP}qhIT*rcQtk-(JtWY47Q>oz6?Xj*AToSWTzuDJEDPj=^y-JRsB zPJqUDUtjayO$R2si*LCpAuukjG;h8heb%G?4H@}CruFM^=v~%BHF~DT`WR#v-NAY& zp;la7p@Mi{u^u>6A@=(1PQOO`dX%h(YV<^=XFKPt9wqCcgj#7vd_79mLp5~*GY{u> ztU=a83COh4yruQP>0YX483^^T3i{_*D``Dc1DS+%yO%?^Ydw@uE6DJj*TXv8Yful! z@PQMub)|nEy4}`CtcPmq1n97$v>r-8rj=$St%qvr1n9gTN_k?Si@xViWU5g@Z%ASPSiXF+^T_KP za9WD-s#SYbwr|HsAfww6mF@Fhj%S7f*~N)Q3AKWZIR!#Z#Qy+eq)|u! literal 0 HcmV?d00001 diff --git a/GEMstack/knowledge/vehicle/model/meshes/front_right_emergency_button_link.STL b/GEMstack/knowledge/vehicle/model/meshes/front_right_emergency_button_link.STL new file mode 100755 index 0000000000000000000000000000000000000000..4180556f8713cd0b379f22a6a6a13b6e3c9a4b7a GIT binary patch literal 38684 zcmb`Q3Ak4C`u>+w85*P#MTG1&QJgx+ey3<68jzu5ItryhgEUG-Dn(^TgG8yeWK4$k zJ8V))szZl}NTD2K<{Ya3{oL!_tNYn>uHU(?|GBQ;<-PXveAfN0^{(}NKl|JM?HvUF zfB#ppLJ(wT9#j|vqe|;Od|`2T^ic(s-+eUG?yK8l_7I z8ag(!v-y5}y>;>f|Ao+FDS^DS9VyJy3?+P*Rl;}c&!h3Y8GI*&vpz|`RCyv_ztp+$ z|M6WZaloiPq%+H|!GHJluCz<9h$rgKn$2U4X*Dl)+MGxEy7p^hiuC+Ep%o>r`e6>~ z^sqL#X8U?q+ND>-6NmM`*p3yX<_w8Xm^_-VPrmP*xMq7oD@qjCxsUXY4u^o=*Spd# zy&|5td1ghs8-n-t%#E)(bva*;x@gw_@m(o#=>GNju3l*|`MjR;I1zP5SnGxS|)mtK(|m|3-Q^2=1W!j~3~ zC=H3ds{vMpxJ_q$w?VLV?)c>BC4CEnMLh7mR!wcWJ^>RmOmtKV+Xj$u+)K5Kz z70y`Mwp1%h*tN2Za5d-^Z=C9I>X5?L!{d(7E`N3Js?a*MxLd!%hXyw&)rt~!S6W7R zSB{y}F_rsg&%$;u*LH+<`TKbH)@xF`$6ism@~a&=tter4rDcTo?x?Xhq?)b2sBrGe zw;Z8edLIYD?%QroReUs6*tXg|IjtyRce`bTYt(Na3{A~F;ctbV{1am?Umsb1e+vY^}K(;cB*x|Re%x3+atC(e3e z!4;L;r?jGktvHquuIJk-S4q`rzGlIm?=NwLcKJ2x-So!ff%PgDzp%J_N-Ij(+HM)) z+WzkQOOpq8s9C)F&Kn(}UET&Z?CP8BI{M_|=RX>f(uxwcwp&JM0J{!2Ir;2u&5Q54 z;uc3}m)bxOyt}M&V)=&l#a-VYnbJx*BE2``on@7?cb<6ZpAk_PXsl+TcLf37Rc?Lm zdcG^I*z2<6;+*(8yjJh*>YKY{zdk&3CA7<4TSjzsbGQ9%5U;LQl)z_`vApmz$0wLO zv0x}aK_#@yURy>;Y_D9Ubj{S^#deoyMG4$v%n0w@u5IgR^8w4wxN7c;_{hzVDEQqa2i3rsjAw98&2q9B^0 zr4vtVQhXhzs8*D~bY(_3+cBw2Hw-?u*e10S+GVdTBU%kg7ggQAcqCQ>ttf$2f*Ii& zg%zi?_kwR0G{B0Zgm&3$%ZOIB()4G~EI0 zWkjoUX^YS6EwI&DD@tH(XGZ7@Fo4qJkj3-O0F=-!duSj>3%4 zePA-B?`J`PM7C7=!JC5{nk{KX3Ah$BLWhHql@`yR)o?nDObP9>*On1k zU+LfpA2c-U(~1&sMrMRAdViyT=c+IMwV|1%653_2Eh8i@%q+~ket2Elt5%eN`*J3R zdl_5ij?cY(c0(Gn653_2Eh8jg;kkbmBx&JVQ3Bn8%|!ek-re-76SCiZcuwJWJx7{T z%dxb}n6mv65Q$wqFDGGN-&@&B;7Bpc`13uPvUGh{!&2As%nR%Oh&$U9y#3 z&mQ+Jzq_|1g{y%Qx&kOsr``$t1iS3m7WWxSXqV1;Phjra6{N8oU3DB^cj>$~4uY@4 z^+Vs4R+RY5^eae=p8Y|&ccp}O;ob7;{_)JOTedi3?`qnD$G9hBuWbd;wZxwXt}c%i z+C;Fxh{?--itAPX1HsRrJRzT8x%1FtX_tOBJ_9QbuZg{PoD*N$Iq6mRgjSSzZs$X! zyR^)ddsj+mmwq-r1GAmSvUQ?#|L^&F&vTE*u&(g+ANLuwqQr>4Uy^9Hvue3_rG$22 zeIyaCwR&G+!m(o0vgp_qe7*CPd$~(tpJq6zmB8F(msON_@SV5$^~uX_&iFG|Lc6d^ zkoe&rlap0(qqIuF732CA3S8!)ItkiAD>zFypGH&Mudsgm#%r z*g5_2GuI~-vm|a^HgWd-)M`ZuJRf{EZQA+sP(r)>)2yGlR+PZ=$PCQgav4hauDw&j zzbn08ajkgfc18Dn?`lN}xyQ=ADb}oai;4 zmvR|pU14P}A$R3}A+&4XUZNExSRC$yYhEQL?Dl^F}wcwt|CIa)aU%W(uxwe3UmofxN;dvXqUfx z^gPV;?F?-l#N8LZ_m&yE+xa>)eI>M_1n%RI?!30#yHY~C^h*0PKl-wtc&t%#KP}Pk z?)1A!PssI&%W=&td89uz%c!D+yu-N9&|_)WzCBSZO2~C9m!X7qsTufph3gZyPtd+c z#&zRsyKd@Tp3sUC@*4k2s-O8j2f!jLcRw-f!Xe=bE7vCFCcT z8t2E?;SP(wE3GJj>qY_=UM@ok?ZW3o;*Y+o6(#WblYj@6%TPkQ^s4Xs^H2hJC^P=l z+gUNw*Dn2Re1;r1F6R;7x9@623AxfSpP__y?RzF_MG3hV{`j2p%mH_uJCKIBNg{^ITVwj&a(U9%=`{|$oo`+ZNMb;V_l zuv%GHx1OJpZuRLb&>sybh+D={iEX0NxV0F|4hg4A0|d~yMai5ES%RB2DFPQ5`Qxnbs+Lg?$Io~SYXbrOSib&Sbzi*HuoTsCnDiRsIV;_?~9l=j5b;g6A6)w5e%KIfRy zp1Aw?nItxh921v&DW28 zXxsmRBAY%ds=Q$nY=KRmFMnDPQ`!?-OFk(vBKPWQ%P27da}YCpFYO6T(R6-_+If(` z6txVcqxr}wN&-{Vt`)m5E$uua+Gk*jX7W?iK96*MirTe`Xis2@lE4(T&zuCNsC^z0 z?Fmd#5}2ZPU$F~Q)IRfw_5`LV2~1JDciDw0YWGz{djeCG1g5AxAMC;uwR<3(fhlUwIlFqDUD2Mwi1q}gC<#o_IA#gEFhz@$_5`LV2~1I& zS0pe+i3(fhlUv5S|B|L1|B5iju$-H7_AyUZS)oFhxmVikkb7F!xc~6PThT zFhw)+Y@7Q;v?nk{IZH4_&B)5;hxt|6WGLrwn4%;wMKdy^(n|XbOi|86Oi@^TGzZNS znej(Y#1!S+#T2!SqWl!KcTzTk%e|}d>E-b^rVmI>I`Gk)rQ3JHwl8+%wW-*XtDlKa zeriodccy~iqUy24TTKS0uKRUbPAf{hStmz2b;l~a^U6mLO<2ZPqaJaDcInPk5L`Uu zQD)o_yFaHDCDK1vjoUlS&VL0N-=$t-#+{rxhi34eQE`ZYMth zVpyjWm@)9=yBwii*a->GgF8hVnl)v{1#^bww4y}cL1UP)b<;!0*!5CdW;{J`v?H_& z-wB5q*vkrnDs?(Ac%Ijt!1#-~%6@nO%qLDanQT4oIU^#(_1m+mJA!SbfvnbCM< zyPQ^(C^~;WGsYb~2pN}Dy_FeLH@A0$cKLnk!y1oZ#(wuS$!SH29)lM%qjjwg$hhmM z3C#HAcTZ@S?$rdrpby6}W7O{IIjty>ZJuSuv}6Nhti0qtX55vj<_PV=cgXxa!tdxS zc9_hJo!@_y)rt~(daeks)eT?ang9BpnatR7+&hlYE_@%&jBsaS(7OAXQTMZ%S*<9s z_Pf>0=+j^_GJbmgVP?Gk#Y9JF7ru{XhV7jMLH4}q%-B8R#H?17s93U=8OOg^itn9k zKRcHhb7t-52<^gm+sv@N8eH9_Gnnz!8SlFNJtgEdzN7zT$fL|S@AJhmJ(hOK*Fij7 zE6j)=@p)V;O2|3Ig5b-_;d!(>s7XQz?UE}3V(jG)@I10Fj!I}n3HfY5eA;U^&tvqH za~z>v^2x?Q%)Eyg9T%-gXhjLR$3S#{Y&tWF8-C#k?UFkbMB}X!n9=6f3Q4UfAVotryCyJTX3_}hDZ!)rCP zMN%tD$m{}f>83%<=-%%VM`)K!J`k^bd?_ZXqT7)h#;9|#?1EjCbgo3I0}d! z|9XZQNB4Nh5!xk&1EPA>e$42(?t!FMln~bfvAsrnX52hssqToV@80dg7|fA9aN9(to3$Kci{JGFmL0kwjPYGd@ZnFP*ncWWYr; zc^7qrcH!Of-|oVn9Ds{v^Db)dDyk@f>&6VYC^F!p*}RK7Lc4I)%l>^31YDFEa8bLu zQAG)S{+Yasf`E%M11{Z-5!!`Sn@0+NZV4{R47g}QD@wp0 z!fSQISMUH{r;G)cci<((R6(!_#30;&Ka8a|@ zKO;)y>mcBw%z%q#w4%qAb4t@inE@BgDxqC+ML@tsnE@BgYDEe8Y(T(8nE@Adgm%d% zo1u#`11_4?iV|{OwH*Xpl+FMbb%b__8GwL`G6OD}(~1(}C?MdX%z%qJ zLc7FpK)^+r0T<0_MG0{&5O7guz(pOQU1Dk=;G*sMTwFZ4~^SZxTE_0 zAfB7Ji5Z>x4|Iff;m&79xRd(KgWoXY;`Lo}T2bPs!%k;L`#uwp@$&YAl6I}O{eGPz zvnIV$5jyd&&{og^9|Ha3}Tk2aA|7ZcBrlR+MP4Z45IG z+tL~tucSILW7-e!cR7}JVP#-OxRcuU>hqcL$&uA^T2W%sEt8pX#M1@H7(TEoGb+uk z?g;I|3df9aCpCHX<;)oJ!RJ}6C=okuIy1(lDj*|1qdzlx@6L=$ zU6y3EqQsd?XEUR)Rt{b=b?69YRH*f|BeV;~5ne0qq!x7S$Bf=ygpy=i8W3wbu2H&@Px0Gs2zJX+Pi0jJs|-D617EF6%y@8KWA^g!RRG-ocC`SH6=` zLc3sq%m{Z<$F&>6jGdn@PHRO8c@2BL_K>m3xA6?F`u6VFK8PauI*6@j4`xQ6#wBsB z=yBzoVpyZLjp2FJIqu+u651u_2O{yw0A{Rd+cBXPCFHXKap{iH%&66Vj3cy5K3Nbi z74>4q+>0MhXhjLR$KtSze#4k?XlbbQDLS`3; zJrmn8qjl*ij?gZdV<6%Kn=s>nS5Hl9MG2X~Aez7SH)brU*~SstB@-OP$1m4mMwj(1 zlUh+i))El2C)Hy{&zHJ5Lc3%o0`b)E0W(gCbxvwU30V_CR5v&sNJ=M$@K4Y?o8^SoaxOs&z~7^ zQDneHnE@Adgm&TX$?V-pg^Mx+E^2p4R8a!=aVGDg$bgG711{Ijz?^3W zTof5_QD(qJ9id%VC3vK8ClxNr47jMR22n)`tXIr{iy{Lq$_%)uBeV;v9gh_5q{2m+ z0T)eZMG36C%z%p`11`!8xTqtv3#&FW!ktvOC^O)qwmL@@CEyRtfQ!O1;G)cci#kHP zU?1TX;Z7=Clo@bQvy7;s1U!fta8YEyMVSE?b%b`oqIjfmClxNr47jM-QdCg_KF18W zD69`I$_%(@TnX)h+wn-@PAXiK8E{cE%c!D+ye^@O=JGCT_WEZ;iF_RdT$CAb(TrB~ zxN=Tux+u>BE}B(ByX5>pz(tt>7d3A$yH;r>F(VSM4khL8IT$JlMT+|WTC1wBuF3JqJXih6ih@*gji!uW)>Im%;!vO&oWd>X{ zrxhi{wLri{nE@Adgm#Ikfq;wB6XBvcttbI~T#$EB5O7g?B3#rFzH9GZW)Q$d>AP@I zx67#n^0=R9JD!*&J8zD!m^Uo7bX`XhW$Ax?W_!`98()nduySz56W>nS8Xq@zcxp+* zqMTNgD5!sZ%;=uk0mvx5@2G@j)SrF6BeV-wn(r#yN&V=@HVMmEKl8MlR+M;k-s8*| z(5ojhmW>$aM;?yrUGvn*8uR_MHl@~GNhKfl? zXczAMc-~$?RGPem87C(Sa#~U1wAu&7?OM(0-3i1m!3Jh*T-($U+Jz^W8R1Uq=}R^; zqx!tMIjty>`uj1=SXnoPjC*VDW=5-%3mlpOg^9|Ha3}TNF4dCuneSe`GpiLPHrG9e8L6FzBIEES$1>xd z-W766XctxnW`sMb-@J1KGbXj$kkyJ38!KPNjE#eS#p-Js}&`7 z{B|QVj;~`s%ei!0D`t%9I^Gf51>;~wxRd(s@uxFm_~*&2R+M<;iJO_Rs7+&J+|&(oMJ)n+2jt) z*suQwj?gZ-A|S?}+MF5Nuc?>NiW2hKfT;i5xy%@~?R-aQmwd7y)^u;mjL{$TOK3$2 zxyL}%S#<?km3E5!xkpXgmmdoz{pMa}S!6(25fBtRUmKrOlaf*2b3|pfyk_ir?=-cg_?ZIV-Cbgo3tR*12 z%=m%pN2i)6Izqc-B?8gvt5=zkTYF4WD@w?k2;%s~tC?|Ijnf^WU9zHrsMPWyX1spb zNlC3JA!|E`)2ltqjB97MaD;Y=8Gu;weGg`guih-F6(z(`K(xQTD>FunKgSW;C58iH zYx6^y@sC-}lUh+iTnog0n<_A)%ggN@p0DBYfB19Zx*9liy6+dVXA!ICnYoW{G3%JudP}@|KCO!$mWB7j=Yo;oWiv z67~uLE}F@^sJ*MGq6Ds6I`5(&;G)^Qi#kHPaMgLFa3>Wmn$5eYUEQdn1U`Rez(tV( z7i9)q)DhZ+yN5>#cT(Y^%z%s9T@qE4z z?NLPuJdc^Yi-LfQG6OE^2<^ht%p-+6sc=zdz(wt;jVelDt}p{GiVV0YGvK0*&@N0R z9x2>Og^Pw6zf`g56IGPJd}Ib(6d7>QT;4?;p_pI;AmQsJV^fQ#Dt5ml7Hdc_R5DAqx^C^O)qj?gZwc05wJlL{AQ z23*uuwWy*5)?H@6MUep)Wd>Z-5!!`Sn@0+FQsJV^fQ#Dd995KnKQIF>iVV0YGvK0* z&@R{qj}-2t!bO<@7d6X>DoVhEm;o0>23(XGa8XBS7c7cL3U^ZBqRfDc#4|VrNBAz?Nrj8X z@-FIjIh8(2 z{hrl|5|6K|8#DUZ#Bn%})~|fXj5TM}$SI*+xYFE#40lpzudI}?jHgfiIja>VMjm-B zGip6m4;gi*{54_cF{@&=oD$lFJBAtIPU`T3lFXR8?5nI+l<2f@Dl;kvwUP1Od;OUa z`}h7iCA157J~P6d)PYNHV#eFYe4N#a63db=GUMb9RgiJQjnkMh^`~8q&@Mc|@w~l) zc>Cb{m{BnJ&8$|Gc&p0>X4DwC2eZBSljoQ*df^w2&@N0OW`sMb>svm~jOD*&vszJN z&7|*{(fi#`k#Y4GYnf5`uWvg-yD(9i5$>d3c~U7e7Jc(rRx3&zkgF88`|8f)RwAS5 zgwL4qpN%Ds&@QYD%m{Z<4;%3oGcwcf$!bN3`PUu7j24*%$jF}mD>DxKeYPXC3o9Hm z!kyG9zkbY&+o$%+YDI~w>egjO_RulNIO3p6NxOHK{4&ZB+J%*x8R1UqslC2tM)6BU zS*<8hBVC^vU$;#mqvgX@n6cu9vmK#bFb-yfJE>b1{LGB57yl)z6(v?RJDwSrKC&G~ zcJPIVFr!Y(z!BO7b7DrgllsJ6zcb^tE2m_%qQpT18#3dwqmD$znKf!LWBBO)j?gX` zATz?9)WQSzFyoldJEgUvguE`oUmE#Wn6c-yO0j(qMe=nJ&mXdz8Rz}pJgyZzuACEy z+osm!dEEc@3`b~}T#;B1ytwdJW*o8ct+-Z{kk1Chc~?|t#y5iwNhqOR^2vg@ZtHi< zSl#5fgjST0dknq!QXC>pY0nZye2x$^*VnXhjKe6cBx89m|Zf zPCq!Qgm#IqfH-#3YWh`;{r{8DiW1^lAlmQ6s5@c8Pa^cx8DbW{hpVJE0XN z;EaK-wJkCYLA0CnX3W;8W{YbjmGE7AcRYjOgWtxa&EY=!&+deE<;@bu+Iw8&mEAZ^~11`!8xTu{+L}(YTA$K6*q9EX+ z*}RL|=Mhzuz~|2lxF`s?Xg2Sn_IX5vcHv&&*TbDuxF|E=qIO?J6(w*VGXpM)47eyW z;G%Y4MTBIm(E z6Y)slPAXiK8E{eatEi#`e2y7#QDneHnE@Adgm%FOd8BYB6)wsQxTu+BR8c}+m(WF- z0T(rU{WGFOz77H|$_%(@Mk{(;IVTWsQD(qJ9id%vMbdOpX23Z- zc0YLU+RvmZA!{NCxF|E=qB$kBOIB16a8YK!MQsd967K>57i9)q)bWMa^509TQXk@D3AGc?_- zKQe9^)2Bb~2<^g^j^*tYXMRy?JTtbRJ1VOcCGeYEnGyaz{lu4RnQ=#Uz9X~?cMLPa zozzRWEn`NtZwF`JRX}j+Y#D@JD(ZhPU?eS{D&Dg{%}K9 zD@x$E-ZH~}XKoPu{>Z7!n0ozGM`#zGU}l6nsYk6iJYk>5=Cxh2T2TVOin@#Y7ZOBjPI_x!V%hql_8$DR}kmb>%xo|met8> zMG5>iWoFp#V#dF1@4SZ@HrHFZKpD@x$^Ve>rfFC_%QO>Gu3qkY2}j?gZc6Enh{)ECaZof-GFtC!J=67shW z@YfM8y6*{QY^+er5!wXSYv!uRLLwW5UFV;}|&p398ZNB`&u?UFkb#N>_rn9=y$&2gb4 zmrQUFXB|@zp2wz+39Tq0YYB*w?&mY3NvpdYp&6WG+aq+*Ox{HupAZ{L zJm8|tfQ#DIjVemu^JfNJ6d7<)X23-qpB=L8 zJE?F{X23;libfSBFz1p9lUH3|*8Na8X+aqho0o)?j`;+)0ItG6ODZ z>v>dB0{*}Z`|B}uQD(qJ9id&Y4<0GpNrj6t11@To5ml6c2QkC`-V9xo8E{cYXcsJs zM+$dR;iAldi<&J(6(!(v%&@;uLlIm(U zl_*0OWd>X{s}&_=O+*GIm%;Ge8Dh zlo@c*tX7l|M?nT$lwJZCb%b__;UEJp$_%(@Rx3(~Yas(J$_%)uBeY9Q4HCfMNn?)DaAb zI_4aBy4#F7q4SDaQ7~f8>D&99s(VkJJ1l zMt;0ETR)s{@b1J+NAG^%g$aN6exg#HebfcXYX7%krD>PO)s+vQ;r_j*=A&IE6s=GD zyF;|y;-TvG|2*4yU6@X(E}b~tp#7*H^vH^5C!OjL;kb%mj5fzts(<#lKw^w)(yqw6 zpWXnWUJYke+v>|=>4?KJTF%|6S)Tp(R5z=YZmY>BbeQbMy>mjd{KoF5NsQmFe!ckq zyQ5qTwGgcc{$8;DDVvn#uciT`!+zR7iV?S1$*WP zJi4PGnr*a8dF#{bxwAXC*>QP~S30;XY5&_1`L$d3a9)aLyqcPW(*EU#Wmkt#3&&Li zf1mflkbHJ4oz?!=)|NYU+q3~fy&BGH)+!^)m0$TWWxS?4pOtsnZ%Kt-(|7-S-u=K9 zZdN*5`qb1sv1oYt)|$;49ET!^UU>Dmywi*ha^zPZGqn8Sz?KaV>P3VelaH}MdU84T zi76>9pFVtE-tnUI-K-AY=iGeBgt--Zb@}y9|F{Q0@r?l{y!v?BQX zwrkJIA6tL1AQpT+uDs-uyBZ)uFFhlER*SD6Rc?0ga}CawA{gVxMXwkDk^o#Gz z$X^(h*ZLSu4xCs%cIr}>eIY`<7~`dTXXKqbDxxxYQrTh5zZ@d8gosuhFU+4kc&fy> z`rAq6E?dlTS1q(CBAC^DKdaVDCzS&}f4|D;{{t~U_;*3bkr%|v(K@soQ?+3XIr2QT z1ZUKt<@h9q9C-tTdNrICv!wUE&lR-Db#~)Qmbh6-Ub){jH8);8wj6ZCgYG!gLbM|I zTk=>C7xz7}od3+628hs0&j^pTrbZam;9Mz!F@$LnLo%@eLcNFx&vZ?VWV<5p^eaI;erNY`!&|ck2=(Hu zq}vHXx^u~~q$B6_l1}Zs6iuI+8tKjsp_UNA-_nC6hIHo!2=!_>D_P072(^Uc^0%x8 zC5Eh)8X(k*i119;)X0j=966(h$0REUYePD^-9=#L3@FA@Wt zGs7OoAwr8Hh(;Gpu=f!Jx^srTK?8((aaQQs33d~LzzQIHbIoQB5n4h7Rt5=nFM_}- zBU|N_A9a;cXHf)ag%wAFy^pMYu#(BJZf}54FU|^Uy96tJL15LFVQ-*opE^s3zdQ;|KzKoD6%M1_<@ytgxO-utO3AR>;}Hxjoz(4lC~j zdjPkN#=0%R4#IgUn(=CCuU*G z1qC5jumM87IFei&LC6(!h|m%uB(DU4{YUoDGjkjwv?zkJk~|g!_Ba{#I1Lc$#aRgp z1R<ZSm7EV)Qbo`CLcq(K}L(zb2lsLA8uUf5)uP@gA98E7eg&X zD}ukJUkL*Hj|}^d28hs0&xoHD_BdH^H;Nt7%}NoBAstm>NXKz8bga;ezxBNN7}C|u zk<$_$lXNwSA*&3B2rY^rT2>i?kX1$lgnDsSvVIVRtTG%Tw1fy*`v?O2j}-e4hX^f- z;H+e=B?#Sql9ieuWM%2juB;~A^^jGj^HMb9x%~%MmJXp7j;jd%mi42= zkdKCdNIB}5wO2yrSD>>B}DMItn_78*ne=P-vAMM=^5dO$REGb zcL=qF>v zZv1bH;J?uFzYzGhoYv(dXr-5+YZ|LV_N-%S%rv`x{Rn^ z{C)fX5ra|nIMj=?(lbJYO7-MM zzgCH}G59Y!EA?VLJtMSQ#2?>v$S?oC*3IO}|6(XIGS0A>y_DHpp+fVzFEM*du3DJy+_*7RdT~~I zMjFmaSd`F9vd{h2ks2b@5+fv!S1>E}B3jQ#!x&Pd+)RY2e_>W3LOAa-a{1>cv^<8EH5x)QkjG)KyOT?J6ogS6r_`1S(O2D!Sr&<-9m6 zJtK@{`5{MJ4ZPfMdaig@GOk0&tX5pxIjit2{11d=h8tJT=wFysh>&Yj<>5mt>#&P0tmds}LdCzJgh)7vt#}VI(^%sW@&X!qmSos}Lca&l|?z zzv#JAFV0HO2(6P#{&)Bvy?c(eFW<#+<9fTS8J3F(y=3L=XJrtw+j17!Eq)aK_ljl}BEq{yHijS1%*xgC@QheQxL*!; z^x;Sr5n4io-hZHd`H0XfJR=Pex|h}6q>s!0UeUP<5xNT}u3-!vEA$G_h(*9s_f8rR z?rl1b>;JQ&S%nD9(7mxoq>T}d6?*aC^^8~q&Z2uaiXJ$-!8=#{mle$_MBr-Hy+>wa za3mco^a{_2MIhtq-k?Fg25%nKk7N-pgv>WYAoJZ@Rz^)h1wn>x@kvPn%?I|Gu9?gwHnh2_F$t&+d>s^ZOVe zCVw#|Y4qj>S=XlqI7IkNP@h2(adrExlNbB!55yC_#wH8TADE>#cXEjE$*4a0BjVB1 z4o|XmHvwYqhhvh7CymOQ9rJ9#x$E;Y{?_MTMC`cW%%u0c_mRh6HyfKYoAQtBx@@pR zgin<8xe5^jcQ`*8@#X*^#(g{{*<+k-ZPTZCr?4PPy5^0 zWUpnXW$jOF<(^Flf~$Ldc2fyrRBCFT|7uKf?VBfMM_w@9A@qp}5&A5Ii1EjtlRR-a z_aF26j!mxr@X+jrHNJF+@acly$0y=HcT7n7j9D|Osd?o0G0Due_sk}YXp?c=@Xo*9 z|0Y7tE)Yk4G$vX5-`i$mXK(5ddS9LBy8G=w{NLt#BuD&X2OxH9F*fRO|Rr zf*%e6esEUY1J=F8NCfzigC9T$KT7b!A;1qFxkG>-d=J^xMDQaAKk_<$l;B6nalsG1 zZ|pcPXV)R*>;fVDD8Ubhkn7-lpW5C4h;2-8zTQB}34=qH8i1%OKr20Vbt$=u{ z<0;w6xa8*F=GDGqDX*>lN0g@+dX9vM61_DBU&e$ZTs^4haNcuh}T{_Jo|IuE%^t>zF&lv7}5Bp zJ*u7i@XeZ;zwMp1{PL#!UrSdjLj-@T*SNM#lh>xcKfh(~TN&&3}J!ut5;5Ue7=GT;;<*f0^HCYre5H^Tp;_ zmnj<-_b=M33@tHY)NZF#Pd@D|AjYh-B>l%h&5ON%JJcYER%xa@`_%g_=dE?79Z`q|>Mfw-;prRn%@)+w3{KEWV}RxehDbq6-8-aLW# z9IhHYI-NHzE4DfwZ?^@O7-9J_sPXRk;U9icVTR-G5V&!j`;B``d~Q@>RvvZm`uTai z9z;zfKdv18WIo}HGn3Flbck5{+&1}k-QNa+{Mh>DLB-4)e>4c9)r(m?Vol$KQ5XR&2WZEQ26gy_l7)cNvl&zVI8wAU}RR?zdv$ zA2+9=B}Ux!WdHoAmDWNG@*}ywP5Iqv4;ci}>cy=5>gYrA1AeOkg8W$Rj`rn$UVS+Y zEivMm&v(zCYQ8QI7KVQEoj~x8yHfghR((YfUp(RFK zvS4`r`C%IXF&6xI>5A>kIVXK<5JamNv+|0?$LCkxusRUrNBeKKFMB@JC<`qyV&rNg z@<*TP3dF78$LG`bD4)7&WrHAEy~qOTgFyTn{J3f2Zsp$}Yo3Lc7*W5Uy_l8gAGPQoKuG^c&_A-!5+l$VD(D|TNdHLCKMaCs^BgsGxrUA^jsk|1b!m)r(n){!xqm0fh9A6#XL$EinR}p@RMag!GRT{lg%L zRxf5H`bP!*0|@CKDf)-YcD2L^bcPE02N2RfQuGgl;JE4~U7~{i0fh9A6#c{T1D(ZL zVnqG^gZx1MNYFpH{$&3EPp)&n_1Ofo68$4V|ESjWj|BZA4=vI^_>8T}e@ACX&_95X z{*j`87)0pBtVI7v&_95X{*j`86rm+Xpfe=sA3#X|NYOtGf@t+(R-%6-=pR5x|47k4 z-1`bUcXVGtZwy_l8g9|`&gVo3i;(LajN5+l$V67&zmkp7XOe;5SO z>cy-?|47h3fRO%?p??&iB}Sk#B zh6Mcs2zC64n!U!F&2Y0e3mge?PC+HbAg{bo}P6 z`R}*=!dS?U5K+HlAwO>V?ydP>+;yzmf9P1ucJ*Rb^50v&vm0WNAG4aztq$Dv5|{02 zi4pZX7V_iPYxb*td-O8~!Ex1#S;>)Z8_0L)$&a_cZ=65%$%ii6)ecP#85_jQ<4 z9Y40Y+kYs61_}k zSG|~(9O;1HbpLU6HX>hd#x`y@p_Uj?zhfakk|p0(&scjmgW$O8#jNB=pRdoAKKU{2 z^E2|pdhP9Y6KaVO^*a{!kM>Je&0C&xxIu7S^P3EVq&{P2AO`!#(fu#aj~kBfaRN(>sNb<%n=VU! zdb2}*eJgxd6d?Fpy^#4XhJVJ|bi1+1HLYgneV+GUA~8BGF+$#r#H_ACj5b^ESZsM3 z?jd7b-TiRf@UDTz18cjFO|HFX)8eWZ@Fh|-lR5;@a<>gJW`8#(S${~=;?lkFwNr#p zFUG5%Rd659-OG@BZ>$WeGvJO%?!zI*^evVpLq`0oIB4bxE{0lSgdU%-SGO(vXK{b+ z7>fwb0(y)3enrPwYZ(N`RWH`AN7`Rez2VNGh%pN_ap*^FiZ>=Tbv02fF+%Up z__}*YkJXBq@4w;dt|BH{aSwiVUM}mu9g^~_nCbEnDo|d z`Pkp58wAHyFZPnl_c^_K-O8IH27A;AyN=KQ`|wEDqtp^3^nRJ|gEO{mmd}{7*!4k0 za9s65<|lYZL*A5SuN`^90o9lOag^(?YKakg7teR+ArD-SE^da^%Cex-CDY(*fqlIj(xy>%s1P&+W_dr9VzJXE#Rd z{PY9WoqyszOJ2c0Ds78%-kWa_99O+;Ua>nLwPvN5dg#k0OJc-IeV?iBy4TK#!AzX@ z;*g^84lA2XpL3+$5k)O zbFN;e?|6C9?~?9@wJ~DV8B41ho^vE(urh4^?<!k+4an;M#D|Y7=!|y06kM}p# zCq}G0>znFBXY#%%yYqsnw-kMzA8HUBSG{cAWp}=|<)g(K&G#`?G)DBe_m}FGm!E2`vUH|lzPnR5`?pXoGt$QK>bp3OKKYK1q%5J|D z%?>%p%}OntNr=!H`Xj&V(wg$iVS8IdFe{#g8&7SYw> z-*;<+2(yG)`QsyN*NL3_tqwZsTzuNf*9Nz zwEk*Zal*78T)k3DjL=Ht`{0pB9$Wmg`4a{aRv%WoDcgNeUG^ux$Ym8h@4wp@UoX7V zRZ+FX2(75T5AHH|?PB8rrx`?8MOn4aJL}o%!}oFT%sx0`>AU%qv-fb_KrJysJA?0o z`NT1K|68AT9Y+yiH(>X{JD2X;6W`U^o%33C=4HcNS5r%j&<!u`GSu}$|t46a2#UC^jp zY0GULqtp^3l$)M|8{fBbxnR@o1`%?bncwY|E_tWf0}z88oV5P3qQ}PF9HZ0{Bb1w- zgKhU)Ts%LtwLyg3X6C=Sc8C14RklS8a`2RspDjLEt%YNhT4IE9({u3aLmw(mS>+pd zr$`YYx0(5KUuc=Py0j-^a0Srw`fH0LHvh;mN-Z%$x#>Chz=G+;scYP45Fxjj`ITXf z@=o{s4Kc{UCNCdT+<(aRj!|lf5z0-^!P`FFyy&+1F$NKGo0&hd#j@(dZ>)hBzucygQrZdvyB)v*MBWdA38*rsHPj z$la{O%U%zzMc03Nm*TDOhnTY)Bia^g=lk!(v&$>kc(1dIA8xzMAULji*}URfbl6XG zijM!9YqBIpy!FEOMcod8DelP+WY2>$|LUVV-Oryy;!xiOZYoQE%w;7{Pv5@ zO*e=U_3xK(ExOslP0As|Dh9!E)r;Lndsj_OW2{BTeYQop+Ub35SBnt(K8tw^$sy|A zjlsBeZ@>Uu|DH^nzRQw}`)yZlKMuMdfrT>(5jsQMjl(^%gPz{LJooet77@&fXF;A| z;_R{yHlEk7{Au_G?(C{1Jo50o`L*b|PxdXho!{CZLN8uTc@isGGJ2z)Ws3{fae1Yd z7@^nS_rbll>ROKeM-zhxvxHeGPm~dZeQ>Lz)-6xjys67}wZsU`eBTFaE^Aq4gFban z8Wa&`JJ}^q#u0<8o&5_|l_xHBJXcGMPzL)x_&|>@ig(X=*dRjIvP#Gke#Bt)dE;*j ziyO{(&{ZF`#0afKz7KZ(^UmUnk1sNau==pt$(stO)U2YdKKf^I;dlNXfLdaNR#e{y z+blV(==a_>uI?%#tfH*i^2UX9gI{`WRt$fzgX;!ri4pbvgB|C*W%uT{-S{upaTF1D z19l&I4@COlKCAZ158KW^^H58S&<kqh=9S&e0e(o*PIpZ$_)mWKfSz~ zW0YD#&J&^B^c=kVj-AR+oBUdYV})MKe0j?PF}NRWa#E!nHDe{mD7C~0<)-K0Zg*}~ z_Bj7TeM-hRHu8|$%zSxU1To0LMQd~~```PqKD*<4Bn=SCw3?c(=xUw&{H>g|{sMyt zxy{U%w_b3~c^7B$)RtwFbb(`(T4IE9v!>>9bm!XdYs#N*zRn;*ZZq@c?H$A*2d~{` zY0;;c;~1ru7@^$s9K7$UM~ZIeOfZO$+su4<3kfmE!2!q4D_(l_NXIC(#0X`Y=ir%N zPbk_A>}U`nx0(6!HWgxUMfUQh+ZU_#ZR$9vmKdQ-^J`Ig|H^St5h1t9L3xu4F?e5e z_RDF$d5bmO%2F*cLb++)t#xmh%KNl@s?Yb({oAJCio9Ek80&3|XA`}TD4*^7RzXgv zB}OPW{eJL=c_YfNy8oX=1l(rk-%~p||89G}2f#i!_Wj{y@#=?;QEFj49XDi}-w&?* z+0b(67S9?)=tZu~==S$~+jahn806p<+YBxzUGbV@lv-kha?^A0f$DbU4$U7lh>+XN z{CV$=&Y#-@z&HGiY$-UbnJn;gXV zwNBTr3J`{xT!s2T*v#ka^#JHs9ayYmJ;-_4&H-`UJ6My!0~ z=6QD9FgfzwH$I^Fu<30E!Ex2gUJvdEKRNuo;@wV<=Ak7F_?+tKV7+eX`5XQg5#=}f9Z;EOv9g5#=J z*d_da@TfV*mOGw*jp+t4qW&w0>#!f(vDcWg*ADj^1jkh`b|39s{@KLJ&m3RgG~;^P z)glDGN}_5yjwASD#3AG>5!VOnzS96&z8C>wLic6K!Rww}ZhzA_H!HPpCLuy+==ZVz3XkKI)+IjV?#HEKy60(2VhYu=D$SmbVP;YY<_UFe{HHfmF=CLl3*YNr z9#!4Uu~scHLK*D);1xaAE|2fEia~^|WtEuv=0W+ee{?_$-WT2W`=({*HP&?1M=dcz zE0OPm!`r`CbUoq8JRB>mKCE^}<%9FT|FI@wun!*p=3~Y2U0!f?S1mC@>!a_3x3|5p zxOw_yg9xiAtM>4N`sUN;)F1}?V3P$Si{@XQ=(>SgVuW@E-v>W#yELEO=1up`rXs>_ z!0sb@Lim1=YtgSh8kxU2{v6lU)Dk1K! zI<0KG$!qQn8nuvvAws$7Ik@?flgo~4J!%mFx0(5!j-8(G^Z6NwK@R@1?1Zvr|Hh6{ zY9R-8Tq2a4o`cIiIHo-Ai~HUCf{F;enE6L6nU+62`c%Xq2S?60tZaYD&u)LFmKdSj z^c+kd9aaw6{6>Qaxy{U<`1s`f=@3BoedA~~y zf@t+(=Jy+QLVoMgLlJ`<{P@jY<)6Dhl82TUq1^NwT=l26{^PPGk207S!uVadr&T8g3sFoO^ zO!FL^yZEzw%q0gp4k{w#HaRFdUWh>sZaQ#O{$r(!Ge*2yWshUk5 z==<<@tvwE|Me~VY;EqF0O=t;b5+Z8-kF|S$ zWjP4M;1!%Y;hEx(;hh>>54oDPHm|rAT{7vT;{L{O7)vmd@ZS-GnRxxF&C7c~+O-;v z75uIZS>UsM|NGjNPaoN-5?YpnKnyaf-RZr{2eR?i5E1;Y4cY8jd(fKOmWzMhwGvvE zgFppGTFacR8;TT9$)A3|8v?-A^hnT<@xChzNeyvTAFW@ZDh5)lMmAeKyN| z%dVE?AP|GkCeGTS5?@T)Uq4|V#t^G{IWPD zqV9|3`mW}VL%L6;re=!t!8V(`mT+9P5G{Q$JaWX~vx)m(oKVi}-y}7N`t#$ihjcZ> z;5R1Ew;Eq=bz3#z`B6)F9N~HMeQ@XpN0)QX`OP3gFJ4XQYKSooS@O)>k>wkmZ%;x? zjFA3_6Y^^cKl%U@<+V-O*0StX>aAqK0@?4_%h zwQCJYLQ9O0{)iZ?a3e2RT>RAcID-hQPtbi3gH^P}El(FeoZKb}EipnXs;|_$jK8>O z^wru15mr%FZRu)=!9Lh>$*5w~Q*+(-r)r52((P~@>^RZ~4I=CY>^{=ffM6e#u10p& zSz?6rM<7JYg5T;p4$4l^F<5qYu42gU4#%PU!R>Au=NP3Haxg?FH$4ZxNsli-`r%}Y z2pG)Fmwhy1aJPNP?c>VTR^KBHEg^&X@5)X8Y+{Y;N0u+nIL07CFJ`{%?hu2Oy5mKM zlwaSzT^d?qL_KTS4fg4{N4a?QVFp38dNK25cZV3{V5{o~l?R>DGYu^t_%|s~0n0c6W%u`=TdY*Q4y%v~?ObF9T4Q;E}tD)Z1icGgq9eg+%)?^$3Y#7X!Rn~WOs)c z!CI6osbz1Kj>X^VW%G(zGJfKJiyKC6n1+@ZA@|`CgPFL_ zdX38|8*gP0M5|ZG0^f12oVRAVXwd#9+hc@0Pe2TIwJ-a0Ef-Y}H3*KYULl)(=ln>p#J3z$rOX&xat*FCESxi^%;86z;gT%mz(MnBjouGVz9!U zdeZRnj?1y432GmIt5;ZE{YvJxp$C))y?&#qqA^0AQy~V|qTSa#x?Jy+*#^OJ)r(bI zyM(_l`p2lF%Of_v+jN5%QLl2twdlc@9ao+)b*@2hT=hcctF{bg#V@M5jvZTGu*w6r zt3?P^)iDY*4k6Fz6OJp-2VEbOr*esTKImqpmKdQk^sDeuCmdL|`(&v_1he8=heD3Nu3?lU6)s&}wI1XmX-^c7;9{bkgE=$xB zBQ#_DT6F9lN%_g0PZ~s+CCtitMF(d4lEK@QFO0v#WxHBpgl4|KFWUOmjmjYp-C_`7 zwv%1*v=7&utX=usj^*^bE_19^ON>wk`^xa&{hF3nPP@P$Le{cM$kRT=VD+hd_j}Rf z;p1HOQA>=_O61p~TVMEW(SMy`1`$>tRy%pxhZwA)7k9tEnDc5+S4GtlBebIWK6vAR zGmFs=G%<*}ytA6)H@y^FqwFL2#JEipnngYP)Ge?DjsVK-p+k*9r#!9FNY z`&?I3ON`JC=l7h;=IvF^d$UEx3|GwxGAdNeQl{0^yt?t&Wb3Q7eHL26^TvOdw|9WxeTGN3*}Obq z___uWdXbOvJ{%CN3?FyjqWt5~7FlSC5%Ts95ZtA{vC9VK>qDCx1kvh6KFa%WK(I2L z@olGa;mn#Ww8RK`dj|;aQolX9c{#J)cdjz%SVXHA`6%zh0l~^J=YwWt`N*4&=W2-& z^7al8Tp{oK_>$tv4WBXyj;mheqr49X1S`Wv`@LE0eAn%c=W2-&^7al8T>Jca)vZPI z4K6bXj;mheqr49X1S`XmU1k?Q%sb8TTrDv|-rfNRxrTe|#Dj}_dS(W}an*}_l=tDJ zGTixPzhc48t7OM@o$z(~4kS`YygPHi;$xjp;{=C2-IIenG zelXjg{ptDQtV`cF*&ZY0dkVxLqqaTzhoW5L7lYuq>J_rt_w!D7|57}7_Ns>GF+#p1 zK@3)geqXmJe;nA#AULjig;mK{pDv%aD6d_&qp3bILcWMW3|6=;_guexy4{8b!Ex0q ztggO_zPnz>^04=MnJOA1$o#tAYQ>Tb9qw7;F*2taujW`zSfPv-Vl1y#M~~-Pu)3 zc;w-E^DE@5-e^`Hyk=$)p%<^Fd>MMcwYZ4DyKcCt&pk3tNxw)=f}H}SO9 zvd|JEl)=6a_CEZs;L-nQqo zqG_jx3?i&PtakE!6k@Osc767gqTiS~u8OK9MrcL#eQ>XXdls{Xj4_C?in40U_fd$! zZqRt^R>ibG`uT3)zjt(ZLUi1)&ijrdUsU;yBZ$z8-ABHULJY2u<@+et)zlIrw8I&F zQO7~~=Gbviz7uvFl<$NQBlxn|F-k4uV2Ds|dJf+9`B%lRjrO+)a8SLN`SL|JVsMw* z_dmZE$Go+dW0YFR!4RR`^i{Omq{YP-^L8@`j;mhGeECioG5F@dmXCg3ymj*qj!|lf z5z0-^!LPf#Sgg{l)*wP|GxOy;VZJJ7L5i2e)o|Nim?) zSB_C?i4n?8&%whlKcu*I{8I)Ia+_R{?}QP99GtSw(4zaITO6a*5+jtGo`X-$Yf+s0 z&?JKhxy{U%?}QP99DIAykNK1L4{{t-ON^*zt$#-EzASbeR0PLWFLF@66GjYjP`+w( z98^n;P;PpJe2Z)l99Q%?Ol)5nL}9~NVua{{$dSL(Z$aMep}ozKb5`nQuLswn3x9n- zpS91~=Iq7@Q9_X`*!Jx1#XZaJHwccaUN*0|7TtGx?_&QpubM205u(q67|g^ChK(xD zKk-k4;JE5#`N8id+CF!5aaEr+Ot!}eQKmr*GOB5lONw9SbTSBzt6rAp+(C9ZJuYGDF`vR7Jcl& zyg0D!o(92j)yvjh?&weNb5}9#jx#jH&ZF$j*UUaZ>MC44t{ z<(6vE^z0)|H;57S+UmSpd)Ya!6jz>bltFM@^`X2r80x>1P1K6qHO z%ZiQ1ALGuhTEZg_&ztXqMdQPZ>-$fAVSu%N{Av9V(=~2e~#@{%)hCzQ*TvE zjL=Ht`(UTqU-FkMY0D$1%YicpBbKG(ISz^roa12K-)sO^M1u}7PTY7|GJ0~aB0cvXj!|kM2SbE%({u3bY3ml% zweZ&?g0c8py_or;-G>UCSG}0|qCtol zT#IhIFs^aYwbxLC2)WJ77cE7^AP0v`=~V2x=gy8%YKalb zO@D{wmD*48^`G9_AVO|4^FCh{nUr^E(`tYRS_Y# znfan^i5Oe~3^??y{JUpXbsSVnj8LX|4({~(#rdOGeBd~!h>+XNe9`Dc407aY6+`>Wi8jD z@>dre2Ne-|k%RSrHIy6_wKvB>wZsVJrf04EEeM0)xO`8Q|7(wfvl1;5xxzY+PMpEflJj;mgl=WZ?f&bQU^Uud|x6X+p34l)M079&u>MS-6jgdTDQddQB0iV$u) zuQ2m{$AKPl0zG8MC?d$U7=cby>lOIf)u4x5fgZ9!2)CVAnE8J73O(cmddQAZj6tr& z2=ri4;3o&6hg^XkvOx&9omZIoegyzMBl zQQ#Ln8JFO;(mpobJ$AmsbAl!M`LRddMmCkQ*S>i}C7b75v>k zcO2NiR^GjDnj5$7@1UWsV9&|F+lLskOHHAN>|&^e~Y&_hNH)?Mf!r_e)o*IX?;yE-lrSo_LfU0`j89&!pjWP=F3m}A&;R-lKB7`&GO zJ>(R6$S!x)5+kremcJgs9tAz*6ne-8!Ex1#T*02R0zG8JAP1p`oI(%TaZoKW0xM+s zD;Vsx&_hn4hiniWSG~x2>^UpYLq-hN66hhP&_i~$L@hA_D`fd=9((R6$Ogf2 z)r++Yd(H~^S%va7p_;JE6=8jL+>1$xMc z!P*Wz`~A|PN0YEdX!pX z1oooxS7Nvp#V$309on0%EYd_Tbn=+*;rx(?k!iKhb%`9J>&#>$mYm7EA_J1gJ&0d$O-h2&Do6+ zxT{`)9(R6$cD8s0?%G5&_hNH zRtD%Hr_e(-2#%{>wqCLNKo2>E9zb&nnPEMhsSJ=pm=jLpBJGt6r?y+9iB9fF5!RJ!I1jVg&B*%HQW?=Y$?| z3O!_l;JE6=?xVfS->ronatb|U+tnfj?(Zh}dxtm<(L?56qjd{WK*&?e6ne;RR(Oi&ESyP*&>8w8haPeUJ!FdrX2r9Br;7>nkmc+`4>^S% zvOBwK36DHHZ+?9RJ>(R6$OaL5@oM53WCA^8#9)>{4>^S%vda>+#0bq8zfOc6atb|U zg9x*PS&3(m3G|Q=gV_!}

_yF5A@-BQ*2==HGXA9K?G)$;a0n;5dkPagw#aIMi_v@8a<9J0pg?y^}!?*)d8j^M#vPFP{>cz~*TTcn}kP(CX59lFh&_i~NQVTg4B9xo{ZY}hXGw2~31jkh`W^M#vSXB5VuW(ja}avS8T611BIGtRAMfHM&_hNHau9mRDfEyXqtp^3 zl$)M|&_hn4hinibx0(5P7bk%pGGdT}&_hn4hwK=omKdSj^c;j9atb|U_x6q=LT)qj z@h(mRJ!Hh-3IKY@DfEyXqtp^3l$)M|&_hn4hinibx0(5PXC{FjGGdT}&_hn4hwK=o zmKdSj^c;j9atb|Ug9y3J%*R`r73d)&1~~{l

_yj)Q865y~{rLAO5zE1)@WP{+iP>ZZ|dgnd&7OTegv%*`f z3G|T7tYQS-drhE+j9Kx>p@*D857`{Ko0WLk>%p}s^pI2NA)B)sBia^gC(uKdD+oR0 z6ne-8!Ex2g<`vhX&_hn4hitMWM&PaK1bWDb!EOLO

_y2ElRF%kqP3QRpG3&_g!a z9wYGfcLF_R#2}-fhnzwW*)WRZs+Z+C*P_rv&Y*{ESQ{hoPI>}8WW*3X?AsYn8RWDn2xfX>Uat1wQQ$=G0zBfpq zhm06pi$V`MgC4R$a9s6b)z&Uir-z(D57~5s7=ia*^M#vPA^5;#t7A8T`9_m=*gV^pG>?A-l7ymhi~K^XAv0 z&_m9khinj`7q2G1y5Qd*lq`WBat1wQmnCY65t=c+4?+()gC4R$gjvF@#8(&mJBo~1^*r-Vvx1aL(ZUw?0Bx07@-XI zeei)EU!>4OHi(e5tP=R@f`8W%F<5<|hnzwW*;OC4#0afKz7IkVIfWjwL4?(Z)ec`> z@b7b?QnL?24>^S%va6zMi4j^+eIJA#atb|Ug9xiAt2Vy6;NKaQZU8;x6ne<68>l5l z)b|hGlYt&`0zG8caTF1D19l&Lo58&W+c!Ea5TV@kYf^M#vVLpn#^Si@#mvVSmHexrh{63J^pG>? zAv;E?B}OPWJqMwOoIwv+zqNE@h1_Q5^S%vSXB5VuW(ja}avSDfEyHBIGtRA751Ruj(QOIS4)E6ne;xQEG`1%1zHf=pm=j zLpF$z+su4?QOUm!j2K*zK@T~F9^P{1klW-SzNiFeu0ss2 zMe#*d0zG8MLAAsPx% z`aTFf_yj!|lf5z0-^LFgf;&_gzeklW0Be7&4N z4;eAYLFgf;&_i~NQcH|bZh8(v4>^S%vO$F0X6EDT^S%vSXB5VuUhH z?#a}?nm`ZPAVO}FgZO$mnfde?h(Qj@-wk))JF6u|C^tO^M#vZ+2X0?I}S^pFvQ`$6a-XV6172#%{>w(fF22tDKs zddQ}V#t0}hCD21g3|4CBA!pD-HVBTZUaZ>MCH#I6ddL~{kWDv;5l{+Ao;aM9LG+L_ z=ph>f$5k(OAMIWK*#z{EGw31Pt`;Gna+N?288Ji;IlC?!>=4kPONMnD==vbktdfow zo$vY})U1*bZw>%L^sh4LA-h?rg)<2eIz!(Fp@*D757{DuS@A4D%_@N&GGcHo3O(cu zddTkVswF(~@Vxmx2tDKsddLP5dhu#Prz(LSGGed~LJv8E9hnztV z*&xC!VOBz?DuEs{Vu&7c20dh#?P`e;n)!Y$3O(cuddLP5W;@vhovH+S$cRDKLJv8E z9(2}$gcXRB}Ql^@_i6`$SL%Y zRfEor6;>ZsJE&PD&_hNH_Ce?&r_e)obyqDhLhGaNgU~}xp@(b`VHIW7hE7!iJ!HgS zAA}xq3O!`k4b&1Nv@`gQ13lyfddRL9DI)9!>^@MlN^ZJhv1rgi%_@N&vg>MUi4of2 z>hzGae_npJ+XF&5GI{pksZL)Ks*XwLj=8EjCZ|uHf*7KQoIwxSKRN6@!&%6|5TV@k z9E2Wn20dhp00-5JnGX%)1bWDbK@LI>IfEXuW0YFR!4RR`^c;j9at1wQ_db*&IIemz z^P%dPKo1!)$U*2KXV61-Z)vF|MkqHu2cd_YK@Zs=LT)qjq3W1G4;e8;4>^M#vU}T1 zEipp5>F>!v4>^M#vO$F0X68fHF@YX3VvvK-L(ZUw?B1GFON>x%dJaMlIfEXuL4@39 z=0nvnfgUnqa0LK8(2}$ZkETV+H8>>^|DN{8|)x$QksI ztD$8%2*eOQ;~NjF~%WFpog464>=DlF+%zy zVsKXkJ>(2}$OaK+Nzi=|gV_!}=DlF+%zyVz9zN4>^S%vO$E^ zC+I$i!72(p

+;S4sI{xkX zGLMO$zqedsBbE&G)o-?ZxZfl7X8X>Y5WF6n?{aRx-vC=2>)(_N(6LvPkl6O43H{Gs zpkG=OaAZK`ErkzwKv?t0Z(o}aM9c&^*?4>v1Ox8#F7C*J)L`w z>h*hQ#|#N->H6o=hli`F=c7$fa>~`4)%^yTvR3>&cJ_+Ixo@mk-|xv$`7?99 z-Fj-;t4+&!c3l0Y1I$lZVJSYUOyrtsKp+sREEqoIS}LCJS^%f z68^QlZTMHNmC6fyKN^Vh^^W4XsKtH@Z|9n?hv!+EMdlu?sReoNsdS zDfyOPPHw%=+XN*fd|b{~I@{2^GxzA@87AqNpoE0xpt(ml&pbO5)Y6PH_bBSQV@yz@ zH9_w2+_OsBjtNRgtUB?oe7XOO$?qCp%q-h|MS@zqD`Oj!kkGm#_gl>?jLrnL;=5hf zy5URix!lwx&&%KZ)A9LA>z);^L3!2aZMZwygr2d6pB$Yt8@|{IjSp8jC*Nz>LtaNU zd?)(v(-WnHgl69jkL{i{cP6OS*(+*k#@+C{#B=M;1SKRi`_4V?dOjR`MS@xrXL%}L zeaz_mf!Y1b8ul(Fnhob3ojvd6nPP$x5}L2)9<@DF?o3dNSGH2wZ}O4hPMl-h^^LzD zIV@bk-|cX5rm-npHP8OCIr_ujAHR8D**IhS*6)y4-sZvvB_#Cz3$#W(5&wK_M6fYz z!LuTQT0ZvO(;{B^-CluMWXgvP-dDVr9-X#!AnK$2E2On=-Zv0OE&WD=5)yjz2d_Lc zuT*XrcTgaXeeH>epcZ?iQrU60g99;bpGTv(n!XfimeeLFA>m^`!L8bDBxpmk zy@tnK&*ezRHYg#X8D+!cuIF-{32L3W=-|evo6pEEI?a1X(<|N$yh}7+Z-jZf=I=2< z35oLBc%I#vpqA$A4UhAlbH@ZFB-kUJ32JG+-tZg8v-Fstgha=_YHDU2Mm5hcNoZyq zMp4g)BO6UhNT5w!2x{RvB?KiY;rrP0q1Y?7&v)|EXeB^LMK-4*FeQ_O$16(U@4JgapP)5i?!U8WUfC<%x)(7RD|S=RVRJ6VE*2 zkt!u5Fp7%6m>3b%!k8!m@2DyzB=9B@fp=6yPz$4k2)v`Jl%z!QjuL_QdF_fnFW=a2 zvvcyj=XfZ(9=uL5q1kDerFtH!d1n|6Jln*3KCwXw3C%~tc;(qWYKnuRx>9dTE__#9{FAMP~RH2}(Wl;^qOTZZSVF+m9l zKkFVv-TR#hYWcWW*CqtL(#$w~ZSlO9_F@~9kkHIH%#b|??o3cibKWrb^^7(qDAC+D zjJux2(soQxLSmT(FV64ND)sl@OipZ&pqBqWa9>@2;W=S`^}#kHYFNdGx+v~Zj}};Y zt9MTu_y$m;#B@pE+klAv;v2w$uOAT+)WTX_#EN^~9lW~k>ceW3kibe`1ik@81hw!D zKm@+Y)F>f=FE1kSO(r6!#k(^4CR3v%B?j(Ye7~w{W?V16A?w->RB`#%vn$rW{Nt#6 z``O>t-$}%h0m8Jex!<`lK^vMG*Ng9>YAtEnpoD~G#`WUctLRPyweDYkwtVrA&&n5W zE}am(mv~p|`*rvR;Q4TDgAx+>e%XbfmS)D`ONi&gu?alQ_3|!{{I@o9v>YvQxtDkKjmrt!%5&pYpQ!zma z3C+GkMA38Z&P1%$$t!AUwjZL1o;9=IVjGl@(9F2M_=cQ#MS@zleKw*0Q+?AP{f}7_ zf)dT2`-?BlJ$gk#^XmTM3v}xlY+nz0MXmVCA|B>$Hj1ynJ$glA#CkVm_v<%B^Bj0VVuM~$ z%YPrZub#~IX!?4*cgYw2GSTiu_U=3Ht{(pWHR7tB=n9ASI{%h zN@dJB2Lv03F7lU%pw=t94+}Q_+3!kIpDNa6ufEvx(JCb*G~Naqo~Zo+>LU!x+Tl#n=h(f?-8 zopNgalgFLYKpXVR$E7F!bw%;DR(42GLZZAjo;!9XsI}PGHLFv9cXpobv}!_7Lc+ht zD8BC|1SKRo_Z10h`S%#b_ua$>d(pqHD89G%cs)q?7aYa+_T+ld6KZwzs)p8PxE|ry zW1{Cn(eMC?>TU1 zf?BrWk-GJqW2AOmEj+27hhWssFdplAV5E)+YL!>kGr?%2Zcsu3g)Db}~jHn_o zQa30ef$>-bM(T*57DiMN7^xeSkl<4gjnolAEk0dQU4xJn?PpCHzYSL>aFqg8D~KwG zPEUBOO$k>gaFqg870{@Tnoi8TZcq#P+<8n;Lc-MvT%|yD2of74sO9Pe&aYK2e;2~l z37jpfO!82jz}d2@NsxHux&@`g)d`#}tJ(uOZFg=530Eg@wyf$9BsO?1YWeR)m4bv| z3tgSSRSHylpusbB_KJk76Szu&>JW74D{8qqfvXg#CP6|_;_3v>mR0S69{Y-fs}nd| zR&@xHma~P_a&-b{%c>?pLQvxB1kRRK?SUS>BH`);&X!djg2V>Bq89J5DD%FCO!x*e z?{j42%LcOhYm|`iv7csDD-eNP{fIz*e%NozPxA?(-s`o4s$tfrT>Z!^63ErpHUG~n z!vdjyBZ68wcNp{4P7$cKP(xLPXv9HH1re{lwpg&CiVihOP@lo|^kL%<3-<*=JrEJp zLgfY7aCHK`tt#q)8YLvyrl?X#^YpPxhOAgs$P4xD%4@)D)1B}&@Ktj~Jm*x-3dxFVi&Usd}qu|a}bom=jTc+P!QJ-AR2&$+Lvch{p= zuAx^Fu88N{SJl4j;uWm>;uQ(nb45H?##7a|#4DcH74e+= zs(N=_Z1B7!ToKQ?ud02Q*dRfz&ey{g@mv{C_25E9JXgk3y}KU0at*zba78><##8OP zE?!Zqb6>e4o-5<2j#{XQ=gN4hch{p=uAx^Fu88N#c&dHZ#VcyDN8-E0y<5)JToKQe z@s@n#@*ce+;fi=6_w{f7_R4XWSCCqZOdc0*AH` z=9OBmi08_9s(06gpjRYZ5zm$JRQoRRiUhTIW#g8+BAzSbsq$K=i08_9s(06;SFWK~ z60V5n%6O`M*TpMpu@7Uf*zc~0ceg6zsoq_WUXgG`JXgk3?Yk~sQOgzaTp3Sw@DhR& zSHyE=Jk`7F(JKa-fDmW!JC~++(uToX1Nm>JE>TH9AYdLw9 zs;W(i4W293x_6RCKIK;HF5wkqYhBC9t5j8L>d`9_uI1!as;V}1@rqim<>XbWDmWzs zC9dV18rKTfBeZ<>Ym(Dj79g%gL)$Rch+79oV>18m7#`f zIeC?;N=-d_MZ&e5yslN%rY>Gli#-y1*Q&NtsO98!t!glJ@rnfP zxt5dHwW?R75tn0$YebdjbuA~aYgMVKiw&Nagljo@U8|~1U0P19&ey}WoV>18C8ON6 zoV-d^r6#{E+Vifs9h8u8Ehn#QRkbN;ISFcY?km@F^14d0nfTLAh%= zd6lY4O+9)=!nK^du2t2hE?!ZKeHeSies?V=uWMDQsYkC!xR#UGwW`|G#VcyLmXp`D zs^F9ml(?3Y*R`tD)T37ElA>kNmQSrSCK`qBni;C}E2**&1 zitizY>Q$;DrwQTcYAJCHwW#>+FB3hqgM?$KMaB2T2G2z;|J~!5|Bd^KEp!aEsQBKa zS0o%mEh@ezHs}?#978QCz9$4Fj-h&$st9S1UXgGNwW#=>*q~R`atyVo_?{4yIELy~ zsv@L4dPTx9)S}{hVuM~$i}zTFDAxQ8DnjarVz__&Ec)2bqmLCg49AL`YR=$jr3wG5 zs9tz#{jVdGe!3L(OLpj13^EXoLDB}#Ysz#h&Z!t=ARL3FgoGlE!7IgA<&~qZ_R29x z64au%trnY5Ox62Mv_~Hwm!pJR>|U_l5O)qX+#X6uuoprUIS_6S32NDY+pwoC|Lv9A zLkWqv9UeVRc%*X-wb*4Wx`OQW)_B{AaLe5u$54x1#?-sCK?%>x`>iuUEyqxcUB(g{ zj-eL2j5QqVEOr_5?=mpL(JK@wEH2G2{vG1Ow0vBU-mYISaT zh@rN284EE~uQ?SVO-2T`oHiVFEeXd^i(SULctx$wedQQxvCCM9p?b}!2x*UAIqF&x zj-eL2jOlLg)DCK~M`FS;)MA&h5JUBvQ?bu3UXftGIfh#7GM0Gd*lc-T$54x1#=6+x zc}X~iTI@2G*dReI_IliM$54x1#zG9$YeU68yLd%{_8dbkb{R{&a%{FduVbjiE@NG6 z@Vq1(LoIe0OKgy!R_E*C7;3T0Scst(yNvbdm7}gD;TUSM%UBn$sMWcz978R384EGg zVwbTVy>isGBpgF6b{Xs96}8wS@m=EHE$3>Ep%%N0_2?A|?H`sGyNq@5idv4L7Q2ik zgkz}1E@L5v>NTgLrCq#oq_xy?47J#0tP8>WiiBgR#V%usS0t##D;xK&W2nV0V@wD)SB|=tgkz}1E@NH1q89rw_KN-P7^>Htijel`6$!^si(SULcttJ8P>Ws05`q%P zP>Ws0di08fW2nV0V~Gu3L2B_jwPL8A`}pgcBQT!t`0KonJqz=(W2pYSzZk~^B_td} z^@>%|(k=wG97FXgRgu$#pu{m$uQL@P?a?a|j-eL&9Ygh6RFTuf1|^Q67W?D44t)lr zi~VsDf)dA2y-HPtv`4QUFPVTuH` z@OSlgpNL?a zqG!`!mj__-jVx;auV6+P{)M9^}gm84Vl#p-? zwb&mgAsj<3_Q$C^hFa{8Q|CP$w}V=ap%(k&bRl>y5{{u3`{UGO8ziX3HpK)bBpgF6 z_Qy$Vkf2uQzH$uJu~bD6>yDv%m8uA7k1Z$R7;3RUPU00?PAy)ixaE$a7W?DW9Yggh zRT0u2y&~ZlYOy~~7q6(r9*Mnj47J!Fr|uZ4*Pn`gcJYb?d%-c(Vt<^(E1uUe)M9^} zE;e{x5{{u3`{N`wNKlKt9=F^vRIh6lA+0-x>h-5$pIy8nL3@s&dR?nHVd53f>lkXW zKTa1LJTD2yP>cO>5*s9_)%kijhU#^#B8XEQL-i_E5z;9sm!iyLd&d z&VA(=s@JuOyiIWo)vHuRNPF~(gkz{)*D6{%rE@!|#U7cSXwB|M4Rs9F>sm!fC$mSU zC(3y(3CB>2{c-N@Oi;@)RIh6l+e-+?P`$2IJaCF*s9v!uTH2+rsO1={*R_g}b|Kh8 z659DDtZNl5?b5r{;+2hC?ii}qwTji<;~1(}sfv*H=oJaaP`$2Iw6u#?)M6jTUa{XD zL-o2=5z@QaBQZe<3CB>qu2r=3p3Vfd97FZGR*}<$pu{m$uWJ<{y@$3t+aTc>s@JuO zmL@iME^6^QMc)AU<-e-D)bJ}`@1l*b_0{PKKOg$?9}&tQ4ZrwR?6V6&Ev&+`*ajse zlyMqr}%V+X9rhgNHEmW3i?p3Py#HQ`eHb^MrG%xZ}yYv;clzo~Pd8r9OiDRfm zUTTkhMM4>;A(ra>u{*beTFO2Ru~hGs9TSu|hFavM_UIJ}Wt@gss`tl^ZLr^|#d|D@ z4>l36t0F#_AqprPj=Fjs<-ATxNch+*NIktG91%6)EKL%K6=t*@MHC~iNFbu9YmNwS zL{JMcRuPV&+AHVTdX%xh9!oglAa*MPF=6ilUdERrBDR5;a70iG(O%g=Ot?u23AQQv zJwr`-sbS5jm}@#^j=oJatP_AWI?Ugj98*PM!w z_UIJ}Wt@gss-mS`yrLF+B)+edWg23sijZcGp?b}!*k>27NbuSy4>H736~jxs;(3*2 z8e*x6kan@b^O8`;X^5pNTAJ7(5ow{<o%QUPx6(Q}>D-y~$4QozCOS^bQE%r!!m$-M!xtg*} z!N(g6{ME(Bg2|gvAu*)PGwkgDjt|QhUzt^qNQEDqL#8u z!H1UcAwRmOYmMh;etT`2{%ammr)|`rv_UIJ}Wt@gJr=q1@ zyrLHSF!qZ5?ii}qoQjb4=oJZNoQ5^0qNQEDqL#8x!Zjb>!XX^14IOTsbKA}_TIK`qBni@el? zpu{oMA}=+v-PtP=%E9a}@=_BUY+Wy>p-0f}-3`-{BPs$-~Lr7Cio z*q}sNru{`;s}L-o2=5z-#LBB6}adXbmf z#VcyDM`Ev(Wm+%tQmc-kdR?p7XBV$XuosjESugTZ6R&t)WtrBCywol>cwQ39IIS0X zsfi5|)MBs4Eq4sH$V<%}L-o2=vCl4Ek)S=tP>a0O)=Z}T4D!6nGOZVRsaojU|+ja16D`OHEo%f?A#X$}!X;FEw)vwa82D z(JK;;p%!_mUA&?ednCR~+>UZ~=NM{{m)fIOB$RP_cafLc#Vcw#hFavMCWK?CMP6#= z7^>H`ik5cqidrFts#vNbq+JMJK@yIk7I~?OS0t##D;xK&W2i-5YUUVfk(b(|S0o%m zE%H*kcttJtVeA$A-7!?JYZW2w(JK;;p%!_mUA&@}W2i-5YC=%r7;2H1+M`z_978Sg zQWG1zg4E)5@(j`cO`YUl>pg$|cdJJ%FnWVIpTB0xW>;+9KK9>tUjKXj{(DQGL@6QR zE(IGzz=k?0o()&F`(WTK&Ka4$XI(yOQ~MrJw#P^YQajUY+8TzKgg38bLi3!uC z*3#FH-_SN5yk%C|czh*ip{pGyo!q1(B}})7dFQV+Obj_iYfhZY$EDUaqv!3njji^X zNj5&bZNEUQaPVajfi#U9j*6!J#EPQlCm@c*ETYIZuW8`UH=t_J#=B8j{@(V{a zDM<;_E#k;a?hC~4|9414m@c(OKDBMI@x$vsmyKobzdsNs+;>Qml9VuA5ZgW%hzIXJ zARIP&FHnv|r3=@#+E?pp+6%8pA%gy~Z2m33baHYU${ ziEO+*dfPy(x8)*DN>ajfi&*2Sp9Et3Y2S(n)1}tB_d3hT1V{td9X3{qHSg4tOpMa#D%v#-Jm2TOt*+Hi(O)BgBuZH zy3|_m;ID&?tvBwMjWI7D7Hs@wjmZs4Qo?kLc;knyU1B!=?)Zo>U246*_sp5ct0n*U zwcfQ~ZPMB$=J(H>)1V|JOt*-Mvz!pT8a?}#5n;O2`p$aa3N|J`I#M>)dg{bLJhAe! z4N6kNbc@(-?bdr^@%q&{2_KhQemA)t9-k|fzdunD%Z9gBDM<;_(-9fZ<>OKdwlxEQ zR~aQKQFtfai$bUj4i3PuEacM9&FdZmK9q)JIj*oN*a5x5g0 z0(VIrPk{*B?Nv%r!Z!4Lh&XfLiHZo^?R7lOBFd+B{vBVbQj!w3q32u#Muv#MQ(MQV zB%&OBt~~8qHA+&#HZ)#|zz7!+7=7v(T}5CNtx=K^wxMxXL^)C)_3|nafl;)Mw}c41 z4QiC6gl*{kA>!u)Z=8t0+n|oOod~?uYLujeZRkBH0&mWUz+0`3x3-A#?L5^&)iE0sfmvUTl9aFw%@ajnW*HHf_0=(})!2K)!0fd~NlMs;=DQ*=Lyic{UUST~ zMPL?Qqa-D4L-TeKnCV9ZX5l$j86vQns8NyyTRZ)!+ z5`H(?hTbV6u=0usYGKtU0;{`PEEza2)@>rNf{X}iVf8BF&4E>FjgpjbJG8D9ft7GX zV3nFPd?Z+NMTHN|SF>$30 zYm}sf=@zlmd#x%^hb;BIh%jAh{pr8=1si80C7$EDV9_Wf_L@tse8A{*bDb-zID zn7>}7BqdC@h+oRX z=o{{c2-Bt3E}IR?{hY7*&Jfvn=Z8lHV*S-7RVhgc(=FoSOOFjiW5H7+!gQ&%(;Tw~ z8z*kw)GYjjFOCbuE|2}RN=ZtXZV_Le*UFH7aIJYF!gQ(C|Icp)8zYvg$i{E(ZRLiK z|M=02l9VvrBA$Jsl_9;yv&%+==~AmalSdF;kN>oY-JiX>pOTa?JsnY>5n-+J@A7KH zN(El!l$16~qVP}zT0TR<=S8oJK<_pvDQ%R5ZRmQ4z!i)L^zMeZd-^Mt@-AsEcxr=^ zl&}rmS0ZpHMg;DXemn&taJM%oNeSD~^C1FHR7Buz@5j?D0#9v&l9aFwJ?A1YGDHNP z+J1~NBFfR{<@-KrP?8e1q47!tMz|&kj6VGsT}70m=ug)8c9W8nunmp7A}~@%1V+(* zyd^~7ZP277C2T|Q4-vBzZ=7A$TRS4~Ht5IOP6Xa+O-fS2HuN48fj4JF;H}n=x3&np zotu=Tgl*`3E&?-vh``&qAF~e;m}N96NeSD~yhH?MG7*7UMn7gzA~0KOQj!w3q4|{v z%*Y}Fv!#B_21Q`j*Q6vRY(w)z5tvy<1ZI8xnAK_|#q2eTE~SKRIMP(9toFN+&0ntm zP2Uf9{88>m)nN^NYE#OZj7kB>TLvub|yMfq!^ua;L^JT$WT&BQ1A`gd6^r=*|* zvEa>{2ck8$J7#xp{$gLHa%&$YByc>XWutGmrH9H!)`6G;+x1pEt{SoaP_-lDxr*Zu z+l+~&zCW`0vsn%vI^xmGGfGn8*v9xwEtid@N1xn$?9&s6UUU4*5n;O2+GG7zUp;&7 zy&`7b;pFCqL(U$0#f|S~l%#~|7V*nlPHeul>JCGPWqnl=J}$Lxetmf8-NS~~v|`!p z&&M~i9MTNeR5gfXP5V+gxaiRNURb(DNlKV*5&P{vym{-kYYjc{ zffXXcbg6aNh=qcUUmfTj5#}4YQFH8l2Ms;xffZ|%q=e}fao5%BH7_{&prJq6am|P@ zU1~`)*f@NItLaL!dE0CU3>8_UBqdC@h=WfY+WhjHorZ3>-Nq4Ny3{&g(8rm_#C5Lp zUP9|GyKHm0{qN~p>Ytm{C`k#^E#ennFWTI5!Q=bJ4BsXqOqW`^a>0grTsE=|7iz9Q z^?QBm5BgD!l9VvrB0l}|?9Kb?vktvtx1A%xbg8AgJlN3PDH~^f{Y~SHeJ}3&fNywx~sr^$VfJn^#{B`IOL zMa((hpBwXE`cB^+{Rc*b=~7E0La?DHSvJny_rXSGo*jn%@t{L$l%#~|7P0kg6B|p_ z7aRJ=Q;v!V)1}s(b8iuBEVagP*;wcM7dAe6eYv44?s!a%l9VvrB8E;qvGMWl+x1QT z_AesBbg88gI@r+2DjVOK_KU{;t1Z{J)^@+BQIZm-3*yDC8~^y;0eyNaM1<*5OK+Nf z-@AH4xE)zvTOhnXi4!E`1YTiV4%D)`Lf1bc@@e8G>y5cCGwrhYrfSEiQ|7Pkzr=2RD;{xDjgpiw-6B3( zYyIk(jq!cMA2}f+OqW`^nz`H2x=V&+J5{&*X0^U|HV=16Tapr{Tf`SDombuZ@z0if z<=Z2CU$qGzms$@_Iy?OR(v>$P@^OzOt**|=l#6;m+S` z)F?>_(=B50M;EJ&9X;zceZSp0B21TBdc!qrqxI&T>)mB*|K0qKYsPK0nctjkNlKV* z5&L|#O6}yQHlO&5@mWNeF15D%=^WuqzZ*Tj`s#@9u3r1@8}Cni;nEFjl%#~|7V-N_ zht;mQa@I-r9R9tCFkNcd8@Iz}(dzEj4QhLRFx#XTS6-t=NlKV*5nn8{S#9~_Zl5@D ztX zm@c(^<=hUvv1Q|#leeoKIp*Doqi!4QSzlX{5~f>(=L-E7Up`TDhlns;YWXg=4ZX2t z!*hj0DmPBl+`%*Cwj?D?w}^#)zi;g?tDisdo^QVq5vEJ66W3ffoN32(uaJ#f&pV*@ z#h9fhEimt2s+6RJ=@xO~jfd2J`pHt07F+Rwh%jAhc|>qK^v0HrCFVM;cJ42}H)-`f z>t0Q?B`IOLMLhSXqiWYLFx#YAhE9kG)1}redXL+NM?I}S{(ektr5!$*`0(MstWuH^ zrd!0zJ04d%>X8p7F8!SYBEod3b?W9D2ODdjw~TE3WbpB|B|f@f;wdZdTBRf z1x~EJ_s-Ob^G{wYB21TBe)GE>ehXD92ds5c?Y%#Yn)t+0i+GjVmZXH~7U4JMtt)*n z(Qi-^J}$Ku(tF%CT3-$PR{qZA4^Q-4nv#?-JwQD0e~V2Lk(2OosRi5pm5RNZ?Yg}u z$*V9MDq7f|5`~BVkE}C~w`zL-_(`TFAw-dMZ#0py!99ELMn#jMjF}24M3bRgq5%nC z4ayLy?nM-3=AON`3@Nh=(O?LnBC~H_mEY&{oV`z&bj-Bb5{rw1?*$1V@H#b2nFDWN-+1YHe0# zJ?LR%G8}!jO!&IurF!cl8Lzxzf;RF5N4VjOKIRDL5HkAMj7b~xlrkBPqF*mv$x$?x zao0+c{;!OWAU?oIy{2vB%JEO{;}EJPvjhmv2DgnltP-<9tde4a_Aq~d;EXf-p|VQM zI1VARfz8US2WB-NF#ybJzi0baVpfY~9`uU|+Q<`}IeV41<;>|2GOPJAYr_U-=YP&@ z$JsenNijhin9o6Q1@PxvCsclZUztP5?Cf(^W5QcTcBp5RJm zj}0ePVkP4cq*E6Qvc@KjPv&<37;5M1g1TD?XkR{9Pht8ibu z3=s4twm!T|CA^7PCB+17!2bY2k7fH)v**KOaR~7ye9p@3SMZ8J&?|an%&YU^6~!tk zCTJs191PFv`|gKT!1Hnl(y5kseXwEPU3u>ccz3Z%iV4#22SLz-98rI61w2TH5bw_C ztju~~76L&pwcSq#R>Dh-RZ>jQMxNk2-us(BD=>pP1nE>uyl~jyJYM(1YL%GRW0fc& zel!Sr^v~^ca|JwlhfpnvCKypOZ1?=Zm53U|Dk&ydLc|$BFf#G|J9R4&nQ#b+8nCUh zJKKuUkKs#Su0ZsIH7`htiL@1vQAC8L*7%_v}`JNRdO3PPHUTg_<)O_3!q7OAw8URZ>ilM*IpyTSUAXHF~N95if_3 zXq3;j0_%}~Y8h1LC}*saVuCjE1lJ1fAN{oi zYX^rQooaEdKpXklfNO>ChmM$!wL`3uVuEy@U_^M^{zuG5MA#unr&76-q79_<4 zZR80?=>4-#D`jk730|jKk{v*)sQLT1x0aGrNijj1zvVLx+qz#-icEt;NEX0n)`9gv zHUk8+8Dm#1DZTu)BVv^l6SR>hm@)aThW%r0G2@p&n-OR-9d3DU?%f#`q?R=WLSFVt)9+VUlw2>#cR%m>ARVmgE4naEA;)p;Se3CO6 zt`){_tH*2~y@`UPm>``em{Gj#np#Z{K6ar)kWRHEn+Y4tTE07@dQ)UABb5{rq><+Y z!OZCLfj=`d>JXB(v=N&1;K&Nk3)$CqPy4PE+1H3;cPc3+Xd_Q>7P#TX8qDxI1nE?Z zvoimQGX!EXm}$;?Yi%iG`zk3WNaqP=s<)p1Rq1SegHs7!r&^LFhYe=Kn~zvjifp*E z51^PJo!>dYjQfRie=i-m;sJ+{Y z)O$+s#h=Bc`d_LgzbAVQE;-~(+iRc_CB$A1p74p|f|6~!Ro)Uk$Pi}_Q#-bt@0t?Z8MS z#RP5Si8bTOgXiKVmD5`U4naEA+Wz-6vvF+SDX{TM|ItCog2O65dZAyWl462%p4eF9 zx}f@*jVt%)ev3npPPM*#=`OSJQuWtikW6Z|4JDS4A z`5&GW?D2lx%KA6&9;>97Ae|>}t9N=Zyyoted-U4ZAxNiMPh3{7dvMmUtrer6J=7scr&^6JA7nQAx9S8N$2UaYW7YbKPNhv^ zl@t@C^TgrzctPDZTPt4Qqm@IDPPJa|*~e_me(5~gc&$xv<~>^~&g*nstde4abe`B{ z(^0`almD#Pvgt&JAf0L*eSJ@}asNRVz(#n)QNfOjey`X(w=7mkF+n;{T=dG}!Satb zRs8OCatP9?*3yB;n~fuT4~LD>-ya%0+jK+4BOANLDk&yN=ZWr*>=#^r!^Vm?uQ=5q zNT*uOe=Ri|M_e}sHooY;cTjiw`ijMa&xlo0OpwkKukE#G@OS-n6(4_ownLCkwY-}3 z&BkxjI@NmX-rqdVD{H#m z4jcD|U-%n3sn&uXTg=AaPtnFF@!Niz z^FFHRux3cCl462%p1ALd7yXkSe6M1c4~IGg=~Qd*NsG+J>Lqu>M$M?we|GfBilf>N zk5y7kkj@jCkEZzFEPb)!U7Rphg4e0mr}bx;jg_sZ!N$mC6a5Ef#}zxg>tdA@6QuLR z$-4~nk6Q3(Men&cI0WfbYsSjc%*F@N4A{tCcZxrB-Tf8qej6RDq?jO`C+e-)*FWmg z+bgD=JJumcr&_NBZ)SPVx1Bo^Hd>DQ-s`dOmWoFGZ;Vw^OpwkKH(z$IxBHPJD|((X z&LK#rT3=4M!)$!CoHk}gw|dL3m{76)YP|hIB*g^jJaK9DIoZ>1Ew6Z#Z`crm*Qpk+ zbF4>!$lZ4M`6*G56cZ_pefrU@;TgRfq@_|KmujJe_Ish`VXL;A=O;BUNLUgjcwK1S zux-3!e$u)Hg8!RpO<#Fh$a)m+U^Hyno^}USQcRF8^pfbt39rs)FHwTmsn)9cGt5T5 zC-&H7V6^VY&hyz5RZ>ilF7)=OR<&C5+1r)ib*eSwq(x?<@I*xociVM7pD2|S6Qm1I zZ8Z9qCiD5!D#7bi>+v32%tm2kh_2Y{=_VW*R8mZkE{s0WsS_S;!qG``e zq9cxq4?T8R>8AWDqd@R~Q>{08_Oag!E19_d+6kpx$*825Ae|?$T8fw4)VGwYB_(*B zYGLJMHVP}UxOD5arOAq{ASotD7gl|7zfqG*lT}}V;QyvtSOMDag_UJ|`E~b}CM(N= zq?jOGSiQyvKUz_mtX>NQ|2Ne-XTTWyy|6-#-}(5NQm&9yQcRF8tit1m?~Y5k3Ri;H zsTNk`W}~pukB1zTD@|7V1xYbMy5LR3cl?+uO}vQ$!T(LQ;91!31&<{jcKXuN#A7K) ziV4yMuPCn7Xmx4g6%`2nZ>n|i&v)AI1>Xo7%`cqN%W&Y@PAV+ujVZKy%1rE z5tC`k2#ZRJ3DP?W#AHZ#O7J?>l6rU+lZg?NVW}7$N=s$55=jX`u;z%#u;#uJQYugG z2MEMuV#H*cA|~Ujq?n)$+z$|l$;61sG{qfs2x(nU`T_{VWMaf*nxdEZDk&yt1N{mF zVlpveGELDF9YT7ECw&?OVlpveGELFjeU%gww1MXX1Y$BVVlqwfL^*`?c2Ay75Qxdd zh{-fXOvYD9F+m%6&Osn16C)m`seA zOjC?-4k4qDFXJu<#AIT`WSU|WbtJ_EZD8C5ftXB;m`qcQ)Peq&jH14b`5+LJi4l`& zirFAgNijhim_I-uCKDqj(-bp~L&$94%RC4IF_{=K8O~~fN{R{Ez&r>7F_{=K8P1#z zA+wq<^En8_WMaf*I6DU_DJEzG^En8_WMaf*xB_qpnVo%EOV9>Z8HmYnl@X|j}9lZg?N;fl;5WVPhWIuQh7 zGBIK@T=fMiDJEzG>qHQU$;61saAoNbvg-3?jS2!WnHVvdQmkGBl@t@Sf%Ps3#AIT` zWJ<9@b_iL$`m)vrftXB;m`o{F;ekqu3EIHA9Ry-B5n?i>Sm`^2tipZqKR_TR6Coy3 z3U4A%Nijhi@IOExCKDkhQwop8A;g>T#rFY$m`sG2OewsgKqbWlZNQHLftXB$m`o`= zFNYAX$QK_D1Y$A~Vlt)h?gEt*6SM(;5Cmc}5n?i>@E{#RygOffQ4om9M2N|h!b=TQ zQcTbW{8|u*$wY|Bl)@8s2=P*V@u@)|CKDkhQwnc8P)RXC8}QFTASM$bCR2)-j6;aG z?Ms{i1Y$BFVlt(O8U!jSCTIh31`vqJgow$MA~N9+5;gE8UIGF!nGi9VQp98el@t@S zfd~r-#AI@a$&?}{;}8=4pp9%2lgSfV#AH&UASotx+CWUkLrf+ul@e*(hizrQ7i#Vy zCR38sydYso(*Gr~v#l8MLQJM4Y25;$S`uwTJs4F(Ovdh@N{R{E$lr5D?hunHVJ}fa zqH4ZG4PgT@86Pp3681!u6cetdDj`u$U!u6M!DuaFGV?exsHB*njr>@`h%jO@^Emn_A<HOM<87#zPn89)g$u4mXXQeHy$O6P`{BQ!_J)m`nv%;Yvu>k{*DSwy@F<5R<7$R{8}=F+m%7f*D@KWGWJGqCoI}Q!RKF z_Itr&2@sR1NIaH;q?jO`Czz>5Or|37iV6h(H`S6XdEWC15R<8(=cSTjf^^ zOr`=c8HbQ;xF^~EyayQ|CR0HVQYFO%ZRCAU?i@f&rh;Co5|Y*TWY+?0aCZV?G8OcM zRZ>jQM&5Vk4hY0#D(G!1A-fY81F$wMc=Q2cG8KtOUyu|Nw2>#clLIlC3dCd>11J!@ zPPGt0u;00#CBIt)F&XX_VPv8pDJDqgiB^x~UheVixS%}O#XEk~gj_g$zUS4u(_hSU zySTo7TK;O`febCIb_Iz`IU-DUFyWXO?HnACr56xVhDC;h)cp3r0`c$2)iTPNwzV6TSRFua?>M(k*BBYu_t1V*Vc75r5nr z`-f{lJo0JAd-0*OO{?be6MSgeHAo+tMt}ry&6<)h1X1<)+U!3)t~9MruWIO{GB z`6!JMC>@9&H?$5P1abGoXR|fl8e>}1wruxMW4lHR_^7cF)BoLoUb5eW_Tlv)+PyhB z``MO>rZxFLOT8W!=C5~uf4PTNHR7<&i$ScvqeFNah>d%nn0@Z4$wqXWGTu95RQ?)w zl6TICi+;QcMB|NJ!oz9fo~p7P)9*0i((9_Tci1(0i#O-RYmIpBu`SrEhF+3QdP#_0 z;_(immqh=;fAbo>B;tQ3y(F?;l1+L^c=3iWO$)swV);p+mqaW-3D(DYNjB*vA$p0Q z^pc2e#A~)0+lU0)%z8;S=_Mh0iD{viM7$3qcwcxQl3oG=y~Im;Nr+xzTIeMa?==bD zd){jjy!X~iyrh?eFFbU%X`z=yub@AXVE>wj{zQWP%X*2I^pYHUiD{viL_ed?l3*YH z9etJr`>^#AFX<&Y^b*rTFA4cvkl=IjJe~^@Xo1jriI?<}9D0dqp_hbw_DG`mgO-=CgUy$)I3aTUIwY3)I5ip+coPt5o5Yj zb0bjm9RAz1P;>9_J-gdAYR)Igi2TTanj3+dhokmB+O$v~4>h-I)ZCZ8>s!rpNzKD4 z&`fIXH(0gIu2FMeo}8KgaKE|S8xT)sbK3Pnk@MYi|xG zq8^XN&p3Bb2|cZVcWfPSX4wC&8-uyiA9V=T()*7++siHpr=V0@4~s*UD50k=kYlNK zN_ZMdwW7@%4xw7whM7#arymJV0x@9w)KE_hXy27Pi?+JI`~9JZdhEJud8iU4^eI4G zH0dSP7ff^r)sh~A5$J_GUJmP{=I5L;)J~o7ez4X`=$?JNH9J^tZB?Uo*3R^hU=Pt< z_k5~&&oREh#^{9~g@?k%_QBPho~XS~_o3sB(m`x@u;II(=TxGEju@HDn?HSKr8<1{ zB8N~d-G`2IkSDA*V%ylMS+QYz-B~B>g3swVhW+hFtPM}b9qiEH@Uwa? z3)|uj);Qx&XG~Nr9Un89M~_?=Hb+}M`0|7@l_;@uA3DcWA*z&6EupdY>EGgQt9jFU zt@WCuAf~-V!vwZ>~5umob8Kb^a1hb(!tp? zaR=+oTjLNqtI3!T;^UgPWRJidthMj!o=TLE*#N|S$^6map3fXYwPY><@pRX}vjb3% z%&3p;9S^JrdSs-;>+;4Mv=#0gYmPhV$qCs=PO?S=ux{8ne{>&mwwFWA$FyDQ5V``8 z^Smh4fiL&*8lvXY7A){oqJ*v`@D<<7MtQ?wqtD0}9YVF_TrzB&{NN<3N4--Qdn!=^ zv!~6XoJ}(s_9xaH{mc3j+X`bY$1c-C{|a?YgkIA6d9MRX)u7uLXSJk+oL)z7pW1hh z*B3Q!`M;|iLbYT*N2#_(Pk7g&RP}F|!nH`mcIPTg30Vz*XqT)Rp8RW;L#URlB|seY z@aNvKu<`XFbF+LdSaXh1@+De7ixnflUD-J6yW(nB1@SAtNAt=?@he{kmwdBnUAoj=e z&3lgLy-MH1fzi%t%TZ8T1S8y(#>=c8k9d3JRHB5g&T*Rjht=L^DAkO^COL#^NxONO z%o*8_tyB#vwj$n8sG;-r3%MU4zFo7zYlV7TI{Acw>6gGsSEi{L>Sm zJRkNh1JYbMv7fQkIsRrcC9^K^n!(09lfzI(277A&3BChBo-PopygjmP-6qr5hB9*6 zd2kYFKVL>W5F=}~&rMo~_j&KTH77o@FWzs_I&t;KPZ}|_-twIIuZ&;V>YninuHARm zqs|o@^ER4|&WUg7i`VG6tBkK-uO6~gwR+xKC4L|MezQS8O=fNMlEvQ)dWpo_pY7_2 z7iV(@y%hRs?)-t8XOo&|C59A9bf{?DMa_*s&9n54`M->)(6i<>{WQ6Qc+OGtyp3j~ zvl4rWB&rgwhrhEx(3dqE^kt>gg?!+_>r?EH01*3vFj`w^ABn2@ zTEd-ixK|LZRf!T3pTqrVSNn~!L1^8&Rh3yKR7*!9?2TGoo;?|*y6DCe89PcNbiNW2 z#e)q*ge}(B91&q9R7+xjARcVhENq3=y}i@3j_<5(rJg0;)>FRB?qJ8+=Q|#x5^6h> zxi}nQV`9Swn{)bKs^!Kq{%W;nb^zL{qSlO*^X$dq05e8WG;ror8PtaUq9-e45|V=%&Xd$7Ak8l6>`8!6ha&ud{% z%(Z*=IxSR*{;x)ju;X{Z!QL)t-7OQhWVN=EY4Ej#c%s&nSZ?BFWUy4Cgybx6KURNq zclJ26?y6259YVEqm5DcneAL|Ai0o3gpO$A;qJ(5NVB`A@tu6m?7qVnZsFvhKu+snc z$Jf{+EUA2wf(JTJ8Ub5@Tz#&x2jkiD3^MPzB z+Unf3jj}3H!mYH%ajd%uw}-{AMBcF8HBS{fKShS&%5 z`_cQ5$FtSZx&!7vTBd|*sZWI{&fHGkT`1L#r)pka4Fr8O=GB-dREZMuM1_ba!bhX82A|C#R7>OVnM}0elki^5A73o^-igpF zA(<`Mke-;6z7$GNEXwdoZ?Dp_DLb~!8^*TLrjziUwRR)Ot zcdkpE{D%^72x`YKc{x90Q%*{|RiYHrgZ#Akqw`;zSI?z@&dglb7v7Q{(AGrUfY zUJ3CBLCAVHCo9%S*1knMYs5FuxTr&j2LKz4xw5SoiPZK{EiED5wg8WdZ3Pd^qRNcW z!RvB%1&J318}#Zpw!_PF2-Ok~8N{J)-xXG1Z2z&>0w<%Wgk<Uu^ql9+X}v?rxGP3t_2&bx^}gG^}u5b9YVEa#{~%4m*M1{m5_ZIAS5OeN>nA1 z_)O8BJBeRuHp3w#N(CDkWHH!QjO}Y}RZB~Vb4Bp#*jDiJJe4RRkwVyz2&6-(mRs|5 zzt4*;-tknTgv57YL!yJB#QGwM4i@cblnA6o?i@m*k+4DUlx+oXRilH>-byWDCd2(> zY^x8klTIc2zY-&7J$A;z9YVDv;tfLb2F{KxB_z`TLZZ&0#Em0~Iy-f8BHKAFyAl%d zh7J0&Y%BP;8mD%4u4)PK&P@2TY%BP;%n}!NQ|SLn?gcjJ&vI;sf9nvcMSnKQ6@r+0 zbhF%IjO|OVTWg+fDp5jqh=Gv2K`4>`NOA~Hotzwt<{%wHGAXdZydc|(*)pxIYH10v zB7^71wt^>VdpMI!RiuQQA6$LoGgSwnt*(1;nM0_STl4wvRIeJ1w(2%^ou?8dc+ED% zjvmxQ@=>9-kL0GD67Jl^dP2=Enq7*NkUSo2NVYGhwN)*aD$SBQ8AZz?r;=iVel5IM z*pRaT4#EFTwLqt51VA90pJh*EcAq;R(tf3Fg*#Z-pNd%D83W6B2e~U(B}%yUpa;xe z0+0Cr5ow*=eXl(h%z2ra(Iw*+=2W8p>(&FiimR9<TtqLbcqTPH+9Uq1O@5N4p{Kdn!>vcRkryl1p-sd_D^8Bj-ONEurNg?ZgOjkfBPH zz!+@*#4`dmQdcE8$ea?YrF#NwHpnG8$WSFp$axdkNKd682k8*1C8t$DjD!cw=i~d1 z&p3O$w5@damgOMr4#MlUy#yTL;7K}r7__vOgUs^zfVY~}|57b?CplICxg-afQ;8C8 zJ+R8iB{|4Y3Dx2W0``1(n5em&$Kkr9Ai)~Wu90Ia+TV^fTrSB$I;BzqE47HvJa=JO z4$^84-!rSFQZ3n81A@LLpAYz+&aQhU;4`GVcR(NqX?GAgNQY1@cRyUqTK9PU@qE<% zWj_5V+f&3nWJoySY!4p{$^fkF3CaWRHB4i z4|u|1l7kGDP%Sz01sifQEL4e{5-U0}f;dAi$w4}$QbKnpSq{=_4!kRu%YLT6{DYRS$zM5B8Avdnu6&&U66?&RzjRl?nEh?q>6i1OZR(OR4q($kU5no!Lg9f2S-55 zLE1?@J8&JeTAkt5l+d?!~hlq{o>PJ{#k^g?gwKvI928z%xUs=%cZ9;j=LdP>?9$?(3tE z#^(b*n?tCU?1x1jr)2tC+hNLGpej*9_uN|EAWU+QJgHY`A32>FY6&d|nV#p&sl*|6 zp7TV_k(J3MImjv{kd-leJm-gOjkO{C6VwBlpD@Wm=2W5tGD1dk1?`*}W#*^wU#cZ% zNkLrvVt!Zg0mlq1(>Bqz(jCT@gS0ycPm-rO><%)gr-a(J9HjLU96BR4r*Y5Imd6=L0!N-QUU_bb2@SDL~0)pY@v87|%!R9y1+6o-WVb51HvTqvQ_+nG@;NR*JL05<5OaV+7!QHPLI(OM_VL0VgJ z->6FTe`N%Rjp}FQY%E!P>c0-5TDtGu+1bxMEVdS9{7?y*YheR9$aE~p%4p!pxKeb| z8#%~y+||9#4k4o}Y#;||GY)sHYi(6aOK3SrYb);1REZKY!@&k}kk(enL551GmaI!a z;H06AyHDcep-PmH6DlB(gS1%L9dSeiaSm9 zzf?<0XgNr0E94+^Dp5k#cCdj{nbuZ3rKyB!xiyy)JbKPYSAd?Jw1ExeAk)=SR@OVd ztd@%2Qh*#}x+2SJ*_DvBoo_ivYb)+eRYJA2PS_C-Kak@U_ok{u3Go?VLrx+&glf4p zmy<}LN|cZ@MzA64-K?xweOdb!y#qpg13jVO5aI#A22Ve*U-2A>)>gH&gqDM}w&E^O zl_()z7;K1l=MbtTULOeYot<;rN{CMlLOd_?LODY+zb2kn(Hl09gG{|U^@e43973X0uz?(;wG~fRDWO_gLd!u~TXCnUN|cb;B5Yvy zs&PJiTlEaLD|QnMR#Gi5v6eOB&5C zdb1Hu*QAl{td?B~iFm^X{aLmZ_t+|-T3SNOL0VgJkF83SkZcWX$SG`xP%Sx~4dRcT zC%v7wcqkz`BoN3!rg;N=2W_73%C1f7}h)>GSj(@&lyLb2*yE*UK);DN>cwBi@_wLEw zrnY=*cI!_Y#oH!s_u}9r=Pk{6M`M(}E%MeW#~D%8l5a3OJhP7QH}(^=Ogd?jZpJ2sW}MLJW6WL?_h-__%#@LD|CdK zTkE3cAW-u-sd+5#r)H_r`w_|g0P*%KB|+QA_76JT`frpw{W7cJ?9Lsd@7oRZ`;VOI z-Mqk$c3XL!UEi>y35eA-SNqGFofTX#uneK>&DIT_Imlm=+0+{+jaZ7hk|(J zk2>Dkv&w_-n+3k?nc(Q-aqQx`)OpKJ_DGMb`5&Jri!bvY?pGc>v%bAAJ5ro;kSEQ3 z#E9Nar+{d*+e2RV^zz_{rpNN#c78h7%6=dJ{6-s$xb%WaAQpVR%zLs|dGNyS&74zh zSjia8mCU8VK30#()5}4;(fudyuWseR%8G`3x1DJrN8y}4d*k{ejp$c>Fo@$W+|%Eu zV|g&8q>e8;0lB6&ns3RQbxt=UhW9)JM9H87{T=PfgZIwe>d8J!U-nu0($XMqx#e*G zrPk%a``>+Rs|(hgEdYPeZ1634az8+v-q#xxnIvN53cy3V)q(GV4sMkLN5VXI!KraD-UJ@m}Bot3L5>GfnFEN78 zqxF&~=_P!(ot26$AW;K8wMOKhTJ(}A=_R2=akwwsXl7#2ON>A-ferMMDCs4k#K^eo z-U#L<{u*SjXuYm?mdToHMvolvx7>; zl}JVg63u3K{m(29dVYJHv!hMMl}JVg5N*y4y|oxiCUtA!?EaH+C6bW=#KczLddK%J z4_aQ@$k|(|yEJ8F0P*KOyZQsWmj`cNw70X@RmPP_Mg|Z=FWb+*9AinzB^hU5u#79b z=RSL4{+=%yae%+RZF#Wk89PFiC?VqtY%IO$CjXUvM+D2??%@2FYROmv;<7KA_(A*f z;3aRJ^NvOtyNYIm)4wV8uRW?f_@d|PQ2$E_8M|QPx<*s{PpgjzzNyv3`7hOy@e0J; zlUw^6FeX;Nf@AzoO3H)X4|s;X+FFslS_v5+(RW+^GTqetbK0Au^n^*cNNr6+A%qRalB{f#y8 z)c(-k`7b4q5wQ9(|AqIey)?&P^!D)JhMz8T2-W&u=ew;`pM1AFh~1t!$)8)hJb2>o z4{|C|LeEXXS9`3p|0sy6F-J0kky`hp?DiH+-ha$U9^MvOd#*ob_VA$j=<^+k5@MS~ z_wN3^+eQbC+vk`uF&q3Z)snMoAikeC&p+h3;X&QK=Vw)-#AU%$t9d>jHE7(){uMh$ z2TKlUU#5g=>FGLrF}>A%|9;dX{Ax;0B}#}rwC>W;-TfP3V^j6{4xw6N8-&z6rxGQk zML=A<`+uwc#Mr)9gHH6e(y`rngR-mue47n&$!tI(-B0PfL0MJ+ATS$*$!y^Gva){g zWd%T@*^Drm4V>75tRH+?0f4}45GJ#M6Ni!YgD)!p5SR_ZWHxZ3T(W-fWd#5Nvq6;1 z22Rvb)(^g{06<_ih?3dBiO|aWf$PL5nGHZ-q>hr2+Ii=)tRJ{eGy*FC5EwP2#j!1GQv5z8(BYivI4;Kfe|iBMmR^JgsdMxV1$d35zZl0>yUnTT0Jnr zfxrkCB_o`ZeUmkc=Mosi0h zDp5kSvNpm+$q2`DqN(*z%FZ_g+wWX++XxpWBb*~qLTr=h-aSf2IG#%_{FiD;W*h`Y zxF{Lnaw<{c(qO99yfDH=$p}}aglcK--bT168R4=jQ9|sYbuq$4$q45VswK8TNX@e< zQ9@b-#Kq4Y7C*Ijmtg&dKb?C}+2`(vzH|HcZwveNo^IEVgf-AsZTjvOJPG2ny_Pz@ zv#x_&Z~Lk8&E{=)+;^(uhby7$6=XB!)eTsxN8f(fAyn(W+a{Vv-{R2SBD~l6rGL!E z%C3VWl_=q^OLqOYzSU#;3u7EYwa!0(irLuy-CL-6u)KP}sKFhb)ia>z}@sYCgxWehhE>r>M>;CM-HJ{XZD_M zHu87y=e9M?#<_cCLzO6@^KK?{%r&KEb4sYzUVUbmjr{Ymy)tiO(GOFyDp5l0 zd6~?%qe`uDD|T>QXp#vdP~+K`KUqn6?aC*VD;MV<|d9r30aq5yc+-2?-Bde^3D?- zLbWiCSvxmLYpXo=&=3H=rHy(^lxr$Rp;7Y9746+n(x#2 zSZk|K+SQ0vq6DJR*1C*FXEF;%91x|k42^QhdbcRz)w<`HgnwJ}um`)9>t$OWOD^^0a z+?wCIy>Yw|&*0%(4~|u$MEAbEt*uUc`drvJ@SJnQPKcg2`shR_7Ajs*QC#$e6J~{< zJTN@CbjL%EL<#Y{V552Oy{xUis<(SA9+nfK?OFPG$dS6{es_Tw)T?g9b;&i4HI7xH z|J!Yk-bQrTYZ{1GSDqH}89egu?hc_^&tJRHGA4s}y&J^w+dD)YuLeDMUaS%&+#E~& zu?J_rKs>SSL7nUks$9|Y)Sq~)j8kX1X2{2>FW+TvFFI*NP=DY*mw?nAb zHEX71nO)j{znQQx^thirwpH1e7sM)2LNak6E}K-%t3V!S`pbb6p_M!i@4w|(kjDYB z*FjUgZ@Zwax<24YlyIZ9>*{>tacsY2`5v+UmuhJVF>{{V*yl6&e&wODN|fkP`na`K zz9-(^y9&%C2MjtI8apXo@HaO2d?KWOc_E)JnuZp|MGAGWp{@$YG|N|adH>St@KmulP&8+Ts6 z)Y}c2xaE&EcfL3znYf~O`x$Q@<+nM0M9}lINsdGbH{L#{-85^fM$0xiglg^8XFs1$ z)YaGAgi`%A<;8qk_1QC4i4xB?KE{ago38?~?Yy^esXor20ou>&XAa?tt4E%U`Dmyk)wx=>qZ}A8QzI+u5u(wsMm+{ z26uJ|*xTP8yxJjD>*2F*F&p`{&vWl)&BhxCFN##6gnE6M%#9oRn2mRPKH(6m)uGFs zX5+KR-^I%EjOks?#tRK@id3S6_#Yq+z2|r*}e7Q-a5+%f2 z0x`1o1$I9c-c!dRR0}I)t4Dr?Jbbr4K^u%dOY7glwR1tDg!*t8MIXD!>M?Dv0~|uN zj_Ehk{wePj1ylRv?|Hw?S(PXu_B@=AYM-}pYvWryB~(jF3u097US{LJqyF(!qJ*>? z2zV1#4|o&45~?Mw4nndrPIg+dGK@g_oSorK_;}0BiaY(pn{XsbNbCdzya^i_;7vG$ zYDqr^0dK-QVR#e1N|cbN3k19gYb$sY4xw7|+<<^LVQmF(!dHnB@|=T^yc(mmK36i# z{Yzer@m*`He0&$)gr9g5jzkHp`i($F5jNmWSX;rHa0u1X5}G$*kqLMczDkt9I@rc8 zcoVPzZ^GIN-h@M_mRoap6V_JnCIXcxA!8+Mz?(=jqn_k8ojn>_LhSeHIn+{@(Y{*K68IyGN;_T#+)dvW86JFv?_$rZgkS}XH5b!3ft>8@r zN~o5sS3tmtKLO@xUz;j2Um)G6Kd0vqrq!o-^hlu#}B47tRc00D0zOuUIeB}$-9spka( z-b9#q6AqzT@ELN6Hvt0PM3{IJfl8D>Tcx|(K){;_6K}%F@X3B3_7bT%yooUJCLD

_I1(k?JSV(~DDfr&t*vTl3C)`@j~?Dcpb{m1{(GbKD|i#A z2fPVuD|izQp;~Uu;Z0au!J7zFqQu9oeztxEZvr;pO@xUz!JUAX!Q$*MJGP4QweTjQ z#G7y=O1Sx2coWuE@FpBWwcs;Ei8p~#!JEjpRi8Zrl_>FC<713~Hvt0PgtZmC35QTE z+5JhP^LA@1coTt2l#tz@AS9~hoDz}<8|SWQXBHVdgra1JkRwq7s|+LZs|@THwYI{3 zQHM}1%w1OV{0abBGK|%8Y)xvBSCEgMU_)!*B zgCE6tupm(aYYF>3zthqk7U`J7`-?MRfsTHENty4`F{ z?6*0m|D{@*r@;Ba$1bvZz&G$zqJ-GPntIr7eayzI^>1+q)e_qv;NzGL_&B~wl#q-7 z2>4NEquM`D?qo2w{XNZo$JflmOlFsUBjPzz$NF6l?GUL%YVPDhumj?NQ89Ot zU;OYShmd-NU%Yge*}zxXVdH>~SI4)u-|nq=^YQ57pYJpYz6tMWNu5C4b?=pN%SmJX zfnU#{Uz@gxL#Vw>=7UquwASrg`!G%d{m!}dq*l!LNZ$*I#$h&E=ElMlgvxbPEys9JsKcnCx^2qRSDfo zk;!z%j+7nPb9WE++{vC2XAi8F7XEqnnNfFUWiHA%^^iR*MLT8Zyp^$!zhtSNJ zwmNe3oer?9OwU2LIIXJ$d{G+{^Et0QZ|M*-&T#s=2OL7RwD)8(NB*~`^^yhOyy)~2 zB{Z{@$vnU0(s(YOkHcD4IfQCypGMT++(Gd<_ip#@{^&!ew<|GZ>n-*aES&W=ncH6z(Z*I?%7AE0Ii#K}qvFq6{ofor-WiXiK2H?)+MkJUfU#o z@3yi2zk|zSl_;Ti7Ht=SS3nmjt%o*_5)kP zdH?K)lu#{M&%s9J&o9{8=dY*VclP`%p}9hwX_$L@v<;cK8b96O5UM4+0%0T9WcTRc z4&}jb7u0pm8z`YC2{M@*4yzt-?77{0Z`wJro+Z)~L$ZE^jZORR8T+Hh`rlpHhjD6~ zad_fL3B6C5%-tJ)v9;*%FFc1(Em;S{#+*8vZN2-*_bnJbw~>sIcqO#e@!pRUm)QO2 z^+HXDP%YV+2^(XlKVhbqE5+%f^hK(=o?_oXhhMLu4t+{Gxt7kH0 zznpEo{lUQvoz_)Cyl~h!VBJi+gZ(CUbO_bb-jm4;{A60R86L}dxAt{rP20WMe_ZSA1JJXUtLo1%8!KCLufd@+Z;wvtvfW#C*+_>_Ew@w^ z^=}O?FWc_GSZDlLzv-fDnQ>2}XAYtD!xJ^= z8H=hltGdu3R7)ayu(6@}28-Nvf4Ud<0i;nt=VYnGwLttd^45^~^L?vquR(!OEr~ON znAQ9ti>e*cs|NQo6wdG|A<;GvfA|N6EAf1cJ$0UQ>QA-wl;FB)}_k#_I zy>jWB|es-{=XcS^+*+37wI5VH4U!u?m~7$e*D3ERn0sJUus ztD{t{YiBL?I^wK00-M$RbXJpd+tGp^TRfg* z<_zcV1L!>UdA~nwd{_6XSS3mfK53EB`H^9d(uaMn+r4;*L#UQS?oq17GjI2MCeOJ_ zl=!s%46~6R89v@R*nhWttbbOGVa|RA)xz^=`x$Uz9X9%nIobc={Ow+s?bkcIMU;^9 z?jSP9@8R=){O9>m4xw7w(ulWTv&y^S*6rT#`^NAN7Ver7a=som=GVW~OUElER15c9 z?x38!kL9#I*Cp0IJd2LifX}E}{`@)CC4RatQHc_IXET}q4F169eun-*H)jWgYGF0t z@7$Nsb^8*Z&&NZLmvPlskSL*hO|WzMky$>U!C?pO>kz8tp69H3@d}^M`C~`?bG2R{-pQq zTYCCGw-^z8_v`U<0J z1&I=fuo#_>k#&FiVyj2DXWw-Q)skH#s5zoIK^nzTi4utDn2mhgr{VUqg5l%F`uBhN zyR&0UwPg1NY~Xz|0pBNc#2LFW8fEq1o-`%S9x%pie7l2t)t=vUven~~J@K)lRsuc&sl)uZjSiIGZ_keyB-9=q=P;F+_wdz{U}jS{*i|bsa*r+)~NN;LEe^ zNgwm1$G`?MKS7fD@l~RP*3U9OHYOtT;}EJPJ1AiTnI9W>k@@jeqJ-|)v&@g}hePJa zAyiAw`N0MibwKL8u@mI6;DN+9!N^JD%DFET%V zlKJ5|VUzI9HuAOw$F^mD{3P?^)I$k(ebAKW>R&L6%K zGM9ir<|jxpKMtWb=kQojHGCx)iWPTh%wX~%z^AjYQA7_WD5;9Z6 zhO8MJLbcpGC~rv%#OLt!Zpw-rHpDjwRHB65S6U65~?LDauCS;*a{h$A73R(h&KTOnIAvN{5XVa$=iWIAoG*1^qu#S zDIsfk5aQhh;>G#m-TC76fk5UbNHRZxN|ez1WSJkIt8ip~9746kZ-)(Jeti0B$ovE< zQ9@hYGCy`dkoj>4)e?^$Hjw$T`+>}luM#EnK4E9gfyetv=EosaOFS>w5MRxCqnr}r z!+}8NCykK>66NwGUgAq!1B66a0+lGC_sKFpc0Z8$aR}9txCU$>^JDh|nV&!I-uz}2vpJaZV_wp&B_sKFpev zPnja~FkewqS zkok#|%ugWup?uj*$8~$5)h+WACz&6ob(N6aTd*O!!W=@iv@bY2GXvRMN$)P=Gml-G z^v|tS`LkrQuaDk#L864#&oV!@_Z*oYhfpoqO^13Q^AjhTpFkx_$bK&n$oyC@LFUI- zLbYT!9SCH8td}73fXt8cen7V#$oxb}=Eo_O>=$&-Y*^;UYL3j0L+B|HZ9~iaSnDG5_JiWi#R=o54s?p}a~U24psn&43NrhwKol<(5kJ z@A`<=*nc65*U0wxvPT#;kok#|%#R~cLhFY$^_^Ype&7uP4xw7Is~k4)mIB+Y ze#@JyctYC7cI;#KmC&;}_MSUCZ}7<54?Bcv$?kaAz`OLU@8Vs0Jn3yuCr^zlp=XTj z&BGDjJiNYE6NgYOd2SX^0c(}=HV!L^RQDY zCFFzxV&QnhpVj=Mu7e#ywY1goU73IDTkGNte@^QvAtw}I1Mh&arxx#ka0u0M`xV{+ zVZ8+JfN*+=5{OgVQ;+p{E40S!s)aKn^laa*z(8T5@6t1oE8m zv-v!yuM#EXq!oxOt6gpNXfti1L#USCO~k2(508_4Eprov{-cDP!GaArgXIva<@Sr~f+k4)U7sVdizunfHbGswkfG+qeEu))mBAi#vJr zU#aylzI;I+m)Cf=sE;qiW=TB!;$P1+!d zx3{h-@j?()kFU-0?HANa-+sYsmhN|yh6GE8)0rDudk=!Rd*ZWMzKxw){PG2B%xkv5 z^QbWiwt#(m*}EP@yEi9inIEK9njhpfV}5K^68Z01uD_#$cN&O|d!LwPu8~^IHS*5! z8t+&0p2eLb!8>W+`t=T{jeDx>?cdb8^t$REdk3%iwsCw%)d=<$>m|9QmxMgsO)b7% zitldYHEc!vf)j16uUqy~Mtu!E5xAs0qGkO@iOnv|f@+dP&H=^3*~v zvHkSCMw>2BsznlGaQ3{d4w`9OrFn@jK@%4X;@` zmWBjNXT5~qCTB0naek#1-`UR^^BTP*VvR|lmxP5cbhDS(SEs4PFJJI9Ag|F&tW` zBLCIt@yJ~8wp-xm4PqHk@(}Rsr;I;Y4Q8uhws_lt}lLRmW?_j@--iU??95^cOggZ zeY9!uTZj0Lrd{(Jk@B45e(>w9Bu?4$RBy^&zk4hRzfjs>)iS&O`YJDy@d^aLxlDrJ zVCFZFN$|VEtP8JEw@Aia5U4r7QpuW^@jK4cf_9Eyx#l(N$}dGbH8%n^w=WP=i?;ZM zU0$Q+92tzrj|`}}5vaM9pIWH7$1jNT8a21?bJ9kBghS2wEjrfRzV1jZ)ZFLS3we#2 z+t&n11`W z_a9%vJhWxF2W-61;vMhF$Dgv2%&2)>B&CX^RJb4aPIw{v7i=7K&u1RLoyY$@w?Ws4 zUl8Q=lV5d=_;o(kgLf7lYQwyvLDHU;(Aui83(U(HH|@6y|>PkO&6yV*5M#b+jyX^+6=rN(_mzUUCD#V@SV2KxcN8~)%Vt4F<47uy$BQ;8C6 zVg8O52l3w#RYn~5`w;tvG$j*ez2x!h$-HL2;#160@hL#-wtn90fSNbxHpY2Al;Br` zN&mS2w;+-)5XUY5ca=k^mfUlcD)|C&T>pkC_8neY=X0lo^cWEBl798%U$Y!SwWPm+ zIO^fgy<>6DzdmGc4!y(5%dhc`@7CF_kGr$6eW9JUIbvW|TfNE~fSONw?M-JaQG(xb zXU+NjKEz~#nBOvu8@~IwL#URHM48NkjaJ(I`1Z1z_7!ki=QF1Szl%;Ad@c)LOpnJt zRN@e-#V@9l=-2i^5c^kKXEykp?EhpplW^qJQB+zam&xGUhE@-J>oBVlC3HN_WDfpe zwf7m?YQ|xc9746E-9o%IBKxtGszJq8tgQ<*45j8ah9vg`#J6i!c&%^;FP(gX$M2uB zhUmMY)K*&rL`9n^X5-+Wp77+!iR77xIJ40PdnCT+HR}?u8Em{WIrR7)UfQ57d4eN( zxa3X9x8b9N# z8I<4%#DC)Wg6u24_|AIp3-J11s--KAOlHxt3qszHt%t>)N|fM;M;pAenao?&P6apvt<(^8= z>k5RfyYOw2oKuMs!$;+9d^uq*yt}h{EeqS?4%Rs1PiGabT3lVQtvI@7GLIg)E^Lmrdhq25 zRVq<}YZJEg|0BwjP%WWRbFN@`2eG2jyQX*3la}_-R+}C&V%WF$vCo=yt_`Fg`_e0Y z%!61f&<55HwpL(y*+b-s^5xkC(RB18e(^S5hC3-E9M^E^80E{j0%ByX_E~(nH_q(4 zH77o@eQBEOXnOPRifr}APZ}|_-g5gkIkgz&5YN=UdC&X7`tU228}l}rjn0X0>5JFs zt%ui=^meorzPaqNRQLvSmH2)1`%{lDD>EE=$>MJY@e9N;zCi4W7Z)wx8G$Mq+fnme zQuD0DkRo~~NzIE^;i$P0s5!smZhjx@L+^wHJ#DU@lA1?W^Sljw&s}0KkwjIBo^yU} zI;nY?#6{@KnhpB0^4y>&A`bU*8i&)^oBFtJ94`63bG#VecUFlK(uTN$FMl|U-@=Yp zY^xqBp;|K6f`HFyz8ZW^^BmbGEVmM_H<5fdJg&9x>kgq>;`_kHeTi4p;GWOyyWxC3 z;1xMu3dchJ&e6#tkX2~}QvH6Oqh<_%(MT;}CX;+OJbtt6ar+iF?=zzVO6YTw$&~l{ z+uCZc{v`%>A;_UxeTmAgUAp2rE+lphZ67DmYe2+eUV@l2;REuAoXU*xu zVXpmeL$4#o-F8FXcf30#)C((oV?8dJ-GR~CLi!H%=fxA~fPkn^_^Y8(49!VxwmHf*ptr~jo|5>G^_ z{%W;nZoseO;)+^xvMN!+t;g4`7UVjjt%fc;##2JI7`p)z z$JiZwW5j(9p<3dLfM{9k9)KkMeBYt?QrG|tgV)=G49YVDv8V%x}qo;T!SdlGjcvq-xqHRU5j!yx81JUQAmUaj4 z*|n7uHBdrJi?bOE->_a%GG$3l|4X$bvJD$`HeH!J1#R`nQ)9C#QNpdqC4K9J_0d-0 z`87NxREsfpwiWX&PQ0D_N(vH*y%)tSTirM@7ob!}XD)V1rG&1DaL?y{ZZ)rW<-IvA zm1?<>q6T;OvDWQaeOpc?O1SH*2Oe8!&&R5+U7bjgYSBmIQ$TMF^Z75!ytnXt{O{&Y z=Dnp7B_tjI;=~09hr6J4w@loU)!Is?!PgRIGFPuDvE0PV$Y7~N3CUUDeyslJ?%Z)` z-Bq1BI)rNJDidcKK58CrM5dwJPs_6^Q9?2su<`wd)|UUc3t2KHR7>(AsCnf-&v}R7 z`M7vtV~vqGYg{)P^<(yYyMrxDmgiKWt*f??uU+xC^^#pz1`eTGZoK`Oo)6?o(N^cK zZIo4s5^g;{nRk5nKH6$Y`5cE(Ey?Mi=KD=(AEx<1mGCW+e2SPWRNI-%Fkeru0*qJv7f-ozzCUbp9? z*)G>RglaKz#HWCM7UEZkLecX=RLY5RDxonz>;w2U8!l$fYy2SQQVZ=PIWJF3n8|## zGfS3Li9_tnp5cDty1}lu#{xO_T)lxLEtVn2&NEaLm9eZ4+%P#@~1c^ZxmrXXo=#4Ob4MM_-UAp|A-QI)6TXD`#~^Df`fMtZr>iIyUj2-mjU|gu{nsI6oM+z4#uCN=olFDcNd<`# zGS`BTu_Py>fxW$#ZN==nme3h@HNxT$GP<(=?z`1y97c@vzf?<0h!g9x^RpVgBb6v2 zGaPLE(D4~-t5NX4lu#{Mmw;fjnd9!0%P#O#qJ(73Kzy3aYEPHX$;liQ%B;qympy~| z9KFn(I^#Hm%%ZRXug=95+!792OEscGeVC@y{;^DJ!i3e z&QbX|wPX}E@8}Sc`GXBvE#+jr6Ul0+Xzz!t$Z}eCC1hZwEt$$7$ttao#=VvS_&TeP!Ad;^V(I)r!tu))Y9 zXEnxPwYI9IC4{fGYb$FjdSEJ1LcB285bw?*R7<=*5aK&KdkvHjZySVoUbd@=V-)>O z@w|%mEs1xhUXeqHrw1GG9IdU+g(s=CRV^(czMO?UID7_2VP}d;l#s{-Y_u75l|6$` zjGyBWs-^i)XRm>i8C61ap4i`-c=R9EJjmLJZAITxJo=(tVG=dSY1x&KXaed1U(?!( zzNZqZr6t7JUVWQIyy$zXLo=TLENFi+0 zXw$&j>fe)Ja0u0MYcBC!PbEr7L>M+CI%s?N*j60lB|2ENqfsJ|8o6@_iAKT(yi;o{ zdaGJn)zT8;v@CYc@frN^sX?Afl#u8-Y)CBJAymt)`7_B*r_892J(VaSc>~yxsB;k&qUm(-n=!=&NC&L3+5_=9r_A7dlDp7)&E&81F7ZG7OW?&iDSM*kuP%U1w=G=FZ$;^MJ zdevyORkyM0oE<4j=w1^i9~El*NNy_95+ah?c}i6;MAc5H*+sKU_J&}#G`()gw)`GmfjB~R7=h` zpyqN4B2)?PzsI&h4zg%BE}oCFAt)7ckWQ(T&C6MoM4|HkzZhjnrj>(7MP$=JdZ*OZNoWY>-WIkao&}Ht6Lk z!IKayAx{$QJe7hRq(i8doK^wxV5??fE41$Iot|~}2y0vEE-TAH+8w0Vtr8{NdcZr) z@%f;)s)TB}JIS#E$R;_+oJy2%>w#59HpxNS84|V?y*$<8ITN-OS0B!K96N!MO0b4A zEuOki+gOkt*eaXkAe~Yvft8w1+w__&2Wd5@@2UT#TC%eS1boeq&j)=^l_&w9!RP!z zKg)8EA?FX|ARR)rWFHWS;n*3(^)7Y_Is5vQkljKcu-?rkIY^#LDYOqVigwMlua?kq zkm=baI|Y=si4yP=jLyG*7v9AG)phRipUu_&|CCEcMy`WOWRzQy5~lg={c$%PW+tMG zOF2h{lS(s5`8JYVbIBm5qYzROol2$5ckdmYBkCvOs7@!65`|86x;cz~uh;s#KYN~Q z9`)b%@qMq?=e^%+t-aru^?I*0EHOy0kb5msN_&R*zxP=YgB+F^WH9&Lhg*nnJk6H% zPA1)tN(f46Zx{&Qh!GQT#`&S$^*1^zF#)M7*&*zq{|TWTa9GegVzv;G$DtTxc!_tC zL{KW<&Co7&SYnXVY#}0#Lp$NB#2_0YDCG*f)|Ge25rdrE3~SipD!!KT{U834X6KVm z9hMkmdMYBwPKp?0jNJP|{uZUkZdCn`^B0D8y)R@75t-4r^ybeuJL>(|_tJU1QIYsi znKik=!f!SEYkjrG`~xbs@ORCR^NP$2$~cp$N(^$Eqjh~}>&lULK4HWl;})G_kkf1- zLT6cl_PwcyK@Lj{G9f5MzE_;8RV4;F%@!i`EsQ?Q!iX4T66sH zg@`;3#UQH^gG>lYndf6``d(SOqd3hL+*b@%qrXbyr&0`ZSYnXN_*6uYix)A-#xtk) zY(!8>(Si8-Xf>s$(jG0e>pdG=h{(J?#UR6iia{m>rNEk190%N5-vx;GzV&$|J}@jej>Ku_7#8$Sk}X8A z?}$N$mzbMM1f}x*K}Gw9B?h^SEkxvTC^(79#M3!-zq~$Q6T3Pem!{O$hTuy}t5YMYa%u_omW4ud8o~_ro_Xh@ccX>4QOg z`@PM_HGkayxrY;5oe13EQy=ieA$+NVCpvyU@i&b_5%-C=JEGXP5P`QqeV8ZeZ;4`% z^xYw)_=FLI3|)E8#ug&*Jysv9{j6y=(pmN@DO68H?x8hb~!xkbiuc!}vONRIw zRQRr}bkiH(U2>fh0$*44VV1geW$rddODR5K#2`agia}1Zg$T@W>O(Qe@GHe2d2h3# z6jm8RY`9`wlI{W!f%S?Iib2M#rWoW9b5w;{%{-a#9`CKv%*h!iAux*yVP>gyFKCp)4x{d2OuGECUU73bD;qT%OjSz}KPF71ptaoaxmR8DA zpcv$2MKx{FK%_Jcww202;p4zXgbvG!dl2L$#8yrGZ~*a4^y-}|s%`8EVcODR5K z#2`ag-hr`&2<*bthjw-G4tkeI1f{Td7GksSp4WU@-}Yb4|6ICVLj-QS34xtgg?*HB zg~e>?{2YA3V3=MO?WcG-KHjrDE+)z3ef5R}Rz$8ErdEky8+QN$o)N3R%Ug*|zV9esMjU@lKi z4IEMIM@s}w6EqIr5tQN+Mhr4eyu9~h3lTWiQXl5K`b%A8v3N-;>DQ>PqDd_raN6sOkT zEAMaF!rw)-Mtzu5>vz!mTOufhh>#FVU$*u17xiub(g{CFw;G8+Tuq2?-S@&t+@QkA zzi(}Yu6)mnPZ;;SCNUP?222P#X&r(Mg(i6tXzsHMwHC=2l?zoxDTJO zh_k9b%)+&<#L9Ixo<74DrTByq?TdKrMasd$79ym>$?bmi;hYKfD@7C&f>MZ73-QMl zv2FX+B!*oRfoQl8s<1k|{|!^!E}QHTnN7T__8yuecaHDbJ73r=87vi|H>7PU9(NfbH*9RH3Ez{>%u7^N@a&mHN8`wGtTF(@?gX`-)pJO(WxqX z%5%o`mFsjEv1otaM7nPAtop%Srn*&M`*d27arNqIc}A>#le45L*JSs_w&m3J}_bFSD-2<4ir@0~r>tv>69in|H!yj)kveK<3wvIvfAB6S~|eOAT28uzuX z;AF&uU%gd3mQr`A+v1Tq6?eis18@x{BMy4%G$G_A&8J^KWiLsQe0fP@k8w;`UeXvL zFKNR|n&KrX&zZa=5RPrSF18W!5+O=WZ+l6~b4I?8^Di4AFA<{D4Y!x1JZJKf)=%X~ zoO4GTAukc4WbCzZJbd=f7&353ts zosrZCd5IA6l2(?JABnY<(rK2>$*P$T3eO?XNB>ouqBB{|R8iW?lwrU#!J2ziMR zn;rKC*ZFDBX%^S66L#gcA8F>?d1mFhWY?Z^Vza~bABk#d{(GD)^nJ6A@1FaC<;@YF zI<0ml$5&o?Sfk2|mGeOQ@0TBRcI6zD6Li#F>Qr~BxoW|>BWKXHl=JL5|E~X5mBPqK zYlJiTM#U-T#6pw`#EmKtk6g#X zQmSSgbu)mdRv=34f@JgJ*RD2l zl_^U(Ke206`R`(nK#c8CYG*d8of&n>{9E=0*CI1Q)ix{FsPf;=dK?)^U3sxl<;B{y z`rM*?uTdM&f7?swW8xajI(}6AD(XR6$`w6b8?Yc6AmqEHo|pZqa}6&`xf&(L(JIsN zWE^c@$;^J$$upwG)pK3R%xG8Gb;U9NJ+3oas-@YlqB7}3ifH*&Af$EmA-}4NUv;iT zVubvvb*&WtEx&Tz_=%SYQR*AmuR7N>u#~H0!xN*@ytO{AgQtH3e$_dPwWVC;6z{q15eQc-?ehrRuUhAnEq>KFE3DD3;_A%9{(D@LRh2N~%iv0w z&e&^&V-U{RYbpQj%)0)&ueRw-x2-bvCIqFNm)F14SM+qQ;>Hy{*+PUf>$;D=YN#{z zwyqjV1f}pz)Kiv>y?#Ghwh)0Yst_e(Z>x;G2|+39u+P}rxWX!1h`<+IeUyy7&F$a5 zHX$fQ+eG!cP8DyPZM#QW=b^S1N55UYrPb&Q+H?N*KR6qEeXpR~Mr zNL9f3PPnpzJ;Rm1T|L6%7}s$xwIG`BUGT<^Ekw8$gwemh;}kvBH47hak3MgCbN!`9 zBm|}MTU+X}G(S`hX;*4-@5iiqe)<~l8za9u?uX3@XDn}A^PXQE%!#clqWG6K+~8t8 zRjGW^)bC%?v4sd%KJhs2xy^`KhhFSzH_a(eWdx;MA7=%kRD+uIF`V>HDSlo18dc3F z|M1?9-&)Mnt*cs1G@`Z7xJFgziY-K7cGfs%Jo0JR+G@VE&v6|Ql)~ID1m^P&b9hTB z%;!R=N=!YmIa^#=aN-&Ap4#K+{mRwlCw|qp5aG&#Mvv>!Uv%{Pqcsm)-t6>?1sz+k zW@xcy&{JWR(XoYyJP($No|CsWp33ht=U2|!gTWhDIo!1~o10GjzchzqjS@AoJ#v3z z`r4WC^>H1}NedBJmk4qEAxF7hYIFWQ-%r0qDXeP7-^9_GbCyrOiP48Eic`v!f~{Sz zSM*e)6J6!FQI+GUI_(y%cN(mNoS!~^sh@FNLwYjf^esea_K7~mvs$Uv+?4G2J%UoM z`|Q3wC&v8YYR#TMqFS?c<<&jbS1YabONDOFA8FM`1V&!P{NbwX)>T4K3VIWwR6n%^ zqxxyFpsNbRvzHng@weBgF@Lx=x#y1&R(dsj$@M=%Bjc(h@I+Vh=v#<@SE>)qAEPpV zBm||fW)uSJ#1YnpQB~JA@QwxVhY*@SMrHnpDz29DS{?6WR1LL8^qvb*>Wun5cP*h9 zhg*oiJ1>OhkIAi&3$NQNeF!Bh0y#lEb~V~P)dJKW*i|jf4Dl=q>st$RZ|M{ zl@QCedS|N|hn_!1m)Vha&ig$tqiqb>7C)IOVNmr_`r3xRce zRAe*4J4i}l1t3JJGUhcy)QPhVyi>%QA*x#WmwLbI%KTw3X(ug2V2z?aG=Fqu{ur?Z z>!2EY10ghjOm-7dYs-CjH%bK7S3;B;Jf1)N4#rdYea0Hj?|kd=jjQ%({^-j5kuY}#M<;e={;085udp|$u*(plR9Er*QL}{z>|TT@)m1!yq~D?x_f*lxWR9va%lN6{ z>+Ib z-(R<%t4?i_mUzxJuxy$`LfK6FOriaPDt z&Em8xx_aUHZ8YaC6C+!fh8@`RuiEGxvK)fT$8 zQ+M-5r+YOKe&y8!5i=KF6n%_W0Bc`!M2zEtwa4{w{2mxVDekEUgVEB3F^*FYer(7V zBG8|7wbo8EMymAJ9ec`E4Yb=pqYcifHIC(1uNjEzA31yaZKI{3cRw!?YcISgY(5^x zQ!m|er22#1Tb?&;*g^#Rj&X#SXdKf-P)g$q4;}ZRbB2+>)UFJ~brd~6BUBkE)>ox6 zQ2$#*@GTGv>6#E(TBz{4UcOmMXwCMiaz95L$(ls{xlBxRag9~B7#!rTL^i3^dWDr*g^!(+l45# zw%U1Lxg(vCVD?Ghn8Bdb^J-PkE42{e+Ft$=Eq~}cjk2*{xOcp@H$L~|grF4dq}m+w zUl1ezUP#=ds`m7lFUvIfD*_=|)f)FQujHz4cY!x{Gf7K+6^)avW!L+bW^mb4J@I1f{6A!QjCk zT++VgfkoXbcbHBQ9wHbw8VvS7c=z@bn@n{t+i1^(pcM1|^pzLeBiC3bo!nt{mNc#N z-LrR&S?#s2UZtZ(iEy1jYxn(6Zz1ivVxecwQ@{Pg^jnmo-gNSN<#Xc8po)bpTZqVU zwNkgQyL<0r5`t3Hn{wU%_CnVN>|XiIXS8e~f^j@WGnUM04}H;8x6W4QrWhTim?@~Q zo!P2(X2(-Uo<>q{eSOZh{+Er?DJK!G)oJa1=ySES``vHO4(;xC#$VGJE2XG6Wg|Ig zwb1U5*1oxA3lTZa`ETQTke%v5CIqFZx4s@^r+SbrTZmv>RW}Y_y+ixU9j3Zxp7XU7 zGo_Rw@$qFC-*zfBa@)TiGdD#uuuEyFx5419H>@ANs~WlKM3@NIWVLqR_s!Q!ySv=A zerWe4zgjmTC`G;L-rc)@-+Jb}{;T)5Y#}1YoqxRMk6m-Jd(+vUPY6m;Z-c=%Pd>T* z=6Z{}+rGP7ibxZ|IJcMs_ixdT=1g_Vs{0!L7NwYtNUShbQda%*_Q0d}PiNuSO|BFx zdTP(*t=H5i-Z7`6Mu~9UUu*Z2$KE0BmI}n(#T#ys5R{_c`U=FIDiF79AtLhtw)yP8 zhjvwmHz6oRy$uF;j%)pPS3huA%N8QYI}q3TZ5y;l?>^Pde#;;sD1|(*8u^o_{-FKi zIZN87u6%Qcy?)Es9re~%0dEf*?VI8TM7Y+swfnB)PF5dJ9r}~j-`)Gyd09eGih2`k z^6am>0&(~3g==(dAtLiKN`2=}^_^QHC`G*~ufe#!bNA5ij!%pYBFF;~|7zV;+au>q zb>BW>orIv2@4T9QF}^2UYTmb1_s<>9VOpH%Bux(nmo=XX-(CFI15)&r2v;_@cK@{f znbK~lvEE&F?c9W*6!q5ESnuAw$$A}Ih{!yd%XYmWe0S4ZA8m=C6!oTc;OAHz!$jccFPJhWSnw=I*b=$r51qneZvtX=Ue<5@W;)!G0JEoSjub=Vm6x#-~ zB57Ll;CBuW?Vk0>8&d>}i2b*`Hnh9u2Ir}dLw7zceD}JW_DTp!QE$3EaMUs3yKDV= zla4J!WZu$Es$l;g`tDx4)srm|l%n4H3ijQ$kDZqoO+=6_E9UpqdDu-8p>`~Tt<2|+35VbX1mldc$AySG1aLWh%PM?)v4 z*(*gx&;0JO(>}#H^zI{4WR!@bpEzsUUxvHazDU}gan>gqe|L|$eL+G{ih5H9v%Riu z{M~(E*V!Fgh{(LY`)2;U@tWZ+w>>K%C`G;LR>~$zn_uj;xSO^2Clce22=WM}-5n2X zzA6^$SudEI5R^jA295l*jqj{xp0cEU(e>|5JQ;aq&yAtpR6pvd8!G$m*2~^(UG+8~ zLRuKE(C&}+zIeE+w7c)s3loA;)SKA2JFGPw+P!$ojx9upjXUkrL9uZ)j<4LkPvbAc zPqtn&At*(?4F*R)bDgH$XK}aDk(VU~CJ|!)PO6EjkGJ3c`{_sCC|=(KqlBOo^E)M0 zaSQfv3s!N|vGKQLoNsB1=N(Yn+b?*}q7*-8oST{+40c++TWxzBb?Kr0GW1p>LLOS# z9^-Gx!`u9_vbWFs^8AFL6g52=nnd;6-N4}0_o zN>S6QaJ1P*pZ)$P7Ij;`<0|W_w=EIOIu+WTE}ZRzpcHMBINP>h@TSeW1!ubjQ(iXT z?)f*=pOQUJ+V7~2Yyq+esA;Vk?!BP)*XOV^4od6FDYI-o3``b5!JuW@wc^zAb z;P`Y`X2IIE?eW0+t0x4dsA--1yz*bFdu5NeJRRSw-gk+}y1MxfGpnD7d;aj&@xAI1 zl%nU01G)Rht8W}I)qP(~a@;FOIh}A1LH2lby){OaqDv3Gd12zPkexzJ4+iJ|^0#4+ zMfX?UdPi=#*P;3445G@h%BLDQa4C)ZHJg{k^(noees+5W(>&kJlyp zg+1QC<}(t4Qq;6~`qcx~f6E^4I^|!J?-G%9HS_Int3IXsA2&QWCm|?>yCBjoZgaG_ zwc#A5wdagdr#${1uSIpjGWy<`OC~2Q5fd~c7Ho)>I7L@qKQp-JYh3cu#3>@;E1T~a z_86Z5Tt4%$u*YW}-Zmj9MNP{duliEFAMn;jqUwr~bkFs2)Kn zYFek~&s)F#h3s+T|13?uO9XBrO1m#u?Xqg9mHt*QdU--n3O8+pz+D;dylSsMeA@wc zWqdm#>@nVXExmV_k>`(1PkwO+-iput!t>3=qNWFfGnQ{2@u(L+@qC|Og_JpvM7-$S z{X!$-6R&??cgD!`$E>w7f>PA9;+(^~!XDL=Pq%C#g5y*C_f`L}Xok{%5yVUzk7D-MISJ2|+1({$PNcNG)z0Id^o}z;{e=t63Jj z=H9(Whc8*uUU$iciLFkCIyF5Qth@QkVEvTrG2`*~C*LI^ z>*_z|Jzo83->L5IPd_gqC`Hd#rPvksyc(Uu#rxr#I=JW6;zqvgao?*BiudE@LkAsr zWQi3>O)IMZU%Q1p9(&cpj!lF;%ws3>P-o;}k8w2PV~1@M_L%wJ-zEg5sA=WJ`Pwrh zw*BV~Z}a(XZ(AZbzQJIPJH8k8c*gI(o)DCxrU!%V_kU;o>`yN0sxQAe`7RMzSFd>U z8uhw5vpjqD%!Hs6JwM%|^BHp3!}p+Yi>}4(I@#lEUwZ4v`;QlHx2y$6un}h_G;Pi$ zHLY>{W&g0p=YIb6WCJ1;5eglSV|Sl<$B0K`CllJK@7VTyH9S9C+*=J`wJHmx!#Z*+*?$KfUWz_q{`& zNZw8~YXqXFBfOTaAdr4?jC}IF3|5>-62i94Q_h6R!Z2zcl&TNRPpm?9=tgCC3|nSTVfT1`?1pfsFS~S*yu6s2M5#JwzL5e zU_GgiNA{W*_E=@t!xDm0)U>{d&)zibapcZ>w`?JT;~NYv|IT3K{l|@)E=UMUQPY|~ z=3QLRlRXYPV&M2-@4E?+^7Y+*&dclF6@8s|(DljNsZn~q-t+%DA!dW8Hk{Rv@AG$f zInvdy<{S~;e#Yj(zY1?Rn~DfA77d^XBk_FKz|zf!>3+ZZ~E0m-E-EtDsj~)g{Kwb zxD_Kehh;Lth6rSV6XIQKT~U8P{ zAt(i(7DBwGct6BjO1GDZ!1#m^Zzg}0PE zky5aY5aKP37JYDuc}wOV_qQFe%B-ok;4OuA#al`(L|}fbgSQmg6>ljaC`G*mZz;a* z;w{x|Ap+kLjYGVp(5`q(2|+39EqF_H;Vo5cAp+kL^&#F;U3g0gK`HpI5MO)r)#1D1 zEu|YH*i+TiTkw`*CoJC5h%H25H7MyEroW)TdLVY1ZF$+A>LA~ zWW-xa2ue|J!CR^eZ>eSr5ts+1EAf`eM;Vo4}Pzq~CA#kdeZujHNGU+XNOX0iXEsdyABCyj} zAL1>AcEwvt2ue|J!CQ(`PVts%wh)1xjQS97DYPrzQbJIQdJEoCU3g11TZq6OM}3I5 zR2SY-MFgd=LlQ!~rPy#Tl}AOCxHO2%KxF5Al{lyW%Y+1f{6A z;4Q_OjCe~mTZq7pUVVtS6xtPUDIq9Dy#;TnzHPI`<}KB1Ap$#k^&#F;U3g0gK`ERE z2=U~Kh>33^O(G^Wq9iNbaQo;nca0-hqkTuzC=oc5RUhIl#fh+ZO9??K>MeLnpOjYTdE6hsb&iiIIUG5;w@E$x0Dc+!db5n;w{yMx0G_dAkLjM9lWK` zu6Rr7<|Gk_(5Vmcmcn<%TS^E@QE$Op3hj!wG-3-8h)t*u@s{esTdIkm6!jLorTU7w zi_KfA*+K+j6Y4{}rK<3j5`t2QYzQIVQg98#TS|9E!Rm1Coe85r2=SJJ`yt-ah%H1Q z9xa4;OQBuymJ)(e)LZbDVpbDxX~Y&H5Q$SC;w^>mino*yl%n2(w^SA0Qq2}35Q$SC z;w@E$x0Dc+LL5&B@s_3wZ)wE)uF_S150-ix48&U+7T(f`EkuBQp+3Z03MPkmO9??K z>MeLnRpBj-*g^#2&gw(FrC<(-x0Dc+qTYhHR2AM*%@!gMceZwSJg_RfrG%gqqSiu) zx6~BgQpy`8uWWpy&bgwfx8N-W=T5vO>#DZ_5z@kh6{bGKTbeGsrG%gq^%lIPVc{)} z*g^zY7V1O1rK<3j5`t3HTkw{u!dt4@LIhYA>O;JxVc{($1f{^y5JD`ZU^I$_lx|^z zTf0(LF0qi>!b0+U-rIl(`CC(1Na{l@q~P3%g_IDKqTYgq)D#wyb=6yn2x(!$98w=* zAx#$+QbJIQdXw+2cgjuH?yrx!yk-j#;1sEke_Z`9bN?t-*xJwCBOxf|+?IvoB?NK; z+8&XY&lw`+?US5-ATs98mvj_N^9!LU4V4EU#sQTUmxG-r>2926z_*vNGXE=5nwc{53!KK z9%3OS1f{6yU?GJ)#6lXeg$Rx>SV(PQAteN*sOexKHHC$ge3yuP9Uu#kd*Ef&&C4%D%7E;(lEF|xWdIY7Y>0lwXg@u%S zmx!z@v5=a=LP`iq(eqO-R_~+Q!a}OGOAQ++7ppV*#@}KgNmpVab%ljAV&)E=`-MHq zxnFOaU?Ii5JF$>_8r8QDf!kc_LoB4Ou#gghQq**?kis5fA=PXlg5wJoQrJT*q=cXp zH61LZwy=6g3?zq_Brr zNHtrC;P`@t6!s7cDIq9DO$Q69Ei9zuyF_GNiG|b@7E(e`ik=@Vq)8s(N~db^emJW% zZcf&?+b3O#g%t0HSV$veLrl44sOexKg+0VVa-^ZR8t%3G{5tF*7Lxi93n}a&7E(e` zikc13sOexKg+0VVN>(F6@tx42 zSV-zaETpi9SV##$DQY@cNL^teCEF6g@dXPh>>(CXLQsmD4i-{dSV%tK?R}SstShmQ z+QLFg-cBice#(LE_($|17E-O~QrJT*Bxg{MzkOm9ETpcmkW#j36g3?zq_BrrNRGtywk3k&3l>t?LoB3(pcFM7ETp!u zkR1Q$eV2%=E3uH;!a_>kPAPhR$}nCbuYs$jg$=|)s*t5Xx)KX1vgwM2lyXyv&k~w; zekW>rFc1r=D=eg%Ekq#ai24ua5gzWn`O_DU|8^BmF+9Su&RH}Vh=tS^7LwUJeG3sM zTySpu(l}3%SV(PQAteN*n1Lu*NNr&u&1DM_=uaaT3#lzEq#+TM!qW;N7Sd$oW~5BU zQ4s-+2q6|yTUbbDz4Qo5(Kf+CY6}agVha&sz=W=p-$#9jh13=nQbJIQ*0hE{@L7FP zy4&7%!d4rv`nvj^>#Z_e^M_Y0!{2lFxpd$D{~5uSzk`^one))?KK;`#oD}^~s{Fl7 z{jrag5a?s>-#`R9o@y(NW2A9>mQwh8S^1^EfndwuK`e`LY^iZXKa?tehu-i@D~x2caWZuvL*h-WAIZz5>Hl@ZeJ{|A5#!b$)D literal 0 HcmV?d00001 diff --git a/GEMstack/knowledge/vehicle/model/meshes/left_I_link.STL b/GEMstack/knowledge/vehicle/model/meshes/left_I_link.STL new file mode 100755 index 0000000000000000000000000000000000000000..e0769efe778ebe005cc7db9fdfbac6e5a0e5b7d9 GIT binary patch literal 2284 zcmb`Iy-fr$5QQ%$rT`>#8KMG~lSmL<5I_|qTLXpA!Ep^7F)^LsZ|vuNws$209N_VI zKELOmTXwtuZ8x#pe4=}Lf7yRL{v0p9ukYS2Z|@agTkCj&Mqt2KHL})Zb{GY-vJ1ciS#3O+^1ShJvob;qT zJuUx6P-oN=rXBOEM0|aiDR&-~#N=qLM(>1Epo%;_EfYTD4!2!7;Z>IJT=`5#MCG`T U4I*w3@2mF_J7dN);*~7KFMt%h=Kufz literal 0 HcmV?d00001 diff --git a/GEMstack/knowledge/vehicle/model/meshes/left_antenna_link.STL b/GEMstack/knowledge/vehicle/model/meshes/left_antenna_link.STL new file mode 100755 index 0000000000000000000000000000000000000000..32c0d65651dd924631cae63335ebed00f9b92f1e GIT binary patch literal 50684 zcmb__dH7b-`u<7^4N{R5DW#$mmBeT7wPcKlB*&phhGXcIM8}*^aw@5)4@rZ_SVze4 zdH3E?isVonWXL=xV;qWp_j=xE@ArP&oh#q#`t?V>SI=|r@m|k*)>_ZKwlV*I|NKpEYqvkhhQ&$ZpPG@+&_7tn@RjT;5+AgI(*Y^QTs{D^&D@tJ0qi3zeWcIoZM9-(Y6q0j0$+3>Rv`^vg$@|Oi zH-7I@s6DTfzK>s5+#NR=Fia3^VZ^d+CKcYd`{-3onzSHZwsuGk!Cw4CjM@K*74gUS zUML8*Fk)EE+X@4twt9{p@tU~Z$n$at_TuMeOkmEA2hF-d5Pau+Pn&9*LcLK3>N!@; zX%{aUaJ3-V!ie5C5373aUkB;4T71>#QO$nW<`C?av>sMf=jwy>9J~L$G763zAqciG z;)5&NRqeV>H%0X9G@~%{$0C9)jKJ@T(p4R~_QRmz=UYT%UN}-k=^VIoo8CF@Hb~ik zrx2vir~Dka^Dw=0wlD(sS5bE7VS49`V6XD4>iEP8o3aG&IY`+6mINvLz@8v&X~y(8 z_i20o%)#<>*}@3$I7pdqOx5xkc4F5e+Zn-L{6wTh*|bHmg%RLekhU~oqD`5|2=?OV zhWm)u*p%&j=X`}=dyvKzV-S688hzNp2t=PCjg=C8TpE2C!Cr_fL0R;1Y4l+WBM^Op zGzJ@kNbS-{%@#%=9tWk~0Fm0Ik(v?gg%})^MQWEuYPK)}kvb^#AAfZ1<_=tPfUtxu zj6i=CmU_;Xk2tsF(S33V_CjwLmij^T&Mxhp(Ibax#)6(YO#5&~8-w22rM)v-7=b=G zEbE{C9W9Q*oNfWEMss*9z0@ z%$T0j&vyqd|4$CVUi?IiLDuKetdA{>Ku#2<*`Q=gF3px0!Cw5_j6p``(u|DnobMJH zS(xU&k|Db^LuLyjkOzlpek~cYOEY9fuorUQuq;D%X@<-eMj%5DOL;poeV1nXY+(dO z0AV@;FlO<;N4QaOGwHDy!CvX_Vt%Cv979GEax8C2z5M^{kt&J^y(&Slg%Ns%6&`I2 z#s=7#sNBIfq~`?X~qB@9em}&j19$7Di}hpor?lEJF}%VT5KJ zdR3aqC5t)ULt69IEx4m+-S{+B;)x zkYH>e2(~Z+{gt1;(yPMwBfpYr3z?dqL)LTX?71M2P5L=@$!n2i`q^{w zVzgwIenwajY+(fQM?Z(G=g?W_9D=>duL^m4LYaOx+m9?f^5X%`;pMl_3}tNK5gH9j z>jsQKcJ7Z<%Jlt8Lk_`S{6r+vPtr`EEsQ`u@7E1VnZ93X$UR;5;^$Vpm*U^oxzDey z9Zs;@7G7SlBG~4f9mDPR9#!Rk7wv7^lzyiOwlHF!e)VvlTSKsyqAT*}XgL1cpye&o z<*J77Zo+Ewu9M$DbU0r?`y|#8$ zjM%5&gkWs1|8C`~*o&V?`BlAiMvbZl&FaaO;CDs(`_Ek!BTjC!tm4iNb?Kgp$GA>n zZ^}6K;wMsmRk+(i`h4J3NT1uEyDCQDd{uwysxmKrBIQ>FW)xB`;fWSfj{Ui-Vg%kz z;ZME6%!{8$`BkA6MQOVO`wD4${Bu{u2=KV@r`Vo(@e?V(D#VN^jZtW+Q5w7c+*L6G zZ9e)_ks3gQ*ZtYnyLU~2#EnO9R@e?V(Ds9`LMo}LnXnhg+oOIO8S{6xyH3NgcHdJ?11Qhf$U$KBdhF+wvZLT~A+*o&V? z*;OT5nE#eqoT68;M(2Mc*o)_^%MloD`IRckZ!yO4D@~f~dcQ55gOAGyj7$9b4xx*l z*CmW#um62jm^JY0vNBHK*+D*1@%NU_!3du5{ND)n;wMs$;JF_B&Ss{HUR!%sjKKVi zUnQ6OD?bMxi@o@Xlp}bSgJ)a#NaYB&FoI`|{x^cX_=%Jwc)ZLbdOmkKf-Q{T8H@jo zU@v|m<%o1->i?HVlSQwsy+KCsD7^d}d@T0jCsK}3OTquIBIGw8sT{!;M(7n%lqhtf^6aNoa#Rz3S zq0@5||1I7jd+`$~zbbfTbtE`PRsq9DDo3z|5gH}7a#ifbPo(@Dc%oSq0^SGJNqE0M z@dh&l?wo2rN@pp5gY3mmq~veRbqUy)t$KsISxrFEYin1<2(Topj3_?`AB(;Ci5N5O z;Vazgbtl{LZ&Zf7Cd{k7T~6y1F5P*b;G?GF(X%}>=wdhW!G~i;8G^=zKTs| zmwELB=cp>3V^h_-_@4XEa`*ls_mQm+@Em)Mo=+BTDm2q`Y~Ok3WbAt50njFpL5 z^{~$A3Ia@wz(hrWi3ymPC=;{lXuS_X=zS;xOiaMUM46b?x9Zc4{8j1GjWQ<2U}B<7 z%qlQ-?M4t_VgXE41eh3uiHR~Xt1wlT2trw+2rw}M6BA`(RvoEpkb(dctH4A>fQc4N zOq7XPRiUyyJ%?wzBEUooCML?ntacDg%&O+V!~jfG1eoZ+#6+2x)xBw}m2+sTRRoym zz{EtEnAN0#iCMK7m>7VGiU1QGn3yONvsx~VCFvXVu|(e>nCQU7SeckrY-xl`dF3OV zA_hG(H9Yu(x`iRfjBq+ClKF2P;}raSz?h-ChV}0nUuBZzh>0~0Xk?ea`&yyV-q$#` zFye&%JBQ!jSEo=!9N*w}+ooy9sNsW`mLb^dty;~)q4(Wh^~?MvILFU-KWSgP>7UWm zzYKP4VZ@pjcMs3IXXio@F@O0+TXWkxqC-~nFGH}`#An-t-@bcS)fL}7gL6dJ)pg@K zuZ~W;vyWp7BZi*ZDm?$?riCJ6$WQHDjki}t<6o&LL$KGwojQc;Kbl?j%1@8r9Cz&1 z&CR=U$GDH};Ml^58u#xTR(r8Up@>-e^@;AfhSlPp19vJzu-E0aJBJ-Fnp<_%pu2I7 zlWzH|o7`)kc=aB}v4s&+|JE@)`d&8K}HrpZcywVY`a7jn>@_Tak?ZY$Q9iuF{uHm+} z?e&$B=M`HR@$<4jf-5J@RYbqa8|^hs>&2c|j9{<5{-_r|HS1Po$>PUm+Rl&K*z<}l zjCgoP&G3*$k1FE&;UCx@uU;B^UNM5bR;_Ck9((6hWy#z9f3eZZ$+71ZTNv@&?sdcN zGoDt&#)*yH(6)19&nrf-*SKeP5APf_U0Krpt>*62uNDcf*usb(ZfX$zkt|Zg+8zhH zLASglykZ1%EbxjgjL>XJ5g)qw!H<8LB)rm@w8+OOok^45kAB@D zxVL_Ts2F{Io>wPaa_-Kt=M`HR@#L$oRb1A#ks_XbVOltA+(h9OBiQS(x4Q*z_G=Oq zqt9&%?+H7cv`~1(7Dh~b^ZklO^P4GRU$c$<@Q7dHgTX6CuvgQ?-GeJ%ZV?ruPmOQ? z8`hs+C-J;u3nNC%`l_OK-`0wFWM)VE^vP`#&nrf-*L$6h3F>XzHY!G+=iX~>_uBuU z#K$YPFrwO=A1m5C)m{D-PahQ8&NrQ!_;|$@ zMqGT+Zxt7fK0pyw^9I}A_nnvcc*O|zT5!}!!Q!bMwdXux=M(L~ZH6R1Ua^G{n(r!N z^>dA*(LHYzUg_Ml#3-Gcmfyp#s4V=q_O{BB?e3ZzUHir#60g|8h`vo07LJ|vlg6u$ zdNhkyA9$VciV^I!xW%l(U&hu}mc%>uj@Ny3r|^m`j5u!SqQW_@nj(%o^rpD`FKm**Wg%K;Be6i5#%Iy@f^W9IyuMKM`ykZ1<9X4=& zVf&AFRhB%~^R@VipPLA;*usd#!&er*eWZ>e4tnl`__4a3lViavMzGh&!yhkvx%=+Q zk|*o`7SGw#Rd~e~Mm%@yn}v;2cT&Xadw!4G&p$?Z#R&G&@rSZxR_j{HUhf^gielS~6th)2d!mw?ZC`*C|eu|!KwNQA)7W9J|0{vB?)DO~c<)!VS2LZb#ve>MU3kS7MxeinO8sD?<6n%=o-ti`#R&Fl zKd@Rft;OoJS9|=+_{u5w3$NJ12=rG`sUIBNeut#_Z~u{gkP+-v@3fjxqsu?kUhS8o z8YfNu`?mChY+(fYtEkiu-u!0kq-td~iC2tZuUfm-iWR4moCW@ovI11*un_( zS5c`S{G@e|4Boqe@QM-a)$D>gQGWK0 zYr^SjhF=p7G;fcPw^w9&dyKq2(7ZjfAaBnQ$gd;h?Ln5e$H?15&D%2sdm%fIkhfQ4 zd3%h!J=DBCvoHerb%eY<$ny3Wd3&gNdxl^yWakm`_KGZTPms5Vnzv^bMj*eAkhcd} z-kufPk5bTBQJVM@Hk>%|P@^-6vduCw-^6LnBdywVr3G#NUd3%OnFXY-0^7e`> zZ%>f7Tg}@u3nP$UN66cQEN@Scw_DBIGX#4fJCBgJS7dp6g1p^o-kw<)Q9d()ygfqR z9%|n1DygfnQF1%t3BQ&lk0(pCayj^(32=+p*9U*U5mLP9Wkhcr3*un^n zD~dqgo*-|xnzv`iVlQOp5%Tt+$SdUS3G#NUd3$DIMEM*U^7aDqcHtGTtn-RHa_s{0 z_AtxaBjoK?^Y+Zb2;|pQ$lDcxygfqRF1+Gnu@`df0`m4S%iAO5?ZPXzFar5?74mjP zAa9S6w_DBIvtzLra_s{0_AtxaBjoK)^Y+Zb2;|pQ$lDcxygf$V?lf=D5bT9qyMVks z%<}dadArlRJ+m+Z`E?cYc10j>kCC@K&D%2sdm+~@Aa4(|ygf$V?lf=DEQ~;YU4^_| z5y;zPB<+b!~T;T0p;3%PcHyj@v>yxk&i z7hbW25y-CtAw+pY>!U*(Ne*Q`k$lD$AcIgKh!CuI7kA7)DP>*d^=ls zww~wVjahc*6noewbqhYfVg!3FZqY){QS1lLJ?|NN!tpB$KEGlMBX}O(m};Xp*&qA= zv*7b9MzGg6pZbcPwrz_2;DQD9T*sMhWxky)jNo~AV;aA`pS$4Gr3K#)GJ?Gh8`x3K zQS1ko)U0qb_8$=WevmDU;CXms_U+!sExqQ~g6{_z!CoT|?;__Y_JfaX>gReMIXd$F zAX^y0v+7>4JlHLGsb1v!K}N7wjhncOGFhW=2^&HRcaE;sRknQ5bUM@$lSNT=x8ojKH>bktFbLo1$ z{MI#k9c|xu%}_TWni~J(r^c2ojNto26~m_U-A!NIChH%JV6V&1*(V%1eR!eBl1pzt z*EOrWwz$SZ7Dn*u3HAeM*T;3N99>+;Aq0Ef`tMfZkne^RifnJXxThP`?X37XaF;EN z;8h^3t1ar}R@OT^J_+rE5$x4(A#&ZF{#Gcq+AFKtxHE3;CUY`uVFa&c8S}+CJGh%B z?zU8#~@5YmjVV1g|a{^V@C>>;vmN$UGb)*h}j=3x2l6n5X947T)vK zI9W?&3nO@y)R>FLO$ht^{%Q`vD`tFdV_NP|#|ATo=B|nnycTB6dDX_*MUSt^-8p;l zGc>0A{0D8FT^q-~H((1RFg~YswfEb6V{fkIWOk4d?8RI#=EA>McV~1Nlw%1acrDDB z|AZ~vz&o$cF_FEP)5cu=)4p!V5qHY$AX^y0YhlLJTz$A(*>*;*MX^_TJMX;i7}xyC zg}GMC2wn@rjzDwzIjp_rA_IGIj4@`=vNK#mvs_lm*un^2Jwt3i{X*CJ_(UQ#BiM^$ zr7`;qIp4jp*K6?u=ndGy2;HASA}SQ151;B5y|+!$5xoJg(Q$PGqm3Eg=?wSHzzuP| zA1Xt(FhXml(sO)2&=ppF8Go^~9Kl}YSJh_Hk#4|4Es_N|eP~sIM*h|M(+8a!GVYqGgP5anq$ZTPRj;R!(qdSSaj9@PvCu(mn z^{^3Pi;vqxKGSClBXn%22px0g5UOJkFFv<1m%sa7`1pw{b63TPrAMp`R=x6`-bd|P zXW9MF?~%K6_Tpz~%&N0S+tzQ4%spL3Ol$pK@Y~H@$oannS2n9274yUvckJ&@ z|7y=%WMD6jF~&T-qJx{!q+KrhFrvJUY}NG@?x7v_l}OFUVlR%B#$0kjSGQ(Cr^NRL zY+(e~tr??LtWrD3HE>$dx`leU0~YS>Zavi{PyO83>fDR0vND3tXUwmQc5|18HaQcc zB1W*6&gkgVUH-=IuG%S`<>|785&Yax`97?+>vBYUd4r5#FP)i+idp#j<7&Gvw%Joy z!WKsG`#0vcUTbaNx%CqtcNxK6I>Qzfv+!mUKeg99wT-N}vxO1NV`C2d_HQ5mB_#d_R<+ojXswh+QXi|-&qoU z*un^oE5^*Owi`CPP|ICEt55RSH-5BTstaWVGt`)GXKv%>zuZf>%Lw+;xlHBm zmFsJ|6(=7dtH^9&1Tz$w{ zY+(d5)R?|kyk>uy*iX322=?l@;+Ej7QF|+QKOVWpe*Vx&5_j3c2xcgH&TkUi>xH9* zyNqD3+t>Xw=vAwQa(9nK&)Zq64-xLNg%Qk9W8Qdnwte>3w!&RTuvg!gMg`C9(p0&- zd!u{o9}n&(++_NdZEXNpwmwcmAjXZz1X&x{-JP}EsS7> z8dE23X`lOLu5gzT>~-11p+TE!b(Fggt=-XXoO7damo1E7h8nZqCu71>kJ(YNk987I`sT@@p^V$+xpdant) z)gG6-bN1qAXiWbje+fIE@~_;}Wdv7j8uQqgLu~!J>vC_9y_gHe4E-svi<@nqV+kX; zViPfO+SPVw&N3nRE<6SKA3-C>iRj?A?v_Tsi_%*FOr zJ8DwzT&raSS8N({eWQo%L;IW|y&4~jy*S2TZ^PH`wsTJVo8-G}VFcHB8Z%?$Lff|K zpv2EpGlIQ1RvPpDkbCW>>xW9d%N9oHUV0KyF_%&86g%Sle@ITvm87gOVYD%yHNV)N z+Whil!MBwmTNt6*EImil0b}it7=PogZ}ki z4<{6^N^bt4v1JP*`2LJp**^*A4IU=%gAwet>ajKzgV%S~-k{ab)$HZl4w84y7DjMo zE;J^~=7mSy(ocBB2=N-=kvbU2U~D=stE)c<8b1lW|y&Vhba+#kVm#e$+Jl`HiO~UNM5bMy{?~G3cPi+8fO3(IITx=yr*T zY+(dft{c;8&iJ6+mAgvZWdwWa&J@}kJka&z;F*i3NNi^dBe(+Jn5BE%QZfI!${a#> z@sQ*4xmELdedF9!ZHA~S-TAnQwSw`}rsVD%$IZO>85%Qp?^~+Qdh40o)7=bFReFOr zv^zSeSGh@g13nghXI{(&W6qvYt8hyFopLPM3{h2L;`Guv>-_aF0wr_^0Dz&Idn5%`^XajZ1v;ZLU( zHUuN2H(<+V2>R-RYF|Zh$Vx`tYgFPcqMg^imf~)d#$C2Bg3o8nPM21Xo1A@##9c

SaTigvDvhFSVFbrV%-jta8>d-@?kOvL)g5W&H}VxKT@X6E2{?xxF< zht@Ur>YB{L2xh1;$L%>ReskR*;VvWCOREi)yZx8+h=+W7zC;GLFoGFsOy%9D$Mv2$ zMYzid_R^|JYUO!0Az{g@Q=7KSA2FJ%&+*32h5=LOmSt!kA9Dewjag8Oda!h0|<}~)E zX+Aoh(z>IJAlbqQj4TVKIho7%7!xmQ)kAs%Mz9yRO{~$cy*s|^vtGGY%Lt4U3#GZG zhnL+EPrLRk>DBmH?8Pw#t#;A;_~fI`$wePVV4O(16rB6?J#oj;Lu7Qv$6_yzm8jlH zo{T@-Z?NPHY+(fNih$Yk;_er+=YZ~bA+c8Xz?R>bFY~)!lxFVYbmopNjNtPbv*^~3 z<9|YH=~qk`!CsgzBNg2XjbDzN*ZzydUA8cSpPMn)eEf3!!BI!Z8)O7~VZMyifX6-f zM10@JR^l#O7{Tw~m<=C268GxRTH-Dv*bDPzq-r#K-5zgjw}-HuEsS6u8*^{RQE`p2 zo6=e5>{#rD`7%;xuJ3tT+^6&B(rVel2yTyH`@DAXxxd~kk%1BHh50g4nI87ZA5rx& zV2;6!O3SdZ}gtq4bX zrx50wF(dY^lkC>NZ!!y&fNWue?&u=SmsOc0U6o-3dvUu#4PAo-W z8!LZ)uNQ4mSc6O^=o%zj7{T{v%=G)3CtnWhCM}8)?1h!TLTQEfq5-=kn<@{M7R44u zV7-NOsZEB|Pd>D5q(w1;y|D6ED6Ld)d;Ye`nwMHh++_k|Tv?#VP0_!cL+r}DXl&(QC zg1xY!nC)SVcr~_TM~~dxPx7Trj5YEw9G|ZhJ1r z5=Nj}gp|cI?)xP^;;f%yKM%*pVlU>jF{5s-m7M<8MyUj33nNeyLdxQs=QK)2pRjYT zMX?vRO=I4BuVu1(#V)y4%Lr79L?vbM^Iz_h9BbN0Cd0>KFOD(DWPa10+&2g1tCa8qnon$g>VT69ILaX$uHXNUfYt~TCfr>W2 zGnQ1)@lI2WHl|zDGue05Zpp&$Dnqs~LigU%bL>6o$mA@o>th6am0#7#-w#aE+ClxY zgB(l03n9Nzh3K`5S_!!SIsKCA)qjoGe%ILVMv_?=!S`p(m^!BeyMiq~3-g%POOBQ^P7-s_$;c;gMJFy&*hmnuWGZt2?>x+FFBeka}Q z#p_SS!U$CCkt*Ju~6#5`B?0wYFVwndf>sGlLO{GF7;PzVFW7nNZtSDf(`My z6URwAX9Rnp`qwLUwT`TH_;&m?vNF=}iiHuV*rQzvPFp)WzGYKaiC26q_EPn-R;0Xo z_;vC0rp+WKvV{?-*rVMRRPQXS`ix*NRAXm*#~Xu6z$mQ*WD6ryEv zp6$lY=a#zgIIRn33nNfT9+fKMyH6eyzjebOQWwq$_Tp!VS%aYu$B(b8mwUR5K=pT2 zs_cK{;4k8;&-&)xAbT+vjJdy6jU?>ZFUJx_pprZ)DHINB-7IblJiPes0DbdqLmitL{VO4Kjkgbgu@DyS+Oc zlT3blq^Jkj!U%ryXU@zTsLgVh?*Y2G(y6O~RJ6jmRJjOiS>{`kC zUw4-l#R&F-3dZlrp>g-n20zBT-P}xCEn67D?GbbOvmT50eDh_|<1m7~bPo`XyC3c_ zA^yvmkwhQ1FoNTX=yBpykHZM|(!ESHib7ozrRo~CFoNSFz7w~@HAxFqpXnEeM3<)D z5|ZE0vH5*8bZ5LXFS;W6{qgp34a|kJg%Qk9V>-?nnq1eivE&SlU@z$W{O%sQ!{3Z& zE=c}1yIWB)LKa3aLs6aZLc4U( z!O0H4eI5BqKt`~a?%bj~E)KY3-=sx{?S;E+VFWYOm=nA2m|WH1$#joKzjKQmi@kIQ z8r?baq*=ekw(j!C@6W&%MleH-8FJ23@g+N5lI}I>cc77Du@`i(e)k*Q0rP~3ljGs1 z3={6Mg%Qk9*)!Acy_4>lnH`J0%D-a*Em@Rm$=JdO<}}6z#T|jtojjxTD>3}76uw%l z{2U66mnw_d!U*VxqmmYR&2CfT`;T5J%3?;a7e95>6y5(!eB@vMDavBDFar8vIY+S$ z`NfHdmrq@?7@uJkM)vm-dkFr9f5=;jDUVv&QYwV{^(p}0Idh4J9%cj zVlU=2zQ}fVMRM@4UkfL1#&$+PKP=}c)`fSjIw`4r=;(-c1d_JKUgholhhhDbRZHuM zvY0K5fPPrcQB)7C8Tt3*&IPxNvX~L<#W4o;?H62{JT<+kD2v&`2q=!_97Qein$xdN zzMnZg@;L(|*o$K&Rz@3*NS4grGxF*IwlE^yhrXyRhAKXqe%125R2460_nJy&zU*wp zjLEnwyIHY?5z0{A{|c)37^?U{Rq=8TuMK4{W{fdV#m7*^2dat}gy$$Dl+(KZ6;$yt zRPlkT;xhz$F=LE@Dn5ZKUUsu$3nP^66-Dks6`w#AAE+u`&fzWW#f&iqs`vz|_)t~x zg76$=gtA@tzk(`0fhs;wReXkEFJ=s?^fvWNpo$Mw6)y_G?pxDke3%9C@_oD`}FhVm9ML-pwKou{$i}A78OLN~KQ^hAx z#ar3ItT_4+3nMh+Py|%*2~_dc^NNqfUYh#`nJPYkD&DFp-jCwM!U)Yc6aiIy0#&?K zReXkEFU@^}VjF}iK7lIU`ZmZGMrg*N2&m!{sN${fqZq+nn)?QsDn5oP-ug_2EsW5N zLlIEL$56$~?t6@2FU@^}OcftP6(9PT$QDLu#-RwP;(Zn#`dzsg!CsnE2bn6~XEL%= zAzK)snT#SdZ_gogCPcjW+}Z3$?y4A}a~ygfP{qek#pmvvz4#f5Dn5oP-l{6z&vM9f zXN1m|==*>wK87mZ`rd$##a_$>QN<@v#phVU2%RrcUO^R~Koy^3B72p$52)f3sN!Ys z9kwt+XGOGqKoy@r6`yNS?8R-<7^vbCsN!?2mJvF~q3s;1_ynr>Tx4J`jxor0mz|M7 z6)$_xv4s&j$D#2Gs`vz|c!|`EU@wl9qKZ$TinpqY&%Wu)2%Qy?h$^c11gdzas`%_H z5jwLiUW^u1d;(RxRaJbpmmVW@20A@Qac0}9Dn3K7SNT;z6`w#A?^G3^eVbZm&*iu} ztFF%qs`vz|c&Dm(zoH-(M(CWiBA|*-po(|CcjjZUm#$OjJBKPhfhyjqD&DV*h=mb4 zXRQdR;uEOiovPw91bgXvi*gsL_ynqW>oXa)Fhb|76#-Rz0#&?KRlHvl5(|6jx{%W2oY#oil>Hbp1uNyaAUbuK(qRlNV=saP1HbK#26 z9h7qjT_qJSK6kbW@iA2KIhHU&*FTk4P{k)u#pjsFUfc>q6`w#AFFX9Pg%P@9s_g@+_ynqW zw|R?Vukv;dReS32wndSi}@~8@d;G% z5~=xE?4>J;8h4?JPoRo-s*2B|C?j;mG%St{po;fj)RAvHX{C!;w7x`sYaNJQm9I#F zD&DCoKKqgpBlvuxicg@5cdCld5bULOAo_Hnicg@5m#51XM(}eJReS zgqbQnfht~D!WKsG`xjMw3{|{SRlKiNkz=u!)`5h@EF7x%7^-;Zvv9UBf_W^e_!z2q zX;F+|FRcR!GgW*HRlLMqwlIR*qp0FzsNy9uFoM0b4n(65RPixX@e+O5!U&ElqKfww zDH7or!CqQlqES@qOC*Z2g%KPdv-&His`$czGxrp}YW!UeRPjz#@!5B~ z7*Wo4sNxf-;)T0>EcVixLgg-0@d;G%t~hHTm5X9w1T$1r@iA2K!d*TVdudIfau=%j z7^-;TE?XGEoEBAl3{|{SRlKitlw+}%Rv{{Pp^A^8iWly(g%Qk9QN_nl#S3>C!CqQZ zsN97rK87k@dK|Vef*C5R_!z2q;VvWCOKS?l;s_F|_!z2q;VxSk!3-5uy#H>7aF-G6 zrB#T^U9F}P?y`ju%xO`@`|py;7xJ{~R`{xwvhrIiT9vy{#rxV?r>b~g3oI5!FhfNZ zA43%{+~s4jmsYeYccF@pp^BHd%N9m3Lq!!ILlrOFWdwU^MXPcbs`wbHc;PNv7{Qzt zReTIpyl|Hh?4=d0%3Y}9W2oYVyKG?uGgMUZF;wx+&wen1y|kiLxeHZ%3{|{vmo1E7 zhKedahALjT%Lw+;idN+=RPixX@xooUFoGGH)z(^>{V1vgvRebKw*^8f{sNy52;&V@z5vp9!HwaaH z3{`yY4YC(=K~(WERPi~MFhW%j%0#H*W2oYDOk^+Sw5Z}^sNyBxWeX!zxu7iys`wbH z_*{!(FK(NnijSd+&$U`csB%Fg161)bRPoZQ@v+#8V~nWcW2oXK-(?FURJouL4yyPV zs(7cW_$BoD#m7*^J5|MJ zJH9hQb!B=E)vGyG#b*fiD!(fIf~0)QRKFT2$5O4O{8mk*J}ao=y*ksWD&Ffv#li@_ zKT*X;P{qsp;A63uY9jTWLlqxG6)*3cEsRhlnj)ZzkD!VdUNM5bR1>M(g(^ORDqgtD z7DlKNO%YJVM^ME}Z@>ulQca|`L8#&*sN$Wf;=TS@ER0Yknj)ZzkD!W|cFxCQFV#e9 zEP*OMf+}9JaJDc)m1v59Dn5cLUg8xa*h@8$8WW+4kD!W|n8+4Js1i*PP{n(7ro>%F zu$O8rwKsq&-YeWBwzGv1s&G?;>N#@=peq_Qt0!K3?o1V*yQ<9)em?-c52)e`P{rr& z9LLSP_!){Sz5=TF+|%6*;rBJr_W@OW0jhZE4ft62op~`AL=_)E6`y0tW(dDOgYpWh z_ySb%(i`xx@H_KjPKzo&fGR%6_RSD}p9yUrP{kLZiqEwu95?ggwkfLk0IK+0tKAIY z_sh_B4pn>ss`y-Fz;QD#jxnN&51@*dT$C-FAu7^1W(-vE1*qbsH(&&QXI>mDMHL@F z6)(L3TQ);f?7B@ijnw)bUil)l?sAgGUH?s9`Hg5tU!B(7NF?sE1#ve+@cBd)Z=s5p zxXTFkLbUT=6V#^*ReT6lyky~QVFW)nQN@Q)#mgIH1bZRc`L7}>OQ4Dmp^6ulu!Rx) z{zVlZLKQEwABGA4L`K_ui2#1KC7y_vHPBugEfjgkO z!U$%lsNyYD@xom`7JDI|^WV-??m`uBp^BHtz!pX@Lq!#Dp^6voGJ?I3m-=sjDtDoZ zw@}49RmEo(MleIM64&Hl3st;CQ9c%XA;0$DGF9$E6>p)6mq^VPMleG~6>p)67w$5G zy)aJj-(*$pLKPoE6))Un3nQ4JqKXfpiWlxOg1s=_@!ytJ?m`tGLKQFEWeX#ip`wcS zU!xW7GJ?G@ZVS#hWrtGE;CIpy?y`ju%xO`@`)}mt5Ey?3^JZ6<smk|15X!FWFwKV!=FIFfeK>zcF7H zKozfJHQmorX71R+2tJ>v;w@D1>8x{hEcU{D8GWM)s(1@kyu@9$FoK_(sNyYD@$v>4 z!Csgz%f63=-r&I}EL8ClciF-Se*dD1w@}4P++_rNVZO}oxTrk$p`}_ru--ccF@R zP{lh{#b-=p1XfRi^|hO5`_R3LWmSgR&R)8Qu_B;~cWuu<#En>78De!Zc&UC(v0z0p zSbF1j@*69E0aWqYqWsR>P{qp{BwHB4_a~}&2UWbZC`PasR{s3H=Nhk|ig!@OON(L) zBe32=Uwwlr-a!>FEs7EBg_S?Qf4iWafd42LKQD9iY<)5dJBDp52|LDUF_)h@YLj)mI6uvypn@*DMuVd-1HP{li_;;pLUGYcd5 z{zMh;po+Juiq8=2g(}Uk^vzTT6#tzf(iHj=Ue;-F;J6jmR-%f=J?S?TSeVaTx7OKj_ zWzCO}-hi)G>caik(xf+F3nNfT?!ObK{UB8F7OHru3ugp-@iP=vyoD-0_jDP7>TmzO zJAH#t#apQ2b8nEnm zdU5~#LCvqAig!@O=UNndaoZGCyn`w}*J>GoN^<`lMXmUSD&9dAFLmL3EcPmoS5U<} zsN&OalV{O~5vcwSQ+*4nMb10VK^1RR6`vv4i({pz;vH1+QWwq^M(9`6G*Uwq?_Q}j z+D=+q8S2+B#R7Frcx0C$@*66c5UO~sr`E4jiXMk8jNtQ$D&9dAFM1qCuoqM?;n~Nu z)~5?qyn`xUo-SJ$!Ou-p@eZnZd4r5#FQ{O`YA?1>mOvHnpo$mu09zQr?_X5$4yt&G zyNqBjs9?hLUv8>whbrDd6)$XO3nQ4vqKbD=#Y>A~1baaRs(1%gd{LD`2=;p)6551O*5$wfW5LLW`Dn3wE ze8xCNKyfVRDArR$74M*m4}Co~AB(-X6^JU{K@}gUDn4U7BcMf=b7ZP`2UUEis`w1S zUghl^s(80*X+2REvxO1RBFi~4RlI{LUX;a*U@wj_qKbD=#f!3-EsTH`SM(}sIjro5q2`NSZ literal 0 HcmV?d00001 diff --git a/GEMstack/knowledge/vehicle/model/meshes/left_blue_outer_link.STL b/GEMstack/knowledge/vehicle/model/meshes/left_blue_outer_link.STL new file mode 100755 index 0000000000000000000000000000000000000000..717f1c931418a2900f0077d3b2a557ef009d5cd9 GIT binary patch literal 4884 zcmb`KJ#HI8424yv_5lI}YJCE&1flUR zn;%JAWD1!c^5Y|CW@n|{?*ERbOgEokzJB^Mz5D&)@ayeuv44-SpC4Wq&Objqo{7{% zc#jtU}j$MS^+_ryGQh{5uPNhTet1RY#7AJ|xFnZHipNp%{8*xLw1`RTwj z4_%Det1=@!nir=8QB~(1(L{Ns>V~Tbc$A=B-PBi!h&rRHp+C21e&(Y&;6&o>Z=vYidR zRzp3S*Y?H<)j)Og1w?rlc`n{+LyeVy6&)sFQ`w(Kp741%99~2N&qV4;wM$Q622bY| zBG)QOR-y#*vMSd=G={&Y(jyv9BZ4_Zx3hSPFn3qg2eaue4 zR1MlPAAQ)l+Ka{{Hg=F26UfpBiO6-0a1t>X>wZ`zN+2)S$~8PZ3H;X*yVkSHt0d4qqd;g5nF5e(k&vR3wCP1qOZJ95*ZQ}ileH`1nBna1FReU}Q zfn4EnT8Xez!+#IPxq8gsXLwuMZMT$6<+mC&3PBH|P@xjA;pdny8ilvoHUd0yDIxDf z*I27+qe27U`aF_V)xiDTF#&c!c>N^S8_w$0yl$gg%rjG|2A>$}A*}@0szhVWG|Kj-(-;%r z;ZXuM=ka&#qmAO(y-hHe(2EcY{2cQ|qok)h1bFLXQ35vS@ptW`jfy?5ep&PcbCI@v YP69Uk9P55W)Y58<3Gf5L*QgNx0JAh5N&o-= literal 0 HcmV?d00001 diff --git a/GEMstack/knowledge/vehicle/model/meshes/left_fixed_hinge_link.STL b/GEMstack/knowledge/vehicle/model/meshes/left_fixed_hinge_link.STL new file mode 100755 index 0000000000000000000000000000000000000000..2c8e0610a6aa3a952abd61dbd34136b0b4b176df GIT binary patch literal 23484 zcmb_kX|z?vl`az;P#n+@mJAvhjToPZiOMVP={Sc$jS3<{D{4>%K@p;WGDH&%Dn>C1 zrXzx2B!Vt5hL(4@N79I(f(8^sP%*kh(<(+g(X`!d?{C*|zqo?Gq=Wk*=CPo?7_nn!4yVZbKanQ>W!=IOZN|HG-mvdTNJAf zx~K-hTu)v#G=F+cVS65acW-05PiaxSvwsaDpFeJBew=WP_|aV}CyW}DA9mepd;hT) zHW@R$?H}0#;h8Fo>_ug!Kb?j*a+O1&A6PJ|FZ*xtxj0CZ5 zLx+6yQycAu?(JpGj~cnXeDQ!QY7optHWb9~e)W2}+p{AS!4yXPePyS7#gYwn{f0Jz z*#5ou${%#Ev94t<_E2LE**UXM_mM8n#lu53uvg7%-MII-9d_$cL+m@B9C|`K@!Pfy z!$d~8>7x_HS5zxTFjt5bXRF6X&RlimC?|utL`GAPks?Msw`0}5KdFg9XjOxdcoePf zdbodi`ztOp@L1s*Tj2 z?=j|k)8>@!8}9sS(83mW^&Xq;yf2Tn!qpgjOti8-CyIvrCq@b*I(>a$<8kL~w~x*oC^8OP zx1-O&mGy`S=3?66vhAcCB)KI(pnZi!EX!c6+Y3p-hZp^rE?2!#V zBxaw8V6N|s?Q4Jk+cox!lb1^_88fLx_OX{CxzC2&*Xy!D_J~QV?cNVvh`bwQ$UMxU zdt^%wig`Cu7$G^>hOBMO(G8!KZadaxIHq*%a+00!);jyxKA%*{c(V0-rHgyU7>qI) zvAdy@-Mnmr-8mFdyL-&*rHePkIFAVCO1-4RLn}%Td^R@tZd~(v2+4LLqd0v@>4}45 zzKV!2F1Xl3jak_F`abh-sogVNyJ>6h-^)H>u$kDbl1k+aUXnAS)N){B zuYTL@-zE(d#EjqcFKw(uZA36v&=7kRV@A9*q;zIw2N33wGeT;6V`a~<@`p1@hdogf zQ8{z9UbCt3qnEbWuGgI`G7erhx76ww7qv{0nqkAPCe>=+=}SvgaiUiB5UxhOe&zPk z_)0a1h%hd=$ah66shlOMoWV=5r&2T!QWI^Z);`env(k5Z#p)ap%#}ve7em@+Z~yqL z0((R+Jx2}?*NE0 zI`>~i#=-s1&$=9Vpdu2Amj}dY+y2dVzGp!GZ1xxskDr?@8`C^~z_fU@N9D!tE}Mf!`U^qtn!E_x8Uj zg1P)zstLI&MZEXiv~2&aT@=BTdI;!Y%(vH1%lhBay$`M#5w7w5(wn#2txpebyy*v+ z$8EpfGqb~nWT0^E<9g*|#h;3PI(xtD()$M~f+@`)M23&r8U&$3)Os16dvwfN9nx13 zK5CWH3_@hgfA8q5+d5l=AT(kev1ui0b7M~V+4r(5r}t6>Q<_1D3?H>M2ttRbwGy== z)eAS;8_FH+fA&Y5KeA$cHu2d7H3;VN zQP3!HE;7FM>cs31>t-o}Da{~6hL74B1fi{u%|?k@k#Y2a6Uz(lyuN^~kUJzJXq`Z| z5mXMO-(TzZvP16Er9A8L8x+BmdI-d&-Y==S`+@iiXvf9(OBSu4R`gxpO`}%y%_Yk~ zUmpw5)p6su%O#Q-3d#&JGe;3QdX2wD4)#BqSB&{n_i4q^4G)K05)sTLnIV_V(Bv}1 zyhm;*=I-iJ##l^Y1Z)ONAU_)O@N<)k9Wz`OWdw7DYnR(4Qx}w}bu3T<7skaJg*P8|!Bz=d(8ilXLf-8JUwofj65Ub&b0Rp0`Gxg>(~$`0V%p=TAxPHU?O zrZ7S>Q7#z{AMr%VS4G%mFe2gdh`5s}XeXm%DTT(x_!t3MPj^d2*e!)|fnYB2**w{i z6|^IZ6h^>Kn3sG+#(xfJTZCO7kHuW!+Eu#0ZQiH&^{~NeE2e~NjEnV#<>ezXj{Eq- za<=r+8U%B3#*lr<(skv5H;+~XQ|cka*F;8(t_#YqY#LvK2xxF|UNPpD2lgx$40Y9+ z@1F5JGCwC|3z6~G?EQ*vmFlb(1f>~7uGJaV%@F527G3Aw>RyIa=Ypy;R!}L;AVh{# z=YpzpM9{eEQ}A2oiBg>ls?O@spfrOJ8Q$A<9^Mn(Sk8B~>iZ}_4HjETbuOqnBi0KrMI@Occ?S!76cE~q+31atZ9is~#fq&gQ=osp@P(hNdmNOdk`Pp$LdvFJMI zYG=$ZAG)FV@Y1e|UNv=t z^$-#_qE)?G8*(mwgNtgSAmk)mgp)8+g6=wQrNRk9PAswF_^g&=UBWd+@tH`!*ZU0h zs#=1e3MVq;K0~aWJXXTxwUW#y2)WNtuR3d$_7yo~QTJWQiCS@}IwxGTGk~r7pI^{@ zhOqxg5Q*Kwoo$s7_PDTBxJCqo3g>*Acj3$xyb+$0BKE9bIW-=@%?Nm^F>?Q^EcdTe zD;_IcgDb42)9TpzJAkMO5W&x20b`okWh7id20TX3A0;|}=&lvgW#)}x9%2#PXY_t0 z=Z_MdKO&_b0;u}WYyEmC+HuA6hae>HW+Cs278YY8>q}0IcM2r0;O>V%M@inzDDOrJ zBSfb4$yI*I87HGNPDC(QxQ=wc6gY^j6IdVze z#c3O796`t#C!;e?r0}@nvljk~k1=w_$>@v|5zG~?W8STIcTo4wVO;TY3y;S~&o~*K zaa6j`&XG&9kM(C9LC6^=qccvVB;!`@cnX5=q$XoAm%ol#wBFrXWH>#wApc??8Z&Bg zM>ud{EannFv;K@DS~YXmIYEexEV6>j406VaceZ&f<_gym0U|@PPex}P9SfAeg>hwF zEOHe-dd4Zy87Cr`OFS@UB|YPm=!_F7^$^I9dd4Zy87CsbxZpy5kr>getxrZv@?%&Mk&7#aj<5nT0e$>-SGo9BYA`mlLKk)n`)Q>1VXacTaX_t|te$=yW zGA`LoWHhsah?B5tQ3fKQl1=6LcHzCmV$JJ#jDDXYyuQsLkXiE-5oQaDx3r>Z=2Zx$ zFv5@2yjCimxmep8t#a5u=!@U@2m;X*zYnPCMKvWLM8hW3!!S|>QD^4L#d8YW_&vQ~ ziocHI26@dRKnYx4t2*UwbHY zR~6h}fa@?WcN9nm#512N;`qad7ffLUx(I+qH>Griwe6k3V)+XV1)k)Cg5J8Yn&<;a z5seGGDq_;HrxZ-7Mugr5=~ernwIX&5IyXUZKLcwkPe(2rrHFoSZz!YR2U?-4koyZ* zTVpmaaD6xvJDOx3)rd+zL(f6|RmMM^&@Mr6KLgK6PArGH{*`I>FJ6V`r_c)Bk^Cf< zwKZm~ouV=hx&PE;9@U7@&m{MK`ngV#H(Jh35Zv{|b28@n?$@h~c6UrEp{EF1p+}Uv zkXTz|Hr(a9wRWs&RbomtB6L7WH`OjT^KGZ^w2Z)Y;Nm&S9j|uIuTFceAtNhV?kSQ! zLepEpjVFY(Q8T0l4_gs6&KCKc2bFoF_De@@SN%f8VFdCSw3425(dw=# zm*{iU8NW^u%q8g932IE2k#8wt%QdPMQ7YpCQJHy%btjiG-h}g}U>*^{TvR1Qt1X}3 zr-++=JOTTXP(QRMHH<5kRvE4utUKT-MO?FNY=U4e?j4nTubJzMx@kcJyd-w^R(JeD zo{Pch9U2PEWA-Zbt2|H`!ClP8blu%v5vT9nPh|uIbFqfTocc%$Mf~!UA&8GS!)iq6 zXqEduvv%st#~w5yK>!`N(wV<_`)Mj;{vS1$#F@hiLBq6j`GC^~DdLiEw#t~o2#I+` zBfA=N&}Ek^V*7wyB}On8t}D4@z_M|Q`1mEwC6U4i?!cEP`A4|!hdCckDKUi+l7m$% z*QY;f){QFTly3Vc2q;HG_nZleX!*e$)WJw$1iu$xOs7$!6mibl4P~YF5%&&&?esDI!o9 z!QH>|#>hK|D&o<$HztUbD`suk?~dK*I(HUG7Y}4X2Hst&M&N9P?~OTj_)e_`H%y$G zAb<{B>2+sMS;ineCT+M66Ud?fiG5@hv zjNse_G=6HeVlK9bg-E~Sv&wllJ2cCVP%jS;D z=jIFFFIHZ0&&#s2?D;|)MSL{p>@1;Fo=zusTjX4O@BWI&&ls2>_znx-t1;%|6=x{o zg>K)qvjq^|ncfhc0W6m1o-hk*lrfnjF5mHAqr;C-vR-a$#5dU#iieRqPR=noPN>zHJ zs=S2#s*aavFP8T=-+wiDUJteI@=yCDUcy|7hnii(Pf)~{^NtHEn4_1A5vi@}thpkX z%daLnN5odo3~_6I-?QB_rZ9rNQX?uu9Quf|)JKLViaK+#h?R)y9V1E+KB6iV_Y6`I zSh;YoS0hRhKB6Lmx%{=iXDJb-2p>`UtP4-|{gY#Kg2CIZMAXU{QHt;p6%owEPxz%* z?H+ee#zz!puGSU1g{Qq$G9;o@hL5Nyoe>f%^u~xplp=gYMFew6L_u3TC6^VHh*E@) zs7UcW4Ctn+(n=yq5k8`#3`SsQhE;}@HKG*ZBPt@8E47tGlp?U^$x2n8P9vh?%BFsm zPzWKOAFXbTM3l<#5f#T`E`RM~P$EhZKB6#|QW(MOUw6$F!CZbdHKS@osSF=c`h3&p z+GscS%A`gWqDdY)1Sqe>jwJU~pYm0~olcAptA{57c~Wr-%E-BoZS9nlIpsb+1VI%i zK`@ukqP{WpE6TeCuYsRAe5uM-!MYEh*^tO!g!dkJsAxs?BSA11`gSMPwsmVAm(}pnL@x6-p)hKr7TJR2)Ibu1{r1jY<&A<*!vkjX_07je;kJ zOpO?f9ZBMe$P(D~i42KBMM#ZG5X|NCuJ7@p8Wm=)-XLBQG7l-nP>QcO+GoeIH3n6N)Tl%TBV-+{uTdgHVo(uMqY?yj zrMBWVPgbh3FUb>MfVZm*_*Ft7g!eZegH)pu1al=Gil|i?Qlr8O=7?uTq_(QF=89l0 zzna+fiLE62s0^u51ydNoUMagh-x-ZAY3x1Dx#PZ7$g^^i$Z;*BW*(x1<`B0&HhxKgb~JdhRenUR0^ zb^#5b6~_1Z3O#H33ECPH-Vj1RGS8zLfxq=*_Iv*bmGLkAPEQa(2QHqIF`-Wl@8!UH zkPf{u2h0VZL|YSj;n0=KlxhUz==@BV#qQ+QZvCMN0_e!)ab3V{nK?yNMjmd#fxqRWojcG_{7ev?y(hL`e`q438sWWC5bYmxPa1Z&Gzo%y zSJxw~O(mkxr$}qAnuKv_%|!-zNrGT5@)$wPY~|j}{P!*6Gs;(5*P)46T(4nyTqjvH zgZ~E#?2obKgDS0-7P*3;4425LMnFr4IAHxgx`IEsd~kxmxPgmTGs)Dtg3ul7%m~;F z)|QWGMHwzZFjwLWM&1z8JLLGk05bE&U?1^e^a$pLwupGiIQL#S{<8y9su96^Wny7 ztuQ_`gFiu2)>f;tBJf{H5=s>Uxdo%B?S4n@)Z0Ro}=|c5mKEK1aq-Pv^pySJ?KoSMu`1Tdu8U5cNHPkIY9s&xY%x5 zofRR~xlHrW_e$W$KoL4e{8yeCxLkqnv^vL`lNFj0>tgQ{xDeyvTI~jTu(nob)ynUE z0+%8J7g<3NQk@lny$@5W=j5#*^N{MS2&v8m`IW|nk6^v_ek=&7&WgZ(mpoi!LH-7} z=5(OpXIh;VA=NpNf#_j`_ew!XbykE_=LA8%tLp(7m`f$1@D>_*iE0wYr8O4>c}ap` zu5`_%I&1ck>ReF1$|)zs>&2!D>!sKxp+LTnbYwrC~QSrPvH5fRLl_yQ_U8S#L( zW_|SNY>^3qeQ=GL<8Q4vijay^Foh958|nMPNv%x~DOcP9h>Y+*Kk!a6w1ae1l6eF?N8N(CYE5bJ&(RBICib77=lH^|0M<$U1hp?TI@ z)Pe)o_#J*~5ugMv(pJ%+IRs?}L~L09uOI_sFoNQyN(MNCCd}2mR-D!7TB=NCBwXVs zojJZ?1Z9l>Lo4QDi(oYTI2knCsyz5rw4!mVG91gmb+8p_r8`P|4}W(2L92j(&yq#+ z@O|LM?^;_ig4RaS^%2a)7722qt#X}*%RYMTvRY++DFT0mnTw2w5Dh7pI85DnBwQE? z7D;6wGJ_S7p>gf1OhtBzz+XWtM#yR^8WpH{1apb46ruIjL)<)wODlob%ChX{Wsp{u l=BKd&RIRO;i>|BuitKJ_J-(t=jG&n-y1rJ-#TGH!;D+Mzkc$eqL=M8Z)EAgVl37)Fgc6mJ9lQ13V?uj$ zlZ$JO`Shso3S(AYD8zfSd)o&eTVhwf(y;dA(z&)t*TvQj+@3Z&?gHEBu1wm-%&s{j zdE7P@;?*~6?UG&l+gm>9Rr}QF`S#RjZ?b96vuc0%*?ik&*PE3%tjUP%h^FmI+^eQv zypz7)uS@a3*Q#rmoby&XWb1Rqi^g;fZMG*iGP02|K{isdk*bZ9Y@})(;ff6MC z`qZ82Npt3=&R0_(Z<@{du1AhQE%H@LzET?t4m~k@^0pR2kWWH?$yZ?j#u~YmtB3vmK=dv=tE_3^65M2m9wg5>rU;sI(>Kio_6l5ClYb(;9=RIyB-h%B}nL8 zu&!6nbsw6IZN4~1pq6jnvn$V%RqqeV{&CM5AyDGmeBIZ(EKmRNM!{~M%J;nYzx!tU z-1LPIC_zGJkM`<>H_yxFw{DQIuaH2k7gyJ&og4SJ4}RE-Y;2K@+*|36(?MV1GYsDk)JNn4%H_vvBdc`Bh(Q16O zQ4|#dB}ix#)%$Vb-i@;4l(TXKYWcRaL2);sxGMzpJ*-8zMv*;BtAW~}xSLSi6#^wl zP(-y9cWsEf3B}zUfm#%IEv-bBS0ahK3B_GMcP+(Nu};s2rFBrARNr>bAjRE;;;s-V zp(tu8?plqz;Y!9(+)XI%=4>EA@zGM;wIS{%6nAq3YM~D$?j{s>g+K`s6j3e3T^r(V zLUA{DKTr#E35jqCML6=BF*@=hKOYpkEXBbh$3cpAmgVk=q9~eB6cqv`m530j6N=Q; zd<`Ugo3*^xoef$I5?T#}KnW6*;aJLWsyM?jhH{^Ta-Zl9^0iRQU&-BbilWISce%Be zVie!olnIKcmSSznu@*fdkvgGBUE*<|q!Qt5&}xv-YLFv5&06R;i3|xvhKz0KJx?_n zSc-!w$3g#h=PQb$2}RL}Uh}u&nssr)_hZo~$Jk3IuCQDG^OM?3?oRAJzg=!mY`GsjA1-fq zF>%`qn+x{penOxGiLc)8Y4=*T)XsWlFS4<{%eKO=TlWJk_=^`;ZYr_}v!!-M4w?waZg`*yqn%t>c(d=vsLCs{a-OB}jbK z|K_Td%huVoXSbqWEx37L;j^LF=Lpp5ciQ5rlRsE%4?gusA~rO*qj133;XI%YgsXElDiL>n+nj7nEoFu0E*zR8{FqqF-y1g*@7{HJ;rVwj z6#^wlT>EY_Tf5^GJGS-^veAD2n!@E92IUCU!l%HPp-;E3{$O$aJ7Mn0ebu)d-+cEC z_UVUPla03q_2_8KD6xSOe?RnY7I`1-#?k+}vuc~nayIG^LFBW2_$sYLKRHs_BBOg$^x%8`RUG$+? zlKLp~#^p&mVBm6lV+V;>ymwab-q&ecX=^$91cGKv(0c5l-f5qCOYGz|4XIaMnrtu4 zy3Iu&lpx{TF8bWv^1D*Im+L23iz*?huY?%$%eL>8UY+COF7};fU+QD9x8Y{Vy^pRb zefDmcyP@w$tX|nH-M7Ii`{5Fv?Q8z?e5vim@O%UUwc=Sa^G^?#`r51H4x$8!yYAm3 zo!Du$o%tL;wbRB;DQzx4=V6wh7S2#(Gz-so#nHSyxBT&n?osInl?_2xY z+8QBH;@fJ2D{N|mi0XQXphdK_oef<-yp167TIwrHkwI;ovG&@6AGz1!YthJqmTx;7 z8maxrMXN4B_r`MlitQOgcd+2^AYKc#eB0U3^;~SA#JBmnx@xNps;cpNo+D5T^B`kr z&zaDkQwWq)B6u$<`}2hM=Q+aDx>tw%>b!q{R~k6cMTV90+XibO)(;r;# z=dtB>$n+%_)$G1FV1?zX8t?9k9lmWF+K$jls`N^CKk1pDZ!GGbGrjZA&lG*m7znP5 zCj1O)oysb~^+c-#*BP}}T7eXTt`#I&PZWZ@z;#h2v;rvvN|4anqHQ!}S}{~0a|CK> z1=1!5Uq*yhAPYPW%DhwF3G)caS6mUU!Z!QO7_C4G;k8(z^+bF0$A_hOCD{pc1u|y? z39S^`dnfKqHnaknBTx%{7%GrLpaco6E!ssRb|V{Ffy~_x)WSO(YJD_|Wp^hPbM}u` z@rs9+EX_n$XLPef>xn|3q!RI)>0PN;TC=QX8%X#zYk99b8(J3?0wqXjt-p$&0(n08 zSAgga^0iRQU&-Bbt|!7ym}g1Kgw__*#xEb{dsTG3(wb$duCFQ)&W6@SbAR5iCK1cC1{pO#d>2XNlG*xymygs-qo6=kGp~J z*JUlO!&Pyd4|P!?P=bWolU39ht@RbSpGcsVZ@ZXCQIzY6LZHOAxmQ{vvmArvm!AZF z`QbXHNRZHZW!=cR4hO&d1Ol~u+r=yT<%es1(kqnsHeXlkel|o=t|tnC5+ro?Xs@(p znXs>rKrO9bT8{G}vlK#~XM1_;BZ^wBvmB%R-`&Wy))x^hK|-sBHbhabC*}y$!XAd2 zr4T5oL~sNT_1zrdXKrP>PHX1M6 zTpD|gt1~pZD@prOEwtr=XVOV;_e^(RzSJIg_p*?;JL1?A-YZR=?RNA?&~;_!&07Ch ze@y!ApzX#eD+O#;n}1z4UM|x0^soCBn@T-EE5vBz&8- z$Rm6@q3m5go#4G2BuJ2_A=B3r5IF+1Xienv6P8y|S!?-}g%Bt~BF^;3?|EzK_D@~K z>&Z{E;*^iq+NOPPPnRD3aq;CIZ`kf_#_^6->JRRI)I2e%bj_SlfeaEP{xNxvbV<9_ zcG|2-bU$7!Wu89SIqxDd^2#5ldzn}5PqyAqHlCWXy7a}F zzsnJ*70;4Oj<}|J%pIXd#yfhsQ=hGGP&MbC^|sCFHR+vG59rvG){tdyjUXFsTW#v( zE0DUQ7Xr2D??rzlW9D_ey0-7{oek6?8%1v;Cf47-q_$?=NEru8DiPZ@jG|s?y(C9? znziCPczNrSO5=_XmF;jpkl1{}xMH6Z*V&(5G@5K&SAA)zYsLz=SM^4+&W;(( zy?V0GNre&Z!#DzgS~R9`XK61xV|(>Ay9e(E2@=md->GWk@^@_2$v2UW;*=%TW6Jj< z5U7PS#u%zh6ntfZW;Iu9BwG3tTO1iEu2^5Okmyr@=o1Lk@>g=t$J}k(3P*qAA{x#Qs1?tWEw|4oY?~A+so|biB9`vQ z(Pzn=NrkiLhIkbSe_htX87h@j{>>}nEJIhdl*gf?joNNCz&f1QVu^1vt@eZtzsiUW zuf+sv`L?q`mDEsAM2T;+4V~?318bIEi?4-RzU^$(sf+S#Pb&~b{yW<YN%7A#JBmn z3$=XP*}!@`N_?BIs~LdW!1IY-i?4-Rx>AeRrIO00cVw2Jq!PioT{!8KBRs9SFQ0nS z{W;Ha_ur^YXS=Oi1*YE0v+1hNUZ2*&3?)iS-B|ywHDn}w-_?fXLEQEpsc1v)R6T_B zwrl}vOJ%616AMz>g_UpbZ_Z^d0Hg21<}nAJ#u|=?QA-m3EF0y8dyX zL~RJ6J(PBC95R2{C#Xejc?R>o@)3t6+Lpen?fPwqqyiyy#a;G?nFR=f)FSCQc{wRHZ{Q36LMVWo%HQckd&_ zb06=OprkHQ&UdFR>o3Ik;y)wrVpfcPGv*Vx7lTaOfCP4BLejk-iR3*XYYqY&F)XcrNf zQ={L=y8~`>^~!8`!n+?HIq#QoSA-s+(>uG(65_q1uZnzy1n$D<{g^ja2r>Q5!4ZL4 z=rj8AWWXB4rQU7Ss$cSLNtVMeW^7;~~Ox)CzPtqIH z?+N#0c?l9&f1sK8!6{Os{^IeNKrN!H%Hx=EV64XEi@ch;xsT zr#29LU9T1Q>Wp7sCd7>`iX7X8;HZxkPwcHRTbB11V!}L$aA6#EiE>PQe)m2?{KZAl zK=5_F7LLi7M_;QEV(9iJwX_KjXB?l?#glG0K4bp&h&$!)HOp1dV$Z}G0i7)jmZu_P;9)kU$2Njt@xDQSy%2U5pMgu8#6qC$!9tF zx_put&#D@;@Hn>`%%yve5+pbRGF^I^PqCiaV}j+s4EnMrB2Ww8J~ifop}nM62hO}9 z>Xl!k_`GOr@1j9&9Xu@?o}r{JQ9k$j#DeF=#@U-MjR>Z_7W&PYPmXz4h^m}E8xeuw3 znV=rZYUj>{ldlTwd-fF)sKssX1!L|lJR!t`w_m}&3KAsnyg1GF9`6eA>9m0vN|2zD zORwDAy=}b9UfW%KZbYCKxBVGtdd|N%AmMR*+`bokH%O51S*AOCe#u8J7k%u)t{F;@ zpr_0F=h2v@13HL}`(_>=5vYZy%BfoW^aVn+{+}Hj8RS|Vck#Umr0I8@b*Bk2=}L)k z!FpZ7pBFY}{km>K+}ge+N4P+6+iS(WqDU=-M(VJmqevaz+onh@S90s%d2`&`38UVS z)gVZa!1pvL3xE4MvC-wUD|r0~1Zts2j2S)SN+G80FHuwo_ElY?9C!cc9QT{rMR!T0 z4g_Dx+ z6=mAJS5#lGPzya0_X;BpOZd8OUD}ymAwgG?@wq7KtmJ)#TIdm{@9#N22lxbgd*45= zkigg#+rVp~R$Y&3zFc_e`oS`ClvE`LrEpV*?4c&rL{dL=4ad;M8daO3uh?3&2jdo(vIo*xr;s_qbOT?tzRJZN~&kv@HbL zOjSzl*KkRU;4V8c5b^%JP&-=WCQ5}ZFi`mh%IFlWR1d4+_JD|s7uE!4v2zpjn) z+b22>IeWZwzCr@;Q(YTnzoQo2fBv1j!aYX`65o5z!#RDNyF`am>~XJ9f`ra?oA)jf zsHK0epAZT8iqGkbckxQ~_X-I-BVIp&T1xBNHDzX0;-ea`GCn49+s_`iMj=s0i=P$A zsp=?z(+pacmY8S1qm)=|sHl{|s{)#pQK9ADfklpx`sk9uv$ z$WhDB_B?_8^-+|y&?9lLP=bVy;CUNJpcX!9u?_66e`@)<=#iK}2@-lG{Z?3+8I>S` zTIy->VOgJN2}+PqPgfxDIUqt-%boWw68b#KjEQ@N-bF3yt-Pt1zaJ>*AH_ zw^4_X%ph+AuSM;k<=3t}ffB!x?Yys$pthWP$=kqQp%&Se6Df|EFmW&03qDuqlbqUX zeA@BY)eHMv@S`G~df_v7{sc^T4}s3m4{jzzaY&B@-v-3@`S42gp4W)|g*YHNJ+gs> z_q02oc+l64gjoG#?}$Jx>>>Sjx7iVGpX(i+@xu2T;$A& z8aZAIwa_C}Z|~AV#xd-o6C+)-9tbA%F6C5j56 zQIx+sChrO2`-2o?!j&Y73ZYRnNRXiTC^di(MTO8P8VJ+ z{9P@13p?%=MNuI%iUu10Jh9HOWY8bt$vS`@E%M{h$E6+)vZe_vAGwx%c{yKRl4V1uHl z5E?~;1c~?!X^NskXcP?uYQ?>xC@O?TQU02yyvvU7xZ{{4iVC4oG}u4_-@=zDDuhPS zK%kb6Nxp<(3`J2PG>Wo+M1pU~$GxH`DuhPSU;_!i7YR{R2#unFKrMWeU7~2FQ8d&1 zs`F1a_vbGSN&X3McIe4|$VD^FKjb^Rnpw&hd+|z9E*jZDLbFWy_OCIJi$(-$VGpBR zl;4%%zDs{KvrPHxgmJGR7maKnp*f>`4_%_D_==)vM4%RWB+5l2Um>BHntqcUa?yxD zEzRM&JhrtDohgD`G}AmvzTd2wrF>^OCLkBhP=bVJnbv*X7;@2wK&^P>kc(#6cg-y2 zJM?Hf%0(j^NND~jU$m#QoaJ0JB2WuG66K;9YH6+|-#U*8$VDUXB0*1W%2Bl6CjQPg zngO>T)g`*+4>bM*WsIj0aGIGjABLcN3`f%R0C`3^qC>Q0YmUAEZwz6iH@|EV8fLxTLPq-Em znq|uOo{ga>DmEw=jR@3=M-I6tN73*NbVID6{jR6;TGjXe9LKkhV;|qM*LD4#^BM2^_ui}TU5Uj1?SCp( zDBItV(y}f5-&s{wKAb!C+hIxD9&pP;xk7DLB5~p&WqpC@cXZOKvpU^0BDbmKF5F%> zcH;j)=)ROdUe@*`c?o}1mcD~79<4vBW{*taksNaW=h+vljOO->otynHk4lN%hg?HC zx9GAmdIv|PU3x|QQPsPDI`=ia%_GTUXFSa9I1#$Mj5?>Yo%R!Mf_3S zFts9|h7Y&SOf5fZF}H`DeSg`0|362iMD5)UdEn8^M9tx+^4F#2%Y#$%tMN2OhQMG}cAdsN9-=ZmukmCXq8Y=BuIWuvnm zZ6dL5<{czjF6dvX727T&?3`>noYR@P*(5gJ-p3Kz<*&lMO}`>h`c=15ttesVWEtVi zpD(RYZ0GU*trt2%yYwm~60K_;L}JR)_N7`;!mgENgxR21su_v4H>Vt-UHVLNaEC&>NrBX{Byiz-DM<}e!DTR6(#Jcw2biV4jIvd#LT5{ zJ3_nkIZh8KZ)L{Bi+@aOMF|^MEF+9QpG~}(#Feen86~t!N1{Zc z^Txg;zPf%!Mk`9#cx4%3<~;oCt4X}`=gW@JElU4D*QnO()PAo!2@- zySxp2u=zR?^FO_@SSw1{+-@1c05S{#^+?$-` zg?o-WNW$)*653_kmJx^zRjQWSdDv5;6(#VDF(W*?coIq2lcF+O?tt z-W6tqcMxwB345cI&@S7yjQFi3VQ;Ngl)&4}j4+m9WFTQ9gA&?h+m;cJJ|t}P(TWln zyOugR39>ro9XzMN-%NWEX|n(;qjWkTnSuJhKh>$wI$@YB8RNj^sx zKA-ChphVsM59J-~vT=RNXDFdvI?j6nMsmAL=M^as+z#`Ho`+VH*md$n zB!*7^xZF`GpO+}Fz&L;DoRXy|2_VE?4lcT{>+uoF3b`nwqMK8ClMJr zI}#j~dn$c~x`-0UBaNdfcdeArE;SCHp%o>X&i;%Umpt97T!s?bWiDaowEaETHx*+^ z%DQaC+4)$WxiqqxBhDQ9{PVav4f!m!6Z)kQspcDm+W^HvV_H4CAe< ztWrkEQ~5s-+O=~p(TWoCu9VAALc8>;`!m;y67tTM%TPkQ^xpUk+>e}HAA1tf#ch}c zf5&D&4=x&*Fft&6U4^G4CXmN%j9uFwRZM7?`kX&1ttf%3K$pM>S1v;d?JEEDSWY|- z@~CVc#M2j!y>-r>c5VmL*E83O5_paS-FZd1qf$b<^h*0PuYdlp+}DtqUzF&lJN-22 z3AsKg*{_);_q0Q^j4MjW5vF{G?n}FN?ulAaLatl63?;Nn&A=ZOu20IIQTvRH>&9)n zZt7j0(25eWUG`hj!c(#n!ug!fkU1kKb5w5U?xPhYWPU97Tq&VldPV$EX+;UK%yPe7 zQbN1rT9x<={S+@oX0sZfxA6HqFx$U_O2|Dgcjme;?UE;^9D(Cyx;+^<4{pQ4vp7F) zhZPn*Dy=Ai>qY_=UM@ok?ZSN`vAyqVMG4%067ZmM8A@oEUiF>d4<+z~GGm9{&Wf47 zcImzG8M5D$oJVTszN-}_+cx6f+YCEIw~AD=fd`R+G^ zix)*pbE_*%E$Y~OdFss@W@g*g*pJ&^zc-6-(Te5EQ{msReBApd5^XCka)g~>Sy#87 zUyyF|#r>c^?b|qI83)W+n5*?koup;l*J47}cWt8+iIKfKl4$nU)47JX9#7(eTSsS= z*1SZb+C%+GRGT;>_w&Q&lIXR3a8_wgtWDib;*Mtb=AK>Gm&83yuE;9wi6tjKKw{$? zLvp8ldpn7%y0_0N?TI#x=8*Wg^M$#Ilg5$w=GP`!r9IJh!3!kj?|)40%nnn+d9Hden3Vk%DeZ~g$1NdI`OC#g zIrbu@JyE@Bp2P?DRZq$FakMASA3cx65-JY6G^2#QKfo&5+jP9OUZke zRN51JkK3O_G$EUkcRQ)HCr((uhGWT{-Cs$`=#y016OCsLBk|Gr*HSV@C6)F>t3DHp zZ1j1x>N1RAiG+vMeSO}v?nl%lE5fx_nZVqQM(^8 z?Fo#cBruBFbHy%NnjMUXO~?VMeVtYX-{AjC4o`Y-Vb(R6t!nJraggC zlmtdmdk5KtQPkd#nDzulQ4$zM?LB8#uT~Z99gJyDU=$^RQ8b0Igk2a#iHN_zsMC<%3HD?It0cTL!6BtEFU=%ekAz@ykv?nl%lE5fx?nA=d zM`=%B6eWRCG$-%2xlc@c0;4F$5{#l|WM$)r`BmA-P|o2niju%6nv*dqtF+I+D9SMr zqbM!DFbWybpW1n80)0L@2;;ib)^xMt*6<_hkq`X#?_;=kr>Ehd8!;x35e^c5rz8&(ABeY9b zrV@#BZhV*-S0%^iwW37!w>?sJgwd>*k?~{ktIU|OVwxkg3u_!HJHN2DRHMZPW)$Bt zCa)DGs{YZE8SfwRA~M>{*ezq{@$;7Pj?gZwgfPQazY>YL>uY7~TD|qwh`d&m*gUW+ zGrAq|B#42X4rNBaBkpp9c3~wXoCjBmR<<~X8E4KInAeID*YzLHjCHFYK*r`5+cV>t zenTChUHBv%GO(6~J6N{^GtMi%Jg*fcmVGgS8K3mL8^m7MUe1i0|LEZe?b7w+L}KwV z-I>vB>8W|GC{c9!EM|$*gC9WDUmlf_c3F1u9_pX3!jjA zKf)*aiXFx>W7AKcMp{u~YtJR&TJ`uA@BerAOl8K}2JbsUyYM-h8DV9j|C{5PQSU!f zBdsX0;>S0baZSUq$oO^sgUopC>(P$TE_{w=hOM0>647asnX!4$VUbpps93Us8I2Z{ z;TDY02Jv`fqY#MX4gjA>`wo6(9A z;wT_`y!$LO>RZ0T)ecMG5#rxK=&Bg_poZnE@Adgm%F`m=XT18eEhaa8a|2xS|9+h#7EEWWYt4 z0T*?IcEO^!C;QiQbWvu&Ma`DtiW2ZSX23;ZeQ;4`z(pOQU2r?@2`&l(E*h@Y@hiZ-5!xkpHb)m_23$1KiW2gSfq;uL11{Z-5!xj)5eT>_ zGvK0mttcULA_%xBGvK0*&@P!#LBK^hpTkA-T2Vsgb`Wq;Is;tP5!xkY00J(`47g}s zD@ur?fPjlK11{7j=YoiK&5ri_#O}qIs<-ALoqF}dzV5Ai# z7B+pD8GV{wiHv{#b{jLQ)wkdO7c-+r)qNbHT{2>Tn6>OAW~}M7 zUq&lR$k+v9>*!O%d6XXM2`@}%XQ&sY31z!BOdW&q;HgQqZK$w^mdw4#JK z3WyeG+{273YYugUc8TGDSa5SIW}JW5^%<=wA+81D%EgB=tl?=!PN44r%oJ+brew>!djZCmk7B*r~gEoT`=A9EvDISXcqeQnz> z^0EcX#LwZPxq^#2Lc4IZvXTlHjS4PmM-^9;z;$B=Tof5_(Wu~}j?gY#b?zywq{2m+ z0T;Ea8&{OT{bvST6d7<)X23-qptV$_%)ujXrTj35<`-fQupnF3JqJs3Wusqbv6mR#M@j z%z%s9C>mFkz&OtgxF|B!VI>tV$_%)u&CYQ}3HSpu z;G(b$xF|E=qK?om*hjb`TuFtCG6ODZmJwH!fCn)HE{Y7eC^O)qj?gYx6!#QXQsJV^ zfQyw{%@~%*( ziToS{T$CAb(VSLvzj97lx+u>BE*dGJU2=XP;G)cci<-BWU8}4Ta&JJuMVSE?b%b`w zodp3GWd>X{(uxxDjOFN}%z%qJLc8P%1@U3GOPK)|jkKbKyelB!qRfDcIzqeTO#=ZJ zWd>X{uN5Waod*FIWd>Z-5!xjq1_-z)GvK0mttcU57YMj$IFHgJ9id$^@_~ShG6OD} z*NPG{27`c$G6OE^2LMUC_ND_n%9aF;*22RqVz<#s3Uw= z?4lsxqV!$3s9WV!0(o3dv=vW`44ZC9EqP>M@xnJdk|>yP?&xPX6uoxsE2-U=4sdIv z_-)^qb*YgvZ!VtKq$scZQljyJS0;__8TCcROZOd+wu}R(pY90l!jBf1jC~<6^$|<{6Gp_Cg;`hV{%viPJ z7)NLq-e6{gmDJcS0w zGGou*tLC+$#3B8TWybkOAC8REE~uHYd;V#MI*!mTjHt{AE2;N(sg|*OzU7Tgkyeyg zQ}1ME6mP1HjD6-E%#3kYSI8@&U6>h|5mr*ae}7+Qj5+m#NGnRLs&YOvR`ve_vvciF zk7UM}5o;WwU6|pR5mr)L7d2tVNnbo0X+??uRKJ25;~rRoj1wM9GNVcJ`Hs*o%+$;X zE2#(m>qusdt9NIl6(u(Qc`Y*<)wO@ixo~|OW(?_ihaecWS?&@LDtGr~&htaOSQ&wqD!Rx3)#HhgzXmrl$W^mV7?PKYA;Ifw^uPBLS~ zgwZLj=zis#l8MBB#&%#vqR+>U&@Q5kAY zxw9aacRz+1LqG1F)`}AHjDgr^PAg{I``CC#XqP;psYIgJu}zsVv+|6zR+Nx;1sM$% zwq(Xht6p-1cFCKDj5p>V$c$ZYT$X zv{samu?xg&Ll0oa+N=MOQ9`?990T!S_lnGTer=_UR+Nx27{mip_h82I*Xub#yJQ3h zQS`$Gj_rx_YiG2ggv=!%&Y$u#=Z{W%9p(t_l9>oZn{QuXMt;RX8LcQGb0UaFbKhXb zZ8eW`gm%e{3Szg`4>05Py${c5MG2YPK^#}@L1tV&^+ZQ#mzV*F=YP728Fy4~krbi!uW)YEMaAQ3B5~GvK1gfQvE% zF6s#F!dsBrwvq}LWd>Z-p7yw+1m4G7!9|e)7i9)q)DhZ+x0!niE2(f%X23=5t&J;6 zU|eAaTof5_QD(qJ9id$qmAI#{k_s1P23*uepSYp~#z$trMUep)%@a8F?+6)wsQxTsl1Tu}lZ#0rbi!uW)n$n6A@Hu9{MPYq#QD(qJ9id&YL1u)NRJbTJ;G$-haYYH)hVQ~fnE@9y zd)*OHB0mQK7i9)qG^Z8aubfksF3JqJs3WvXt_TRYC^O)qkyezDdjkS4$_%)uBeYBI zEC{$LGvK0;R+Nxu3D@w>*0s=0|`2#NM2V68E{cYXqU{WAmF0RfQ#m}qJ+%tAmF0RfQvdpyTlAYz(tt>7tL!$ z32_t4|VrNBFMTMM1ztlLZ%btDH(8FJAG4Gc0ME>U!p&;&i`SBnl>+d*P$0MZ4_zdg|e6 zjolh4ehYBTq}1qLZY{p$)W0I#ml99BSubhybLj>+sx~iw!i?p|*UT%SUAWR*feb6D z)0b9CTgKBz{T69OiNX6_&Wu`5?~janPhdusL>**&@L?ZjB){4%uY`8t$!A7bNxgpI^~`wpptX@!lvtEmz>Fh0R7J+2 z*G^)__+K|WLc8z=rwaB8;=MiZV@9I^|Bkex#M@myU`EY;TQRmj_WAS77&7~7M`#yD zB4&h@)OT7x!HmU!Mv+#OSU%<_W?a4U3uIjK^$KQGKKeaJXctCQW`vd0iw`el#+>gT zkF=u1?)ge7d#>(muoM|59Qq$-{IROU5!!{Bff->Xwa%conUR}(PoxzkW?fN(87Jl* zMMiY`AK^Uyn(heg!VJfZu#!6VkG0IWZ9?xzD@t5auO2g^+QX5tZ{4rYXv)U}WP#*E9( z*)`IN60fyr#EkPE+5jWl^Q;=o*r#>E5!wZFVn$d=opaY;%y{kMaXGChQMq3eX8h-X z{g81&&05U3acCb$Xcr8S8DS;0$v?I-qrsP*vRY9>wu=&p;&(&FreiB5cS01&&q2(u zv4t6@|J5?372U6#6NuX;?8Wn#@ZJ_3>X->SD$T2Vso4T#e&s?Ln> z``1V-pM`kQ*-XN_NCFB_cvGkZK%;;VHEJtXUJfR?-dVf7L#uj%;Yeflp zS3tbev;s3Ox#|u_XqUWcAl{z+Av5-Wc0^h$O2|78;*N#C@I7C;ah4;rOGb@YefkegOO2l^-^Zc*|5qH z+9e}6GJY8O05clQc`dCKC1frEvHNjPF{Aa&9~_}wG82Kg=J4B@anF=hX{{(Bb0Uay zT8?AJ%<8*jl+Z4jQ9&%Ja4s{Rnz$jY6(wYD2l2v~uFN=l>_0L}XqU|MAeJqw&y31_ ze@bgb32_t<*W7gz_Lf`HT2aEB(dOC{b4@^W9P{s_%~37p*2*a1ySA-(CK8|gIXr6)_sM^^ z@Gqbg%o6+BwqN9x6fD!uV@cCo!9}?)T1IFWvSlR|E}AR2sGUb#Q3BU3TX0ciz(tt> z7q#<<3GKo)V&5_pc80T)FET$CAbQG2dpLc8!x^XFkD6)wsQxTw7!aYYHdkIaCJA_FeU47jKx zvrb zi!uW)YO_IHQ3CT7GvK1gfQyFn_=_`6OlTKoJN`VZq{2m+0T;DdEv_hmd6yY*QDneH z^92`mgmz)p=AObzDqNHqa8a9`=<=^isn5Ek<^5PZGM55={QL=UI!NoNjKSiQo!tUEiJ<)#X zKB?pT4=!$U>99yE`hBMO&QyN4seNmHBGKo-!70m_H2DcfXcw+@vS6<`+RnvyFk{0h zLn5sxfp2nUM)*Gce^jIuCGfq)%&>1g##_7h z2xk0v$wiLPF3b$6g1v$`ZT~LJcwtf9NGnR<+mxAM-^Gl-T)*iaX7njdIzqcJ!!aYQ zq~3aI4`xiSx;dv6CGZ{3;eNETzmNRuXVaLmX+qsd3GKp6&5W>;T6#-=X1v;XNlq(D z$hZH)eMUX=Ff#_dxZV-k1>;~wSV>)Z@DOHPJz-Q%D@x$|uz4Q#ml6_*zU^i+qeGJ^ zj?gZc6Eng}>Vi{-F=N81`{%Txg#4`o{B?x0?|YIND=XA;gm%FInGse}Yt0$Xj9p=t zT2Vr_@!jEzMm@!hPW3M@+6i%j{JaRiQ9LPRMG1MvKwLjy zCNtX9|HTp7B~K`bv8#GBquD8IQd&_$-W3piPM*q)<-gQVE1_NT-hga528bbam+Yu-bs$oE*UXETzh{fW?a>*QCcfX$k+v9+OlEH*!bRMj?gX{`9M@? zlwwBRQ<7<|C?R7oh_;h@F=Oq9TOFZYGJ=C>bx`AQ9;-X1wW5T~B_LkxemXOnwYkd? z+9fkl3cul9Ta_6HJak!FD@w?mh>Sb>HD$&-%_liRyJSX1#)Shv<6OJo+}>%eC?Rt@ zGEyyeV@AzAA993ti5Vc{+9r=PqwR{D(^^qN90eJ3TD?RsY5B^dj?gYK9AxC{c45XI z-w#b|MG0{&WZYe)8#AgNKgSW;C8maqyJ~H5<*@BBYLc4IZWwwkx!9{Zg7qz2` zD@x$HF~k1$2wgN+a8XBS7p{7?;G)QYi!uW)YF9U|D1rOW47eyV;G)cci#kHP@bqv` zVI>tV$_%)uJtc8P2|UNyf{P*pE*ceF)DhZ+w}5*JE2(f%X23=5X^$&P;C*C<{Y4bI zC^O)qj?gZ=&D>L1Nrj6>1sAoqHm)dvafKQ7H&p1N%z%qJLc1_3aZh0-6)wsQxTuXj zaYYG?kIb;YxtV$_%(@N-IiW-VOHye+z~# z$_%)u&4cm2vi!uW)>Im(EMR8AIB^55p47jM-Qe062KF19E3pI36X23-qpVd>1at47g~?PKbr_^Afr!GvK1;yJZ>fuieNwfq;uL11_3V zLc8ROfPjlK11_4=iV|{fK)^+r0T*?IcFCR1(nXm87tLu!33GvK23>5dupNl^)T=Rv?lnE@Ad zgm%e@0Rk?{47g~d6(wZs0s$9g23*t;+9e|&2)HOS;G&UMl#nqP1YDFEa8XBSmyF;b z;G*F?R(FiFqJ+#PAmF0RfQvdpyJRNH(M6d77mc){gv^P^fQvE%F6s#Fk{J~la8b^+ zaM4IBO32)f47eyW;G&MuE-?dSz(tt>7mc){gg6Q^;G*;rxTqtvOAH4Ya8YK!MI)^! zA+CiCxF|E=qK?omF*RhsMY9DLjkKbKI3qIPqVz<#s3Uw=?4rnkixw4J)U9$Vfjq7! JhQHeM{{YlW;{X5v literal 0 HcmV?d00001 diff --git a/GEMstack/knowledge/vehicle/model/meshes/rear_left_light_link.STL b/GEMstack/knowledge/vehicle/model/meshes/rear_left_light_link.STL new file mode 100755 index 0000000000000000000000000000000000000000..b24d6ae97b5676dd648b3afcd77c7309304b9f99 GIT binary patch literal 8084 zcmb_he~1-T6n@wbQbR4bB-GZ_l+sMgRoi{@rocjiL`w|ZOiH6Hi%hLHb9c2e79%Pu z#H{>*wq+oi(PQ_`8!;+12r8DsElm5PbT=uqEGz7M_s%zS?vBs*{%HSjKj(bk`Oe%o zbMHC(GMWGPXG4^3-{H>e{GXe`<~_@{*G_-9?nr)e0E}?=%qc;iZ$=b|twa53zo0d|L1rK8D@zDP3!@1rhqhLhm1zz%Lzo7S(N6gcb$$UM_3tyN%Hl-j79>msT z=+5b3|2~6^f)Sk;xMo9j&^WIz@yzb7i z!AJR3k;k{A9t;ni{34|w3z>+m$J8H}gxznyVHAw$yuf#?ofy2{Ffj6{$v+XcUA;1; zAPXME)?@gj6=A;ZQlnr*=LLRe%#@&|>6bREs6N;j?yA~t-e;{K3m(K)G4fPXxNt~) zR!4MR;KP4S3I+x{>a1eSqNebo z;)D8zaBFaXNmsT z_kerC&Qr&Yf)Sk;_{JTBf|(1yj64opGbjA+=y|@*rCGS{Dym+)HC*t_5Tjs3D}dJ> zJ2!ZL?&-*5;=!B3#&M%l3bNoqZ11D)z_@VJ-?c`;h|UW&6=cDK z*m}qg=W~Z+MCS#Tz0yneUD-u_?xI>j7CeZphwRk;=4hv8MCS#TJ>N^t4>=8do(5V$ z7CeZphnzS*PaH;cUSK)ZyyP5|Q_X)eI@Pp-EO-!G4>>t~o}7&6yuflgd&zk&r?bz~ zSu4nb2eI{#4#3|TbpVX$yui{Kcu8L(U53vtLo3LF2eI{#PR4JKIvGZEUSR2oyrjR9 zZpml2q!nbrgV=gVN9MC5V?^f#maflB`b6pae0F_WK^8oSt%r1$K08ZBbY5WTQN5(! zmG0H=7j>^%K^8oSt%r2TK09PabY5WTwX;dzE?v0KE?g_ff(NnnkWSxcr_YGa3oJ83 zHkm)(t*!DoO=tyK@F2DxGO^_TjV2aGbY5VYeX_|MRnvMX$Eipw$btv4^^nOc$H|Kk zoflYUxNI^H%5<0Gbf*<$!GqX($OM_=1j&fb3(N`GDr8E{aZ1$+vfx2%75fg?dzgfE zMCZkIFfn=Kce9Uw@dFlqBcc_&p2>`FH9SWlcW&lau%tpWFP~k39LUvE!6_WkbX8Q4 zMUOMzhdjGxQUpt$F*BJ`apwDgD?PMAo}PGiE?pH_@ZgFdpR17F$IN74$u41Lz{;!A z3VHwIDb@9WEAN9WcyL7!bro`cnCS;B+2_r)Re4ofAv<_H54s+3WmROsgDZlltB?-B z%o$+GNp0qu%B#`}IfLWL%k_XOt0D^?ToFWFh4gTyqX$cREi*w>UX@lz7ZuMqt_NIM z6wzn*iY!#c6+zTh=#ETxfMAxdN-Nl-Lg#wm3acUuRdGcSbrrhz(Y+R!<*U*Pc7xEl z9=O7)$U;?I5ky^u?lN>&17`WEw1RyXbgl=kuqv`p6;}jNSE0{y-9La?zACL?hXbAK zfh(+vEL6o6LDW_76b4J5)L@pcN-Nk)K<9ek3acUueq0emn?wAIAAQnC-9Y@eaLb5x z21miXP_QayitocwFjr3nR|N5NRmc@pWxf%hM|_?;9{dcz;wMN&`Kq+y>}$oU$btt~ zBz+%zUcutiUU^ko;XGH)o$J*l3m#mNbX9z}!Q#$Pc~x5Byn`jHA`2c|k#tqu2f^Yl zT6tAk;p|r>t0D^?T#-NH&MDOvf#lLNmnKNhnX6{lHJG5 zAC*_774n|P-!7G|iY$0=MbcHtUTY>Suwp%|S0t194+#EOWdHyG literal 0 HcmV?d00001 diff --git a/GEMstack/knowledge/vehicle/model/meshes/rear_left_stop_light_link.STL b/GEMstack/knowledge/vehicle/model/meshes/rear_left_stop_light_link.STL new file mode 100755 index 0000000000000000000000000000000000000000..9e30a0a210b42cbeb0dec03551717ce2229901ce GIT binary patch literal 45484 zcmb__3;0&U_WxUv3Z)ym)9p>kQKFOYyZ0{TQX&zR2qEbrMM^36dv4{LOPy|SVznn# zmn#U$cxz;{(%lD+2l}}?XSDsKUBjfx;Zw^H!sXU#Xoqw1g>GLYeTSVHkRRC`Ii>Glk75bgldOSh!zBY@7;7!Y4Dce zL~JVLpX{ycdUjQd*UznQ!+d3n$A3Ssw^ASmOB$@i9qtQ`Rv3u@KP zuf1bt(x>HwGK6puA^n!iZSOxRzwY5*lJkl~otE3JC8GImyTpSB90M8OuedfpxLK`q z%Z&pSBBR*-GpFs?dG+JFCiMcM@24~J?@wu%zP_ek8A7-yqx)I)<7KUg=&)>7{^c>v z($*V$D?~=g$|d6QZO!7rJqth_)@nh1agBEAp)GqTL`KOFY*WjyQ+z?#9*EIucCtVLKqY@0{j0 z3_UEZGOMjZWRwh%%dKp?xJRG(#(Q@K;_=6y&-d%lJ3Zlq<{l#BqKrfLJv`pFsvZz? zKYA~}?(tJojBeNWXmuQ(~~@YJpfA<}IG ze}A&Icl^Y;tkn|({+6Hd^>Jy%*Y(Q~!sXU#>9}w6kNtH*`orh9grv0pc2xYuW7nx# zO&vQbK4{x?RjZk`N5}7{*Wvg1M}3_SFB+fDI(mM{`U-_;L8y`*JR=^u+xeOs(L}WevWA2Ci_@gGJ)2_YPX}RB~wEFn?KaaPEj1AxZn7{dmDd~f6_EdXsR;yRej%Odeq(m-b ziQuwjytL_ue6Is9POqImQX%Ye1wr(!m!BUGKZUh=2|B+RIv@2`&oYE?xwWc4V^jW! z+ef71zI|IEjK!&18QWF0lG^5Sw|?|le%8-p(uqq-W$h3IWsDnjcKm4dB|xWrzsk3| zXk6NU&xgto!sYftTX=>XJVVWI>ca!gY5Vo5VO;&ZCQ3KPN5$+bsV%Hz-P(LKb5L6K z(i%Wy6qYLp{>~7u-t|Gg-KE3Qt7d;))^gz@LfVwe^?|4E4o|(|r2|#1>TPQocl)8M zs+IA5=zNznf5sVyrFHLWTh5>h-%McmYoVL;mdl;AZdyJmR!Qr}r#LOA4(v9Wl@nxySdlfs zifq8JGZiAEWC)^HFIrh@y!S95M!$D#zVYNW$-trKmLY_Twfgsfm8I{VJOhaBpBC~> zyRA&N96m-NGD=o15oWCg#KHHs%D*^eVKRTu@d}YqG6dJY&-55oI^%)!fT;Us&HU<$ z>B&D2zQ{vlT$ItU#i-Kg%ZWG*E95J%LOvpyq!1a!MVK`l5IeV8-nQ$oLNe|zQxqbj zWC+%(ZI=gDO#kshAo|~POWW$r>m{e3F|`aKT&$H@x9eIhM6E)rRt46VT##45x*c3f zUO~5f@6FFGY&PVm@Yvm_z)CWTjW9AQur~nuI7e?26)=r5O+Au_JYoeU7q9586X z!0qb`LqF9Bv&T^_7X)SGa-F#M0pjkx2eoDC0-WDy7t(I3JP%FhnM5e*|Z`LfXshA#$CBm+h27TSYrVH4ypdGOG;tNw2 zhL*J(N~TS$aXAJHdJJMj6)~bh8BtkT85e7Xkyg-SaMXLp78^}o6UwN~C@uoyzkppB zY87=j2Qt10Eze*m8G^NfUkS7q9k^~<5#A>f?~|34aj{nL#{vDZ^3+9m>d5lchTA+L z>~Vm=tX9OV7U@~7JLlR!=34mL0DBH_*)rg%i}2Ku_S6}LimH{=R?VD6%$$*)Io);$f-*3R z270c=>|Dg`9Mw~^vx^WeyG^-VgBhEON8Uan(yOH$*KmQX;jm5!u!F#QC#!8PhgC)q ztBgpmGBOIw6$F1v`_xLNh?PvFS28X_xQLK8sg-3BE6Yf)EOT6?23)0*3+u!HyCPL9 zsjXU(6|o|V^oq=FhaiZ?>MYP}IIQ}LSoKAE)#oCFiwJ2`E{9ck5v%aXT7?H(pOXu# z{y?vmb6n}Gzvpr-r|&4{zMU4;ul+Q1n^9~8e`8G@V2^_~o!DV}vDyt&qx+ZFA!ii3T>i#tIWTMLO+OT|3Xk+E+(if%5z=pJ$5OquYlWy`pyP?hd^)4JVM@d3ZzcknQCx(XwILf(&LX0mkrn0SOs{H{ z)ucNk!UY`>{<;68;(HJO5=taBD=Xt-tq@x-Ft(h_A?jR2)H$@G&W7S5%z6cgnj4QT zzH#ZAaQ9QsjaXJj$q?*mM2ZWHs^@YaHa)a>;puT0y*s81AzUoUtki&b`m?VVB0?YP z2)&Bq7bK2vR{G$wWh|^!xA^uQGeaG9&L}Kb5d4h@bV0|dPrt8K@$1P8Lmk<65yIux zs&Uo(+FYG9kDq=0Qq>MQQ6QIDQ=?Xu>vsGGVgV2V5jMp}@VD7n0D;qtg*eR!{L>7V zE9;S5?%6wMEZo$tVQ8H+RQ8pWOEgX$3i@mUrx^=znh{#38I=g(B0~BNJ}q}ybkUtZ z=lQGFx_O1-7lqQyBag)XV_xB(U6K`jM;@(y=W++N!`@_3IYKDqh|cZ)_FCWgw-LFV z<}&CC$}2~7YVc8MPLmF*CRNrhEA6=xqb>8GoByR&Hsaj9rkA#k@BUw8NLegbxcFOo zq`X!`j%Xb}aQ6>bU(G8F_^Cns)(yM;fm+#!JLXr5U-`J{@6<}TC{KE%yjEf7Uh#jv z8>wowZMQ-cuq-tfXPyLqml_P}0a&3gMyk3-F?H>wu~yO}<+Xyn2JoWF!lCB?Ui1&t%0|Fq0(jBi zsg-cCR?;KowSvzG;6+ufFeUq^MgFqZ)F{i2X6sdW6^)dc;9w@eGHir>zv#CRaucQLlF@E()=cU2ZExSbbUE4(=?2}44=Op5aq*HLtV|gHYw_Y0DGh(FCaA?S7L z4?s{Kk8f%pH8>_vaZ!o4Q-;LFiKtn>S+Jl}MWFT3@4h{v#&wTZ2#JMTy&Di=dKU=l zqyD1J;hKXhZ%3;*H4zelCcSL#F zCnPH`yI3LYd)h##d*KFA(g^Bf-M@B9$K5+vA?!Qbuo87!*|Z~ul|TmdF?;);(|_Ie zCxwvvyKD!nMBUjX0#*{kN`Rm~+V>xvj+(f$LfCg*jkhZh0e!?;A0_DH!(kVvFPwRz z=)CgYtGQvQ5Fal*KVGw9KWLESW9p&P(syS6C16eDW~S1Ixs6E~u&Y?x74^~Rk!k6N z%LZT%pe#|{z?9!SueA`^c~Kud&b=rdckz|V+U*;LuteU*EfE20kF~W^AAKJV(rc%* zPg$;gqs{b{@(iZ0Vm&^N`272%_m0yP!oJ-GE8!h_g@Bcm^f>>=E|*5{&G^1F@0enI z;ckB^tQ$D9)aBehYF~r>hl&E5{fCMt=W;}xQkY+QG5D+E!oH?57A^>u)cWxwN+;dj zAGK=H?2@SG=SRn1AK5;!DJ<7Ui0oYMi~G-y9_af-JZJ492VvLntPOV;c3$1D)be27 zNMWt+Jh@G2zjq#0wKDM?r-nq2+5M#z?|*xusnthc{#ZI}w?8QvLSe0>O?GW{t)3oq zbUfz!haH5?#abPB=$k8^UUeE|tgbyG+H~@q_~`L#6Pw~AvUb#YyMOfhYmdZB|Gh_Q zBkb1BdH2RbvnKDYc=CV|rscDy@5m3TwN$m1J7JzEupQD1l*coKWy1%WmZzt*Da{z) zNwq^LK0ADPgxw2lIsbn0v*$v_o1J?__k7tszB|`CwJAO#>#HYAt)my~eq0*)R!;|E z_bArYN=E7M^G)xE1;zDvFPgKFsCVyB+?~J-9Njdsh&))=V!{XuD$Xo>cwg z!X8KK-bF7eijTAspo@MQC>qQMG)(Sda&_A^) zK7ul|J{qL&hE*od2xfOV$3fUyqZiFqOQXX_!ox0|5&!VcSV63ybi=iRYbySxj9#bm zej*Vs?DOa3*1bljq+o{ReCHr2?~?hamR7tA#6Cz)DB zuP;fiUVD;~Arv3cYRLRj_!38L9q428bq^=4YDW%&Va#YgnqJi9dHA$n@s)u?x`Nj~_cp@U$#!bKaaa>y&CzWsZ%RHW33_|e{s~XKJ6(2hR2zs9lxdW41E`DBlA3?BO;o?}SHfU98z*L@da{f5$#t0DEC zOJ3Xe?+$|H3K#qBw!`*}7uP!o29`yS>imXNo22t@9H?|I6d!Tyx2MI|?|BUn9Otj!dr109+nXH(%M~v6bj9pb z;%iP!fS_;h+Tnu_Jq!#2?nLb$BPbvXyKyH_d4VB_@tSu zfS{*7dh(fRa>{*)P4N-gn%dHNK&=^_V>dakASb+*&I?-S6W29QzPNFAU{id=zi&7+ zUN(Fk5Y&0=vmZ!Wd|E%W5&SJ&md=5o&YM+VnM_-JL}*idMC(R9<0VIa1O#>d(LFn* zO{Y(G5JU@?rE?&t^Zu*rrXA|s9oiHhv0+@F_~d6l1A;nlU9D3(w9z65L9}pLnq{q^ z^FGVErJqlDCbTI&;@=I9i%W-Z0fOWF;$i*My3<~C5JU@?rCA`T^QX5BNMCtiV`x)+ zM7AHae7n-Q@$Kq2&Wdio#(|1Wu9+dmxy z%M~v6wDHG4Q0Fa9U6~v*Z0E?P_=t-x%*AIN+Y<=-_P4*>lAL=}V+TRBaIvS22M1yg z=={uuKP1l<+DA6UN91el6wghL0)jeUGpKg@NRzG(f@tBQW{n32f;u1AYPWRJr9C5? z;v*0*F>wa!-0W+Wp3Oc}{WiNhrE|0AgbZt!sx&AR>fA<{eJv2w`LVOt$Af-c;2@|$ z;bKpl6$cR1`Cl7;9Us2#4W&V$_z1Hf1cExBoE)5lV|R`0viMuL*wbd^1O#>d@~#IZ zLki8628H4y%*ql7j`I%&k4qjo?@$N9a)paMZB~G+6?8s#)3D^b*Ly1s3dKj5bubXr z`IN(NPAXQO;viVAa8a{nB?|=S^KJ7lPcEN#j?%eMe1ut@13{gey_(XqIjF(x6a`&MOhnW&yDbAgFW100P7S9E8!J;$lym{S^?@Ibr|-VgO3# zLh%vMW&yDbAgFW100P7Sl+FcVG^n`P(`J7K1a)56XIn62+P+GILh%vMW&yhiAgJ@T zRlW``S<=Hn7!4{e_Vg;fR|A6cId&`|b}UMRLh%vMW&yh*AgFWfibCv)9E8!J;-b#Y zUJVGd^9r%^QaTrkkH}({)cFN(+#FPyH$drGZiSfHS=|<4Pj`QD|KPhhImn>S7hm2W zJaq80$^!_+M_{H7viZDgcuUyy?4y*<1;KKKi#`47<6VN**H(uN>iqqhPlop%cCOO7 zP<#Yt>L8oXhwk-l_+yQtgJ8MB#hy+suL!o^#rFWH^X4mSML%5gsG6OH;v+Cq2ibgn z>(Tp0<8J)GL9krmVowiyx_eM}N*&1HIRAT{PSJVif2d|>q4)^Q)Im0%cdH*ocTK3K zbS?;%D_qq1+^W5T`@XCT8Pxd?#~mHby)LJ8E)*Y;#oMX#&rWm?zY>JP-E-cV{wWpx-m9wKLc(0X%AX>OA%|Zspd6kw&NBgwsr*>Y(8cIF_ zyRbm-)u{8~$*^cvgPsn8}lh{A%i-v@%XmzABU_{8Wf6;K(r;$F&U2Y znd|qC_CI8+gJ8MB#hy0)7&55y%X>GEdYoS~wJAOV(Uw5RWVk>U2m`H%=)-2p3DrqRxN9Ip>T;8%pE8nWhjzvCHM}EPLJD14!f^0M7pT z&K1T=_Lc!0`EN`_E;g!G}-VBxSC$=hwub`UIAxTsBu4(r+A z@=GQr(KV+jD-nv1kQlkP#Hu?@OAdeWNC&}kg^N}x(P2HS&2DvEQsaw4YEyhf7Cq;P zx})n6NsYfXbr3`g7e|*whqaYF^WN&@zHz$c5^rZ;*=MQJhq+wO05>4!yqrANW2Dnp zHiEyiH!i;1duhiZibz5>k(_^Q{g_gF^8Uasr{f=)uq61i8)b4ua(h7jDv*^nvIlf6qhb^x+XRn7 zsToHoJ|a7t;Oh0}^szYjrjdhSxx&R6&P1jlgEQyuZ?uT}HlD3!PNDb++$y$C^+zr4 z8Ru8t?jTsMoQ1gUV69Ay%&C=+kaH2;@^OogO73iPi-Taf!sY6NbM2fCS0)qJFLrv@ zN65K|)?ka#4<_f0`o=-9T;X!dd&PB8rt$SDX6bG;lg5?UAJI*=R{<#IcAUmDDPv`zZc#vWw|;UXfd z)kO`K20w*;((_MgqS}F6ZNB8Eyr|r=VVkfQjj>BbJ8mm<4)B~_ezHo|yNco?{wK-e1thS!aj;EM>HxyG|Fi?Yb9K+KIlaejY<%W za(dTCm~$h@pav0*N)U~55G+@?T)UzdMKmf!G|I6OA7RdoAcK~OXjF=5l!IWo!sU(+ z6OBp{jZ%9~86Q5voEt#~M--w_DWXwj<3qUIac-hfDWXx%sAWxTggIS;jH}?`TEEpV z9lfNsgJ8MBMK2*fMtjjeJvK1?u3int`}m0LE;r}%DhJMr2i5AV>`H8jRwAd?wl=k0 znNv$;S7I4HLe8VLT{Zjkp5&_++bFvd1j`jJTbp{+?iln;GJRyAtVArsN5~1bwyQQ{ zs-z1(zurNxT;Z~{sl8A0It|hm&2LdwB9`GJ z)%u@@rW-qc;UHM9aM7+ZE8*T|>5!oA!oSo0P>Advyf6rAitC^mw><)uozREW8D^x{$J`CFbTLkJfUS*vm6HsnSr5 zL815vxjCZ8dAIM^B*lTT#4J@=ELXTV<`E;05pRbK&QZz6MM<*o|0I&CC_VyFRdY{< zy9q>V6DwM)5G+@?=(`a2HSZeGC*FR`Lvg+CuSrB$QGA5l%h9tl&JALm8#oA-i&Fr; zys*M;hdDP$aBd*cWmPL5ffIok=LRcu%W-ay;M~AzIm;C;S09|6ac+>{+`#EwAAu8r z80Q9%K@H;EAjP?XgJ8MB<=PczXPg_PI5&uGijTmFK#X$($l&aZbAuG;1`dK~;c~}^ zIX6ggZlLZV%E<8%I1z|(ZU7ndqBu85ac88S>(N@``LsP~&$F1eVY zVxcSWo+V;39qV3_Ubn|kb?4udi!Am3ihvBZe9@)nrw1oDsN4lXSmmy;dI2)%ud07^ zPWr*}St`bEdQ|dbn8#ovAcO0xBk$>-ZkaZ$V3%e6USVkyGU%^XZSI+#_V5krtiV`C z#jhYBgO<4KnAT~hz4s~DWm&&hSXK!cwD#h?_0p409agd_zk+}aj;J;Vyqny!WI=_E zuzss?ZpI^I&|j@6ElK88+eeLaq5KL0GIUI)Q&My4qx)JTwZi%>?+>UKU9|V9h#!lO zpS!@J{0agxzCd*FhR>&@i@s{E@>nEyMcJ!)RoogMg?9Wmig@W;8q2c@Q#aS0A=qlC)^DwLm=!#Yc#} zX}kL9#sfLyI0(y1)LRy29)t|egT}5LijOce9NJ-W;!??pGb_CUtwg>NK>eF_5M=P& zV9Ze$rdLidxpk3iaF~x~uXj6PdW{I>boLZ(h zwR8|f3m3I%)Cm$}qDX=L%LhMc3m04do2%?3Hs~WRf zf(+V~SuMdbGK!CIEzzvV90bvF&(^N3u9dk@?bOOgnEj_|`8%I3NRB`3eFwpEh0E0k zd-t0juOu(Vdxti~N0|Mm(cq`sYo%WtQQ;tn7B1U*wD-BJ*eLzK!6O|j@eyYK2^sWo zi)VC8pISb}L9krmvPXgTqL-vS)AOp|=~%muF#Au);E0+ueMnmE+B+Ns%M~tnoHP2d z8}>NQFM8M+wLZe^`XIyFK{^PQD_ryv;$!ss>csEIr2oErnVQvv;v>v{5HhTtu##c+ z&dOie8K5E$wi_)CE_>vx^n+(VQV5~2CW7E^f|A-M+{VPeP*f@l+Ic4X^X;noWy+YZG?m?*btIc~iqxb@<+ zoV5}zS08GQ+A=S}trw?veT0eD8x7*tOM+W34ua(hmupwF65M)8aO=gf5+7ks9Uz02 zh+8iyZoN1NmMdKD_@K4p)=P?8FOg005$5y+GR&=)6t`X+1ku7}k7ga~!>yMTw_co4 z>m$r55M0EL!XeIU= z5Mn+0o=l^Od#5*!?dw>Hjo|O>i*wuw?>KdzwAA;AGK6puAvRt4UPdDCWtbZ~%G%|X z3fh>t&jM>_OlEQIACnq2PEj(1!g6hdv`>%oj{o{J*=PLm4ua(h7j4YkXMqe_`?l^| zlI~|8p=?(uK0>l!^z2-3(yPhMy>+gPAXu(&(Z>bK>h2kS5D@j{>ucap>b+0Tr2$m~c zv@vs^1u{50Z#}zfGW)IDmF)_}M@V*+wsvz*#zC-L;i9#hTQ88o+1cEBQPwULA0atk z8ewkMI0%+2IYw?fxMpbZ`t-QbA+4NR`3T83(k<^htA5gZ;sXwXTYnbeM&lm^6a)pb!S=DwU-%fxGdeN0lx+FcWI#cOfC_X~+%Cr}4u%KEpW|w{r zg5?SqZ47x+d{qT9=tcK$(1!7j4v4Uwi@SB7Rwbbj(Oy<@s%6Mpcj3t?oILE z4_T~yiBNomLb50|!o1ewAXu(>RYmP& zq_(VsYsud0;rs*2OQK7u#1@ydsuJT>6$im`h07i19JRwQX&mn|Nc$2Q=RSgHys82j^l)3c-5*ameoEOm z7cP1U@iE$qKDf0-{KML5j`v|rY()0$30h)}zpJ;9lwFA}8GBVPjN96*v@5>WqpUoaSwtcf7ZoM^sEV&>YAbFE(!%$$nLj1N;Q-jlho z=|dssb5byG^V@)Gc9z%vSQ1tSdI6JqP*EoFOqTSUP z6pD|?^0qmDocUueY%%0@HO>XWa)pay9&7jl-q?c-&dziCJ`v!ZJLOA+;v=&BbM7Ya zmR^9j^c)1s6)yTN>_yDC2h8kTz*i#qq{uN}<67l|3c*{KpI|!C5T<-Xw zwd0Mg5N~Wb*6t&)(=Xs1FUVj7vis{x!mHMvkku>@Rt$iItZ34T(*zVv-7|Y)`V9aGQ#mbJ_36mej5}r%xj^MycUY+kouk% z%at#35slah-;@Qy#AL#nCMF{kA0ai={tCHEA##^gI|O0ZioJl?NuXaNF}X`2a+g%^ z3dKiAPwU+Ta+gBnE;$Ihcd1RpP6GX^3atdWOCfTXl$8j@M~KDf-2`%%LgX$v2-`|% zm57}bve#jdyA&dKNm;v4e1urOUY8(uDMap)8c~9&bd2E=3n6Zo36Q&_ypK?Pgm@x&Q5_wO7#*Z#APT6yUdP|^ zvM#lW2&8#`m-l44ytij`$&TL2N`&Gg#Co({A-g6*c8!Cu?UmX@{5rs!XRuw)gUH~C zkiny@L?}K&>`mL%{rHCBimGiLgl(_XCZf>+-fn{o+7&X9!c(7ap{ztGK0@qG+ZD2% zLS#ER2-{w%O~kJQyg>&UY91W@V2F$=WhFxK5n?^su8_4AB5TV**!D_oB7PmrtJ#ZXMy!XlPb%$SK1Zg*XCik1}Q<2)l`3GOLMmx-jNhBvGLh%t|Z~DXpuhvC)wNBZUAZ&Z3 zHgW#JENsZ2UEyWC2ruI)D-nv15PQ>hh1d5YyuRlkY$@v_3m9QI&D&2 zWhFxK5n^xJuJDRrh*t#FiHRU=d!;sU{=uwx$e>-}rNR&|6)GzcijNR`({_c|5JS9% z=pbx+r8aT?!R&s>pj|yWeMI=-wO1&+5{i!yd((D>6O#b1Iywm3UTIh6H37(=UE$@( z053->yAq0z5PQ=IoUsJRD{>Gl*Sv9{?tV#ab*;?125RLc6d!@}X!FVqTRw9B72)-L zN0hZgxLkd3eRX}WVu&0pr+3*78)05TFd9UjSBN|>2f=cM%e5=6uaHX?BA3ju5+8vZ z1?H6-Mn90R7Cj$UaV(ML3YR-RxV}P8T!frB$J%`aZbq0_ZaAWlcNZb=&OxwT;c~}0 z*H_5xi;&yrj9MQdZ`qjW$KQkK`*m#`1j`jJdI|9{dVN(IdqlLn(>`ie6N-<>zB9`; z+&d?n7|lAax{`q#BI<>DmWx|2*h6nsw=_i_zOjybGJ7>15OuzHcZCp&jo@$j&TKAc zZoNdj_2Sn=xQNJVWp36)yjeqv`R28{y(4eyvn1Tn3Gk{T_UXJQ^GnNN(erCQkh?gF zLbQ#L_UYLf*)dYZr=-zzrDlLKDXavYjGiJ2?oJD_k5axP=zr zwNS{Q7ez)@gp4XR28H4ya0AA?G{td_tgR4PTMmNd3Kz#bZqo&L^%OGbOOP2Be*Iz_ z&;A67Rwbb`YzlGRNsu#J`ovi0W#c_PZWxez&#oBojCek zyxtn%^;QSLa?Sfb%8N>EwHL*0!w|2xDlaM&AAx(8d=bdB9Iv;Ac)itWIcp_cu0Ghi zc)c~m>#a`j`Uu<#<%>W@gLu6)!t1RLg5?UAYge=qyxtn&^;XA9e1v)H2Qp}hc)c~k z>#Yug#Y%9Z*{EQN0_&MAcOlTyxtn&^;QSLa)rws=k%g@y*0w?tk*NB zJp#Ax)py)gx#mmkMB}crdCkh)j*jGZv`~D6)KIVbkbM>*`%JY%5O%HD3%JE>Uga{` zXA!c`RPPGKM@UcWRUfj?B4nRA2)lQwP26HOuZx-Nvk2K|%1VUdBgA6#st?&`5wg!5 zgl#3XO5AleucXmmA^R*s_L;JFq4)@~e7)*J_F0JRGr4uI%CfDUqYJl~1O3_?{S~s$ zLS&z*aV``eAtP9O2J=>!gRn;}y@Yvn3|2z#gS*ZFvd`3AXQB8A@kH8oAOC!EH0S7N zRIC^|80s4}v=U?q1^8l!%FPj5$mM$BJ(&qdPK`R=_O)blD2uZZ{Ee@b1aIB*C2sbc zjFE^LBesp&TvT~PL+ZC0$OOchkq$t0FK&?#fQiR+k z$#zl*)=+wZHfG+6gA9|q6d`v>az6OhoMcg{ezOpe!PyzPOA&IHB-=?LY%bcEdGii3 zOzu*I+$G6G;+uJr6Q$m^vk;I$zl+?Z2)Rp=?W7Pk7j4YE-3J-8cH}Na$XzPflwUzW z2ImjtE``Wlk~}EB7HI#L93#F|2pP0?$^RM~+E=+$D$dD+tK25U{1nR~FT8Gge9#8ZuZbWWMl?Mu%dJJN0)n znoGLn$gT;SHQDMQSgvqcy#N{PU1act$l!@>ijOc}2{NcbWC=yc5^@kk3zwx$$e@)p ztlla@CX&jW6pQl_#=AlWXJ=$PMb)pI=^$9Ha9MT?8MJm}R7J?BifxLIFtY??aJ@Tt zi4L7z zGqEW?!py-&#?ZYkjC%euMb*m8sU@P#9Ikwf$U{4DPiFq|Nzop|&rk@V*a-f{_n3m= zr}TmhlYbsD|J<*Ma1oK!%H+65W0B)dirM3+TFF<CVsa13tVUMoUAPGVDh zgjq9C2FCf894I>;VeiK_#YdPm0}%9AW;fv=h!!sT zF0+#X!df%HGBS#fFlz>bFngTXM)0@U2`SH)wZqzZIkoZ;W*25!j;|Gj_*y|?x17I) z%kFjEyUnVv4Dq!Br+0mX*-b(QHHfbjMEF{PgJ8MBWm}K-qWD@tgs&AiR^lVft{5_C ziTGMUgs&Ai2$m~c_9!r3bXm6uUn_8|-A9<+J!Ei1;cEpEzEmy8*0y5}D&%myz*-`H~2$m~cwvW+X^oB>zh<3i}E64lz2onQ>3|gYuZ7aJH zTcVYi2&A$r(Z9BK^J=!TE1~!Z6Df@Kh-w($9@coItFkLW&`N~M)~2>AWblN@;89j0 zmf<5zY!NbOS9fjL7XEaI{yvT%Sgvr{+SGQ1Or!{zNXkmYGJJ%IEkXwE>Tk8%M#y$@ z5G+@?Y;9`0LPk}Dj4EX%Vi`Wd#1O+SDBUYp3KP8kB>Ix_egDuk1(-5BV&t>aw-|-Gy^tP8QD}T z1CgiSld18ao>A5PTPcK4Yy^MfjkO@^*aR|oPi9-#CmM^l+x(gc7ZF*lc<&YO!$sTh zJ{&3Ld{EU&zEaAP%&81y+=_cL5ANI{`o2pyB||7g+X!i&)(0|QB4oZe2$m~c)Qvfn zfeh*#nJ*DCUs9XmBh2{@5RAzn^Cd#&i-RCqxM*YMR0aszE;3&tWWJ;}#YdRa8X&lO zMdnM0%okeWq{xqMCMC~%ojCkh2kU3`3?}AosszxBJ;&Tuw3Edm^Y^~ zKyY^M&}d?a%opWLgyJL2xd;%P2hBN-gJ8MBMc-vkWq_bhG^aAkCkn+!nDZTjFeg6_ zg5{c1MCB``wz^j4)Y7Syk1*$)rsepqOo;EwI0)8CxLkd(ckx}B5Z{$?de=vo^IFKD z2Ju~)5Z{$?5G+@?Z0pfhg73_-vuQ zW9>e|oS#DmM-;v*6XClu4ua(hmpjfmJL9`D5xy(qj9MRI?g2msy=e1m8b`-;Jkmk1 zT;Z~PjGmom4Qmkf8QIVAK0dPqh2CW^rOCfTXl(h@RM~LNX ze}&wo5V=bZ!nSsfE_3SzGU%_6yA&dKNsU^e_y`%n+B2AYG7iEXwe%9^)(d3NUm@T+GM>jhnL7V^AzVJ^9Aza!A=*ZW z^=P|7c1?)v8V6z9E468Eg+c~LEi!mQWbh~}5sHrxd((C`==#~=n|P1aE{nf~i`q1| zLLq~8b$Oe4Au^Gal?cU0h`njMLbg+gY$pd{+bgwc?s!55?Ft!HAu_5`o8lwH-n3mI zYb!+7ma;1;i)i7ZHqC8H$e>*vGpl~sXW|3ON`&Gg#NM=BnVXpo!nRl1mAMrP8MG^8 zxbgm#vMZtZ2(dSPPX=%Hhw^5>x!`D-}y;7UzzA$9auJFaF5MP{9Rw5K1A@-*23SYGf@l`7aVcQtBY3>U{2JLFY z;Bn!S^A1&3A`~AX_NMLX#a#~y@pUc-VcRRUY3>U{2JH%801NR2FlARl@eyJ@+OF`G zu>fBgQ+6c?+bXF|b6*%TXjlDauMhAgGi4=0@eyKg+OEt!WCvl}EA7hMDuxW&mAO@{ z>`Ev;LhMZ=kXOW;%MOC&ns0ll^_A3C*UEg)%c+%*FnJoL<&W0ADR}RY#SVhC5-wLC zTwfsvD?kpG)4M*xWOEn|BF`&8o|mIRmMdJYU2zqTT(SVUWR8{i2$RhL8C+j=Y||(_ zsAG2r!E%Mm9UqJ#BPT9IPMl-yK4O*5=70>2DCFIR$h&h8ELXVPac*+^Lge;2qt-{5 zya~wQ`pRTlI0%+2T=Wv+WAys!%-YSv<=;(FvzkzRgvsWB4DJm~MlRwdmHEKRmf$(n z7lDmcmT*rW2#ycjR!?wSU0DgnfufL05N51cUm!*ouXb1fjzWNs9t8dCmOje^hb%5_u|X z?^LT>FIP{Ak@MpqY%cybnLUufvpeMc#K`$kRw5J|LEV@<9Ux3DS%6$J2VryB+SFEJ sa(wsf1TH}*88r#_t|Ifz1G_MoLuhz@82Pn zx!isaO^9#W|KEJS0mp_%-QB|s{R$=MkW@Gr>(_!PB-G;{p9oL|; z*+GkZm1GIhC1Swj3*(_ZPpv$B@k)mvooc=H#sOwy(wt{tV?&R@@sp4Em2I#7$X7|0 zAYCFRMrXzKj{7Np@u;62f^@3Y{}6(;|Y*lS>X_EQ`411HuARFWk~mx%6{^@+z`ldC-b znI;ZFI@RiSR%5fV)1Nh>T<)(wdc-GGHL2X`gBF2GvIOZ8asKID<0X9$svP>lJ`O=T z)f#qrBeU_Jq1(d7P7}Jsw=KV*a{LSX1}e!Cq)Wt8^A3w=Ty{a_$pa2_2-2w*G|k2( zmp6h9XvUA#9#RQ1P)U{`T_P?VR~i5P@4(8=$9HoG(y7*v8ozlQ6Fc0~3^qFMwO3p* z_}P5(ACC%Dk|ju&h|yb`#Aoh0CO@TXABP~FYT?eA4YW9Hc%2)?omL)_?^NU1KqXm% zbcy)mo$cf0#afkjpLUW%kWRJG%gqLQCv4oX<=^PK^JeF7T6$Wbk}N^GM11h(chRGF zo}3>XpW_guQ>}*|e8gju!(G3Hi&cFQHxq(Wu1nCk{XQy|f2Dg8kUs@RI z5TsKrj0k1}Pcm#wJMYCPw`2dx*DtszP)U{`T_Sqdu8Nu$cdvYX;s}QzooYQyHg8o2|OaAxNiM3$NVEY`ng657?-lFej|;)U0xN?+JlQvIOZ8aa`{@;lZO$ z$f~P^&CPdxd8|W_PPK41L)N3zOPYBD{iFZg zFaK>1>m_ALmLOds{%Sql@BQlkDn4#_Ir~+a;B~6?V)c#o|J&PiMm=7dJJ-MNx09>x z@kRzJ$r7YX#9j>__y2BkVAb32Ug8j>Q>_tLE3h7=r*_Zdmil)bJ*4XJ+b;=Jk|ju& z2(A_0=rMBv)(#FqI@OwtwE}IFMmVk&{@8ri0<0YZm1GIhC1O$iP5%4dF;!1LbcREa zPPG<)vD$2$(7H9+>ff5%1cjSlTd?Z7L4iuL1nCm7ZdIM2#e;RLwrw`hAxNiMFJP^} zdX#2^*ILvM4!w8Cg4@3DAE+ctkS-B>tlB-eZBnfT`Gvh5f^@2d87`uY(#%=+yS;)x zdn{dWSFfWubCxApf^>;EXLH-&syBO7jh^c{1nE@k_(40^FFiD=0ov-)1NILNSiiCA zgWEd?D#;S0OT?qM9~#_!Pp#@_FFC{^NT*sX4eP;Q$>o|YIXpP)huYO2wrL-zBukJk z5q~v0D%ktV$E&K^v~md2sn(LU6=vhRMqgqL_x%yQgWo@ht6n;Gk3c0^f^>-(-S_z5 z(r4CIb^YJY4naEA;+)}D7UBzYX`27%aSZXx7LxR7iw5Z;t{`cXC!JyxpSMR>>3l2d#)#8Z2dSJ$ejiz;n1=B_! zQoa9~MS2ruNtPg8BHmj)B6whz+SS`u&UXmXsn#Qy$7zG39{i6lM+L3>|6aA?lAC;$ zWC_wGV%>l%gAp(PP}QQ<5QiY0YF*Q#o7p&cdP~?idFL@f(_dy(O>A?juaYc5xOfLXXRFRuBhTHt&%K3dMok5iMv;W2$kSmXxX>t&Wnhb>H}EQZ-sPQc0Ge4cre9yn~PY)xH{c z&>^ICJ?T9l*h>cduVpoQNu-i2K^y2-AlMV7Mjx9oX@j0pF2_;y z^X02KipDbTT1nF1mGKe8TNtT7>e#aSn#Xo_2-T8V0t9D+8^-NbjoBbpNtU2J%pV{) z>>R5kOV9@9a}Zns{QkU*=svDH}h#VW}Xw1IUZh<~uMTzO*e>Q}BCKp`D;jJrws$v9BC0T+t@a%)&O8@7YJ5*z( z?+~&I_r=QqL2qKyz1vj7n}}7CC1?Zw2MBsBTOPS<0X!Cm5O2cgtjvA|uLuOaqUXjv zzW`oQtdcB28zo{-cwXQ1+^Y(nmqUvwIrHgM4j-kC-f6qr$EmldEpp6nS6_L9o{c}}_+&Kj4R7;|UC>5iF z?{xdT0@1-(C0T+r;)x&_f&6v%2N;2L2#F5*ocURg(g?Q(QO+;_GnY}$SS4A4HcAB7 z3Z3r%xdLkkhajD5ajifbrP+XMg>Qz9T!6JhtdcB2x(ttI&-e|S&!1pc>$v5dlmjuQ8>OE zXU?)DOVCD%V1(X3>9{;&`%3US)spN0N=40Izq~$AQYBe}H2+u1G;Hp9VIG+Vhmb6Q z&#VLMfoui{W;4dGc{D%dg?(a`WC_|R5zLr;)%Eo}GA0f|I@RKxqYburF2}6Q+;#Ps zmEo$dEXfk2O9V4N`~AFA<%tvPI0WfbOL9oC!R*qRRUhV&U5ZtbB}gM51)>WwSo^*; zni;G}3CS*5FK0d2J99Z^$=bB&l^-_hXReT~9+YGW+9(lRE3_Q4ERVH=Ly%6jI3myn zpX6MQYlUkzH)OVt-b7iFB}kVDW)yF@v~J~|2Q6|4(y5kYGhu^S%hzYstVGr_Qc0E| zjXWm^W=2<@^CL5(4k1}f8=+Ybj;!#!kbQmqxUcfazD69oQ%RPfjS|6G;L4|WV20Nr zNT*tymHA7YArO++24t0YU1E)mRBZ#wO>{9TK_vo%5bTclGh$&$kcv*E2r zF3uwx?(74|5~NEz2bgg`W8Sa%%U0d#5RwfqNcO#RX&=CUcWK6b0M70NCAdF;Hn8rg zW*p$^_}E)3u(M%FUVlrqIL^&h`(T zKgg@uqn=$aJakmZYroDM`+q4i@xmJuf|JkPuKL=jxg#O11h2Oew_jSHM5w>T>r_i@ zgJP)$Z>q^sg(}Gsi9HZCo*N&GzG27eiYsbIN=T`~or|-q9v4kH3dAd|#|L-J-Kn}s zttOF5vIK3Eh>s?W4W5WwRnKe_I0WfbYs;Uvn2m$_Plb)=28{_S7VcI3&Qk*-m1GIh zC1S%4R|GXrY*}5q=XDN2I@S90nVZbUGc{j?jl-Y3ENH(?%j&U%W=AT?5~NGSZg&q4 zdJf;S`ozN)It1xd>+Bz=n~fXhzX2Ol8xIc-JAL=+s^<0x!krp4h^PP>{i|X^LHYZWC_wGqA>fMpw9<&tN*@agF}!` zwQ4*#*=&rOxf5(0b=KKIxO21W_Zs{ZsU%B~E)f^ZJS}KaYscz64$H+#@H*8x>FjZ4 zs!l!P;8-PD zf^>=4X5;?Bty6xl`f20g4naEAI$(5fvvJ4nr^80L&;G$bXZ~9C{k+bxO0op$5^?5p zdj~7u*;w_fcZ5TbPPLYwbBNj4ukQ%h81qewU}@#oRrhV^5vwFikS-BD@7pyPedUI# zmoGflAxNiMt$)s&jeV{d2OFOZY7p!+bA8p4p(n&D$r7YX#0&Me5B_ZYan-vYp5zdu zQ!TGfW3%zg>({`>clEXnyc<5Py5QJTW0hnH(j}tF)SvwEhp(ynt;^XCK|0lX<+fiu z&MO}sc_VDx7JlMi*7dcj6DOV@t0YU1E)nCFzUDu==hIbn@4LVuNT*s0d;MfK{(OWs z-iu%LJDmDXRhN%0h*gp$NSBD)FMQfR>h3qHwt0J)Ly%6jh90%pY^;6sX4t3`Rr^cF ztghO>6O66RRXkkS-Ao zKib9L|GXQkrk*n1AxNiM&jl|Rc+WSVG8;D9j{3&ywdlI4=7X+^Rgxu0mxzhy-{x(% z-(^+3k3qadev8+s)~A!EnT>Z=(#GuQdT-^0ld9HVG9gw;mLOds&Z{}MaQyXStM32R zB}k`QxGu6DWukb)-lwHRS&}7EI+wdOx;{Li?;dHXlqjZJD53qoT=TG9$L|*;H7`q8 z5+!(DZr!kB{Lg}5+oQTQ>Mme!SAy56)&)l`HXG$9Dr#D5+XZ~0 zRFWk~m!H~b%zs-g;8UvvuT!lDd;MfK$|FN`Vg1Kiab!?QmLOdoeWGJ0-QS9%j}p92 zwJ;Kyjq(T=t(yI9t7L>LOR@y%@+ca;`0IHU$tYST_`9i=U#D@zdtM%?qj8tqS;3K7 zC0T-Wc{Yeg+_a&Bvw;%4PPN+noHrY#8Ry0N+s7lqt1CF;s3c2}F3)Q5Kc`n$a8^@- z*Qpj}II~fnIpcZX?Ve9&&axy+kS@>8aZtZUKAD}%1b;Wx!c1-dFRuXNb&pNUCo6!m zBukJk5z#*T$1M&Tp5ItnWt0j2ZmRWC?|%0G@=7LdylzsSD;bq!3DV`&QvB%E{qtNc zDZ%Sh3o9qHQC^Y7`AwJSlNDK6k|ju&SAFq-QB(5Cs;^A&cT+8_0PX+fm1R8SirezZ z%CaoU5~Rzk*LctStMbX}wM_7LQ>~NF9%uhAuaM){-hDjJ6|zdQ1nKfBJihnlIL}qM z61+~eup&1b<&}PX!S2O;veGY0vIOa}HxW9SW8*KNKwpLj)Og1?(;o%Q2%`+wQI2FpV#vAAXSnjNSD3T_@h^U%+pI%g4e0m=09&S8)Z*8e&LSa z^7MpNk|ju&z3up!`#0t3Z7ad+R12QB*(iJTaf3RW@`*=ZmShRi<)}e?@#KH5TA*7dh(x*WnCKDqjQ;FX0t0YU%2A&TPh{?o=$yDNratP_|o;;f%5R-`! zlc_{Z##c#}pbb3dAP|#@5tFIJ$lwt2)Os>r`4*Fj5tFIJ=;Ny-OV9?!D-eju#E8jM zVuW)D8GU>icR?T~6C);5iBZ&%WC_~9xC;U?nHVvdN{rNj{+5iQzKr=G5R-`!lc~gP z5U3_ppq;>8<@{QASM$dCc_ngL&)sx%UXgqUg!`bCc{-mppq;>8(5cs zKujh^Ool5Nhmcib4}2~?6LXanmj5Qxddh{eZLEHVDLIV#H+fScL~F$r7}Ibvp>eWFo|5@>uCRgsj4S@jpNyCKDkhlZQ7E zs3c3!2K)~Yh{;5V$>ia&ID~i;zW6>M5R-`zlgYy?3RIFMXajx}2*hL}#ANdDyc|Nj zB42zs5Qxb{h{@#P-32Pi60`w-5Cmc}5n?iVc#sYu-kmSLC98XdCLms2XB2b_Z3GC1|5`&l$NxOs0apLg)35gE+68(e?MmZ6aso)c(k}N?RrDu?lRK#Q| z_|z&PQBGf?xUj)!En+hBIWnjuOVCDXEMY_#F`4-seUy-BEyqNU{i-~|`H0EPPe!=1 zBumgniC|VZz>!)dS%P$FY-fZXF_{IN4U~}Rxi8rP z*g#AsKul%7G`SurSb|OKum^N8Lj}zk}N^GL?9*;ASP3Vn2bY^PPHWKgtlUK2{9RF zmjab!3DTvt4>MSZ$uNWE5RzTu8qP{vUXcZe$uLXC6KK|0mK z3ebM3ys``slVP@xE6cJZOOP%R%qSuz!;GRskWRHEn~An!))Fz9Dz1=Kk|ju&*3`_5 zA|_MCRk#w8wWJ4Nr7f@Y1H@#il9hg0k|k)PL@>jPm`qjTO_T}#ZmI>(!v0_OSOUak zsuGW-EXfk2O9V63h{;qXUQwCg@1|OkB`i zhI^9jFL{swVlq|qAXSnjXrttFa_0bIGF9|am5{8yC%YD4gS!(Dlc}O7tdcB28ztYF zJ0K8~siL>7gzQdW48Yp3?9m5^$y6mCeOZzvXrn}MCkJ9ORfx$j22dt=ooXS1VE^ZS zmeOt!#ALWzgprA|BukJk5$*0PKHF>QgkWs3yLZT_NyVD2=XhSj={|Sk@_O_wrR(0a zZ}+afVKknP8#jHs>_`v;mmJ{@=+ix<*1c_~`e#nw-mVY3ahkvMfuD*b?tS`l5HsHB zS1f>tzxTW~&E}id&u3rn-+b-$cHMu}6#tCxE)GdN(Qi12Pby{=+kr$YrnbDu6v&`*>BZti4nh_H3Y<}fl;vqh$C-o=RGiB$B3mm`0dO5VYk+_>rPLO z@n`+}wGmG>7zAR$4__7QfmpmxOK0r&a`g%X^V#%+cjFiM~#h``R~{0CA&`Q6pjXQ*vnH2AN(}gw5I%L zx!3EA()D(4uJq8VM(ovX35fO6x`fAp*wEnc!V`~7F`~!RYrGRim9B9odFPBc^Sg^d zwA|1=+?zITUDo-ZnbV9o?~0lpdWT)3w|H}(zTAi>9{34+)zC`{NiPY}OFZ5|^pfa5 z_-$UJmqh&Sq?bh2OA1LZ3D5faQ`15(iCBIT=p_-$PlENaUQ$SUNr+zJC%q(M8}XWL z#x^3sHnUz*NP0<#USeA4B@yof3EmgphoqN)Kriu^qd$>g|FT}`pUg9Oaq=;T(TIeMqpFI+2<&e)F3A8c@^b#-W zB}McS(?Tx^`FxY$^S%_%HwoNH5a=ad(o2^8J9C<8p_halLr8E;K`$`^y#)LE`gNPy zxeuP&4s~q2Do~5#)fwndye7&1L>r~iXZHCcylC2lVC@O#EPLyW{?Q%h&-P~ZdZWL%kZ2-G}GYTg-AKdE^UHMeWlbuz|ur{+eW=0*Ir zX`$xc-rM)IYt)=ik`bkm0W~)QH4jHMIKZ?}9}hLRYt-DAzUy1fi%HGHsnASn?(eZ? zgxuT>rKwCm$j?p%Ah5EG_#%F86%?(Xca!8Ve_TvKKs(J=@wM z=ZCD#No@(=2sOK1@RKAo7_2{tblVy1jHNReG z`;1vz?)KG_FPz(15B7sxuHHdY!o5JWe{`{(C?vr>|9Tcc?^7<<=JJW*WYpvS_;KeB zDxs$p@Q$tBP7DXVa#b*I=KT(#T6+JnXM4rz;Z&4r(_V3?5+(H11#&DkjtP%LsaAD( z$strr+c1~w@z{OgQ6SFVG9%Oz1KM}x&Z4dE=y^xzp&r|AJ2q5_68aP%E}Ha`nhPg8 zglb8T!3gx!v}eP{sQJmq46{=wydSK!61rzUm#ZJFw6@xzUct`vkYEqdUH5#dc+WAu zz{Z$G?}RO2W6RJQPEXX{r~A-zxz<5!cd+T}9~M=jgpL@w+{-_FV5Qo7%wmU7E!~HX zbC8FwHDdGl83nOnd)-+l?1C@qIEMZ0`>YF(#vSak$I%6q$nO^2ec=Q9tOz^e4(@Qm z@6MR0S~@=Fa`*4|ao8Gdb@#KAI;%v9t^3e9rV6o43DpuBYo9@FUbUK6Hf*nVP48wX zEse3{pN;nzG5pKhZ8S@s+DQ6wB)t;j)xp1BV8s7MF0=C;B+x@5d7>hD&Oub-&hZ&s z@xupp0)YftHj>k45oZVXE6zl@+@|$+btbWEjgRearG%XAi)8cx@%!?jg%fcH8_xg8 zA#_%gF(1Ucb*?MygF9Gvmlr*iC?T@}h})C-V~<-ua0u0sxdg;xNB&tj8}-PIde`3Z zz-(^obglfsTWY{?R?rW_c4Ub*osYD6Po;Hhe zHqGVOpICGBFY8ZiD~!1uyG#rHE7Ua+dP(~yy)G!#9zDi6t0g7m^g4R`jQ(@I{-}A| zzbrd2f@E>y=LbYTq0b>7qKlBcQ zjnA9SEAY8s%{fNN8y!ME7qrdwBc8#vYrL~j^J`yt*;!dCA#Zm8fpOR4%!zT=AyiA( zrFgGF^VN1gzC6EWwO^7#?Yv{cFLhc8MFF#u4wL?A5n{sH#u`ubo&U+@LbwN~hm})lm{NbTco)3GM z0cozB*w5JN9Dj4UiaFiB0A2woG!<9wxUm3r!)ji`ET)S_r$Bq|n zDB0L|Oi_GGU%W=oU1fa!V$G1Hs@wbeW#aeI?>8It(`430FIn=%;Acp@`oXrIcyTso z&`Y78=FT6ec_FEJL1IXeM29ltE^2NBYF?mk%->~1g`PF9>8HsZ#B+|Cmu&1irXaDG zNTMp?diZN>D~`pv9BS?*HSa8O5&E)bgTAcvWB9d*!yTT+;aEfZvW&eUCRg@x`TwL9 zaLKo%YI9BNSLtu57W!3z_27LmpVNFb_?)3i zl#mqwh*R&MU*vezr22V>P%T+Mfavo2nqoIR=U;Dp-%ek$hjaC(gm`2i5P|HRMj+Mi zM>Nu60E|Xz33IvA#|-Oy0ov;2&JPw;qJ%y-x!l-3e_C7BKcq&eglcICu@~pA|5#i7 z_}k!6B}%xy+UH|FE_O#-&8ZnXglf4pUy^vK->-i=REZMm8^Ztic&`HEB^7sdVYIf~ zJ`z>)wS-&aaL*xHs}dz7K8O2pSiP4z4@T?mw5+)v?8Qpb1Jwo=a$Z|fPm!tP+#yH0aF zNF~&EE_YTq(#FK5dwgHi-%>3%mhnfs?F(n4t*YwIEvQ5Zw;rFjTUh9dwi>qLKt|@$ z*rcyo62C;v5erYFoQ&&PB#m)CiFjrrEc-TTR~Up+O*~?@Qz|8NmdNFnUV5w5{M{uV z6}42VCEf%|HT2v@7Abo6!oZ0EDB;dHXM8`-e9o6f-tG{prEe3+$dGel_;U5&E-y7^pf?Gim8tll~64=I=JJ;iweh}t?qkd zd_g5jxb--<|BhZ`v{iW84xSRKC6RR016i3g-tMVHV(*!lWxJ~;7Xp;(fZSP5sg%$) z5$^fC53S}6FS@O$rBW@8=;U&H+}zJvw`{5>(Ru)vEgk&~gc5|TZ`{pj25!9q>6?%50O@2rGssZWI{&b%YMn^3BM9;sJQi4u}ygAK{Vbyh;P zBtr*6BB}P(4z?oSA);-i(a&6N`bnjHRMXYNow%qHYCD&MA85UVexd%BYPlJ#Nx{Q~ zpZ+@`=s5a-&MHyDt;g+m9qA20TRr`U?+~g*PmCTJ;~L0EZ6%heM2Jvr=WpUojuOXKjlT(s)F@HWgJ zpDg^wiO?${nJw6mo>-K=6iQFbWO${wFVnIsAx{Bp&_`oi!DrLHTU0GAVJ=4>jco;= zjZrm=a=>SEvePnx!$z&o!>}>hYS)23ID~4sHUD^Pw$D?E5|a6Y4H-*{G8%+3t~e#k zWLA4@?A)TvQK8IgncWF8bLx!a5HgFx2E97A6}&v1IYZUb z5+WwE{jt_o%72x`YKc{x90Q%*{|RiYHrgZ#Akqw+mr0;cH5412-T9TEQq7F zW_X<(y%ORNf{^uYQC6&xtbH>(Ys5FuxTr&j2LKz4xw5SoiPZK{EiED5wg8WdZ3Pd^ zqRNcW!RvB%1&J318}#Zpw!_PF2-Ok~8AOX$Zwjk0wtv@Wp_5TmLNfdy#PbTpkBY?e za!QCu>Q?Vgy&{JYPY*WeIkK%zS@e>6Ud|3GEg?=jVJ8aPY83Y5s6>BPA``Ij{XLh3 zP0&`~eQ}pVsFquE*#Y6HL$pZNB?%6-9z!oBk|~+Iyq5;qLy6=i6)>P^flR5 z@I4DksFs!xV>^6JwiSF&PbEr7TnjeV9C@Vmt2-Z9Yttc2{#03k7% zP@*c4#Ah;l?j(Mt*$jt}C>3nvki}qIF}AO@RV^(c&K1F{V_U(?^HidQL<(U;B9IQD zT5iqL{XS2(dCgOa5)$8q4T%nh66=d3I+)qfC=p1F+&P3qBVmKyDccI(szwK$y_H(R zT#oz4*j8_2C!I?4cO^#7dTfn_JA`UU#2bX<4V)cYN=T*wghZV~i5o`}b$06HM7E1s zb|oa@4IA`l*;epxHBRm9T-6fdotf}w*;epxnI$gorqJJ&+zV{bpXJyN|JET?i~ekq zD+Dp)fPITgFt$H>#X9qJQ;8C?LkxuE4MK_hN0LKu>g42DGzaMrl1YIL<^|bS%$8|w zRZB~V6&XB7wiP@{+ryb;sv;%a{NUQF9$&UQ+UknCS2%=fxiw$#TFqr+&{jRhf9$D5 z30|`ev7-m|kbG3A?IXDt%k)8!`2>x!W1v)(=00PslVHdpVsYD6g^<-m7G08#l`6#!Kod1ZlgqDM}6C=n$ zhAL44W3c@a&j{E^y)4N=7L`yf-4kH5K{3fehAL4)&YQqSdMX7uNQY1@IjsWXGI+pz zKECPtxU&l4Au>OmdJ# zl_=rX1FMW;l7kGDP%WMyV9$q#iJHrK9Ii{s60G6u8acMi{&uY4ib)RADU}jfsYQI| zxeLQ`kXCc}o&_zHYRS$T5cDyN?X(-C~l15pI|gk ztC%-YOmdK1A(wwkwcs<@|G5Lka*)L&2N|kF37$-033;Z)IUnT^ss-QB2%d<6Uwgn* zuL94BQMEA1K^9e_1jj-? z9~=QK2Wcnukb`sx)k6Hz2%gQtmrwqF!fS@sJ!?@*-IM6-Hk18{An2X)4#Hb4s6<;= zOKUku>m~5=9744a>$T?tJ`ijml3Gl1kc_03B}%yUKn^lYa*z(8T5|djHsp+AQ6-3l zTl?@Nn%cHlcrnRAE>npTx);xKkRE4F_-u^tmg}Kf$PU;T1J4YlqL0Sbh0n$;Kv|-M zyRVNv8lMmNY!0DXvL6ho3(OA6wwr%StvcRTQ$&e|s0R=UI3a*%ch;Yso|huuNu^psHBmV>ljf*fQgB~;5j zKZtB!G08zLQ;8C8J&=P8lN_W&sMZy?Ot-dTX)Ont5}j2dgzc8)tX3kVRGqa{N=OL{ zmV>mK+rCjbA*ou@ZXkFzkIq39m>QjJ{-8Jw9uO*(3_Pu61ggjlIyUSbl z(CbcnJAuM=0%It$*Bv&bCl;hHdD0WPC%Ifgr?)esSe7UuPXTPuN8?z+eWMN`r=qn^ zmV>mm;=WOp=IQJf*3GYPmI+6Fhp(M^}KJoV0-r{mPoqP0~mEurNg zt*y8VR3%D?7X};R-8qD6iPr~0d}rs}wi4n~gAmWlyil&TnO_snEAxg8plD%d~{(%OnAtCUbJEurNgt*yAzR3%DC zY!NoFd)3;CyIGY`Ew|9Vab#`_W-%)EO?B9I!na|nq>!Unxl z_ABm~)!M3-me6vL)>g6Z#^d*szeDnSqvMPvXWr z`I1JnGjBG+>6$dMUC^>CArWubpg+sD;vQQiR7*=}IY?_O?y*&g5|XWf4LODF5UM4o zvqAi}^`y7+77ryPhXevS$TV+Y?~Y-=;=VY^A!ObgB{>#74d@V(Nr4UIAT7tjvx-_< z)zT7L4$?AM+|8;IB_x{#8}v>&Ucp;+2-V_sl2HU9IY{ROs1lN!1d(R2_+A{zNAdh% zny<^el?xd~%aZZ@pq5<;+Dme5ut5)){ffJCl~64$p=J9lUpotLqEU$wXhS)1$n(K$ zD`XTMLbW8fjZ*zHeullJAlG4Ss1hY)9{`B=I-eB(c;Oar?-Ob{@7dNjXuo~%*yzD& zW4w(W`PS_A?>CP(Pu}9i!BNgzn(>atD1BSx^-~WvVp&_h!EEo`&VD>{i??XlSiV!X z{GL>OpXttPj`e6`ay`E3c45CC{2@1O@fP2GCf__3&GZ>qd*>cK{oN;P`7QNbSLws>dWd#&?kJbi=R>K?Zk(SGrbShu6* zK~nRWZ;NDY`DGBX5s8h+Y91vu=NFEOB=|iadEak@nukfvL7?VQQgeO>Dl%G?*g5|E zHaB_`7y41H)mPZ{mH)H?v9``yf5pB7gVU!z0B%Oef-m!e{IBhr(X+V;pZ#7hx?2Tp4x6- z=TsY3GDdSHb6&8s)nm%cu^?XR`GfaIkFmk(s-}FmooOLQ;ha8uY4mzM1`PI9&x?s)O0`LdT2H%n=_XEVLX$SdTE5`;s`Y-0Y;7p6H4FBA&`Ifxi zuT8X4J%7eFApYuG@Mr8kHkiBTBpPLa`FA0-g5@|kLX0-^tBush<2=tOL=_Qe@8MtpLT{A>I z=G|umdI<>hk}&Bde79Yc^pZ$cWYOu(zcvEB1O$3XnDi39+s+93p0eJJ&JT8uSSs`q z5a=ag(o6VmJ0qCM65k*~FEIkW1O$3Xl=PBFb6(=BMYo;Y!wB>e5a=aQ(n~_|gd_2U zBlHp@_&i!KiIQHzciUO1*a8wY;8SZv>8V98iIQFtN)(6t!i{Do2ED`x^b*)WFNu;~ z5=xAWyY7u(ZsLz|HyD9l66SIjuKK0$?a5<RC*w*aBLj%Z z?Y{I5={q)PdtP&AZ>8?il#v0%?>lenpVM<}@bZ}roV~6xu0%32fEafEuKo~=B^Br9 zoPEJEuJE4w?1`m&zIfzr{`!t%gKbavCsc_NGOobJ@~f}*pW9_*u=3R|&Tpxfj3pq> z|D=^4bQ&8x<9+PBqfy4L%xrM{7kU5k{l^BM^j;h4Zz&;T7i?V7e5(I`&5^+ubz3>V zrCKsxftYu6d;e>Ui8ZG^8LAe&uVj3TTw-Hzp#NUQ*kHTe9%rw%R%EYMLdHk*-M0Uo z>DT^sL~!UfHJsm4Eg2I*j2_>~KNaI{gMFs+DYBB-Q?zvq4qc-AX`THojmHMFE2cOS z8MU1=ExFtm@897c``L)#;Pyp_kdZoUK47}lum9$2QK~)zy83rwY(JoJH|MwXq>W2- zZ`94-PzO)#x1F5dQUVzPs~_`Uc(2+sbN$7yjtH*&;e3Zst-re6Y^8edtL;G4di*GV zUcIrwLw~+iREZLLZVJBI1Ks@lK`a}$A2S%Kbx+D}Z^7jK$Bg9RZK3t%`Qz>y5wsq2 znj=v{Y?J8O)4y%=n4o2+A~PmtgTJL(a&`^GHg4PH^6!EGqyIm<_^Y zHgJ4dSwHx)0wA&PtT34koY;b_AADH>fWT}JCbNMPhmrMzFDn2Lm<_^YHgKX`vVQPo z1porGL6pn}PSjD>55BAbKwvhAlG(tC(8~IO>%=IT4M1R|j*^kudFQgMAGl650xJLz z7)7IG6!m1C;LG~KmlXgAjBrsh!a2DcSwDEP0>JZu5iUwbI7gy{tRFyNgo~09&LLE* z*?{R*4~%diFv3O225*TA5jwO8GvyE_3GQv58YT;S2QelJx zfe|iBM!14Xl+diKjc`#i!ttDFYCV*)^9{lFf3CT0go~09&XFh~wn_Bt86_he&!v`s zOSL334gw=wl#Fmil_+suFvDtI9^s;7gj=SBYH9A?Mz|;$;R-5ILhPY+F~UX32R}coqJH-@8*cUbEh|N2nY0?Y1j9KJD{yP^sf~> z4B~_O%N^fY*Fmng{m9tw&D-v}%M8a4S3=h-$Y#vnDPXDYfAwC6P_5fn-;Yq zyw~}ezs<(#BZo#RQNmr9Z2NCxtH;cz#yNy)opu_$dbGlpuUo+di;LTAr7Hh_w~EkY_O%V%X?#Ov+?iqABQSY0(aBrm{?k6v>4sW>T$t2 z?>K~No!ED#*(lw?A3N4D8>iGSgep-&=iOZHz)SOHV@UV!i%O_g{eH8|M(O$3QeCpK z_}i%kl_(+hyj*Vc{&{PwbDI`CB~(jngQ$1N4pxtgu36xzLwgQNr$r zJ+(u-e_v3E5@HW_aL>&K?zyLgYKd(S=vP(`^ee6n(^7d#$S45?}l&pxW%H5 zh=qp#JN8z){`j7{VJ-(hDoXt*jTFe5f!>m}NGWR2bJg_dK&)PSOl;*yl#q1^#;a>S z`!!;}TG?%~L#P(UF{^oLgqt{gN4pOXyk5D8q3fqm#lX)5wG^WhedVKR$U%D z!;vTh$&4qlFKdbl#omui1V+l;Z-4z zGxOQNiO@c*ie1j_v2JtQ~7@RZB~Vne&vEKA*ui zt6Rh>QKDD=L2Ij0PrR}Fem>i3;a#TYkp67ueH_4e~*h*qQvTU zKU!Nov%`(BF@5xMuNE?KD<5d>d~rxJahZ7g2`}&OcQ|BZ(EEdH9f=ZdynXIrw^&;> zU$N04RI7f!U41@Lmt1-^O7+Lor%P?sZ~Is!N-S-8pb^)6e=&&7r>?WM`lP`D4xw6- zsV32Fi?!95*E_{3QNqn4_nF!u;B0XG(KR_6_`3l5q8c8P)!e96fAYG3G$a z@J@btjU!P)y*`{bnBF~LZ+~^@T8B`rdk0=;HcD%sCtfd@jhFUZ9H~SJ_4;zTtG@1M zHeT=jkVB|em+sTe#s?3+j+NyJGmkVIPwjDaq!J~>{{YeA(v!@_)NrIjsFq~)LHx3) zm)SV+*;bKCln`$T#AWqPxBIc^)*T%}wXj0AdX!ekBWm>vI$-o!-uODMoy!s>)Q7_! z`UlRmdfZZfH-}KI0|(5uUn+S;!Hj;Tdp_X%f=ZMSdmhe5bt>7ozU6hE5~?Mo1u?2` zAG7hlQGa_XQ9{}c1iT5W2fPVi3DuHT2O(J*Cp#@!8Ac#|&d%^Ae7xmm)pS4cCLD

iN)9746Ugyv0H zWCGrVuM#D&4z{ri-UMvGo3OTmH{lSf<<=bDgtZmCi9jVv$XE#*@FvpCs3*BiXOD)K z5c_?45Azdmf^qe7n@BD-vy%hfgtZmC35SrZuCFCDZ^BkG@FpCI5|z_?SzE!IKt141 zSX;rH2=up9%dI)Q2^+8AO#~`Y0^Wp;CGaL-Lsl}(n53&0XD5%WK0v^m@DgvrSBb2H zd|BIpfHz@n1#coyLbYVQ0s`KI&Cc*90+lEst3eR(CTwOs@Fr|_hBpzY zLJJueXOCc?yF@go!udNR)8%obV>1#G44TwyLEiG;hK@dUz9o zN|gBV&kfeE;7y<&@FuLS;7vG$YPmIsH(_lBZz52M67RPA(fSp<3D|%)5hmUQcLG`l zi?hG%*vjN<;Y~z|H{nQ>aPzhBCakUCO*n*V!DomPZvv%)H&JSCIXcxA-g|8NL0-^B_t6x&Rx;gEHZWoMad2!N1_B) z8Ag;=8Q3psZH4`!4xw6@yR7D=6#%ki7Oh2=jPqbwq6F3w_J8<0s0Vhj#(V~`i`5}i z3$tC6cuOGQM_E)2eiY}yvP222CG7vDz0O$gnhmUXLyd)FC2Lw--AjBwv^90i=NxNl zN1_DQ+D4bx?Pg>0fbWa?TdJjb3Y;H&;7qFrd;?DXX zAIEIK$MIF7gk%Ijz>hK;1D}%~S@&M+5K@oulV@%+8~7?aZ0y$clKA>gTf9{-KNy|$<8+hYoA8d7 z)Ct5*w_Oysy>`5R&gZk}*QRaa5Na=%d+XQ}t#$j?yTKt;OWF!HzU|)ATDRt5gCdnE zA@>QyFLj&QQ+rN_BOOAuB)bHn#W%GqAJuO|gGePxNM;K}*JXD_XCbElUhWxZC#h=5 z9t{w(lf&7Qs)X*P$mP0WN6J6gb9XED+{vC2XAi8F7XEq9*-=ksWzNhw^^iR*nVqt8 zU&&d`pK8|EAv80lt&SZ15xZGdruX3MoYqwWzNn3frJUFH*L8^*XE^@jI~_u`wD;t4 z`~9!C^^%2OJni%nB{Z{@%RTw%dGS0vAA7Z3<`Al-eHu}NQwGN;-?qiO`JK0&-mb(2 zo368`VEHYzqg?KzoA!$jI&6!#-Na5jX<-tcw0Nm^KfAu`nNuS-|MC3fL*r9nr^T~yf@j&7znrY45;Y#2Z1os5b0^sN<;}C=cfBoMoA_IYP%ZZk$|<2( zPon7ElywPggqOF9-?(AC|L@Swu}YNCJBv30E#A@k?)G==?+~gb>mb;8apxUugxjs& zp0P@l&>S1)!NOa%hV%aZCsIPSWIYEP)jvLEYo9+Jd(+wTuY~3bai(G3@zG{v;&%Aq zN{3J_*%b&I#a7!zdv+Nc{BrtE&UphR^dvzpcjaC+;|;yHcyHWta;#^G^u&;?A7NwT zF5AccnDPEsXY^y7+GZS{I8s9IQ!aP&*Z;M(=!j1|hfpn92gAnP9ly8r?tS01Vf5Ta zGDhN+&{oHLKMsG??nj@e>NtdI$<9pJ7(eqKyB{A{e-Wuf3HJ`})Z~!pN8FFnA(s_2(luMtbH; zd>q*Ld-D6y@6*Qno9CYqt3(OCPZ+P-zhL)c+KgiyLbb%Ff{kldJa6~o#*rOkl_;V2 z3HM|5f6RA&zQL{zp<3b_!p5l$Cq;~9ES&sXq!K0cK4I5O(}vNPxF1jbG{YfOOT0eV z5P#4)^P_}#dLa6Dy)As^xUs=ommch#43a&Fr8faMWUZ3f4Z# ztbVJe$30EBvKEt9*uHNF^_1opnJ^(#yxu)?fv$488_ZqaA zePeV?_buL<^DlD<)pAQ!)%f~wNarn{f93f2(@E3pJm)(rXGeOrQzBuoacz?~!yT^~ z?^iCqoEi5tdgc&XKRi)`AGfI5zRS*V2-T8^9&CKw`fH2a^?a-k_W`6)K<8ws#I->D zaM|@C^XI!Pv%LmoLbW8$2x3m_dn~Hftj`YI&rm+Yr-Ve?K>X%630LF!7=P@1=hUBS z=_$dj(ZLzmYoHP(B<=?r5_{$Djr8<@v#Uc(i|=Oqaq&KHp;VO@FK|l5Q`qS~5D?`Z z9>`|gaZ!;mvTYx-ogC$wtCqGpO4Ytz!D6qo^UnRq5VH5M|D4k!0(o| zwD%wa`RYXldumso>GYBeA$vd0y=q>OPt>YSS2zTIx2&ao8e_?+vkQD`ui5PO_6%X? zx%m{>tmdb)nw;B?7WVqd<4I=DaPB^UZZn?r2f@ZyJ6#;BM2VqCEjGF|GStrB>vP@i z#TPh)YDwfCrD{3*M!$FRoU25M_Z!bL8>Nxq-AzON*T;_c2ktQ3+0UR_cphy(15T{N z#(;50``@0n#p}Lhw6j}82|4c$B6mn_pZDWGPmXd3)zX$my#3NO-j&yH@kZP}j(4zp z*OZX+^{}y^@%3IhUMZnkxaV>Q<>Y-Vr|r2evG(CvbgTw^M%7B^&#^A?({+hTl+Zhy z%l&8QTR!(Q3<`QUJ0MgGs{w!OzKkQcJnHlLxaYynT=kVDO6Xn_>|DNYj?ZUs`0l$n zglf6xIhQ?sq0i_1fqnjVc8e&XduDREN6)J7&+9xgX!HF|4xw6d7M;DM>unxa8E<2i zp%NwZj4IycJ+@xJ-hTX$-m&fq(RU7LtK*%r3+o0WuG->#d0>C1b(LuSbKd9kxX%^i zP%8KaLFyamZ>g5{1@q5?)IWc*cR%|r`sDgn1o%|eOG^6_;oSwPcc&61w0?+Roz&2> zmV-WMP5-?7TdE})Ow?n;r!@jbgl}!sDprXSy2}Q>+Ar^0FPV7qrbr3Zl1waYJb1?< z>m?^1@}YB9R|%~8eMZkqC%td{ski@Qn~}j+KaX+<)q-zex%<-lso_m{sW+h#CG?cB z`GdargZ5k8^D6HgaBSytZ(KgaU)f@0Q2p5;N1}w}yixPk_rGX0zx}Zn9746U4UwrH z{)@Hl!%uwTw5}48!G?{FZ#A?#xZig>J9kjEv@hV?-OhUljJNx98aus23CVfG#yQ^} zU{BP{HTyY)YH6QFFZr``z9g_oNm{Q z^&$>ueY&*MsZYZT&Bo#x&oQc2mMDP;i_xVRSDb`np4?mh2)y%@M^3(kPBf zlt4tsY?R_YO}7jTMobv*-|^|M&W3WclWnV7*#VH+z+P&;$>!|6o*6PE|ADw znNThF4*oJ?M6mwGE#Bw{=0ti2_1?&vVi0w{u*M};kB+xYj#Q$A>~sS0z!jr|#|Lil zHcmUiAyf-F3#$in7C3iz{$;@nh{=4=sx`A2Wr-5VQ&{~Ct?gN|G4P=~9YVFFv>=ej36eaHFYV*Wy>a%iS*|E(gIv*Hi}rW+ zswp9@4ja)GH4pU@)9746U_gLn~dI>T=PA^eHW(nUiKQ=NT z^WzYzrG45mKS7fDaeBKFGW);=GC%3cGLW^QFY~T1D*zD4{MhJ&%uk>aC1h*|fy|GM zKFItyglfsW0z&2w?i@(x4_^tHOF$s=6C{}*hfpnnV&!%wV>_3T`EdxLFm>4nIA97{5YkO$c?iH+A=@Z z6Os7|^tW{1v$ncreyq16^W(Ix61oT4GCy_)k@;~5)zaQ$nIAvN{5ZWt35l1Yt&sWg zlgy7psFwC=%l!CB=Ev#nN=O_QHjw$TxF|9|+$o#JSbd3d`bt~o$4@dp&Yo>0Bn}H3 z$o%+8=Eosa%Pkc$KWQX2kcg=-kyKwItgwO1kC$YA0+lGC^|Q>6oz6t&$01Zp;`^|H z%#WP_MdpWlw$ogJuLLqQcD4^^MnNF+<0Y9NhfpoaQ-DC`$4+M=^TWO8X=cP%0vVe0 z>?;Ule!L{}!~N}LLbc@Uo*>dwrpWyGDp5ktkAlFvCJV{CCLKaf>HIh?!h zHw>QZNHRp4-+>KeehNwE$Ei8$RMyf~x6Ds5$^1C2n<3JC8*Cu+Q%EvD4uRh-YiaMX z%ug}N{5ZWNL!_BT*g)o|kYs)w0>4|<(mrjOpJI~vae8}(Nb{etA^REl#@;Y_Z>=wR zU|;giAdvZqlFUz_5+x-23Ids*D9QXdglb7n7z8puQIh#_c9JV0*+ENDdkVGC!8vM&`#MR7+dhGCyIG`QaTb-!&yLuGsy+`-Ncx znV&RM?GUOZ***~R=HWng2ytCfzMEJLL`micgzQM+s;?|jLhr0)exfAv;}EKa)j+xr z2sV)UiIU6@SAAuP60&Ck1TsHSlKF86)slT6AdvZqlFW~@vtJ3>uK@y?pD4-vID~4+ z`(;5O^JDu;X{lSQP7?AmK-Vf;31DT&F$^1B_lKq0tnGMVQSk007aR@yn zqHSoIA8TD?ew@}-LQi>E=Ev?JGC$58R4wg2midX3%#YJclt8S;`WvzXXe(rX?1@6= z$01Zp`?O_#;w1Cq^mZi>1G1iv%nxiJn_)JP&0tK%tn)01?5*{cwrob6WHT5kDwkIY z#DL5OvKg=;`;Z+%wcJw4{#_r@8v89|k$gmP>>Ak~U-k&Y1~NZ!lKF8YN@)GCrk>v2 z?g!o=;1H@MyUJk$Zz-_d>es!zh9{(LY{x!!UkN>%WAC}M^9J|5dapyMmh6s)4ZKUw z`Yzt3$CKXnbn?`=5_-nS-aH)f&BN>KwsHv7k~cTOhP>0sd1s~)^0p=r^2RLtMl_#V zdaLsGEKf^oZyt`4HxE0dQbJBBAQp}{{8`Q4IdZ5&sFt=mzAN)@V{2W!;m>JZCFFzx zY~URb_SE7X5DuYQZok4iAgq_*9S}}0Q37#ldkRWtevs$1CklB^hfpo;(>UkV@IrfP zADZ!;)7zDh6AGvY@;I?%$?Tb6#tpd}yJlt#nIR7*|_fk2)!URug?`YKUEPFjJusKzB$j}Es?b_mtdyNNjUh!Js;uVrqc z+<%miGgz=8XRsVXwcK9P?!MyTy_Qah#}>PL^cuqv3qr5qbpJViuLjqA4>PZ~`>Z;| zS4Huh-?-`9&PRe6xa0_r{wuZa#g{MWv*K+-| zF5Ynm}}&n<2Bx|<}JmYBf&dq-}?3Trj1*d+1tOVb>0;^KIk! zj;aytE!InlNiPX`x|>>jyAIx#t(SyJF9~`6m|Ey1_6-eQa}7*Q5+tpc z@cZZNB}LBL)Z%x}SsGrmbSw=Cmd<(!zfI0wQsn$fExxm#HRd&XNyHkHKrac)U+88p zv9C^3i(kIrX+U11msqQkD1A2^y@X$#W-lr7EF!h|-h7^91t4NeapV{~}6~5IN zuRY%lt<53<%g?;8+{|CrKyX2*QP_vkUsc|MfjSA$7^*XTLldiaky4xw7o-$3kt?}y$&xaXfYn^#2du=4V2eAo2oX4eN#Z)sm>r)`cH znAO&<@yB*c9_Mm=f6f}B?}k!aZ4nSv9j2O%J%4z}lP4#VXCmUvMjPyr_@39C zbG?0Gpc1yBrxJcG7@oyE7AsMIDC6x)hEmH zAZmWS&SMWG!B*z?GI{;_&OIXj5(&0AJmK;71<4p+kaP&0IoShAa|}jS|Ni;>N@d)n z`gu#zxeGSx9W*7}3-xIK=wc5o>eD)(zace#vyybU zr&**cgIuo7%lL;>u;%+t~heJ#Vbw^c|SJo z6?-aCf+HSn@XqFPuhcjuJPxH=)!`+FP%WJwbGaUm-4`AO;_NLmykQtu`CG|M=JT$x zPsywe8+Y`)BlJ*@ZMPlksRX^QOz64`--bH=tY(e5C|#DYqc&^2l<_wo-PSgH0Nv)Cb23(t$$;8TX@{4eYZb?1($K!wJ7Tt8mrg z>Vj>>(KVO5f4`5z)@ZA{pPjT!B}#B@!j}HOh|Wr=me8m6Jd_L97*M18WCcE3mxmA@W4|@@#^r9J82Typ31jPRa0cE=XTjt6d&2XG|hE1y?J*F-CrQmSt8moZ2-LhF@g4f)<^$5x=ISY_d1N&& z*}(VQCH4|YR3-DA^J~*d%{xn6gublVpf4-W4SFKtaL=Z3IM$H9EMsr#YO$NFM)DhmLczV^{+5J~^e$|%qO1-u!QV|N zl-T^T+A43&40;!KI>B0;C!DxAV~pDB?8UBzB}~}gU~nJ3ziE_b5v(P*&P&c^4u`(> zN(rYf+TDk{@3dxjOzyp3N+ACITbscUUR%`j)nV|JK zyj5_6y`L{_q29`#{w&s_bvO`>4kmh!VePeZ(jyK_n2^W;DNR}Hy}8y`2`j=(uokTW zg6LJMijKm6tGmXUbF!^?HiYdn1)_kp1PVvCSCA8vs z%L+@yVpY87@KyusO}5^O30mbu8lSv1Nprqu|K9?W+-M-G>R9 zO@Qchx}TQdrk+zRg0*Na0-|!RNzQZlKJuNLuOmwNa-?@=!k*W@S$Mbi5Ujg*e0lL3 zsIA0rKCEt#XqS0J-7^ylX`JKOPn z{4=ng&fd}`Owf7&h)0%`G#O#tKZpDo=G>B}!R0p$h2A_=Mtu`&;lW}F6Xdf%c^v$H ztoIl` zt=b*FJIoR$?0oEzcc(MCN z{XQyYeAgmaOID8LE0B2>)~~P%B{MIqN?EI%Oz;{Y;sE{%o0a188q`&Msd4*|&&%OA z426!}^pb^HVi7mJXDE*rcYWk#f_0ytzbJtT^08TSDy(eJt!Gm4R{yQY9p>2<6LJTr zl%{xMEl*qm6Rah-i3%ZpT#S9bh^=xKdEkXKwh7xx*59NAWApRTZDanZ61(4)8GT&B z1gDMjkTDOG84KoxUoyd3wg+o)WV!d}xn%#LcdI9`gb6zzQ)e_ZufSGc{Owu12ywEqm3O*7SMh-&$$r6=OH(cjnjL7<+u2U`3C-*oOLA@x_z^qPfC9^z!7HjbvVoe6#eE9~&$ITKZXl#cxWMy7f z=&@4IBMTnS=~}+@QL%Mu@+h+3(IUw6hcsxk?AMHWFbJ*0t|quQz+W|Ev+*5WtB%~^=Sk#Dd! zB2!qx1g%UUjoQ6m*KhFSL9;D_wb=h@#TrsRc}un1bELK-2g<;yoHUJcGI zYw;W6`zW(jZ6&ijmM}ppg-9bu?K{<0Hy-=kB3R4LIj!$HEMbCHgpmfV4r&aa*h<=X zS{=M4qLEf0dF9R`Xf+aPV0NmulG!TfmbLf|v0E0AbMg&-x1y`V5+-Pk9BI&6xJ9s* zo%1z8q*JK(9)~4Nklz4l(5kbcbz{9-SnMXzru>H1%C^T6TBp7xCKdBpwUx|onV^;Q zTVlL0pH*AQ{FdLH3G&JyALL`P2-YGW3y6#ByM>>|y3ZZ+4q1_BOo%U7Mj0|Aw)_Sf zw<-3K2wd_Z+>&$hv9J%)BFHO)G~gFhAB*@2Ik&9EZ-^1u?za=9Udc?7B}|BCOXi$1 zU&IQ_11}`V_)2E0Ot6;xmYhr6Nhmb`>r82VVXMadk5~~YOmM7;<&QFKAM#B_`3

zT7OhpbF8Y>%GrRuOL{`ESXyS?BN0#JskVHyuzEZ`6>EKn!j%$~*i@FVb?tm$2AmdnE&m^p zo?AQawds=CkGzKUl2yq|J(lou?R=m-64J|q3D%MxM z&>e3DAEfnGOt1%AeUO@SncwnTu@=Pv;H@y9^~Aa|zhwy%c1-H=zDK+U_&%m&@-2e3 z?6{?sK{W2^pT2Wg!UV^_YFiQ(>%s>q-$&d&a*twqyTWgHbH@mLkh-5B@F+%^KpU*I zwA$KICv=5%;e+(}S**n|0oogc10SUBa*#A+mdAwbgpfCsodh>`rN9Si5v)bKRY1(F zQqfd_bw}3w#EKDSTXB??`XIFgW!B9SChUA*cIwIZA+uE`Sj&zi#|R)C_#i!&Fk$Bd zql|FigVa4FVk?>Dv6k#J5nIXV!`hFdJ5bUk7{jTS?7HBzF(4~eB^>x5t+!$VBQ=em zkXe)ZAT{SQ_vB}>7Dd*8z+BVF_aSpnmN0=igDd@q%(K)7X{7&v57Hu7i{gMl^gv{g zjCT61NXLiuzl|zWj#jgG}GMq`QEmJj5nUV4k3K?EGEK zCc=RaQbx#eE3y{m4ElGOXQ>Y|9QYtLa$nLA2@~Q^laiI0jI}??B3KJ^LnUNK3?cz@ zj8*I2QFMeA3COlWIcRy{Zy+!O))JH%F-w@R^8p{E))JXXGQnE*-VDrA!+{UdV+j*> zJ}?t@0w1Jdg0z7K%-mFjvGe`YCWG2ZGrfe&U zPXvM4sg|J3R$0OXzpeTpwU)>%j|tX7zo;z(dI+R}mDF(HgOrujxP%EiAMimsfe+Fm zSWDu3q%>t;nYBmJV+rk7)Tl;jm11uNA7nW2L8kFrF~PBT>Vq`WbIP2J3D$ylKwBS- zrtnsnqp5Xe&c+fZ?6^MoAhiVHgR}_NqNrK;aVWM{_5$d4AagS&>?l_F4V=ISDLeJl zisCDv-I<2pP<@c;`#C+9FadvyK1n<@>XiuxKFBmCSPQ-vtqT~dA|LQUI)M+;V+j+o zTTjYdW=htcQSto5pT$}?Cd3HYC1^zzC$LS}R+tBB3C28em^o?*%1n|aOmN!jgVb6g zv8hb3mc4%v-o9|)gG^%y6Lvn}gLDEPq(!inM1zX0V)=j%GMz|Z2@wvbjg!A_zEuKC zn4mWds}E9hE;BGDSc~iiLgGYad?kAoS;7Q;HxBlBE&NKq57}|S1Z#0jdMFg#w%2@s z{^RJ9->hhLCTIsA(x93crn=-%O%(rmdVNDa;Bil{?c!04OPHXq0BJ~^sI(>UL2}&< zvlhRh`XJR-GG}866Vx6fjV#BFDT=Q|5kwIyL{4IFA$ zZrSNg?JmbUTLiVPNJFC3#a0r#&ADYQena&^s;%II^jN|K^>9c7K1i)s@ImsvO^3B; zlmVjf&2fpf7k~*GuYiCLQhPP{Aj8y0In=93oQ&2UnOj*sC-*oOLA@vli7XXc$t;hb z#ajG^>Vs5U$qr+dFhOHGq(Ngi9=Gv$jz?-BXs?W6oA7gK4-E+TAk#-nVH)qaG+Mgl zlmhr5(??`ses?BlZ0D*EQf&nvB#*Bg*5WrrL_A_qrM;4QAxoH`IRny|8tg>MnmN%T zSc`TjfoODdx0AIOnF*Q?f`AV)eY_i{5vxmM-&@Xrpt%9>P_PJ^0U!<8_aXI4c0+J( zS&QFLeUNG^nSrr{37Ul=4b1BF8jDFjg6-$J1`l#q(gIZmuB?V z8*1co`l^9=6yv#Nf>sld4~cgbTfqk@UduSaTKtCUgVYr-nR~K?30l`e8WQg+YclXb zS_Es+?n4l?N734Y#RTn91VL*u4y~%Vv_2zo;hI0JynvwfEAc4CB}~vN6$tns)mHF9 z@|uiwP7S}I`XJR-GRtELKbKYtkp`_mS_Es^IZr>=;EVgdHY{O+)_0Kxtq#h51O4u# zji=Q?D^I!$B7FstSMDr=RwI#yM950Lf)A2c2dz_p_zl$uskVX-Qul<*H;8B?i=Z`f z$;ZvLaEo9qTJZ)!yMC>cDVX40d)BJ6L+i#atvXw8Xsv9A*(OZTiZ|X$Vrs=!@ImrA zwROf4zadWYL`&}MUW>2X~^D0v6bxDk8;U_b<3$- z@F=R6O!g1*yE7qa$O;QQibzAEaK%=L%9Yc2;wOBu7Qdl-`_x}M5ohqQgbCO%eRn_7 zkTVmcUcsYi5v)a?Y7m!h`nIKBrTeg5CdeBO0ynINkG4(pA1YqYl{b-Db+Fem-M6Wy zX&*_RZTg4Cfe6m>_9p~qc?%&kNv?@RXHB~AR891cHaqC>c$Y`|ICoNsI&<#C?@au>|)n`K3?Rad;-oYXEWwlMrpL4F!Q( zVir7;D7D1$JN2u~!Jx5~P7z5)EpJ6+6grmU6PL5U3>}f)h!lmS{AXyt}OY zqn2nIvW_pOlL~=a0wOq(RBDNOC54ccc+?UlWQ|=;BozX+1O#eH6gOu{EwRoyLoHE4 zR#oNXP$5uDjMkFqA2}1Hme}W<-Q2-p?s{sp5~w90?s==N-18GnF+E+mC+xXilTDqS z!yUPoEZ^7>rrNTRdRvwRAj-Df&t|ccL%X5X6^RVUba)Nd!R6bN7>i4{EmcEe~ zku%#xA}71ciSP1zS9GG>@?eC<4a6XV8;A{VAdbjA7NUjQjP>3OBAlB)?_ll&`ax0De9XADo2yTNi zex#A!=Oq%!q1+55zwd9+!<9RKgifn0=UE0fNSg9bW{JoxQ=%p36U!Y{@;fLGC1T|f z+?{D~cc$J;CeM=EAa{`of!j76xuZ&c%c;kDBB|WGXmInQD|hvY1n0f#-GK62Y6;gd z#2OUo9SQ1{-UlgKa-*l*4HyuH2-Mx+J};?PzTDv@T5=mDI~0D>s=5EjR4SjbrjVcF$;VTbk4>y_qy!i)qv=C17==fqLZz^~#r}S5e#>F7?W1EvDsG0U_iDYOPoPwISD~UitLpMCGh|(L%k7%IWVxy#j%H z<>O{jsaL+7Vl7&7%PD>5QXWdkjivE(gr#0Z``q+U16W_Gp+*0R6a;64_!4`)crO)Zjox6EU$)_~g>)T_7lnLfj=8@cnITO8^W zqjDpPJgIP@$#|>a<`d(-*WYIe6LRy3GYsvjMH;LdjsPr_# z>8Z08x32L!s?3aw@A%x-QcoR~TdmS9g0WBRjw-bkOPHYE8TrU@a)I2nWmYwM%V&bM zsBZ^B{kczlc$BrMKL>$ZV%+pHXNlY_m|inbdtAv!yk5!e^6B*|E@47$78E*mAN|Bv z?ug`k;<~B%OADVRG-im>m;rA^qYR%VOxXQkaHD7XSF3L&-!u2G+-rwI&t~c%cW0Wl zegCoga2liN9odp|X=CDdXKL#s_i(05n4ob9h~DkG%6+M3?DyYU&tfea)x_Gw$nZMX z)7wN%Lv9pjEx9RJtSjRcyj7&H+;VJi%dy@%EfS1(42^^2e0qISyvLC{q|Iu!IS!l}H2qMaDs`1~Oxz?*jz-k4Vse=q;|I zC1Z8^9`)8xu?W6%5Wzj8@}0|FLYhO7FhSou2=pK6ZHYy&7PT=T(0{nN&r8}wy|+(N zNB?2XQmB0df&Rk@`i}^;yLxY*gEgAuU2yPjZF@xR{CuJZrMH(~c ztyc1+c)jw2{zGa>G+n|3jZu&W`VT+oKO!ulaga-M0}$vx(q|KT*OsIqvr#5!d<7!7 zgGc%g`3Ci^n*I3j+OzAM_vAvsjBp$gwuj5Bd*j6Ez<)cV;abUrU=9>FWpmhf8C1hvo(j%`!j) zx2s71;j)AYn!SJsZdZ~1!+I8L@tjK2NbjRu>Sg4uv~`x*J@slx1NWFjf?1Kgm9|&t z?<|65^dNfW?ij)Cbm3GJ>6o0u2Owya)3C$w5i-W?LW1)w967EcwGx$?YpHT zxS!L1^@Z;pCRppA`eR*LRoi=#8WLMD2;p=&AHsjCONkV)}oRH(IZPsx!cKKU-W$$O=!K6(F7BDT29n7Vk3aO zi#uyR#^;UQk0alK5Uj;>>QE>$uBGN<$Wy1oEMbDugROGc%n`v&fBtKO<{PrEA&VMX zr$#=mFU+aLvXi5{mm}lU?()7&tZ^nHgVOi-Rs9uK@#R%`n!4NixdU@f*fA^{(Yl}Ee0VTUD5kfo6Zz9_lX z%J2Td_l9dYw4%XRWYtPd!F9V-vyL(@P$JgRYqwYXMlz0x#Lufi;0 zg3?1iP_O);UO7y#7NrdWwO!LdZFgA01g*D&2=3a7Hu>ZmYmJ0@AFGWCg@XIMqPWk? zk}x56dr3=l{ls>I)7U38)UWpQI|o<HCMX|Bqr<6en)4f9 z9kI%swa5w}`hGb(x@<=e|GhIWOKT9X8BD;NrJjvgly{ajjiPgNC;A^>-sLgDTJU=+ z5sTRl?$nD;`|(1QdVOovk?n@M8@p34iaYhJ^($VdlsnwSy0|$n8o!av$Bk?j!CGv$ z_^ogL#LxRhS;B6t1{YIfsv#07t zrx#E3s~4?r5v;}M{={!yjJ}XPzqN8lqch9WSl=C0TYI%9AIs#kMVXL$0>!%T{Z|^+ zl^YAC=Nz(SpY<%(V!L7GcV0ei8E|7^lqF2qezoAY&V>Be{O=@4d~a( zm?6p%CfJV$Z$|$*(e~vM{rnY1TRuA0;*)~ncV|X%cc#y)j=UPlc8lN78Fi-=wN^Qq zkh?m?x&xQEusANN681Z%O~ z;`c%NxDPVQ5+>NMiXDfKRg3;wEz!@I@|oo`Wi5E(wPlFyb_(vujo#>%V0klWmJ(&V zg+ja9-l26DcjQ_t!c54WtYY1F*F6L4KD6r&wQiN)3s?kevE8um?(OqY={c8udNj%s zCTzd+!JG%>&Pl)HsE;jzwb*W<(7FKwqU#Fw^tbMK)bdC(!G3N;4je5Vjnql>)0`uQ zpT$~y8WEzxaFa6bKaW1~N;7LMoMw}^_=>L8zaEt_b>DC5_-s)osze* z=34`h#h%-Egi! z?0#qe#9zIwhz%w<4g~R61u{opXp-n}>73spSWEW2O7ul+pKx&Jebn*0`?L-dr4=2^ z(xK2SGe_%g&l{~R?<*5>v$h%-7rqvQZ-t;W>3HQ{-IU`4HF!f6AHaw^xtoMpGB~i^k!mR>D{m+_rYvYX?Mqb*4y&ku~&}mhSul7vqsw8 z@Q)pRmN3ycTMM=Bqj|?8jgbxRSL-ghx2Z+27TXPTgLb8~SKGPp9-k#l*l}c)c2(25 zdvIJPo1kbjwp%FlMeF^hdflG>)uNN5EaB&J+!|t1D^4`eJ)P(``{hB4U@bm}3A;Ix z=7z<(+phNUX{A}bq3NsHw|GW}?|99VRh;&_J6oPnCSJKZ!jqO^cixGxZjKStjkLSn zwzaSb)?&Ni1hWPo8EJQqJzU0T2@`f)-;q2&8yPdaxHX$auol}5yHbjeGru(G=@)4@ z-HP~Qg5wBb-3Oj9pSDf(N8FuY5v)abHX!Fii|uss4C)^(x9lA&P6o9y9vj1U!~IcR z*EmvlE2ec4TgA(O30NU~)4KZ`P7Xf|>o#84(jr)k?S^RFYPmhN?&PvQOPFY1YM3YM z8i>Y4K0evq$Vkg@xMEI=U@f*=DD+Ck{3hC{r(g7iSylul6Nr0GzfBZryt?hYck)@p z^&N{?1Z(m6PF7TL6weK(zc0m8>$ynMmc-6mDqW(rE46)muO62Foc-Kv=}@TV^+#PP zkFGP@OUn>1H6~C)9Vw4kTk>0_UmdCKO;$Iz2-adtheBt14Rd6KTrjPSST|m_OmO}} zp+VDL3rlU!{IQltoM0`sG;TP$r|6>ZruXp6zCK@U6)#&RC^8%6ftYPCh}pIX*5b0U zVz#9O9Vriqx}})yC`HO6jmjn0xN}e*Nlm-@94)|61Z-)H8TO8MrS*AkSQ{%kfr+MN zKhpAu^_*YrZtY5W+<&==MX(lI8u@6R&z0}vt;MCJEs2*c6P!QXGg@huBjr)Dc@B$U zEw(iF%DBax-6)U#t>#&EmkHZeEB|g0{tKud_yLH|Y?eai* zU=;3NO6i|I3U>m(n#B0%%B{p=u%+R_sRJSAv86+ygmZ1RJZ5$);j@GZ&L8&5w8-m9c^tbVt3|LDTN>*=wWc_GQ64Y;r|ng| z?lNK9YW>AL&SAu!|5j1kt2n`0T=NkFS@#3y%hrkhcZejXeFfH;PP7jJ<#DQD_K1U+ zyAz#SS}`mfox+w5g~tARPRpamQAg%D@ls;~BWG9ItJth)(B`kSJVy3>$Rb#aEsZ{E z_ZU~&tFQ7G@>#+J=MU$2O>3&<@m|gh7QtF1^1J)q?gTLYM#=d_l`hriut5v;|QMtMB4O23chpXZc$RJ?4N z;QS#9>5jo#9*c)ulzCK~U@f*ZR?kb^;r@d1`25dtR^4TSb|S*McW0U9gfY^uP_BkW zuomsK0YQ6ZWagz_GTH4wdu6Qiw&3C2`%pyskGlqx_bF~AiZw*7`4Wr8mJWr6T`#5n zsPb1!%KDXRNemzWYGEJGDHT7s_Q3ti_hb4D$8US{`KzpNO)A3CfJ1K(;iz`Uf7>@;Lp-Z{nNK@{l-ojy%K~xt2%Fn=$FRN?IOy z-Z^Ixti_hbxj3I?RNwaH!dqp1H(s_(aQ;G}?B9H=<&oj9FD!z!*wUfU{mtHRbIs`C zJF7ccb(aa-Ru6W{?iRqB<)|`wEP}PT=3BeyWDQx%L-s+@F1je~u0wfzw(6yb%s=j} zoED`RL4%kXwY0=svZaxaE6ub#mi+vMRR&DJBcwKr`R+cfQd`R-$KWj%!CGu-oFe#k zo{044#h+g+-i&zJGQs%^h5G;ala|Lf%V%2zYq6y<6Mk;6dl$;%iP!4Mig3K{GGW`Q zOxI%We-9`6-?qDI)ppk6ns4n<6px9fA-l}rkJ9!^cAwGSMU+SC2d_mc5A7d){`f>| zKMqCKSY-o`Nvo%|JlfAr`?}Y-yYWxox!j0Lr8Bz|!I|iPv2wY+JqmetGvx z_@j27*kjdp*5aCP?Ep2j(^KwB(ejYJeY7(a{_~7a_0;&1hW9*bMHN%*$1VG#25fjP zavJl&kau5{%YX@rdO{i}8#K}K$n@}Y7QtFAl(;{PgQ3!xAR!XsUaD%c9n8`A7aJ6RgE{!-*$pGu$q)?%vRsR!wArb{r!g|F#Ib z^V*VjLlX?~a` zOz=r_Xs@cwcc&pA=GZ8UU@eYk3Wd5RKjyxQG*%UzJT@;z*-@;ri|=>=Q17eZu@K*5cCCxF!8Q5VvH-=2MUCQk(B++>(ADh+DEGOi+sf z0&z?FeIRbhB3O&+Gzi2k>Gy%SC2RLG6O=y?h+ER{193|ZKZ~`foIoIM$qnL`9F{Oa zb_0R9B{zs$vT7o0QQ3e%+)|`Ra({_ilGtONJ4@^_jWS)fo5n4vbrH8@NtmGi(bc#m zwJze8EP}PzZW_0wZ9C$YT$V6FZ3*&$xFxkN;+8Cewb*VNx8w$KOAbqzptb~QAa2PG z;+8CewW#ib`0UhUT6Yn*WbGKCIhAE;ja$;0FyfXXY*8j?GzjY=Zb_|+xFzdZti^WI zxFxkN;+9;NFhRW?(m>pjj${zGWD%^zcGI{eH;7wuS;7SMgRm9imfRq2$zg)Es22tC z!pZ7tUBoR#cux$iAh>Kdja$;Xi?}6;?ALx!BKw)3xes!VxFxkN;+Cvuu@>7+)+xB5uiL2@^DvK^ll# zQtKja$s$;b?WS={ZVW z;+Av`8F5PywkQ*{u7xxZx1`oZ+>%AG7TZnZmUK-9aZ4^sn4lRw(m>pjS{HFk7QtF< zH;r3zx8BoJ;+9;NFhMhVq=C34H;7xZ2-c$Y01)Ick)25C9ut?mB)9Bv8`Eu9%!3ta z9AS$xL2I%|193~bB8<2ti(oCbo5n4vbrH7|VF?qoeuXp;x1`oZ+>*-#Yq8xlZpl4+ zUr&i!a#_LztzRJx#4Wi&+>%AG7Oj4PK-`l02NAavq5a1$`2;OXYuu97UBoR}r;#v0 zJ`1FQxFuKo=ZIUf2-ae|Y21=p7ja7wmM}r9wMYYTOKM%jExAmv7TZnZmfRq2$z=%> zv|5Wa5Vzz6aZ47#TC~;+0&z=j5VvHV^+JAb%hDRRq}D~;lC^V^3G&b(4a6;J-9_Az zMX(mzP2-l-x`%AG7Wwf& zAa2PE;+7)3-xaos?}KH#g+hp13I}mZ5tcAP(HBSqaZ4J>fw(1$U@f+r#w|HP+){)k zOpxChX&`P%BL@(-WD%^zcGI{eCx}~eS;7SQoyEEjJmCa!OBTUepj7sM@D1Z%O~G;S#z#4SZw!URQG zAPvMVIYHc#MX(mzP2-lFAa2QJ2@@1$fiw`e6b|B+EP}NtMgs(*kTjwZQApMKVD zB$cWxxdLn+c+jkOrcVH0BObNEX3bY&VTUGC>rQ*eYI9Ou!21kwZuW zQAl18g=7(|#dbs8EjVbcSoe>vvt5=jK`}*0qf6E+374Kt^z+_X&mvfhB9cJRnSfFr zCWu0klOxm51av8m3647;t_=u4Wf{&J?>0UR4CFw6jC&ZLb3?f zVoPfjQZ$G{l9nM}woGvTGzv*$AQ6RR5v;|Q)+i(sL?MZF<7LZ)Z7W0}c|jDCMX(l^ zjYc7*pSb8!1g4z7n||V=OHq@s73~GEcK2hn9F^8bcJ#BQH3~_;4@4nZCkQY>5zR;g zQAk=Ih(fXm)?!O*6q1$)qL3miVS@9gQAp7s3dtf^i!H5DNG6Cvvg$4qwyh9_WP&Ip zi(oCT`5J{}f+!@HqKaLLz;-D{7`8$bk{?7NStlXTo|aoqTR;?&mItDcWX2LNH6}0) zjs{UkNCQzwS{{f(vIy2h+10C zfn-Z#w!JKmFZ~CikgSs_n4sM%NCQzwS{{f(vIy2?qw3`cQAPUJ3qL3_t zwb;@cg{0+yC?uC9OmO}*3Q5ZYQAifST5M^JLW%}aNLJlt!nPHnkW3JTWD%^zHD9BU zq9q?q)bo&O=ak$Yp=BWVO<>hPe`B{3Y=tN!KZruI&SJ$Xw^~}x`(#UN6q0@)h(eOp z+IXokfi*y_p@>348i+#D@<0@lMX(lITBDG(JP?KCvV;lFpGF~Rc_0eOB3O$ptx-tP zAPUK&Co61)C?ws*8gjQAk=Ih(Z!C za$Ld$ox%VQ7NU@}JP?Is5v;|Q)+i(`4@4n}CoW#LOmO}*3Q5ZYQAifST5M^JLW%}a zNaFv9*Ig!TTOkT58bl#kwVk!N=36I>J9Msr+?J+gfG8w~PAPz`5QU_t=^_frI-3gd zENW>v--#_93Ly%~52BDV(I5&*ynXSy%Y zNG23Q6jC&ZLXzm6xP*y5<45b0V&@bg3Mm>yAz1`#@d-p4g%k~AfSSi%G%VANJP z-v?yAz1`#acPQ$`z=C?;%|MqPlaNcpLX9Um?F^QSS$GLAw5px7J|}9xDBDSzEuU}BZ7P^VlDce7Ch-T1WW!0k*4`5 zi+pH0tQGuLyU~+wAy{%7LTSmz03UrD(pXvcHfiX)GksfvOYl|#)~(P;?hQe|UZszp z6JO}GsZ-5~iw&ZEa${zX-?=wB>AxNM9SUW5Y>pD!@9pUaS}I{8+tPtTI~@*(p}Vue zd?lvO>*2HHHiU^0W20-8Xw~5jiwJ1ddgs-Zn#PjpHK3b#?pr1LR_yMx z{T{Li)(U<*F(Ndrp%Sy!m-bo0MBDo+Xd1^~KWGqB)TD(Ho2M4F2-XUInZqQYUr^g(!h=5kD35RQI8ehLU z2Wgx*_KFhO=kJNKf zc&N7$U9wHEh=5kDy`x0i7lub!avQ?Lh?BeeDlsx!bBhRQ)jCqP zk*3k@&{Et2ezjhIC31Bx9Aya;{cb2>y8JO1#Hq7MN;KQJ)-b_Z!EYxp^kLejwf&P0U&2f=>_L2u;{k*=lBrMCq^Id@q?ZxtphI2eTo)*X?pxka#6@Y_Lo zfS?j|S;7R>9uQPZT$bF1kQxJmYNAC@Epg~80O1FUsTTddn|%# zyF*_yi1e@a*)fM)mfVJrFBk;13>HCOtwU`L2x@&Ix6#5~$p>#CsD+F0v#9lPsC{(N z4cu%+ErPYEbp=5!b%Z5MP&*HTdIO7KE$SseTnKuc^Btauu!ITfuRu_*W)ZAKy&VYZ zIU_7#f_iNb)H_F5avMVWU=TC{un6kUT^fCWpixGICAT4D!~tSgFp`-zuZKm@D8mg# zH8LgwL8GMzOKwBRSPKM=$SfkDRVx^&IT)#dNb{eK$|$2kxxNvW+=h^`9f+PzekCUL z=x-4;0(6@;o#;tli}nmemSuk$N#kQDDZ-N55Ym!^sQW>Z5{(BYTSPzyS_8^S8nJsV z>wWMa`h-xZ?Xlzt#=ddMZHV9|Ob}>&|34AXss%cHGaq;>eC=5OiM)?EL{NfpB6zN9p)~dH@mit;#_du| z;*#4CLA^pvR0896iwJ1dLao#%#cDgo?Mh(WF10-_xeXC~ANZn_z_{Ha0$R23b?KAh zU#$`tx64->m)wR3zH_t;N?_b>5dp1QXeIPX7?DF4t&b8Ix2F@VC8KcHCeXs62I{z7 z+N=1pg5OG@eU!f&jKcABjN6sKxZNUHEBGzrb`WT(mB6@NT2W0yBut>4cO?ys!a<-n zPy*w2i(swbw~X5*&(j(zfpNR^2J$SGFoFI`(~urc$L&gB+-?!975tWQI|%fgN?_bB zy_%*G^p^4GN?A+V@!nYpjN7Gmj!QU=;O{|yjuC(o7`IylYhg5?Pl}H+l)$)MMj3I* zZHQo8f^oYN7`IzQK&uu;HTop^0(7*b1jg+$T8c|b1jL4M0xZNTGTD34b(ff2HdMMa|H&)~O=io??0%HJ^xkBvo@z$jcsmT?Iab{ZIqDiMrD;{W8fJ$l4OU75^P86CYfU5f6089VQ}y z3HptkFOSBEBYSE)|AR<>QktY63O$k-Bfe}lD4kFVKR5Ut%qA!w*0WeENL!wSbsx${ zdJa{>1pP)2Nck}QEY_m@Aq~n$I*~xum3Nofl9ZFw7^Fe<%CLmfpxOfhbDZ>g6=j08 zsQiu2ankFR%pf&&)DrD6gZk=G?Eyjc$|6{czBCZ@MMYV18$xHr)>ms0R9_9X7)S$i z9L)#jI8m0|hS1r)&T*8$9LFN4WzZf-$|Jrqp#1;C=R=_% z-cGVswwa(=h7w(rSUDrvB5bYrJRwFnl7!7yNeQ_YXZ|f3G@eKHB!M ziLJxc%DBT}$!!QHMhrd}TkEU$WM-F%;J0cme6Ome{rs52NaMT1{gC5ODEa$)T$V8L zZms);aI#O%iIQk=BTY9&G=-7vn1M$kl{;|X&Zqn$TDGld;5NVV)@=<7B?5zsa zZf}(!rIAi(X@)|zw#JA;|5QvTRKi5?TSo@=TX8wFR`9l{vHv6IDzS)I&Ls_uuPEn+ zpG8Chr5(2NVOT5pt>s}8WUKTNl$={7NY+If^nF+aYf-HPLEndA$!!RO?*jyVA5kWP z->MaS1rELs5cGXSS;7R>U0D8|6|verqgH}Nuol&P5LLZp-j0*We$kHydwr_j>ApUB zis^p+g5wX(sWp6AtwTB3P?p<`Qnl=2Ohe)3<`y5&hk3 zd?49>^Pd?WOPE-cqp(}+>}2y|sZAgzj>u|;e4Xs~UHqxX5+?RvEvRpG=Hdnr!;j`Q z4L2wIJ4*W&!CK$t%jc%OHrZ@ixE@4_4kOKXd6WH%dE1%_?;myU$vNH(EWN_Xx%78u z*Wcq!oi3}Lk6Rvd?k+msjQMy4h?9ffGKZc>_P?!C&6F*7!+C7-MDz6AFPzMEuQ_#| zpJ>|e{M^ZK?W%Lf!xPPxQlEp!UH2XH&SS~`>tEM2EMemBmY1Bbew<)dZTl3&qv2sD zYsqB4QlypP)cLKR>vY!n`{@a$(#AC)-W)W$<%YLi9MF*HR4=4M5esc{=n8^J7MW@6M6HL81l8=%7`{`;Fs#A>W9gGubSsAg0*rK&FNk}ImvvpE(&6%sbfZCyl}^r8y-uT z`09?FZqkWKX3ZucKIrP0mp@4Mm;9K~Fu_{OPvmfq{5;7NSRlmyry80|srb%c&tX`? zMB9Q{+-|KWnKFmcKvdk;-1Hoh?7#m~ev4qO^J$sg#~V#DQ|Ae>|F>sMl|IRSp`*nN zOPJXDR367kbXT@^-SHJg}riu+~ErGP*s_O*DVqD@57E&ZhFK$^PNz zOBt3h@%YpX?#D+an)~*C31an#m(0c&lKmVP%31_#@t21EIH|7~w^Ooz%11Xk*%pj3%jPda8duLvFy6i-|Hj0Ah9yjx@K$Hx9b?VjxaA9lHVoV9ZCaP?yU!LjHTtY~3cfhmB&^BnN*gQVQu!`x^xNQ6|8%lB z_E15Lblbf0y;pf{vVZW4l7=O_qwAfWZ%sA_9?9qOlR}|(FaP4TTY)q(RJ77yVt9si z&gW$(o68Qq-jI9bl=sR<$$t2F6^mf4-Vd*Hdfz|Ulo>0;rpYbS_Wzgcr%hjwCOxL~ zoYEgkpC`Yir~CH(ZO#*&rIXspyF*aji?Q7Gf-vF`Z{kdKNq;a|96pLW3!QWn0OUwVb_c3b$Zy(Ya zv!#H?5+)90$)#z?|A^n+GRaFq8h5muV-c(+?=Ph(ZygG4`!~C{5@|GTdY8u%CglCa zZjvre1X?xP%O_)ovL9IlYsuI|(hyrB4e!4+$;bNc_j)X0g3Bos>hxo>w;O3pd}^gd zuol4?ll|VCMtUq^!Y=d1-Di2=Mwzn)an zaE;@dxZ`Tnx%0v#Q}uPp`5$lm=gpp(?C;+Guwe-kYthrpN00M+5g}eJpV7QE6(u+z zY!R&0Yje~&2O@7_A^!X_leuq7vVZ+O*RX_%HVvXq+wUfsN9yJPG3{J7lW$zIe{5cT zi(st+r#xrh$VsNy3Ar8k@xODMu_KcG-?uzwSi;1E!#t-U-jGEa5LB*Z<%&5n1H{pyw58rCYeeXTR1$Rty?Nha4O{ux%vTz!|L}NadueRLz%BC** zkFG^tH!NWyq1ETk@AW5|?6dy?kz-PIlhO)he&%h9V6DIX&zvQ9;}({gS3vapskZr} zA=;}h?;4gc(P6@;&R4r9n9n}E2%_$(1oNts?El=NzeTXtud6F*GzLzGLgN4P5`o;1FrdQQuKmXT*EP}O8eYD0Y(`thGB>Pzq zl{z;u)hZ_YbKV|eSi;2R`Kz7A*(aFngZ=>FuYTM_%A!r|In=O(iStjbc2-;%Z<-GM z9mHc}TbcHECi`EX7-kWyRethHC$-mjbFJ6UAlmGD(i|+5>@Rv~gkcF2?LS}XTuT~n zLYIVS_+DF+Ef3nntfMS~wHl9E;rv)}yqR+LM-Y1swll?YAdO!}8I~}yuhq$^U4=7>i)7BUP3j;%eireB}~k9K61VrH`ZMJ^c$q{*z<22|3s2scfxp!V67Lw zTjFegbF5kO@Yf&)R(QwkIhy3Z@WBMb5++*BUhFI=FxJd0FZ0@qk$27MLrH#yt2V(} z%jYk4Iu#si{;48F!^wTk`u$1%@@FR+mN1d^-$l;GBV$a)KV&96`{hKl0wc>e`b;#e z_2|__&Jk#pIK9cSiCkU#nNB|>`75SPG%R7F@~%Zr-tWeks~shcsyX_b@q3f}KFe%^ zwXXGEa;lFVW7<#o3Pkxf$>y`&Nq&dZ zHo;nDfBewNICPBZTSAEOFAXpkF$&+93oSoMm^kskhfdL!W6W1OWp=mgI}kgQ{6Qsb zg0-4A`OumD)EM(o;dLO!yqjv4tWUy{L8>XaWx8`AONzNa>kNlS{bzSicV^~DG0UsY z01Euk1}WzHr$SWpN1LG_UOjFTtaa|^8P2kf zDQ4yV*&v>)KgxXUC;1f@k2jCip6%2xKHA8)(YEz$=jy$qO=7jh&X(V2In6SRHmi1g z2;#>4(dH$j@j=e9hM#-t;0))R_9^D%7qcBZjq!a(o7y1GK0em4go$U$&vZKVOflc5 zNi63}PmMN3L2P-?CRl55)0s}8#`z$Ik4Q1| zKrHNO6Rh>&owJ-mc=DZ@7l7FRWQv&p;?HH{3`>~E)@GJ-dmb2toiutwcLJ*h!9c4y>D3^7-VF?pGX3uig{+?nwZWp5S=24o)!G~;uwd`6_ zeC{YS9%)Q`cD!K;6G#4-<@7_nYWR)RtJB>^nOPtX54Q={;u;zX<=^wZsjxB0ul2)3 z)2RGBr*F1Y^VjdIoX7on&W8`Bn%~Z^abCJK&nfpD{FP7g%y>Vr+%_9XwW zhLa3Sn3z9dfz$TuR5SfiS@C-1@4=?VHneaNn_w+F=YtmwF$cCJ`4ehQGAv>wRVHXllP+Q6(hGB(vG0yHUtyGnUM<5&^QyF0Lu`VzvJao*)E+Y0>}|Ic zM63QI%mENhc46#K5+=6)GskJRc(h45z6``8g-4jW=nW2K!pw>Y)~fK#Txa*D(dGrL z+=oK1%^z;of;fj2c$P3Rd)!>7!2Z$Zso#WHaMy6t;j1M7`0F;oTKpBD=Ug|;>;=(a zto?m3(W~M-=McV|yU(mb8r^FRGm|%r0{ zMX=V?y?40cG3m8oA&Ayf7pTYNY?s<$mM~HCkwUI`Ob(7)1mftMbJSxp_rgOK!CI?B zMP2dZELge*M5y2_^_bLI_;8rDj%_O9ikIZgb*nv_xbMnT^_Zk2)CseMi6f=Yn6DoWvxJFLi6va|Y}M|u1w@;X zV|Desa7&wDt?2p^uB^9LPT30LuKfGdqgZa_m<0CfKmSfd*C~^tH4H}-;O@*ujn!+} zvDno|Si(f($LcG6&mEs3jZ+u)sb{q6<<}FKU@h{*f|xvbwE7LMbblz!@5}iZ`OIDF zn>aLZCy3wQ9i_gBJ6F^WvxJFU`|eWz$Cw@8fq1asaP@!8f2@{8uvXVIcdL(Ocb^|X zEH67$eJtyCJs4&Q6OkIF)Q=M>Cvh3Wy9`o4PM>BqEP}P#3@)XYyF|}>braN@v9(?eD;L;?z((^SC}PCoSt1tJ-jEj zWHj)^jc%m=!SdsaS_EsomHj^TF4mlx3B;2R)>a?ng!*~IEMbED^&r+wt*CzIUE8vR zS;EBFLe4V}3ItGMF%saP_H zgBktUIz~J{HJa!5SW;_CC09H@RqxK^@RP9alhW9T=jX4g#jG@#IGwwKE1sW>b^i$? z)?i+9Bc7iw-Ah;mYxQVX!4=O>|9AccQEa|+^YcN5yA!z0AUZu3%SbF1&Q+_}N$FzQgVoE$FKKEkn)v7<<1o8T#N7VDv ze%nhH!CD+^gwAtrbM^c<_hK4IT%`V>Uisz^3H_DcD#q)Ef?RKP*r|~HD z{QUfGZHr*7c4;MC@%-HV)>aVj%^a(qpRtjLJ(e)h_|@XBczz0Wj)G`)d4hU=D(<;Cm@A$ix9M6C+u!>@JwF#7t>dwTiAAf5xZ?Sl)^#`AF>G6%CYs&ewHXCm@%&UNG6O`Z zy-U>dGkt#zi(svN2lBe&`6=_$7!Wo7_*gwZZ`}QW#}X#?7tH61=cn1(u^>w9Tdtm; zu9d1<1Zy33^0?ypY5Lu85c`|1RL@W8XR3HCVPeqS3E!Wv=L(R_BHDHDfV^+i(swa=jL+7 z^D}+jKoDiNeWIS9nV*#NSi;2d|8ltE`8g5k4I*^lGxhxZIPG4GV6A`t%;t*cXHVW2 zKsa}Nsh*!)`S0>rD_ieuu6TaFINvdB6Prh-sprSpT*PAu6Ln8zcE$5^|A$SG#;|Li zdVVf-FK7|0Rn5)pisxtP%z7Zsz38jwC$u`J#}Xz+bjj$7=ciJ;8X!)+yiPqo&Tm;Q zg0&pR&(@mW6v#qRQ;U>iKE8K0_URgA2E*=cibn^A^EcFYGw1o}UbzYJlkX(Khw` zEGS(3OO`Ov_~2pn{QNw(9*7w$x2fmn)j#T41Zzz#c|<)wRkjQTQT>x`>iKCoy#1Ff zVdDA1N7VCEbNxUNWz)8)=VyKE_br08cD{Z@JwMwzt_JbQx^3$DIs4@YU$TUW4@MnP z&(ET{Ux8@5W1D(@^0fKNB3LUS|55e)oY|b^5u985-8S|7Y};}0OO`P4ZHA-j`3bGh z0AlBnZR+`{v?0q{CRl6H>Z9uUY2UF1h^K$urkiOxtc_@h7_itCvPtoQT(tdV+Q_s)kS@jaSPy9_iKb;meNto91 zSM~fn|w z6X(_Q^U%z%66W7Hub!W_3%5$n@7$`MpHJ@pD2*jdRLlIgdVad+{u#ucJe$<>Q}Mvj zG;Wc(r5>C5uX=tyJCFk{^`~!aQqRx#pB_kK2@`#0{G*iHSca+F1|7JmiUE0c4ZdVX488f$$YOze5@oO*ud zzO))?Jho-4dVYFmpK1}T#otOObh+}Hw3>*N{cvF;FJEd4@6CdPP5CFUdJn$;ivG@( z@1pl!>Hgk>p~2?;{h6`WH{+Xk>O2Ud!I@`KlLwR&B4g!j&W}|FJR-k$mB{8iJz~@& zLQE@s2Uff)zqZm@gt+h#l@i0#`sR(EAB!l3d7HiUWeP->!mrY3&3E3Vy8e@Z-bHf_|0p z9wX;$@+M;CZd3SS(=PvfjRpQ_bxF7H zjWKsuJBsp{{9hZV#~(?4r$*DA%MbN39luR6KP_5k=(#52OD}2~o4gbdsXMlYn`KP) zi~q9JX}5j9cQ*fUGb`&Nlez0YuUFsUW_IbNX2O$`Jb9~$?N)&pxpz-^@h{2#;~QIq zXMSHkT59YR^L&m?1{RJ=)HN(_%!l{t@AlnOLCjBmBmCKwWPi%CClh|lSTTB6m&s;L zw_@g}1UD*?-L>X4GER=L{@$_tB@j7I%y+)Wn0o7(c219x8%>U8h=S>xXiDCH)GYVM zn77UhHI4dzYkF=TV=^3_0V4OM7fjW}WWTfcr-1NTVY5jfU(KSfpwI!>( zr~XX#vwXWf?ex+I+&RBZHlqeragcLeJw?u)TD>Z2WdD_^Z5))~H^#I^Jly0`UwG@Q zTy@s;9Ao|*b1}TK%{529i6*~Z2%qu)b)?KI9=VFzUVp+Ya|%(D-Jh;u+CMQ_-*;Z} z3ncQW#d7#}7;Tq>= zI(-TaGjl&Z7`}RUFSXTnbV+j)vzVWIO&;7a_MC!@aruL;I ze?!jCJbqu!$5+|&yT4=Ir~MP9@mAAvPc@su$^MEiGdz|sG5+2%u6(tXm&@w;+XefZ zTJI(MD=&_+2-fQUUMW|;`Clu`X(VfNeyhH_My>LCYwCsudA^e6{>Tsvna_^}QR|0y%*J-f{x<`QTLf$MYn#V?9Xs{H z=Oof8bZ1wywO6vgziSr55+<@>C3TZG$sCv_@ri3X)Hf}sVPDbPr#vQD>%TmC-C5Ts znUl}U&dEG26U;jcll_+2_joK};-MME-BtZ3o0p49-QAxtvuV5=y}{IJ7QtFv^O45% z)84;_ll@DZ`g$y3LVD|sdG;ra0Q${ySi*#Shr#FrX*`hlq4f=|y*R3PsW5%%16`qL%EfvECwBOZr&pYte@xjsACy@Vp~Q z{wMDkhb2s`zA`Vo@(?0Wf6Ib222P#ry?_$D_vcS6g0<%ST->QNZoFxAE*FTx-;D4I zWlQ#_URmz27DmZo87<4G*(N5H80{@?gxxjYO>$Vm#KiN}b-Y{smwS=MmPvEG1}&2P z<4wj{1ZzpJEWI=OVh~;1jrA&`uN^wDAKLJnlK*4tti!81wl*F-xVsm3m*ngT?(Py? z3dNlw&A~O05ZpDmJ2`uDf@^Vir)YuVMZS0K26*Q_-~H$IVXa@***3Fg-dQtDNFOVG zE&5y#{Q`R0bC89%9Z+4dg$c=df{5v94nodpEA5 zSk6NhTbMAf<3PDNp3jKU?Sac6*el_Y=}wF@#Y!W_`ndBv(x0Ck;BT>o3BGSWK67JL z(DReIz2&b?Q_^cm?}gq*mv6LE`A!Mbg?c^Hi_)%8RUS;!VXYqE`&bi@Q~yyN`-@Z? zso0BY>CL29Lyv@C)uUx{{VLGyEjxawVha-+>&{Z2^3Ko;BYZ(*2>xuhM_aODX-k7( zFMhI^r~dlNX?#LGYIzL=Z`u_*KR!sxzFl3 zGb|o8@MwZYsTfUUtFd1ztoY5cWtR2)?mee3+F#*_efY@-^%7Zs>y`i5-P65SAsFMf zI4&zWqHgZh`_BY=*uq5h!9D>pDyr5p7(|XF<8`SzZtsZe@f44WCN-PoWcs~* zQy3#8%s_4#sx4GCP8s&Z;;|DG=;f63cIfpG<5Z63`s8%Ccm26N2Ekr5HUN=(rCaCg zi5&zw9kkfOM1r()RhC!d^!Vwr@@$T8h(1sc6>hI~7zBIqUB~m7wn`^Y>h`XEd&+no zOkiy5^t&?F_3^p?&vw1`S&(oBDawxu!RM(eapElIv#A>40Lb)$zoFEG4T&c^VkBWV`u|ZHKD`S6WJScMk zK0XPvFVwv-^4c-Ff?^93XC}pTMqX9wqUzA6NUCP~G-f~cH;SYFDi$LkFx3p5xY7ol zsb1oMy8CD9`cJkyb0*TZV@3qTv}Tsxztrumc;JpDvnk&#OzeqF9v~zA{kwL7_}sIQ z-n|v=)!cms!CsWlfw&msl${*&48x}Ow%Ec1jmSVey13U_{kdREHG^O;$`e5}sh7Yb zqr20GU;5ElM%V1^=Zx-ZhFhA(J|KKn1=%?;y4zB6vx_ZE&D8F19ei_YE0x4zIq4nTb|+7g*fNaO*>3b$n3) zm$fbcVrr$`Jbz)daI60O*U8Qw&69PObKT4J5aiT#PAoDA_M*`}uH&D)^L5KIn3?Fe z$YQTu1rrBIe|4gMCT$YSHjmJ|Fpg@_WQxTWCdv-W=8U8E<*tkve#QKC-(7C+p59dr zg1yquDHbs5?JTXD6$G(wdO>{xD;igIt!c4^iKwt#&NwP?bzKmPYu>eEBg=@_<*SPc z_TqO8Z^`>_&Nymzjm#EXn4mch#K`sSg&pe-){*7RY7p$j@0gEI%8JWWMYLB(GdEBe zlRI;kGIv=iX{eSNuefgl^+c@pi1mDuew(fdVx(@mP`!B`nB)yq4K!>{rIQKxpO zx`h!-La)b?kxKN8mn|ce=ov42M)5vcMl2V%hT%=@v81P}fh?m%v2_+(n8UZqeY zKrH>TTXjZd@#_2=EVeKaGuJlVO8|2=-dkbb}M)Y{WSb zr?+iWQ_+8<{J2tP8h`wDz9tzHM9Z0Pnj z-xFdG>?Na!=$Sjj@M$wrb;te;?b3I%*uq4)yE!7IziN6uDTs`xu_GR4KMLgPXAtbw zGf(!&8X$^Uqe;7ADNOaNE~qJw)FAqCmJou-E;*rJNY+8qY$EDXIUorebXH!pdN=g$Wry$v6t5 zCJ<+eRIT}8WFHK{?c7ti(M zjP)K{(KBg!RRlW!2Y97Zgi_U2IMF?(Jv>3GE!CY}`9rsZCp zeJmp{cdwYL0!H+4E_5^q_L6K*zCq-8AR_lxu#VwPyjXX?_3p)NEpJ@A-?K)F;v@f! zEG<&L7x`}F`@t@>$lWA|yA~((7E`7e?Ed8pP#3=gcj`ea0_Il~A6kC|!y8vS9GwUpfGqwB;g1sb5mevP3 zFk%dv^vO>$%aGggU7~NvJwb*UDH)~c2I#RPFWnsG{JXonKZvNtD_q%;Ste>f!eR>( zrD}F??)2*>c|g3WG}?6v-+BMRl?;Nt4wjwe#PBwfd4`4Ma#Gr1{ho8i)vkAskIb+?eK8hAPld&7i^gw zyc72;2yglgR(bU2?S79^K4f7+vR2Uzka>cLvtyPO7kNoH?`nf!uYG>;^m#Q?r}1XR zy()TZp*6OE+Z+0Mv0@7olEF&bh5Qu6#pffe(-@zRtu@Xd*lXy+q*`WJK0c8duWk7z zS)v>Cyfs3xg$c=XrA21|5<@-b2w1bgwDk4g*VxuP2&@3q*%g!F$u=M%R*OlN(8ZZImt zOM_r9e)D~NN>}Twx}k-tZp=!*%DgK+2WuHKJxT7{dLGVgJ3UO4FO`nUCNU7|qP(P{>Wzs7I0njp)l(PW#f zCHQIi+1klmzmsK%A`k6uM>{JQ_HG;4t&4vCIiAj0Vy1qXDO-SK+|u_Ue+$4|zmqeF z@{YX?dp5CTrfAW(#-hRhurMKOK_mk}RtO?S<7Q37AB}q1VMeRL9iF~+90Sux7oskc^#B97zBG!_JJ6K!$&#&`Jz(+Hd~nB z`-Yn8`+;gc)-8>$yxdux^Szbf)`#*^yorrE)K}?1L={`btD6)PvgSwnTG7;Tn#YD> z>JQ8mrMx}WAlQqtGhD~2wmDUM%oIK7G0|B+^!;x^X>j^i(a}v}`Ip#gA9~Iat-ENp zFabrt={ZFq$8OVE?pVQi+r!RT2EkqhSM1U^tXX>3;^ZLKOgv^)U+?y&8Cg=Zg$XDP zPR}U{ImS`xr&(z)p|-EfCz}cO;&%+Y!yFvy^qiu+vxN!DuMs2ppiY(#W{N^WZW{!9 z@jHgScSd{8;GK3+dK0<1uEXP*}??P`+(Szsf=0#oik0?QCmhpl7HYnDH$_G&x`X| z6z}e%Se;cNjJ)~;`SAGFAY@c0qdSb{Kf%}^KKRVFvwdq!w#G8sAS*LlOea} z86;f!uD`S@ge*MWl5m^vI}?(9OXh^E8N|att#+eVE4wnxAlQp$jX+$y7^OO*S9?4u zoY#elV)oDug6U$9E=WYBbjV6XA%l1KV~2-DNYoB>fVV1p`&4B$f9 zWj0%wknB5pJ{k9FP3Uy>4)4{enqv)uy(IgVEF3vE2+6)B3r99?vxN!Cz9kDs)(k?j zZ^^=ujT;1eN%k#SIC5?fb=S019p}5fixc&;*}_DH&)Fhxo|>tBid6wIxKdV?;5cI3 z&TSCvB_ma5#2Rjan6qo8<-!j9+dm)lu!RYlK?0FxSbUfCoHa`7zBIK$`KGzv)9;5QaC{$e^6WJT_LA=+ zdXx&{(EJ4YA?Cu}AICXuVf6f!lD05<{z}Cj`Px~FQ}JaWh}=i6I{NvnbsaTZn4r}= zAU56_XlKBDV$o^$ZBpC=2K-!E5g=`3^sEuCoYqX(Y+-^{Mu4C-69&Ovw6*~Rt(mad z!UV0108uSxN@qWS*UA1g2=+q8>0F1XC>VJq>+6x(5AU$@l3D(+FhQ## zGFn&bhrPU$wy@d41Xff9MAsppH>f&up`K9E?Y;GIg3T5tNaqAmd(UqD5NkgQR2gp& z>{S8lG6FH$F3>UkO4>Ab$;))2Y_o=pD z*G5~iyxT0BElfZ+a#knEdO55$xaHOF(Vt(a*4-f3i`KA!SXIZX$KX0zwV!FTg^8(i&#vs7q99;#k$L@%Uuofrp-CXSntCGuP?%A z`|bgq8oMD@R&xx3y^uMn=!^`%YEf~29kSc){dBI7p;RM(aMlIOY#zP&xL@_Awb6x; zm*lKj(@?{iK!)S2T$cGp>;iRiqAuML=YL!qX%Os1Z$5ri*Ruw0WeXu zbCLjAg*LN>XsPQD@75a6V?w3z2EksuYQe{+OtL}R)ec!-zvPm6|5(GqYh!pdjE~Rr zOdwM?HIgklR5N!AT;Vl3VxM8Slk zbU%!7PQ;mH5bQPKNU)lgaI#(%HXp>ZuWp?SU+rS7fn*C4n3Hu{2F%uiC>E=yev2#L zlr~JUg$Z7n?c=j7S2x`O&!bF?xdy>rn5|XO^C%LdYJ2?}_i8TAHe?GEymB2^uG{Gb zSUHfz-z3<}T+8{@)kH4?aX-&O#TF)bZ9R7RpHe}$`4Z&KaAU4PuotiE#JgKzx>H>< zIpr&V%Jf7qg}HTFn_+x)@3EX;*Dzg@;Ol*2`0 zHc~~;a>{ia@wJCv!K^`HU&R(CC_4ku^=)l?6LOyn3z`@Ndtp{pMbE>6a9wL}cR=nl zb=qjf7AAO&IQGS9`M^I0dd_q6cBx8UAE)Zif82JwaXu@he?{M@OWY{nlAberz8(1Y zIN^i`2GTaW8_Gs0~R zMQ@O!By^ykv+_=#_nnZHzS1(Fcf+sx=fp%S0GUidm&YL3i!=mz9=+OGdvP5*hDNd; z;jAG3{&ywkk=zG)3y6EWs#>Y=tG4urFbMWC-=4|GQds-367Wr}ea3smMBMXv?Hy^S z=tjN|5u?Y&9j*wpa5+mw8ieWf^BqGiK+@DI0B`$etDRyko@Q<%rH_@q7CkFsTufX{ z^+%S`iVkOmJ;4*861d zu0BG$Yc_6)L9mzfxXkbbE_ zuvfNJv-Ged*dzYiZV=ah>#Q0>8Ey0;T(K8d8Jk3suU*w*Ga0#d)JfDz-2oJ->V(qRv7MKOUlD;VpSOs-I#D z6TBW0b*X>PR#or~*7EIX5bR~vJ7>DEKxMj((cS7+iY-j=icRe6+$UURIUeL~vp>)v z*h^~RWNaYHGWO(nx611J-0giitEwfvZ*;vY&p;b%>)V(8B^G}vJLD(SnUD;bSnh?<5y6;yHb=i6(( zGS+x8A=N0+wU&qx=W9=Op)2Z&_9s>R+u4g(q@fj^G*+GQhbpt7fU#DM38|NnRvVQu zh>`o`0`=*2koRI#6@y?esacenJ5jaJ4=$OfV&L5!7^8_|3llM7pVBYShUidVS*Jf4 zXGko;o&ygPwl@g&;Jr=S?OJ@8p&LlgA3c`kzhwFNbPU_08X?Bx4t)$Yg9+*R zrKd(852EEOkBW`wQLW=3gJ3VZyC8<2jZ{N%ul6@-Xs9wwNY5WV`vGF%!wB^OW1K^^ z^BV+v(UZk)Bp(ayQ|a*p+im>I!xknsHovSp;VnsY`WA?*X(ClPuH*d8z6QZw{Ep%K zXctp0y@vfuZfCPukB}8dvhqk~QCW4s_&nt;OKSU`#7$(gg$Y^%tBkd^9wyj}*4%=i z^}9A(n4q=1Ail2=eqJEl!vuSo+THD64_K%E!j30bEt@S&P%DZUu4nZu>m$}oL|peU z!CtHzVyyP~rM2@acJZh`-ewCE)K(%!tkz$xo#%1(@|Jl9!CtcJQ$|Ht>j~oT?fz;F z#yHnzJ+j%tgsiWWF%EJ(5V3o-SB;SMWy+e;S$X;0!h~dd(K9R{lBXS~es!VdCsjTt z5BzRn!qifWubrccyun=GrTPZJUMtY<{)KjTzpqr@2W(rS?jdLBGNOTI3lp+qi>$@L z`d$$Awk}eO@qMID)7~K1OESvnc^?qxZ!T9hMl8!R20FRscMB7e?Mc>$j19!ipatqP z#!>DET zFTEP_dc+6{g5;K$M=5R+Yf~Zg7#_2Ekr5-obSwm{LsD!N{w7#5iO1 z4il0kNuP-92E?z~o2fbI2frqrXAtaVu4o+XJK5^p$L$^e4^EJzm1n%7jn}YYcjH&n zt$^ZK#d>$4vAT^38inImbssds8krC40J<$R2=y}Bznkp9K2eW;T8O|bg&jTnfnQaq%V_I4-jaV-YS}64 zr-cZb0|0SlWi4w8zQHrDy#~Qv!FTi8+0sqXXA(XHk=YKgh9LteyDvhsg$bGi0MR^p zM4!4;q(PWow{u6&Gl8JlD2+WC$$geo@rV}m!@>m3Qh~UTud-bq&*N1luR*Yv z-R`EhzaTF;lsmR&g1t=rJZsEBwl8Xa#>K&| zL!_)TA!~5H>*{z*!m`?>Fy{O_Np{V@MAqFzuYxz!cc}WQ8`*wnMTh&e(foIrkd;Bv z>-2FQMY@c$t00r97dXlw*vq`T2XBwHS66X+16R+|Y+(X(i&peZA!209Imz~ki=A7V zZ!!q>;&%Z%&}5Be%gpx5!gXz$l{Z#$NbV*%oK$9`%Cx~$dxXqv$9ZkDh35DFXZO9X z;rHy_$of)Va5;J4_rFE+_yLmbNp2?<=E&P?e6jbAa(k2K4s`Os?-nM^{rZCYXVQn7 zyS+^l4K@h&!W^KZ#EI^P^FKoJ>axY$-rX@Ki#GSe!i22Oi>|@Kue#MTK<_~PN8LoB z2EksV)2~p$*e_#RhX;s}Cw4g<9Lw#EpJt9`3lowbN}hL-{)THuBxH zDVAxrFcIFcoLaFPryyUKQ{Rew4$u{lQ{QO2$ROB@c02+>YM&;Bk99mn8XJfvQ2Y8q z?fV#Kl4c8XxbG^W%6v3f9faB!G-E!9__6xwamZe?-J5C*leU@v~h ze0(mod+Tcd+3j6;`IW0%_#sR7Lk-J$#j0^J(vp2rH(ZXiGXH(k`S+7qqcFpgWotI8 z)F;$OrA%p9m}q+BghQ7dwi(3R@Hm#lxS#uqi~kmTtx5aFiLs#T3J@iS6}HMEMtGu_ z7F(FOQRcQ2V|Sd{AgWGD?!*`yYqyID_8R>-rjqNM(P12jK9?suSMF|?*?Ll{wG(|p zD_`Y4RoD5u^;Unhwx^!z{Clz+=>B~+-ivaT!LMqYt&(A3BHNfz4xKIX8Dd;~v(bqW z*dUcbu-Bz&>zo+hGW`u=_ta-Dx$?GaOIvJVV)NXEPKETo&s(pZ7+-_(83cO` z&Xv)*yYF5l2Jv?q<=ov`-5XnMVPg5{B+ixB>KGHm>VwstyX&_rr$Mk6zdhJ>C|l@% zF`Cvf-YX`OmZ;^#aF6+fyL&KExJ&jbzO}c8L9iFUW0;v3cV>^gi47K+yBqVJ-Wb2U zNA6X_WpQyGzg^53A#wr*JnQ~IkHmNu+Rz}_t7N`Hwp>TEMDh)u39jLh z>xi>Dr^OZ~`i-(|xsIou6M`5#XO>6WtJHmK8w7jNp3-<8VOvHyF(!1%YO#e0+HD#! zXn$&hU@zLM8Zi#6_~=}Do{Gh-WA#FvD{M07zST9uLg%;lyY|7l)nu*n?^&NoEr9;z zjPtAJpY$~>O!)NPsss9#C87tR@I&$ z4wkQO%iI1r-+C8Yn3&o5y+i-u1H=j*62==Pl<%{#H?yQ~(qDjB_t)jr=#;XJ98LlSzd7jd8(xS4b11&`hFXAA$`X7S@Vzi@ap zFNmdM^Exrc4@qqNE%xF!6#Hd7Yv{!2Rivr$?lRG`Y78ev!M`%&?iO5J$1aU4KUN{c zAlQrFIdT>ueMGrtq#Qn3>eOt2R{SrB{MG6+}*}1y>WsA^_DjEaES5HebMPTW3^O< zg$e3WL7Xoe<-~|}JBdLUUO#&{5Wn5`ajtww(;_y%S4>dv41)SvgJ3Uy$B^&dS?rOv zBvnXF<4g<688l@$Xovgs@9kX2+y2?{?*7P%urJ-ulP@So0dX*GZ|7d!3}|2w>_wRx zh~^!$J2Be+n#X1f6O?O#NY*2P6JzV;rUt=YlyQO>pJkboCzkq_-)0LFlrw@@cfM?d z+^f33w=f9y^1HRZl=N2vzQhILe>dwM$xFJr3fgR8f^uIF*W(QSeqxA0uosO*KwMfl z&Ka@%`L4Om7A9z90V27*+!?VX`k3El3llW<0daF^K9^)NgZeiy2==0p1qg4UUtDtK zxmxD2*}?>keL&n@HqMEW=v7^VU@sbr;B8+~x{nj%eEaM+TbQ6x5n|97#~|2?#yE&U z<8zxWOwjloF=%{l5bQJ&W-~vVElkj;7(|hfDCf#w>`P*^g$WwBgIJv} zo+VE()|C7P!Co|u2I2a2+lf)BZA_ajOwhO;1dY!Pg1u;b4ua-=JZxct=4wFDypPQU zd(r$1i1&R8I9Hz3H?GYVCTM;}e$~5#mb|-f=N<8|g$bJ70g*YazY}Bqk~;>$UW-S* zw4`PD_wFDNbuOoIVq8hH(!&-eXr>56wU?Eh8LxLKBMgGQ`gHi{#5gj&E{K8Mvp6w& z*Bb9(3lsLs_)11ge*e@4(LYZuXNG0gwS@-3Ua7i&abnc2WPzx^+;Xlwxz80B-7AZ( z$)b3caUCwUFhRc-1YL(guowM85Of_bwlG200it5s9L~L(_NkRYuvdU@Qs-VBD4zht zpv(20D}S|kfQv0mJnaxm$urON^@|H5$f0?i7`3V-F$nh3nNv71Uiwc4ad$yeCx$me zG8bEz_@!)IC&uohZV+ik7I0#`sW`}=3HHjBJEarjzw9+>n-)%tJpsA>*}{aJS@nGs zhBd-j3OX@{`!3nT1bb0zv(c5hledp(0xOU11pZX{7{QL^JYHI$Sm4}P*L86XMW+&S=Q~Fm=|q`y+eQIY6h_- zAd9nK#)3GN6jnNQdF8~IxFwT8uova?h%xTkMkmIFuTeZUu$U-aqNEe!`rm~SBYnpN zmRv`N28j)Vy(phYjEe&fI58sLuH~_T#YCPZ)tnf8JEud8^4T*uF%CX?&tn6Ny=Vl0 z7`ba-a$*FG3$xk61n(f?<1=bU9w)~6U1xY~V6hjC4G<$T^CKrl*JOQcwlHDtMw0UH z;!X@TeKn5_EcT-DE@B+t{Eri3{*E#{Mm7lA0T;x=aF-KfL-wIO66Sq!EgHSzt4(|P zvlBy2`N$(-7ysQWMFu<1LvJgF7^nACaAJI(o7EuLi$<@A(atZ1l6SXn;SnCTFmZDG zP$$NzM7=v4sh0yAY#cU~(tMkQ{Lh!tnapf+NP&?VFt# z=jvb%nk-CE8;ls+e)n-=gmz405bR~n8YH|l$BEJD`dN!DOi=HG7>7cyIsHeG@i`5G zy?Eq}`I1$CI5CP2yl1h63EC?VF|uXc=ERsBSkxfci$~r#b23F$Cq~%ymlj)?pgj)} z<5czuPK+Eo{S1P=c;tX@Sd})}<*|R2P=id=y z;`_Z3661O8%B)&y_Tq6gMt5t@I5ASE|Hc}mLGamCnAt9%JQ5>ylJW+@UObM*xVBGD zTdreW#`mm28mDE^PCB@bZ!IP}F;ZmqGYIzLQ8DI_?bc2V*UG1?hHEBh7azo^pKqrV z<5XA?gJ3Tn6=VJGyNOPWS9h+n8g4W3?6(w3p83hdwdFc~yXnN3J1vJnuosVtv9c!1 zawo=}SjSlnx0xs~HlGtCQC&a8*mf|6Eze_m<~kkZpNfqwwlKk` z`C!FXoN`W#4E}X^Jjf@A+B{mq*g27pmha0C~X$Oa=kOt2TdyCD8N|H6q;XMH`JElkim z1|oLx;!cdO>(_ahU@!UxL2SEq+lg_n_u$}VhrDR z%84-}-a?x#Owc!v7?l#GcVdj3`N_isdr_N+7~v5fC&pX%cAG6sP}_wV>+{5SV$2zx z#30y<+IGaqmn__gvA*|Fn=MRG8;lqo*S~Pu_8N9(gJ3V}qd>S*1v@d^ldsuqVS@S+ z5PLQqc4B0Y%x@6vMSU%Z>lHgVF`9)vvDv}|^@$+*KUnC*Xy3AwL9iF)3?LR3$>+o< zUH6^M7A7bg05RflM<>RkZpt9oi!vM#k-uMa@{(6GzS@T6=LwsNvKkQMrujNC_MEL~ z5bQ-c9EddkR&-)?UJ*mHg$c^FKqTE?$jPs|1XZz_U@yuaLHORT>*R?&3&zxJVS;i- z5Z#N`aB|T$ovPSOuoq>{AQoSq;gbGi)omZm7A7e71>x5?sY`N(w__^WOt2S?06-MD z71xp&zfbALS{t-{!WK2|AGv1fBF} z5bVV*DozJZI8w*M9$N_}yyMKmVnX&*k3QQ8*U_eUXB}@S_TG8=*&x`9TU6|A_{UgX ztpZN3dz)Reg$Z+2@#(GNNt50n*o#|KJi!eEwF@yCoh+}}!i2f1IK%$(PK@)} ziWvlZaf^zI!`!W%7{8BdrP;y+uVRPhH88&uOa&)Kfh+?xTbSTg z?9d?hCwF4x?cc&6*o#|KtgX$T!-+8>=U8L6P$tZk{l~3TdTDvL_r|V?2EkskYxDP= zO0fzlNl`rnwU)PDFEjQqWr8aSu-7EckS^WL?HyX@4`n91B!TZIH!Gvn_9=7X zkR4};+Z)5bKaZXGtY^i$(_(+0nal0>p=cSdwKWLCi&||c4Z}9t2U?-VWGD76BnuPf zPPb{d_qXNUy*4MvAlQprZR`Q@vX3qA?w@7m@>tf`L6_^wFjh7VzAH@prj0 z5E($7&n}7a$IFoh!Cu^ILos<(-I5q*GSAa&VS+0hvF5J-9P0~qR&AAahC#5`)}dGI zvHiyDbE%i%%5NSxV3o)D&L^9%GfvuIg3pM+)?4M4tM=IUW8;^yn(L_L)T!?~nwvG% zW9m&%8ei1*0_indn4o!4wCzjRj#6^v{Xge72=?NNW9)|L+eA5UV$O6%Eiw}{e~Bxf zQMI=deYuC1bdlhjJ(*B!iiD!&*sL7AxzNxC1SK#65AoZZfkE4 z>}6&EohlD;a)yU%@7ru)g63rL%#$Tp>f|N))|4~|_A>L5VRbioWaYr!(y4eRRWU)U zw-96goVv#Za?wcaP6=Vtj3o)1td*^WUXwvaw5A+!4-ow8m<8CfJLfIfyS+ zXFD;Lo}S0rChvH|=TLz7)M2KYhjw>g<2?pJ&)nwoN1@{s*`%VdgPDElvT-sg6MR-D zT85(|RC#1F13MkF_%u>_6ZxISull@gkh+b^;^R^0`OD#RI&Aa2)NtQcs@-Iq2btU? z*o)eE#Q62aNENrK+nZ4(Bo1fHlVqEH+%OKc`+IbL%&i>}a7!s$RVha=0M}a8xqLdS3vSk?rdr>3lo&df>?aBmy;pK+BnJ}*o!iK5cMZ7 z^Orm^ef9;4Elf}j4`Soi5zc6$O!z2+U@sc6fS8csn=_gi&}2T(Y-uKFECM3UXqPi8 zdVXkxK^R^?$5$YZo}S>0isl5)Q8e=6b2|835Di$?SyYVGpT z0myxBm2mUPAo6{DA3JLrd4up>5=YCs`z2F*gJ3V3e*m$?Kfjju>h$ALiY-jg3<8LI z^|CrK=0(&q2==0R6c8PKsyi`0UG1&d!UWBPfUx$Lc4F-4=`slRqWK^Y&EI!$Vze34 zRI!B#n$ZDqJiL|@qoO;fL9iFiYk^o53DFMs>T-U6#TF)LW(vgin`88nif*sImE9oN ztJmU1s(FbCdSJO+AeR5OP(S__OiwX9k z*vPLo|N38y$<21S*un(GLr$G2;XLO$PL8T=F~MGR*Ab&kt`W|4B<J%ov@4=c5fxm~>7Mj~0}16s-KIrn~rWu@@ckTw(MO4$eP>p5#{3q2TZ5bQ0B^%Y|yVG>r zL)Uf4x=kue+AzJY-fg`%e633l| z!TQIDk*{2R9XAv9varS*1bgK>uuZ*dI$gJF`vSz!iPiP9JlHvM)ELDUCbs!(SM|D1 z*X_&w4Pr~%ih2O{ZVTQ%(jeGt%h4Tb->vETUA?y;20seWjmzTvkF+BcdsSSrLuI@; zUB^E6Mw>(lA3xm~t>~mbhAOr&aX8y9m9p#%9pm#y#OQINq#lIRXcJTzWDx8XcxspO z>o7yduJ9Se$$~}nwT5o*U!(dcwlL9j>26hH)(o99*EbLi&lk`=kW(l9+QT5&E8y&I zb#uuK?b#zl+s=R3N3dJyZ~eAdmmVB-&Zt`XPqIim?38nIL7#tfN4D5|%K7&+H|0cx z(np>d&j3~Of)?3Mj;gbK!}IhpQ1#_i2}w2op66UkRZsv9^>aN~pcAky@V zuis8Z2GFF6L9o}hgOMue0ZtQ4DR+16t(f}PId1QqE=sY5i9e$v)yKbP>iB7eNcrKL zJ!Jv*tkHf3!Cs3Wd6iGrS-Ml4L?8x~d~FwAiSttL7gcOw;$Zk*<>@g?pGle&MAcIF z?A)8(-pa-D7zBIef3a5$9E?-!-9iMmJ!P-9-QHLKrdMoX;`y8X&UB*Jtq&P=$`qof`U@!iDy&e1QgwYe;+Qp{9oOjNf(H4dmDE>XR+mqf6{B=R#W%Am_ZGRnTa4od3pE>#=h(1vG3oTb~?v6hx1(V0$>)k`E(R zTij-FThgijU(Pdsy+ppj*U#hITRuTo>z~PD3lpCC-<TH=}5bTBa)`@|831V-z?9O!@wZFR9 z!UR7j=r~O_JEtPHz2&x;U@v|vQQ>xQk{$LMD%sLf7F(DwpLw@Tf7@qp%5k-BiwuIj z_?^ZHt3f4o%Vo$JHoUj^jpH}5aL)t*8UC56kAIBBm7hIURxe(Nwa&f1T5MtBahe1H z%h4uAU|&rtn~onMDnPy;?2& zpw?uWq2GCTg7CEeT|dDto5SyxR%~Hn=gK!~-`VN9^>jHC>0aGGba&`vsX}TVd84)zg1G42)*FVHW0~9jM4)NqlMd8*&x_! zyYCB?qyBXLbgd9e`i{{>^18kG+ErIu?y0E*!gTIgn?bB9Gf`i~zJrZVH&Se2 z!sqQh^*Ja^2ksK0R@})tUShYm%8=#;!Ctdp+)}slhUsb{ndUrpBZwDErs$Y4+}_B&Z53OX z*tGt-8g^%z-aJQ$;V-7>Ntj`|xu%^#uvgWt*Hzl<({!&1LKGV|RiF4AF_0OwRd8g?c1!c}MV^pX1xVCgyFU1xnKJNHaotYM@m#VdhQDJ(R_F{L+8Xfu? z1bb~OdqN%S9jZH>Sp%Zuoay>J&R!mwXOLnG6AN=6Q7e*%>iUaUgNX5Qx_)*Ir}mWl z-5}WOQ^6yuZHiF6ak&s1Tg=dVvDbZ-Swj_Dn27o0pgM3PM92MCRDfQCXXs5BpD+G( zm}0Mt&km{^@GAdtl{Se@^JeI_*k?Oom*I*nOnhu}P$fBolVVRxjKLdb=rHU~SvdY5 z2Ekr+vL8@Yx8pp>fkGTPIYVbTALLzGEJ(41iNM+WR8j1nA1{Uwt)I=%JI~@gmd0*_ zV6UMW_oG_`&+cS((c? z7d2IffGF49B-rbhwhPqP#KAho9U($bP1SA?4LVL$Y+<5X?*(db(qMh`fe@SSPSrg? zTx)I;?3H%+0+k?5uzvVSh-c5I>UJPDH=L^2!bGmk3sj@j!8-hd5XEAL=$as`swTl+ ziIOi=X|n|D9-S33xu^{q#O@h5PUtX*>v3$ zIJ3CYWQA``RZ2fa*C@SM4=b`-eat>ZH*c_5Z#lkF)s8VmAAY7k zi-UElZ9@E6Vw&Cq;z3lfVha;f4=h);B7*gNU%6M|{io?=ASO&S3HHhmdxc6B6|7fg z5aRC*)AV!@mm38uwlFd1@CxNCq}zNCc$3jTQZ|Xm<~gX^h+lzwlGoU&y{L8 z-m4o=B*t}|w!R3&v)@dDz4#6F@hNq2hR$;UXF))tfAx5a8X9k^u9|z9e)M{qT3KeQ zuIXK-gSKo}xoS++o!>4)jD@jg>d6Oje$yr2Iaso26qAz!VICl1jEItcMcrJ4HQ z<3ZlZvqu>OdnHX^t10hresTsOUR9Z?J;$&odC}2|ElkWWAEBC`n5vggUjZU@xtY2+ z&Qa|8&Lr5&yz=R#X6h@4gS?|xjZti2BGHgt>d2(2ddva2R~^u+bvP8{P4oL$gJ3Vd z>)3@(|be$3{L!1ed6kC|scWs>t{e6ml z+i?kqIb){l?jRb(FbVd$&~m*hJ!XpboghT@)6?}85cU6#W=lc5#H@G(h#t!)D7G-s=_*CCX3!xVzMn@uO@}e!`9?jJ!X6qAki#;ckf|?{6(`i}JI)yUaRARE=ke@>Bk` zN3n&8^2>7CqWok$@0{ZL>Wxd3pO%mJ8U%Zd%9PI*<)?CEnG0XHcY#ZkpQ-wQVha!vyM#aCKiCY~P z*rNQb-dV(6mMA|V<<}SldkxqhZj16W_d-e#FWQ&3MEPkjcZFgL6IZ9LvPJnR z>7NS3(tpZWqWs+Ky~H5cYsLC)wkSVaebR#P3omPl^5c_Ykz%jjQCn?Mer_L36KN8` zEGK0vl zsk9}^&*R@GE4DBZa{P=f%1^>eLM*RQ$`a+LM2ZOp!Cq$vU$jN}>GC`ah^W&gEKz%|qe>Rl)tr7Uid1>Rce+2IsPVh4K^jdk4i9Cc+oL zvPJoM=Mc{Vb6BGMG``r{AlR#X&5yPyKYOp`MvV3+GFzhj+}PPrv4x2Thhu6{ex5DP z2O@V^T1%9lIa8_{1bdZS7)y)t)5kYIi0PG*SfcziDp6Xog$dtT3ADUdzn3Zm;`Grt zmMA|_bMq>;Fwtdy5-rM4XexOVhm?Qs66I%eU{-@*FaB;&v7Y^kOO&5VITI+hFi|cl zgBIoI^u&^g@vQD>mnc6SPOdY)LH6RW3q8*H1hyzYPev3~_hQ9VqWpZRlP?n2R*Ef5U_ZqcCO*`&&dwLld7mK%Fo@@K?cEIX=h!uMER-xM*6`A^^4o0 z{459^rP!-X!;6+EKc{bIi8P5dex+*JZ0E%Fn7TX+T_fUDg)mr@^=R2Ekr|dDdH^ z{1mGxx^t4IWo=P@^37kY*uuo@fK`?#KjrgCzMFY&8C#T}-{WG{J^d~Aib@@BiSiSF zqvX`v2A8%)`8gl7La~L3z}Sl{QGT8$mo*bz=a;fY`Pmb1rD6*c1=B3BMEUu=Kr;RL zmy6q?{A9bZ#vs@$$K4Q1l%GpiWKB`8EX8b5eu_U?2OZ_7g^AiPLM>5#E~k*SA6@bl zwnh2Lcxj_Suve`!6D(1FuB*f#erZ zt+pBjd&R0Z$`a+L`94wgpViE3i}JIf!ZyVgCbBjjWr^~0*(*f4zIkj>er6pr3HF*F zHPRC0=kZb@7H-dFi}I7>=yt^xCLWXQ3=c}v`x-~DmEy|D2m7NB`Ugwi^v_$#& z^mjZE36o{EMfp)F_bB$-{kn}M%1^w3@ghw^9ZF-1@^fgCN3n&8LMy9VqWn~ND(f=d zc1vN4@-zOkZ4m6WeqlvRl%FC2LilV=V2kqevXfV_g^7GEi(8`nOl&WsZS^RwEy~Z+ zU!x3yy#{qIZi({KxU&!!d&aay`8gA`SFweO4vq6!qWr{YEu-xVM|^Bie#YL|tJten zw|tf;KUv^q63+&H@rd%1vB5sY7A6{$%wvi2vo({%D7)j6N0gsk&}x`quYQGou|)ZC z2g|HMqNQ&=qWq*uw_mY^iO?jOEKz>!O|n{Kz?hdFQGRw#HwpF{kvxMX%1@#4LJVB= z*dxkMP~iiLElk|~E14zAPukpHKztehz$3~}fpI3mUbEjOw?z4A-9?Dyy~pkr<)_8M zqbf_=tz|{|DL7Q-EPl>k)Y}`wPn4g6i{;2Orl%E4`hpL^<&Zo8_wOO&5(Gal)} zt%|!u`I%SmA&6A9T11HQ^Df3Q#ea7})JT6(epXz)rOg;$Bi#|A{3J+rOtFQD2}PIr zi}I8B@NLAXTYPGSC_g^wO@h6qw%+P5%1=Y<4v49#mPCm1(>KR4#TF*oEZOHT%Fm!} zLJU8>B|?;+$puV;y@tNI=`YGp?vZyv$jeA<~z49U;ok5$l*@3lqEECwGbRv+4KyAV$sc@rd$MS(yZT z{hch6OO&5u2_Ar`wAR-n%1JlCc$3jTk*nD{T%!Ce|MnU&wijCK5#=XVh9inCOms_h&n3!Fk=XA*4+v5@C=Rn=ViY-h8zP#xYVb^UHhV<*u}_%k=38)##Hi%@^dB5F~t@p&PI-OiSje#?Suzz znjIMH66NPYho>O^nE#tcl%MwcsA3BfecnxTiSkqN$TJY9TMzb#@)Iz}B-pEU(giM2 ze)>Fn4&pEL>h(OT*uq4D!pmHu{3Ki|^&eyEP4=kz>N3D-2KdAjt z{M(t3S|3q|g%1d+^%3O`IMqQv390oFm$k!YJU`4n2=f@QGQU{0zztiMEODOk3q1P z)cT0>gIXF8QtKni4{Cobsr7MYGanq4RrirH11YQSrPfFO9Th$xq}E52AJqQ1*un(X zZ#%TC-^UtZ)cT0>gW4a93HFj&ABpkb+He-!^-z7DDN5#NUe`3KdAk&*usR= z`iSy_iW?A8>m$k!YJUuZy`vA5nf#`y(|bKiUj#OQhCE?!teyGE(a! z$`5LPr1Is5g$b$kk$C^r%1Et`C_kwEF$ngOS|5q=U(Juy`iNqJ+8?Rl`C(x~YJDWe ze>Fc+>m$k!YJUuZz2x^x4EfaK8OqkDH zYJEicLG6!0uou76$Qe-UBgzkIe-yuQ{3c4Rk0?K=*TI!bt&b=_sQpoFVM1zsMEOCD z4hX6B5#NUe`3KdAjtY+*ubeMI>|jSdK@^%3OIUQ+8L z$`2}hKuE2RC_kwEQEXvCYJEicLA?$Lsr3=%2em&2!Cq49Bgzlzb%a2zk0?K={ZZ^C zwLYT!ppqxjB&60ylpoaoD7G*mwLYT!phgEVq}E52AJqOB1ba!Xk0?K=@IfmowLTS) z`=Itmv4sh#^%3O2g3(K zu8%4|xIe*HoRI6I$`6hXgj^q0esF&h!lUH+sPcp110mN(l^@)n;44nZ^-<*qs|P}^ zk19X7KMCPca(z_!!SI2Q>!ZpK?oaR)C*=C5@`IxTA=gKhAKagW@F=-Hs{CO1K*;q` z z2lpo-JW8&QDnIx-5ORG~`N91O9wpaDl^;x=Xb1gG$n{a>2lprV&vHVpk19VnI_x3W zN0lGkpM>xzxjw4=VE91D^-<*q_b2#@6LNi2`N6({kn5w$5AIJwc$8cpRemshAmsX} z@`L*me8ma5KC1lS>p;l$QRN5sCwP=xA60%Zd7>TkHzC(Yl^@)n;6KX=dU;D#esFZy zL#~f1Ke#^$;ZbsZRQbX1fspH?$`9^O@D(TI`l#}QqXQw=N0lGkpM>xzxjw4=VE91D z^-<*q_b2#@6LNi2`JwY0LavW0Ke#^$;ZbsZRQaLP973*-DnGbCL9UM~Ke#{fStYgn zg!ZpKh7W{XA60&Ee}b<#A=gKh9~>PBxjw4=;Ql0pN6Gb3*GH8f+@FN-D7ikW{9yP%$n{a> z2lprViW72uRQbWtfspH?$`9^OLU@#1A60%Zd?4idsPcpR6MV%9xjw4=;OIce^-<*q z_a`AdO0JJ8KNvm`a(z_!!Tkxo;)GluReo@EAmsXJ58R)G@F*E!e}78k`l#}Q`xAV{ z3AsM1{9yI4hg=_3esF&h!lV2XivNM@qskBNPmt@Q$`95!ZpKjt+!eA60&Ee-gr@(pN6m zN0lGkpWrJ_$n{a>2djrY><}j zl^@)n;44nZ^-<*qM+ZW#k19X7KMCPca(!aur>{(Jxjw4=;Qj<(aYC+-DnB?n5ORG~ z`N9232#=EMqskA44}@GFReo@Pg0DCs*GH8f932R`KC1lS{v?D)`L}>GC$5hwKe#{1 z_rnRfKC1j+^{|IrA60&Ee-gr@{JT!ZpKh7W{XA60&Ee+pl5LavW0KlnNj(ew4xjw4=;Ql0pN6Gb3g4*U@`L-+!ZpKh7W{XA60&Ee+pl5 zLatAAem2#6CD%ulAKagW@F=-Hs{CO1K*;q`xz zxjw4=VE91D^*Q!Brdo~IwD1)t*GH8f+@FN-sOb7o`N8mkkn5w$5AILl zD^AGuQRN5YCQy&U^-<*q_a`AdO0JJ8KNvm`a(z_!!Tl+G#R=Ij`drBsz}mv~QRN5s zr|=ag*GH8f+@B^VJj%Z}+(+U1sPcpRlYFC`kn5w$4^|I*$n{x)$`9^O zLU@#ayU0`H`l#}Q`;*D_QRN3?Cz?&wtBtOYDnHl|C3p0=KC1lS{$#R%YAbSmRQbW= ziPli!ZpKCI*CDA60&Ef4bYz zps-gPT_06`Fg$o2a(z_!!To9SV}{Y092va}@?7fbM` z>!ZpK?oUE^lw2R}!MTGor(7RZOmKg?`ic{BeYD5_2)RD0{NVm{cfzCWx8=Q(>!ZpK z?oW4Lal-b4kn5w$5AILB6CP#nA%t8Xy^eM_KGxk=oUr!|LavW0Ke#{jPI#1kZ+P`` zeN_3u{i*jAC**hi{Wq8EqskBNPeOQDiW72uRQbWtfspGHD?iI@nh+i(*GH8f3?B%&KC1lS{$#%5gj^q0esFXksh6KC1lS z{$w5{*GH8fOr9boDiW72uRQbWtVGp@Js{G*oB!oxF^-<*q!v{jHPY2S*1&u8%4|xIYQuQF47$`N8mkkn5w$5AILqD^AGuQRN3m2STooDnGbC z3E@$4eN_3u@PUx)qskBNPv$F5$n{a>2S*1&u8%4|xIYQuQF47$`N8mkkn5w$5AILq zD^AGuQRN3;2STooDnGbC3E@$4eN@N6*MX4hqskBNPv%i_eN_3u!ZpK?oUE^ zlw2QGelUC>DiW72uRL8--fspH?$`9^O=23EeRQbW=DN;hNk19X7KlQ%i zgj^q0esFZyL#~f1Ke#^$;ZbsZRQbX1fspH?$`9^Oy{|YS*GH8f932R`KC1lS{v?D) z$@Nj?2g3(Ku8%4|xIgv2;)GluRetFFhLG!{$`9^OLU@#1A60(nG>4GuqskBNPgl7< zs{G*oO!xeSTpv|_aCBzy9mMrf2luC5u8%4|^v^fR^-<-APW&dhKFaCiZZJ1Pu8%4|xIf+f=gRd_ggh!>H61hIA{NVo7`-&5CeN_3u>R}JLKC1lS{v?D)`6rbAD_kE{ zesF*4<@%`dgWJ#~*GF|6?1Uz{KC18Fn&_3|`l#}Q`%~{LPRR99!ZpK?oYk1 zI3d?Zl^+}(i0JxI$HDzc2#@k_0Zs$1k19X7KgsvQ3AsM1{9yI4hg=_3esF&h!lV4V z66gHH$`9^ObbYEhKbm6`4IXS5&E|<_4~9>m!i(#p$`9^Ow189-(uxyueX2P>5ORI0 zIX?;EQF48%IX@6`eX2P>(E_TiIAP8Ygj}C$&QJ0>oF53e zKF3n|!TpIAP;JEtxjxmL9|*ZVs{G*oB!ovr*XMt8ejw!fRC9j*X8~0!PRRAC=KMg& z^{M9kB!oxF^{M9kK*;q`gKGm8v;)GnEYR(UYT%T&r zPeOQ&+&QI{4#2&al)tsMX4=3dMRC9jVL#|IX=O-aNO0G{e z=LbTrPc`SK$sC+uhEtI1qbdM~2ZUUoYR*sL#|%G~m=VLfE7zx*^HcbW6Xvu)$n~k_ z{3L`&nc2f{CD%t46WpJ|SDY|6hdt!_sPcpRlMo(dh7x^?oX4iIN^V%IOiu;esF&ZCp^kOm2u8bto-2q6u#m_`Zt&BQ_cBF z2#@m5be!`OD?hkDg@5AwlPK4xn)Aaem+Pa-5AILlD^AGuspkAZ$n{a>2lpp>L$#mf zQF47$`N8mkkn2;;`H2=#ZN&+>KGmEb2)RD0{NVm1gh$EsspkAZ$n{a>2lpphK(!So z3`&mxN z^-<*qM~6M+`l#}Q`;!nJCD*5#^8+E*rw7+QxIfVXs;xL7*Qc8E10mO^n)8zo9wpbO zn)3r8*Qc8E6D^?HiW72usyROpa(z_!!Tm`HkCN+C&G~_l>!ZpK?oYIUYAa62^{M9k zK*;r}=KLgtN6Gc6=KMg&^{M9kL<^|4;)GluRemshAmsW~bAF-)R9kUEu1_`R2SToo zoFCkugzzZ2KGmEb2)RD0{NVmX3#hi@gj}C$&JToKpK8ueLU@#1pK8vJ_Q3V2=KMqp zXwi!OT)95goF53eKGmF`gzzZ2KGmEb2)RDhoS$d`)mEI4>r>77fspH?$`9^OLU@#1 zpK8tzgj}C$&QG*}YAa62^{M9kK*;r}=KLgtN6Gb3oF53eKC1lS{zMC?w&H|bpK8tz zgj}C$&QC&klw6-`&JToKpK8uew18?WPRR99y*wcX|VsPco!quD%0 z$n~k_{6uf4_OqOj>r>77VGp@J)tsM%@F=-H)tny)xjxmLpVC*Hkn2;;`GJt@Q_cBF z2#=EMQ_cB-kn2;;`H2=#ZN&+>KGmEb2)RDhoS%g7D7ik>oF53eKC1lS{zTWOn)4Gp ze<9aLl^+}(2)RDhoS%g7D7ik>oF53eKGmF`XaUt$oRI5N&G~_l>r>77NeGXU>r>77 zfspG{&H0HIP;JEtxjxmL9|*ZV)tsM%@F=-H)tny)xjw4=;QmAlsJ7yST%T&r4}@GF zReo@P62hb8`c!j%AmsW~bAF-)R9kU^c|8Afes&rUA=jsx^OF!BCD%ul9}FJ|xjxmL zpJ)NqR-BOQQ_cB-kn5w$5AIJwc$8e9YR(UYT%T&rPjr1$`JsPaQ#WGehfaLWX^E8| z+zkl1KC1lS{zTKLw!1p;t2sZK=3{%v^{M9kMAN9YyAyJKRQbWtVGp@J)tsM%@F=-H zs{CO1K*;q`!ZpKjt+!eAMJtrlMo)2eoEx}RC9i!E2he!K0i*#^{M9ku!me9Reo@P z62hZoqt!m4an4Vy{NVmX*Qc8E6Xg1+@`IhAX+E*?gKNSba(${fKhXkGO-L(F$n~k_ z{6NU{spkAd`?7XK_9L}ipK8tzgj}C$&QG*}YAa62^{M9kK*;q`v=KMsvu$nBUiDQfY&T@UKIX~N^-d5ORI0IX}??s;xL7*GJVFd>sh6KC1lS{v?D)$@NjS z244q4u8%4|xIfVws{JgvKC1j+@-(D`T%T&rPxOXrKg$WZKGmEb_K@qN$`9^OLU@#1 zAJum-d?4idRC9i!1yoycLat9W=LbTrk19X7KMCPca(z@u!KHza>r>77DdhSn7mmZw zV3Rf)!ZpK?oYIUYAa62^{M9kK*;q`5ORI0IX?;EQPK6GzJuWdA=jsx^YcFos9JGCu1_`R z2STn-HRmTGJW8&Q>N^-d5ORG~`N92(7Eo=)37ZQ7A=jsx^Ajx~eX8*e8k~^pQ_cB- zkn2;;`AGr>77NeGXU>r>77fspG{&G~8KXi%FCrlU`MY8mcNgIpg~elR>Bp(=;hl&aA4?RhLucX9+ zwsL-ObRgvVsPcpRlMrP47e(>g7TN<}2STooDnGbC`mJo`Z-V`5^NJwk`c!j%62hZ+ z593e5*MX4hqskBNkKWxyD^B>|DbD$+ujc$Dgh%EB$gPc`R9 z-@!$naF0qq?Q(spIX}@Zt9|19lPK3m)fx;RUb$Q!Reo@Pq6Ji2abi3E@$4eN?T%*MX4hQ_cB_-capl$@Qt`{4}J5Tpv|_ zaDSpVRQp*@$n{a>2S!ZpK z?oYIUYAa62^{M9kK*;r}=KLgtN6Gb3eFwt_Lat9W=ON^-d5ORI0IX}??s;xL7*Qc8E10mO^n)8zo9wpaD^&Jc!2)RDhoS$d`)mEI4 z>r>77fspH?$`9^OLU@#1AJum-d?4idRC9i!1yoycLavXhHTXIZa(${fKMCPca(z^- z!PkM1>r>77iQZ7{XUX-c=KM6Igj}C$&QJ7)YCp>fxjxmLANG*zQ_cBF2#=EMqxuep z4}@GFReo@Pq6Ji2aYC+-YA@I~5ORI0IX?;EQF47$-@)*Kkn2;;`H2=#ZN&+>KC0H> z>p;l$spkAd)2Oz)Tpv|_FnJnMLat9W=O=nYwV&mLT%T&r4|~Yj6KGmEb2)RDhoS%g7D7ikW?_l^q$n~k_{6q_=w&H|bpK8tzgj}C$ z&QC&klw2RxcQAY)!bP(z7B+3pK8ue zw18?WPRRAC=KMg&^{M9kB!oxF^-+BX!v{jHPc`Q!T0o0d?B~k$QSAl$212fnDnGbC z3E@$4eN=nFzJZYIQ_cB_u8;ES^v?&mKGmEb&1q>;<{ozgLavW0Ke#{9G^*_`*Qc8E zqiH_2hg_d(&QCOrYP&lj*GH8f93A$M>r>77NeGXU>!bP(h7W{XA60&Ef1(9cTX90J zPc`QULat9W=O-aNO0JLUI~YC?a(${fKhXlJtvDgqr<(HvA=jsx^OF!BCD%vw9ef=K zxjxmLpJ)NqR-BOQQ_cB-kn5wW4DL@tc$8cp)psy_AmsW~bAF-)R9kUEu8%4|I64q= zeY6MePeOQ9`YDm?qskBNPjtmXT&_T4&e8ma+tm7-EZybUS?1DU8t`2M`Jc@4YxQG55ySxi>eYv{4 zeZ>j-#e@EW`fuzckFP_WV^%zwfKHs zV}8)oj|yLLLZ5Q&p-(6I_7iU^$PVW8hbM$b$$lW?EgJ%YSt$kHL>>-WHF^=Xm4v{f zAQvth0)km71=;f)eK5fEcQ@v%uK!7LWbp4ib8{N%)*lzJZ1|KgQKzKFl4IEvzTyPabsDJS1dJO9nLE^R za!j6t@F=GFG*A%=*g_DpgO0tfF~8&87NxH^!IYo|>QMo62to!D^{9OHQM$OrHwW zYXe3aL^RtDYs@j-62haHb`_|928=xjIek=ka~!|YSDaunSfExM@CYH88CFt7&hZFK zUvYx@VS!3@z$t{damYDki`^RY$!)qMgh$DRq%s~b9U(^Cc|rL_56&O^bSrOsl{jrp`my`w8i=YXtIO=k;K_yhK5U}jvP??4_Y zdpz^?;Bxkcjro+}dz8N7gzsHfx8+|$%F*jK=8ON-D6R=Oc@OHodld@2<8u#bfn}s$qC_6^zsHeQq=x63DR!YzWOa3FOEF{se>!3-ayx!d@4ZzTyOPS^}B- zfYkxP1ecPWeqJ1LUg;}NFwG@UHwYLW5Us{;RZ=&|U;g5ZgzzZl%>*hC0XqdkHVU3fM^yX>%qoa4XDnV)SIaT0qGMHC zae|3Tf!bZbvVxGUMeQ!f-bx6MV&+qz3K;OfAY_EyJfShi5G#GfiS&Ff>x>#?&cvyN z@F*rx1!|K4JB>YYpVC*H zV46>$z7ueNAmsW``N?sA62haH#}lah1gsti=KPdYesbKO(pQ{dnopp<6L5bZnDbLo z`N?sA62haH#}lah1RNcRt#>%Ir1F#F{*=Dr1k-#1^__tG1Hqi1lFCnx`;!nJ#XO!s z@{{BKl)mBw(|iK;oq+oT!JMCx%1@5_lMo)oY@R^1CSdhIFz2VF@{{BK zl)mDGTpy}6GI=0YpqrT7QohaWV@jT(9=NLx^i^s`Kp<9o~<6ZClB;n>Y3|{_NI6| zN1#s?qU)-|O0pk0{jUk(QR=BBj}qvlh1ln!VI>)soF3cKSDfJ4`hhG?px;)+V#7Fe?s$77Ogm;es{8;@+TnF*G`r*e`o0EXjs&CXQo9U7aHhu*Q^U8 z*1F}2l1yq&FMaHtul+11)SpkbR(Tce;sfeAeduPlG)C28%kesf|(|P?0LX* zfM8ZiN%lO)pGXLgV(LmD4&DTX91E3e}8&cLKrenv!Zpj?a=19>o-#KwU)63iY zP(2HnRS-;3DyggGm{p~(IKf1vKKZzY6BG4m-<1q>Ks5HiB359SzR zrLQ=_WT-$5GGL2AFmbA+2AN}_C4@&YyDCu4447^ZOtmVhbLNX+cg`^nOJ8v!y<=hKOGy&S%$Go|AmD*$7L1(-nJZIL zX~@TP8C&{_6U>+iR5JqJ3BT0|KMpFXX5_2oDdAB}!3oqw0?rJC92qJmInGS!D^4&g zCs384m9d17heK5+$ID3wk7AlnpuQ7ue;}CiQ&RcKaeqo*ae|pYfj)qM2L#dgqDxAu zOZjVCri4c^V<=E{3Yee}FTZ?oN#{V0J6igR6HJ^7^dJQMR0w9#m2@ZM_^G9@IKf=H zKnFy?RfTA~e`84pM1JV!V-munn4A~rr3l!x5X{so>9WZ2Y)fBpLg!dIIReftM2Dp> zD(U3N&%P%mJW56}Jt6XiA(lJt!jf*09A7xP#pZXKyORHdxn@d=7N&0mwflWV@h9ff=Pyf-j;v^4Z$46lFphOw>lv_iiwPY9-V-{ z4Iy8f?wuTeyYv+&nA;fW5DK{55W63FMoEWIzQZ-66T+j?t5;@DmUJQIc<9k#uU*$V z!TiZU4^zNNXAkCDmUKGhxb6wzQGVqdrxnD?&zFncJyTuE%EYTjnZ^OKhn!lTsbErPyS_E68D z@+I^T7Ceo+LHQCo^fI0o-k^L5J%oBHc!TmKbRA|KMd?dazJxx-!dIM7@1yc1^g=@L z-1C?(`F{Iug|9flGte89FQG3IVy~aBiTM)xEfd0{)WfNK2|b+<>fuzrgr3gASDa9v zsB#?icS5L7RQZw*&)YU3JWAcG%9qfa3ZY(9+tU55}ONv#tN(hfq->&i{^zlNdZ&&#e`gjXpaf0XfHz;31 zPcOv1^ad+mLa%T_c$E5&l@*~M8RDzCN5y=}wDxTaUvYvt1P#iU(3=dQ9_N@ZS!UCO z@F?|BD_=riHN>s-Q7d0UUv=RtPB2fQLG=%MtRbeh-nIPg-p2gn;j1TvN2QOarTo!!~oRIyX`VRf!d_R7?V!2YaB09=7!DSKQQU2YG&(n_?mUXV*F8O|_ zk5(BL`f4-(rp4#!#|#TSw#j$U3H8(}!$OZOubk)U#|#TSwh7@;Jommq85VkBA!1K0 z85VkM3tw?UJ+;cP&|?dso?2yC=&?-*kK(!a4a%_43k$*X^kasF9^1lKoKR1#GA#7i zLhwBOm|>yEHX%HU=iWCc!$L1C1kclt85VkM3tw?UJ+;cP&|?e1^Ymkeg&y04@F<>p z-=GW&y|57Ksa1xB9^1lKoKR1#GA#7iLhwBOm|>yEHX%GpJ+;cP&^-&m^Ymkeg&y0& zSDa8!te^9;h5iLSi#KLi=oG0}2aob7^c>X3C-%k+3tc>V zuJ581C)Bm03=6$15b9%4hK0U{gy0#bF~dS%gPv`=Xm94-E%QvwuiJNHg&q(H^?WG9LJvrjuQgj%%jkO2*ESSV}^x3MLman(TWr5 zOH@{b4m60Z=pR#trT+#SHhC1!j*b}?`pNW6X(QC5rVPu^ZPsY=6(`gOrwj}IYwV#u zIAuTRi%STPQm>uzDD>Vzw4ggr85Vl)nta6xp1B<}EcD?)sGm=J47#o^Av{VwgUYbb zLkPk1!efSo9>STv;snnQj~N#F2_bkUdCaiTrJ6*RjW*#=_^jCPgGeE`a2S^;v{6N2}GAt|q^B_Ib ze$k2(>cUlqg??N1P#3N;EOg~2gh#2!-49jbOtv=INoZyN7F~dUN zFvJV*JQFi4bQdRtN2z0385TO2A(&PWGc3wxC7lo+ zrOs<*Sm?xtQ0KKWEOcVe@D(SRzz{PmbY(*@*&$|F==M$sk5UJ@GAwkILohueW?1Mb zpW!P`Fi9e2Sm-W?m~j6yF~dUFdO~=VI^mUJq5mC%DHt)sLTCI8UvWa+_R6r(B@c1; zlxJdwh3@<5PIweEJ7R`~nH^o@G>@2Jp~HW=uQvt(|*y} zl4q;O3=931dgi*F2j}$qSIn@`)7j)JPVg-Em|>y6lOqGqh>sZ-`bHDNqtuJ43=6%f zx@MpkRT&m~Q=5Fn37$zGGc5F}La5(W85a6q6T+j^Q>zRMJ+=@$Pd{c@=&^0`6(@MM ze$24YZwv8S>p3yQ((cXq3E@#PER_5Vfo_hKbm~S30XYKu;A!GZ1?u;m|^MvOr7TW zEc#gf{+)b z49j8rl56U;|yP=*C(3S#K*Ma;0^VkLw}rB|=ac8VDme6PY+oM6sVgEB0*U+lsB zsF-2FDN6{C@+)VKyOVc_ow6-Qt(q<0fAiQWyV8br(fwDaEYAWcnbjFPW%2jRI0H0x z%JN)*%vbcZfEr}KYN_{;l$V}`|byq*ZYd^=RXN+YtHkr zQ+DK9m)84=6X|ay!&{xQGQOSgC?-9|-%$29PuRHl?bs)=a)1{>hKe;-FuYXLA&B4sYxiJ^cA~GhcCnnY^)IbV{6S$*kYlFUs>j z62hbOOcC{q@{AGo&@)BUFUm7UGGB3m*}}13l;@2==(#287v(u73E@$CHj4U1c~%O< z(>xnR{i1^=byA0x|4}OJl$2`Fm`g5FT|L&v;S4D9?O>xQA!Fs9%(4 zzGS}Q1hbxFzbMatfnbJo>=)&^G6~^PdRC44MR|4&1aqomzvw#mZJYUu6U?k`P`@b8 zv4I%N^Kf`BPR{dj62hbOTp#s|@|+(CJqbwtqO0xIHS-lG^t2)Mi}Lg#2qulke$gwR z@0$6F6HFa%P`@ZoB7!)p=*soR>waYcA zUzDd$vBxV*-X8l!XSD5{`HB<1H_!dJWoqmfox1bZ3E@#pnr~3QC{LeakE46t6#GR- z?6h6xD^8@ZqviHD$9~c9+qMbeQF@A%`bBwO6?+`J%Z;&L^p25TGhcBceRtPy^I+^3 z<#}Go>lppqvJL7Nop|}Bg};Yf^)2~m>=)f;=32?S>x7 zF+BXRM(?uc^5f&rZQHwRx#J2~$A2&ReZP{syFb4vdJbyL51xKVxVP81@ayJd!i1Tv zn!j6aQaJq6vEjj=S89Iqh6!O#F*dYh{wv4bmGbh>?*`^u(5tY{Re3o7sbOK~qwg%I z)omH{yMOlRP35?K_KW{Mq{lVvvEwy2mH(xW?8H7>mp89)OIUr<&~S6dEy9b>-5k!k zU}zY>%Vwe9zT+Y>sd0B+$JZVDlv8fOW7%S-;^P*ZH>`WaxbV;kYlM8^#tprm7#sS` zT_KF#aN`F3hVAcF&FhvP*UWtLFRB?Uf75-p5l@6yhhqbsw@LE_FFqCBmFFk6Yd-6Z zGX8tZjvaU%Grzhv?EKEa{GY8(2`hA(QU3M($S{55ab-{5(KC5R7n?u+|GihME#458 zpUivJ;pJ?*@oP3eaM8GM?CQ6adSCSZ@IIB7T(V-beyf}Bzmr$qbI|?axFs6%;n8x(S#^azuib~JSAId;ds+<(lTR;0=XcuI z>;G@qPQJnWExww$AxEFPA1KOnPI~j%rUs4-Q{J1A5FV8t z88-ZS`Qn7P2j)AqeXR5qCl>D7Gt(#Zlyzk_?$maV;y^yTZ~WYx5FYizUe{;(Ts?P~ zy1dstaJS+kjwNTF`9$d}PVCZmM5a&vuIGxFd|SU_8}_JUGLI7;mA<-GAWg)9PowPd8PU=7dP2{{D>dob9)-?XDxk-j94alOtSN9pM@{!j<|? zaD;1kdhI*nzxQnH#9wgXvX5jLRm<6DZ&dbO@zzrJGIu_>PJ@nFI(BgkYv?ff(ej;a zTzK^6HW00MoSW^A8TR5mol0ME;3<4zTAMW3E@$n967Dj zvE~Bg1aLO%E-OIXa$~<`i@pem}U>_mThdUhVSZ zfY63-?dM|#m%ie}h-EH~^w}3)2(j$PgTwuw56myvZBRmZ)YJ4@cX()6Xt&)^h{X^2 zGkb(1+-VQoQ1n=Hv*x?bzBU}uWlosU+@@J)pC=xDG}y5n;;V)iQrM?y#JOTE;cGOb{!5e^}xa5zS#AEqz;E9F*?jGgmcCIp>9UV5@ zvoZhg`lAY8apKVqt($jyk7qOQy$-+Cd8^zT_HNaf-*oEegz%{Jn&F74kB0B)x+k+y zx5VcU$M3;{XYOj^Y!<&obbGe7|4-KWKdUu|DSQX#&Of8cSDd)_zr zEq>dR?RU>~K4ul5_iZEPTZY&SvqtOJ^anQHM5%(HyB?zU+jA z@Tl~aU%&AaVHJAro*jN*;VVvXHfz>dP3JA9d5oSB_TzPYcI4>^;Zc62#@z6e?+>?g z4L7XafNb{0ZJO`qo~-9XFBhE6n)SWYxytq~IF?*CBV5EDTOE74U)?1HXR~IV)pQo( ze(;;7umpdP_m4a$Aw0_7Lx@#hZVm%^uQon@U%zW8oZxI$>a3=-5Kr>_aAx@Jvw`^) zhi#D%9%X;orn53g=aqNzDQW-yyAaE+-W(?LI<|TDjD+wg z|BPY9pL=Mxzc{NczuB?fCcN6Vd4sF34M#3Lr_}Yj&T2ZlJ@a|z`0rxSO(o9@|G9nm z_rs0(=JyrJRk$64OU`o5I@{^2S68>>@FU1-keS$I<`&-yU&p@D(TQ3v!_s_q_gM-n$X1;AX}hz^Lth*b7T*3C#JE5A5B(ty>v>~B zc$EK!@|}+lH`DjpwflI#7Ac)bU&q@g9254Z`nunjQ-ZHJ!Tox?Z`b`hvl^G^AKG9E z&0X`Bgz%{Ew-^_{wLk8{HF4dfUylx_KrDO5l;A5)OgOEveD|Y~VZjQ|L5$q+r0@$p z+XoDpm=GRCwjgE=be1Lu@bP=u*AuZbPYU6JaTCh?uCd|vwyQMHJ?GJKF8Af%9MGoO zuIHK|uKYZE1>)s@b`QSd1lK&Ju6=Z^QdgHxUOjZiSns*%X$j#`Gp`vQ?}X=H`WC;{ zDnmPkGq%BMylY7C6(_jniPt{5R$*T1atDOj9CtTZ@`i-)sPvVeGyKwJ8D`1$(%<27}cvo>$;H?>#1 zrhaVnrp;Wz#OqyMg)m`tr(W4PQ#gP8u(z&l7OgnJ^-o#dt3y2a?y=csZw%DLDvyw9%$eoyz~6T+h&@3vGqH;fId%~~JgjmJl13+PE5Ja};M zD6TidfuvkUkOZoJJ5s(^elD_G|SK#AZc9Hh`ng zE|1R)zT$-4K|-8d-4AZkr8yzesJh##ECqz+GJ^UQYAa4y#sXr`#s8Pfc>jSSAv|i` z6A!Kbgj~j^FFgx!!IZn2)*>_U`@bFwzTyN|7g=@h4Drl=S{J|b%De8=r0b4FD^6IB z17h23r(!?;9#^bADsm!53V)7cg#=LR-8}{Q+Jc(G$CGnx>a%En_QRtqgBjq)>fRbOc=xxpYPxF z$j^=WgmX{L{AYQT<;WneUw=^f6ZZ!H9(Qq=wEM82%+{nyC+n^_RCn0r@^_sT|NqT1 z2J`pmuNe8q{OPmc(rmc1g}KKe$8X)XGfmy>n=j`?IxcvPAZ{{79f z$}w+Z*Bm}B_=*$cVuQZ5%FWW>{_C-2fBu3aJKm5G9(6{aYlCu2qd$8EV$KeymA{bj zx@gq+;44m$;|)5NDCf&7FPVmj|FK^8>l4DGZd!eE*!jazVf4WtLJWEL%5vhW{5^Kr zF?`Z#v4(!Dj0vrGyr<-R6smjj@{3+?#NX=ZmZKmZ|M|Ld1V^}UckUZ}#R<;Jp~~q) z95v&{ay_o82W-(VAw0^m=Ma5b-B3>8z51!+ah_K%o#5&s=v%963Nl4|Vear-{nale zJjy>kb#+VejPBpbcrA9zfaG)K#5rB>3>O|hBD6k1ul)HPN0tTO+D^@l3E@%x8LO-7 zz1K2LIy?XSUtf3QtlUuL!b@d;t6X@wV9&1c-y8f_SIF%~tx=AAk>{`+xJ|}cIacp= zmgcP7pp2K!ple>&so~Ne#)WV|2Z((h?^wRV6PlJ>ty|_RPFSS@V&c}_%d4h0=D)n! zF(EvPGk-&s%YfKx)S+cZ?j| z61%_lSh*a;Vy(6+e8manT&ufO_UJyesa%uaYUtpFO-^{!C1G0pt(5P;|5&@Zyq)jI z-p?G?lgh$!l+&k}Ze_1}t9t#g!Snn%NC^N6) zm98o9AYXs1T!vS^_zzq9ds2ARNo)KRuHt<==s9)0Jh;@Ha_W-<^9R?yE_rufowhKj z^7me^r!s%v=z-kjiE@u;dG^kU;|gDKVs?jL!b4|X6~4Oad*0noUYT8f@-ns5BL*gf zM=8%5PQs+UVg;iy#3CXCxl0(ztu&TcPf8vCJ$F`medFRH~jqWP7M=39v7~-v;%+l z;_GhZ1p z6~o8Qr1lt(SE@xSGhgL0!Y7~pBmVovk*W!AzEitWcN0roF{@B!zRFp|%zRZ{j9GIX zOUN@o^yu2P)ZN5N@j`itIDrdY0PgMyJJFl6xp3nWp^MZ zwz$4LiqF-&zI{tyae^~{yaLcUo*Mm~6UuG5n|N@|lT`;^wBiKUBk_B#>j--2_Z(j~ zajxzB?%}1cIALdJh@od*Uryp~V)cg86T+kVcDXZb!kM$p@uMI%-RzojGRO9-A3d@3 z6({WM3^AQ^ZOOTIh33YD@F+XiLfCbpUmN(dUKt42G@zdv>cugb_E#LeP%?M z!*$}oF?z<<_rEljn{!M&@2yd#uQC+zwW;`j|t zERW&u@t?)6PY91vuY`_px*j6e*Yk+-Ti&Z{uD`zY6({Wa5u#nw;bkAL6L0OB5*{^Z z&B|jBdYQx z4Vd>+-Y=$eH?i_-^`);^Uq*v!Qo3iL;smkjK35hO>u#duw}r1bVI2?y-=3>aGf}AgXzh!-H9(|{T9^E zviUo|a5h-tl3UC3H)_lmn|4z|c$6QtarOD0Kauei+7=U%bCeU0w_345?|Q#|H{$Pc z#!45JUCwXJ@BjXagzzXo&ezqwwDE!Ei`O*fcfUHLIP|o`!Xpirg=Y@_F#GlE%fok9 z4i1}U?`54&Jt_YGgFm{L*Kz;!3(JA0^Tgimo+y09i9fF!8|GX*BrLn-I}pn+IHBAU zBX^Gg7k5QD zSH*sea-#q6C&SWvj0}S>7yz;9yA#Vh$N?<9ASFD?k3{5P`>j3E@%RIYhps+pop^*BkTee;l2h2mQS3XH<@f zcb-yg@Ka;nV%DEczT!lBcHZ}a*##2|^FiHrP0r39wOQMB<5~N-ee}$l9q-vT_6W~> zzG(6lC*C=7SIUn~yb(>}THL*8eX z5U1|(Qa1m>;o*eio`l%zk*USXUk}Xp9X2f?Jj%01+~b@vsTjs{CWe1kc>iAMgs#MO zMb33Ld*sES;&r|sb&EA8ghzRviD?BlPbjYBJNVkxvxBcVp<|(ri5$b&vq*X z>8v?=a51(gfAfEiQx$a4iW6y$Y(T49izz%o;H{2_g}P%e%XAc7e5d~9w5N*r@BND7 z%jHg8kS#WAaF~Aka9;W8`BTLlj?`z2=pTH=2_1WN4CcrR@iKS7?{K7UbzGl#RIaT! zvBV|c#{G8qx*tTpuD=#KJNLZu;)L)h^(d-Wk)B0}4F`8C)SYnG{-ZPRHncNmv#!^5 zb*?%g*H@ceSKK$ZF|YsQugq7RuroD8&x5`wb|ho z--{#Y<(za&-{31wc#kL7SMAm*4?n0ef8@q<62haXl*VgnRZg)7KHj3-zXLYM zU9{qauJ(1+&lw5g`o(*cH?G*2Z~vcB3E@#`R_*+eJ<3D>7?`j1&h^1poS>c>&v2@* za@}6vyPU)o*$10VNC=Ozt22mcj~`H8%y)2uHdB&ZpA$O&={(4J3u5ix`<5^9Js&db zriAb)yJm#wG+@7Scg};Ym%BB|SvsNfpU#7v=^(-@yOswnq-uHLq=fJ&@400zz}Sh! zPQ4oQ_jaY*+Va%8&e8P_S2Rh^nn`ATuP!#{8#VZn3xj8xozNYy?u5Ap;&b)TmYWsj zt8}DXw_-wglxLus1##<|#hULz{P(BKSDYX(7oV-p`Gq|iS3ILhXPj9BwoeF;TK4H{ zg6^YV?zAn$E}N`eFb^{ScEuMmUvXmQoXg@Kv+q}ieolT})9=6X{Pqv)6T+hoK7L%> zu@ShJv^}U&~SFXX-RE9W*}90w`)5-yIVaqvFyXW+BX~R#8vj9 zZtjGj3LbM=s$Ns!eS2bg4d1A%7w?@A9%a|45dYZZwz4bV+9m$AzhBp?JATp6rH3uv zP0$?=anz^d%IjM+<}JV3F(Ew4GxvPjXJ1{ux?W@c!Mv@KoW2vfchk3vdpY)a{_Fnb zhMYf+ermOZ@F=R_v2$J3YpxkCKdRh??_lvs3)ROLtvEpiK4zm-k>?Kbg_C(AH#Pc= zZp!Q)pjc-0>%)5A3<;NC^S0kJ6qw$(HJ0s8Y0NJ>dXC?jB!u0IK-fJ_LU@$j`#|jV z(V%h*s$@s@IVkfCw%wnV>P1&hM)h2JSZv|82%Y4O&FBZNZ&mT|pkRNr`+*##{WIs+TPf7@n^4v1dhigZ^oxAO2 z28~T}$WCnCac)@ur7OZdL!M`kuj;3l=kQ+Laow1N@F=SeKs-3ADBt89b?k!aUQsBV z7_#IG@fw)_ku?=UvWYPf$pO*3V0n2^UAV4pQ|f(oSqOK<$r(fQa5_FxQz41r9XdO z@6{!*X4(A}uj99kFDcgNE_K!lH`e=#6LuE{VRv^)&C8?gt`EZQAnSd_3A>wwu)EaE z36HY7R|vZkuJ;uu?5-HX?zS^0Jj(9dAv$l+Io_r2xaW*|Uva{6?+|-W{V-maZ2!&~ znG+tB9(TK~^IdV-o1D-08j<;m6Ux6;J>u*!>VT|#g3MiyC*Mm5kMd(aXU-w5L#Joy z9N6cc%)1K7Oho@j-TvN%$TOXOygfVqi^lxxaXpj%L?^tPl4o*U{%zLzKkTvd(1h?P zUBUd_HTmx5`(-VEY0P&Uxj^skq7^67&ddeJKAFA5r+vC5(0>V3tD56K*;<(s9;GWvy$)4=xgXqW z$LvG)*#5;c^^IDz;)L~xL-hLB_t}?Rk>A@Z=y}3_ldn;X&Q%_0= zkJ9yeRl$O|>975RK8Zh{(mV4NC)B&5tTXrN5Nn@xQP6eC`?n5F2#?YoMU_c~*yYGk zq20cXdGDtNWxnEscTMwLoE7d0`z=pZ|M7_l;Ze$ZR2gB8yU+D`B&_xgIm;ui$$Z6$ zv;%wU!pFj%Tqi!C`ZVtlDb(ys2)1MJrAy%T{$1Ky>TbFU%!ha{r-sW@ENKy;M%-^#?~6>%D$V z{P%)uH7LB&yD`6Z&=SE3k5VqC@<-X@3ZAw-k#6;mmOUbPr?q!r zyW3e;xAcd%hFAHNJpD!A*a4&~NLimw=-$7|g|o*`my8dqkcazd=_3-tqr4lNXEgqL zOSpmSt8Rz(3BKZl?)|G=ID4$T!=$hSpTuX@-6tVD%H3Y-YOh}xMv?35vD!Y#EB9V^ z?@8y$syhw|?{;Sz)V}SKZgnTpGtTYZhK8v;z4hWj>m`IoDc@67dwCs4jyOKt$2HvO z){DnXP;JEt-D_5LXNapl=ofCJ`Z{f=Tjet^>QMI1W$y&$$#^I49ae{U=O4Ex9luWK zK2XOJ?%&ws>qk3<3#l&s^!Akr;Zfev%=zPu4a2ikmtMT>@}zUw3Ec`IJ@lo?7ZU36^DkKc*4Ma z^C!mtzwv)h;dKn#b9S~FeHruD8XSDZ3G$*vE&EA-`=$?O&+|Q>`ouvA;ZeUYF)!|s z6-Tni^pWpp`N{ZE;ey~RPCVS)x*V`@NH}-k7>Jcl|0vsKFz1f}hbDwa4Q#Vy{GMNS zsLsx({d8Z};;VuAV;4-5{}ewz>OIyKcjfT9=Ls=u&3m%#`PLqO9?$8vo?Rz&$E9yA zcS;b4^tdIvg>Te_Q|Nm&!lS%1mwunS@6KBBt-a~$GWd!Ux*O8Bmir#|nD|qf&F8M@ zpo69*gh%OaNXIMgjvxlMS}9WnYu{6rOZvjS4_#Lf$CzuP3Hg-5wV!PK57pUk$WD)Zujca;xb@MbZ%|K;J;RVS$f zu&AnJ{&@@JuNFL<)su%Sc~Y!>b`ye1Q&Cm0Ao?$POLhg{j|KM?36Vto{k?&>;$L@X zTksw1bQ!LVtvErYsi-Pg5UcDoF6+2D(>D7|O$d*2XPm30RmW!?x26x^)fg{8)6~Xxw_t6>#U1PUvYw*bu?ns50D&1{fO*G zJJpbC$6a3ee?HtJyux+KJ9|$l@4exy@~(GAP*Iqz%6B~LtHy0k6U6vu>%(l0CAaM{ zsq_^ms7J+XA3Z~Z=i*$kdFa=QjPT^~3E@$%FScqq=Hko4@vrC^SjR8-TDB26nQiB0 zrQ6+PfumQVE-pI{^2#Uuu|#;B^ZCF-jw^k|2`V)42(Dg)y1D`TwGAhblj-`((1h?P zJD)?W@bdQIYjQI8es^=}D^AFy)0sgX3-s?Exp!EDD}cv3-JTF0b=;)Ja_|3+46iTy z9K<2#49iY^i;l({J}=yHccP z;^FPbhxyz=PH5k@l$EJFMJ&x|W$KJWr`Wns0F28)t{QD4QZgA~$Z;=ol zrR!W>?{eJ>vGbdB?Q^9+@%X8QuJEhey`It&kLP-7k7ZjRUVr_ua1>V=pAMhmhJEIQ zuJCoG&y_jENBzn$ohzBHw~bB+kFsnF#G{{-p(9uNt52MgJafPaUE%9WpKE!DIqOaj zBj|hWxz@CV@F;)27yUlJowXg$V93LSH>Q&}ju}DqRr+_^GM@a+@7StO*6<6xA2&SS z>#*;lPlUn$S6PEpiuuN)`6CP#RPl(G`emC2bqt9ncE?4-96EbEi zHwWUo!&`(~I6L3AV1tD4D1SZ&4%Tje6tn48Z_~D4(kbh`wN@qPY*0Vx+hQ_A&z%n~ zeZ>hKp(_s>;>7c=Dw^nk_)qU862habb`Q~F-TtxCu;sW93tw@9Yl)z{JC4N=);W+6 z9%VfU5Z0Yg_=*$OsQ~fh-yIMM;ZfF00de8&8DmF zz76HH)f)3&%UzxHIy;eeM{l-7UXECtY38e4mk=IBwk1~eRfVS~b*J9tZRB3}-FQOj zD^6Iy55$144=7LMSn}O6Qxd|XbiCDFk-7<}L9XAg)Uo93;-=D9oUnc$h@ZFLvs}PA zYW0;SC4@&!**6c9rwpai-9>O~4O6!3O)=> zIHCA9!E#%KiC({=_`qtNtU4V&}%ZbEk31v-F&>ZZY1g zUb{>x_S=;{vf0-pgh%O#Mmo={rj8lbG^)6ZJID^lUtIc%6Z8VaE+kd@>HS#phNf0z zab7&Dd*R0=KVDgX8N`~0u2Q^Ars#vWo==`T=mhsA@wm%b2x9IQZHjfs`@FKrFA3pM z{u?s!_WQ$%XCKDRXqhEXLv#YuH1=Pq-+?Cxv^b||#ohLhmU}0JN2Ra)jl+MaKjL?; z!smU{bmEk!vd(pb!st!jEOvXnIXi8oLE)Zx&BeN3&5!^8#q}R6xTbz^gRBdgyX{wA zIazU{&(qIGy6b@ZA%2+BGSeO(w0*P5f0jqxvHJIMkMYM(hS+AnKeDduF=e?Hg|9gA z&UOpp9@AT13(<3Ao4Ci|#iutp;ZcJ=Z4vbP#vG}q>7G9CiulSK4_~+Vtji&B_n`;3 zDjQ$w6@TttQ-3KQUiHfO|5toR)unsif2@8xeyhVa*fCjgVuQ;rjr0c1pR>p7-`^Ye z=(o=*3E@$1jJhlC@z*+EK}^5$^LoAV!|tTR-&UNs|N04WkKZQ01@YTU|BicX{bj3! z@F@Sw*416zdfE8yetPs~g|9fV@VrOj9v7dZr!>#{e${LneyiRaua^)W<$r&20OL07 zuD|(hAGR<047;Mc-uD|;UAcU>!^Pe8x%&6oOO;>0cu&3l|8B$D@a~>9?B4Er<)2-4 zVBsrHtUvYUdeKkb*An7|cfXB${5h~)LU`1|MRF85L4&u8sFV+k8Y9>9_61NGQt~N{l7i>?3sM7oLHgrKjR*am;K7SJ7>8m z^__X;@6O&WAw0@IWAuJJaA}j?-JwUXU!1?uMTOqQA@i0fSGclQq4%fle!mp`FU{ir z|L-x&@;c7FZd{YTwX2@7N3!C?Htjk_`hey1X@7adZgG#6Q#VNnkNW=nZ=1CDA%Ci> zzy1^bn)Da^{OWxRUvc7%ruj|!4eNGZ0^-5*zn`hs@yyxn62hZ)T4A5K#{r{Of;e@X zFJ@|w6~-M<_=*$vF1>x+W8X_yB)SJe8q`p_qsan(fd06Rs(w77x!4W?J5c3QT_?7tGjW= z3vrLF=j6#}*NM(Uj*ojRyTbSE@l*SUnsoHJZA#CC@F@QrV@U6@L7~r8-sZxlCz_Tk z^%>put$@u@@?Rg4&%-Md|LVv;E+uhydD^83(=BG$+^us|A zpERx=_n80rH3{KSJ&*e%zPs;D9ShOB|MrDGyYK(wxh7w6;@CN##63agSwRpO+9G z<)6^Hx~`o!j(fcH-3o=TIPuC)v*R8^_AJ=rfPrhrcXyp9)<_7C^3O3g`QY~Px7xSm znKOTXf2H`By6yaBo3byLEcLxRXT7?nwdbxF|NmR{|K^#1ZT@vY{H;1X``%1napHib zTSofAU1mYtGI;a2$K~g@PJWh0`KO0|hR^qndz`vupX77pMBko^#XUNFvM#T@!_9jZ z+wwPmw#QWo;Zgn>`}?!o(B{H=`y^%-mDz8V@#M(A_o(+3Cu~26$5w6|UwQFOmxS;r zdk^dBVOeYc_{!gZcn6+bzvz9hcf#HUh^uzrBJS}^~aLIuDb%+!MR;$ z>Im2Cyn`}dal)>gATD2TQoJJT^4As#;Zb(|2(jYH%fxs0!Fhc$Uva{&03i-MYQy;M z9(L?z3E@$8g$(i3>Zip$<~Qt<`HB;EB@1!-nWx1)emHZ(gzzZ;^zgKv_ik>|d$r0{ zyCb`d1;p=90{~GKLBC|UdUWeU(Br8tXy$HY6jvK{2HtoAvLU@$jCqm4>pk3VK zoHKi8zT$-4=|Qw9ZjE=4t$*1fAw0^z1>Dh37!vPNU-$QgmRTywtl#JJoM-Fv-OlN{|LAqU-}iae zUVH6neb#$@O+^X$tq!97uOEfI+xddZhR`lK{{Z6Q<~t^Q2Dcm9BGHNxas~m!!NV7Z zHNJm-S3_u*9-+8SzwT$@8LWI}dvok6A!kCchMbczgm&q1jPndvG)Q>t{^$6+GU@uA z9Df_M|DkJgb&p>XzQZjYePSYKim=Af>$`+AUYl!|WVE8hlz!_2{o5xufH+}Qy|Bi+ z^&T>WcF9>P5c||G410Ih)Q>Y-Q9{mTfmpS9=di}62}=#3U3&E3z2xeaVT~G9cSy9N zgq&f+8gj1B5Za~37|fUHNm!$1!Mj=cyQw^mRQ6$N_HI@yO30oD(QE57XbA0+XBNbD zO^*-fug0yOoYjgFb*}g$JcC_3Cm=f2KOpSgk-wg62<Ual@*U!Xw`> z<@&5vl=!B{c8U2Y)R+NzSKop~ceBm+bWfXU|Jc50B&P zHxI~YMG4t&SmWk~O~M)U`b1^Bdplc>Ok?1KEdo&X258*?;r_l7_cF(S4Ow;<_F;2YTtW??5bD z*CniR)mftrp^eIgYp8{F3r< z^nb2yq7^0Njz=Kg+&vT4C_TBa?pw65&A-}aQtZ~AuZu+io23h50t;u8-IM?^#M`4Xm&l!-&d%GdVoN!WjK5ji>7msfl%bSEXx=wjZ-`i8|l6P=C z^4p$Y8P*uH<79oOHblGPqOit!KOTTJI`6VaSfk(AU-er?s$KFe18dAE$%ZvH^_i#N z84S^KVDqrXE+@9f8nc@26xJAzbL#rHv`fBAV2$Rx%?NAE`p+``&X6kc?PayX8n0IG ziZw2twJyuo$Fb=?hR`ngmI0zqogrb3K7&{5cLuM7ep-zT*VuGNC;gS`wM%}BVvUv`?vQYen+E@;zc~$|o(>ZCvo8;84EQ=Rgm%fV zRIG8vl^w$xkG`@&e{_@7E zHFy?3xIC;e_JihzFkM^Emtc*zUl|wHxZsqx^z28f#8X8LJfHJPRXXF57hSp`ta0~K znCdQnOS|N38`ijU^%G%@xBpzIXYNuZjyUY_u*RD255gLITwE>TbKc|R>W0uRIopOc z{(Jr6utv$INA=8IszlSNM~5}8=}CvTL&H788ZUnRlb*RtwM)*=VT~qT-wA6J-8m}J ziV|{FD2V<~Hw|mN_3Z0<=1#92&C6Iy_xU2M@vq&kPUM`PA>`UotWo>>)?p1d`e8kD zXPi+v;|*fP>>t7!6Q6FYXUPpA*N%diJR=jM${xp>>;IjVy=Vw|ObHBy-krna*#3(3n&V`&OP+HOFJARWcs>eNey?W z`|fvLyQKQJv`c;)fLQRz>tT($du&OyqJ(^h2eG`R%kpv5-L-=uv`c>DfH?T-Mkzm| z9^31u)Ks?q<}g?078GnbdvI8z);{eGA-{2){8qyn!_)J^8kvW_NwuPc{0akcQuAlR z8Y@Q~YzXa=-<)`zSKEAdSYyM-Yf`N!A-@f=#+J)I2y5Io@&H3D-%N}#$r%f*(ayaZ*0`<86g|t4C?RJlu*Q3bH4JNXZ?{&j%uKXP&dFenTkiWXtkH46 zKs{G%2stMM;+(0i!W#2$@p?u$(JncI1me&)z6)zy-RZPcD@w?@B@kasY8%#QS!cAK z5!O4{C321oM5lQ_hc(6w*fZ6N{#`kj1>(Lc#bJ#-3s1-@plxvU5^_!s#9IqGhc)KD^+}2TE$!0tj5wdTu~Jy$+AFJMwW5TcTg2S(r*84d<$a0= z-}*K0+>*OT3TW6a~aj1TVcQ#v89h_E_km(2@_I#m3SmUkz4mE^!$txJd&P~n>YuwcTT&EQ!WO4zBhkLaMYixPq zC_`wMyc2=g6dCDWZ&l(2WYT~_pLT6$@p;)crxm^(pp zE)tJj-qlDx6R}nOASZ6$6&Brbn4+=uv(GDG?=W6}-gPODtJULs8$!F}lNxIbUVnAU zL1t{GQ<&x3BMK2ulW7I_>B5J~cX-R=)LPtDb08-<^fy>i#naIISol_iX^NZhkGteRb3;XBk4f z7(%<`*CdEBNBt+P@!zM8aavJAY-teRRXshdv8K`PhR`ngRgBN5X^-{~ zYh3qx3#Sz}4~2MrwLmf-zr+&Q}&Lc8qU#g0B?x;qEP`fjV+hI_#0?mMQ0y(`yP z*WVq3&)PO=iMdOf-hEBZYv6I5*>{Bd^mxpDJz&0`zu*M8zwXzj_i@7~&J(wVebwUA zL59#SIopCYcJDMk?5kbJ+@t4VQYFNY260f|eqoKzyX|fW?UJ)mSzLR5?8LCfgvQ$? zT2VshiNpGRr+--E%h_uSmC!Ev|M6{U<^Gex8jnpISfUjrE zn{!#%yDKJyHU2!gQ7U^e(Z4H?DZxEbcIX=($9cFCT?y@y=N!ZzN8KCNnD*KPJ+rA3 z+7o$hK>S=Z)=kE-TT~}&2<@`w{p!1(bX_q6^q7NJr&>|M8teUz>+K%vf!~~G{$}nV zp!b82R~okJ+BfcSd*MBC`f0ViR+Ny}io+wXeqPvD3zJ<8peiT&0`WiW2hP1)|luHerpyNn!}?l6Pv$a^q|_b+Y`)>wYkNruoa`6L2S>(9@VukdYY-n+Nc$o=bnM0#$? z-Vx}HkG@Jy>xT&yyZ7)~QNpfq;)(U$=40`x*6R*KXqS9mVXLw;TZcz}VeP)=K1E9C zW5Qj`aSzk0aW|{ij+$r)?b5p{;jXyC*4uDIcEqZ|4L(T-~<+q3)!^aUc3McN#*w^zKl|it5yL4RN>7KhL?)+yzPr zOe+af&N*$cpkQW;O-aiM@VxHnUMIaX*;98A+$?=ErA%c=a%pr z=latpdaWoSzmP!G!=+u^SKqzV*AS*_>#sf#%U&B4eyfe|K3;z*>eMEk5(VP17PHfN z_^hqE6Yf1Ne@lMdg}d8qz30Hr@2^b1#$9fD?ljly-3XMhuKqhM*QICS*lqUA&F0<- zdQS%V6^^Yc=~>-x!1u&Og?H+8E8#9pxw|;X?`RNJr&jUYSAXn%ks-88&L)6(s<4IU zbN<>_{q_1Ar-Ymj0P$(JeZv|PO1c?ByX340h>Hu332XfN-haGSl#ufpAd(l32x~lj zWyTQNC1-a)ob^+Wu*Ug!oZ+>igq)uNv0}#YVU13G8W}>n|d88$!F}Y#Y8`t)Fz4?~LbT;o?2@3|*oG?*$ltmtc)|cJAkQys%Gk zwLzQpinc_%XE9`setqlL_(rBb*)Nc@sT8Vzfka-hWqiy59;gQ$4;&el3m!7}G`NW+kguVM}|E_u!V@3&?n}Ic+`oI2RjlpL= zoz=gkUG}`_QNK?NYkYKUPjfY<68+57=^<~Ht#Mt?DjEG-+9hk_SJB3_Y>n)hPiM5E zgshk1JoV-M!sB@8^Su)#v`h9ni1jDj7am9VORm&sDpf-E8;F-XjPRx1;Me{%!w}k~ zGiKoGkDTdi*1%`&rj?0Sl)$fya3u0f3%>PDd@#G}Ps{}v*DZ7PZ%xAV!*tY2f8#-W zhJRoF#}9ts_`Qoxx$s{1>Yd9xuDU;PP&#HKK5=$;iB^=T_rb13ynE8wi&ld8?9#8& zFIM#_-s|%zhS086ztjrEcR#)WVpWrVejvWd+|sb4d#~>It_JSkJn6@|{+WklD=5W|a``QM(v^Kr&nLui*h+Bd$vhxaM+s7qHST2bPowzY~5d3u~{eH&jN zm*KuAufKyckeACa(T`xxc^upgzUVKGDUzKITibpw5IBh1H{bDSZx>-d3RxhH=Z`R;q-C>e2*(~1(mU;n8acKs;VWZY~JGuz(n->ZX9wbxEHgz4J!sr$Y6DA)a2 z636c_*zZ`qPw|mAW16j0l(=`@hwj5>qukNMpX3^!4feb5goz06onr{?`r(of+zC65 za_{U;;-bBW`WtbVwAP)@cUn>6tk`pT7Xx9LR}7(%mBY@~btK;9|+@c)kSO&4RD`CE6o z4PQOwZrO2|JF3Y8zV}n}T;pShxt^OI@Lz14>mF)5%pJGj0T7e78|w$Zh&xCAJkV)H ziJSj?)*XEBF!$rP(?K*#$M|tC^e(=v&0U6Q@ZD2xHP*Yn*#lnJM*2EpjDH)y=-tA* z%vLFJ`WH{SnyZGoDI=$0jgPM!^!X7~c^@ySjH9Lc88RXO=tSj-jsVAQH#CHrl_tuy^sv zx8LowqQvv7A9Eva8tOJ(Oyb@N3|Lgm`CB~dR%8vrE=d{62 zD@vTde1 zu;f9v<@F(M$J0nWzG`GxV`=jthS07(w|~&pSvbT!v?q!0A0O#QV~tg(4slvhV%Xy8 z?)Z`+ZempuGp-xy9{@4vZcAv_iBlhNL#7OIb>?zn;cJJD^z%V{j#agygfE@ue!FLg zd*K=q)4mzu-vRN$AC}OrKFKs!r_T^K;CK?Hb4U0eL9}i$)M-VDH?vdS1=kI6XEq_R zPAd_mcNA~+r83#i2LTfN!}9o zRvY1ag7|a#P^T3o{=l@FE?tJW-ov@Z6(0}x13@%fUc6(uGfI@#^qaER;PfJEKG;l3V-&P^?$UAxqr?CLid;#Sll@oJsnz7WJ4$uOrC zB^uA3ksM_S?W+IWBv-8-UJbvJ`1ZSD{z4G5PZ{R4qQvF@ zndEM)F~lufOXA5-hWUSkSbdfyv}^whCSkVo5LfAA5+ha)^L;>^eDN@+6(ycHXp)<} z(-61r4H9oG9Oj3ED7wND+SO`@N$!U#L)_j=NTf4|`A0wuziF7$iW2P}pXk2+W3a=2 zLG;*btncws@8Wtl4Rre1x694Xx~2CFb9XGB?(OH`m^NemyGwc(514s}(~1%kJCwMy zULNMAkA4tq)GHqATjM%M)mCLw4y}!d!KiQjKICiE6oIP{oMYrqg!}+NPqSxbN{3y(|JaDJm4WV6? zzkbmzet)>z;WrXbP8j1aK*qAmrMEe)D6!YKFS_?ZbohnD@EgYXxtN0S$R)QLLc4xF zaH+eX)(H2+bj%1TIPRP=ei81Ix@ycVPAf`GZnD%pSaXCsX$px-zl`?ZuEr;4@lA%% zuDR`AcFX@W!d>$EBOopwKia>AJFE6-6GfPMohHsQ=|078H-%@-{aitHENV% z=KTdL(}(eUaKmqVIISpw^CaOusrbDJV#WRo(j#BOy$wIu)ezcs$$l@oHtWW@nLE`5 z(O~~+)R06gO5o@SYheFjjf2w1(-k1=s_cTjd;Q@X(}Nzuyt~g1aavL0m4&757o7LmsXmY0+COhehfcyB zdwqLDXxH2qOI`1^W8L$$Nj&mlW&eNU`xKAA)H$svQS-r4_x`72-4knf0#X0Uo&2U@ zeTr9|exxC^>wwi+ciG8f-C4D&fVi{gZvMJEkS;Ad!D&T_`yR-;Qnj@f7$pm-0WQ?7R|sE*4iVSPnKe< zzWw+b-v-|R-hXd|A++o9=`-Dq4-R)tN*9CpbIff%#kZwj){k~tQDVXmGu=I_hr4H1 zy$IseL+`q<8; zJAbo}V=D9WublMv>Wx=qnaVugXnLX*C3*~BlQ5N;aq~eSO1@l~Wh(Pg^_`s(+EsO2 zweT5rQ=3*Gc0HqA%2cNL#3}CHqL~R(nGTo|I^ohe2~(MwPt_~!-gH*NROZm*_*wh* z#&#)FnUl9nbXrlO==hR^smvq&cL(uf2Ut!>WtQJO-f2aNnirNPOl6L~Vh<3_-fEXJ zmFf1=XhUdMgR7S&Ol8i=@_WgM;&v%hnVTn%a9UB~yR()jOl7t-;>5zWHyx2Om8pL8 zU_)qE{c-pvg?c1bGWv**6$Z1#GQ~sMUm3i%h2Bntx{G`??Q<+I4`a7*C z@$>PYBur(}@eQ#?TIZ0Ismy0}dmBQ#I{VKOrZNLs?GIvbl><|zGJABt)@enF_D8Kt zn93|Zr4fi_tD2=uWuEADxgoUcnmaZmOl5}EYYgJ)mQ7NoGT*;-vD1nYji+o#n98iG zOQLqQ#wk;ok50bG5ZdL}ZcLcU>~JZGHt+7APMM4=8mFA=w4y}ij=v^MWxm~ovopWA zr+&&*=Hcqc7(%=3(O&R!^^~d1&3hf;w4y|_y?1g<~689_wDabn96)t zlfMoAHL*>~RA&B;4;ezc4y-pRVJh?cq?#Zmu40%{A@#L*HI6Q>HQpESqNt z?OI#hD`6`0@t^!=`Qe0yDN~t(cb{=uQR1y#FHV@s{QCWlAjaHwf0n7thhvty?&r+O zFqNrx!+L+#jHMZ-GSjzg^lc|UpJ6I9`IL?LjGEW#(JWJ$?e<*iw4%i2yL_5qDs%Am zn?dxddS8~Q%&|)>F|FsE3{#o6ZeH(oZG4B@G$PAX=JIOG%vLE;?VtxTOl5YSwhn9D z(QR;+sZ8U;EumfK)tHoFDs%O>-+}mf*8y3kGTp9R=Cq>3)tg6Vn96io`Yni+=iQiP zD&xjmLc7jfJTSvl=ItKefVh3)Wm%>&7x`sQD@wdk+AqUY=H~Ce2Ju7jnOUYXhpn}Q zcHOb@{0vi>_V4ny+M9QD&N7vGx5{#-6(xSUzf*>(%%|=P5H0ULEX!18xBV=kT^Gze zCc{+b@-ZappU^bRRA!e}%biw~IOyEg8KyE5x_u7f+Wi`4naUi}db!iCqDxz6n9AIC z^5@-*jI&M=i(UX4WO zN2_L;%2amComP~1_NST|rZP|7^cjc&;|szXUGfO+n(|_m3{#n(U;Grr9*1o#VJfpU zS?;u=#Fq;yWthqwJ%q%BOFt+HsZ4uIXxA-2eo)9%rb)j~Kr}jiSqW2_A%`t@T2bQs zsm~WOmAPT=#~^Nf?Wq!`GJ{)MLc4~YH>Z%P%qaB}`=s_OOI@^?GSwAyb*#fBF!_pQU|Dn95Y!ZMoB~NelZGGL?Doy$`)5 zY9D`g2~(L(m6kiLC~^3-PK8Wm+OOlUqPYz_mN1p6{_`?JXjk|1TNg5wnK_5V+gs|F zFqJv;bG(;GMTvq%l?s{4yjqDw^B1a=FqL`beM@N9cP~{bWGa){jl}X5@6Bf_v-tI8 z&Q#>@&Ybpqd!{nu2fq)Z`f1P4XDV~n3QK6$vh(M(XDYMuN)qelkDt#}rf}ghrxhg* zU(~NXQ<)xhNh~_~&iPDb8f7h^T?Z~1*q*7(eS4GWHmLi2rZR`jTjsQ)#HZ6bwPz}G z^m}VST=8|M`AlUd&$fhiRl1;cd!{lMuORVY-96?rmAUQFWlk$fbX!!ZJyV$jr;yma z`o`y&%FLQ!3GHfd!JKwXWe&WB#Pt6Re2%Hi*^`$!ttbKi_#vh;o12l?>)Y8`rZVZu zB~Cy4y08Br!&JuIy~*3p!7g31S*9{Cp18zmMTyHYn=(vg-mUdB))+PTg)CECdR*+e{fWh(Q`=obv3UDvkSKVd4*VL1R+KpY^5zLsnFfKlc3DBnRHp5k zMTXF>8+x`*n97{ilV|R__NtsRl_~AL$Z181=I69dn9AIJ5efIj4k=TaZ~kwgA+&4O zJ4eoqadUH03nd#PT^ zROY37vQ8^XJh$=ugsIGqz4(21=iT;6naa4@^9`Y0`pp@4x*b_JVJdUhgPmNhh6SFf z%&ylqD?NPjcAlxs)m2-Ru3b{uGnM&vN^`6+y7R6HQ<+l_JHly23H(m0) z=f@eG>q&EGhj7-&^WQvcRJ;(^r6ZMj?e4=teE8X28KyGVt(}@^Mc326glV*U_Rlbt zx&FnM6Rjv=x2pNXg@sHrUOud=A++nMum2Oa_Sv*EwyMkb`(>EQ?Adosq7^0Tjcp$u zdC#Bt$Y(F>S;$moL*0`MVY~Xy;9huWViyn-x?WYtRAx%&)d}wF`Bx>M;NE>_`XL}( ztE%nzI3AjIf+0xfy0Eq3oLt%CICojk5~ea&c6gs#C6%oN)(hw1${t76;U||cmGRBO z)&^-9Ye+pc2?`VU4n*cW@zNtnvK|I8^)D@x3mvLR(EvpJmi`L_E3 z2~(NV{(GJww5wyE4JlKZ3j?ufNaKX5%&41sIISr0?7QnzrZS&@$@5ohuWg<%l{x;I ze;Y!(>Rk1H%2ejG0sDa%@Ib4Csm#*JH#)5-QQUY<%2cMfHHn+MwoaJJ+r$F@nB${bc}kRh~db-$G< zQ<;0tB(e9CMH5S!m_moSxive5*$;n`U!Ql{x70>ZRAeFe7CubKl#wOK;oh&XlRl&-e1&()=ce zB}`@B*kPvAiW0gu?k96(>x8LH_h}CsLc2b^cv8w#X4Vrt4>zPs+k~miB`4nRw4#K4 z9PYOx5~ea$I!rNycD*-pX3A9N@WMJ+#t_;?M~0~k%oq@KWSGjpnF;nx zuA&4T8KyGuT(Ga`$S{?GGh+ztq9emp2A&HDIx1$1PX%D|a1uMavhOl4rec-m;WR~mi^!;xVs182s(29=;A!&C-t z3yyX=GE8OQ%oswu=*TdYff)mWjto;7I5WYX$yJn~Bg0e%ZVL!HGE8OQ%oswu=*TdY zff)mWjto;7I5WYX$yJn~Bg0e%ZVL!HGE8OQ%oswu=*TdYff)mWjto;7I5WYX$yJn~ zBg0e%ZVL!HGE8OQ%oswu=*TdYff)mWjto;7I5WYX$yJn~Bg0e%ZVL!HGE8OQ%oswu z=*TdY!S#J0=*TdYfin~AnOsE)Ix6rHx3*brZRA5 z%vLEuM~0~k+!m}sM~0~koEbxC7abXn9AU4f2=`AhN%pknM5l}@H`36m+;pgz5&3IVJZV>#t_;?M~0~kyb};~WSGjp znMt&w1RWW!QD#BVkzpzWXC}k5LOeUfb3Qy<#DDYb5gi$(GB9JX1|1ouGH_-v^L%SX z*VDg*X;5%vn99JJp=t5g8cNu$q9emJ1I~=uD(#{p!!0axOz6lkm4P!uW8|-j5_Dwv z$jclPIx|{al0V;*LOYWSGjpnK6WR=~=vj0y;8GW#G)vMEdKDpb|Vf zxCZwhuD^mK!&C;&j3Km3&-=l_f+NFJ2F{Fmedv)N92ulCFk^6B(UD;)17{}DiV}2W zn99Iy0YOKGsZ8ykw-`dZ=*TdYff)mWjto;7I5WYX$yJn~Bg0e%ZVL!HGE8OQ%oswu z=*TdYff)mWjto;7I5WYX$yJn~Bg0e%ZVT6dBg0e%&Ws_ni;fIa8JIC3=*TdYfin~A znOsE)IxzQyKUk zo{kJt85l60jto;7m@!y`jto;7I5WYX$yJn~pOae~^H|`>FqMHbV+ie{Bg0e%W(?M# zBg0e%&P=dpaup@)$& zhN%p$zQ-DLWSGjpnaOBH2|6--r$#D{yQI;PVJZV>#t_=YYd%QuS`C~Lh9kpN2F^@E zM~3H$aV39BM~0~ke3q1s46_%QF<66+3{x36Gl^D|pd-WV1!fEgIxEPwM~0~koS8%`O3;yEDg(C#1RWWsGH_-Lp?pnUKmy(_fNE<1RWWsGH_c!(2-#(182q%+GUS+ zIxGOBg0$-)(QwZGE8OQ%oswu=*Td8ff)mWjto;7I5QcoC_zVtNeVm{ z5Oidi%D|b)XcrwBrZO;KvX-DD!&C;&Ohzk8(2-#(1Gfch(2-$c0%yh$+C@i(*$d1V z5Oidi%D|b)XhjJ+GE8OQwt%1`!!_W{7(%<~$S`|>83Tfj3{x36Glg1Ff{qMR8MrMV z2EmbGDg$T65ZXmYhS>|um=gS&fFr|H2F^^OR+OM4!&C-t3kW(gOl9EA7(%<~$S`|> z83Tfj3{x36Glg1Ff{qN66nHKm=*TdYfiq(W?V=;YBn6%e2s$!MW#G&dY8M?DrZO;K zN-RM~hN%pknL@27K}UwE4BQs1K}UwE44fH5XcrwBW-l;fK+ut4Dg$SxP%BE%kzpzW z8wLa&8KyFDW(=WSbYz&lz>EPwM~0~koSF7oQG$*PQyI7|^Krj$I5JFS;LI38yXeR; zdx04Pf{qMR88|cTwW0(a8KyFDTR_l}VJZV>#t_;?M~2x8%oq@KWSGjpnQ5;TCFsa7 zm4Vv=f{qMR88|bB&@MVM;SOdOv<5*(hN%pknf6*yf{qMR8MrMV=*TdYfiu%i3GJdI z!|VlS%yR_=bYz&yz?o^M6(#7%FqOgGVVmG;bvQCiW#G(Y^s|qS3{x2xFj@OKNJoaL z44j#aR+OM4!&C-t3*H&%$S{?GGh+ztq9eoX1!fGtGr*ByD)Zp@mor*Xf{qMR8MrMV z=*TdYfiq(W?V=;Y>;+~F2s$!MW#G(Yw4wwZ8KyEYRY1^@VJZV>#t_;?M~2x8%oq@K zWSGjpnaOBH2|6;&USP(6pd-Un2F^@ID@xFjVJZW+1q2-#rZRA5453|gWSG6ca{)m| zhN%pknT%GHpd-Un25t)oIxtNrorKu3nD44j#i_Drrqt0qUt zuRaiTWSGjpnK6WR(UD;)1MdU`9T}!FaAvYvQG)gZ&&kkpz#4F5n99JJDUowMiJUbG zjto;7m@!y`jto;7I5Sz=Gr5Ycr+*3d85|j=GH_rbH`B z(2?O9NEsRH0y72#9T}!FaAs1i zC_zVtsSMl}5Oidi%D|a1gm&EnM~2x8%oq@KWSGjpnZdl}traEc$S{?GsRDwI3{x36 zGltMEIx@^&V8(!;Bg0e%&P=KmCFsa7dx3ocf{qMR88|bkR+OM4!&C+~3!^88|a39T_GH@I4Yb zGE8M)z$A2Jn7zP^!5VaAn99JJNwuPcu8lij!jWMr182q%+C@i(*$d1VtU*VHsSKQ% zR4Yo@$3aJisSKPMLueNr8D=jqW3UDt8KyFDW>T#vVfQW_8KyFDX3XQDBg0e%227&+ z5a0UX$S{?GGh_Cy5_Dvk%D`>GR?(4RDg$T65ZXmYhS>|u7!Y)1n99JJ$!bLjIxH1WlS;mt3O(f{qMR88|bXb`h@N$CdoSk%@ClBoGatCq68h8I9CP)9T}!FaApjlU36ra%D|ZcK}UwE44j!%D@xFjiF0K@ z(2-#(182q%+GUS+Ix+1_T|MI9J9H z+C@i(sSK{~13^b7&Xw_6QG$*PQyE-!2!f6bQyDljo{kJt8F(wfkzpzW112~!Ol9EA zfS@B2=gN56Gr0<_njAq#hN%p$6$U{^hN%pk8AH&KiF0LwpOafV%#{hL44fIWRZ7s2 ziF0MJ1|1ouGH_-Lp_?hN%pk z8AE6n9T}!FaArWzk%@ChKUKB8AE6n9T}!FaArWzk%@Cw`Lc8e5 zFqMHb1A>lBoGatCq68forZR9_K+utib7c&nU36ra%D|ZcK}ROemGN3pf{sj_D+7X# z3{x36GltMEIx+ z#%mWH8KyEYV1iY%m7pWTR0hrrC(iu!x0IkG6X(ic4LUMRW#G&hLc8e5FqMHb1A>lB zoGatCq6Fr@l({lpNYIgqb7c&nU36ra%D|ZcK}ROemGN3pf{sj_D+7X#3{x36GltME zIxlBoGW7p?V=;YR0hrr2s$!x zu8h};5_DwZTp18_Wa3;ILui-%_DV-4&Xw_6QG$+4oGXJh=*YymGKSDD{pK9z%7iHf~);+~F2s$!xu1u;GT~Gf~m@5-f88|bk zR+O+?MMs8d2Aml~XqT8I*eW_Qajs0N6(z(40YOKGsSKPMLui*6F(By3FqMHblWIi? zaawR((UIZffHPwV?Gm#G1Ra?;S0>ep65{57pd%CK${0es^ekSOD-%)~I5VkMln}=V zYtWI2b7c&nU3%Ux%#{guFoQE=ULSho2S=uCt_=1r9ho>+#%o0hIx=yt42arrWSGjp znK6WR(UD;)17`*V9ho>+#%o0hIx=yt3+#?z5uDg(bHI5KgrjMKHlT$zx{ zz?tDpl;C;5_Xv(moGTL?8KyFDX0QewnK)O*)1JvyXw~EhT|3N`38@U68AE6n9T}!F zaAvRu9T}!FaAv$#l(3J3jto;7I5UROE;=$yW#G(U4LUM$u8h};5_a#>k%@C<%;TUV z6X(hV&xpwu_hFbT6H*yCGiL89K}ROel>tFVhN%pk8AE6n9T}!FaArWzk%@CR;wT*+TVM}`>-e3l|QGR$6J#(EPwM<&jd@mf)Wj!c{@1A>lBoGW7p?V=;YR0d`Y2s$!xu8h};5_Dvk z%D{60K}UwE44fH5XcrwBW-RbrK+ut4Dg$T6YZo1vI9H~~5_DwZTp6zwCFsb+xiVOT zjto;7I5UROE;=$yWnjjDpd%CK%6P3PK}ROel>tFVhN%pk8AE6n9T}!FFk?W_k%@C< zyjGN;BNOM!fWTatgsBXi8AE6n9T}!FJ6y^&=*TdYfivT^q68h8I9CP)9T}!FaApjl zUG`|FBg0e%&WzWJ5_DwZTp6rEM<&jdF@$#MD=o~GN#a}?^ZKA86X(hl=_@VFl}X}U z8S@%cf{qMR8MrOjDmpT8u8bkHi;fIa8JIC3=*YymGF~f6(2#t_;? zM~2x8%oq@KWa3;IuN5We$i%raAn3@%xiW^(E;=$yWnjjDpd%CK%HY#^Yefk1y=zFM~2x8%ouz|(UFOBWjJvro2$^O z$q{s9cs2@G1cRU>!&C;&j3MaA#JMuT&&jPF=E`K^Tp6=fO3;ysb7imw9T}!FaApjl zU36ra%D{{PK}UwE44fIS6(#7%#JMsc=*YymGKSDDIx=yt3+1_T`$t^sGp5ZXmYhN%q97!Y)1;#?W86(#7% z#JMsc=*YymGKSDDIx)%p>j!c{@gEi>LFqMHbV+ie{Bg0e%W(){AGI6eq*NPH!Wa3;I5OieXTp2@X7abX< zGB9I6(2#%o0hUKJhZ%7CCF6X(i!{p_P7 z6X(hVS9I&=ARU=FSH|lnq!M&w;#?W5K}ROel`({N(UD;)12YB$9T}!FaAv$#l%OLM z=gNSfBg0e%&Ws_ni;fIa8JIC3=*YymGF~f6(2`Ix ztNpPC9T~bZaAv$#l)&#q$1^N&TR_l}iF0KPplBoGX)RMc3266z0lg<6N0kD@xd{q9emJ1I~;g zv`eP0V5{iJ#JMu5R+NyrDIn;`FqMHbV+h;zQ4{V3crGC5$S{?GGn3+a)4wW~SlEQm zAlw!ZbY%EA;LI2Tj?!OU*xHn9z>EPwM<&jd;Z{jyD}nXGc{sQ&An3@%xiW^(E+1_T|MI9J9H z+C@i(sSL~*5Oidi%D|cNT2TV?Uy?Xi1_T`$rZRA5453|gWSGjpi~&JMhN%pk8Lt&3 z=*YymG9c*4#JMtt&@MVMOl4rkfS@B2=gN4kC_zUi&XoZ{M~0~koEbxC7abXuhq*H8sC~j*8AE6n9T}!FFk`R=9T}!FaAv$#l(3J3jto;7I5UROE;=$yWnji& z4LUM$u8h};5_a#>k%@C<%;TUV6X(hl={^i|WzslT#_U}~z>$e_Ww2FrWSGjpnK1-S znp_th8KyEYV?fZ6iF0MVR+OM46X(i+pd%CK${50S>2HJctDUw0)@4Djt7|O4b^1m4 zobb3_!aelEZsFhW;EpKq|K~kS@m=(=+NT7f{|U8nM5ri%G(6B{uFSX9y9HveA@vNQ zUC7c&@E)dE@82;Y|YU(Em5*e(#KR62BlR>~oK8Np6IA0(BC z{|;T;8tyCpm4X6p4GC_YR>~oK8L<(Mm<0EL67k=mi+h!8aBtvO5%wwx?q#i%L-;bH z%2|5^;@dyE8Y0r6i^mh!;PHiD!t-kfqG_Fz7igs%!j}${^am*``_}v%R8R7X*LMwXY+oN3xT?6+sE#mw+T&rQ$vuo(zRf5-J#5&Ska>hw z$|0C!=MlUbB;F@AT(uGJXBw_{!QSN+D|v+O6Wv$w-{lZmQG!>y#QVVJt)YZ=>DJn# zgjby8wmpk0L*hMCxA8c14JCM$NW6dQHnvK;;uiACn><1*O5mQUj^8+N&(v)Y+7%x; zue`}4w4wyBH;MO2-3FmuaUb%^n>->OSK;`Vu60WZJ-$$YnaSQ$5AGsd8 z+7)SD36r-~T2UhIX^$&Nwn1o@?ge{XX+?>6#PFJ0!E8Wj=Rg;_Zc36_Tklt<8bz&UnLw+FL19L|_~cn7(EbN)vj zff+0g$%uzv5_}RQ7#<$THnvK)ga%3;;bC~>t)WExcj%(`!K4B1MjoLRCF0|Y?vn1S z_-Ml;)JI+mhDDr8lD7seAm&c6cN`|_xHy9+TtSX=mb`8}kKncCxr!3>qL{?-*|g7~ z657RU&T*EL*Nx{9T2Ue%J)DWO4MMwk%{k6;^1AUnLieKXUEPQFacD(}_&m|R$y-AS z?b0LEuA$qjkAv5><4h{AP0w3HD@w%I2WM1mgU~Ks*N!u(yf!_L(25e6iRI#~t!)t6 z#p~K}CY9Hw=Mgj`k+{=tbeQMmke_?FivRF6s6<@P!$QnkBR*@KedM&O;`fqx^o94R zc(i-ibpLRxl!&i1&sUm#&ULG_OW&0&p|4tfbwz?Rs`A#*iW0O@kblr9*#@Cq@!gIy zs`3b}C_$?RIS$R3Z4la}d&E9+ttdfD7I_p6pS(4c&@MgR>>Bai(!(Qjn2F?&RC@Sc zx$nN=zn0K%$Vy<^kwXUQVRGed6=oEd*c>*7-IkMkt;!m45_7u`<1sSuFr?k`uHrN6(!<&?(bWrgm&rk zWY_4`ZlUYdYMeh{#4bhp`?K|pi(IWs#`(hv$!$Dx&Yj0GYdC7k=3w}x(Sd~fIUvT&D$|NY37h@U>3 zOP05W?knxWBvgm%6Fu(okVj}miTEkXxny}ndOb69O2oA}_cd<~-MiYQ z&y#&VbieanCA>No_ZazyTcrdh1-m#~cpF=#UHZOK?pB5O41F(&>v?XWCA6Xh?=}?Y zaBqXquDFFBcXP=jw4wy>HpJ`OamS#%_gy8lD?W1GZzgXIttb&66Ys8+M`%R}-fbw( z;m+GCCA2F(Cf;2sZw;*|5#Jv&4XCd)`D z{r%US656G&8@q;9l!(8tIE627Un!wo`i^SX(9d)I#L@j`39Tp*pBvsKDsS&9ph`5tDTna9Dgu*9eeXcDsl37~5&s>!kwNSaw+MvR_4H`PixgvX{> zB2gm#J9Np`re>?0R>~o`g&^dS8$z}!m3;_8_O8=PIRy7Kh}<*S>D29ul#sof#%D9m zE6N=uecs%+NGnRn5sE!=!;@u4;-oeiLugn0H;+&d`<}76l+U^Q_k|1MeSJNzSrQ`m z?{G~2Pa<^1yP=j{w_(=UdVj&bP2#_?6;qq&9SrRnS}BJJ>8vGmb$PVBN`!Y-4OeosKIev`g=-Y>9Y>$dFj;Ju~CuE9Y@&MG1SaNqq*D&@SDFcB}MWta{JXcyH5i z-G(LfF0_#d*Mr2r6s|w9L^*#q+)cIOHMA1{9SFTgr(Ht{?TY^n*M?X^D@w$Brg~lv zVhMe2^?tv4^jJbGi>GU%>sdl8e58sA?TQm0!nNs^(7mX8SNEYMw4y|Oo`T_1F`-?0gjzzkS06{55fQF`w}e)d z(0NrA6WSH0N`&j*Euj@9bnaHggm%TL65;xHOT@Wk!Jv#Y!#sV+xToVxBz>K0MTxkc zFPkz}5usfbznAEHR6N=}jXho4J`SxY5npM(Yz|gMTcut4u4LEHSFOGtbzYSvw4y|u z1rw~5iV5w~c~zFsiV|_AO|Wk&CbUcUp(V7UM4ZhNETW1D?b74T67k*A({77%mpq*^ z{XTCAttb&ED*3WWP5PYc93-8)r0?2x4Xr4llc6dmw5#Gz1Kr-Zg`O6gK0dpKR+NY{ zn0(o6Cw=5fXjlCI!!IPehCUxk>mIR$R+P}mP!$u}rO%Tku05w|DU+YuZ}<&Y8gHE- z`o{^)OPTz9x?N@ao3mIeO2mKrzx_%r)-`ay2i}c4+_OPxyH#3IBF<_Jca^A^(5^_w znXLK@#_5-yX1~t;jgvQh*+fqzw4#L00JdADgm%RVqPTxFCzI+L`YEF`CoBHM(TWl} zA=9p*gm%R_M!~qUgjST$Sz?yZy{mJc;@WXilRk2tMq1AF)9^f1yoM4wpVbn&z43k5 z(ZAHkX9=w+5kDE?TrzzeN@!P{gz9;h2fKz=l!%{jaW0vzp?fi|=V;dHUbky#MG2kH zS}~zr`aD@e_q)#F)wM056(w|1aK(gn>Fd!F`dZW1U|i3aO(532s}&`54!2!H3GIqo z=y^96OK3$2ovK|ipwz^CbTO)rf_#9OK3$2ox@!* zpdRoqi7LezSyD zl!(twxJy*Ugm&5I19nZwCScbTr2-r1&fL&tN*-{8mu0?tgaR>~ph&46Gha|75l zhKO|N;?{5t{*_?Y1cF}8 z&m12IpGhU+ze5*~4z9sx759L^(Lv%H94%T=f=3{Ta75z%yC3crh+TI()ezbh|4jo1 zYv6kDBCdfeo)*AY;j~3sDY+v&9QpQW{~ts+^5JZh!n7&7$EjHZSAzNIvCv=Pzr%lF zkA!<0@=k_!tF%%M5$G5U>-S7H*#3P^nPu?0@Q6m1OaQ9ogh7#JPuT4v6MG06p z;V!$pGi}9$cIhj)?ERMSyL>mrHQSt`LfggTN@-3zp_P*RH?Ne(8hnS&5pWDRYljAp z$JOzii4&&NMEZXa+J&p`IT?rsPu?2kY*qNXxQd-~W$5YT5xVU#EjUpnOheK2?Bmdi z5^ys(H-+|4`D=tN(Jov&%vmYCW;>6-mCI!lPB7^tcG1nr{kt3jSN4bLJe;NjdmzmD z;q)F{GsVdcVUB}+99mH#J~#An^0rC|?ZTB+oCOi)IM_9`qC`9v=;P$Ap@eqf$|}x+ z2y-0l8oGbt-lgHRjeVv2U5WT?(x}SYDkZc_j|IC`y1n{1aJ?7jO@vtyme7h4@o1-y zlebk$Xcw*{*39Tp**Q1YFIGL2!@8=QvDHA^p=*swtKXJ68M0{tUE0ec|650iag7Z1U zbRzpWw4y|OC!#Bpw}$TB__<40CiggKd6ZAkmB~E^G+(^_CA(ExiF-N_aqrTV$y-CW zH@@%EmGS!c>>658B7QQ^mC0K}3GKqQ^_;LuS0<0piW2b?j;>4|5ud@Z7vp+#W&Yv5 zQX;NRS0--_-MiWq|Nrnj*?pz^9llAJ@5_0-`j;%B6(!(>gxSKJ7+f)-UHW>ogud4F zH5k{UE0ec|R+NCV5hiqV9=BaX3GIqoNLMD0(25f94SaNE^4_nM(60E%!)#`|Ra#LZ zKBh2<+!9(*0!D<7u1wxmDWP5QF@;Iwb`7m45#P1x%H*w~gm%R(40FZp8v4qKzp3cT zczvZ=LMuwdUov!M@}5B@v`dd^yM|Vjh`(g$%H*w~gm&pWs$D}r@APv}_nRfOqC|Xd z!bJ6o3GK4a2OOCqp8cRR!z(p-&YM?Tz>(qoB|V*)`2Pos0Qa-Jkarm^b7r)nM7-Ce zr}KdOFT;KyK^sB|?UFlHf`B6v2pSh!DTfGV4DRq(d4=N|v^tcC{|;Sp|4gg_ME75zH7&U6_4XAn42}5&s>#`p#g|KvM&U5 z%A6VfTk+qaizXExN7+#VMFRzf(|9-4Qrz1# zWhz5U!ak0;uY!3L2~Qg){v}Tv!V=~DUEWP~8*Aw5@!x^KJv!5PXVttll+dpDZ%>!P zZk1M)fFqMKm7y7734Lzk5$(OHgt&~HAeONJ}dm8uUO_|EjJF$dTl=z>|M|jqh z(0ypv(25dqZQe&XZ>yBhEgo41A%+NH1HutvyO_`VARCBsyP*HyzODP$_c>!0Jl9sg|!STz}@GV}m2l_tYf zhF7rvGeWyy)nu5;@XC0*Mmbv*wgm1>hN%p%G`ECqJEou%GL@kXq3e}Pgukl=RE37P``zP*Q$LFBp zeWev8;&#R~H z8cJwa#qSLIjuVe|PXk8(QpIa15npMZue6E@?W*|QM_;x2dW?ko`}>tvl)x;QgsBX# zG`3r%gm%UEO2>C_OK3$2TvMGemEjfB6%*R^&-Shon9Y-6D#L5K?Hc;Gv`ddSOT>3k zPe%ieOnas>bWQB{d3>|{>r+iDO2Cn6&s2sEid_Q+O8Yopi6#xZ9J}-#!xCCiBChAk zwotc93DYH?5_xOL_Qoyrv_#UsREFM3#f0tJ`gyBhE`6Tt8gOJ1rZV(d@H>jXOvCR%I5OcbX*6Rjp%o?Kzr*iOOXwPy zgqkpw;WfQVTS6;JU{-6wREF2|R!nGDq&br{kANeSFqPpI%$WO|#EHPAaAXpuGPE!3 z8d^~TGk}vg9e5jrcEOQJn9A@ve!GT#%EV6t$Ip+7KXJ68M0{s({3Nn#D4|`jEfS_O zbSW&M6(!<3k^B4mmG0g6Dar{@rEzUeYRX$95{}PD+|!QFf&L}CRa#LZ?p^oyy{p?B z-*-8^jCRmJc;rgNPX^8<%iFv9x3mk6Ou|%#SLNHsp%o?KCmiRJ<*lK6F|Nm{s{e3b zDG}Fpf8Q$IyV|AClYJbz-(jF6alY?A+$tsDmLzeuaNfSstfIp@3Q%*?%Wr`&TUw?PRBJ5_rqozUHfpjIk*RAfwUgAx*{Oi__BIY9{tJBNEH zozUHfpjIkVRAfwUgAx*{*VYN$eF$nL52IoP1{#mv|@ z6TarH@8@*_jn=;v0h9io;tg~HjR?ieP(s3D9h~k&K{%n984}d8hzK9mbRsRBNRbvD zNe?2$X5g$8#b$JfbnRLe+2Mb0MU3bK8kHkOjC3SDh!kUjGhY;A(jn5dYgvSf|Gg9W z;xiKqkz$u{mQY3{+O_QN@L#f4H5(Qq<6bFdh7uBXXNvHcmRikX zWSmgU3<+wbYmaI1UCUvWT;FV4e21UasF(oW`8w-GXV)kuBqt~#!FxI`x@xwRBR5_Koy~e{O?y!n#V=9yyW|l#tL_ zFFLzMu@uz=wRCce_K*~DkrNi#qSIia;u&;iiS6A)#ZRQ`pzEBVgoI8b(aAT859vwx z?aI83TDR|37z$z-4}fyt}_|5Z=~1j4our{%8GU`PGdZ*?qc8lGkz2bm`gSTOC?SzrQzsJjA*iK%#oCq8 z7go6qN=T%;C+O~}Ca9&X#@dz97gjmJT4e3A4s(JM5~-bHcMFoB7Vps92K{9@lsQ?u zGWzZ-CnzD2o{!M|e2}1)ve#=@M&Fa=HYg#X(_yqLqwkcf32G@TzIJ8w&1z04i@$bd z^hL4G1JJIFzFyE6LHxSF6=>g{yKS3yuhLgx=?S4Lk<=Qc=Ci*=Y2l#tN* z4BC~^H{I0)wRpefMCvW0Vl;FjjCN%dYr=7GPEbNZr_pFvMlmQkp%Y=WE2CJ9q@^=# z+V3cTU*!b*a}vp(PT47Jkf2ue+kpNi52HL}`Esu)A)(V@v@4^ylWKxm>6d(-kP~bV z+GF{0f)WzRUg-9U1hv>sxec8mqg@%rvv8iNGg1^QqsW+?po9cxtT{m&I_pKdGWw>M zbWTu0LT3)VYP&M}rnj1)R-%LK<%G^J(XNcXN7k7P+Lh7Qa|06-%f&B$-~%PSA25PEG%e##wRT=2PGuZOeS>Cyhu=s_jGQ95)x@96S`+b zB&fw6HMha{9p8hjx16AaL~5JZ-R2~ymAA)w&(HSNk5hjC-I3iEyU2F|F1=<{JzYm# z-!SWE{`Z@%Ub${7^k2Nsi8Yu0-UuZ&HwwHw<4kF-}``$*deKp9L=TCxS};)Pj@3 zZ&p1s91w?sH<$)AVQzCJ0eGW6uo>%TlHy!-0U+t*RowHk?}<&s3(_w#@A+h_e ztA|N@pAtX)=9Iz)32LS5&`nT6;*y<)!^PK~8drVvw}lN7)JoT(o1laQYdtSH32LS5 z)E;{u&^krwq*rR&g5P(tFP`#m^x_%Wx%DWAT)ut9=a={j^1 zl#n=nhbM+MdElhD+^)YUY>=QY=3!Q2V%X@|mHH6WN_6b@iV_mL|7QE}yB|#oH%?fk zut9=aiH_Y~Q9^?6;JoA{sFmp0?G+^?(sg>D>zq67<5&#u2)-n(>zq67%UcX@9bbi7 z$#u@12s`(#P3X(jj7Slcis3av=iG^~=**0u7UDdO&^dP^EQWW4k{*PjL5zq3gcJ7_MLFY(% z5Q@%i5$&koj7YR=8QqYLj#u{VcD#bb?U6|3K=iW8(IL{cYgsM$-#fMIHd5_&Bt3}K z9y;evUZoc75b1Ya%UaX_-nvV4&YcL|C6th`J2C36)cxi$yiQmQZ$?lnUHcuHeN9!j z7)AeD#Ntoecewwq&cD;wA{NPNzm6~B>y)Ht!ijYKUu;-ZE6b zZXY7iu4PezL;708Vt5OJk{*QOhYP}DDu+@GZ~c*<+&7eBc{P_MNy`G2x_I0D?+*;C?R3-qeCgmv=2e8RELV~Er@hq`Tb+Ds6+N0kz#7=yx;Qn zpoB#7P!ZC-ZTMYHtwaae%WY6XBGt6ww)+s&VlCu0C?S#V7{$03Hb_vbt9E_#YB9WZ z`%<=Hdmf4mQ9r2u+>-3yBP?L$z@z7cPvsNdGz-nkRmYN@Ui_1mWfS&Jl6 z+bHU{@QMVr*s}TEPJdYr`*OXJqJE2VP(mWz?TY#>ydps@`y#%PqJ9e-l#sAUtC=b4 zx3EEiS{8NFNKwCq4U37InWBD!#bC`$QNIH|A0(1JMg10DvEHdw-7~PqNq4)Veh2i5 zM0(N`_1niQYE}0>d}{eTCPGoag$+tbSgcedMg8_6sFnIkMg0~8B_u57tC6C9`w-M( zJLS&@B_u2=ZDxx4Eo_jW7Vo#*hDCZ_pCWRD&bCVtxdZkLBrMkUdiy#>5xIp|>=`mG zyjOCs(i=yyuOShNMYiANc%E-gN=PIR6^mSWMH{5)ZSGYrnd6B?&R%cdmngorut9=a zto6c1s}0=Wq@`Ho0ZUFI*;6cX;T21pYt5POPhQ&uU>}wIljMgpMtzln_C=RY}(RB^msaD)wVS`$v zE%L2lUyCRvt{`YVJ++D%^|Q(TdpSs?enl~(MLAeD@sz^DE_=& z-7`=^BGtO$&kL_eP|IRs8}<#0qGbz$5)!G_Lw9?Spq52vHtZV~Mavd8sFmt1sOPLE zC?S!0*PuQ)uU!(6SU#$-nK$-YrZ zW3ABJN^4QOB&e0Vjg{qa35jGc%ER0%N=T&Z*zFZ1B($!pb!uD9Eo_jWmR4!Cs%~qu z1)+6MMK#)bWkc(eifXiV#rAd3bzY97TOZq0>yuhTww0Ytwc4zx zMq4A;q?(|XR@1bGY%4~a=7iP`wJK{XgPUmeS5b{N*KJ>G^`Nk!RT`}>+uF>gT20Zq zxUHe|@rs`GAYykpNTh4m(psgW8f{gw@QM-=seD1@%S)b0>m_8#wNjxqa%EA=39W%? z)!EjuHq~mHR-J9FY*Wp+w6<(BnxUMaghXmh?FTD}8MSGB-mgZ<$ld-u~VMA*!T6MOyl1;UGqg7{H zn;GyKB$4dJZm&|Sc`rk)>b``1RJz+eCo6v`Z$U~(q$e%vNvkHP#a<~V_|)?0N<>gU zmJ^ha(CUp=oo&^nXb%$9O1)iB|CrmLgoM_YwCZfDM}-X%)M6dxHYg#X)ikX-+xk}F z6$xtbe#>p7-ZHAU)Vi*s8g12fV~($Lf)Wy1*Hu)bazo~XR!z0CZEK<%CoQdTZ_Hjh zCnzD2>}e&sut9=a)o%m(n>>v2kmbw0qJ)IjbrscUE4YPMB&e1C-aTU(v22bWKd8)$ zm~#ZJ*lFcXIUIAZC?SD4LqX7n=Cg_)wApHAFSo(pC82q_;sb>+rUQR@k6~gw~g|LT{@_1wrenzY6LH z>1|$eN=T$0HFWpXB&elzM6I{miecduB_z_DLEjt{1WT@UL|X+8wn{j}I?T&K2??zu z+WM}=TaGJikf4^Q)WgX@v zr-Vcr+lB72C<$t%T91`?qDx4mv0dmMC-S$bmD(n%HS=;%LL!arLiae41hrDz*tvma zn^Qs}J^$LnE4(5>t<;*ayUi&fk)9jveHAuHP^p{yk8R? z)Zm~W!u(Z3xX07>1ht?U2_{GsKs|;PEbN3J^!J*XCOhX zRKC#toKuoK3@R;usoJX^MCcv?@VC;nYvm(=`mgu(Z=+5;{HdnJ@ip}=pCb0sb<}m7 z`YHeW?%(^Rjbv8(U_U3OAN^31k{(2C5lcLIkQ1NyT+E0>yOzZ!x(&rP)N04B`9mk} zoq1W4k{(2C5f;tZ)Ox!j59tZZWKoAri*^i(DXi5vDpU9z^UT9j8Sor ziafOF!l<}JMF^(rpzEBVgamC@6VyuALEh#BB_yiLVey(#F`SAvOV?4?Z*4s`{_2w_ zhi@(XuJwtmD@uA0u|JV$*J2&!HYn*qMAdpVk!aUqP1kA`F&Wk7idD48$f#&ZMboA0 zsB4RbjEbmK3}a4E(u0VVgiBUl@!I(I`lrU7-uml+Hb_`BV^kcZA`+{;qE@1V?BxU{ zB+_;0wm}IAwtsGe1hvw&-)|OmHsb}~wNzAK>Z!d)wrIAd#o9&1u(1d4Nd)!bBsP0* zrRHPzO^mg5x3IgUhYcsFmFOUQIl*@39b*xbQE``wVay4O_G?-!VpPPQMHey zPE2>dz0P&whvyuoj1C=14?<6t=^lOVxBWf%=vQB8KDqsE4UJ^}a_v(gT}NH7KKq@9 zvJ|{LqA%#G2x_J4&`nT6V)vas9hGh2=J^&YydpuZbRD`0N=Q7j=H^iuE53KMVwYGB z64Xl9p_`zD1ZzFFL4sQ8I{8TdfH84_UpU)IAP6eTsZS?Re$}8H-ZBUY~otV7UYCg)i_ikm_U^z%o zD_w_ff)Wz{H`h|}%pdWANt#-?!hk2V{cE>q& zwjkSJzY9-@JH9wJ{NI8)J(|Sd&OSG41TfEPo)<@buxGjX?lKodjcPtWc{%HSNKnEz z4&PllL9ggZx{lpmQ9|O7mrwGM%&4^$eMYZHP%B->Zh{gL=k9ZQR1Sz+UihG}L4sQ8 zI(8G3kVv&2RO@*;NKlLIloOPYNbMB5TaW~`*qXH(#wEj$G||pYj0T$7xMY};9z?Wp zi4ho=WJID}3!?!eFfJLUqz4ggTw(;qB^i-u*TP%P2#iaHDd|BdGldbh7UR#LR$6Q| z#aCD~k4@K6*XJI5LVWz0vEhkDmHmMPB|V7PpGdT8*;1nOmuR&jCn)JbC>K^ABGImuyoy>w$!$>5gXmEX5-e@15oNRLT~{t4!Fuzx z7;kf}H~jnahsQnd9TT6Lc4OA&yccr9Rt0=bM)QALfAKXL&HvN2ug&BHB_wFOnxIy? z4)Qi9C?Qc@4!n!B7SkS)#ospkTAayaVvGYcD(^dMq?BGInJI?T&KNe@Cfy$Y{L zq-)n=P5WBRh{n5Go3ZtmM#^B-zE;j6t)DbfmMgPit2Z5jl0=hGW~)9#qFu{YJsP&c zqP$VP32G@HmDXY^2ujkm6T98@P~(-wPKoDzY+7N11hvw2=q4y3!S>JViUhUNbWJID}E3Nfu4bTYea{-D)9)!h1)iE*6?Tlih4=mBY^UmA>XEt~sm=O=3Zp4;GWC3`{kstHPZ5TV-! ziFEB+w(6mMoT!zH+$&0Y5TQSjXxFmU8;yOUR$y`)l=L8c#i*J{v}@V=lE!vXs}(sx zNe{wTM|_>c%HNvVV|BTKRp*ASNchM=Gy9yNqz4hZiR6`ApL><*@%wL{64p5IuMK*e z+n|Jmt;J}J;;SIl1hoaP(mVIr@FFr67So!dSI&%zDA zgvJa}s|vXd64Xl9p_|~{&ga8cR32G%e$X-rRLLyzKa;)=});RGS$G)g>Nj-gEqI*f#`o1Ktw(1K0_x--2 zHh=e&7IE-JFVrdNLBtl({D1p;@&S@nh}Y1EgMU?jn+u!p!*MX;?T7()YzvZ=|T9Y#=qq7v5!_kSX$Pb ztrpZZlF=+bCn)Jb=&P4LM50~G))(p;muQxs+n}Tep)XSU5Q%mzTVL?3*;;SNZBWvK z(6=~!h(x=VtuFZ>V#*s){NM{XXp@=^dR(o zNkLeT9MYE@8vE$lR}XAn?isr^1J7+x(u2_V69tjHa_c{sa$eYV{Zqmb!>dGko7fmli+fCc-Rg=2B_z@>>1&aK zpoB!a*0&}_IVd5KYDC{?^dYFlI?T&K35isP`m(05L4sPW>D&fum-UveLuKu{gan`F z+y;M(TKQ9pb2GG?5i~9_zqLlDYhPo)nH_cyu9VK^czXK5!<6(ObWVp6IR7Ifa5jhb zjoh}qv5mkPBidc+NO}-H8uxV)f8%J~#8w{sG!Ly9&?}ZNCv3((l)e_x>|NLTT12Y_ zL;CJjbM~B|qz9qzOZpIrcCGXOzFb&i{DiRMs|#AmZM~;cjviW3TGa$4>DmcfC-L(? zw7!wsAVIBktuImvf)Wy}_1p#tYNcy^ky6;8ghbwg_9chcm3?0lfAHn|h8{caw0OXN zw`MKKmi3jD4q@vdL+Ps!tq=^QuTa|8`ohCnkT#N*OGwamH9@U(9pr6JP(q@*95!!l zpIxF+lCJd)OI+v&PYlg9a#FZ%nr1942PHj-*q=zWYq1V<8X6j64Xl9zVhYkBwo8(H=%@t&E$P7 zp&4;bq`uwza9ionsT96$!alzz5%iuQVXGb?eW_x7iGBOg@ru7itwie!h=QPm#Fg7m z3h%CdW<2+X`3iz1XKB;5zAq_CP6-KHS@APQv<{J%g9NqGwXcHY1SKR=IYM_iNKmV~ zuFin<~}E!KLihV>G~<7kZQF*umf2dq+rY`vsONe?2}dWjKOFUg2RyB1a{ zjKF$Hlad}pu=NrnuwIf8iFPfF!i~UsiDG`d4aqrXMyg{BztJLpec74tMya!^8o_2#=7=3DEX z`|$k_Smur~@z0;SD{FJ!3prtLUtdYld)CG|zH+1YY`WGyjo6||B|Ql3E)`yp zNY}2#n)Wfzu-Zc-nvLzNSgrNwEp6{^e~0TWl>V-rCTlx=>01ykA(5`NgH;f$AJ(*u zl6*}@Bc0p^B|Ql36%_>iowDc!VVMiK-kVx05 z9QvkKwX4yFz2|&QMsGB}acp$qYchJf`MyDipoB!a_P1S5u%+07HoEZfl|~5F1hvw& zc4Z2J5)w8Z@o|Yp2)PXs)JoUdT`CAlNTfQ{4ptw6TCDZlD@sVDTGzf>VS@y<*fzD= z5r-`5Pt=|Z>^$=F8@EJ_OCEY>iTZ<2-|5#=Utg@A{vP!ATJ5LXE#buaAK$4>xP-(v zZo1Fur5{ti*X747?Zit9?~oDHx?+PzM1+x(7BFJLQKOu=`5)ViP||~lEn(u0UCV((|ya$?&%hcY73u65$Q@3;;7 z*V<#Jxz=rY_1Z=wl=L8Ci`eS5jhrwtBNFXe=1o&|WxrxJ%o``nyAeuy5V1vAiJf@u z=v6Wz(XM5+>Nc!4%!bvf6IRP3l=L8Ci?Eh+!dfyT675=cceo8}RkQKp!aF!&cgqMR zBcriTFP0J1O4p%9{O*n;M%2SCwcfbq^jXblSwZ8?A77w8<=K&F zCxFH8%(GB&x0B#=K;kp6+!QVAX*}qJMeV+-BB+&q$)B{G*yxILqR#WOfAv3IM_pfW z(X^-xv8y(3wUW~YB|V7PO|Trvt03Q5Be@MqNIdq!jZt}E_qbW-dC@Bp)JpXhRMR;z z?y{?*Wzdb6?eIicnRUOp*DLLk_b5jyxl2f-UkduA+y)71u?};B{-!bo-7zd* zPEbN(oB)L2?^S+Ca9I#CU&uZPI-lb?4_^QNq?tzZ7&YR1?(V zla>>dka+&K-$!L{J?FuH6*fpvi_fF?x7PA*YuHYHZ|an>yWeSQ+~98j_0H_IbK>Sl zE{n?d`sTOK4{QEuT2#K*tv8$!V)KHie6P3sP~$7>(>pduP;1PSS48D|z3bic3*x!! zrbOj?eevPR;r(mRi^}(U{J73_&~ei@yukRf(tsq#7tX zB$B-#5331kRlg1BZ}Kq8LzXYMK?#W~KRY=p-|H)XE=x{=TIui6{w>PE_8`p~$-Sb4 zM6wsUy&^#^wo`6{y;|yhg8HlK9*zdP6 z2>P3z^Pv8N<*P0^iPRH??jDZ6MXfFOe>5sj>JLu2vha!$5~)WG-J_*%p8IxGPT99c z{t%8H_phj&vd{eP_u(s7J!;u6$A^{9Ep1Rj;`j5t5|vZ-#Y?9bUXeKKmB*uUv2Hc) zszBR$T~R{fy~F<=m5X)NNmmy(NKh+Y_F+^m*3aB~T|rPnV!ofg5S5Gd-xpoehoIIj zdwis+T&zET^oD|9y{8di&}fqFl$V?m5^3BOy2ptmsFi9xR<@u^NThLB=pMuIx2Toc zCaN{_a!^7djk`kk7>)$BQrpDtHm8I{>XkzG7>)$BQftQUHm8I{dNxCM4@ZJp)z1ed zBvQ+U?&q8YwfLmv?ZNvs(LqmY^}S08iS*0|^%A)a64YAu>5ny)i*@lA8wEiLiS#rF z^-8%764Xk4eyn^OxP(M{{zG@qz~7=)DqrY+&iS55@2jXa2fm5&a!}HPs4j=U@91Hw zkx*H?E+LVZLu)0q+K+v8`DVa1&;cNUqAiE=FOIc zwpXU*o=B^6{k2V+8=SwT|NW^=>jgm@{M{YaJ;c48F<)te5)vp!VS@y_=dROiOt{al z5Bblk%^SCQ)33jA#tMZEN=O`QA>^|0{Y{tZLs0AP=az6{moRTZP(s3f+X?$yAA(xD zer7c%o;>K`qU4m2u+lqWW$Qyw>$m5u=fo1DuPzAIJKKYF-X4^Y&@-vp)iYX6P^;Q2 zN_r93UwL6+gGBpUT4y}Ep?h`Df#(+lB_#H~cmpTaK1P{BTK~0r9}?7hc#q(Op8cGl zgv3H$+hhQOT2GGO%!&7x*u1b|&zMW}%vn$4*XnuNW%|frpRFbWem7W;;Iw*1EsN=Tp|>qAfr z{YpVlLIOQsLA2XIEl9fkceQ3-4oXP;cN_XGYT+$W*r0?2-d*+FE9>*T-gSS?d-+fN zdXGnk>PH@UwO`BYoZ#=`9aXQkK?w=GMGG4wsD<}@K~O@1cT8Rm64b)zqp(2<3EtDW z4HDFU^_d&PF97RJ6s$tmec*xN0)L85bQTK1mua;S&M35;>; z7%giI?;~W5=W~J*5*P>fA*hwl6IxbUBLGTB*mZm4+-<`p@|Ri|Ef)kOBrvA#Lr}|V zI_fU5c}YRoo#+x9Q>)+gYdy*K6!^7`sSAP<5*p{GF?An;TJ|(MVPooopoE0=5>Dtz z&fA;>wXElJ!p79yePTyK!b{OkEI^kg)fO6Y4E;8ziV@;|C|yTjT^K zBy7Ag06{GqojGA+>cWQRt-7n#k67R2*XpavHB6YVxo3(~9h-_@GE2}ww>Myd&F z;k{DWpo9e8c11a;g|}L>nxKRP-n)ej64b)TpdctA!FI~)iUhSVUMXx)LZZ6ONl?p1 z&VHAu?Q^dvA)&iQy=Z@eTK4{PLj6E)qcc{sw^--e)|0CVN=Vpv-fh^tt*}9YS}b4g zmGuU7l~8YC>#6-(Z%gYL{95nCoS=k+y(OH`8?~CCmer~g-S1jTdJ!-Fbm_tdiT1U$ zEF#wnN_r9IVa&ZE(Y}@zYM~%7o5=1f%oB>cgc9CY zT2oZX^;XEeB0(*ACc-=|2uet(j{ZAQYKgG=D@raO+meEqs=r$c_aO}KXqmU(<~_?n zNry0d{JU3IYedH1qL!Wud1WnG)D9B>DK9xCB<#)LME59z z1hwpa<%HhexeZE4Xhx|P)MzRvIBw&ZT6c#CJ!LsT2?^bSBJ@;O6Vy_ziqKP*6O{BK z)DKh>ZCYA-T4lrT*j00a5)$eW60u4(L9I5erz|HZ=|$+Nt|r>Fv``BL!4e3T4N6Gh3GPEsOP;B&%+rFPgamq`K189lnrvA86(zS)btF0Q#Hu3nF3w9%!p`~V zXqmU(<~_>+$sEG$;qNUgou0ZQp_ZNtd1WnGl$;V0diF%v6W52JmbIo6-79yL^dx$% zy>@=9Lz@;xfQ46-kiht{4?!)AEDM4X5*RJ_A*hA%d_hn`0%Q0-1hp`;C_VvofDLh*m?72*!BL2 zVUx|~FKm#Y7Cp>u(BIV;zCQftsx!lF+tvp3io~Wn&Ir$c@ysyalz02I2etM%0wdJz4Gu<|I}C^=w8sjc{wN{@!BregsWbk5Vk$(`91`-cAs%| zc<=ZLq4wtA3xbjdm%S=%H}8b-`ga~1&?^#G|LV$c?33feRhR4i!MlXzpw_pKxgxwb zW_(!Tfrko$lJ_3DEPQLR@!_Z~{xYCfBrXV-hWp2#9^Se3kA)3-MXepD{3cwy`03%? zRqrSWO1|*Uv@m=2xUl?7vj+5vghkziMeZLL-q~|jVS`>#Yu>r0h5vW@xUl;QEVIM7aPxg51A0Z`)_pDscP~6HtUaIJ=T$98t&7gMIP7}QFT*)s(3i_3DEZl~ z7lk`c`(;?@=otfgMPlDKFAS?}{mXE?e=kZKtSf45x$1@Cn0bF0{`LIt3a{>7a&lN^ z#W7)_#m^1Tyn9YqVCgYond?0ArQ#VRL3h^QO>+_5WYky3UFSJ2|TKaoCB0ncsC#!w^g7D{AW5c&Uebs>NL1MmB z&JP>@Y;1U7H^pXDc||RY1`JpK&)Bf}8H$M`LCLOPnG)Xl)Yx$BI=>mvD-yRqe_r^q z#diMgZpB*C2J4Di8~*gX@Y^TGglG0s)D{U!rhekQu;h(n!Y4j@@qk{DSaSNgVa${< zVf*v7cSjraidrXbdu~|rgfZcSAw?XLpybuRPYze?IVN2F(3AnaBC+Rjlf$m{G2!vU z72!r3^om;f-Ttv(ec3ZpJofl19J@tJPFu5vl=7NU%(HCX$VFMX2rB=F{e1s=mQ1maS!_S=l#CIl)#V zvHC}sukX3tS>e0q=*>wRB&e0QIf>V1ezd;LmJ`FTFPs^!e0u)+?7vS8i(lLhIWC^p7?sW%+WiC?RqGqKnpNet%M!b&2AKD+eq&iPcViEPQf-3E?O9 zX2`vwC)8Tt^5?^!-kK0L-us$@nCrcF!pAo{Gu*z?j4*nY55v}z&J16>;JN|5BJugv z=B^+1>Y3qRpVBCUC8t-^;@y)I^mp&!e}*0QKO;=9{eD2NNPP4!Z-nLl?~L$2=U>~$ zD{8SuYPBC7^p-ulwc20y{noJ7D)c;Sg+kZrOLYCGQ$OcV)bNd;h&e$C39YP%)=En? zL9Nr5T*sgJ{cc&LAcogl$)CaDRUU0T^W12E250>3)rMAxWW$`dT^W{xl8jht6@MNt znes2&)vqGnf)+i@2}(%3G-VBcYM;J+?xGwds8wC^iw>N-uBY}N*Q}S7cJrO*s_Uu! z>8Le|a!|rr(6yf0?z*Cl33o48*He4`&wrZP%S+DRCGqxI3)S`19ykBVg;yk~b@`Qx z*Y(ss{_V*HF?*%u>UwI|UM@CXJa+lIp4tr$y?sEhNG$l^3jWlNyZipa2EC#d@3*|< z^!Ia{ELqo6`|$W_1A0Z`iCIh6_0%4G<28M}q84i;^J)b5m9I9Yr#8I(?gn+O8ZG$Z z3fAtp+eawDQ|okk{tMzEdnUB1vdWZy4YA%{T4=SpR&nOu?A@W<1|=luZ8bry3x2Xz zUF%n?kD9;miV_kmUv7itxOJz|b*=SmyyYudnR0@@lW6?vQ+2IOy}j*IMafA}>raoZ zSl9a1=XX+ORkjBuAC4YX*GkdLyWTaRS0uJNaJjlxiWdJ?v#>$0s5R|(OV_nhboPGN z6a*z-u-ukfDLSh@Z9uO`yf=CAx>kzTT6%I}gI-bVp(PfrYo+MRubf^Gl>F(Gh3Z-< zdj7VP2K0)=Ln8~;wNmuSoqt-`pjXs-@`L&7S}A&Z_=tj_WZom@t!t&|y4Us`&?^#~ zz4+0(R*Kf1`lZ4Ky`t8sd(U0hO3@m-tyd6~thmQqb*&U_`@J;=^oqnaqvon>rRXc4 zTdlA`uc+0y>O)^CI(?B*1wqL&tG@3mMNd7q*nnPTcs;?C7zS}hg zao<6+eWmEmJ+ImL*P~|pO3_-kpR_T5Dffy5wKiSsF<&Wq`L=mB$qD}Mx9@(`SBmD^ zYrQ@;_`4+5I_6PdDOz!_Yc|Slkf4_S-g8_s!a6zRrI&rBXpcoF57-_g9@ytaUn%<$>nlfvi0lgxz>QA2Xm7-(bc&xZf=oPhg8hX-KihjArH3dP* zkN*9*uM{0|+ew@7m#Xg)64S1E%vXwb-*dgf27ilM`Q1MK=pXsYL_B=ax_u+;GZV#3 zVC)mO+WLz=_xa?<|Inz__V~)NPJH?G|EW_#Lf7rtQmyvv+s8X`-dAS?5;GdD-~HVS z2RCTDR(tx=*2(XuUA`k@DjOuGp0l~zuyOk|`(N$HZbMi6Eo$NK)+eGIP57IQ6XC59 zsH-L=C^@|~0wrfH4$%{o$q1A@QbK}dvf^%hw$D<-sKZC>%Nef|+eZ!G{om2`znpef z*m}$@Swvkop;2*3e6a8$_4D4J7@pflbLY}Vo1m6`FYI$p{hJe%kT`DFh3f~|s?pG^ z$}>S5lw9~ut$y4m&I~{P5=yx^B14bI*U)?}dBEDqGKC-))_jy5<@$HYp*|o+s#=tXl2VU+nKT4qE2_ zGJ;yO_uRm3yfUPyl(+Uc(1~}yb!U?j684Rnd#G>AYPCQ7{vapLS)!Q{)OupOjoijc zFP>t=5_2EYvhm4lnv{^R@Aut?eR*NT&;za0Zf^VcIT=AMeOIFXO5f+yYAh%@&o)o4Zu&mjvBB<4F8+|pD z6O@p6>GE~!=RZ3s{Nkr;^&zOGI_zCnl$6Ar_Fy?!i({Amci8LhUxu@8Ie3UQl9z)L z5}O@WtM6{l`I@_pDcXYswb)LXjgf;^c-eb{r@pjhLv*{%`Aa$R&I>Dh-*?P2i^eVY zU8Jr)YU0+nIo-Z{stNw?qi2lvp8D!77LPeW2??}pAA(xT{c7F%Pv4vr!q?X-2uet7 zbMVIg_Sxo=p@N`<1nz}C1hsUX?vjFFjeg16S^fD|yN&5nyR07)2QK^XFwX9=Z`^%w zBd=W&)Z)F6_0)CrwTgUk-|f8{(H~nm&{Jmwwc7QjZ?dwUx=slR^v6b^r_Km!p+_|W zJ$0QD66lYOKu?_!)IyJH1bXT^B_#4TM^Bv*)Z!hJz0Zf=+Uk1mk>B{tq=@%!JaVH; z!*TX@Uig6V<`qT&!<3M~+qocUV~FXoU-*4tgAx*X zIW*2SOKO+qDR+zs;}`rzm^R@YuhBF@Dr%R6#<}Vrv zmXOfMSR-T`(e@#z#WLkKsHM@cM#VM;&hk6u1b>T!#<_Zz*of9@m*pTqt@D<-IBfCs z_%Pv{PZtCw8V#!#wJ~s?+NBK=8YOGAY-8ZU1_^4hWoxzg{s%t3TK|JRhS`E_wZk8b z-m>egy_V^I|B`oZOF=F1;;;;p0i%Lr9G|rU`>rG8}r}a*B z;<>|)$_Q%dT2ESw(8yR1t&QdC8Ubr0Y-2g~0G*hh6~4FUrqAtpT3F@2yX@~Ia>*P* zw4Ql;7Z-%a(&{a3%+}OcT4QP(Da-4Qz1#*RBs7-RnA*m`M$;=2)Y4db&V5CK5)##Q zMS@za>D(*UuEw@{<@==IslIu72e7aN@J`^eH*DSnKYU_ta{0jdRtj*|<0J zM59*qqBd4-+2|0tWKOGDjl`^WdlJ;r7*zedjXVn*l#sC6bsL>~w_}3@wRD}`?Hz(8 zzj@<%<6pzXu=L0$vs%dOiuV->%@5SK+vv6^2MKCv%&T78MzjS%iDoV8oo(crJ&)C1 zk@(nOS8rUq%-HbN`JQP#gPoGot6Ymu?Zo5nubXD=ACnFkp0$ykdt`ma$X7RLYHZtX z=R21Ft^a+y6V|nIEI#cSCq6&+JHwQauzud@*86<3wOU_tTzAyBGJ;yVZjTIVwLM=O z<2D{x{>WjrE!+IT$BuR4gfFPyJ$dw5P8@L7;lq@WupZUDYW38&?sbI|J3etpMo^12 zQmd`7;B`(+{`(KIx*}n32Dj0A<2-Oj@Cul<>WA#@y?#=Aw1b>%=M#k#%Z46v^ zMS@xygX+y-BhO}TgLeb(5{-=YHn7ocK~O@1wsRXKsP)$)XT-nmG%5V+>!l4!NaW>E z%c%j?E^Ch(8<(GcYIu9YQ@lpoZ9ux!)@?#hjGjA{LDzaFbban$R&B0y`dMM0`Ddw@ zfDKACmQJhAPPcz4CuoC&#?ookxv)WkTGi#Cmd4U)rMbATSPuRc35})G8gk(k32M#t z(fi`7e;yZ3pYPm)phRQow9-7FS0pr+PAkxb4SGc_-V3$bcdz@QKeh8u{!RTKKit6E z`LdlSMfFW;HT5ZB{vrSS-B<2wHctL(D+cQ`+fArbLPBp$(dzYTwO8&s(rs+8>-*muC!S|E*1vLJCl3AOQ*}y6XoN4X)YH{! zmrnkk6GuIMPexFSHBzhXV!fxHkC(oEXI57v)Zfa6dR9Ay)_Q0W8!U8PMo^3O)*2a$ zu<_!EM#gEaSZh|^?<#Kh-Q6CFmtOyiu;$+%pP3VskkGZB`Bv1gMq<5eXndH~LNj~0 z4gM|(jj_}Eb!&~RV}k^>Zd!Tq=H>Qv+m_Sy{OK z??mm&beuSi_E>qGH7_S7!)r^oH<1hyc(qL%(X=cz?6 zs{N>TZ|O7Z)Yk^|$5y-OshgCrJ<$6Yfww_MPz!yc5$NHXl#oDgXT;dsTfOMXhuoeK z)Itw##N6k$dg>=;-_xXoMEkC^zTF7C4KjjSc&`}oy)|2JoPB=vy7p4rZyaA0O79F` z71XtjgN(qKVMJriv?}YPNcC4X8Vh&_7X&35ceV+QDAixtsIU(~Exh3hf)Wy&Ew@_p zvLnt4dvBnqMwWvFwOAuLp*exxQ8s?hN_&TmIM=cf=Ng~ael2ZK!dlRE8kZIXZD>xA zR?jngxefjk>dg8b z%!)DziM1}C5og=p`HU%x_aUf7Z*v=zkg&C7UtzKFaAAWITSNBs8GU)dU#hl2!q$_0 zgskradS}^-V=iP+}{>-tX$$iNU-gF>{GY@q^pPhOPf|U15X2MJ@e(&Yg%= zgAukl+ZpQ*R=Zf47@>p&X4^)bnN~lZo^(J)Pz&>RBQT>Mp@alx_eQM#t?TXo+GkQ1 z{2(K!g%u0a9ZD+`2Rw1e2qh%2=3vB0b5=hxf?68k>$$PFkP-HEg?ptvJW5JJPgIN0 z$XMmDH)zvVIU8vW+1hqaHj*(DeZP>bKBdw&G z*Q9BK5)!s9+DNO>MpqHkdilM1D~=o=8)uC_tKR-k;`+{?zD01adJ@z!Z~d2S98nOIkkEKNt!(!pa;>UzP)qZJw32SWTSZVp!d8ce z(i(E%6$xr>|JsE^<82qPCK*xv9o0!V$W-Y5)#%Ed7Ima)`&1?Uo9i3g&jI0uy;2?2?^^_-G+^5jcD%= zZgl#sADoZD!PeXw7f5!BLk zdlcm(fD!fWHZs#_sUsnwk#SmkHLtL@U8jVEz0ch%{aZ~?%g64m72(1LB_wP;*}u!s zmlwGWjf~UkxkfJ?Pgb~dOqgX~EgXNQ^2x9ql#tN%oN);W+OV~7|Gq?DjgZc5P(tFw z^p$*`#fEEMS@y+$&said3>TG)fKUB5!jx&Nq3?}l{d4z2F%^mB%w%kMXXy) zdLM#Xi25%GMXD=e-C~cMid0v`y2Ye75u+S)uc)O+bw#XO9C{yuzePfk>WWymnDoLc z64YWX=RqBGnc9YLVatp-6SbzFM4iRHV9MUo8%OK(9zBQe6@27L(qmJ*dUICoehu zRiwINUo8%OK(9zBQeCmH7L#6-oOMMl)<_mdKcXyOic7T|UQs!_6whhdxeBikt3N^; zB$Q!H@tl^=%e<;0sHHq)is!UEUj>1D5>YwZ6oqRU*&^~!^dQt{*mIo`%GsvaSIf25 zhoBbAS6vPg%D|==Udy6Z*x+wbi?yEHV4Wz}nIc&&li7gnK|;CC6v=8?&H8vnE#*2> zB&%gOD+o%I>r9cXmdR{DuSh7@nIc&&t65=#b(LvZt}{ilT86WNP!_bdM7hos$!eL* z2K0)Aa-AuX)v}ruHs}?#lOgYai!&yO4qFiUnd1jf+2K0)Aa-AvXnPoLAY|txeDc6~D zo>`u+f>5qALA$l=IATl=bn71nnu;nR1?4HmJe|e^UL#Nu6i3#OTRQ{ltF@ZqFiUnd1jf+2K0)Aa-AvXnPoNW;}x}(>r6S%EW=qr zP@-IC%6Vp)%m(y|gmRrJ=b2?SD{QcKsijr6S% zEUQ^zgI-Zfxz3dH%rcx61SQIKrkrP%$!tKcNGR8ta-LaMv%&_wqE>#lBahecv2${Q zWpfT>>#|WFa)k|3g3Mn|YnIxYu^{tTMj)qGleV+WUzt}Vkon8JLe8^{pcZnW8G+nw z!yI36Oog0oR=da#H%tkM+y=6}Wdya5$IWaY+uJZDBv__ao+T{-SpJWuax1CcEwEBLtM*Exo?5@wQ>#2nn(0~gp_YvfK?w<6 zx1ayqhVm?FUTgV^veGKglICibU8%5W~r84sURp(o+ZsvEsN5CUXf6qCCySTqf%jm zUQtVVmNZMX>`DbeiSjIImTFm)2K0)A@+@hVY8jOZ8}y1=%Cn?ds%2Mdy>U9d4<*X8 zq*yyIB(%SoGIRGKsHI<0U3J^g{$|R|9ksuiGIMK9rsHky6}7a#nKEx%+rUE!Ifu+0!#Cd?n%dt?XB26V9(TK*);2*23GHvD6P2uI zs3NGP{mpdlQbFjc)YGY_RQsFhj4G`sx>x#pZi5mM+TToPRP`aK#q#AgC?TQ!&2-{a zVS@yF=I>@KNl4{B+DGo9^J5R_sHOeQbhcALP@?_KbhgugUXjrLW;)xcutBe=rTxuxwo^g){^p8) zwo}ypW;)xck5?pUPy3tcY^TBoe^>jP>1?MyHu$?Fw7;3ob}DR;pqBnVXOzLdgmt3* z&2+ZYfL@W%{$@JcsgGCG(*9;T+o>QZ(f(#S+i5_rNN9gEo$XZEU|ms5`YN=eBU&)s5*E*r{aD2s)lS-^|sGO}j zQeCOeC?S#CP>DsT21rm#rI!tr&3Aa6u>H$_ zZ)!ehyP6> zp|#`FE(awUVY@V%P1?Ss#n)C5+68TE(ZigegoO4tHRrUQ%%U75s8wBZ?Qf=YWwO$0 ze>0scQ0Ft@D-zVw{$@H?rXaMxsX3?Z z?hR>wGo33lpjRZczo|K=?PL}<=oPhizvU&TzuMnS=gJJ|6$$NcrgLTbcttJNNaocr z?yHDrFlv7@ohuV_f)WzCPS1ZqXn!-EE7M@TX@4`FE7QnrP(p&Do)3W5^tZ>Do)2K0)A_BYeHGKCF#MJ?@bYL;rdngv0L_BYeHG6Q-=Li?NP zT$#cKy`q-(H`BQ?1wo1SH`BQ?1A0Y5`W~sJ&Ig`JX6O@q9{-$QBwv$=dAVDqdZ)%omdwT_;{Y~w2+V17`+TYYH)%GQ? z=P%`6k)W3LH#JMO9iSU>g1@W%P5&Bqul4%a;O~;q{-$QBwv%~XZi581^!J|Ql3~_~ z_BS<4wcX1B+k=Fi7~`{4+sQ0ymtIjz`#lYtK$|1MT5y|4;K8?Wtkx+M{-*U7{Fb*$~%)iIB*=L97rEK<|I-_;qz)daQlOKJ~Wp(qH8$cvh# z>MU7{)Ql;fvyOEXYelTXDeAMMWzm^Yb55NrTuo3y!Xh>O+ghD5oZBElE!IL#SgfV* zbLx~}(iXMp`SW)X(Eg_8oH}>cqBDJ;Q|AiPc1}=2!XhK991!y@J5HVX$~kpZ(hIrSE&H&$p+y2ho<0u((T~bK1USAA(veUv)W1 zSfr-Uooy$xu)*J=7Hd7X!8)<%OrJs8?&W~(LBb+6eV@~IGW&Q%EsNUpeNNleEC@<0 zI@9+#ZTE6OuSi&=rtfpwPG(_)b(Lw^{$`5WEC}sHD0vdpV$2BrH$0sAW-`zRzj9ngv0LMQ8dxr|n)2=oJZz)bxE$+sQ0!&?{J6kGf3N)?Bf*)+Or5ZpF!FVP+^0=Ytfml8RV1wZ18tUSfr-UAZ;hJut9=a`um(w z2Hzj76N}FD8KmuA_9;1Skg!NipF!GAW*@JpWl@_xgS1`Ef}q5rGkpeWyO#rcMZzLA zeFkYenS~9OgIX4~=`%>%)hq}~EIQL?khXg{pjRX;QqyOUwv$=dpjXtgs7;?i+OB3n zP-4-UK7+K~%K^P2VUe0XgS4H@!UnyfR(`i@w^Ab+MK^Lb!TA7o=xo%ZokS6epu~<_ z9XplvW9RHB8lgQ@5sHVT4gPLUV1ICg5)#-2G#lCxl?}y1lAsp7&Gu_YIKI+#d*p(@{CYIA}@#bH$~X4UtN2en#I|i)~{6# zU2A_c#dBI+k)Q-${MHd&)rX*#_BT^JXGz%pW{R(?YkxDvbDCCdHF;=j9aeIBMF|P* zZ)!Ga`;vtX64auHxeZE4Xn!-sa~3v8P^-G+7Hc__;yJU@TGZxHisvkBSa)ydps@i;o;i@tg&r{Y}j|ZFjG3(V0Ujo^wF2 zNN9gE#d8)m=oPgrp0jhm?knH# zx1BycwSKLq)}k8yi&oq9YuV@!l#tMM`}xmptYVSSDV{Sct;JwAQaop2BbUs%6X|Vk zg9NoKYSX{1wO!4^1|=j|zT5`OVbPh56wjHJDJOWBkg!P2MvCVwydps@i`s0Yc+P^L z#G*4BDV}pcuSi&=W+TOO7B=V=wJd70k>WWEf)b0)Y@~S30lgw&k(!MZ&so@@SJcw} zrskryt630~SafD1#d8km6$y*fY@~S3!UnyfmPKtgQaootP-4-UjTFy0pjRX;QnQib zISU)~idq)6*+}u61wn~LXEsti=YU?3ut?2DisvkB&?{25%w%*R2-iH$HZ>D%o z)0)#uR6m0xw7;3+ISU*7Eoy0hGsSZj1SQ(vO!1rpdPPF}n<<{NutBe=rTxtm&sh-K z-%RnGzQ38`Is14;g7&n(nc_JM8`?K*|E@)6UZ3JQ``F;`lFD(8K3-8v`Jrt#;$8(z2bmy6uiOH0Q7#IbF9SCyhWHWM+fEn-hqG z9HE2+q8-hKc0}cv?Gt81t~JNoEG|`Ebw+o(ZqM$_UPI-xUCmZGy!^J`IYJ2u)`IWs zs!g@unGw`758a0Ccecvmgvvn)3D&xPUH_>qYPD^*JyUHEXOG^pZr5r9zt%ULx?b|i zt-J(th?K29E_7?Ccdjj8wB?ajEyPyldg-@qEO69ET=MiAo43c*+8dU=j_sCyo1i4s zl@qB<+8ZvsB0;UZOf4&&l6Oi=!mj=AJ#CQaXj%D!O0M$d<)DPWYh`jmwNOn^D`n93 zTF;3m$8V-JlKB1-o2!oeT6K2ZhgS|z81MA{jTs*P%bTKJ`*N}~Nm zg8we)!H6N0&+l{DX_X_L?Gu&39OY=AV-uC9KKCkpzv+@*gw1>U5N%poIgaGC-6)(JI~;)p@}E0nG?8wMEKpObBj{;cRjTQ zK^y#CJSzo32?>>0b!B}?AA(wVR=SDyb7zt{zl$fW4?!(FT?L^XT={EjiCR6a>)O`* z>NjrlrvLpLXRJ`qYnKudcR#m;)4POu3xX07vLk!?TW*5{wRZi?YEC?P(8I;OO9=^; zOEy%_+y)71*`4Ub5~Hs!h?IL?Ctud*|9I2uXYO;?si#c&QDkm|5)wxqc(v3032LQ` z|FLzFK+8(&iK2wWyqEvPZS3*rP~jB`YT;Qa2ugYq_I}JuPNH*dT6hKvf)WzAcl!|3 zN@sTTXb(zAsF%}S(%l{;axFibLnjv&cS$gw>l9_D<<;kIrvV%UaX_u2EFiUDA<|K#y8Q*eHy@ zYxlJOQqSk3BOzh;vH!j2^U)!wWlxv?z56anJ2BqN=u9=WntF@07Z&Z`;x3_tgq_CV zHgqaOURNZjm3Fqg2hRygNSJ4Cqjj1`i)q~@*6+IS>cg#n^lSCCEMIPe5)xKNPIvdB zB&fw&sJ3B!yZ^4<8T2+MC?R2#(|SWx6V$S|o!3>*_h3gtg0-I8;BQgO-VFXrdY9w` zB_yg_kOZ}=?_Ekr*t^TU>b~1aP^xrU-L^|U#>Rnt-P>at>PEgW|&?uyuXw%ZFeg=Du z)%8|r(|W)3wjoJdO9Wc84?!)oO+ipX0{226f?8;sf}n&1?w&pbwa_*NK?w=mJ$(pj zwQE|>W$*Toq!(d5bwS{6(A&lDaP>lXmlOmgB=GL)Lr@DnQ8O=SYPJ8~ zeJ8S=*&fwxP6-L#3%OS$s3mXGn7U{WN=V>s*N31M-h%}}2?>lc`w-OXjAU(HBQH56 zJqcSosU|wKX<-IX5R{O>7`_idEzC;_f)Wy#i}WE1t*L5rtv%%>xBssrDTtZ~z4fXI zN!nWGZRmYpm6A4L_68uRWwq{v-g>!Ll#sA`b3*UNYJytUnoihUtsp2N!F8tGhTY+v z657+%xz?CRwV=0NPIPS8UER4hPpSz@NZ6h4Hf(lR*dReIdYgM?Jy~7;s<&)ktGBS; z&i}5yCMWDKZe9JM^;dqa-qhZYey#UpPEbO^`bsC%XI2x`s`iQ!66TqgLp^J5g9NqO zwb1?kU^}x$StGd(N=R5A>?OBZQPF}VsKt8AZBRnOMh0%fW_N`R64bJHyVsT8zqt)c zNZ82037b>*A*f})?S#e=xeZE4ux)aJ5)w8ta2qzeFWQ_0wW`~^EzvX4zSf;#&$rvK zC$6wT2?-mQI$`suJ_NOFbnb*b`vpM>2^(JzKv2v2TPO6^%WK#ARhQ`fWOD<**4~uO zcm2A1cZm`b+LKftbHF2)7yD5psD-~5yG!_8?G?2>44?~w5)#!mSU<4mJEAH_cU`d- zNx)uFyCkU9zGE~($lHUGUWDH9)kK??mezGu4%42R6O@q9y6%4`sMV%5Ldb3O($agq znxLe8EdsSr*l26XI<-*i1wjc3v}PZIT6i`Kf)WzA-}(^LLLXBQl#oC#(TAW`yAJi% z%Uh6=UWE0JeTX(KExdyZf)Wzw!TS)@!sw$QC?SFILmz@#cx%`5x}t;x-obqcYT?~p z5R{O>o4O#__o07m;JQyQ3ay5HIpBS8_ty!~8lo1i&4!|VRbv*5rEJ4GYsb$@RXObY z8(;Znnfepzqtud$#I-C?Q75A21SR}kwoNrbtv@$!3ill{DgJGf6i44FhoY11E9j_m zWfkXa-&6ZJwxn|#B&emRW&1ih>IBxD;O{D~+P*`NI>D86PEbNZ5ykekdem94)daPw zORlJ1`))ewY*xht+gI07r@7L0wG9%AN477%qfU>lCa6_iSC*?d*mu)WXR|6M*uJ`s zI?Z)3uSh5!*}nLWIz6`9D{8SuazgRC_C<8m>8gtGwQs1S&S|aoiUhS3yK7%ZN1eKw z+u-ji?%2NUjyf@xbWTu0LNU+wRe972wbcZ*SnD~V7+w1cI_jiVMfln`)KMq6(sngL zEyeNLm(o$EuI2=PS24);m3P#Mv7~c?5)z7YwlB$}POGgZs8!t_itx2>sH4tfRZOsb zbscrGD{WWXAfXs!`^r1&^w?^GTGe%>I9L0UIO0>y?+pDWwG{JgUw`|VwmG5r zS^Gjc>f}>J;@Y>)QRk*sdqpip_}VwrQRlQ)6O@opM6rFd9d#CL?iC4Yv1M~Y5x4eD zbJSU>iruxZqoYn*Xe#6RdZSL0@r9)QQ2gofDLhP~5qF z*&lV%YBfPEMf=+K)KTZO<^&~*D7J65qt1V&?VO;5grb)1yYQ&9XR8Tnv7K6@B#o9d zYSK7IBP5Mtl#|F}QKMxa3LMFH6S~_=Livy^$~0P@AM;8hG1_Po)MEK^f)WzSHe?Z? z(eervHb_uQ*^MkNHCpbXK7?}lSbSx)tUWphUTfEPgavUZJ7|S#o+s zLK%%L$~0OYqrwIWYU%Ioek`vmme9_zsap(hv^-A(dPPEcq%0aZT4ta=UQx@=O{rT1 zXtcaS1wn~28d;QSw0uPadPPFHkt|*{T4tca2J4Di$~I&XpwaRQ6$B;9Xk<~Q(ef1y z=oJa&avuQ;uFgc1_E zZqIjGvF&;Wb#^fci@bL&i(=2dXw6P*&b%UFG49@D=-=$L=8T{g)?|&qY0Zl6@AN+G zaa3ZJLtba6H7i!XBO#I7z-i4HK`oVDHdMA&b^_H^itg`7NU%(;sD2R^9Y2h<9(}#x zv{pRZYYwedHANJ+2}(#btxIYEhK=B}&X)k(yb*SoHMSLYb#1SOU`ysmy%XC?EOa)J^PmaDw3 zephERR}<9IFR9g!|UpIbyjlj6(yFFysmy%XE5`Za)J^P zmJhwIeplx|R}<9YJ?6P4z28lFIoo>>%Cgzn1yHn>dIm*{wIbW})TX?g9SI3M!Pb{3 zT1!OA%h@3mp{3tdOc~eCT2W^rQeMuES0of8C)(7eNw@X&oUZs=)WYAbt`wms?Ua|( ze@lH7%AqWxZEuZGoSF!$E9K?vNJ!*1P;!rXOSP!Hob56xFQ@;KqSLaH>s-c;gapf! zwYg4@a6-H7@Ji=w*R=*{*$S*Z@YIe_LIOQsAA(xSnV{7{oqV0!poGK*x35vxTHj|^ z{76AqHukz!=ydwDJ)9-&Iw8^4}FKQEcSJ+4(inIYJysQrmX7hl)vpw7pp?P`Krmi@i1)j^$hofG_B%UoaA>Yz^QCY=+Mkg!bob*&ESWbkT& zTCDY)u#E4%I;az_Ek}G^tAjcdo3^V7YFYMoUmetG*Ezx8waoQ(tq$s>ZqhkH2?@)Z zU)SoOWtAvwkf2s|dstq0Umesr*p^}5R|j>XHh-zwD-xE)-d6{8YIik3t?Ih6?C8Ea zsMDY=&$_P;S{{M{y&_>*?0t1mr*>C+MJ?7yH_;y5S&n#L9n_iFgVhxY%SrF6gF1t| z+lE#@>_s}2T9yOfR|j?GcTQLac3&OTiPM(9-B$-Kzd@h6qL$^0_tin2k3Cp9NLWsK zUmesL+__i$Eo!l4bHZ}A`|6<1sJ4vnzB;HAuK7zjK?w=VHt(y0I$gV(pcd;eCs^JvOH8oS=k+WqkM5L7i}2O;F47#rx`@~v zD{ehT*^Oy~1hw>cjUTo5ofGs**H_GUs=l}nyKQi37`^|PxcL6#3xbkG*S$V`c+c2) z-O7^!f2rCAi7kJ0Z#e9>adEE4vRbJl>R;Dt16|)TV@6nE?@96c z=HhmLR1wr-jpPI+BzAn^_hI{6CdN@aEL_+iL9Lm4PYth~J|WIC`6Vkky%N#BGf1y+ z=a?{S!C%DV&s4-A2}(%3@tH~CbN7vnZ*6sbLD2e%%UvACJUu>+-{UU6aU$GpAkw( z;9FHAZod3sC*C@Gzl@;PH}{|9Hm)46%y>udeWw$T>~Y`-B_!~*u@Udze6thV-}L>A zpw@zSoZ&X^Uw1QOrNHR z+{F$Z>%`CIKXQZ;68OU0h@I9u(TV2{J1QfnrE5K1`f99J+j-@0532>2S?i_dQ(xM0 zNPW~nE4*xX!<;zk&Az_prnB}uEq>(QyX@~Ia>*P*w4Q=i6gCN3r&rrtG8EKPZ*%a* zg;$i2!1w!o2x?uu#o|Hll1I-NT@aLzU@hb&Cqb=ao>?@gPkiTvl?xlWWKLa8-1@d5 z_0(JLyGTK>J+|6y%#hvyUph+Pl+2-XuP7n0{c9Hvjeo?xvUqx)!UhRyb$R7IweFIy z{dLi(-g5XUm2i$H(+^lSs;7Q-?$uj1Iz%p+Ls(5m_4%5=dpUX%)Ux)E*}dB#C@Bfq z=-llcg5`Mmy?Nv4^(V$xN3E2VDffz{C9(B|w>9)OIQy8?f*l(qsI}&9V;bsrH}lrC z=c7YV@{jXWw4U0I4SJPp@u{77{QXuJwc0-> z9WXL$qe))xBVXM>Sv5MXcE|F+^}la-!n&rr__Sx7`25)Kj8H$=^}4?cFR6DNE@{qD)5&vN2`vko7jgoM6Q z7p<>cYqeYVy26PapEx8VsKpwo)mB*WIwvOo{RdfHknNkh45(%YI8WgP%^7iEUy~xY-I`R@)OOKkog|vi3VdneY_uT*g zbIx<`UBA{c&u{*Ff9~Gr+3)b>odo1hlY>|k*C>NmudxXFc=&3^KR-Qo;>;-Al}G&aRq z^X#wMWEg+H;flj#aagUc^GGKe?dc4J0R zi#;+J?Ei|Rg1GC@>$1Kgq473scxFBr{L7DDAH;4CU7ZosV!y@ASodx{&(h2|#$C_M zoVDtEMKQ7MuXyP#)7M;e*7Tv@x=nA2G)r0{C?VnBzJpEY1Z`-xH}kmbxg6=7poD~G zlrxXJp38L;)OyF3o6er|$8)FeJ>7dqvmLw|c$H|rK8ty~=I=Q{35n+1c%I!&P)qam zna6q0xpRUN66}#~f?Ard&-}#kEIlVEA<@}abIpunRPzjzgl5Juih4er*_cy80&VIc zsD<-X5R{aJuVc@LaN<*8Bsz4qo@dsi5WpH zjEN%fj2clw0#70lct&LewJ=JEz%yz@NlBz$ziYg9NqMBRQc} zL_F2Js-TBY(Twx4nsNT|nP(I>C?VnBX}_U54kXIY9{t-|HSl-TU1HwfsA+ zYYT#2X=WU6TVmb|4|5yzgoI|sF+=toxSODs=DacY^^7(rDAC+D#$C^1X*(weqXpFvcoA>Y}(uJz8Mpt=>I-`5nNR64MQV zcLO4Z=^empZ$CC8sD-tYvKvtM6_9ZthyIBK&vHrgDN35}JKSMA38ZZX(y} z@`_rT?MD>Rvu5^NZi5mMni&t%JLJME64bi#j~^L+M(^}b`}u|iL5b$i!}O+kL9a+? zUOh~2pzC{Z>3q;DYUO7Z@hFefOJ|K|6Ok=>h?v)y5)ys`;&bkqr=B>=akY$~79w;a z5W5>wLc(tgY{N6?<@n&-gnZs%#*ZI;Mn# zM)0sv&r1-m%?N7w_wv||DDuqT5~TOI5%W)PXp8DeB=p=4>wbRwD}jda*Bt51t=iE= zP>UYs1SKT=%}09oTG${#t?riltBv%&-SeHLHl1>>k{XDLoU1` zK`nnPk=_m$1SS4zBfSM)&?^!rth~HBN#7Jb?6vPHY|txe`R~iu)igW!Tu}S6-!V zw*IlTjjgX7Q9?q`jj-XBfM)vNdt(s)ecuN&f?Aq&gbh7~L}=X+gx4XIl!UMLnsD6Q zE%yvl^Vv94`hP#>FD*Q-ct-2LoABS`ZB#}y5)wykd0+MJ8{RcN@CN5J&<4Ho@5U2< zU6J0_$_@!iNHpihbH{FiT95g_(?+M>d)~A5 z6F6H|wFjoO-Q5lnu1?@=S=AvZZ17mr^50XHf`VWRU7f&H3RHVw#v^rmMZ(nyT%|yD z2zvU8TCPsuDg~-ZP!N>3I)SrgReNB;z9Ql31kRRK9fG3eY$3H=oxs_$s!31~l(;&9 zvt?C#U_q})xH^HeWmSiuutBe=#cM3fydNVIeum8ZDKhe91KIs!N=W#(?`Bmi5P@9% zj6i;V?6>8+`NXLA`myy!G3!&Ve&!Vk8a=D4ni=L}iZyX&#RSJk^)&@0!_YY11wbMC8Z-}QJ!t?s^ZMLg%e zs#aT6#B=Ve>fJ5qm22oVge&4X_f@s;dc2|*dnCWEToKQ?uc~(!74e+=s!Db}UXkFr zaYa1mzN#Wy;gu`xHOF;DJmP!r>bv-S3IsO;yL$K_3nCX@VF#g5zo1=s(n}3AVIC}^Wlnk zu8gO8a8VJ@mGM;XZb7eHL$4uR5zm$JRQs;SD{6K3l`G=8GM?(FMMXSU##6n!1-)_& zy@qf_JXgk3?YkbYsKp-1uM+oeGgos(JXgkh+%+Fu&?^$Ii08_9s(shv6}7flePQIj zs#04)xFVh_LIA*T25Z2s)AEN zP~uunUT5BQ@s106MZ&e5yyjFLqrwK;k!vmQ=90JEJ>Wi3wsO>R@+wtzcV@2TsO5TL%{5k6X0oO#9F1KG2zPD7PkqrIx75(2RRl=eth3UX=A!6DhO7SXCz64ieOIEvKv< zLAV{1kYKOJJs9iSH0~~)HJ(k^a&k>4Rd7;YY1~~RC?TP7EUty6k-C+jmTNhAU8@RC zg$+tbxR#Swsj6305U%CqwWVqX&0NdLD^^u)l2$RoEqO&P*K+duQsnQ6>aoG&l5j02uWMDcsjxwUTI}__ z<*w!Ab**YUMJ*?i-2dRk7c?(^YVPF~lllF`()oV-d^rKWgVH1n>!9rTKXYdLvctEx>!%SlkHyRTf! z$?IBG0Ghg%lUJ##)U=>iBwWkM>snQ9>hX$N?2&a_-puY?%gO6nRccz$D-y2dl8%dI+9D60YSG72gl} zRpAv0YVpkGz3W;|Ue~H-(A2e@yh>H2rUkts;aW~!*Q#n$k5|-UALd@M-(Abe>snQ6 zTF@&JuI1!)t*SQlcttJOa`L)X6`Tr!64!F_x>l8%7W9gQYdLvctEx?f4W2=2@jS&l zfRQy7?{v-OndfSLkM9_2s`ws}QjaD6`?^FUA>kNms`%bRP)n=uSUdaQ+y*5i979bN z-+KsZIfj}lzV{H0p?U?Ocvr+wy-HQ&v>+T^Z6uDNri$-=GqFHBNH~U?D!vyscr0r9 z@6G$Uysy|o$52zn_XWKo;TUSF_}=3cwH!lD72gYj630+e#rFlhBHR0U0tr%nwjzQ7}k88?w9p_XGG6=^YDIuXqV|bF-_5w<7P}X0H{#A=!|kDj1bZQ($U(S0B&cQo zZNr|{{@W|JhY}KbJ3M-tP-JoB7;4&OEIWhj^?JPRBHVJf$1&8j%b0qXHYnk7dA)TL z)N%|p?J`!_a11r=GB$Gz)oV`0KK)$=MmTy!f?AHDrd`Gg8$7OKsA-q69veI^3CB>= zE@Ooa64dH$xnrnlm$8VUdd;Z_X)!Xe<+S0bYeP7OnsyoM@rqjAedQQx+GQ+as9tj_ zLb{+=j=DC4W2kADF8^STvw98nJSJYyUKj-jSq#(KP>mSd=C zm$8Cy3^naC7BSSc%UF+Bj{&ureij-jSq#v+EA zb{SjHD@R=$!ZFme%UF+B)M6jzUa{XDL-m?d5z+;{BHkOR zSFDPb_7K!^4ArYtMNSKX630-z&QyeSL9a+ShMM-r(YNQ0Vl*vhJE-N@qg$>x$aXnF ziDRfll#p=z)^vSG>HmfeQzWQ` zzpJktL$$W|`GLPNUNvJEycOXXstL!2DM8EWtq8Q7z3AP5nw}n_O(GmawT;*rXt{qf zf^Ev~LGMczeWI~8zFkS}h!|?xA4mO#yLRm8Y9m2A;%k>QQuh!T?IMPn_Qxp*M^_sO z3CB>={x}8U7;4%dXW|%Y+8<}aYdUWSwH!nBx>ga=9)iar;TUS#A7_%=AVDp*DJLi) z;TUS#AE&TEf?C~uJ#U9DMatt-?k27%$)$32iK6|_(!Cr6-HSLd6c*Wy7hMM-r z>9N7%l5h+)?T=H~AVDqmdfsx!P`$2IgmmH2efD@og7zFk^}1GZ!on*a*D=(z zKTeMg9+!k;sA+$k!UhRyb)OH%P`$2I1aXaHs9vQiLb`@W%KM5E5{{vIU8`tmk5|;{ z?kmSoy{=W{ZH;57UZpBRx}aAi97FZGR?*Tm-R+4!Bqt~#;TWpdwThO0xtpMtW2j!&Dsoy7lsJa!b*&<#U#9JD8zdY<^}1Hk z(!vIhMJ=AE>>U8#{Ew8E8ejQ(7j3+)AFWIH{?MEMj8Oh)eDSN;XAeOwtir3@1|=kv zaT?zXdw=Y1f?CSjoTj|g9>OtHuTs6kv16!SrFyUI+y*7eGL2ZO_r#{RIY9{tWt>JV z)%#<26V&pN()+oBU<;LHI!$@0Biin^K|&d))0CIm(^u3|_USa`r4|Gw$}){us`tcR z%qtSgIE`4U_s8yT2ep)a8nIOGm7NomD9bcrsooQNF|SA{<1}Ka-XA-+!DCU2*H{)G zoFiU0LVU176i_xCb@e*Rd7YGy@Ncgmb@z&JMAU?{G)W*9n zK`q2sML33PubgM=QO5pyEa8ZQ*sTb}guM%R6JO4V+y-L889^;Xdu0PL;W;HF*rx1z zhOzQeW6i0UYQ=NFbJI_FMDHtijXeo z6$xdWMl4m)(jKp<#U9D8D`lBREL9QG$}v>0ITict@rne`jq)HPmZ}(D;T4aoEYpak zDni<0gU2PIjMIpvDq33DAdzXI*YlPu%QV)UijY>0p?b}!*k_MdBxp~$ma*nkoUrhU z$5obT#8MR@?Xkh*l2FEJ#8MS4Eo_jWR`>Z(7G|tD6+x_&Wg2TvMMxL)ii9#wW6h~( zX^&Ub>h3FLFUFcvk+(`&rm^N!gmgi#NGRhp)|`r#_IO1t_DFt}xObbmnzBq|&8Z0K zf?knO#%aCg{9o_%$8ncukXp)*j5ViXdj+AK%2;zM9#|>kG}fGomiBl>EoGU;no|+d z9)ezxP{wJjITbA}ydps@p4q(R%6E)4r($)LvP@&msR-$UUXf77X{PN`B(X0nK4VlDrLpX+-@=|*UYB`3Q@=^IfEm|P`yf3nFk#F60u(gh%ro7Yzy&|EE(_zX>?eU6Qj-jT!)PkTy zS*F93m%5-=B$RPFOnIq=4fYkalzlo(d8q|KiLy+GDKB+FuSh84beQr|3mf!`TD->U z7^*ZKC!8bq(RXdc<$c#8qf#~;Lp7mTmjJ6?9=#0Sdr6$poD~SE#r${#R&^S`Hqv6mpW3$=_KW)N~;**mfArr$52yVY7fC< zk=RZ(2U1>Y;S~vLu}yjJQbIx*r<0VITG${#t?s^37Um@7rH&j!^}1FO(gj;iLK&x% zl$Tm~#ga2ux7;z*l$TmL zhU#^#VxK);k)S=tP*YxNJ(F3w2YFm&nNCt(YL5*bmxMA-Cn+zrr{&b@J|B*uro7b3 zG1QcoD&M=t5=uxohMMwHijywo1AsO1=H%1iAbcm_#0 zhMMwH3$I8}i)S|PUB^&UUTWnSYRXGp&?^#-p{Bgl9BN86Uh1#)esIn%qlf(9 zqig)X=Uw#trQhlAtNiy?A|xcz?~FKQZkETQ7XH4fv9S)ZiUfWy5if8%<~$a)(%;>_ zb|NGs((jC@ziQ;MsD-~T_0>8Ad$(zmZHV~BmFM`0GI;4ZZ<;@2$EQq=+3d9G0S_Hi z>38MdKUnjlHU9fx&kc0W*Wd47gSceXTjrFs5LHdwvCE1eK6BVf8IkDFx?+>(hK+qc zvXN}OXxj$`am-KtZB9uGQPsqupFYl4^WaDCJUJs0owQEb&h1!##e=20+53JwG_l8z zPu7*PEFtmi+djFQi0b&i*sIMqeS*IF84Patb52m}ww+FSj%|GFv9|G*dp{h+(|&jI zoRSuzs)^BC&z{=G8xPHiM2FVamtDNdHopGp4Q1no9i4@)cKqAF&namks+xHCBgZon zTfI$dP8=)!4y})#_VA%?yztQVW#gVJ4-eu=N4<4UNefZc#4!ieyJz3~=;JdY(V_K- zU0)bBPCos9oryo3`Khq6`j%tol(Z04O}yd!tAqILUysg+M2FVNH|-NPUVPb~WMkW} zel>^_uReNCNefXWVxR8?@%5{Y$cRLT);6b~8aB3>-6b2}J@RKk9C6`m=9IJ$RZU!X z;07^PJ^TqT%ZNmW)@LrbC~Q1%$q!}Yd%t*S5G%jD|D2K*qN<6tFWD-H_3qg#BN822 zcf93`VdIn&u91x&?z&wN7r%RtIVCMbRTIBHcjq9UyU%knBGI9>*Y{^(<5RcHWaIdM ze0oiM`dM>IT8OG9_I&-bgE;c!T{0rkq4kn$ZwwnNPyCE*96hOmc*CtL=9IJ$RZZM+ z@C$-iv;Wo^k?7D``>fl;#_A2vmyMsDwoec%_u67kNefZc#LhPz7{tY=ZJa>qN<54Z#g`Ohwr~OBN822#~$*huyO5s_mPb=zW&-E z&b{(mGfG;BswN&tyTpt)on=I#Lu>P+{t`A`w8v03&b;;YVdMKdubxrTLR2+z$BXM- zV)oeO;*3aiX#MJt2UQ-g9{1P3=vn*cf2enf`RupPno-h1R5fwQ1}BDBr)|7fMkG44 zp0IMGu(A5OlV#)SH=Pv3jZfZoMo9}%)x^HL`nfR}{N3ckQxfTSX!+UXc35vP_{oh8 zv28rH8c7SGQMw>19xMG0E!fr!0A5v;v=H`C1X?~K0k77e*F~UrN0hV>?r9M?gBgL| zU4yGf>%*kr5b0CwNMTz|&w%Nekg8gNQdSKXEbwPlE}bb|Uap8&lFk_z5QhPtJ_MQ*DB$ zwut8Gy#76VjVWm%{G=9v89+wh={&*gLj-0SV@g^G&p1S2CX*4EWlS)O60z;_Y-vnM z3*niQiRBqtMqsuy!E8_jW_@EyS_sboMPO!`5t#K&Fss$rd+hS;bxcVM;hC%m%#bqz zv)3u++9EIuA5+poct$P)GyROfEPRSph6t=C#+0-WURj91iX|hknwX~5%T%i(5m*(C zDIt;8SAHUiz{)ElsD)LZ2(0eLxg^$Yaa^q1L|_G(5!Ax!Rm6{%SE*x4S_rRLMPMbI z5m=>8v8EP*)%KW@7Q!oU5qEv*ijkk|TYco%jKFGp`iOV!Gx5w|`~7@JeLC%heYW<( zrlf_aYT~xPy)kT@d+m`Kk?7Fc_3cN5jlX%s?`31Foo)_dy+0o@rlf_aYU0m(-W|jj z&pRX|5*=FCzxbT6vHu5tA{#5#8;srZ6`y;>n35Kvs)=_$X44>Ee&@a!k?7F6ZU4)| z#@2UzTQ;uUudbf7<$8OMDQO|9nz;K>JA{p+x7&)?4gcqvVdJGMcO6sGLR2+z==(-N zeDAI&XGEey>x;L4KWwag$R)Dzg`s+`BSVkl|w1#(Y6gEzH{6IF||CKs7 z{NmqVS5eYJR5fw)jdh0fD{tO5BN822&5=BU=zRRHCJw&&!$V41h-w{T(neUT`MbPY zH5kCFDJ6{!5cW_6THZ=n3%xD^y*s0%u>rz8EdpmSBhb66aP?7xnUBODoy26z-fOS( z*k|8+*8M{G|NedUGa>wD{qnxKCoRb4Y*^Csm$N43x2^wH=f1BW)tT%Np6+_T*^z(Y zp1Jn#AuN9DlKl5~-k1&VI(?0L6tUO#m>+P}?9LDtc7<^8k-hmPC(i*#+gL?tRI0J z$lt}`T`!GMk0R!uGBcl4T-brV?G9n+1J@Nl*}N=bRPBn;sAQKM-NSAw-dI0~9PR2! zHuE0x=*%2z)?FfC6=P?Q8oBPuRW*+y-0m$$Pq z#Hd(Te$F|nF`7%Gl3k8!)TqDWlq|G)s3+OX3p=7?_^5V4RGwA{pz()MHPC%*RGKT< zjKOFly3fv;M|7Vw^U9+LtXo9);mq-e)s5&rwz`^2qmo_D96K1%eXL5%<8q!St7iyfUu_;>&iTe@EXIY7GkYfyXZa{&N=&4 zh0v&EmmGdRfM^@5o@6txpBo<)x)0A_dIR7YG>;I)%!{ayC5o0D@6JHcnZ%yc4_iFaN5-Pt5*-|<@?V?w@tNrrA;(PL^}jU zT(makmktU|dcL%wGrxGn!De$*tr6Khlj1eKMm1YlqFLMA*OA5uU3b;@Vl0yal2)N0rO-T9mIy3xw8>@3U3@ryG?b ze5DOtUtP_mQF_wq2w%}oIZR|5k5ll@qM=% zZ9hciQ3UvS69$@hgI(rPAv6l3;w=>j-cl9eW7nCR?en0GXQm?5<7=gePOk0l5xPG9 z9^~(d%AuYX2!DrDgwGc23%TdjDgZ6_b49491p;&0b*&WPwnbsIa@$r8^|U~6=Geho z&RE+ zMQC>ofqTI{A%`L~>h_H%!BLp_Sn=X_ba(-vND9E#8=uj$Tmt$02b z-Q5+&%3g9tdzW!2LZiILI0yR`_T4zt zqX_Sh{zm3K(Kr;LQQm`{+0rLi<<< z$2`6?AJ93$I255#uda^ys>QSX`Ekhn`|^?7_csppC_?)f6tibH=cC3SWgLpos6jVO z$v?Plf^+-M^<4}Y~{ptB>`NppfbdG87>{YyT zZ8PU{P(6y!J{H1;>yIh&eV)sEupf%hsBbTwo*<LNA}YAUd}yNghrim|BU?df1l|bn{WPnvGj^feVm7S6rp`Agu{=UR?Hc;xQ`r) z(5UZxGQ;j4voTI6Qaz+Jc`iH z7Xs@R^&7b#noFa64V{B^d+7Z8j6*$&&^{Kz7g4vUU*k}OMtLoCmh)iUZW#JzWbLX) z5!%N>VBK!rzF#JFWw|uUYuY(jx2WHYYo#7VXderq4|R+BH4a5+l%GxK_%-Sl^_y`X z>QRLDu@KHh-J*Uo?zti~%6p7+EJ59(er+D=QAE8b&O_azevLyB8bzB=n{q$i+BPu% z=XEz0kN%^*_J*w84jLf8C^q@#9K!0iZ^^HF{cHA4tsX^a9}8jmgHPmd54f`U88{T7 zQRz-qa(uYzqdZ%5rg5l85!%N>n1Akm#rl`eEFK1jA~XsLYrgX|E&aQ}Wv6|)7%;gf=N(5qiqJk5LT}H!V%xN3`6J*^ghu)O$~o3vb#<}sje$Am zp&mtO9}D5-i@#eOxM)QmITWE$`fV}<-qU_?#^MI&p&mtO9}9tX``c{;BRLeIQR$vo z?g#4@^&82d9z|#$3xRce&x21Ghaxn}*U-K|guuE*{ThdQ6rr6j1lBF;HF8@sz# zj2&LQc)2MPm4_TDiZ=2$@&D-5FHgCr8_@+&d_%4wQWXC^*&+P+(o4EAq5>o1)1dNb zUfNXj%9-DE;plGMR)84Y50RpnDcK>Mwd!83mE8@Pi+Q+`j8dC(DA(%G4=v_eMPI8L zB1JJ%vP1Z=eH_;+^R=ox)NzD<<@11k)xi6xy)$SO?KE?| zKSbzPzPjM-jgN&cV7(nx*E_D6a+QfPNK47iC?UM-g7fO?DvDuVT_(HJ3(tO*hN6V%>_q z%kyC#MfiDi4nKoAYgcn=l%I3w;5pyAQ>W&sHIE{^uQ&&LNz%eKmqvMyaSrw?(c9Ut z%%ceJkIn)8iapWhp}925d!=(gziL1Su)7*P>B*wquHM_BUq$Eu={{I>eMQuJBJcmu z0n&Z2LTD7;wIcK@e||u}ibrqXKiz99k0P{>nSK?a1EhOxh0rLxGe+oF&H?=@LI*Gn zKs}1kK4$t=1|1;X&#PP-g?HZw{mMCb|NrB)P17>eqX_L|re9^nKF^t!p$Lt_JA8zG z<$4M4|In{&9_mp)7epThtDBMLN^egA!{eSTln@n3$k0P{>nSPZ)2QY0( z5gLU%6?$dpF5i9lzQFHZu3uFiMQ9&0{VJpW>iSiM&?x8bEjd`X)L&h{;tb8B2<>C0 zUuD!^$)UM4%2(YvpkHOsuZ%-IiqJl0`c?KG^jB(2iqI&pg=RSq)-Cia(_Yo12<>C0 zUuD!^IS)l>l%E3UfPNLJzq)?KYB!G}w2zs76{){+9-2#|{G2-n^s7ky)%7c$TJtDE z`>KB3`K)=eMUm1sb6rp|0^s5Z|m1zKq&?u-0{N1b1gZF>v0Hy(`M-kfj zOux#Y14Q1>6`@g3MXFzHhQRy(-jjQhUQ&4!p?%Ess|@;;X)>BiqoCFBm$I(O@cs`S zAi924c@$CaiM;z4Yf>sK6=c@&|2%=D{_`YZQCb7_>Xp>wcqKZ5?swNj5Fw2zs7l~I4ChO7vU z@>+1!0Qyx1{VM6A_DgH7l_Io{nSPZ)zcTGrb7_>K^;hn>dK963%=D`W{idKwd??YKstjP(ZLq;GH)7Uy_?dtj%M`fBT^uq`pue_qt z*p;5wq#iY?M-x7%-IzCtw)nn6>c#|XKwAxFkKnt>i;du#M~zglsK>k>1h?r zIj7^wqB@cFL)y}K(c9zCntat=j~x8%Ig>~4eo%HC&Xs7?J2XP53_|*+^782$GlDft zbngcfY~|lW$os(>CNQQa<{ z2w}0(OjteUNj+vhx?>O&_7I7^?W;a&WAcdsm#yYZcvSF#o_i$zy*mL76X?0osCktS z5Ny>mDvdoSgf9BDTjqJ@gNbOx8PVOjBlXZTHM~Vq}hE>=FL zyAy1+>*N+CUYgUgbvH(J!&0m5A5N_wT`=3^{eM|I`ocPsw>`Z!~cm4C;IQB6R@ME6{ATWlpOk@f>CQR;&=OmrVtGBVm2 zqZmsv##F`_6I$hRu2{o_j5j69BasQVk}N1ut{~2ah^jb$s*E`=vrFajtYr<(rJzCh zii+8s=86fnlKI%h2Wyz{{>jXnmHJ?Ut)w36qdd=9!vya>sgG~nX>Fluo4;o=s(Ese z$>n;mh6x#O8dbUGOt6*A6(!0QWDOH8m*+_QMTPyGd+r2w`kY97#IvYa>3d1huD+MJY(#%eeUu1!xrr|< zPFPgaggE^39W9AW-vBr#9#sfWCK0BDM+F~37jGm(1O6TUstIVAz(}-y1Ua{JRNNL@ zd4!cdv{KM8A#yPimr6Y{A526m&PaL+M^wlnd~k$_%D#I0{(yX^1R zWgo7|2}D(X*>)dzC3nIjT=>pOjq0delN0DuBw{_pN~>1%R;yO{(C^&|Xh3`HkllAW z65XoEPy98*zsH^@QE|JJ>G-=ywGWS-GEGtOZh(`Fj|QBaT;>x_y5q2h3CPHiDDLwGQnqw5+R;-K7)v|_-MGlGT|B~ zAp7_9l;M@~3c?DR##syU`mu%bD;eLsn80cWEBwwS-_-|NDiKk`1lD$^Q-U=vBP!et ztE0kM9hw(fi^g!$hrF@5DE?Mtzr=ArI1(ms%c%Cj1Y7xc8}00abHy2TqIXnG;N z$3b@Uy$@pv-|@S;jVs>OSR=VgX!tlk;Z}&YtBK*6!ufI}5ygo8qM!Qbf-x}b=hf^{L)>IJ|6;}{%88kAq=NOez&31LoStC9o z!KaUOlt@%<>PM9E-N$j6a1DGgJu$AhAKVs4g*Tb5^CN1Q;EYVv1HU_aBt@NLRNgtG{%^%uaqbM6U2=$tOU~Rr9ecF0Bur*@rWg#*4EvWG684A=}HHL?guZxx;6! zN(i=sjGo)MMCM2Ri{Ck3f8fEj$^8Snb5TM3#-aqy!I)9kG&Wpvtp3y!U+b_YCqUcV z>(RIDZ`?KSNPX3{%M${$TX9B07+?Kd<5Pb>TtB(@jwDw(0UGbVTJz?O+eYfsZ@w`h z(5_o?-n1SauSfodjQk+e{5ou7*XzL=K2u|UOk@|M!|TBWTlws=3SzzTdf-fj*kwi~ zw>y4~)_SzP9<1RL8K3P!kb1Pe9!#(mXGH7K_Ij`;C(v^{w_^@^J(z&(R-CuA9yr}o z)g%K}52>Jj$6QJ4!5YX;$Y@vDMmyJo3ATa^-{pG92v-g20U17ULY7gf-)*$Z{D}2n zO-_Ke8O8Nr0%jzMx8l4>J;tXrZo2=u`gNaO(~+?hdkfh|CI21? zVpHSP%SY?|zquzN*ebn$Oy2uuW96K&`tP^i)?p13{EKM_gKzdVKlXti*7qE}IU(4J z?`xry!Zq~b6IFYf23BDoO{_*OmdTZw!%MyaEx<@7Z zc8mlvMmwUCeO~2wW@udY{#pws8Yb8ZGWui$=ZZB<$azJ5#IsMV2NP@s89w6qD%PAe zOvt%Qec+^~XSg`7m|!c&@L@#$O9M1`_rb}6{(f5tdyUG7sL2VZC+-H9Uq7gK1J^iF U+!OSkXg>UIP!Lg5Mc8fPe~5gy=>Px# literal 0 HcmV?d00001 diff --git a/GEMstack/knowledge/vehicle/model/meshes/rear_right_emergency_button_link.STL b/GEMstack/knowledge/vehicle/model/meshes/rear_right_emergency_button_link.STL new file mode 100755 index 0000000000000000000000000000000000000000..4bb494cd51dd0cad59999357c16eae4aef315546 GIT binary patch literal 38684 zcmb`Q3Ak3{-o}?x85*P#MTG3OqBwO>`<-Yc8j$E@I0~gfgXW}CDwPIFgGA$&jES`0 zcdeI{lIqZ@h)AIvW9A&ncR%-fTl@ZR`mXO>*LSY#yR2*f|G#yw@p*pl)BfJ=dH=uv zD_zR-GINg0_q>tW>W^Jr818*!UfFjRW?FqYI)6gn+-`^( zN{M4e_9C5GeGC43q@&UAETI)8Zu)*c>GaSR zxMoK>D(%uMVu_RbUhDSdrREQgPna@_+viQcEUwv>(25d;)uxl)-{u6+M>;C)(ko(# z0dq>br@?#o_XY8d7p&p-$ZO{QACF3j6OXRRqk8p{DgVn+X_sCRdsOIhN08_Cg^ZZn z{;!TIB5;1(cIRg^+*#v)eAl!~uZSgZMR`>2y5oLu`@gz_5rH%3wtE(AMtD%+QE8W6 z5li6dIDndjbTyyx8huSSN5z#GMF zH^$fuJu2xEr1IXgzPwg7L{wD|+WQS~)PQ6}NquaOdQg-+GXdG zF5Oe9n?J0wq{6{EDXl2sW(JoL&L3wCYMAQrO@}32rd(tQ?b5l#^SZRGo~kqVsU> z^WLiD@og#>Zn*zWLui+^f$ax-Cp(WiukghW2dA{6gqz!4MrZ&Bk2x>-{Jo6|C*5$j zA+$?v!1LZ&T{f|1d+Wl^?~O=lr38^K&e*oPtbc!<>;8<0x?>O?yK%;_LidztMF~7(%m|;|&Mm8F*H;}@=$=F+w99R~jOc04wtaG7 zp?li3q6FR*W`yq`-l**RLBGQCc%ziiF1PJ6qPI3XXK~j;_tt7f3B1kB2*(nP4B1VC z{!!>g1|_u1ZM%$U^vPDuYg_0>AFU{Xv5Ohun1~TBd#=~K@N-Mp3OOfzg#2;noG`rMK;Fso@r3CxMi2<=P9?OWAw99R~jL0&wpFY|+&sm06lz^i!BXl2_ zO!hthlRRfKN@$ncb{UZ^W#4~mP;F;RT2TV7#f;G5U}V|C#dB-Vf{`hqU2fZDMAnxb zG~xZ)&ib^X1e}o>p^H9L_uoOq<-gQ+W~qdBxowvb5?5!I25+2Po%X5~CE&gs6T`KP z-3!JCuQaJmLsmk&+_uXI30QdWue>BJTq{bT+jCrRJ7f}Lvq;XUwu9XtnrN&`1w4y}arMsDN(=$y9}GuU;sQ@XA?4(Wc1y% zgjST0jLeYeWRCyK+xSL?Dmb7`y&>R1u+F>T~v}w4wyA0$l`gQ7Y3Fum`bua;2|ULk-F{Pvqf$b<^h(<^KmGb2xv!B6J}J^qclv44 z5^{awvR`MG+|!?$WmHi@jxcUBbYI$aWKYzJ5^~*2WGJCsY6kYGaDC$L4!Y0CxNh8b z*G;|45?WD0w(+l|de4tQ7@xC*%o!P(qcTT!AFU`M^J9tUN(t@KD`JmID@urE;7CVBYtGx)rt~wrDHZj3GF)an5Y#c?}2>pl$t)@y!Dkq??~`Dz`u1y4bCVc$+qEjJyAO-g|w%BhkF{YD2i%;jS*- zKOx=hlewTj?3WjJ8K*5*i5?qAq?NYBNAU+pjIZ}#=D9unNKC7JTUu#LthwY-68krd z%v}EEeI&YdZJAcu63xzDM&kSSoiY#4oJ!)0A8V(TwnX!lFOgVLqe14XHnYR?Xi_?@ zv?W%)oh9+^u%k0=zk7^C)d|@mr7cmt{p%$DS$TQ-!Jdmq+_k@Jk%XcF%|v_39lR7`10wCwwEfg63+ zmV48UV0muz`QpbVF{LfBr|9D%M+C2Ja2Z98z&MC8yqLBGM$vR`6m{o80;8zQP&yhP zIf|0NDC({iyD(b1^N47hfl)M*8%5pyNasdTcda7Y5*S5EU=(%toCHQucRwQ95*S5E zU=(%F6}vEsx_chcmcS@V0;8yVcG-nd)IC=bZ3&E`BruA)_k&#+McuO-(U!m{N&=&( zdk5KtQPjO35p4;Kq9ibiy7!!2J(`qu?_fk*0;4DijG}RjCG5f|TA;KgFp84EDC)*5 z5*S4bl(qy$Q4$zMV;I#)U=(evv?VZ#lE5gsN(kLZ&eFOr|w&iBQJaUkc7+la^&NN&@Nq> z^1N#YFJ#6Yv4;Y!D3SiDeB2$OzxY*Te4Bcm8S^(iVhHWR8b{oH(ht{`PH4D~8JFBW zInas{<$h_zjBWWZBcs{;qm%ADzCZMkA+!rCA~_rNjC*t7FdWE_0CB{QDw zKgtl=g-^m^2G+7XuUxe@%(yOfYoHY+-uz?+Gd}440Eo(W-pY)jzuaL6?b7vR&s)== zD>Le?YZYikiGnK^Gh^K81Ci08{5{N=v8%Nqw9BqjpHy!+Gme^8KhTO2-3BdZM)N9d zkTL1B3C#HUH%n-juGM(nzz@bTW8|TVfmW388~MzbnXHA3bseTNV^XGqA+!shka<7C zPxPhROku`>?>_XkqQvjr*M`^XjxX{4e>H6mGj^Y~%@Ep!&(X{XS0)B-eux>>Kb_-i zMTt${ZeT{QT2qkmbUv|CA3Sf2#B$r9_D%YD@P`@qJ-QV5TEpz$MYEV z^n62Tm)zMnh&j`k(RSI|gjST0XADHwCuT9Du=eMM&@OpGLDbtbff+4+DV5ZU67sHq zxO3}NX3Q))*$~<#ZyJcDm)*;ZzqGHF)QS@F&V#5}ZX7cnY~RQb+9e|fh`+ttJG@py zE=g)d2^qUUT(@%|GrIQaU_cW~DnNwW5TK!61IP;s$1XxVWz&v`a>C zM;weZ!<*eNsTCz;E&;Lkl_WE6eshc=v`c0p5IZN;WX9M1MklqRgv^N`2FyR58C4HV zHiUM`j0$4Q-rqT&U%6#sQY%Wx+z#S}RR`z{?_N055ZWbX0K!Z9%$U>q!K7A{5Jv&g z?O)F^oAkN#_fu6X&(?UbouE-xjES}vU<1#K;Iy)(5iAwQ)k(bU{CVmbV z&E#Cv5ZZ;K<-gs9zc~OG^>Z%jjw-4sf$PQ$xF|BWBY*5CmM58E{c| zb)$+Bxc`})i-LfQG6ODZ2<^htlgYU#2)HOS;G*s+i7HCqIc5f26a-u}$hoK?vEqlyxEADICcMFw1y8E{cUXcyk*@M!T{Xr2cbWd>Z-y|qzA35+Yu zfQy2Fi!uW)Y6$JZs1)vrzfA=fWd>Z-jXqID35<`-fQupnF3JqJs3Eiqqbv91e&35O z$_%)u8%3jv5*X*10T%@U7i9)q)DYT*S%Q0Vzmep5a8YK!Mcr%=Rg}Pd#SFM82)HOS z;G%}mF3fh^Q}}yJa8YK!Mcu3xRg}QI%M7?EGT@@jfQuSJyD)2WPvP$^!9|$?7fonI z3HU>Jt?u{|UIG_o23*t-+6DVyM)TD^hC;^{i23!=@2Nz`qT+|TS1-Ij#;G!VlqRfDcIX{(25fB&Vzu9G6ODZ2X{ z(25c=27`c$G6ODZ2LRm7>UrJ! zoRqk-)8JI+;R6EQmlB<~&mz6?V)y@-)9Ixv5-#J`MWYR&UAWS+lKRgVM>FI3fxQE* zDA97+9%h{L{3FP?@yZ3v7(8=?A+!rmOgv|=Ao}(wV#aR`ZV$AgMA6C<nkSR{g^ePRiG6mHvit9885yw92o^q)nZ1Ap6v~xT^Na&5w4^*ySg?r zw)SomXhn%jkLk;dGPid@M%98CGn)REGK6+vL}f;}lKRFY1+sdmhm`91ty_N85z8JH2Sq_({IN@jd~YK1^6N=&|c3Nuc5HV+xY`gdkVnFSRM zpLb-#}pr>@(UQ9`?5 zfXoP2QpdF#%!~t{EKh4i3E76d-g?5=%Vy*b_Ak8ehy+!lR?brRj(+n72U6# zQw(#|-Z4CnYG)mvP(r)p{6Hi=?#GOcE!!rvqJ-QV5ZCP=#f&Pg#~4Dp52QyyVwKbs?CFETJQEFZ(%AITo?UE4##NszEWyY>{rzW+cgp6GvexKNi z8O^ij8$!Ee90L*WU!NHdzji@VD@w>145HENe`Cgq$}J3`T{41$_~?~t%;>nKX;Ldn z$Xo(q-sBq0=>Bp?Lui-GL?E8|&11&-vGz%=C?Rtqh*FLJ!i-ycb~l7}$&BjG44>72o_NjA_Zh-=6|Z=D-sI;iWL!pr27|fEnKMi5t9ZZ2OXn;TKZlEEaxQ8J z?ZVN@N-A8`&$*~Os;Hs_t{XGpqR4=Y`Z*Uhgm&Sob5G$)DqNHqa8Y-4qlyx^|IC1k zA_FeU47jKvvYnzfq6FSYX23;}0T&H&E@}wv!rRO}g)6CW(IDrd?yZd~N?=@J23!;wa8YK!MGc`{ z7?rrEa3vKk$_%)u8-1dR5*Qzu0T)FET$CAbQA21KMpy1BTuFtCG6OE^M$xFE1jc!0 zz(tV(7i9)q)DYT*S%P~CS5o1k%z%r!*&wPYf%%FVa8YEyMVSE?HH3Cyw&R|{l~lMW zGvJ~Lttf$cml<$TWWYt40T(rdc45|LM!1p+7i9)q)XmOOMG5!=GvK1I47eyW;G%}m zF4#wSMYxg*7i9)q)LBMUQ34*s47eyV;G)cciyA_^U{TytxRMGNWd>Z-*-}(d0zStK zxG1a-F3JqJXj}>Hg4=OV;Yuo8lo@bQXO>Y#3E3{9iv~Ftb@uvaM3MX)1YDFEaM6rb zbiZ;=X}T!S11{<-p7Y($cgg6QaxF|E=qK42eF&q$ZQD(qJ z1Fa|_t_1=v$_%)uA+$?O4Fp`2o(LBWw4wx@adFN?LBK`niEvRv*sjP$LBK`nyKqsn z%BckMxSr@%JTaCW7!Y5(XlQEH=C+QA(*OG0zJm34z7{`b-5|3@>UrNx-V-0UU|4EJ z?Seq}r9@uM+hdOI?)O7RcKT@vmr--xm4?tRTxlLvxRUze4=oZdW6PWi1Fb0W+M*|! z(XU5$WUL-Hj2U@LTNpyS@We19TuIFyn8b|Ooce)Ql(^uFUCj9EtDBHF)W5ZK@hVyD*|MBV0*+uw#X!yXS{C9PqWG#IEX>F(Y;0L}Z-2;!I{t z>scyLLc1_CFe6+^{d(Ie%$VG2yRQ``c9gxI89N64g4y}R56@@Dlj7vXx&ew_(pH{q$8B-r!i;TvFF=o`R|DqwZ3o|t{!j;sTH=oapY1QxdwW7rS zU+-kb+11?da<1Cjj2R<4k2i#N!8n)^uB5(m_C?GX_F2-`iV}}MHGmn*TGT_v19xA+ zjIP5Q8bZ5ZPRs~bQV-o#z>F=Gwq&%T#HO-CnDOF?-C%uRUe%Tv8>SW-Lc3sq%m`Of z7boJ(Sn|~aX{{(B+XWa!JGNuS-JiFM9f2s2pM!X8Sd1BO&6pV1itbm=Ddu^fPHDr8 zqx!yY2XU53AR~kaQv*iW2g!Amgl6jhJ!ij#mt!UGkk?W~Lf&~0Pq#de8EtxhZV2s?5d*{}6{;{}d&4ghT2VsAE)eTSoyLrhdLElp zLc3%f1Myhb(#&|_qcTaYC?R7ohnjRWNrs>QH95taqFB*453|O1|U{^*NqwDD>h7OMG0{f5UoddX2$UGml;C4#Bf0D zX>=kp{xP>vQY%V`Yk@dwXDMcMe5JJ^v`b74#Opr~pu<&rGM3be67C!MoR{nvI0VE8 z&sCr&es+F4L)fn36;HgiQ{GCu`TVTkNrj6t11{<;BdRC?4`K#f6d7<)X23-apj?kQYJg^Mx+E*jU067V@@ zz(rwwa8YK!MGc`{ut8>oE2(f%X23NI5O7guz(q4! z(f!IfrRk!~fQuSJyX1<1fQvE%F6wJV3Ar~Q;G)cciyA_^T5*_dB#A% zMVSE?HH3D_6PlrmG6OE^YeflpSC9c0Wd>Z-5ZWbg8ZzLb%z%sfT2VsYc@S_>X23-a zphqQsM%tH&JueBvyeNAp)dV8+IaD+Nku7p^o{Aj6f^dF#p~T*k8({N!szi4mvX z%8V+{)Idh{seetl^O#$@LZF0p;fY~JxRN^TxFj=Xtp3v1iW2RX&R|AauPQR$eYY<& zV*frmP(r)#g_v!lom+J%{c8R1ImNyFb}MrPJDUn@#1zU>5NT#{LW4FAesm~rfH^9-R~nBkZa zuB1-=0{-XvG$H8hR`k;2Q$Kz)ZI&dVn*j{|Ke*!iS-T7X2x}o?}L#Y zfAtB>sMgdogm%H4m=Ug|J~in#X1spm)Qnb?IIe$fW_)_usmN$tsR}cOjp}O%?ScU^ zBV0+%KlXQKobg$^v{sam?E?Izk$;65zh77;b_Ak8eh%Wr6Am%sir*T=wW9l#a{_Vi zjLJNZhqlf(gm%dliFw}2rN1!alpSx!wW5UF8xU9AP>~s54?H2Egm%fD1##P+Z<(>7 z{#gmFC?U@nh;wNv1Z4R+Ha~xjCxg@+wIsY*+D$r{}%@>zK52xDWqxD4}biN+7Q&XPL-=i)L~z zignTAeQ6i6WhE6Zn#sASJCCTM1g={;=c34fi!uW)>dqq~vggR8a!sBQxNl$bgG711@R^?ZW8FJ%uZ& za8YK!McpVGRg}OupUJr>GT@@jfQuSJyD&>|PvJ@`T$CAbQ8ybz6(ulVF#|4&47eyW z;G%}mF3fh^Q@D}}7i9)q)Xi#9MG4Hi%z%p`11=imT+|TSg;|?>3RhC$qRfDcy4g9Z zC;@+923!;wa8YK!MGc`{un+DjTuFtCG6OE^EF-EY0S{sZToir<7i9)q)DYSQC*q#M zl~lMWGvK1mucC?)@Hu9{MUep)Wd>Z-5ZVPBz@%t@^cVyQD(qJGg{I8$~l36i!uW)Y6$I;E0U&*G6OE^Ed21bN-H7v1_WG`8E{cw z3GI?Q3j!|647jMT6(!^u0|6Ih23*t-+9gjY2)HOS;G(`(l#q7?1YDFEa8W~Om%M2p z;G)cci~3qoLf&~0a8bVJa8W~Omy8%0x+pW?qP|v?kg*FHa8YK!MGc`{GV&nT5*_nM**xMVSE?HH3D_OauZh$_%)uTm9g( z>wYIq37Hc?z(tt>7Y&rqE}2n5z(tt>7j>&Rhv(Xi5;C`gfQvE%E*dDIT{6#ufQvE% zF6!2=4jVv532_tdg6#w<-Dg!98TA7C$&V2Q76YQ9ylVE_m9!OR+PYZrt-T@-M8j@UjLdS z;x1#>tS1ejUAWS*oW0`AuStz(#=gr(`dU!}-{i`S@cZ-=Uu=+j0)cj^tGY{zF#($`%Y<`$5%o5ggcKX7R@t+cHzlqM!1st$mjoI#+~2a;cG<+ zeCsVU+;`@B-fxdzz>FEU&oG2`;SFX+xRQF>+LIIRe(c)R(btL+_%2>%xNraWyeT!W zX2xZ;CKy7yFcL8%TuB{%%mvK2{G}GYR+PXu1T({Zzp&>$_j(^@j4w6R5ZZ+il^Nkm z>fq0sGh^-77x-FH0^eKA4EL?acxz7@%ZzVty1@|Ig_$9qvsVyT)ab~JmsVHvwW0*R zO_>?)yO{BB+XtpGhOQu!Hh@C9n5G&34F(Mct4uBzmNRW?njt$ zU`91x3GKp6&5Up*HMn~qGhWYIo6(9A^6md{pNY>dWXAB9_ZmXGU>wW{S5n_Ob0jl* z%$ShTiW2xfY@UbvO9`HLSBs_0XkB}@A+!tT#Efty^`*;4Gh=$I8X2u9A%E)te;whP z=}$3ZN2w}?&@LDtGs2bB%FD(u<5-xbR+Nx!e0TV36P{+qb*JB2a0H^U{Ja4FqIhYT zk!`UerWM_V)Ufti$X#zf=3TR+Nx?1ENg-CwLxP$`l$x zyX4NsJa0+;yP2`{y~S~@C?U@ni2j2XFr)eDKNv#04(!3N@$n7Hy{=_>CBAlc9czMMG1N5L9{6~l^JzbTxtmIk`V($uet4*(Y4;$ z39Tq0V;6|IZ;ochw_9&9gm%fu2cp#3ab{GzJeJUk5;6vZXfd+~Gj{L0#}L{jBRGgl z&&UhUV`tlhR+Nyr1VmBSE16Nh*(5_~m&`=qmPaDE^=}KzF^v6XmWBRjWxGtJAOQaX?7kP)jDIezn z7ft6})DYT*qm`9ZxM(KlqVA}oiW0bP%y55ugf5!Nxu_wu3s*gzb5R^ET$CAbQFnEt ziW0d0%z%p`11`!8xTqnt3r`RC6t1MgMVSE?bx%oDQ3B6#`taX3p^N%C7d3=-;Vs~v z!j)9GC^O)q?rD!IO5lBDhWm>sbWvu&MGc`{c$>MWa3vKk>gQb4y|qzA35+YuaDPLE zF3JqJs3EiqqZ0QNuB5_6nE@Adqfb;(0^=hy++SUxi!uW)Y6$JZ=*m5XE2(f%X23<= zC>m9iz&Otg_jg+8qRfDc8bZ4;OJs5`3IZ<547jM94Wfz?n6H=t7X<+qWd>Z-5ZZ;= zj(ZAMQsJV^fQ!bpq6FsM@P6QL!O%sS0T*@iV6-po!W_(>hbyUYQD(qJ-FzNZlz=}l z!~OLbx+pW?qK42e*a!C%uB5_6nE@AdmJwByfCn+d{k<8wC^O)qhR`lp6!#Raq{2m+ z0T*?)6jhXf&oRUOg&MjjGvK0z&@Q+g_Y|(A!bO<@7j>Q(Rg{oz_%2+O8F0~}BM__P z=S6f;X23bK)^+r0T=a^&@Opz zK)^+r0T*?j?wH{|DJmiFJP5cbGvK0z&@LGT$FPyT-4W!5;C_V11`!8xTqntOUwWna8YK!MSZO( zA&!C!xG22@E@}wv62n0TT$CAbQC}-ch-)DOF3JqJs3EjVObr=u(R9v5eXS?~XOzE> k1Q(?z!bJ^XyNXvl@ja>Oj|*}xYF0UwKpxiPx# literal 0 HcmV?d00001 diff --git a/GEMstack/knowledge/vehicle/model/meshes/rear_right_light_link.STL b/GEMstack/knowledge/vehicle/model/meshes/rear_right_light_link.STL new file mode 100755 index 0000000000000000000000000000000000000000..afc66745f5c7befbcadd078a0e65fa8cb672c990 GIT binary patch literal 8084 zcmb_hZHQG>6n)qSsiBrr5^6K~Nol6#sLj0lZh?gaiIy1nGAWI+EHbs4%$d>37>uaM z5Vi6HZOTA2qhaRVcg3jGAgCA$r!ehD=}b~+SytFy=iK$~esj9x{n7jw7H_Y$*S_c7 zbI#r~nauzDvnfh<;Als7{!a~I{=DAB4|cCG9*k%O@EwcC7xw>tedN(O-!ERZ zV!5Lr3m(L_s$Y7oE%xnPY7~sYUsftP&JFX%n;7~U57`D&IIzBqlXqaX_& z#8xqM_w=xTpFu{!h|UXKy{R(jn%NS0oPBO~c;BABj)E+B5L=JC{RQFnLq8UEMCS!w zf7jUH!>JLl8uD3QA1tU5y@SW=>2Cvr*j6AAao(x;B zS?MUqf(Nnn7&d7|*wT8rQ81$O0>3?GO3>8sbE{QU9Dz`7d$(}C>YTS z;PofY58j)5Hu9Kw_~x*F+-OHZ7CeaUbJQLh7jF5h#wZxkd4WeS`>wEf&Opy9hOHS9 z?if1NQIG`>VyhUiu3uQSah6dqqVodppRuFRzj}D&G3ZpUaLpfiM?n@mh^mt;wT>5xtzSN26pZM+z_m?XZQq}$ zjyyiSaZYj7l}|egvfx2%Jvz2^1ZSVGHws2{USMJ3c8)wcw&jC8n;RSjS@0mHN8Y1? z5uG>ktBs#Ss`6NsR!D`06+MSi$dl*zb~wLW*PR*(e`V(TF%gU^$J5uF!U&KNH~ujKUcdHQGtS@0mX9&*C@ zJmDD8d4c7u^x|_@PEntys8)~#4`S;fC$+ydI;k1ad4c83_u~6QZUdjUfmVmr|Zcd*!CnGv9u-wjGe4oqh?DKZk3bNoq zY(1m{@OMWY03$jtuyh7q+?Pm~;j_!o3bNoqY(1ot@!O(Kh7p|?Sb8Ea?ysa<^4TqE z1zGSQwjR=v`RvFT(RqQT>+|A1QMx{#U7uEv1rK8DA)Teq&XN(G7g%~!FYb4xd-eN8 z-K$oR1rK8DAsw>M4w(_17g&1jY}~g?7w)qQ*9x-WL2Nyw)A!lwGoteX%gm6C=Z|-4 zDtt~8T0s^(h^>cAEV+N8iG>lJ7g%PWY&=I*Hy_DyD$)wF;6ZFXWb(>!@?u2i1(q2u z8_$C>-Q_slX$4vEAhsSdLFPC?GNSVWb3(QXnNo9{Qni9Cco18~fung3ldz8Hy!c$0 zrD?m-x4KLQEJn0~pJy`To53wt$djA-6)dUH%*#D1;DKD-6`aCd53L}J9{3A_tB`ls zOp0L1J7y+RD*pR9w1-y6+f$mI%b#2;$btt~#H~tBA2XAIC8va$0n=Bd6|(PR!GkN}R;Bwy-Iv1e+YneG6Y$yG3dyjsB?wPyuc zP;*6Gh3$~1%g|j7yngr4?m+FtIAK;K3DftKvBb z7EjUiRcS@pd6ifdS@7VBxK;6H0gE?I`l_^|>}*f0iY$0=Mck@*zp@hi?Tz@{drdoZyovY_CKxK&B*regt1p4{|4>8sL;vYsKaDzc*Ii2ITp%|SH!J~ cb0%1vYtvVy6>@)+{==JG6n+a literal 0 HcmV?d00001 diff --git a/GEMstack/knowledge/vehicle/model/meshes/rear_right_stop_light_link.STL b/GEMstack/knowledge/vehicle/model/meshes/rear_right_stop_light_link.STL new file mode 100755 index 0000000000000000000000000000000000000000..9e30a0a210b42cbeb0dec03551717ce2229901ce GIT binary patch literal 45484 zcmb__3;0&U_WxUv3Z)ym)9p>kQKFOYyZ0{TQX&zR2qEbrMM^36dv4{LOPy|SVznn# zmn#U$cxz;{(%lD+2l}}?XSDsKUBjfx;Zw^H!sXU#Xoqw1g>GLYeTSVHkRRC`Ii>Glk75bgldOSh!zBY@7;7!Y4Dce zL~JVLpX{ycdUjQd*UznQ!+d3n$A3Ssw^ASmOB$@i9qtQ`Rv3u@KP zuf1bt(x>HwGK6puA^n!iZSOxRzwY5*lJkl~otE3JC8GImyTpSB90M8OuedfpxLK`q z%Z&pSBBR*-GpFs?dG+JFCiMcM@24~J?@wu%zP_ek8A7-yqx)I)<7KUg=&)>7{^c>v z($*V$D?~=g$|d6QZO!7rJqth_)@nh1agBEAp)GqTL`KOFY*WjyQ+z?#9*EIucCtVLKqY@0{j0 z3_UEZGOMjZWRwh%%dKp?xJRG(#(Q@K;_=6y&-d%lJ3Zlq<{l#BqKrfLJv`pFsvZz? zKYA~}?(tJojBeNWXmuQ(~~@YJpfA<}IG ze}A&Icl^Y;tkn|({+6Hd^>Jy%*Y(Q~!sXU#>9}w6kNtH*`orh9grv0pc2xYuW7nx# zO&vQbK4{x?RjZk`N5}7{*Wvg1M}3_SFB+fDI(mM{`U-_;L8y`*JR=^u+xeOs(L}WevWA2Ci_@gGJ)2_YPX}RB~wEFn?KaaPEj1AxZn7{dmDd~f6_EdXsR;yRej%Odeq(m-b ziQuwjytL_ue6Is9POqImQX%Ye1wr(!m!BUGKZUh=2|B+RIv@2`&oYE?xwWc4V^jW! z+ef71zI|IEjK!&18QWF0lG^5Sw|?|le%8-p(uqq-W$h3IWsDnjcKm4dB|xWrzsk3| zXk6NU&xgto!sYftTX=>XJVVWI>ca!gY5Vo5VO;&ZCQ3KPN5$+bsV%Hz-P(LKb5L6K z(i%Wy6qYLp{>~7u-t|Gg-KE3Qt7d;))^gz@LfVwe^?|4E4o|(|r2|#1>TPQocl)8M zs+IA5=zNznf5sVyrFHLWTh5>h-%McmYoVL;mdl;AZdyJmR!Qr}r#LOA4(v9Wl@nxySdlfs zifq8JGZiAEWC)^HFIrh@y!S95M!$D#zVYNW$-trKmLY_Twfgsfm8I{VJOhaBpBC~> zyRA&N96m-NGD=o15oWCg#KHHs%D*^eVKRTu@d}YqG6dJY&-55oI^%)!fT;Us&HU<$ z>B&D2zQ{vlT$ItU#i-Kg%ZWG*E95J%LOvpyq!1a!MVK`l5IeV8-nQ$oLNe|zQxqbj zWC+%(ZI=gDO#kshAo|~POWW$r>m{e3F|`aKT&$H@x9eIhM6E)rRt46VT##45x*c3f zUO~5f@6FFGY&PVm@Yvm_z)CWTjW9AQur~nuI7e?26)=r5O+Au_JYoeU7q9586X z!0qb`LqF9Bv&T^_7X)SGa-F#M0pjkx2eoDC0-WDy7t(I3JP%FhnM5e*|Z`LfXshA#$CBm+h27TSYrVH4ypdGOG;tNw2 zhL*J(N~TS$aXAJHdJJMj6)~bh8BtkT85e7Xkyg-SaMXLp78^}o6UwN~C@uoyzkppB zY87=j2Qt10Eze*m8G^NfUkS7q9k^~<5#A>f?~|34aj{nL#{vDZ^3+9m>d5lchTA+L z>~Vm=tX9OV7U@~7JLlR!=34mL0DBH_*)rg%i}2Ku_S6}LimH{=R?VD6%$$*)Io);$f-*3R z270c=>|Dg`9Mw~^vx^WeyG^-VgBhEON8Uan(yOH$*KmQX;jm5!u!F#QC#!8PhgC)q ztBgpmGBOIw6$F1v`_xLNh?PvFS28X_xQLK8sg-3BE6Yf)EOT6?23)0*3+u!HyCPL9 zsjXU(6|o|V^oq=FhaiZ?>MYP}IIQ}LSoKAE)#oCFiwJ2`E{9ck5v%aXT7?H(pOXu# z{y?vmb6n}Gzvpr-r|&4{zMU4;ul+Q1n^9~8e`8G@V2^_~o!DV}vDyt&qx+ZFA!ii3T>i#tIWTMLO+OT|3Xk+E+(if%5z=pJ$5OquYlWy`pyP?hd^)4JVM@d3ZzcknQCx(XwILf(&LX0mkrn0SOs{H{ z)ucNk!UY`>{<;68;(HJO5=taBD=Xt-tq@x-Ft(h_A?jR2)H$@G&W7S5%z6cgnj4QT zzH#ZAaQ9QsjaXJj$q?*mM2ZWHs^@YaHa)a>;puT0y*s81AzUoUtki&b`m?VVB0?YP z2)&Bq7bK2vR{G$wWh|^!xA^uQGeaG9&L}Kb5d4h@bV0|dPrt8K@$1P8Lmk<65yIux zs&Uo(+FYG9kDq=0Qq>MQQ6QIDQ=?Xu>vsGGVgV2V5jMp}@VD7n0D;qtg*eR!{L>7V zE9;S5?%6wMEZo$tVQ8H+RQ8pWOEgX$3i@mUrx^=znh{#38I=g(B0~BNJ}q}ybkUtZ z=lQGFx_O1-7lqQyBag)XV_xB(U6K`jM;@(y=W++N!`@_3IYKDqh|cZ)_FCWgw-LFV z<}&CC$}2~7YVc8MPLmF*CRNrhEA6=xqb>8GoByR&Hsaj9rkA#k@BUw8NLegbxcFOo zq`X!`j%Xb}aQ6>bU(G8F_^Cns)(yM;fm+#!JLXr5U-`J{@6<}TC{KE%yjEf7Uh#jv z8>wowZMQ-cuq-tfXPyLqml_P}0a&3gMyk3-F?H>wu~yO}<+Xyn2JoWF!lCB?Ui1&t%0|Fq0(jBi zsg-cCR?;KowSvzG;6+ufFeUq^MgFqZ)F{i2X6sdW6^)dc;9w@eGHir>zv#CRaucQLlF@E()=cU2ZExSbbUE4(=?2}44=Op5aq*HLtV|gHYw_Y0DGh(FCaA?S7L z4?s{Kk8f%pH8>_vaZ!o4Q-;LFiKtn>S+Jl}MWFT3@4h{v#&wTZ2#JMTy&Di=dKU=l zqyD1J;hKXhZ%3;*H4zelCcSL#F zCnPH`yI3LYd)h##d*KFA(g^Bf-M@B9$K5+vA?!Qbuo87!*|Z~ul|TmdF?;);(|_Ie zCxwvvyKD!nMBUjX0#*{kN`Rm~+V>xvj+(f$LfCg*jkhZh0e!?;A0_DH!(kVvFPwRz z=)CgYtGQvQ5Fal*KVGw9KWLESW9p&P(syS6C16eDW~S1Ixs6E~u&Y?x74^~Rk!k6N z%LZT%pe#|{z?9!SueA`^c~Kud&b=rdckz|V+U*;LuteU*EfE20kF~W^AAKJV(rc%* zPg$;gqs{b{@(iZ0Vm&^N`272%_m0yP!oJ-GE8!h_g@Bcm^f>>=E|*5{&G^1F@0enI z;ckB^tQ$D9)aBehYF~r>hl&E5{fCMt=W;}xQkY+QG5D+E!oH?57A^>u)cWxwN+;dj zAGK=H?2@SG=SRn1AK5;!DJ<7Ui0oYMi~G-y9_af-JZJ492VvLntPOV;c3$1D)be27 zNMWt+Jh@G2zjq#0wKDM?r-nq2+5M#z?|*xusnthc{#ZI}w?8QvLSe0>O?GW{t)3oq zbUfz!haH5?#abPB=$k8^UUeE|tgbyG+H~@q_~`L#6Pw~AvUb#YyMOfhYmdZB|Gh_Q zBkb1BdH2RbvnKDYc=CV|rscDy@5m3TwN$m1J7JzEupQD1l*coKWy1%WmZzt*Da{z) zNwq^LK0ADPgxw2lIsbn0v*$v_o1J?__k7tszB|`CwJAO#>#HYAt)my~eq0*)R!;|E z_bArYN=E7M^G)xE1;zDvFPgKFsCVyB+?~J-9Njdsh&))=V!{XuD$Xo>cwg z!X8KK-bF7eijTAspo@MQC>qQMG)(Sda&_A^) zK7ul|J{qL&hE*od2xfOV$3fUyqZiFqOQXX_!ox0|5&!VcSV63ybi=iRYbySxj9#bm zej*Vs?DOa3*1bljq+o{ReCHr2?~?hamR7tA#6Cz)DB zuP;fiUVD;~Arv3cYRLRj_!38L9q428bq^=4YDW%&Va#YgnqJi9dHA$n@s)u?x`Nj~_cp@U$#!bKaaa>y&CzWsZ%RHW33_|e{s~XKJ6(2hR2zs9lxdW41E`DBlA3?BO;o?}SHfU98z*L@da{f5$#t0DEC zOJ3Xe?+$|H3K#qBw!`*}7uP!o29`yS>imXNo22t@9H?|I6d!Tyx2MI|?|BUn9Otj!dr109+nXH(%M~v6bj9pb z;%iP!fS_;h+Tnu_Jq!#2?nLb$BPbvXyKyH_d4VB_@tSu zfS{*7dh(fRa>{*)P4N-gn%dHNK&=^_V>dakASb+*&I?-S6W29QzPNFAU{id=zi&7+ zUN(Fk5Y&0=vmZ!Wd|E%W5&SJ&md=5o&YM+VnM_-JL}*idMC(R9<0VIa1O#>d(LFn* zO{Y(G5JU@?rE?&t^Zu*rrXA|s9oiHhv0+@F_~d6l1A;nlU9D3(w9z65L9}pLnq{q^ z^FGVErJqlDCbTI&;@=I9i%W-Z0fOWF;$i*My3<~C5JU@?rCA`T^QX5BNMCtiV`x)+ zM7AHae7n-Q@$Kq2&Wdio#(|1Wu9+dmxy z%M~v6wDHG4Q0Fa9U6~v*Z0E?P_=t-x%*AIN+Y<=-_P4*>lAL=}V+TRBaIvS22M1yg z=={uuKP1l<+DA6UN91el6wghL0)jeUGpKg@NRzG(f@tBQW{n32f;u1AYPWRJr9C5? z;v*0*F>wa!-0W+Wp3Oc}{WiNhrE|0AgbZt!sx&AR>fA<{eJv2w`LVOt$Af-c;2@|$ z;bKpl6$cR1`Cl7;9Us2#4W&V$_z1Hf1cExBoE)5lV|R`0viMuL*wbd^1O#>d@~#IZ zLki8628H4y%*ql7j`I%&k4qjo?@$N9a)paMZB~G+6?8s#)3D^b*Ly1s3dKj5bubXr z`IN(NPAXQO;viVAa8a{nB?|=S^KJ7lPcEN#j?%eMe1ut@13{gey_(XqIjF(x6a`&MOhnW&yDbAgFW100P7S9E8!J;$lym{S^?@Ibr|-VgO3# zLh%vMW&yDbAgFW100P7Sl+FcVG^n`P(`J7K1a)56XIn62+P+GILh%vMW&yhiAgJ@T zRlW``S<=Hn7!4{e_Vg;fR|A6cId&`|b}UMRLh%vMW&yh*AgFWfibCv)9E8!J;-b#Y zUJVGd^9r%^QaTrkkH}({)cFN(+#FPyH$drGZiSfHS=|<4Pj`QD|KPhhImn>S7hm2W zJaq80$^!_+M_{H7viZDgcuUyy?4y*<1;KKKi#`47<6VN**H(uN>iqqhPlop%cCOO7 zP<#Yt>L8oXhwk-l_+yQtgJ8MB#hy+suL!o^#rFWH^X4mSML%5gsG6OH;v+Cq2ibgn z>(Tp0<8J)GL9krmVowiyx_eM}N*&1HIRAT{PSJVif2d|>q4)^Q)Im0%cdH*ocTK3K zbS?;%D_qq1+^W5T`@XCT8Pxd?#~mHby)LJ8E)*Y;#oMX#&rWm?zY>JP-E-cV{wWpx-m9wKLc(0X%AX>OA%|Zspd6kw&NBgwsr*>Y(8cIF_ zyRbm-)u{8~$*^cvgPsn8}lh{A%i-v@%XmzABU_{8Wf6;K(r;$F&U2Y znd|qC_CI8+gJ8MB#hy0)7&55y%X>GEdYoS~wJAOV(Uw5RWVk>U2m`H%=)-2p3DrqRxN9Ip>T;8%pE8nWhjzvCHM}EPLJD14!f^0M7pT z&K1T=_Lc!0`EN`_E;g!G}-VBxSC$=hwub`UIAxTsBu4(r+A z@=GQr(KV+jD-nv1kQlkP#Hu?@OAdeWNC&}kg^N}x(P2HS&2DvEQsaw4YEyhf7Cq;P zx})n6NsYfXbr3`g7e|*whqaYF^WN&@zHz$c5^rZ;*=MQJhq+wO05>4!yqrANW2Dnp zHiEyiH!i;1duhiZibz5>k(_^Q{g_gF^8Uasr{f=)uq61i8)b4ua(h7jDv*^nvIlf6qhb^x+XRn7 zsToHoJ|a7t;Oh0}^szYjrjdhSxx&R6&P1jlgEQyuZ?uT}HlD3!PNDb++$y$C^+zr4 z8Ru8t?jTsMoQ1gUV69Ay%&C=+kaH2;@^OogO73iPi-Taf!sY6NbM2fCS0)qJFLrv@ zN65K|)?ka#4<_f0`o=-9T;X!dd&PB8rt$SDX6bG;lg5?UAJI*=R{<#IcAUmDDPv`zZc#vWw|;UXfd z)kO`K20w*;((_MgqS}F6ZNB8Eyr|r=VVkfQjj>BbJ8mm<4)B~_ezHo|yNco?{wK-e1thS!aj;EM>HxyG|Fi?Yb9K+KIlaejY<%W za(dTCm~$h@pav0*N)U~55G+@?T)UzdMKmf!G|I6OA7RdoAcK~OXjF=5l!IWo!sU(+ z6OBp{jZ%9~86Q5voEt#~M--w_DWXwj<3qUIac-hfDWXx%sAWxTggIS;jH}?`TEEpV z9lfNsgJ8MBMK2*fMtjjeJvK1?u3int`}m0LE;r}%DhJMr2i5AV>`H8jRwAd?wl=k0 znNv$;S7I4HLe8VLT{Zjkp5&_++bFvd1j`jJTbp{+?iln;GJRyAtVArsN5~1bwyQQ{ zs-z1(zurNxT;Z~{sl8A0It|hm&2LdwB9`GJ z)%u@@rW-qc;UHM9aM7+ZE8*T|>5!oA!oSo0P>Advyf6rAitC^mw><)uozREW8D^x{$J`CFbTLkJfUS*vm6HsnSr5 zL815vxjCZ8dAIM^B*lTT#4J@=ELXTV<`E;05pRbK&QZz6MM<*o|0I&CC_VyFRdY{< zy9q>V6DwM)5G+@?=(`a2HSZeGC*FR`Lvg+CuSrB$QGA5l%h9tl&JALm8#oA-i&Fr; zys*M;hdDP$aBd*cWmPL5ffIok=LRcu%W-ay;M~AzIm;C;S09|6ac+>{+`#EwAAu8r z80Q9%K@H;EAjP?XgJ8MB<=PczXPg_PI5&uGijTmFK#X$($l&aZbAuG;1`dK~;c~}^ zIX6ggZlLZV%E<8%I1z|(ZU7ndqBu85ac88S>(N@``LsP~&$F1eVY zVxcSWo+V;39qV3_Ubn|kb?4udi!Am3ihvBZe9@)nrw1oDsN4lXSmmy;dI2)%ud07^ zPWr*}St`bEdQ|dbn8#ovAcO0xBk$>-ZkaZ$V3%e6USVkyGU%^XZSI+#_V5krtiV`C z#jhYBgO<4KnAT~hz4s~DWm&&hSXK!cwD#h?_0p409agd_zk+}aj;J;Vyqny!WI=_E zuzss?ZpI^I&|j@6ElK88+eeLaq5KL0GIUI)Q&My4qx)JTwZi%>?+>UKU9|V9h#!lO zpS!@J{0agxzCd*FhR>&@i@s{E@>nEyMcJ!)RoogMg?9Wmig@W;8q2c@Q#aS0A=qlC)^DwLm=!#Yc#} zX}kL9#sfLyI0(y1)LRy29)t|egT}5LijOce9NJ-W;!??pGb_CUtwg>NK>eF_5M=P& zV9Ze$rdLidxpk3iaF~x~uXj6PdW{I>boLZ(h zwR8|f3m3I%)Cm$}qDX=L%LhMc3m04do2%?3Hs~WRf zf(+V~SuMdbGK!CIEzzvV90bvF&(^N3u9dk@?bOOgnEj_|`8%I3NRB`3eFwpEh0E0k zd-t0juOu(Vdxti~N0|Mm(cq`sYo%WtQQ;tn7B1U*wD-BJ*eLzK!6O|j@eyYK2^sWo zi)VC8pISb}L9krmvPXgTqL-vS)AOp|=~%muF#Au);E0+ueMnmE+B+Ns%M~tnoHP2d z8}>NQFM8M+wLZe^`XIyFK{^PQD_ryv;$!ss>csEIr2oErnVQvv;v>v{5HhTtu##c+ z&dOie8K5E$wi_)CE_>vx^n+(VQV5~2CW7E^f|A-M+{VPeP*f@l+Ic4X^X;noWy+YZG?m?*btIc~iqxb@<+ zoV5}zS08GQ+A=S}trw?veT0eD8x7*tOM+W34ua(hmupwF65M)8aO=gf5+7ks9Uz02 zh+8iyZoN1NmMdKD_@K4p)=P?8FOg005$5y+GR&=)6t`X+1ku7}k7ga~!>yMTw_co4 z>m$r55M0EL!XeIU= z5Mn+0o=l^Od#5*!?dw>Hjo|O>i*wuw?>KdzwAA;AGK6puAvRt4UPdDCWtbZ~%G%|X z3fh>t&jM>_OlEQIACnq2PEj(1!g6hdv`>%oj{o{J*=PLm4ua(h7j4YkXMqe_`?l^| zlI~|8p=?(uK0>l!^z2-3(yPhMy>+gPAXu(&(Z>bK>h2kS5D@j{>ucap>b+0Tr2$m~c zv@vs^1u{50Z#}zfGW)IDmF)_}M@V*+wsvz*#zC-L;i9#hTQ88o+1cEBQPwULA0atk z8ewkMI0%+2IYw?fxMpbZ`t-QbA+4NR`3T83(k<^htA5gZ;sXwXTYnbeM&lm^6a)pb!S=DwU-%fxGdeN0lx+FcWI#cOfC_X~+%Cr}4u%KEpW|w{r zg5?SqZ47x+d{qT9=tcK$(1!7j4v4Uwi@SB7Rwbbj(Oy<@s%6Mpcj3t?oILE z4_T~yiBNomLb50|!o1ewAXu(>RYmP& zq_(VsYsud0;rs*2OQK7u#1@ydsuJT>6$im`h07i19JRwQX&mn|Nc$2Q=RSgHys82j^l)3c-5*ameoEOm z7cP1U@iE$qKDf0-{KML5j`v|rY()0$30h)}zpJ;9lwFA}8GBVPjN96*v@5>WqpUoaSwtcf7ZoM^sEV&>YAbFE(!%$$nLj1N;Q-jlho z=|dssb5byG^V@)Gc9z%vSQ1tSdI6JqP*EoFOqTSUP z6pD|?^0qmDocUueY%%0@HO>XWa)pay9&7jl-q?c-&dziCJ`v!ZJLOA+;v=&BbM7Ya zmR^9j^c)1s6)yTN>_yDC2h8kTz*i#qq{uN}<67l|3c*{KpI|!C5T<-Xw zwd0Mg5N~Wb*6t&)(=Xs1FUVj7vis{x!mHMvkku>@Rt$iItZ34T(*zVv-7|Y)`V9aGQ#mbJ_36mej5}r%xj^MycUY+kouk% z%at#35slah-;@Qy#AL#nCMF{kA0ai={tCHEA##^gI|O0ZioJl?NuXaNF}X`2a+g%^ z3dKiAPwU+Ta+gBnE;$Ihcd1RpP6GX^3atdWOCfTXl$8j@M~KDf-2`%%LgX$v2-`|% zm57}bve#jdyA&dKNm;v4e1urOUY8(uDMap)8c~9&bd2E=3n6Zo36Q&_ypK?Pgm@x&Q5_wO7#*Z#APT6yUdP|^ zvM#lW2&8#`m-l44ytij`$&TL2N`&Gg#Co({A-g6*c8!Cu?UmX@{5rs!XRuw)gUH~C zkiny@L?}K&>`mL%{rHCBimGiLgl(_XCZf>+-fn{o+7&X9!c(7ap{ztGK0@qG+ZD2% zLS#ER2-{w%O~kJQyg>&UY91W@V2F$=WhFxK5n?^su8_4AB5TV**!D_oB7PmrtJ#ZXMy!XlPb%$SK1Zg*XCik1}Q<2)l`3GOLMmx-jNhBvGLh%t|Z~DXpuhvC)wNBZUAZ&Z3 zHgW#JENsZ2UEyWC2ruI)D-nv15PQ>hh1d5YyuRlkY$@v_3m9QI&D&2 zWhFxK5n^xJuJDRrh*t#FiHRU=d!;sU{=uwx$e>-}rNR&|6)GzcijNR`({_c|5JS9% z=pbx+r8aT?!R&s>pj|yWeMI=-wO1&+5{i!yd((D>6O#b1Iywm3UTIh6H37(=UE$@( z053->yAq0z5PQ=IoUsJRD{>Gl*Sv9{?tV#ab*;?125RLc6d!@}X!FVqTRw9B72)-L zN0hZgxLkd3eRX}WVu&0pr+3*78)05TFd9UjSBN|>2f=cM%e5=6uaHX?BA3ju5+8vZ z1?H6-Mn90R7Cj$UaV(ML3YR-RxV}P8T!frB$J%`aZbq0_ZaAWlcNZb=&OxwT;c~}0 z*H_5xi;&yrj9MQdZ`qjW$KQkK`*m#`1j`jJdI|9{dVN(IdqlLn(>`ie6N-<>zB9`; z+&d?n7|lAax{`q#BI<>DmWx|2*h6nsw=_i_zOjybGJ7>15OuzHcZCp&jo@$j&TKAc zZoNdj_2Sn=xQNJVWp36)yjeqv`R28{y(4eyvn1Tn3Gk{T_UXJQ^GnNN(erCQkh?gF zLbQ#L_UYLf*)dYZr=-zzrDlLKDXavYjGiJ2?oJD_k5axP=zr zwNS{Q7ez)@gp4XR28H4ya0AA?G{td_tgR4PTMmNd3Kz#bZqo&L^%OGbOOP2Be*Iz_ z&;A67Rwbb`YzlGRNsu#J`ovi0W#c_PZWxez&#oBojCek zyxtn%^;QSLa?Sfb%8N>EwHL*0!w|2xDlaM&AAx(8d=bdB9Iv;Ac)itWIcp_cu0Ghi zc)c~m>#a`j`Uu<#<%>W@gLu6)!t1RLg5?UAYge=qyxtn&^;XA9e1v)H2Qp}hc)c~k z>#Yug#Y%9Z*{EQN0_&MAcOlTyxtn&^;QSLa)rws=k%g@y*0w?tk*NB zJp#Ax)py)gx#mmkMB}crdCkh)j*jGZv`~D6)KIVbkbM>*`%JY%5O%HD3%JE>Uga{` zXA!c`RPPGKM@UcWRUfj?B4nRA2)lQwP26HOuZx-Nvk2K|%1VUdBgA6#st?&`5wg!5 zgl#3XO5AleucXmmA^R*s_L;JFq4)@~e7)*J_F0JRGr4uI%CfDUqYJl~1O3_?{S~s$ zLS&z*aV``eAtP9O2J=>!gRn;}y@Yvn3|2z#gS*ZFvd`3AXQB8A@kH8oAOC!EH0S7N zRIC^|80s4}v=U?q1^8l!%FPj5$mM$BJ(&qdPK`R=_O)blD2uZZ{Ee@b1aIB*C2sbc zjFE^LBesp&TvT~PL+ZC0$OOchkq$t0FK&?#fQiR+k z$#zl*)=+wZHfG+6gA9|q6d`v>az6OhoMcg{ezOpe!PyzPOA&IHB-=?LY%bcEdGii3 zOzu*I+$G6G;+uJr6Q$m^vk;I$zl+?Z2)Rp=?W7Pk7j4YE-3J-8cH}Na$XzPflwUzW z2ImjtE``Wlk~}EB7HI#L93#F|2pP0?$^RM~+E=+$D$dD+tK25U{1nR~FT8Gge9#8ZuZbWWMl?Mu%dJJN0)n znoGLn$gT;SHQDMQSgvqcy#N{PU1act$l!@>ijOc}2{NcbWC=yc5^@kk3zwx$$e@)p ztlla@CX&jW6pQl_#=AlWXJ=$PMb)pI=^$9Ha9MT?8MJm}R7J?BifxLIFtY??aJ@Tt zi4L7z zGqEW?!py-&#?ZYkjC%euMb*m8sU@P#9Ikwf$U{4DPiFq|Nzop|&rk@V*a-f{_n3m= zr}TmhlYbsD|J<*Ma1oK!%H+65W0B)dirM3+TFF<CVsa13tVUMoUAPGVDh zgjq9C2FCf894I>;VeiK_#YdPm0}%9AW;fv=h!!sT zF0+#X!df%HGBS#fFlz>bFngTXM)0@U2`SH)wZqzZIkoZ;W*25!j;|Gj_*y|?x17I) z%kFjEyUnVv4Dq!Br+0mX*-b(QHHfbjMEF{PgJ8MBWm}K-qWD@tgs&AiR^lVft{5_C ziTGMUgs&Ai2$m~c_9!r3bXm6uUn_8|-A9<+J!Ei1;cEpEzEmy8*0y5}D&%myz*-`H~2$m~cwvW+X^oB>zh<3i}E64lz2onQ>3|gYuZ7aJH zTcVYi2&A$r(Z9BK^J=!TE1~!Z6Df@Kh-w($9@coItFkLW&`N~M)~2>AWblN@;89j0 zmf<5zY!NbOS9fjL7XEaI{yvT%Sgvr{+SGQ1Or!{zNXkmYGJJ%IEkXwE>Tk8%M#y$@ z5G+@?Y;9`0LPk}Dj4EX%Vi`Wd#1O+SDBUYp3KP8kB>Ix_egDuk1(-5BV&t>aw-|-Gy^tP8QD}T z1CgiSld18ao>A5PTPcK4Yy^MfjkO@^*aR|oPi9-#CmM^l+x(gc7ZF*lc<&YO!$sTh zJ{&3Ld{EU&zEaAP%&81y+=_cL5ANI{`o2pyB||7g+X!i&)(0|QB4oZe2$m~c)Qvfn zfeh*#nJ*DCUs9XmBh2{@5RAzn^Cd#&i-RCqxM*YMR0aszE;3&tWWJ;}#YdRa8X&lO zMdnM0%okeWq{xqMCMC~%ojCkh2kU3`3?}AosszxBJ;&Tuw3Edm^Y^~ zKyY^M&}d?a%opWLgyJL2xd;%P2hBN-gJ8MBMc-vkWq_bhG^aAkCkn+!nDZTjFeg6_ zg5{c1MCB``wz^j4)Y7Syk1*$)rsepqOo;EwI0)8CxLkd(ckx}B5Z{$?de=vo^IFKD z2Ju~)5Z{$?5G+@?Z0pfhg73_-vuQ zW9>e|oS#DmM-;v*6XClu4ua(hmpjfmJL9`D5xy(qj9MRI?g2msy=e1m8b`-;Jkmk1 zT;Z~PjGmom4Qmkf8QIVAK0dPqh2CW^rOCfTXl(h@RM~LNX ze}&wo5V=bZ!nSsfE_3SzGU%_6yA&dKNsU^e_y`%n+B2AYG7iEXwe%9^)(d3NUm@T+GM>jhnL7V^AzVJ^9Aza!A=*ZW z^=P|7c1?)v8V6z9E468Eg+c~LEi!mQWbh~}5sHrxd((C`==#~=n|P1aE{nf~i`q1| zLLq~8b$Oe4Au^Gal?cU0h`njMLbg+gY$pd{+bgwc?s!55?Ft!HAu_5`o8lwH-n3mI zYb!+7ma;1;i)i7ZHqC8H$e>*vGpl~sXW|3ON`&Gg#NM=BnVXpo!nRl1mAMrP8MG^8 zxbgm#vMZtZ2(dSPPX=%Hhw^5>x!`D-}y;7UzzA$9auJFaF5MP{9Rw5K1A@-*23SYGf@l`7aVcQtBY3>U{2JLFY z;Bn!S^A1&3A`~AX_NMLX#a#~y@pUc-VcRRUY3>U{2JH%801NR2FlARl@eyJ@+OF`G zu>fBgQ+6c?+bXF|b6*%TXjlDauMhAgGi4=0@eyKg+OEt!WCvl}EA7hMDuxW&mAO@{ z>`Ev;LhMZ=kXOW;%MOC&ns0ll^_A3C*UEg)%c+%*FnJoL<&W0ADR}RY#SVhC5-wLC zTwfsvD?kpG)4M*xWOEn|BF`&8o|mIRmMdJYU2zqTT(SVUWR8{i2$RhL8C+j=Y||(_ zsAG2r!E%Mm9UqJ#BPT9IPMl-yK4O*5=70>2DCFIR$h&h8ELXVPac*+^Lge;2qt-{5 zya~wQ`pRTlI0%+2T=Wv+WAys!%-YSv<=;(FvzkzRgvsWB4DJm~MlRwdmHEKRmf$(n z7lDmcmT*rW2#ycjR!?wSU0DgnfufL05N51cUm!*ouXb1fjzWNs9t8dCmOje^hb%5_u|X z?^LT>FIP{Ak@MpqY%cybnLUufvpeMc#K`$kRw5J|LEV@<9Ux3DS%6$J2VryB+SFEJ sa(0jDm&y`aNQ#o)x#gMUENas<#Rfx*Nb>Pbi`qPIDA_8*@W4pLZRnNHoEdVck#OYiXXxAMeg(JT)&hmDpKu83d#V@&m&Q7asR zbf$G$r=+dkyWu$yb^BcrcW!=t^kg?7!b0J&cSpt7x7)wE^+&yYmE;N139-8KWpTr)O{#x>f1*Q>&a{@b^UcN`^M=62 z{MSds6W@8USl;13zDn{0>4Z4+>7ntSQ{&=mFWl=8q%*D3!h_AmC3j7Mjk9*RB;N1n zM%B&to9C+}PmoTC{u9rS2lqU=`r!FX9D;PF_4b?ln2iZDpMj0lJqE^4KH^vJdF3a* zO7aBhgcu*45jQycr{aYpes&1bnbwZy>}@vooVFM?g4a)v*Z+Qd@qd5(=Bp%6kWPrf zkDMI$Ke=x8y+i5-O7J?Nk@9v`3i)SBY)&XT^ z%|?s%U16icAvZ_Ad|p+(NB3DPO?QLpIR0|pf_D>ww{ObatjiG3F{1nc1yqctCGU5%M1P)VL3 zoe(<&uY{|P3aXngy}}_#XIgVF-_>lqv2737s2w*mtnJji`jTGb0+r+m(g|^NulnKs zBTg#b`>{)q&a|EzKJ5|K11kjBIJ(#M<%OqL73cmjE>MXQ3qX)gh^?0wy`4UtRQ&E$ zmryN~u)MLY8Z58zcK+WZ<&HNr0b}v5k`dEh`ooUUu;%ED% zlXgB7^|*3;BY$ACQ;K_BJT_2Co*P^=YLkL0P{<>-a}?S~JlIrz4V0+r+m z(h0$}!kay&&B5BiAxLLh6R}pHjbw!5TH%lNch14uAy7%4Ae|8N8m{v{@Q$c?`k~Vt zf^?=e|I1}&TE`67(thco360QJ7w@xou+OSB zH6PyAIZ#QSAe|78-gaPc*WH`dK6}vt4naE8Vrf_p{z{?He8IuN89&sk{itpGKqYyC zbVB^qi1nGom^5{9i2YcUC^K9c)4naE88nbUl`=$OJ z?}Cj5Qw9ZpO=?-YUBeH2mE;N12{C5g1;K#dTh#8f#|sWYI@98az>Ipj(YGvz8Vp<>Gylh%NO0~ zt0Yg5PKXu#FAs*k@^inI5JV81kIAbno^Fs}1 zP$hVsX*Iz-P8&(ofU|PzJ6^8gEUl6}L3$(c!f`v*f(Vu1b*3e@ON9bURqy^YYf&m& z4W%_K<%zU}AXxKH>YP>kT8pNU{+5)gB(08;v31}4dO|H)H&RKSpbgv)5WItr{MEh| zchDiEbv@}lAlOU#|F2aodP$^`JV6`iS0LCEXHR^TJ<%bgm)MNS7U7DvP+)Ig_GGu( z&8qK>pCVWxzOygCNj8|TsppAs!2sd>8dmP~$LPj5(F=>OIQlY?6 z^ozyIIEuzH?pjH*-<9zZ#M>CDKk3-2_NvFWbqLjxSpo!SgX_lZT8r5rR!N?qJ+BFRJNulKSr7aQ2(B_d{9;foRvEEM z@&s)p1XnWkzB#NGD;b9%ooUG`3O1TywY2BHd(>9V?G>vePmsnv0>Ks8rJt{eX&aN1Z`lQ2;v{CESDVDtM=7v1~`PQ`g~c{g5c`)u1?jp zSiQz7$rH4JCjbOj$O~4ru3>ad30b}RvN{LBRd}1~pK2JvQ%Rnn4LtiGxYGZ*?v}M! z={tn1!hP{FK+v05ch4rZ@FrrFTIV-bY!7Bnmujsik z&(DEZ6ssgp&_+V+0?+H)p1an-^KuB%nU;8cuwmZa=sq>@?qZeX3DWQfLC}L7)^v6a zJV=KS@6P9}%z9uJ0zohJpdWUug_jzuBu~&rLU11M^X2a~m_Z$abfzUp?}mS?5RHmek|#(beg&c<8 zJW_>-mqSQ2%I8{v^+=vtM%B)2`uDwvs>LeF6SR>KlM%UF(63N~$elxw&a@(ttI&-e|S&wAqJP**sB%j~id#AxLLhl0$+GW|vN{`KXBOQmm3ZK^ple5M7YL+T-n! z%wR=INOsA3IqSjRStu||*0$x5#UUep<_g*BK}nvVjfCJ@q1B*8MXVhhf^??E5rH=N zBo_)?D_pg{F|&R2CMuFVK{_FrQM~Trt*Up~Z=OSt&a@<(2^-8>zA?RSHL{kGO7aA0 zC^ELMk~~2=A(*LNcgp9*JLi3GYl7^zNM~A-C5H`W!`lp- zUqm+C*$0p(NGCf7m~lUC_OHd^OYd+9$%dCC``$U(2k_tRnsXn3vpYcv?hl|1Y%{no z*=umrEmhdru%M{FrCRd;bg#kL&5yIa1}afP?3LjOA3QFoTEAKCHPPMPYn#sS=N>r1 ztJ|Z2T_1SwfRNXI{h9XvBr@^Bo8y8L&)&TD>ZpYyA*}?jHxjp9+>k`5zs2iJOKgK; zsRpjA%Tk3Z$rGtP5Otm#8;rbe>)NWz>P1ROslsi`)2$vCOgaq2t8K;xx6j(9cE`~Cq%*Azf8K01_UktpHl7Mbt|>K@mswqDO`9D;PF_1QBwnvG}bz6cu!KRG;Tze%gw(F0~gD#;V16Jm$EE(v;G zvP=2|gt@GAhV>TAwTrVmVHr;w~Fr{jT+J0ZW8>u8ukWPrwjI)B?A8u9q_eHB6f^?=; z=fR0)W5l#=VB@ee&J4nBo7cYI=%+{}d4hC8oHy;1V8_k2uHE^dLaYR@Gp!TO9Ah@V z`llK;PI>3Vpx#^C)HWTzd90E=K{_F>YkW*FwEpI`^?GmT5TrA$arK6njqQ4Lf{nG! z`vedC`%BGM?=_88k|#(f#JP=o2FG8ru4dH2mJUHW(`qqjpxGGE?hx2Gpc(QW%U9JL zQfwWoBu|h|h}~}Sf^9mit9h|rJBJ{hX}#F1ui3csnUiVbg$}`SxBOId@*(@jD#;V1 z6JnD!dk42n`n~3-H3vHc=}c>%k-f~u?K_vEL$$7C#@&xIGxb6I>{lo5hvu2ZbhByT2Ol$CA^UcP`kKP0u^`lyU;izRb zdv_cft0Yg5PKd(0ll?CjKV9=i_e&jubf)z|)9GeoS^Jw|WBAJx{X6cAYyR;ri&c^* zNGHVMo1EqEJ@@{aKC>@(2-2C>^kqkzjklxeuu;0~2!F`R+iMQ`WmK$^JV81k8h^5# zzxO%U*GxWXtV58_w4MuIDe<1KKWPSR>^b6F@5p)A)U+6IMXZuMK{_GEpL?sf`Ch|o zdL4myiToC?Gp)}i++a4|T|yf(qHDb+=TE3vb9dnWOSi$OLT2`Y@eO8QYlf+v`|9(f2HPOyN+w;q&2TdSP~_8 zU1{C0WBkvYv~?>4e>c;bw(RJT^{Cvz=#rbausf)dJVCnBOQI_#JU@rMLqLq7fo5P-{k~~4W(%Yl0>TETKyr4wH zk=dw>aM98k-?dIhxQZlCkgklP(Tl&HQi| zFvFRR%FG$h{(h%oI&)Sed4hChc8-IFJ&Nh4b=O-#c!(-zCL0$tt5l@OLwhiYzX!yR?|D$SRUNLAtW)i~En5R7_WW6@tH;X<-Fu|F5hp<3X3*T1;1# z6-k~TU0J=xyWC$>OjoZJg1?(-op|OL`+sGH9KZhF<3+BJRgx!2S61QiJvYTguELez zb*6qUByD#;V1D_&~+$!k9r>7^>c>r89?pEsM0iYFYuaQkmX zdcrEn6QnENcKpo!>x%TYmEd)z1<%`TR6P2)QT=tr)T6IR@&xHh)F8fa;y=ZmlBhw2 z;O}Nyh#=Vi5j%nJjL1a%RsT(@)5t_ck|#(f1fm}?Vlvff^rJ%XcQY-o{!IISCBhOT zCR5D_i%RkY>5T+pG9)}Dc%5lUJv@ua#E8kTRE!Q~r7~KHw1gm7bHrp=b6*K5l_&QD z1Y$BVVlvf;$@nVC6SRT*0Rl0Z7%`b@+(Czs*7c+>fIv(pMogv}y~I~Zo}dl%D-eju z#E8jMqbE9q^b$|{Gzi3GV#H*s(c68M5iaL@!K^qu%K_Dg*BPLUgkvh=dl2O!`F&_kCGBIK@)tC(e zmE;N9!2AIMF_{=KnQF{94k5FFFY_P>#AIT`WH_q@D#;VHfq4)FVlpveGMqUbLS{8z z=5r8;$;61saCQzZ8HmYnl@X{UPtXR|B_I%! zi4l|GO2#2%mEp_!3It*@F=8@B#AE`MjS8DDdCR3Hxydq&q zvfm}Kv8@>KLQJMAZQTl?S`uwTJs4F(Ovdh@O7aA4B=?+=JH%wF*h`dWrqqT_1+{=+cC3%82lCgvlVZ>za<>;e?L~A)FdhAz~5za?U=H7IKt4Q($ zZ6pLE+la}`Nk`EN!QaiaB&v>jFnW%d%p8u?D#;V1ld+uwgenHFYh`=!bXAV5rpSsAVXDv~@wIw25~2@sR1K}^OWNM~A-bwXP)yM&kwvrBA&I6vXih4)OZ;?jBO>o;@e~r%&9%t`EBY27loLKb1+`^Yo=4roP#?TmliV z^}OZH?=`KT&%D;Z>FR6ky5ERN{%PM|7?OCR?@n_ z>MuFaho)VF^r2}4NDvo)QWb_E7CpG4^!Je$nAQguHuF&$yGH4Jl*R~@4#fB0v=8qB zanr*gNvH zrx`aoASl#I0(i4wNGNQ-itGr`JB-gl;ymLmJ{{4j@TCMIL z?nWE8Eb9Evv>S{#=d!vUdWT)3w|KLjzSM{(9{34+)zC{yX)g)UOFZ5|^pfa5_-$UJ zmqh&Sw3kHIOG;@k3D5ZEGt)vZiCBIT=p_-$PlENaUQ$YXNr+zJr@bU%8}XWL#x^3s zHnUz*N_$C&USeA4B@yof3EmgphqRY~KrivqUJ|00m==0T#CuJG_n!Bf1n<4|5-;r~ z;Zt{?U|Q%U(R1ieB-p?1MSmi}{$;(yOM6Kfy~MQ8OQIjqXGyRR|B60Kf_>O}iI?`0 zGJ1(=p_hbwE=ce>c@obB3A8|Hy~Im)UN|=iYc~ zJJh%Fszfc0SEr#r@tP$26Ky1;&x~`2deIHzf{%|qYth@M^^5u~xYwJ091WX+98YCdd*Z$!^#J9w8i z+Q+nRX!vWmWY<=9eay!5+cj$LOW*aa=H;~J;bds0HTQR3{<2-8 z=Ds|GAa0%TROyd#R|GrV@?of_U9j^unkrUQ&1NM2Ao< z=`k3Ap1R@LuqkSO;t@ma)CungYpsOt*)J3t21~51wro(cGd(2OLv+_YpDNySj4!Y; zYTmnHOW4>jxQ^2kwfE^h^g^Lc5ZfJW_QpqLl_;SjMxpS^4yxl1k)v%kIAL<9ojxcElar^4Q;< zF;TU2d@L01-)m*q25oiMvlBY2M2U_2(D^PsAr>j2T0&#(GobBjR`cq{?e(td-3+Cr zF_!$Z=58Y{`RX2-T9g1jJ*9{#iN`^(c&Z&))IC zdZ0%}O1vmrZSejJX`UObh)h)HM-$N&6?gE-2N`J;pezB_-taI(qxmezUxOsQI3M zUFZ<1CG$B-wJv(dyA-8rdii9oMIyF4S7A!XY5>GR>6+o;KV~|FYROsx#NPLOKXq)RtJcA!E_s&GkuYTbbXJx5`yxjo=#$AsyC&pceP%T}T z;=Kkfmf8LI>fHLaQlWLOSe3wv!%B-;0ya+j@(u4ilxpnVRSuzA^5z8)P4Im4p5u96 zr0?OtXlJ$M%2HYcBi!UxFIzqC^XipVqJ*x_ahm+QkG&63s_DC4?GUOZ?dBB<$Clo+ zQte!`4)KOc4V|}N$o&BE)hA26cBscWlMW0y7N&jIdC!EjE{K{Alg-91KRgu5^I`8Y zAkCE%`x#rE<8Pr*HS=t557>BpQW(m}U~df|!FK@2(*{WQ6Qc+OGt#Ks<@N)mgC zB&rgwg1^SL;#gcLpypm$^Ue|%p)YGT=*vn!hF^;~+`(BKjy0q&%h(%Yaupw!|4&;1 z_xy;tvkt!CXS}gz+`N)Xl#n(A@$5U7EMlpauCHtTD*G+fLcc1p9=tE+bDFOPpEFd6 z60!mSaq|85mN{PSSo^#~sFtiBKy-OydAS>&^KaICV5cwH!@2rXLOe1Mh(LDEB9Q9$ zBN}Nj07fIVgoVPXqlR=o4{h~I=LbtFQ9_@aLSc08Kdr4A9#AJ#LbbGn*o$-Lf2^&3 z{B2;U5+z(;?Tb+>%iYmdGwa3bGRP|HF&A>K(y{Qi)u?ssFsdI*cXPiC?1Th=pfSPR8{tlEyfnL_Bj5mOXZCR~mp)jXz|DQz|8NmM9b!UVMwy{JjOA zl(kfz}hKIcorZgU9L(zgi|3PZnwCT320M=DW5 zJS3Frq9)5q9nre)-@F_12G&;08%TVYSpb`_k}SaNAHL2a!i=p}BuYr67&cbF)4S9U zt=nbvWX?DhLbY_>#XgxG{#V)qrFy&mPK@{(!5LWzi6_H`M4cT%wImu1qQ{muS?e}# zI?0KCXj_Q~38L@md)ghmWz%+{N|eyj778cKd&zo9)#OLZN~o3_9o%}&1*Idk9+A2I{OHT>al1Mu0fvijxZ}(IpvG-ievfULEO94u?PvH!wR7&WY z2={#UM^^L37u;IbQmK|kbP9!?Z|ZBU+qLfcvPzV2*H=>)KNRkZ5w6EwJvGwktis$# z(e`~`2zz0!-JbkNzLpSA)F)Mzn|Kx(ER`rB zISbs6kKetiv_D#R`5|2$LbY_2i8qD3+s0ds>{5>(mXuVYgk&~gCkM?kE+}Rwu1!QBsK#Zav<=_W?#1rXrRwPQek-G8NF&CbE!6eFqbMhFHcKYD15## zOIA{e5|TZ`{pi#D!BSnc?wND$@2rGssZWI{&g?_H8&Rr%9%)cgi4u}ygAK{Vbyh;P zBtr*6BB}P(4z?oSA);-i(a%C*$_Yt6s@bwjoVchGYP(Q?A85UVexd%BYPlJ#3Bkjq zpZ+^8=s0qp&MHyDt;cP59_kH3TRr`U?+~g*PmCT}k{`TvBe6&&LWF9&P>@nBQi&2$ zLimI9(deteXLCxWTGDPH=%X>O#yp`)l#nMXL_85b8hthRY!0DX8iy|wqNVSLw_^VI zbndrKgkA~BY{7=~#Ip3IPA(=nekg=pJqd_R+ic`Wu zLB?H;usDQ_uCT!f5!;G!6Kx;W(h?R5^oH10@Qz9ws3#&wC4|4>5KDvmi0~~tEJrD4_T3w zwd_jB+Acy?27Vyh3VxxkuR_&wYfe9q{R)1e<~AKdd}!-ye?-~ka%IRL9dQuJG?xHP%ZJ0L9~4B#;^us`}e))IvGVJB*PCvJg-pvs7O37 zr-X>4ZuIWdD{=_&^k9RYBirhvc`vEw`nt>AllDp5k>TClPF&_k_X-SNOYhfpoqaREa1WjJ|fC1hU)2#Lvr z5><&LK9k#XC-E!IW;ldIsbHgkEC$<(v3;$rYH0~^t_WTo+X`NurxGP3QV1IofpiGf za%-OL_j$VQ>z+!KkoYcaNOUliSYIU3!Q75Ui9l-P&LJck2^;iI*;epYH9F|*t<(}0 z3fw=&wt5FU=~SY>D=~7`V`D7bAyi8u-XJ7z;Oy8^LNW~?Bst zA&9B_>``8TvHj7@R+y)oNtBQsVjv`M5K81fk{p6lCnv|EIY@_)ObTo;FUYoHwoGfQ zT3SM^$ly7$t>8)89?mpV6)EB72S2{z@kKkKtuDLkWrt8Lx8`$Rue)dz+N#Icm7YqJ z;5FM2J9w)#VYj!D8Lh^X9A=$pN)>gGxsx+quLNbb)?Thk6 znrTdk>@0vo@OLvU(AgOQ5Xk12*b|xE=gx<$Uuj$64p#Q3BGz~8S)F+Yxhq#CO1Sl) z2h3gqkNE#0vf8@)UXPqR>se+-A00QZtP=fQw;tG4yogyc-VY^IOU^f-=5h)mR0-~X z$hJZbGPfHSImkt64$>)=5}Lub9HiA8{;j8_QZ3z)WI4zZTNnPVvqxA7cNfy>zpO9y z!X12Ra@iqN%iZbp>i?Q~UGaPzblzK@N|exDPd1j6(;Ot9k4pQ<`Hx6TXgNqbF@hXq zs1hYG2HP+3jDU^Qi_#oqSqatBJpncwl+zq!s1haQya{Y%r&5rEbO_aw(<&f_!vp5? z@om?~ojqRKR=Ru3a*%ch;dR?y0*-L-B%M7BT3X9NmiT zLsg%Gww3@^BENQ7!OLo?Pps&g21HPxT>s|@?4B74-5XeE=9YhY&AymuV54Y!5w|E2a zd~EaIIrO7!PZ9T!DdFxT!+N)z<{)`0rP4k;#laR$&zMNfk%P?6E`?flCEzC*&C@F8 zO_b9dBv;6l-%>634EBHSfUz88In6WtX>ra+IfQD#H#CALV&K>AGuf-c z^YL=C8$E3kZ7X=fc0c$(%R$;5ghx!jwjxnNOKUku>m~3cOG>B~Ys`Md|CyIsPIHiD zl_=rX1D$g)b5;8@7# zgCn5jAnl|ca*z(8T8Lj7!LwQT^2y&%c+JteXUuD*dlH@9X0ksK1ie$i1OHLochMZ9>s|2xd zYagCOQ`;5`FQ+-kMJiE3_u^R&(&NktpN;X|N z_w~_7hkeiLtZkxgr8|r*2WfW@o+M9m*d1h6PYJbcIY{dz$U$~eLbcrU zgUI%k(;Va?l_=rX13Abr%|SYZYF&2o6l<$W4l*M;t3(LfEz4OgA*58DwNy$-2}_oP zw3^$#Q8^*0TGDPHcs7yG2Xc_Qzm+-Y>~88)fRf#L{0m+yJRj|koZ%4ibb0PBZ`nhy zJMHZR3RlaFp~zl$*pQxBlD_0gPvoBDN(r6b&WvJ3qJ%sJut6Vup=IRAjd22O;w2!;xoX8oJ4X6 z)pBbtCy_#xC?RKzU_;isC0Vihvi8lr144WQJ)z(b;sL-0Pd~6<@f?WOR<*Q*mV>mm z;x15?C?Q@LY>0Q~5UM3!9|-ZCopakth))edJTLP?x!PuaO+2sM8#a)G%)C4GiX1{b zJ=mb<$hJZbQavx8m9b|VEs#6&!}kENUm*t>YT1>L$OLS37;&LJgAZLb%OO-t&l@>s z`<#-=gwWlwzA;cPqc(i)PNbqN^O;pXaa1|*JN99|Em(J zr6sf+q(!{A|5YVQNL&jx=xcIK4d2rtR7+1<;r)pXN;bA{gOk!KQ9@#tupu!Sdz%K^ z3eO_<&|6z^kGPf)S(%OTD`pg}t?*mm;!abQC?T;$ z*ud^pYb)+%RYJAgnoE2)REZK2_k|6K4w|RSw!#?iOLQ>z?j4ChYUIu#BpL}D^iJ8Y zxMNmpt6Ew@%RyROAqN?%LEZd5EY?V+gEurNgt*yAnRwYVEwgxuj6t+XCmYmK8 z@!Q6e-p*S*l#m<}2;?BMyn($thW(2B;v|QVdvBEFSoAcYLr5kCHjsm~91G7XYHd|Z zOK3Sr%V2Rgt4frRY!+tb^MhHw zF85Y0WE3q+#`A+(b|q*p&9T7-Jz(}L?#fj{wX}qm?X!ICbi9d1B}$+T<-{S+2eYk^ zQFI8^lH4{*_0QO;_LhP|hmS**C?Wd*K)m1ig!sqvH+Z`pyP5NzZGD6GJNu80wz+AN zx27ZCn%(|`7V-Lt8@xC;%y~;Q-q9FkZ;QNk^8Q9F+LLcE+pVyz9}nB$%^NbB@06{) zCsp5Py6y6#JldGpfN#2;+xG{5(2X0s`FEYpHxF0dvZ-&w+_(P@K8fA;<@=DQ4{99L zKW2k>z*l{o_gU(jDzBNmzY$5PM(!{o*m=wb@AP}FcHWGqZ?Id|<7Ok;&%Yk)cGNsb zYaa7$k*qDh3?eonu@PC#qqOGy!cmz7zvmIIVds@26&|vilLq{Q&XWb5%jd2bu(3uKhPEA9JqN@Xl^sqi+v7%O5a& zhBtn$A8oemGP}O~pVlBguK%(B@*c+rr%ryz(K__HQ~j0WW_b;tJvf@OaHw5(n%xq_ zbH8ovtvG&k@a-OfFMB39`gk0>crNwcmk;+ykE{P5pC^mY_3r6EI(U3lCtr4?IOiY_ zn|+@VeX1veXtCMdUg?<8!S2=j@!fWQHrL92AODmV-xzVusaJ!T`^C%N!@WlbPi?-3 zbE*w18Kb$9IVafG>M?2BXb>;;{K5O9$LL^LO*6jR&a{xDa894SG;%K^`qv!{V*k^& z@VD(cI+$FwwJ$pXxu!OnZ^@f^VhzS3_4RwUx?s)O0`LdT2H%n=_XEVz8}{?NR*w#P^qbFj!I>6Y8UDFl^DTM3 zULS9zdj7OcK>XFG?In?{$f8qQd}9Q92?+F(FzqFLx1AC6J!QQcof~W$u~g_K zAka&~w3qPRc1AFhCB8v~USb4#2?+F(DD5SY=DfsLi*7x!hY{!{Aka&qw3me92}j}y zN9ZL+@OiXe5~aO_@3ym2u>~Y*z^B%T)4c)5jShN!wZF5YO~#c-Mg|ZaP71vh7)!41(bn1hC*w*aBLj$u z?Y{C3=rcOl^PCpW-b&r2DI)`j-?!b=Kda~H;FZ%GIeT4YT#00405Rm;?fpR*ORCN; zIQxQST;V z{j{|obQ&Ezd138|^-YPmz_xo}!IoaOe`iT$Uzw6}umJ-MaSpAs)!h6-8ndQ%aZD?@$59d0BYW>yiCM(tZUvCa#v&Rqf zXEzufJoM+=WtAwQ=ceGRJbAzc?^CTZN zaNObk`TvXx9^Ii+XC+iiPuJm#>FwtDx1%26=ab7SQ9|sYbr+B7>0bdGYwFH%2-OnX zAf)DHl_()C0^*F#|F`IOjO`6~K7`&@Hnux&P?i;dZ?i!;oefB2>jdWw%CZ6gf!QET zX9LHVmGy%!D*zIEOb^r9z=L?wlop&zF`hn|2Bd`Jh zfl)L{M^R7K3BIf!d|3g2zz7$mBb<}Fk@bToD*!wn7~!IHgmWZH$oc^UMz|;);T%G> zn)jb#^}q-R0wY|Mj&M%)P1Y!$OJIbH(h<&)D1k91;#k7>J=+Kur6Zg}s1}|TD-}jK z5E$X2bc8FZL4l&@my-< zw^U0q;~+4?Md=7vR*4el1XHc%l@TsVN4P~wsFvpLZG?-`5w4^XCBz} zhe3SUaIxb%>pIBwwjUY2*1YYm+f8-+a3yrTf^5dU+XO7t{jc5Q5UO?Cbra2_Z`*RS z2p@2H=5MpH?9joHN|bQdC7b@+)ao(qsWA?rTBn>c*=%h1`c>3CSW-7&)Zm6-uSg|I z$h-?;M(-9@kKZpiz#&xYzP>k^4Yo9Pd9SHwHvWBnWvCJ*a5sI9iODLX<;d1nkMquY z*CABvxIWX&Msf##>{#DyoYb%sszeE$cMFAmFD{ymLEYDul~ApQeW#m^OtH%Xb&GA&CgtQw7^meNUdb>lYmb7|e zBj!E7@Txh^^P$fK>}6wOX!VHse4N#+6skmtt@}=o_;gj;%50#mxK6D6mTKuJVfVwH z+QHq|mQnhiXI4xw7^?0n@51L8F={N@+RZ6o>J@SPqvThtM; z(C~jp-D1}(@7^jb6yQfinIEN*0$DTATe22Oq6R&ePKox#>b1xC){aC8S(jkEy6W>^ zBlfE$-6lGOYGE9+nkOUN_)E67`?2Gh4{*GyNR+_1YyVH8ocFcs5Hl{i<%CxpLbYZc ze~r~V`0wT@)h{1)v9?-!@VAjll#u8-2zbI#<_XLCDv}jhE+%vJfC*7^wAHZ}9O6in zkX0XSjQMPpwbdIB&vFRW(h}mG98Ydy{p!yqOE`a2+C&LNhwcB24r4#VfHu}vTVMKL zhfpoI=G(T~&)Vw!gSL!Sq6DJR*1C*F7Yg%+?GRz+v6En9#}iKq4?*<2#k&VPu~6}f za&gh84xAajf5*_^oPX|iBua?q1siSpG_f2&5*>Y2W`^Giw+wWG(GEXMzAXq z@p0J-mT5pX1EpHH>@e>oj8`l6s2?k#T7%Y2DzUAWHJlEje)k7Gw$%tvY{pYOE3^BohbX+^g$&HOS*k zdp2+)w35fk)x6T&jogIgym&fKOIRp8ee{RkK3#_e>zdARBucn(>Nan;_t{n-Ppup4Z>g4+5F_=# z!9M%dR;zc4RieZXf3CK+`eU!_aL-TfaJ9A7yl1;Rglf4pzdO9g+G^OpN5?8rVp+Q% zt*xHf@_N{qGIFuE88UH89%$oyaY!<8xp@1ruk7u2IAB=N>%*%Zi4tzSebzxYTU)hw zd5uG;R>QvA`+TAW|4!CvDYti&!N}ENr!}5m&9f5XAbES6Ewp+Grn#P%X(+ zljyd=+G^AronnI;*;SEl;`!Vm9tsO$OutK(aBrD{hoAnJkVDwqs^ct?6D-tEthr=HF z2Tr$o+}v;nhfuA3`_HgnO1z?AYTx9Z_g`C5i4tPZ!}+LAiH&PpUE?XCT2fjNBl`3< z8~+>ex2F;%q}@Qko3MJooA8xTEopTSl9h3?(~^~81k&g13~$26TW*$4@l$WYktiXt z6A8@rDp5klO4xumk!40b$!$7&G_-`+ z@6&6DpL!FFt5@1Ya;dqU9PlQrt>8^Kgk*JnEunc6wvvH2;YgIIo^qtM6}$=51KxzS z6}*W+e@nI8n!}s0@e1BVpb{nEP1slhZvr-CCBuwKwt8`P^2q7~1iT3^^(K6k$U4ZE zwH*j}6V_JnCITf?OV%qO;7!=<3~wS(i4w9J1OactW@mU44xw7IUI77b!e(c96M;&U zkkudvcoXH+n{e`6n$2=^UhpQu)SK{Cq6F%c?RtR?coSjjO$17)7JPP>)vHxZ`Z zM4%ESP^ZlE0s(I#OuY$*P%Zcj<-EAP?O@yg8;biz^zYlwf z)EwSKn0gbAL<#XlVFTVon0ga|{+4QK3C)`@j~?Dcpb{m-dxZ^n6H)3-ID~4sHHSA5 zrQSrK5+%fYg$?oOov*{nPN!U+6W&CadJ~RB2{+FPZz4*)i9liN)0+lH7Ub`QyU%{Jz4R{k_>P>Jbpk=T) z`^%24T)r0GM3j0HjzkGJUkh)-+6vx;L#P&fhA8zWP%3y6Nn7>ZB2bAEPqf|%}i3}P3nL#P&J zyD0URK){c(s2cnz&Vv<+5?D*v|C7DWSnrw*tan3=g<~aaT3p>rd_S}`baDv_Ey zxe)At*kMG>o#bcSbG1WAJ;G0)xzTLktL(6`L)VMqYddZ5mcH^}bjFWUOoDI1J6cjF z5I5d>LA>YHWBs$fm`=YoYZHf1dxgT=M;&La+pocO4xw7oRdCCk=>?}AvWF$NQ+C#? z1*`c}&HFfnX2!JDk)uCk2g}Oz8hDM4I zf4!`i%>D9drpP!0IdbzK&rdusJ{dM1e{$bg zB}%jyG|=b)?GAyBsqc4;??FA9U%8t@sFutUAl{$dJzm;ngV$zxD<>jQ@3%>8z`YC2?~YFcdZ+*?zO>t^X3y{Jxin~hGhK+8*8@P zBKAj(^}jx?FXPlUsKWb0E&LLDw z_I1L>m_FZyyW^Bl`JX|WULS0T zKj@tKQ9?XD5dFH|8a{LM=-};(_jgVP$sS?HHoj5ieI9;-QeAY_ZH`0<@u^|s)7y`< zo_KlvIh0gyy!Fu~$gPS?6tAu#ru(89+8FmNzPweUts-?ZBP&n)To1?Yx zSWdpSpVLc}5HB1y_T1(1h%4kPjvVL^s-=Azv)Xqx5ohN|54+gu?Mj??*nE2mK7N#0 z{npKnj=0LWdH7IfU$YpJb8=GYLSfPFL!yhW+~D2$+ojGv06lBDyy}di@nY$I`<<-$li|+51mmy2jwL8j2`PBzvU&)eg@UT^Jx1SaAF-c z`j0u>|L&9xUiS?no!ufz$a!}Vg#+sOydVF0a)d*umbNtF?H4ciF28nzH}tkKyn~gy zri7fYhmAQ+ul2I=N(t4%J(oKuC+}l9ZO?UywGYptV>RG2s+OET$GXJN)+H)YLho#$ z@SnkN``phkAn4)jfKV;02KNC)c+kz^AfalI%}}cNb*dol2C@`XPRGLSxHX z4*0MQ{qxFisg`6gQIFN1)d?68zNJa)SS3p6E*to2zkFc5Wc-QiA|+HyGO@7n;O+CQ zmmGJ%N6uMYC9vwZTyb*J`}&`H`9HQD7JU8l2!~KD_y(4{Pu@=rZ^FyG36&_Jr;N=X z^u-^v-{PKEdFOy*yHI%Z(n0=`mcxSD&j&aXB_!vKnzyqDv;y%qb93KoFH`c%XvtOMZTdF0yFJJ@jlL`1fnca`wjL|5o2lu2Yal)Bn%*I#$ zaIe~vYYw-1oV`UOhfpnTX}mY;lOuxQstw*<-|fh#n%UrfI3*A-GaE@94w1V+B6k%+ zwcI=S%g~|0s_Qp+BOjO<=^fO2BX5d9)cO267g;?z-aIi zhGQKX+<1`)BFspnuN|UbDA1cL>#b zZPOX{OLcoRfQ@e5E(^FW>2UuYp-Pm{-D1cty*JkS?$f1R9YVGI`ZLW&lJgq>(Ph?F z>znN0sYD5}=OJ3#GqG{}Lw7iYYDsB9AdeHIc^qHb$CG>G>|wK9QP38-qQBckoj?1SASP`Ar=bA{MZgtWPTh%wY2wG=Er&oGCxi)Q9@=3-!eZoG9dHg z5UQnp+A=>un)z{hyAm?{zy>lu*~&7IwV^Nbt}iP95Xk)4=!48ppb{lyYzKkNkBvUa z{5XVa$-DwW<`3>1$mS1U37JbkAoCNXnIDHxEtwxdAoCNXnV&!VMEpo4xw7^9hA4E1>$q~dN*Z74jbYd1S(NN@2q8htnVW8 z;}EJPD{|OC=Ep`jWPSpbC?Ts?5Xk)4>J^zEUkTNc6*&lGer$z|%#W`UCB&Nmfy|Ge zW_}z(wdCzUAdvaVR{GBS$dr&ZJP7gb0`cN}@$P)_`amG_6Qr4+KqX4(eX`7t&s8`w zKMtW<;2PsyiraG@!>!q^OMEM0*P|@5-;&3t^qAq)eb<6x%Z%5|GX<%LH;}EK)y~i>?ewz7ldWjMeFGX7+^W&$P zABRva?bDX|@zczY)7zDhI4o=+^J8&QWPZ3)HjA7I1DPK$&HMx^Q9|oynIAiyiOi2fsFuX{VFQ^T zI{}K!5BF?mxdLAaWN7ScAI^+|K<39wGd~WYT9T&#fy|Gc&P3*id(X4Xh_3`PG}+l# z5Xk&^Y37If+be`>$=5wWWT#A#`SDevgq$A*fp<-o(sxZdgq+BAY~$_5+g)`qcipcZ zILndbh%CPY8_4{W(#(%jbJVG#rLAt6pK_Y{aauP=WcfDOK<1~EW_}z3zgyAL-eZ}c za+>*ZdP$DRGL5i-%ugxJ{5S-Dx1yze+A=@oH1p&1_8gJrKVd`mGw_YQVfx-$U-H1d z4J6O4EN?=^E`+@fh!v-=x zS*F?{R7SPrTHP`~ahmyYT2~3#y#*VxE6gEO zOZ$SeGc%CAmGtf+KJ(b6N&nnRm7FD$eSP${D-tENewO*Mz30gMID~4+ZaUNhnV&e# z`~)gdLiT%sK<3AK2{J#v5~?M;=|CX!W4#2KALqS%N?_G*ry!CyK_l}MrI{axP%YUN z1{<=E%y}oE60-9QgzN;QKNxWj12R9(`vKj0AoCNYnIETAvR}|SvtgMZt2r`14xy(+ zv<)ruW37wKkJGwJ=qV4&{Ma2t=Eu2%s-?ZhGCy&e`Eh!Q5{T7Ue?xWvZH3H_JyFQ~ zID~3xpSH|ToMwKU-mU~zw0AfW50zgl8-2kT_fA$%N}9aK;|b-Ge3?*39TR2)Kj|K z{lFUp9745ZS2=9pEd{n){hC*n^MtgG?byfeE1_p|>^*mO-r&C1?r{j!lHKvJfp_Uy z-^IK1c+%URPM#W9LeCi4n};L5d3e=UtsO$O-t@5=n!)LIvB_;XrU2|1wv z8+ZqVJ+*iTghQy7+pq8r2%SBVmG(h9@{buO}cbhvq(_nP`A`tYFF3@b|4OZU@Z}5oxV*-@MSXlBwnXBdr!NID_07Je5{P)M=keq{ zwea2`J9*D*X0=ZL{z8ugz84AN)2ivE_8{6`)xl%@iduWUJl^70yk=gCUtA=CuO@=P z_vlM4K^%I0JCCt2YVpe#9D#Vvc-gdnzcB*e4g@jhhp$TwK+NC0mB(l%wfKcJ#zJ|G z(T!gK^J#?PYHyh=X34RAPRRT3LRO*NpkGRY@e@wOn;W z7w>2gs~a6$Vy=-|%r)}P@fz<}^A_UHk>H)QZ~c0^(Z(%{?CsywI_I*w9(xC``L=O< zN7V@S7V9PDw3mcD-AygNU5f8+<27tW{DKp0@T;QMOUh|43F()mxMfjOfB>h`-TRuxdx^t36j=J z`2BPCk}~IQYVkYgEDf(&I+lh6OJ}`=-zH}-DRX|M7T?*=8uJ>xBw~$8pqGS|FLbk) z*jJ~i#V=p*G$60hORQB%B;O53FX30G*-Oeii%2cLH=idNdCfb?J4XV&1U6c&?jEMS z#NMDxE%Xw5$1|_FW13&vC6Rn}I{gk-%|gwL6^Uf@nSpOp;aiRI z$H$(v=&jTG`L~}tgJ0Uq2@lnUdU_I+`cAAA{nV4@fw7EuDl{%v+AAj$p$^WaQL*aMfdc)Ob~~e~PpxhKtmES=w|4#fidA}_yh33`{C0TbxGUmI z_T1iE*3LJrJLV0s-zE)P&i%)iFk9{!)`N|w+P>~R{NN*2lIivLkEB$QlnVFb)(KCQ z{(z00Zu!vTxAXYBC+&P_#4iZ)`r*&JM*KP->%lt<4|22F-nSs;|1s0!msF|s(1b=2 zzbDIUek)a48pLDC7YpNmhrefEETq^vFu*uKt6eqYT>h40ea ztWSFThkMvHOT}lVP^fO)o?qLH2ef_7zP3p%d{Now*Cct(`@t_VZoD5o&pW{@qaI^A zE_MjL=lqr_>0{fpfsGxX?dvsr^@{lBxpPC6D8VO;HrRVA-%E}A4u9GqREu9&r49B2 zd^h~AtF0c5k6K_~Sj{9#u!Z@5v^a?W4O?Wy{=c4Q-;kzc!pvtpem$Aj>{on>St>pS zXx;WtdR6&%Z8o2-T8%j#8yxAdZ_}KH0v*OY3~@ zl#m_+;-Iu&J^aT^hfpo)Zy@%*=Ob@F-19G*&n}~PSb6z1zN>n4v+Mn*w6ZU>(>6y8 z%xWJm_s&GkuYTbbXDm^I-*IQn`Tah`WP+IAGL4(P@sUHQmX1V)!d)$v+5PzH-1_zv za9Zaxrv$%?P8)nKD_=~H$KGA#5URy5rjzL3@h%We>Z~*yd`_A?+`}XsIdv437AY4B z__m?d1K&C8Fc| zAnJaz!eb94!B*z?GI{;Rwml;L5(&0AJmInS1<4p+kaP&0IoShAa|}jS|NeXVmCAU> z+UGr$D4}z3q0r@x<>hX;gWs(Az#&vi<}TQ1u-~L`SJb2Zqw_tqs88#B{sz_g%}UbY z?&guM3<`y|myQo7!p8maJ7oT%HK+7GM{&i zeM)9+*tost?V*QyY`W=aPbKJe6++it__l1i0;oH8qC=<_X93zq-O$^gy5ZTdDQbS= z5kokhS0qa8c+TGT|2?NI2GI~-n`T>WiLXy{&f{-!oxr(}*L=FTnqi$dZ{h1I^WF_x zg4i&)jL0j4Bx6#319Aw3)`(Li;rwyn&vv1-n_da`}n952B4omHZQv>}LR-?@a}!j6}&|37q{dAv>4|NoD97BWU9vrG|+d-gt&P^Oe7 z5>kmqgmSsZJZC2JJT#b9%H8X1GEGhxprf_uaLJcTw}1Z&aU2Wd!-(YYby}xC&XA!I= zx6Vt>We$hF_DV^o0ovXByY04ScTDgsEP2PeUv}05vRa$853Q$t2%>u?|%A5Qfi#@cJgwE7N9n2^W;DNR}Hy}8y`87sm} zuokTWf_STRRUL)@+F-3U=VV*)Y!YXlrEb*{Y%r_6_SaH^(tk6-X(KMf^wc)7 z{w>y`^+deY-&J#Z&;J?q7v-57W(gB^K7OeBf!6@GdVOn6hY8k_)jP43tod52oZ^8? zN@&G1!wO5K;#Iw8@m2#HPPN{O30mbu8XvzoMRUGy)e(>1inVB@52EV}MRcWT{VNe` z-G>R9O@Qcdrk|GJmY&lsg0*Na0-{QuDbBO_K5jX`P)C&Vc6SkGi>f|fH z|3I|rSVc>4O4h2@ssR)Hw%D7oY>U>CvZGgf{9CL=E89pT-|1JqM_{WZEBl98!i1fV z7uw`A#b7JbK9|D;Yss3s*h>5@)_S|dl_Vv!_MTzQvTE88FM_waC)CM$D<*hMgfgFh zNOOMctJ6GwE7r1Cif$X)Y)4?!UU}cfT;gLDU%u2{bR@#Wz{#a9v&=~FhM>G zl*i$3$9wm}x(6CIun5-TQ6}~@d|TQ44o^dqv)jWgVS+pxNaNREYN-EXEWBh)uon46 zkn_d=e&XDY@1xVQ(!54ujdAVOsNcfvwFIk_-R`l3t;=b{U%TV7){?AyBNoA0_Imr; z<}F)u+{3+xfa1%tYH^nBW;eC{$oeNaqHBt<3B(!CJBgF0D^|J#qiW*VVdD9KFX{9c03u zO}x-;vwk0yGQVvRtR*W)@)gKD3+q={g_4;UR;8>}P9}H_5ODy1hRrJRc@63!zSN|B z$miwo8-_wBZhFbWEU}22-ZPX(%iBNnvcS5}FI<|!1o_ykITcp6=QlKC@mBw>%p2y} z787y@sFbF7Vl7Wx3KOg)w}}cNeq4-wK8vq%7OmMioo&LllJz$!!T9|A-KXRJsFHiT z%ZxrLVS>}fdB~Ut%8Ui`!q1stE!%@NII_a~<9yV=@9le1Si*#zkLj}>GB3kcpZ)Dx z1Z&A%t&;P2KBnCy(pf@;&QxU_94F|l()q2Jpf|*P5OXxmxz5?hN5@)ZHxS|%6u+9x z*;v8^eNlL`Sx;?pN~49V(QK+ku$H~*Ol$hQ@^7s)^9r<86ZIb6pvLLFzw#{pVSYoa zwx_d%>TU)vGUjM%E19!d1o@gdPq+#5Vi&cQ%-L8%Usr~;@GOse+Lo+(^oB)HJ1>4O zZA)Yg(DF3MdQwut1ogEbs4elRHPF+0#a7~d=Qp(4U0z|a2x?uC23Cl)$B`8y{w>zx zH^h$hS@B*?W=AYxf_gZlajL;uwN)?7z?fhy8kc~O)n;jTS8RRGVF?rDF$3{k(5tOU zo$FB_WvEw^RWBWD$9?qFb8?Sk5!8z!4b1A)Rx-=u-(oF(L#)Zbn=jv>__$fZ1dZ*G zhOErX3O!cpd1S%kIbF+_J}SOWO&&$|J6Z&J{*VTZmOL8o#AvjXA@+ktWFEge6EwDq zVUNkGBWf#|7c#+GcFr*mR9nfskR?peoB?T&XVfBC%g#A@Mje(gK|W8ULE~MIMyxR! z`(}u&p}7ICi&_ND0FZ{PJW8)7Yp|SK*5WtBTrF!=wUx}kSi%I&!jJ~d?ks|}Xx0aU z=FV2E0TVRa20=3~jcSrMO6Hq1^U4snM6)}d6DI5MwwurC!)NA8T~i8OQ?;+Rx# z*z=29d*B_Dw*8jKcFQNs1g%*j4O)}YNH(#Re2cU`lOg7g*00!`VG*=Sg)~A~%a?CZ zyc(Qa*5WtB_fdAc+Dc}5EMbCH3Xw*xy0@vVZalosB3R4LIj!$HEMbCHgpmfV4r&aa z*h<=XS{=*~(MT(hymDs|v>J&tFgsOS$!wK#%Ub+~*e#35Ir#>^S=q&52@|w>jx=a3 z+#*=Z&iUFP(kawypTiO+$Zvo&Xw})!y0P9ZEOwJTrsYv&Z=dzMLP&aY zQ?wF^y#N-$T1YRkM*svOoHR~GBA&=oZTVPHhPQ$b(t0Z<*n_P;NX@y-Z~3iQi{b$AR+!IvVqKZvvV;jcCiRED$Gk@PKHkgX zTLf#_aZ9U$XxuYDe&eu&366o)wj?apg%47`kEDI%9>qkv!f&WPNZm04AEfRl2t0~0 zCeQ{eEv>e;)G1wHUHBk9{w>zxm;mh!!hsJ`cR5HJGRtE^c0$M-%1(ltyHenTvu72@`fcFgx|+`;gfx6Rc%Nl4ArA4t$Uv zOPH|pfl)>{@ImSx60w!c@>omunTV}q^kMDC(H$rW3C3`$CA%&-Z4AhYR}BX~Nb9Yb zz(`HwCuG*7K1j{E%su(HSc@WSKwz$Eld<+kSp;igZm5Lp zh(RP^uJLN!TZ@gfA_3V}CSbBW4K`c0S;P)LJ4lNhVm!-kX70YB=yg zdMshW&Ie|~PT+$yOt6;Ruq(Eb8M68y6Fb8UOXL<`(USc?{7dMa(}sitAEfnGOmK9P z`XDvuGB4!cVl9qt#Qh)RTd8$rUdR$A?1;t*8$U8N@qILz-IRA!Sn*JH)MVjSn@n?z zuX46%?XZM@SK{MjL?#iGx+dcUK1h#qEB8B#t;F-rZ>T;<-9-l_ zWH|6aS_ErxyqB)3Ie`z-V+j*z3pEXi!cZTiBYUvmgR}_N!uq8WvNtOf!pu>>51C1F zgelvK;uAq&cB&;PvsIQb!EdWRNUbF@%VUDI&@XDsfF1&AU?nvi_#kB^H7Q}j&If#u zPT+&I2-cD~A1O`QS7z-|^jJds6*a0+TBZ0~!3P-*e30qFVn3(H5+>kp(O(h|je2Fmfe$jB3D$z|Me72_s>la?kWS!( z^jN}#?ADVqmzk2aXH+~t$=_nF8=Lx1ic{DoY%9zIwFHwsNG(B`NwS0qPFsDD zT1zB0l?m3e_YcC`7Y=-o=`3Nw&If#uPT+&I2-cElP_b3g2bmyJSVDxuY2)Otn{SoE z5+>*k!|H?7oXZT13DzRJfsi;+8DGg>MV2r@-;INPUW>ob??ZN6Fu__JlO77icI-FP z(0?5N;8!bJoeA2(hcu`rhN&(&R1?L2o~Uog2R!bH+Abc&q=X6j3Xq1xiAq}nA0*e^ zFl+G}st;0aC37~GFhT7x(#ZCMF~!i=7JlliMX;8g^J6!6H5!&MLH!ESptdATt${=B zN`{@@)b4VuvqezriZmojU2G+>+nih0;x|+uq}mETNRK5C-BltaCm#K~ywk-3%Cb8?Sk5!8!?%UkZLRVAbEV{uok}|BH|H?D(#ib3t7Sh%^8r!^k64a_N=KE z!CJIK2}I+YyPd4P$V||D5CnXXiScfjMyxK4eKVW^L30D%p0_CRmH+&LHmGHP$Rb+x}aN53JoaOwevO5H$00 zXdWeJg=udo=X3BIYJ_QGcE__Ki=dev(vav?u@!ufJoA#hGWu;}RxA<5iB$s-vKwCN z6?~8yI~%MgSOl#W*WiB$vfC?<2u1g$0@9}@2>wt^2*yp~CVwfGIy2dOJwGWTQ&6SS^{G$h_t)@0y= zvzJ|SK?7jN|>NkDiH8Ns;%II zjaLX%Vbt=R9$)!Dn}WX;{Jpt?wcYS{;=A2KwDe z8&9i)R-SYhL}CS!SMDr=RwI#yM950Lf)A2c2dz_p_zl$uskVX-Qul<*H;8B?i=Z`f z$;ZvLaEo9qTJZ)!yMC>cDVX40d)BJ6L+i$}S0=HVZM~tjvK?ldFhMKccq@si6cN5!(y)XH@@658!)a^NOTborW^c6!*0OU>K1jn7CgeHrS|W{v2TRVyA%B!h9;^(f za>1jhUNYG~$nVaCq#-LT@F*e;iNY0IAu3l+<4Kg`j1?PQ$6!xAQ7!^G}> zq#fcwQp(}49v+7{4Wx}_q zr)ih1JIVA9O#l&`zeqPfR`DE>@ar{NQ+{vF@ex6V1^uU5{z z7ouhP(IA2|`+YgHpIZiQMdh4*AzplLD2U)*0Dt@Ym92BmxW|z@0)!YjDHTL;vxAR2 zy{&W3xIdR$9)yUW_Zr;I;p0|z>zp$lU&%ckLiA`ZJCT<4Eb9JvU#g$=@&Bw58INA& zwmc#7ua{HOaMq;TyLzgBy!l~=$Gbez$GMYA)SG`N2%I(P?k}6_XD_LK{<09LB_M)(!=;v3=bWLI#N@5S6DMa!3xQe!A~>;EYKe8u8ET0V;!%>*dxePK z2N|5$E49Qr=M1$(3Gw#GiM>LgmLLt(l2}kntk^-0vy_u{g+MI<5u8XWwM3)AClB_L2sVz@a=YKe8u8ET0V zvZ^X4hYEpOVzidTe$SmMwZuN>?B)&*bNdtTDuG%8;?6gpmV16;V@yw1?g?9P_b5|u z_XtPsCHrtpUsGfGD7`IBp5v#5zFoAJe_OxnrsKS!uAJmpXTh@uH!nJJ4x~KSYBSoA zGbj_Z-n-=E-X*iJWx4LQeA48>i%4P7~ZXrN1R-UCY_Q zLf|G;xfx2I*+bd2`xF%SbkS%IS*U@FDGb+LKQ*Ui?x>PyIrUgiB$b;N4Q^g^<*q)F;JjD88&IC5mT(S3YWn zO62xjxyejuxnWms9FynxJ)^;GX;QEBX3~Tf)2LTU!0Jc?^~w$El`l7u2!VPPle<#n z8TCr;jZf4P5W)QhQm=fu(?GQ3mTantdegjEJ$@Hy>|P$aSe#K7BbcIqP1uP_JTg`g>5XK%idv zxS3Syl`p4QiQ zZo-rkdxa1mgq+wbTJkI>>&kQTwoN(dHii>>ErPY=TweL5*e8j7yE{0_L1Y9+A`7jodBEHG_JF zn4Hosza)3gCQoBGl@FBmS;7SM1|XJPPVw8K|2T&GgqdJ1>PtXS{~;}drYj7{+8P#Bp>m6+=IIy%-0j2@ma!z+yx=@g|7zTt=?~S zHumz^>t^}vjuydM_E#I+$6^lP3~9NkMN;pYb-dLYa2tbq_2vQ7XZUp^ciwZ0Lw#aQ zZbXq^DpGhV-YU5H#JKPD_gTV(+X_VWm9PlLKJh!M)K)BEf_i7)kzwa9KDg4<7}1oigQpakVs0e$!24h?;lF{<_-ayPm39}ybqxm1_r{tvZC z{8kdGiE^7qQo;n)N~D4QBNFr<7QtFHW&}aw#0ZTI^;TUe1DUbV_W=U^MG54hZxgaywTdjYRL|vKIAMAkr(o9>X1n(tkv#A9Sg=bg4%Lf&L?gI}X)W zEMbC1;ULg|#De}q?>S=vkARxOVW_pC=)ck0ukK7 zBmIYbgZftTJ<}LYzWJEsFMewe`VT+oKdiL{8h`5jCXzP#52O*?+M}%xjb8QE9{F8q zacCq90{w>{^dHu5u@;Sx<87iJ^dHhDYCdG{%vvnyW->eY}2?lFmMiqDGVt+c&D ze`gUiqX+R;-sd8?y)L$FNDrscHC9OOS>oVdBNe1f}EUfqZBh$cINY&af8OO08F#2I^Iq zB}`Cy$Or0`AJi*{3D%;tL7=v48mR3KOPHYbb`Zf`Td}4ee`T$aQ14^4F`-a!pH~d` zd07%Bc0*q=)pYU3c36i(oA-C)~}^;ttLErB`dmSi%J518KBBokMee zfyh0_9bZzk~M<~c(c^A5s&iDwzhF>e%@67qsx0dCRhu8 zPbK0p+rgcBu^He06{B9?T6JW*q3*`-)QjOxJ!}1n*D2)=H?b~m&Wj~)Wb<(&n?ClZ?OD{iV=GCE!JYYC2uVBabsbOB}~|Uwcy@9fA2$GErPY!ZaC}y{3N*>(65s@ zQ;a1{upbZJjQ;gv?aHV61uDL4`RG`SPYO!jof*U3nLe*N@@gd8EqOm@%zdwzwaUqa z+|?=89r%F@>+af6R;~NM@Eg_|D{Haca2iRQY})P~%)c?l5+-av=gRnfkUs8%v zyCv^~^l=|#j3rF4UlltJAFdJmrADfsdCaGl&y=;`iPx4PzS}9dBR6)VYl`K~pjk?c z?G_5{dHPnZySO9QS`lVK?qn6~zP;foSogj?x2kok{#MW;Sc~n3eRth2#H8n3{>kwe zOPH|z&WCd!mOCf?=SF{I5v;{_3xzfe7!cb~sHeYu*8`SEnhExEBXZz)nOLM=s-Ny0 zGyGeu#itP=DhxL%ISWUkF(QYtcEd$oaoRzKdNN(?51?K?k4a`Z4z1vE7olfXAMVG_m{! zOvqi|V%<019Dp>gwL2PmC0)?&M1oVcxetZwa|ev5-ctq2+>I4&m?8dmjZQ@drVU**L+ zEP}Np3P!9eEd+K!Tw%^4+mlj_rol z=iYNh+THN?&-pB2qDhXHYTXC&PedA{8dX#4esEVai(oCb8|DUWOKY#Td-0t_B0ge*2e(PnJ7Q0TMP2hBYVdiqz3O^vaHf0yId5R+PIvU&E&RKNMp_gVyN z@i|P`&5<@gEY{s|wU19L&EgGBtY&BMjE>m#swb;B?e=!GJflp!e08KJEyLdYlVROl zBWD_Ecf0OrX%Vc&cEbr~jXpHe?w+{6tj`iA?6|&T`F=7oW_V$H4vSzdwi|Y(l$czb)I8IU^0QY=frKINaK|q z7rax?Ag=F3#3ERW&v&w-ievcQaN>O_o?6dElC~s%-cp&8tzD_@6W{7#`On$U&6W;@ zYF~fAmGbB^yPdQQ$x>qiHPn&vh_@xbR{q72+TL_c3yWYawsa_T_O0QLjF1bZmlf+K z%a#ewUnn$a#;ake?O8w4@<v%}k1 z(Fsg6EBB$6N4)3!VsC3#%A?xlrWV0kY-!}9#VxLUA8)>2TH2Ci*)qZT!#$&w=QvUx zrCQ{&2-adtW3P-`+}Vrr=>O;ftL`#k+iKO{EyI7J^?Bt~1B+lSuK6gzn-TFbihQ@u zTcTYaC=ZOnT^fZufnQBxe01ejVlmj#@L<*0q~FJw36EH@A55IR{JYvPK29upY^s*W z6GIwU1Z%OSL!p%OPiuM1?po4k2@{+@?3HPm-<9$>acg#qU@f*Z)_v-{=j=y$yzrm4 zSIN4|gl(&h7xOts5qth?C2g;g1Z#24M+{_xY0l@ZQ~hrcNlyC;tTUZx9|FqbbfKIP z2i~QV9a>p2EF7J}mJWr+|8ic-qsMVa<~YexV*(>*SK6!itZ2~IFSI;H^}Np_Sc@%< zK5FkcSK6yD3KaHP!UX3J=XlL%rseTY?o1ZJT5M^=={qN!BPfqI22Ho>E)%w`^1bqs zGY|Ve*8W(}B3O&|g21}8n%1*^c=z8Ik^bZM0Tq0TTak4?t@#p*#g-0*hF>qO z{-_F9OUe3`YDo+v6XoA+rWT2>cx^72DZNe)PjuXGM!te_i%U7QtFv^Ftxp zi4>z9M{;(weiO3CgmyI}jraFI6lveTe{9)|B386IN2s%CHv86GCeC>>uN7*7LV=Q5U^M_TnbL+G`{$8`&B3O$p zjoHNf$J}cuk6dTpvFa`pwym}_J?s44B-P)$sH8=(7T0{-6nk@@m%%!mejl<^hxU2J zXh%NE<5>MR`h9F{7xF2N%!&$ROT(*w=m9N{GxdKJ--MQj#IbYaA=b#XJmTJrDbH5c z^2pcwyhX4UTN>x$e41H(+n0-Mm-XFb*)qZT3x#ri^|h8qrawQk2-adtheFkwzwYLl z)x&qzbg=3!6Sl4H?U2(gh&9X6W%F4CYjMrDcG1ZivX+PJgQ8t@G1^^+^7wT1ixHWB z+*Kt#Mlpg0F*9muiMeD;BOh0qYk7R|(`Qy0FaeK{+A!|BTT->ImPf9^+bn{$*wQ#f zuzNoBpO<+4eeq@_%a#ewUntc7`yaJDzFINYB3O$pjhXPXgWcOv9*@1+P*#MKb(aa- zR%N>scmKOT)&IKfRjanM7T0`hkD_=?G!5Bh27i>cSF-zz_Aa74#!h=RQe|lW*z-S3 zw)W#tWQ|oe@R&UMq?SjUyd%W#oGdja+P5FAHjI0!a}0Yx%j5B5GcAI(*wUfUw+)MG zc{J}bOni6AvSotvhxy=%zqCBIJ~+f8Sc@%()ehG#OY%JSNGy%Y<#KVZ$o8 zpTi%u`{X{WwzC%3d}{}&p`D&`SBjR0?CqnSq41w)exj$wmppXm16EWq#eQViA2ndp zvyn5H4~D$EV_XJIP}CFBIMt}BmPeNRpS1|qVoRe<%yYYzN9Vc^#aO}w=PwkRyE7D# z`Nz83TUrEbv8B;}G@a@;MR~O87!vEl0M7r1nce(eQwo6CTPbo^6_uW zusZ>f19M9awg}eZdW^WGrcK>x*ZTUU>v`6hXMEZlB0RKY<1u#|`!;pc{_E?X&ayDf z5+?YhIkZ<*7rHZ$4|8I)MX(mfGlfE3q7S>TAdS^U>!q`V2}%z+|8>X$_x4YE__q{T zXvM0r7QHQqH*e-#VptM6G)&Mba3J2uJKybxd{pk+-in%IEiN0x2*3ZJyA*LU>HVr% zv2{$)K5?Y+V37yi)7U3m7W;(xw^)lyQ{$HO`#{{16`M~zvP*5gqj5|6eIRbhk}yFn z1_;D0>Gy%SC5vD!s?#74x1`?(;+Cx4%S=%IKp<{OzYoMMIs99!MdbtnaZ7Fxx8$&d z39=gq#4Wi&+>%ujS&PaB1mcz=J)-?3Zb@Q~le-;gl7s*x{J6aYsU!9sa&?3#x3bg7;#GxmM}r1L0A`YOKM%jEm^`yl6tTT<&HZpr#B)?&M9+>%-s zaZ4^sn4qy8(m>pjS{HFk7QtF%-saZ47#T5LCsThdid#4WijVS;8dNCR<8 zYF)%FSp;jb-862=4dRwumM}qc9HfD`B{zs$a+qK(njwKe+>*{Y5w~RR!J^gS3}+`G zZb{dW5w{d!i!wp$T1W$NOKM%jEm;I>vE4LoN!Mf$x8$;f37XL(4a6;}brH8@5v;{_ z)3_yf`<*={Zpmc{6Eveo8i-qRgSaJ&U@ck?0P*ilkBRI=N_b3M@{(lO;Wn=8p121q z(j>wbWrEgZkp|+HbVV3(OBTUeY&VTtQtKjaDZ&yaX#EOlAZ|&mi?}713D#n}Y21=~ z?(Uuvx8$;f30l8G8i-qRgSaJ&U@cnx0)et-FX@vQ8sm zf_xT8193~P_|FlyWD%^zcGI{ewJze8A}nEoR%?+4;+E99h+A@*U@f+r#x1!)+>*-@ zCTO)5X&`RN3F4M4g0*O^7X;##+#qhrI_rh}+?J&^Zb_|+xFu`nBopMJLmG%%(z=Vd zC5vD!wwuN+sdW*z6k!Py$##rKiL#xh!FVd=p3maZ64R zw`38lMV<{1h+EQF1H>&^dqyd$L(bkwL==EP+>*wAAZ{tb5+=wW4FYjXYF)%FSp;jb z-861Vdo{!@MOeZFdE$@;;+C}TB5uhdSc~nZaZ64Rx8$;f3G&1t4a6-uLEMr>uon68 zKp<|(3*wd{yx$eJO74SYyM;oCTM7qpOA(eZLD3gT193|l$$_{fi(oCbo5n3ULEKV= zB}|at8EGJHNh1dkw`38l#dg!UB`1hma#_Lz`JKhOH6L?=xFw5VE%I7}K-`iE;+Cv) zqfjf2?5LBoqS$U4x1=$5h+7g{CCh*bSRoM=hBOejEro-)C5vD!iqQapC?t(&L==*>3!7qV zGn~qWD5O{rg(Tm3vJ99&eKSE664F2vlE&O23dtf^i|wXSNG6Cv5?dupiV0XD5jli3 z5QXFgQAifST5LDe-9m%bi*rQRd<=NZG|W# z6GS0d1Z#24*C-?tL?O8pRqRp(wo5U>uoa?^{2&U+IthXHv}8DK0Z~X=9*9Dc8B4O% zn7}wV7DOQ-4MZVnc_0eOB3O$ptx-rCfsH7n2uqmY{Am=DmItDcEP}Pz(i(+if+!@b z?lNK93Q56r0RLdv~x;skI*uZ`zEkzpwHOt1Y02r$q%BCtg~3L%B_}`^FGMj$utq_G|f+!@5U@fls8ikZNN7%utntmU0sxf=APUJUH74NSQ5zx(327h-Ny`IK zNEX3bY-x=`@@4*kC?up@fTXdWp4i8r1-Pk;)w_k zEm=9UC=@~zQY?rA-_>7=pHqY=q*xGzWD%^zClF~AQY?riNUOJCdvQX z1WW!8A_YBXyDE#mUy-KiuvYM#j`TQ<3L^YB&0&3yx*aKIh%+=yRK&7CZ7B3T1kDo)SCn>gkJCLc&CjWdrs9 z?T?0`ySvdsC1x(@;j<(oA!)~n@v-$vJlg(six4`Y)%%rIn#Kn+Ye6^l{MSnKt<=qD zNk&5GIPpx^Q%V#p`GQ3VozTj4YfRI~Ji7*TYZN@E#MDL4E5TawELt|vGH-U2Ap9UD z+WIV!=LE6gkxTmg%%t1#>lc40sKlS`AF~M7l4r4coG5!oB_&4P(!gg46T40oib;A; zI608UvLUsU7})PVi(oBzmNeo-XvRZI%-LARX9*Ke-(6AD_~Es~1~ElVTPm@2dNGS& zEqRtS;zaq)?UcCGEQ`+)CZyzqC{#}FCja|*M?Hx@+z5w*KyWUh{ z#-8OdmSiM^juR{I>!n1e9Fr_U=!Dh}6B=k5*9$d58kslrR^sW-BVsJcNC+J#PVMQd z#HbuCEJEmn*0FMpHI1%Emf;rgs}1`rk*8yk7)zMwccZb=oqit-;`F&RC7N$uZG#MDR2%&Fk4Ja>Z6kgE;X*8VnANqt)=;;&D2*$oiNk&5GB!SlV|0je_ zXn_vj%m>~IUpv-+;%`L~o4EOgIhOySM3D0&A-|i@f)$*bFU4y+#_dXA+%B~} zDal9(9VhTbDS>gjMF^eH!q=t0l>BOyz_?w$+N2~SA#|KT%b*0t?G_<)LJO^g{t`yy z&_(N`1jg-3u$DZFmQA3ALk-k%yR=uy-;(D9f%Z|KF$%}8W8AI;#_bltTJkKlBu=2E zRs!R8X+@I~CeY5ik{(9kNCUlr5*W8z1Z&B&q!B03<0ye~yYvQ02@~kAG!5zDblk24 z#_bltTJkJu#0m7AN?_bBy;@Sjgp`~R$=+EBjN7GmPD(NolJhu$5r7gHw_AkJ2`!8U z^p}#O3?(pbmr+Jil93QPPGH=w1jg+aA#_3uqZ<7s`2uvbqy)z8GFnPXG7>_^35>{; zz_{HagidH-bf&))AN64@ssu*JG8R=W8Q03QSX7>+y%idx@c39%35>#JWSNvOVW)wy zs1m_gG)b_QJWCqMv8WQ5O~_a@DPe;1gflsQl{P&TTCwg2PgXyku2)-ECg`pB|5%xr zc0EqiY@atwL<$r1jGV8C#ffA4>N@`ip}+KIp~3ZKohcNmpBg7VZ$3zggoJ-ro+an; z*#zao`YqOyw1Z#5x)0?;bC{4YLC@#`DIbP^i?t|!NQ3gB1Y0+FcTeb`#vl!bDS7UG7^$Td<_6|93?Qvu?T7zv^NXdM5K{u z;V{REQJbi5lK5R}yFg%$qiF=IADRzYPuqyz;E_A7QtH76M>*!&1VS{)F*&i+WTLnB!EIgX}*IgUlph)h<5HEoP6kp|{CN(3vyNl8XR(ufn7<0v7k&iq^QoY0~% zHPWCtju1w^9QiG1>9ed^%d^n(914}|`UC2GDD++TG;3v>37Tan(MgF_v!WJZYbECi zal(-_grGSGB+1!}yp>uc`BqBETQR{}@_aKN$hj+NU~V99m6R~Sb_<2}mX5EH9sK@% z=f%r4+|{Y0OwlRzJb5mE%R)zyV%=3Nd;G7>_^iNS~CYkdtL z&+0NE&k3!??^M^cpC5M=X?%0EA95TDMZdk%WeF2+*Qus-&Z)Uk5{+)8Dv`5eZHr*7 zttYB!8mE81f;84W8z-jbZ0NFt33(Qa#M5ZwmDQ)DV@PhbT6|CFNDnUv^i9~6JLUp#siNgO>QX(N? zLY@;N1N*JGoLNiWR(=Ut{U13`NG#%J8W>+u&JF(-5h;{**vf}tEqP9i&TN8gr6m~T z+$uq`F4Cay!y;IVY9$EzJ`77T5>l`5eSo0vBgTY0C$!`%khjJ60fN4d7)zL-x{EUD zy)s_gXVpou2-c#S52Cua+}m|3>KFTHu-B*hZSLCUqfNK#e>wip-1=6_>l|^49?!4O z&urWc;`=jYyj=fA{kq%FrZd4>Z~j|Bf61FDMAsgxz3oV&!;AermN2p8uL7FJfs;Ex zOjh$)TwK#y_(>mN2n2R}nXL(J1pm z=`A28kIZg{d>QrozW<5G5+)8_Eu?RC_TnZGBaY`c4{eS5yUO?$!CK$ka*La(>?pHk z@kS6O+mABe8=bUi9;imHD zwIJRYG{l^#2wRP8YFNTVr^p}9lskr-wV{tejQMz=d8<~`U)`ahMX;9rR{M($Fm3LS z`h9+N4NI8F`t3!h)0p9=;XKL5sQ!ITn}$*U-cUV@U@f*tDD>yQCCvL?)Nj{ex5uUS zTJ#n-y&7&DI=9iWOR!PRil)My;ZGOPKiL*4*yqnIp~GEkaD|;+U7FMg0%H z&uo}rtraJ8xn*aJGzAw4aqx+U%%!pT&R@%ASi;29g|fLTbBr`)kEDaBw4;UTIV9>2 zd$E8;u-1k2tnT=0Bh2&#LLB_{DO0si)GvIzxM2ws+n>nd?)`d%x$EG15F-jdYhLai z^`iqzSp;j{S245u`H~Ul&%1;um)g-(c_r!}eZI6|2@{V@&*c6&X@t3Z|K}jqjC|2- z?i}@V{Z-B)Sc|_j?8h1VvT-{^{Tm-ww7x+m(m%i9lzVD~arb_PG;aCtRrBi8QU9@h zRV;$F_O2!og*|Ehp=fr$=Vk2-%(8*1*Jw*qN&TQkNypEc@tZ19{#uoky`q0pw`+r2FtqQ3h~ z5mT$rM(63iAN()sr_WrJE2hAmsNY57kZw8bwBG_%3J+U)W2{xm&Xz&#%C^~eQo;88z9yW zo9`7w8ke7Y&mvfB@Yh$>((*SH`X_rq?*P&mx2>SZ5+)91%cE(?U&QZjo8qM*jaysI zvk2Cb_m|R?w+@AN{F~ETg*2KqyWL|66Y~CIH%S*K03yd2?q+ z{k=QyH!NXdJ$jno=8QDI6&2!@3YpED(@}y0!WO|=Z*7e^bbC_EuMEw&B9<&J7DtOv+Zf`Ks6hA4q13&V2UNe4V z)ciG9+enD-M;12!^^f`|cRpqjtTp`TdgrU%Bg_-+CBFUpJ4={d zy`%m;Rh~AiRetAsXZM#QOu436T$}i3cxiK`ThyO5qoZL76P5CP?lgF5gxT6GgfvQi zTF%sd0YtqQErPY~{`xbg%9A6E`AELn@)xR@2IxP!6n)LGgo%_#*Eu!*8E$gU{Rc#@ zDfgH$kD|=acDD%D`rH51`D5R3^X%*^Ao~4S*Zlqv+N(})8up@JO`q3$EK!6rKmrz`w+ttCN3{rZiYI>Supk`NEQ^R&s44{c)h(H6m4O~$Qs z%6~u9ym#(<5c>|dHN|rwjh{ywmN0Rk_)2Gz8EXD|;W&s|4WBc8vPAt(rQWp&)+#-F zh0_)NdFz!&LBuw8Fqtz&{d4o)H7sFb)wC7P#`lJrmCJ-U{y|4G>PDL1@0?Ar*6Sly zIPE76HH}{u;?0iFn=h}W`889=8kR88x$knP;e$iX?fVac7?SlRQ}}Y4|KX%@7QtG_ zsxEWd9v@6S}%O_fm5Ku5VQ9FFF_2f*xT$op5}L+ zHp#GriAU$Y@BF@Pu$f&!=Cv0iZ<{km()>(UZGyE{EPUTtynV3wr>YPSP3>zo9!&FB zJTuv_go*6`E_HHG9&9rIE;He|FQuB57+JpFXR=|f2d*x4%0jE;nJtb@a##ZUKwk~f%tZVO|Vv`A7(nkM?_7T z4nnl9OWj5G#MQ3D)}MpPA0wX;D+`Ga*(z zHr8|mapvq;!xAPIUzzFDd@pLsuM#5Mc&vE@M9r+@EP}Om6`tjM{(jWtEjSy*-tbsc zAH>&%#~GF|(e92}&ioZoGqa`;4^|v&ih?Lo-zHdVO4C`+rR`C3=?ftS+&0!^26494 zIKvVq3N@PL6x$j#h1Lo&E;QC0*^uU+>}wOO^<2MMPRegl^Zi?MKzw=TUE_oJY{odl z5+>5d&2nzN6gAgB5u%d+t{DpAl^<+^wa))E%lWJD0JG}gToBJbINE&Vr}>rMpJ*Pg zJJ%Vxdw`K|>H=0uYOP+5~GYxowWqw)X&YTh>J& z4n97{Oak%8@(G3|Oyp=Y2Rk)mLeL?fO#;OPJXF{9>oz=0T=fP6J}} zdxOlsyVCsr584E4&AV-}^X;-h=9b(Zh+g*$Ht9Rl{68O>Vpzh&!byvqIfDk7nGeW{ z*UNtoHnn!3g^Sn(YuPy;ymW{;v@Ok_RA-7|2@^w5%kwuFWb(cvwkrDeQ1krOH2-<@ zYD};eTRjx|;NmFrCCWVQ=ZS_}94=>RPyW6#z%-il0n*4eVwAZREkl8-leDEtNSL_P zd7krK^?~LKjMC7nWg2B(k@jkcO|VwZ5%ZjW^#_{$ZI^*~wEswR2t?C8lMG9k*!j;q zXX0}M&6ppSgQ#C*q-lWO;7FFq7QtE-pPKI!?>EqN#>#yt^y?}LfADlKsCiVZY(oL!AH zy44wOrfx!S;MoLg@wbArinFiNwZ7WxZwpV{mB*Dey?Mh2dDXk+bHyL=^Q4j9!dEi8 zvYzTRz0reae!f>?BUqI$5#eR+SFB}|-7E$ND9t8R~NAli%?udC-pTG<3^#Wt37Wxc)1 znC&2LFK|FTiseU*OJT46^SvXwPMH>~WjLY$cV{+kqF&4AieIhI5+<5F{Gifz-ufxh zIQ`cF^^8`({8|bVtVNz!5K{-gtA2wk-R=wX`*J=;J$1YKCXNi;4dS=AN2_n*wv~0m zEMX$gf!o#pF>cp4Anq*$8^Hgu@ZmZZ!CGC;-l0C0y?wp|v7+2i^|5T&b8na>Ohjsx zRzFUpyu@XU=rlbra3k*gq%efpUC?mB&Wdzd9moS9o$J-jEkWj64{z1vv*gB2zgvk2CD zGw0pvU93Gj3y8<>t*buBNe|`^vxEuq*MrzFy^{K!_w2|PW(gDH3)fKJc9%{0L9A+b zr~0lxJNeJhBTi4`XlwxpJ_SRB3O&R zF04}zxW|a+r}nPbj9EHWb5XE;I_57U6v}`@K24TvrbLF2pu6Ta(oW33TST*LbdVZ#5x+8_#45Bp_ zOS~Bpi-mL5Dm|*6pPb`b*Qb~gkBN0&yuDie`x_u$d*GOQe%kGL(IQxjV~w!FGQWj- zew=DKKVu0KOJ+9GHZdOWGxxzG>iL<`{Pp!ruok^7Z1rc6N7eJQYR8M~S;7RR2cpD) zqw4u-^harqfeN!0*$~8+_cqsjRGztEJxiD%yMZ`T;edL6PW?0@oe9?BS{Vwx_tXOQ z{9Il*Je?&>*kyisbY3H#pX~0>7QtFvr$eD4wVpEK`C0Ck_PEAzP0ZeL@=6I;JU<0H#y~uJd6Ig5D($lg*7{&jaaTM)ZnO0ucD^%B zJwJavP|srt6H8YYb#ub=Go#BI5Up>_G~)T$f8lu6miA#)2^cIF{wOru6lm* zKY72$5+)v~SlAWM&wK7t5N~H+pq`)Gr{8B0td(oUt*&@}HWXP5Vqe-K_57^uQ`ch& z6K4w+a>eu0F6$f+pXXSjo}ZUz*6~=v#I;!kUGe->EjkNC>HQz5=V#`@S{A`t2M*t_70*xebK^mjJg`DNKV2$Uw+Plc>g039^V95` z5g-mWTcw_#GEY_YSi;1f5qVwl{QS0cD2S(?U8A0#^V2I^1ZzG0MIKi?KUrE00= zIb8Ale0JfvuuW_om9Cy2XKPW9B}_Cpoz)f3PqigYk;d?Ao_c;Rbt_~MtX0F!>Wb%Q z+3bcO&cEQR=O?r#x5pADMs~{Visz?t+gcz_zqCO;KhCe&ErPY$yqMV)&rk0ch4?0I zqk4Y6do8oa5+*XW&*X~d=lM33K@2^%Q9VEVw}(8|x&vC``Dxaza@ZzHw*EprKWBPf zPiF}eYf5Eu#q-m;c15JI?!7P6^K<_v|5yZTMaP6(@%;3tRt7}T;+xd-lXw25be1sT zt-PV0pYi!if%tUNCiVQhHRQZSuvWDPZm8#HK*8HUq*dRno}XTGeoJQw6U8cASI^In zrwV|mG7JPfKi7w!viH?2?}A0JR_9$u)$^07LoE>fKHQ<6pG8GVe9jUknjAi=o}ZuQ zHv}iOB&dYDD9*6!Dispn_Mb8A4<->^eHKj%K5_Bl(Km^S*DdVZG9{{qC*yLPDOCtsT{ zEP}OC3LIC@&)Kcn>f_wnZ+58XXUDF?pRRPrK)8fq3$l9qRencca*PmM~H8+;R2%)SllEM7}FK)bq3Ut_BvtTKzA7ub!V? zTZe+kTWzO$eu}lInEsRVt9pJe&uN&_ZSt?``RTB*pAz?8SkDqBR=)kSdVbbjE(oHLvs1k?gQkVjnP9D*xlgL+=Z^xVKx6?So}ULl z%$d#-CW^jzQawLuHOhc!TtA*h+g$}Mg0<{gvgy8^>iM}^uy{I4nCRE~7xnzOU8G)B zueDP>Kix~;Wf82!H5BnzleeqqXG*_0>A8EKSIDEMcP0tbf$=^U$VjARhW@i+X-ey5Cv^Yi<7Is(OBom`otbw%)3q zpGDKYOlJubhYDR$&rjEsOUOrqgIm?}Gja4Li(oA~=bKw@Q_oMM=IQAyVZs@CNj*R9 z&L2k_-tKMc`6+p3l|`@?TV2kl-l?9Ss_)&K&Mgj?bG<{S)blgs!gEODP_~`w`T2Ip zgXt_`;+;Q!SI^Jh*gz2Xp4_3HpT8ncSp;kCfBv+3exBMq6htSpLp?wJXLe0z2@?&s zpHa`xn}1IL;ZED3o}WGK`&a~Py?N%WdVbp9G7Chj*LJAq=Su#;=`3L)&-`=h`N>^< z0f_Rocc|xQNUPBn!CL$kV6RN>9qRdMeQCV)eK4`_o%8DXng8M%r19{!?dtjIm2DrobwGW2-cvG%^W@0U^@W&G(ZLrnk+aepT=uqvmb#CS&DpOZa}% zw!lJ-1^#eNDYx&`+0M{TBhAtZh26jME^wA$Eo03Ui6l>1aKT$NDC#$U=sCj@CVtE_ z)j4-`xOuZvP7wQ7P6`hm5cLoBe9Nrqd&ry8y0`hZ$O32O@p<0m-`+4~Prv32Khsj5 zb8nI}AP%2w?(9W0)v-qxn`3`HZ8ELuZ|c4CiL+wHTjtM615A%m8=dk48W_pP=myh4 z9D4Oprx>D;j#Xdk%zgvWGqZ7~;Vrw&`bk*fgnf<=I%2XO9BK}~I@sJ%<2cG=>VIvV z9>1sg9U9McF5mZ-Su|vT`Elt6L%(Y>zxaZtvBet$V(hN%;pUm6eue+%&;GVT?4`z|&GWgo z7+5$a>y)s#F-z{!=XTx3f>=2A_3)=xqW*i!A5Zx;bER14Vx!F3uEoudDQ-+6yX(wr zY@A$SecrX=MG(18E_A-dn0ou!woZ>xn@y|C1I^IBsisu5htAR~FL``h<>HFTTh#h=v z#K^HwE|?7uR-je`>W%9z%OhnrgZGjC(ntIpNRgUuh~E{0dN zx#mcjH~ro;x(&6l#ur6D!wxjpr?M*4231)NK1*xYqgE&O1|jnfad_4qv_F zEw$CIzh6NbO`5-H9vvL@uXLX2v4n|xUw=i3XMb4%V(h6krtYOQe^c&HJ$_%##}_#Z zxHU>)rRcFTc&izCr<*O|sK2t)ERQ8jOuVbCD_?Du6|#EXy-f&gNV6ATN zly>Et|D}qYjJH1b*Xp}#{AhlU?at+KWlDK1kN(+vgQ#`%kM)OcM1616l=WZEtE{Eg z_v@|BOK+EROEeg59v-vFIrUq0{r}hR%AUCI!moR!FGu~sBd?{igo%n3Zr3!rw3fJ~ z2bb5?b?WtBdKST2$DXUBX`BmB1u^Td?OqS;Q0QK#rpFQ{?0mev?*UC?!P>FuOt998 z7WZo!rB9DQ8UsEKdpWV6bHvcG=`3M_?S{G9()lLsG~)VJM-10EY31bWLaXO+4Mn{w zw8#|0H`r+e;;O0cGJ)^k3BG^4Rr&AdnGcSp`MFNCu?W^W+wy>ZD=%c50HW>POH50& zC6VcE3`>|myW#}x3W$A0-!r+*jP9JH)=Oxl9bXym*{jI2f zuuC?>5+<@?B{fe^#JbFo_{6pCA2h9IU|&)9(;gG7^8Nu`)fW4)llO1b#p+RdAx=R|CQ$N3omq7A}w@+C^atP^uOBIJoLhcASM=y znEycBjp$J(Sj&E^l)X*OGe2Sk&~Jgm5+>w33`QSFqh{*k<`H~@`SLEb2-aeYghDgZ z*Li<7i~5VFj(4Qrkp2Vxi1r)Of1p<|p_hh)rQglcs0Y&6+Ge5G82!hi+1_wiB0Wul z_++c6#N*z}ASQQT;EhCl`>4M>tFPt$^@o;Q!~K3lgy|>?OUj^v>vuL3C?5)h>X(HY{WW+VJldCZvy*z7~Bhi2eb+?YYRp z+YPL#*usS5Jo25RF9vb8P-;6XcG)C-Nwp#X+$=o)beH#7X-K)n9 zg1w>+jCNw|*_<21I((NsjyP`p`7e9a0LArM9!N`5q%$;fRsDVclG)l#2 zB4@3AT4BX+_ARrmC%5l7ebK(a!}g(v?^L-$p}Nhgf9zhF-m3E$-6r?9uy9 z2YD+G4YJt6M9m>S0WvD8(Q+b)+$qNDvUT0w;A@E#kBY`Oo9$%!zxt*zMo5@}+%imC zsA`-v{Gr8TCnnI#De3Ld>mkO;+|Big8E)_TvyleDUNklUk#Ch-7wnB41UetE*uq4T zjPul?dV}=X8M5+huJ07RzdkD5UhFUk_Tsya=P_-yPMy;2{r&Yx<9RTFv8~hZ%2?OO z=k7n-_3w{^yrbXkHwgCPaU$NUgG+T&jJ99=SXKS_dWkcRYSp{|=cT$?n|(_9sI(!& z@O`AawiNrcp&ln*6U7$FeL3R*Vm{6mcmf-+ed`#a-7nG5joNt$bs?t_un zj?h5G7A8)QkL!%Qs@0ngqIkMy`V?kA_BBeN{w^6OVA;{JI(d~1I&1yp0W*h=(?37l z?#!7;+m0C#5Yw7jdfzg)xAOi!EtyUEYGEQWI(2}I^!M%B1>$4xqI&mMv{&=?8U%Y$ zJ_q7LoRfBH%rgw1{Hw(lCTK(k;;##PoYkKTx708Q_M$uyM3eeSJTkgFb?CVtjb-#t zzxp|&yPqN~O=BMrKC6T5+!)<$DYMzd7A9zf1cF9h2Ekr5A_GCAJBuw$nAbrgNEZ|A zMPpIKXtcGov+gxI<1QClnBe<{3^}(~-@(j8>)Q)0Ze_Ujp|Lu?sDMja7X~r8%5I*& zFj~0PfBfrY=YP$Yb(ZtoEA&w0)OC+9HVF2j(LJu?p8^YX%kr3+=)c%vuU$ow2S|T) z{O7FNB$jUu*1Ir{YS3ho#TF(i4A1F|qxR;jiWq(+{dK=xZg1qT)eVBZGS4j;aCqH# zt(p}9v3EuheH<$qS9kx(Vha;7)AKsxs8(z0fmrg>Z96`)j6~f&yO>}ve#h{Zy#3;g zqvq7gX0e3{n&Uu>ykDN$@&3d*vOGBqg1z`1^YKYrdAX{L_UcHs1`1zjp%&RZwz(yFb+(LDq&L9$1VpW_S}n)jt=DV1L9o}Q4qKgjl|}`FSoUeR>VnGR zHH9`zYp@pYZ7G;?6tV*1}DausIwqWZQG_MqyI?z zewEBLe*5iwO)@5kow>u^jkvo`^}}vfH&RZs*un(Q?_*|r{#4blq1)R$a*9E)my9A} zXYLTgr)`Mph5Z@YXYOgSg^7x{b4N>m)%09S5I>y4j(C{;D4e&yL9kcv{JEm1fG9q_ z8i;m7+WLJ#Z;&E?S3k6U(K0uUxjxOa+(#alcK+QCl@WcN-Yu*|@7-S2`=E<0Oqg@w zwy(>&kG%b9;Ru6Zue<%qIx*HYo{boj(*I#i#@OJgmBnHU6Ec31aTG>PAWoO4V%)jiv!Yka~ zM|&GtY+-_*4Z2#taJ2@j4MRe+tG-1Z=_1=l>+&??STHd(!zvYM)#Yg@hSz5GwFY?{U_k&$% zk-JF_cQMXMi!Dq@ekge&@;VTbA4;Bxd{ME53G-LoNpaEYv)1j6epJRF*z4TjT{=tR z@%lwGiBaOOKdt9WvDZs4rP#s*-vtnpA6sWYoUZL}5bPycva~+Pfe~Zy_z!-PSx&i? z*d_Xw+!JJ&(UMV$Zh#&;`r?h@&cC}W`GbgQywa5mnPsvL!4_MXDEm`K=T5(Dk{`sY zDxt2E_|69msbUc9b)dp*Cx*9?%rh*inAhrvCwTtoF^ers@RLPt#)~aZi~t{hgJ7@2 zKdg0P)OD9cj0wlrxnv*6ek03SY+-`m1s|WKZ?$y;Bd-=Mb|}^zMU9hrN{qVxM}w@q ze!b<3Im^XUwPJOW2^mX^Zh)~hzNj{V%dBPSYez)b24Q&JK5xtH;GYRUgYahFU{ykY z-u|~3lDW4VYSB?1bYp;pHj;V%ln5i&lTMOd9TG5CZzxSKA*VlekSV^bc0b@o*M*v@tg1CQ?5oA z)e|+miC;!&*5yTemUl@sBTt&yx@u5}uJ!M3g%yoo8mqpT12|QE0junWs!xhLi1GLP zsr;zn?UQwx=D)=;cITe0tA&Q>lqDlU4-Z>v5bPzoxy%$nM+cGhg4gQQ2QTzE?~R;@!Zv11hzZiz&Juw&H>5d9M_vnHUuy0yu6 zMhjmp)Y@?y17gCV^;RLYS0zWs7zDLlqCnWOY6ghE$8NNmAj_!LWSgud_-^^$+R0qM zlVyk^5AAM8dn+&YZX49In||^!k?#2*TtCm6Ge9zK>HCns1z@h<$r(g>$KHm$n^-ba zwD?P7(cr&Xn2@y~k^vwq1QDlkGbaO3zg9E|_M$Hs#Ngd;T#{vsNb{G?7AB|<29Z0B zuXP0dV9tCe4T8O>WdL#F+8lrB&wt+eG>Uq!0O!fo2fT3oi2nRZqJB18 zn4mrp1ogEB!CusBgP{K0W(yPMbx_V=5bQ1L89Dj1QY?M=M;q; zyG>{R)0&94efn9;AlR$O%3V75KjZYSC807g$XDPPR}U{ImS_$ zr&$>sRhunL z6eF*`K|VZwH3%8i$>Q>_d92~_ zszn!f2WHM6{i5&$-J$FOMe`bpW-LG)$hKQeydUJPo@Iy4cT}=(>B*2=^9&NMeAnMv z6-5@FX=#Mb_nisJz9n-))(ql)E3I~;SF5mUxSs5f}8PW}{T5bPz{w`AeSxj{(wEm=6SahoknNcJsRII?CCl6^}Sj%?f@ z*h{i+$-dERFY$eaVwueu$PQf zoe^t<1!C^5RhA1o@NfTkz{3_MXa)&HhT(}_(sSl69XE;z_L7lt>`G7&U4A`hH_VQc zRq9|pS^Znqmka}R=H?S*Y-mYaB8nWXxdf5)`bqoYvmkGm#M^i^ra_#~eA=3kV}w50 zSoZ8cH+qe|5N}Dc);kP>y=dhKh?qHR?FZPS(YL3ES9vNX%@!u)ONt%WBF2dqi|hz|9|`jBF$ngO?;>`T3gX~` zB>Fz)!rkvt4U4ugcK%99TNpckrQ(OYbk^cje%=a1zQb1>{e1SiPMR%D(CQr!8*dJ> zvtT~4#I(CMDeeKZej-5H$k054PhVG!(vjMKReQBg4RO4ZLJvmf5!l_azLW?_O>S%3&@n#@^W65scxL9iFb zxX$Vn(RQ%b*)z>vhqk0}_h6^3h#k2H&^nm_jP9NF8fafY)T^=FZd4Pq276|RBKFO~ zM3ak|RMCoK^spW(yNoQ56tdhk)Lo`m9Adyo}p>^M1I^7A8pN1W_k)x4w_HABC%pH3;?!#JY@S z7;P7BIT3_!Mz2nceNsnWSZK3_310n;vD%qE`fsfLusZ}91bcBs1lIf1*r)5DEm_fX zw#^nMpc^@>6J)&{)*9UO>bL06&)4W>5bQ;3SU{|<>(!%i9j!aevf0AKmDA@{;0U)q zlgrr&q3Ld&ANT6-Ei(;*y=Wx|VqDp%wdXF@w};*KaQz3zTiI8udn1SH|91W=(0`XM zh&(Y}U>6Ttm`EhgBDSM{J`-R0F4uLOBB<{50P_hEw97h$x0d%sSP z-4Ls)xdy>r$eg~dHS+OUT*_Zh+3ogzI9t?Es*yi9>w;xAkKTOTulm#4>Y~U?^8ECZ zp@uVo498iyEc1=n1?t2&U9J<(|F{}r5bQ;7KJHcbGmCUiR>wwZ`)ZuQJvk*o#*!`1q7hHCVgaBkSv*S~72^RTBk(*T(Q_7$2V}S*Pen z$V+m5ENiTjVS-oLU_XGHll9W{nEj|x#UR)#!NSK%S|3k`Rk&As-_6w%aUCzKwNz|j zq5@{@q%HY)T`FIet;0Dn7(4%#?ia-tCf?MDbn2#F6%s}9hk6TjG*+?Rz1&{0g$Z7f zgf?;DJiQ9v`Qr+G4T8M}SNL7+%^s|i_n3wl74px}D=_1=byrWt7ABVeG|u@3moNVX z#PKSVw0#HjSJ7^RV6S?w!kq6M{{=BGN2q>_5#*`a!HO+Rq*yo5iLoS7h$2Zx>HZkw z98WObAlNJX@ISMl#JI~zs8ks$~axI zg$Z7n?c=jNZ%^G3&!c>tc?Q8=n5|W@^C%LddI$Xy_iEm}d5SGe@XB>uxo)o;VC6t| zf0JM@b1mm*R};M)#NGUh6kC|!we{HLe^Q`s`zgqq<@!8>U@uG##&A$ zr20X|QK)$UQN6_zy9!#kUoKZR2=?N&s>qfeH}*({+kzo|EX;*Dzg@;Ol*2`1Hd4jT za>{ia_O(Y`#;idxU&R(CC_4ku{dFCC6LOy{3!4}Odr8g{I}Z!Ob+v=t5xLLgX`zZO zOz;|U?2FU#o_`$loM-3nQdPV@PSv0PnC*Dud{#;SioQ{ozFycRJ!h_hJMiyy<2{SY zh28P*Y_XMT`A%f(+1Ayn&P$lO9ZZGW1o^G+U4BcoponhM_meT?RVP z_gQ(T&-+TqN?&Oi(7WMR{d0Vr6@W~ph|6OT>_r-aJdZx@tv$Go9mAqok8oBHfBn0X z^GNQ4yamLaUDd60_*Gkei82WGGT)vFN7GpQuoCc9?Y+i(#YDn$1?+$S2-b~!?<2-9 z7k0R!(8A>@8*LD#*Y|e}wE!v8s{p+1AFcL^wRoDjjg~%E`daj?h;bo#Ni_gjMw2sR z6kC{}d1?^uWX;qbTzSrf^9_Q%q*s==1bs1xsj+k6JF2cwY+-_Hd$HapS1^{oF z990e9U~S*t2Ekrty>r&{3su%z7~QRDt=Pf@uh_)C&V3_P_G3Zbw)oXjnW zvWz`B-mJE|KXH4X&#rDs?;Bh1$}`Z$+BodFT*yZqJC9Xie@!uJ!+B+uxtc0P@J;I~ zH2TMxdl>|K(X2XtRf#dlRY~;cSsH9GewFmyv6YO*FGNj4WS}aA{(SpSFN`%_Oh`3~ z%+{h`M~noYd#m%^QCGAtrQ+YtUc4d=t?2kLb=n`Q%!b0oS~Vu5UPfANRK_4iz7q@8 zhnGR#3o+FUg1w|>QD*K$)j~hGbiRs%cXv>nCWts~yd|en}=c9l3VD2?zv|5R;w#?0b zF19f7q2(og^Jb7PeCH;J)*qwP8hju5N~E!vU@y`WFuJ?bXpdTp>uA)wC~FWl6Vmg? z?hOGVX`5&@8(-ASIXw)5y+~;QQR>Hi&Tb2Z7Bx3k<1!&Vf9xy{i1?!;)ks`N@veOh zg1vZ;3uKm|n^m{?Zg2Ne!wua)dj8n4EdM3T$EVZuNYw~29(3$$s2NO1&o4bS`gjm6 zUwBk}JdYZk1{(x>(cJ|x;!Ly}hI_TINkc=GVM2QT*x3&di|$9McNpUwtW(G!*o&Sl zb|ZOTbg#;cC)j@D-yXIwv9b9j-3V_^ z2G2*rPZ0$UUvzNEbHwgBURi82{!dg!d&$j!kwHV`Eo&A^1 z7A9nUrHpZqLb5%{`jD}KxDm8aeZ)A*U9^Ki zuovYIAQF^Zu6kSw^45LTglj&e67AdHjVZT7hddvt3$JSdBFBP7$`{ofZ~pknAlQrQ zG(bE>p12Ts;uZge#+o}`8%OyZh_$hKVvDI$csCnkWgcaNASh2X2==1v3`Eku{>u}G z)e6;YVd60I#5>3n3ziQDv4870bqtl>xjPOq2=+4XZj)c8t31fzM$8#v+$$y|!iV*vouN-kg14?O%>n#ltHY>q{_~;jG`3T^?w>6M#AWLa(jD z$d($6uVk!YVM4Mb$(E4afG9UJqbiO0-HFA2H3;^i@eZyd$)u91E=FFxqQ)4jcbJeY zN%}-&Hz2y^YNqC*AN-thzCo~;xuP-DcY^h6U$=McKR7{>R-W;SHeSPq-Hl(&umVb9 z73=Lq#_BdEXcUfL)oXCD6;crE0D3Mr2=t7-%YiDuc$}gEkt0J!j7H&z^^LWE!28~x8$EyT6W6%ZXtr^ z06<(`Roj|`Z}7Bhk3q24#M=ezt|x-^>7@5TWU~XT;m80g?2XcFVS?rWKs1jX(WfsP zZ4jo{t$eZbOdx1BN@I_eZx$wK&I!bwxc|*Yt>0oB1bYQGYwJpn*{FCYj)J)0Ugyb( zHnH%L7|j+YFiT;@&VGPMa5%XwxzEyS9?^onS(u<%DiG%jR<(b|^LUZfYY^-uxm)aP z3!eG)_$}q1iLAScT?KEb?@;yAH?sZEijMGUtNHITAuEHV6%|zr zRoLCe*wv89)NeJ)AlS>iy9aKC*=wq~y{*>F)@)${bBk8&Od(?A%roBhNr;_Wnr|`) z_TqN|JJ95aXUoj?s$%tQnw2+Ja!BqbIh<5xqsp|wWII@9wiCRx*+TRC|FipE_lP_8 zZe)FF&%2yF@ax~AdHev$_9VBH3UlP`wLaNDW%4#=txHg|iQ zCL3Z9?1ec%M~M^N4d;JMDWEHqbbEKlnIPKSHwzQ8Ixn^c3%}}S%K*It^&j<;O*IJi z3eCJyoxy$?(>h{LR-gRwE9!~y+}^|)=4!SuA^D-?iOB0f^2SF^$(MroIy+QV3gJ3UGnn1j(R9D|ZzMC=4 za?KVdA{tgyXRi;_`L4;SZ^b_b=s@Ju*V`>N2=<~Kk3f*xr%B;s9Z!+Q2BHbnzJ5^q z-X|EZ*@7JItBR5vK zI+&2$Eq1mRG3LDPst2Lntx#;fL9mzk1ShIr^(Q>RT+n#s-;Y>37g3imV!LyjM)LEc?6a32i%d_i2c+8%niC@0>E)Z4m6m z@0gFz#rCgV9X`6fi!Qxz^^7=Z$$qHQ^IW!SU5K`1pVSSPqOEMtZaDvbB1a5nSh8=; zX_fte`lz&N4GR-Z4%xP=*Nh0;nhYb zMym$t41&EbPFv^1_>%P*h~1MPyX4B-{ay|k(RT|Io98WZV*I=EDu{nio^oQ8dg^Ns z?8Q$O%1`p7&fR^`IlsjgCT{<>(}@v0_z+@vU!}KX|J^3Jvl|3^@$-j1I6IfWJo8oe z3R}F-F7Lnl{KN*AJdaxAWR38^aU1>R${&tyZn1@l9BY=ixi2+^dGm6XH60T*wn8&tux{!WLVYsG72YN1jKsX=y<8E%PKwo=3{r%?yIQE_!Y_ zF?_1U2eD=7D<{U0K?NQePWyO4Y%lZFiIMi? zJC|Xhzgwo@StmxT&&NTOs*}@}=TR~B2-iMOGA;ML=3j-ac_ZFCf4A56de*wN37vnx zS-m%i1C?sp^0t30xZcGUCT4Yc>(D>GmiPN__YY2t8;@rg1bbEQ_R0BGf3BGYqDlWs zw!Bw&iXC&Yg^8{Q{&r&Y96Am}s%L3|!CuCb^|@EIi1VvNSNnJ;jq{{d4NdB?o+i}t-N`ys`giCbo%Xb_r8l^- z<&7U(nE3ktgR}d9*cn#XiP12@0RR7w5U(H3rE+3lb)5o{`cO0H%8MNR)1NK;cbg?n z;QYc7HM}5}g%xmOj2)WX_*?A7Zz%T5c-+v5(WiJ*aSCLGx z*Vq65Z*?@aR~~BBYk#@;O&t zt3WcFElkiC3?k@KQs?eYe0JEw1bb0C2EzBxvQCWb@1AHx z={e)IREC8K>QO^w$c1As(QK{*PD0~vpH?$wQe z1_r@il&OJe-YJ(8qg~hhHd~mWTnj|1Uy?X6wq9y#5bQ-6Cy24xmpgf4*)N4`wlG0C zBZzh9Dn!Y>s`pz9gJ3Veo9oL;e>Lz^LJKGQZ6hCTQ#f;`Z_}PK;zP>KO!k(O3j;`^s{Cofzjj^$`($CJ7zgRNR#TF(Wb&RLvnP>g{$%PT*umVnu+SO7R1bgXhX`C3({U?C9 zy|Aeh!%{mkdrjH4g%cw(AfG>5 zn26y%J|qCE%|E6`8;A=7`Wew5%v0a9vfIp9DiP5i1Cd8MgWMBug*m$M!=ZqHd~nB9YlP5M(xPlL>G>;7|_M))?Vnk>A%ZbrFRbQJe zOqjcoq;#ca$;=AHH=5Xyicx0 zqgQ;j883ZwVyH>)c_i%Ozk9j(5a)U5Z6y)oRAitN2Ekr5dPR)(esPq%yZwp< zd)UIniS5Ij7$=kU0dXdMH7CZM`z+I231ZXRa!!oLm1n#7 zZ?PABX&^RM{@aQ1W_~Y=Elkk20wTxpB2J7=BVu?4lK1-I76U}s)=N%|qWz~@)XEqH zee=kWXO_>3SBG(L_e4pICv~c_YN^?a$I%$wtv&6;NT2x&Ymf%PXIEinyRh;|jPxlg83cRr zI2z;HzIkl9j&(o0Wew6eEsJ*2!F7CTF~NzECYzr@uosVtF^6ooabmbuJz_OnGeNuf zAjZ!HcRDdnPA_f{?8T#Etlxbz&WZ8j&ugrP+e|#}kw(e$IFY=LTt|-^PKfSi-9;Y$nW;Nw1X7<-}-J z;U2HDFwQTfktN#pVe@V}F#zHSyVKijVS=7Hh_jhoPK@XV!5${qi{4!jf1G>j#HhQz zzReaU=p6$Qzf>tF#^?3xJWQ|`eS;vj-Mr<*xYIJ!W(yPa4JwQvkLGh?)LC-Q!vuR# zTY?xP_MUWN%uKY%W(yPa%_ByYWSN~9A+tVsm|!nz6A>dK%Hza%?cQ#)g$ZiA5MzD* z#7>O4p(zZ4y{K(RjDo2moEYnWJz}$k32K88qtp7QPTO9~&SntoMST4f2_XcquIg)<-Q>N8mDwg&hUD4Wt$21 zq7eXy!Z#CI663cC|JrO}f^v8em0I+4VuU`l41&FABm<&p??5NU?|-~tz1G-)oyH;{ zg2Tt^F>O$J@4H`4HF9=xl+#r|&z+^x_Zg^@7QfCX=ixiww0ndOLVc8{{63r8S|;d3 zJ`i-$pFyw}x2QNBIBAGZggv&Bgumg;!eT=9RF6H|3D?oKR2Q9S81~+I^wA*Li(6Fe zZ8$Pa*9gSvb+2=2wlHC?Dn8Y!v5tor*)wD|2=?L@6;E)(AnihoMkgw1wlHC?D$cU6 zk`v=x&XNYfUfiOh;xJzuC&q81T5Gm2!K>Jzc?~M$#Q3tYxOUe03JK>S#^2@2 zKx6=QKe{Bw$mbyj!Cu^ILos<#(~=mcv(49RVS+0hvF2{TT{=^aNrkV+wzeJ39*P1vnzRc=m5bR}Elh12f*ol$% zNj0N3oC%u0M2v@h{hSyzYYsOE_A<{Hc^a9tGP< zWo7`Ks}6N?hWo$Ywb{Z1&B@}Kr%JNS$x8~ZEn^VuW#%Qr>uvJL%7NSE((z2HVuDt0 zA;yBpKb&<-r4Cdy2=<~iWgt}Y5Y@S(+Z!|NvCX^gzo|7zd)5um?UR2nv?-iTesQ3R zI|wJ_Wj$-t%)iA1pGknMuX-zW4kyuUY5TiDuoo#C_*L5)k5xY+liAa7H!B#D$$UHO zfKM?%f4*^q^8^ds2{#D#BE1DMGF6`IyjLk^j%OvtI5)xExusZeh!f*}{Y(bIUZgZ( zo?&>c1x}3ldE?n^VS@K(!H#klM>#S6-h3~L3HG9Y$DGW`9~U|?)-4P3XA2Yb{~$)S z_%FuRS<$S%@xCvHnuWW2Y`zoYbAvn<-9?-KE?tw2UD6T;JJ-<$tKFGkFM8%6K2@LN z#8`G}K5Lu2;|-rf0pdf)S!zDo-Mx(?4T7Gz&F7Co$0@!^#b5_B`{E_zWKt&htWLBH zM}k!)WHN&~AGP>2QhF2loyM>FxNWeyh05Y%G3WTp;d44{^Ssmu-`1-A1e^z%+9cSE z+Iht2`ZPo(Z0h#@ppx>58phwHo=D^FCU4_Bj~FYNL9iFK^B}r633i^xi3cSWTbQ6e z3dH7zKRGcjcFAiH>_zQ7h=XT(I5CDMsIS<<1ocrMiasst#F$`N2Eks`&Vv}ZwZ0Rh zm|qXY7AB~V0&%@lb|=QsK0g}-dr>k#b4asWonqBUd%_ zeeCIFy5-SJcDKnx^x}l8L415W%X&HjXPKTIVi4>_`6GxCp83{}s@OaFKTlZh zFL`3-TniOjn4laU#Kx_`&S;{1#3+McFB-9c2+#7x8BGjqvVdo{G!rxy0g)lp<&27+ z91J!H!|VI_3dE69;m)XNZmYS9MqYeQ2cHW9qCl^W_Ii9D35#MU9{O7}@{+UNtk|>N zK%}pK!fy5~$h)%THpLbu`qVjT)#y4x_vp4CM3vNs>~NfSx3>Q%C9^lNC-3QGeQsHk z9`@I}SC8kBC5XNi584MXO6@nXKaXDxg2uQYPIup9Uq|la+pVcVuosQ!LDb&mqXUrp z+$`?4@71XXqZC`1pcw=Zck1VG zV$6@KZxHN7^C%!X`P6h`e7N$fVha;A69U58SI&vCqqoZ-*o)?aKs0~b(TUM^bW_C^ zCTKbu>gf+^b84{1sc6pqVKU+i#54ODns*`erVJV6Q$) z7Ax1;A$m~7ydYNeSfn3(3GyZ{T1v5n35+J4(_^GpzzM_;cjyJ^4X)w+;?o?E?>Jua z1(+v0G`l@ppTQS(x919*EljY|gws6g&U3E3Rp;IY!CrJag5~2A*fYeryQ}VJHO`x0 zf)z9DB4{sgVtAVE@bKSaFFxe~JN%u+4zqaM2Xsl`VG9$i{GpEi<9{)3)#~D6g1sm< z@~h2V|BEr9*$x+5n4oybsgot0?_9@;QFSaP*o*EuVwBGt>|966UQPH(8Hy|2HxLKf zVIL)2dD5H{41&FAZW%fh3PBG#x!M?$r>4&(cH{AWL17CWV1zcN*^g^3L-R;#)#Lv_Ar z=?y;59HDLO3Hbi`41-{=`Twj|r>2GKotF-PXjEdf&WF9i8YZ2t*uq4G4GUDe?rx3$ zf@mAqR(HgXq&>DyG_E7$$4#nBOqk9;=7w=i*mEF7bA37mGW|B=75{c7{5ot^88(d3 zN!C9=jDi(^)(Nv>FAHm|L9kcB{o9n4e5`KW?kR|2<7(>1`LT24sL_foOl{Ta*H!KN=FWd9$fOgn7 zYI1kQzn8D0(D_L9Vn(?BX?G1vxa$Sm2XHJCc!%gCWaED~o-TS${;pti{wlFboxkpX?7_MJ>;)6(cBa<#N z1ZUp=)yyE+EB958+LUOVZk{Fqh%sGK=>enN-U3JJDz-3@dS$fAJ%60ucrP)C480TU z*OQR}G^u6~?6vJcwA#M_rwOK&yZigixVr0Hw|8zgrP#v6A2HFY;*xPXaYiB1zWZWN zT8KSsw4Xt+*OI@ys`~kHx^seLAO@CsX%}0C^HT4YP;6o1K*SyuC--=LI%P@_)yv+o z^KEu}tCq}f5bRax=^o`NI$rm73(>0GNqdd$_P+QxvtkPqPhRbF-m6RR(||bkqt~v6 zlgz?zq)=>OqI1pzYWT|WdUfLTAcn2kVUIqJGsDIuGzj+M?*{wne^_YOz@BHvq8}Jv z6cb$+99ApiP0$76|9}{$CRDXk;vB^pTc;WXd-2zWN{bfh^??}ZoMR7Lu5Bp-nr9iW zOAXnhag_mbjvlT}-zuLbU~n(|`v}?P|H|&Hx^R@++qnB#i!GP^QwF5ZKVF}S-lO?1 zAx4}6y5%Ofw`JG6Mhqt2s$>D5u8h;+abgg|`m>1c{=3^7aQ%@%uvhM>$pSog#_2&7 zgzzj_>ACb7dlk>F??PJ#(_51LkI!pihiB0^*nH6YUXbOWp;q zvAE6Pwxsibzny3Pa;bcSFP|i~w|s!EHXy6T7A8CkzBujG)VT7@-?p7&r$&rzW0n~N zdxf5O@5I1=@vEjBN^M_6j1LJ@TWn$Ca)PAJHQ~RAk+%L)I|wln9hzkj?1kU&JWc#+ z#Hd|6o4pw^j{NIuv4sizekTUvf@qiLcRM9w)ZH@4AlM7-trG+H62zXKxt!}bVt;nA zg$aI6&~ch>AvEE4n+OHj_kG+q^m7h6UK`&W^wa$G$TWn$CL53s& z4;GKpQP@`#PcYchedj@g%okTN!CooSCkZHrR&?M&AwCTa(1qr>z0V@!DYh`-ADB2` z@z`;?aaAF1Ew7?ePIG(bKTl*3?3L+W!hmdn<8aa41&Fyw22q+$H{O#_F5E(5`~-VV}n8D$gJ2aPtAA% zCy$5gyeMNciG}mq>vx!^{xCMDVha-oYx@KQb`94Bl1C!OLccD$OlM@4JM$O>d+Bvw zRN6u&y^}<)%K%_c8N)IfC7H(rzgJ7@i zzE4$;gk$xi--TG(Z?rC6!0j#AzNTUe6TYJ!s!7pf^xG9%LA)IhrYq)gd%atKQfy(O zcGv^;dhHnfvWXDK?~T>1vbepqrv7XY?DcWr9d)kI7@cqSW)Q2(kJDGM?_lFojTBp$ z@OgblRW6IuYIg}yJK+SKD7o8PZD@0YV6Qn(Z>qdEu`X!JCW&!(g3go}YQ~k8%COMi z{ipK{HA9E#ik z)B0;_&zvy5d9Dy6o=(!^F~f3WZF_@Yuj<{esW#KYbf0h`N)Df_kADpE_HEx$v4x3j z=P#+sRl;U4jz3h!nxpkH^*dq&&X}&f*qyRg$9@LE zUfU`hSE=%i)}2qU1<`5l41Eq~FNfqGtk}ZDqI`$d!$YC^=Ot@E#CbnMKfa1ndn*2B z5bX7#$YB+6I8<+3A;iWOGxZ+qbzg1vFvS)o;yyf}lFSU%3I7!ppwEz*dK1RyOS%qM z?DfOr11dMXD!pH=O=8phnYtbJ*-qMRgklR5@7o?wjmP4o*i#Z?$cCAEI(DZlmUyH= zuvgt&`_;srI1h4=5Qk69)Y;Dkc~_MTQfy(O)ttR*aP?4~D2@`8K!p$R%~Hn?@6y}lOR;zD=EaNA3$Ia(^IESg1vrE zAEWLi4b^pP3SqCFtk>eisVTorRz(voRQ-N)>#T2g=%cLTgUlRh^Z$hYd44nohB=`FwyhZg=**ow?1-Dh)uUA>t8@z zZEh0mm2vk%wPdba-~S-Q<0q4Kdk~u&PF8GTBJbvfs^lEEj(8_T$@o+BPav%7Cc$3G zQZG`GYux%+x`iN4q?@AsL7cHBE4DDPpyVR8Y@=JZ$}U8D|0y~Hh${I_g1uhvU8G(g zcI#O+g?LgQr!9a8&N5lCg^4uV7O9K}-8xNGA?^*EqOZo_3Hq1>d)*v}S?33C-FAc! zyXQ~QUJ%D0Pf~1Q;uFp^O8eTagQf`4>(41V3`7C1NwC-EOH0&0>4Nq1J3_YI6BNENHST1vu2pV{9$tKns(2|_H*c^+Z#lL~P2Ux)4?S26Vs4VDx(i}_SusiR z-~D^{5|uVhuzqx9p*CYY{b{N$2V(k=Ns28@ob@bK5e0D~TRu6d>Cn)rIwOcKO-zEl z+}1MHvTU#ptt~|KwyF9RuA@|;Ns28@=;&oCFfdr}>nFsrM^p7h5c@t&Gzj*pw{*EW z(Wo`IgLVFD7G+B?T=Mz zFW#%`4<*L6@acLnh{rulg1z_+_38qkr*Wi;B@9x_Z9l`mdMU)Z-^1 z`X}#l9kgY;>h&c=cX_=WF&4#}r6(M~`BCq}6kC`W`gxZcRCknq^>_t{v&CoW9w&ml zEk=eYZjrgAzLqjtb-y-B58e_1qKyA6UH^|D@5g^b6kC`m>Z?`i{iF2$jzWyAGE4t^ zEXX@y&M1Rmuarq_b$0zIy)=suFRIPbo}<{4yhNyC3lj?}MXAN3M(GtZR)R=hah5KH za}>M3F$wlEuY5+?S^Dy!AaCgE(TXihBpbR*r3f6QNAH(=)e*f~$AdxM48MgL1bgva z#~yTdr|aW*=4)S#SKQ+8bFMmLt$On=SfjN-j8sKt=(K1V5`>ReY++*W)phDZu@L>b z(^3#~N6*l`Ks1PB66|%p<$5*3KScY63sLjb41F2I&m+evwlFdA&kbsN+Yo*9gAiBa z&D4SD4gAxa1bcOYhLCAQh|b?^8HnczO?I?$%PaC_gKD$*gl!^+c8^Kb2m3 z6kC|6v^1)AGR{gJ7>wSqs{t{8Vi$bK&duEOd$TGgeJ`qmMA|{Dy=mL_8Pb^!WQLc-ubj3o^~i_iSpB6-b%$5Caz3dZHw|# z#y=g1W&f17MESY#>r#VYua)b!*`oYx^~ngrFQS4a%8yT)#frUtjoE68@^kAzhG>(R z=<>5f`6={no?;6VMKfz#l%MN4Gb6^IKl)js{B-^}+aTC0diEY$l%F_7L@}9iyn-dl z&&s#c6af$MiE!9Qq z(ZhGP%o`uPRWv#%x|EiA*p7oMMt7WY&H49;p~XP7&Ggxp@-u26oa|JG5lg^7qI zFKkhM-Z;eLR=F)vei~nBV-W0B>8JO$C_j6y=0l7Q$Fo_Y{9NDJP_c!Hdxzp`QGOmT zDF`Cp^o*7$KXWHlHwgABvnZYx<)^Q2ArLdFq_9N!X;iwLVha<#vy*6fuYN0A6vU|` z2`o{5V&)Zq?)%-sM7Mn@v?xDQ)5)7Sw9;FbC_kH9$xtwMER+bCy8PU z6BT2!XiVx92~vKN0{=yA>^u|@fL7+gZ#i5FLi^7E-~!Dw8Q zqesZq7RZ`diSn~7qzGb^s+-CduZ~V zt96tZX?>DD%BDp5dH10#h`DjHyF~ffJn@RfZ3ed`8D{x8ZAq86@&tXSH1HSYM;G|n zVha;n9{%dISG#O!uUZ}H;xEci?@HGV!t@G`koW51iV`4HQQzI7{H$75*ODCqzFPj5 zkn3Bupel&@b^1h!^0TChoF(y{kpKVcg^v-pV!}TvoOKW2|N7V3HO{qjH~%B z8U%asTZuX36=OZ3{LE>#++qt8<}*(iaMvTs&)W&f41&G- zjecQ?@-sPu#MoIlpDoJI%X6I+TbS^x{?roXXMaO!+mBo-V2kpzVNg$lV6Q6rt|iJ( zXwe@*Oh{0~7Ud^%tNw~DOuVao+Y;r+o|_AVCtV3!l%Lz_gA9VbGS0qWiSkqDmGp!6 zelBH;^0RR2D8*jo8(y$P`8jnXd$dWc^($+O@-v`NxMB+vPnsXKMEUuWCo5vy`K_ES z%1`nd6AXgAviCh~iSpCZBbm(9iWTfY{2U!RSFweO`Q5f!qWrAhk^#i|mlbSLej0pPU=Zxp zD*t**l%JA6iSC@DX$4!9pMndPD7G*$Ct$TD%1@>IlJ91lSKb!o=eLAdbx(hby<*Zw zSfczS-Y7Zswjt$gQGU(^tyFAbqE-CGmMA|@Qp=i&?hDG=qWnZATBX>+M3D>&Em3|x zE|g4v!KG5RC_g#RuQdqv%6)r^CCbmm%d)1ZPxg|wC_kkhu2XDbqR!K)mMA}$(#YD6 zZUu|kqWt`Daic-7SMAf`mMA~hRB{kMHY;L_@^h*7X2ljJ9vlp_MEN-tE^Anx&nsw) z^3$yKR)b)#c=d7m5Jr8?_lm0j_@@H4C_ftlw<)$Tk)!b_OO&5WULi8|%WsSFGyAAX zu-Af^5KEMw2g`(5v^}pa%1`bi+Z9`wxL0wICCbmApJj#6&H1@(QGR?b?=%SZI+vo8 zCCbl-XNf>0O_j|SpG1QaMVo{=n86n1=iqpcVha;RSJkvc`3Za^ z>oQ*VOk<1kGxnox5bU*nQDsY%pW*>R_-svLi}LflvsbZ&iGnRlS)%-m>mZ|T^;be$ zl%GdkV+?}526riCiSpC9ix3xj$F)WIIUTe|v4x3_jSE_${KRP^qwVvDeQZ&F!mjU8 z>{YvGK}(dM?C>&)$Adn3MEUul!Cu7{CK{BT8z_BzsbtDh)8CwmL=G;(gFC_nx&M-*F_ zSiNkopC~_bCkT^C{cb+UN;H$YSp%szbHSew+eCYOU5WsewyAtq6`cD-7?E6`-}49_f&{& zxdNj^`APoHB-m@v!7zVOen!5%2_j?N{2oz$k`+Cw-Y%}}66NQP`b)Q4UDGAXPtTcu z>0+%*xkUMyU;jRcbhTSViSqL%&QZmGcVSG3zbHQ|uiVsTjL*^TC{ccrq&lkD!bEt9 z<^H1lBtLWuG3u3?93{$+PiB)~ugPt;`it_@(E1a^0|I6K$97^%v!5 z@HQbvoZ1p4%Fl$tCc$3AUfu8)#<k;KA9tgHD5mfv~mnc6Ox(LzoSZXImb$^p!FY_&VpE{FA zl%IX&k1Dn>5zwuaOO&4x4dlJ*mot|~l%HayOoF}m4fXMvHDa+xl%Jb3535!!x4K06 zNiz7kF2886OO&5Q4PWZ!5rBCryIA_^#trt2w1TqWq-J zc~o(W!_Rs2%eF32e*7-W>d&*It9V5Dxt!prVha;zqC;Gw{0x2e5X3(fn|Va}DUDVA zOt4q8{b4Rqe$ID%1Y+cZ9v)GCI_M*cEll)%GtDK+PvygpL7Zwc#3Ra2z+97HuQn+c zx4(e)>IMES{E#w6H_zXBhh2Ct`j zMEU8F1ib-$A51LkvehNZ&$*$`5o3_=JdY?pwGNqI6npWvf-^u->m$k!YJZf}`iSy_ z+8?LZN0c8_!#K4*qWqx32Qj49N0cAb{wS#e`f8Etps$3~`iSy_8XXW)>m$k!YJUuZ zy`?O56qWqv<2ZYr6i1LHlAH`l$>m$k!DtVmhpznm#`iSy_+8@P#iwUXq z5#Y`9Xyb2&wfExL}XqkbORrgZsBma&H9}rUOBgzkIe_U)~ z0_(ROTGsDljWB9`MEODOkHrLgNv)5>_;2mGQ|kle2em(ne=lE$)cT0>g9;zSkXj#6 zeo*_P*usR=`iSy_8XXW)>m$k!YJUuZy`gBl$W zQtKni4{Co5g1w~HN0c8__<)dFA5nf#`=i*xgw*m$k!YJV&y*h^}CMEOC54+yFC5#m$k!YJV)YFoCK9=e?3D7(BrnDU>Kb zsQr=Zfo~Qjq}E52AJpi8kXj#6eo*^k5bVX@4eE+e>m$k!YJZF`iV3Op5#=M9WpmS0vXawLYT!pc(>m08;BC$`5LP z6kDX$N0c8_@BIT zYJEicLG6!A+6rlLq*ahsNB&=~T55en`9XyT2&wfE9U%pwGkXj#!_g}4y)cT0>gW4a1U@xilkr@Bg{79{jC?=@=kqVw~7ABIUi?=2_(-jfC_kwEvDm_d z`OKx(N0cAb{ul&%@jH#20kuA&{Gj$n@f*i)qSX3`@`HLET)EWxi1LHlAH^0Xq}E52 zAJpi8kXj#6eo*^k5bPzjKBD}f!Uu%Z`iSy_+8@OhCZyI!lpoaSfRI`rQGQVSV-V~m zwLYT!puz`))cT0>gW4a(7ABwu72A5nf#`(qI7CAB`H{GeV(2-NzB@`KtR z#a>eDBgzjdd7@21YJEicLG6!X3lmc7BgzkIbPz*oeMI>|?Ty`F*N2rK7(O8A z`mpi?_s3{N3A#S4{J_xxLDz?sAGkjOp;>f&SowkB1A?v(D?f05j7F58>%+y0YTS?l^?i20ijuReOUQ{;RAxM z4=X=#e~dnnl-#l^+;BAn5wA@&otBXhaFRKCJw}*8xG- zhm{|=KLMdxbbVO)fv*FCt`93eaDR+u(e+{F2PTiRgN_k&eOUQ{`(yNHDM8nVl^-}d zI0juGR(|0A1cYYM^%+MJ zl^-}dI0juGR(|0A1cYYM^MlI;2gT_09{;OKy$>%+%+to*?60YTS? zl^?i2Mk7kl^%+!^#ibpMcOTx<0J@!0-V<*N2rKxIacC zO3?LTF_KbA3?xfujS0t`Cm^_a`7U zi$>V7PYGQgR(|0A7>y`F*N2rKSUorfT_09{;Qj=JX6Yvs{s&wiR(|0A7`i^J{J?r} zt`93euoIl?!^#g_6C8uC4=X=#e+(_4Y=m}DmZ0my$`3pj5OjT5`GNam^o*=$YPvqG z{J`)5LDz?sAGkk8BTCTqVdV#o4hXtFto*?J2?))i>%+No=;f$f#HK=(Dh;E2kwv2h!S*tSowjY1A?v(D?f050z$Ls`nbwZCz{@L zeOUQ{`(res1YI9ie&FbUpzFiR58R)C&@8$>to*?60YTS?l^?i2Mk7kl^%+H4tp1NSGf&SowkB1A?v(D?f055{)Q9*N2rK_&Ok* z>x0S<+@FBZEV@3dX3_OwfheD?c!NK+yGJ@UA69qDA-+&MXPeOUQ{ z`;$>Zv)FUaW3baaCx@;NogcVAiT=L&I_Uba@&m&M1YI9ie&GIKF2J#f5_El7`GKPY zg02rMKX88nLbK@lu<`@L2LxRoR(|0ABpOkIu8(tms`0&|>%+MwFoI!^#gF9T0SVSowkb6A+q3*N2rK7(O8A`rL!c58R(bBTCTqVdV#o z4hXtFto*?J2?))i>%+H#^5*VciF=4=X=#e}ZEuLDz?s zAD9sdDp+uRSowkb6A+q3*N2rKm>3{VhwH=258R)|ayCfh)jHRQl^+-$cpY?oSowkb zlhJdA&=DOOz66$aObl^?i20ijuReRvF9IjdoX z1+EV(CUAcmYD5XTK0L;M1YI9ie&GHzRzkDnx5ax!*N2rKxIc|GqJ$g|1YI9ie&GJ( zDxq2O9)h6j!`D%B>Z-;XQ9|A~5OjT5`GNbBtAu9B_Xe+?t`93eaDQ?&q6Gb}V}EnH zKCJw}{Rs%o($6&9SGYc`{J{N*^b@C_M7ln#{J`+R>!9ny$`9P1NFz$n^%+%+ZnwAF>Vcr^!^#ibpGF!{g02rMKX7zF z(Dh;E2kuWmXck=`R(@dkfS~Kc$`9P1MjBCqt`93eaCAV>^to*?60YTS?l^?i2jWwbK zT_09{;OKy$>%+AGkk_HKGJvA69f&SowkB1A?v(D?f058f!!ex<0J@z|jFg*N0UZxIei{Xck=`R(@dkfS~Kc$`9P1 zT#YE%(Kf{Rs%o3O^-ueOUQ{`;)5?CFuIF@&l^}$Dr%O$`9P1fY2=c zgrffnt`93eaDQ^?`mpi?w;@Bnialsx<0J@!2QY9h!S*tSowj~ zgJaP3VdV$zPe5pvzUw(TbbVO)f%}uIXB_=I)AeEH2fhxDLDz?sAGklc8c~9-4=X=# zbU@JcVdV$zPe5oET_09{VEBNb>%+fi}pYsEPu8*Jd<1CKK z0YTS?&JWz5fY2fheD?c!NK+yH^bAFr!l#M7s*T>KK0YTS?l^?i20ijuReOUQ{ zO9O(gkDv3CU|xyq@`l5ZlCJv{T_3lSy5r=OoAZ;)$`9P1L?cQ_|27D^K7P(mKxme9 zn1i6}!^#ibALk}ze_wqabbb7s9}skX{G1KK0YTS?l^?i2&H~Ctl%VUw$`2eJ z5OjT5`GNZr5Sm5T$ItlzLD%OVRDR(8I14BnQG%|IpYsEPu8*Jd6A+q3*T>KK0YTTt z&-rl{P&T3jT_09{VBCP9>*MGA1cYYM_3?9lK+yGJKK367xz zT_09{U`F5=bbb7spMcOTx;}o+4+y$Gto*?J$%unv#BefneOLv6;Q@lKkDv3C=s82r zC1S+j-KFc}=lmoZQ9_&+5OjU~oS%TuEHQiVThaAl#RTq8q7fy;&A~C~`mpi?_a`7U zOAI9(gRT!NKX88%jVK|G5eT|Ie$G!oXqI?WAn5w=b-?|}XhaG9JGnVOuJQx-Cs9JP z^i%2P{J6>w+@C}vN`!xNx;}o+Pe5pvex}`=A6NN-`;+J=PCtosef*psymGoeto*?J zNi?DaT^~Q^2LxRoR(|0AIBzKXvowpYkDv1cg07FB^W!X_Y(xpVK7P&*2)aJ3{J{MQ z2+gAF!^#f~9}skXSowkb<1CKK;cOlu==!ko1NX;yL)o9D1YI9L=Lg52>%+K234&1NX;S zK-q{AbbVO)fujS0u8*Jd6A+q3*T>KK0YTTt&-rl{P&T3jT_09{;OKy$>*MGA1cYYM z_3?9lK+yGJKK0YTS?&JWz5fY2K7P)Rvw*S@ zCFuJ2IX@ui`mpi?_a`7Ui>{BK^8RIR(@dea5j$+bbb7sALk8af0hz-ef*ps9D}ZppYszCnnl;g z&-npC*N2rKxIfMU%0`r+>*MGAfS~K+=lleOX3_QWbACY3_3?9loCTDPC_&eUl^^&z zAn5w|IX})c${wArkDv3y**rqf^%+{BK^8KCJw}{Rs%oqU+=5{D7eA zKK;nWRR`9UW>=d`%W58Mq9bbVO)f&1f3qwLYyf$!)1aGH-CgRYOC^W#jT z?9r8=>%+KK0YTTt&-rl{P&T3jT^~Q^2LxRoKj$YPG>fi} zpYsEPt`93eaDSWyl#M7s*T>KK0YTTt&-n=m&7$kW$`1@55OjU~oF8WaWg|+^_3?9l zK+yGJRR-=)Kxh_SA3x^@1YI9L=f_z<*@zO(_4#kk4+y$GJOQHd_d6k@pFEh1(b~_!Tw`9Kj@voE2rz@=lle( zgRYOC^Ao%#H|Hmz^8@$CnN8VOs{~yiKj#O(6KK zao$k&XDLC~$Itn}G3ffR@&orLAT*1v59>QHd_d6k@pFEh1(b~_LD$F6`2j)Khm{|= zKLMdxbbVM!flC8|u8*JdlhF0yS~whrluX)4(e>f~hpz*It`93eaDNhwC?PW&K+yH^ zbAAFsvt+6S2)aJ3{J{NjZc_I5)z?AShxHv8J|O7&_&Gn$0?I~|pzGu3{D7eAQHd_d6kVdV$z zkF$WX5hdvQu<`>(2LxRoR(|0A1cYYM^tna|^0YTTt&-rl{P&T3jT_09{VBCP9>*MGA1cYYM^g1pz_V$Itn377#zx@D5T+(Dm_ien8Om@pFCxLbLRHIwYA3x^@$Dr%O$`9P1;5(>U`t5Rae%x+vaDSZZ!^#ibpA=rLtI_f`(e+{F2Q~zb zLD$F6`EeFdHbU3O&-qEw8p{48H|NLg_6GMSIEE5*eOUQ{8G&Qa_3?9l0z$Ls`uI6N zAn5wA@&orLgR?<)HW<%7Zr3unKPkFCto*?6072Ks&-qF8oT29unP~%pu8*JdlW0T< znPUTju8*Jd6A)q6s_Oj9!q)-eTpv_S;QpW|=~yHrc2%eI14jo0T_09{;Qj;zR{M`; z;kQkA4EQ=A==!ko1NVo&l|+saI9_&M5eT|Ie$G!oXcpc>_mkl3fS~Kc$`9NhzPm>w zO6cFo&H2gobAAFsv-DHx=KSQ+`GNa`NqfgWuS$e}bGkl$&JVwXM?c}36@J?3`uI6N z&MwP-;`Eb9*N4>_7(RIAbbVO)f&1eupln15x;}o+4+zZpiCFo8`x6kFMc0S*9T+|! z==%6MKh6TmMwFoItna|^0YTS?l^?i2&H~Ctl%VUwY7KlH z5OjU~oS%TuEV@3d*1*>RLD$F6`ElM*_Gi)c@pFDsAwk!Nl^?i2&Kt`9EG6jr_&Gl~ z23;Rke&GHDgl5t8VSNXN4+y$Gto*?JaTZWEq6A$ZR({~QHd_d6kVdV$zkF$WX5hdvQ_&Gly z==%6MKLMdxbbVOgf#Cy!u8*Jd<1CK7P(mKxh_SAJ%tZ_<*46fhe>pL)fK+yH^bAFr!l#M7s z*T>KK!5RQvA3x_OAT*1v59>QHd_d6k@pFEh1(b~_LD$F6`2j)K$Itl*2+gAF!*xb< znuDP0!^#ibALsh8@&oq=kz?x@bbb7sAN+s1K7P(mKxh`G`7CFB2Zj#_x;}o+kJX40 zbbb7s9}skX{G6YF&@8$>tna|^0YTTt&-rl{P&T3jT^~Q^2LxRoKj$YPG>fhe>pL)f zK+yGJ?prJMeWt(Dm_iew+oAjVM9a$Itlz zLD$F6`3VTkqU*!@4h$a%-a$>>ChteOUQ{`x6kFMc0S57uYu- z==%6MKhE{xx;pyj4P76u!=e+Pb6PT7xre&}g02rMKX8AXX_P%WT^~Q^htquI7<7I7 zoF8WzWsj}|T_09{;OO8Obbb7spMcOTx<0J$!0-V<*T>KKaTZWEq6A$ZKj#MoT^~Q^ zCm=M7t`F-wFnmDJ^col>%%o~SPzD- z4=X>g6AWD+)_35V;23m$Sowkb<1CS_&Gl~23;RN=O-XEEBt%V_3?9loL!hbnx)?r)acQ%jP(y2xh3(Su1R~byJNL{?Tz@WF?uoM2# zHwp~;(eYccuN|wLG5XvSjVOT*+EleNvkm&(L13nZ#VTivKKFpoEX>wJvH#B+gmvsDlzxs(r^mzJ{uuIx|&nL(IkdFIJ`d^|ECBokdoy!T(s+fe!2h>u@nUu$9m(bYr_?@V~Ch zJHc9C%r0+@D1m-)!@nT^>pIEZ>tH9j5}L)|pYJq(2iL8hV9hdKJa|^35heKh^B6p? z>xfUVE*fJRMnGs*_}N9*eS)>u7!x-VjVQrS2amz`54#9Gvil zXXv2W$-%AZxa0i2iAI#*r<}*&rxWY#-Df0N9gNW*9uS&E`{Db43TQ)sz^s%6-b8FV zmUmu6HWCo46LFw=bsS^5=dVoEh{xkGVOi72OI9EE{}EFj2>%#uCG_Ni?Da zrt73$uUBAT+J%85 zLm+4%p&k`i>{&7(Gz)W#QdOqTGO(UN&~ie}D~9!CHKGJfs$!#O85mGJ#y1@->S{5} zs({ce%wtNmxMP-qy#<1{7HW4f>@BMiB`~!qRj2VR1Ct8`ra@WM2V)pw0iju#E0wyt z#w-I14Fo1mS=1oolD}598c_n%r%cgZ`36QB2xqq4mX2Y%1%zhN(98Qi-@w=dL8lKD z-WZObbN8|lCFl+Q`a-^eM+gEl!z`-EF+4(N6lNnzV1Af+e?Y#0QwU<};NG@K%XB=a zY=eN%EKD^spPZX-U^;>rvG7T|zbURCZ5r9BpZ;vN?3ro4Tep}~%}n2#`LrfY_*=c( zYN)MxYC2w0(9XG{TW_C1tCZ8(%&Yk`4eU>YnQ>-Y+Zpsoag28l46>`wOUHAEU1v3- zgdRI5=i+|{+p%Y-a?wl!^AyL})3C3-Bu>XA4mY+MQ6hYIF@?{fFC&JT8@vuo7Bt;! z&oG!Q$jNyo`yRUagBBerG3E~j@2(Owjc>bk8l7bPR&K2wDXS4BFsH@b*)89| z>HvWWE*5M0ankj1s}Ut=ip(CFZ(w+UC^6v@i@HI)Y5&6kp;?$WV`hGrZ(yf@ppAms zM0|IJo>n7DU@DDSayZ|>RKeBYEEq4Sf5b3g0z$JeH^(%+a~3Td5VUGgV~JteSk1yj z9nA-e7G@=xg}AE0tOD`l z@}d@XwHRiV)rb<9sAO&h0m}*mZ7tO9V%S>&p;?&uWHv_y1|Ap)8euc1r(+mmRwGJ; z*K=BDs6obQXM>@*w$)6x>u&tn*rRwGL2{R4J^dbznpK4x;S83yhT2+aAhsQkome*!|YFptNa&}N2#qXVMe6NSX+wGUF>>}vk@h*Yrgqz z*A#;uTM+l5zYnSWP?6c z5Dm*?FJ%zue+>xDVo&XX_a_^4(t>F7)KH5RmKZ&@RwGJaZ+&yko0ARtZAlzA%wiQM zp7cyeXcl{eyN{S`&?^iAa{(+?iemH%yRPAEL#+f$ zS?o)Gy~kvl5g;%t#bWh5hCkstma`Eh*zbP)wUg;jfM8!cRypJCL&jRo!b}Tu8M4sl z&RG{ioH1*-#Y$?7UV7I%pZ!@%V1|Zyr2b^~)#Dgl(Vvgi+8F)%0iju#@?q}0aI%3D z0OH_Z!!1^XV>kg;BT8Tvh*^H-WCK3{1U&;D1KvSEXck?DjU^`=xD6mM$HZb~JBHif zEQf4F3CuJx#fwcg@Eky3R*J>yc?^FdAT$e8S4@lV@(dge5PRWdV1+*Zu>KgU5hXC2 z#VpyJXW(mqz|0qmDnJYmBp@^k(__rWck&Ee6A+jyV^L|qhVY}UMwFnxQpx5Scqbq* zyT+oL5yNK*2+hJ29CPpdJUTNVFdxUFViLodaV|{uXJI~$d3J6dr&e$Zju8LA!$DOh zo^;}9&e}N|Q3A7h%s(UZ3_KtlgLV*VMKNrlfY2<=7&7ICnR{K3$v2UPmkppm{lM!MaiPB7Q?Kv8c_lhmCV}i zc?Omh2-;ex-NmrC0z$KBgl)Pv&%h7^K_d+H!5D^^bH%a|B`_Jvl)f#`z!n36iBlFe z$QTw{Kxh`twzojQbOV8@Ru*;67^a(Z-m(!TFyYG7?U-j^y@9~wEQ?xd44W<>Gz&Ah z%(4!72F4x;Oy{zw*TyjRtVWc;q%PB;ZJvR>2O`yDltoQA{%BQ5Xcm3Kms;l;%n}1Z z(-3v%80Mif4YLs?!Y3BYe6gqk#PC3zRg=A1V&;o^dh-+m4}`N|Tl6G5W^j{8c_lh=S;G3s)3&h0<-8Wx)Wmf zsa7LOU@o2ce%n+7R~1C{o6;5?5OJ4%;{!soFgefU{4>?Svju^fdKO(4F+5wV5hZwy zedmm62F@*r+9jW|=;VkWeJLa~i$-z38q??tgE$F(FuFxz_`=RL&PJ5LoIo=P1l(Z| z3-0P;U&r(LbG<`CvoOifRJvuFf%gnz>-Z-vx?bXII*qp)Q38_;O_$Eo3>;_>n4@UX zSrfyp4hYS{L`L(>@@WSCHVFFK=-!FpZ(EHhfw_%l_~&@9mb?$*nmZo0=n#sp7&kT` zG%LJ&#mq^IE~FS9x^vjG_q9sUT0f)HbOR?H$G}`mi%zE)u6saeR(Ma%j%8MU(80Wd zUCLaEXOA{^u6O@tcQHGbSrI~?Dvt3|)!E5-tc7oUtVc#8O3<+2%JzTLRd$swWxv^) zj#qs9K|p90JH1JuFBZpO&mh-J&_kGDH|`YIOVFVgu@{l+CFmjKuHY%Im!Rt~!ddj+ zsg~;{=u=EIq6B*%xn6=^ND$cf+^v@!Y|<#vh!X6tbi) zTrWXSCkXa%a=ipSory-2z+Ubtu9u*{69oH2xn8p8@yh~2v)H}L^%C@^f?zKy*Gryn z)F9C;>_ea8dI@?{x!b%D*z4Y{m+ZZv9{03A8c~8hwOlVj_biU_b@_g7y(Bs9l7P@G z_U&?21bw_9*tg5|67=yV8c_oK_oujCf}UOwFQYe@>m}$F4hYR+|1sA~(2oq_r_Fb| z^^zsEswWyz0&@sbTrWXyG6?oKyY-S2s|AE+v5%VTCFrXLF&ll1FNKxkI@X@BC(%dACZG-pF;PH;K;Jy3%71M55J56Ac8_u(g5 z){4+k&Iv9@3C+^)rrS^7t+1Rm`SRfV!9H59u%NFt(r=pEPv5PupvN}&4l2Q(TCT95 z#}=;~`{}zC7WCK#gl1vi`xIAL&AMvc^wAMvc^w=gEQGz|STwy_vEePzV?^amQV;c~fg?;Z+Twy^kEC}qU z?^amQW1DD13HH=-g#|sfAh4glTVX+uZ9r%i_PtMWg$2E^AlOsO6&Cc^CK^$KJ+)k6 zL60p6?5FQmSkPk|5SqoFTCSs@dlm%t(|0Q@=&?;Sq6B+tc_l)}EC}q_>sDCC_nnbp z*A7=$(7(XFc-;yMIz@8X!NYYF^c>{69edph3%Yo?ukX=_671UH3JZE!K(LR2D=g@1 z2ng(9>Q-3L*TB6^j~*NI?$9g26_y)+8y);sN?^}ax59!x3LFD_vAPu&^k)QwX0hjk z>nP{}0l}URuCSm7B%=`}u=lH5VL?9#2$T1&TVeU&*2e-uv#>j@TVX*j3kd96>sDCM z%aYNE64=Amt+1f41qAlSbt^3Bmk9{XVh;}2QP7hE0{ic}6&Cd5WHh1#dkMM1g8m#3 zr&M0=R#<9Hsvi)V#g0R+qo4y31ok9%D=g?!q6GG;b}KCCU&Arj2glV9^u+~)X0g|fD=g@} z15pIsd0b&Z?_EYCN?^}zx59!xJP_>X<1q&2>ch_SkO-h0(+9X6&Ca<283p@_mL|s=!I;IIwyJ`xx!Ml-McF^q6GFpcPlLDiv)qa z)!hn9pATOP2+d*-Cs$a|(+L9mx4RXV=T6ICp%Eq6C(2b3^ml^59`SC4rFFeg0ijv! zcjXETdQ(AQA9}aKg5J~>nuUGn-3kkOQ@Pu`5Wk_{l`AZ#UfYp-+8>Q5!7f~`u%O=- z$6yyOS6I-M8xWesPG7FDbna3QM2Efax)qjB{;jw|BT8V$f49PdzF`pWZ-3XVu%Np* zAT)~|%UoeW2QvsvD{w0;>)-oqxki-0TVX**`ErdYfk_f> zg$3Q^Af~_iu3KS2*Lpx`7CYg&!h-&H5SW7DR#?y(zg#0qU?PTFVL_KXh!^L+>sDCM zeZNcz&0^m^*HJLDqoJGT;Z|7C;lE5HN^o}q)`T%Db)MT>-L0^o-;#UUAH7;)Z*{lA zf__Wxxh~hiwXNQED=g^g%xFXj?B(uOSkT{zGXwUBcPlLD8x07}VlOJ!QP7*pdxkda z+zJbNQ!^S-0(;WC6&CcVf?&TZS6I;h8W5Vro?5Q3pvM*j_S1JOEaFm%KC&d*OI65FM|6;XUVd?d54(ItC z{aKntpNK0g@QXkc_FL^%Sgw1tNTLxX=qz!C1+EbY%qwy$EO3|tLbK>aafJn*6bO1z zTwytG(TRyhl)!wX6jxZ_Oo143BylS&aIpeHv%y%BJeUYmXCFoLf zO@;8HCX zm9A5k=DHG^MH`-LXSh3lJ|~AZd_Q!U(vH`N5;X344BYpCpmERFK?7e2&5~o|lZc6) zu2c3FSpFJOLXHOlQ$t;+EO!!6LbK#O1cAwfY2=NjlzCW z?3DuI9qf(5e$jyibs~)@ff>oJUljYMfEe2KY1c3M#C7!oLbLA09xv<{#hx!9Ucw$P z>=(tJFOf!+z^rH2FN*zNKwyTn>lekoG6A7k+^dHDqS(6z1m;w`e$lgDxh&F%5|~+? zV!tT%u>mmw`{7_;oEZD#1cYXBUmtdbVxJ!n+zE*Nq7_;+`$e%65r{|XOmh9AUsP!n5SoQq=qdJ#Vt*tMuT-7l`bB^Lq+wLK zNBI={MSouUV#3{+*e{B`mN>IqeyfLPzUcZz8$4N?bLUg+b;NF2oavrozbN*MN-$|Y z#ePxjK80g^bo}$KUvzo(`jJMI&|_oYk6H6wzv%oc>ji{nVbXkx{i4`?3dgvs)eP4! zI->dIkw%mVUq|sKGhM%^`RlTP&@Ap^#ePxjSA}ETbJbMWFS=l4!$>1agzxUTWf!@A zQS9dxypFN&l}fQ+H2>MB6MYYH*LVC<*DreMiZgdz6=4a+7 z(@@7b>6Rt-lS-SS)a;4ogPULrR9qSTJ`Q{HZhqN3dTM+3?|+-HZ|R@sUNaT{=og>A ze??N|oF#VAQxnXMzi*Caw13Hx_-Mt)(N@f^;lIn7{t+Ck9k5$agPeJ0XWQY{HTJ-x zlg+6Eo;2rNyu-H2nP!S@9b_6lwb7P8Wtus%omJ%1+D|tJ_xFpt^}WUn#cHIzY?Ary z^mewz$@sc1g~~hQIsw zOJ~@LZQ8nj-`aE>j?rw~4EqE6$hx<$XJ?j~Wj6gV-ps6Xq1pJ}Omop&;`Wn2B1GU@RxwGK0T-ZGMrpN`UPZz=xxbJim@2-+6QM$mi-(1FwJ+DfNzhSMH zS@W9Jbli$<|Du|4>d%c^j#y(xZiWr?c-6uuH?A|h>Tk%eS@_7O*8Th9I<@gSR{S){ zT)Dkpd~J!IrcB-Cc6o&M zy=>vZrZdgBXEsH@rT?`BxYM8Y(o+1*EA%Ou%hyq*evuW|JlLp^uj87zk=dP_D&*^E zkl(_Xl9BuOdoSOOS6<@$JCZAVrQ?0m2U`AY9s|cpJ-N4xsex>v8YYpX4{8d0KFrx6Lya82EBwR*$QDD`!}xK3^+ zAT(=S+X?P3JHFFvIL4m-w?}W`b+mq>&}u}90kc{pKb}6tWa{zVU9i4IR1v>b%N{EN zLbJk8PxI~NqIFmU=y%PV!RJbe5xXx)KI=N!Y$`>&|K=@Aa#wtXZmI@_0TE^$`;1|q z?Jp)Z=9%G!H-21!Go1BjxD?KC)}P^0@0_{7{rmcKUHk=imwF?LP_eDbFH0#?tmRO!k{wYnvZNZW!%mn-eJC1(NX39;p%gRnME&p0(irjsd zyDqIwMwnIy2U&g}@n5`GSN-0{l*PAp-}pgRBT9@o@o7gt+P5!=Qr`?RukPy?KiP6% zKxo!G=(XN^WP+)A`4A9AZ~Z5F182AgUz?INtyH7%?v=Am*9L3N^1`x(y!xzJy41+I z9mG$I8=D2VMtwft;g@=vi|&I5xv-30CyZvnQ->3Y7r~|Ga-!+(&(d(dI`$FQxk54xDeUgs< zoKZf}h!RbYR4&Y`gbvoaSMqf%=w$AknvQ3k)GHt~OMly(oEmoxFgL?v+0(CkqQARl z>9rkq8SBTI^R7?FKb$)z(TEaDYnLu8T5G1+aKl;ntsXz^WphJ`bUfpMu>ql3;XOmw z`Af~O=(@)`MNYAOi{1BN*Sjxda5Zz^BHTk)m;aAd=g%q>nz{H6Zr<^5Mk7kReDhX& zPEqu7ez+6Fg-2GH`8X$@d`Y=P3C#-cUQchg+B}a>$zz@BBpOiyS2K6t#j6ljqq-ED zu{cw2dgi`>(5Pp-1YoQ9se^}}vXG@=BqW`(?}@w$a+9%GlAws;-i-|SubSs^4>z=CpJ;WJvW55HnXJX@n-W~j3i-X`wMvei;9T;|a`P09amhUo>D^sG z;A&RLs~WFDcpm&YV~XML@zou@146UpJp@sHQ=#dH_o_;_8}+FnQ36*p%c~l%LfFZ3 z&kFO`_x=*t=E%V{xbbP@pNpKe~=U|JgTp_P^yz1rT96zipRyD9PQT0?)=Yf5ecgRiJ&a-`Q zF73`f(SgN!J_d2+@}{O9&R2`C`8m>`s|2oQ?tI0o8=i5t<(uw1`^ERqY-1j({e#WF zYPz}nv|;wFIy)@yMIYKf$R3BY=t7)DN0*omVq6cL8FuxHCr^7Uc>d7mvpTp&eS&M$ zAD0aQv2f8)^B&IazjS@fXhaFQ!h!f@?|;|9t}O=!gl5SV6@*-C^(t(Ykn1jpj{bUH zWAt+Yp;?trn`j%9n_^!3cNvJfQB6~&R61_kW~zCxL^)fx%Q!Qv!$jNp<_qi%FN`)+I!$A&kZ45HC3O-xCAcH5kQJ~4?Xap>|#?CGaZHoKo+1!CeqH!ZzPRsha}%nsZGW6=G@=Ba*WGhFpWiX7u~;ut z7F{o!E6oZB%{qADME9-z{VLoO=M?;Tm+1+j)PlK2BT7tv5W9X|GR5pF^B#zi=k+j$ z(X-uQaDG5&7FG+~ssXRkSOfUx%jiHp?93jRLWgl2`Wy!Ws_8}Xj{xm_i5 z@to=Isd=}7=S=ILGYdc6(Z~He-J~&I$7efRM-|?{s<o^T*_y+&y)JM=mJrJinE@ zr(QL-S|RRW-2E=^LNH;qd8?@RTwFhXyMgyMMS=fbr6eo-V@cpIz!IE8+d1Q zG@=CVo-EfKcprhz%++0^PNUQDOO3k)gl4_j=mb0J*;%H-%5y<{`sRpe7kW|$4H{%L z3-=(F_aeO82#K|`Cqxr!rQ;_a$u}BNLZ0F9_qb+b|ETE&>3I291p%R1Sg}a_iUoeF zgZ7m0s%#&5OZ z)`8LYxN>%$Z%q&pLY@;roIC#7XeiDMSDDoTp;^aoz94xJPj_ug>;+LHNkx5d_POfK z6-FaU$P*-p`~CA^)dqzD5oYDg^Q#mfWG%zs#_woE30biKaedMM)-t|&EeQzCI=g$9 z+ybm+RQq5(h$rX1kU0Y@6Gz@&Wi+A$?k*z#>TN1hZFmof@_8vu51+)+|Q?ClPG{=I018GFkf5QBG)viarl_qeK=`L^zH zsq$U&P3dMYSzM2de&q1^=F~v^Ddv&PJy}GV$mB8JF;kTCe6j&*04RZ&-)xVuXLbLSK zlaq5or3v;3R=kdz)hGB|Dbc&(LUY-oJX88UzVZ#tM%o15+Pa15fY2=cjOFCCYkgvd zSLYAkKF|nP<&<9ww_N?@)tOi6UDr2s|E~N4?~rSbIo*!jh<#XYzBIyB*;Vg(mBv*$ z#T74JK`Z6eO-1o+V>;9Z(dNxM_9N`jbbN(Ikw%n|N&|@edX4RK%hK`TkLv`4X5q@8 z@@p9&T94^s>)>gk>NVFy8c~9)^nN7-#DGT@*ndt;$ITvlFR6E6y5Sx2tR01lO7~gKC-H&hWyX|`?nl-Y*AycV5`nuLU7=^?&pRBScfjF+j zC5c9q;F_y{O2si656Rd{_^pNv+MQ8Cvj&(Y?ze))IyWb0_L+tDd3--^c=xu9MwH;X zKF@al_4QrQYpJb?^~BSf-kqz2X34RWoSZ9OwRS0vvHP~&xf)S|EAu>G@ty)6hx(eq{p0M;{Kg zm*c*D`;q~Pd|rb}+^aVoac8)z_x=i^^t$Objr;arCJah6qP06#0{q$ui0hUwvwQJ3 zuXW|K0ijvpZ}rr(b?u*pSckJUg8HEThWlQuo9a||wi*6(ZT#Jn1C8vQrRn&c^I9Yt zQKI`3l~a87*;}hQh@z{i+Pks0;XQXX4G7JWa}0=jU;MO!=c{DcgcYbgy7Lulkyy)c z=P1@9zy0na_wS7(SrfjXc}>fwiDJW7CR~~KYZh*0-d7jhsyWXkSZ4syv|&Tbr-^bC zcO+a-&qlbGpCzzL;m##k*8uUx=*aSEV#BUa5{)Q<3TDbzFhP`iw1e&ObUJ?eiQ-%% zIr_6StKe`>>ax4?P5*PbGeyn)PuMRz!Ki9{8mpm4f7Y7s|1o@;n107-6B2)y9Alq5 z9lJWNYiKp1gj^qSjAf@jXMZ{^9nYK4EFd%st2@T8?tsWIGTGjV&(+pWovcQbz?I+K z0q`1+8vVlQ_A)$8EUI)r>%d1NO5lFPeb0Fxfgbwnr`Zgywe@%2ZZ)EWT%AD-`QKz) zfTxLysfPkWvpO|cXm-4oXUcXP1EN}uadr;Q?W31=w;EAGuFfEq;aY2Ptu0fS4hYSX zYb^-5Pt#WT#9JNAHBSG|lq_x5yL zchF<@%2s2|>{n)*O~Z<$c9)uH?szEQJk+&BiZvp?UXp@&KliI-8J;Fi{Uq0FMEWvP ztV!{i0Tm|@)!K|o`txa`_%De@l#mVx5M$3Rn(%32{za_Lx&~rZ4;oi5l4ek>sR$dmI+m+bA5_Nj?vs|$KFs=s02F$ikoS%-5TQVac zG)vFgaP{#$UlU;$+9K0~Ym^dimN+HFcfIqC=i~43aJi>!gD2AQs|SY%gl6e^J}2jc zDmUAWu?k#(wKMy=>I1{#7^kr24fgbMv-?H~*ypC6w^|k#T z!j8R{uSqnb#6NixOd1uUQWtLraq_PF?8Pv0ulsFkKxo$Ca~^TWc<=WfAcpUqVbA;t z6_XR2TRn4P)!Fz}XMJYCEAMpSJlhISMKSJ*^&F){uVHVQH4`SAK~MGpQEg|wU4S)! zlDk4ev-C`aHRN)0Y{jkEnPLcb=aRl2B^o`k#5~$#lG*<2%{WHm=V#e|I8)bsEe;6H z(#|2Qmo)k_*|8-ZPyT&ua2?d^u3k}bPF&bCseC9M7g_mFMk7juSLYjFTb*EHVLY($ z)xp(Svuad7+g-KqZNoiln!R+H>k(eDA<1Y&iS1n)xI2I!BVIqI{rXPQ3&(i4LES_N z&H7_PHFu1sj_(cP@y$)#F$!KEmC=Y2@>B$3_oW+?4LHWG=A{!QG%LK5d8S>H1d|uz z<*RySG@^t&h2a=I7rd6V`w1Oe8`lSfX6bzw_Gs+!QL+}#IPV{~z&+dW83)fgmd`eP z#=(<|m2NuAnUfon4*0as>GZnx*#*P{*L@J>t($1>yZ0>+t>2iRoO%G3>Chzsp;@|W zglC+G3zDJOXJXi|iT3YVC3q*!J96A-;}~%=Fxi6dN6vAD0ijvC&V*?NGp8q`@E!c5 z-fE)}C3r66IT7bD9OJ38hb9TGYKwc@fY7XP{c6DEnaQ1~6`l9hV)XDGTiH@V*R}BO zzCScM?F4+I{&+bcGz+!Pi1+QReWJ7Gu0hF!7WkWAJCRk;qY)*-HL^Y>W+!v8gTUu? zZZkReJQMLOTC{mDyJTJB{@pg|W>0!xSClC+)+~E|7+(29@w#L!&eRW&=w&pb1kb%Z z2jk2NViTT#x8qD*;@`r*$rm>NB8_JclkoW7nJ7=8`_g6LYl2dYM6C<12 zE`Rrn&)7cMXhaFrQ{5Gg^;O)r=eDy2xFh?z#`J*DEV(-avE}+d8Cv50N?Y$D`y0RX30Gxh`N2++G}tfEPc}KV9inqUjKL<#FY+&`RHof zaW|@#eG39Yv$W?Ha{(sgC(T=><1eos6RcD7K8N=^xT6WytTD-~)9B;^e4_>p=xcPP zSqVM?^GO)@K=@p}esK+qLq|tS-YEg0S-Jv^SrD@;C6#u9_~B5b5hbuL=k`{|^##XB zpYm{qSDcl7ngoPqm3n8K;kw_Zx|e~ts_Ll;=0V24obrC85hYfvea0PQ^{ZT=UmNFT zj{J%J+xO%Kgl65+ZK6BI%VQdVc;U{=lVvzY-Ky&%jVOU019uGe9N?+QB$>Z(jQvyU z2ZUzncOHhq&PS6o@Lts&^L3;VCG;B%cgZeG)-6uQx1L_dXhaEg>>1zVhu`Ys#_uP^ zum*5pl{g?Y3*F1oGr#S@!73Y&pd!#56e9@-aHytv#8Cx6-ZXz<=zgT-AmTx z+xB=?`}zFlxXV7;%^eV^g1faWRA}g)xpwxhC~`sLY^Q& zy!iGqYq=ua?Ad_OEOspW9xo7QR9R`i!ZT;*-P0nCDDn39f0%_>7rk}fuOL?KSZ&u} zUG$14`UQk$g{!rdTduJNYp>_LHZjtO68m?5<*pxVn$nMYZu3fe3RXWJv^@esvvh44 z`@_}5dOM!BPaHTQSVLB#UY*Tm+v$0x&EO3<#!tD+Y;U|*3-ZPXgl0)~0K}p(iQR^4 z)IGbFX+qXYNb4%-U2rRf>_5=IKWvUy``e|Dpx3$G$VekfphF?$yC(7dxbV`cw)5rbc+86F z0ijv?_s2TJ$xG~>AF;>plS?CwC_#gO&(San@H$dkt*wR6)u?960z$L&?~kX{^FL0W z!S&t+U0G&ou11uQr!WxmbQjdTG)tcPK*$qhu11uQ zr%4dLY{RR1#^ zH?LKYpW*MwE~qaS*NEJ{bLoJF?C5EAkt4l+di6HO?z6ir$Zl$6g8I zzJ1R`&;5?7%=NQ#H4CdB?ssRUIwS@kDsH;t?{V*vGLc4G0JUgW2(2Za6m}G>fY@zOIU6w7kcf0^EzX>M=Ibh!SB3_N>2`nY;1K zIsd|!0z$KjRD0c4kKvf~*o ze51;4jx?gg>+#L*c*`F67snW~ZlL+7T{@mLu$WOov$z)H{ZSlaICk64N4NUkQeBO9 zT5AWkx}7;WCHKrWALCQ<&i+oW1BiE!v_6&Kv%g;p$1x5Km}XAHI^5opT?0b1v>O|H zH2yiuOu_wCqb}`@MwH;Qzh4W-F;2arz+8b(;=5$qb?H}eYa z;l`FO>Q;iX5hc`|#U1k3oy}BKUzaqW?RuYljm~Q4vUUPvXT1AwFcm>;zv%g(<5vkj z2l8Bk=QsRT2bR_~eNkOH^u?%v&@Am}#`WXV^UQiwmp0COHt1Ydg3p0GC*t`HPuuAS zikPN2ix&Un&VbM??X$)=>d=Jf$G)(HK7PzRyRTKk@8F4R9<`m;Z%yWR8gFJ`hk;ji zqxP!?if*W z2ad69mm8i&1{o++mE}{Q)wD*{I+`RL~y|sFtAXZj-DQbdm?d^|apKj^dRf11k{MO=0 z3B;{UXGOE{jp{oWeXl}jmUiZ%-{-{_qZ0Vm&KPZtMwH;w5Wlr}?!htg57}r3o{Bnl zToMqP#it>jukdsPqF;$}5i3|X_B<)*3)en$-ofxrhIb)&x_e=2E-P47Dh!A;qD0uO z{>e=zMDOBm>7gq=2nfw;aLpa=7{9cufnywOHZb=C+%5g@v1XA*lvvwvqU9ag%C=l1 zn;ut-?!YlVS^r)@Xx8sPPIAY%{c-l5fB*Aq?ii_@#*s#p5R( zWcqnCSijn}ILgI3oW)MD^4SdtRGJcB!2;3i_*v0#d_Q)*k_1GMb?kcsV))xHMi=5c zSoayYHWE<+m8Qg3ut1#Fd}36mBBpJ&pC1sKrOr6+mda0y>eNFY!2Qz$n_LO3S-bNt z>-PB8*6J7CiHdu%%)o%qEZ*n(&TJ67ai7ck-7_9}%4$RjtXVrFhW!A+Sya!+dbVQ? zDSO_<`7mu$abu6=pRBlhkZtSGEz<=b8LS>qO`3Bsapi5R_2W#pk0ycWcG4%&`B;;=Y;$DQ?#3#x z^GevoCD%c`@`AsMnKyAg?|19HRwGKFLgUWh>_y1Q>C?8lxeseH4L=$Z5Sk^|a}Z@V zH8BUUCiC*IGp$CHph?Fo13MPbzkA0G=5*Wvtg8EbKxo#z1!;R?gDGZ9srNwK+Iwj9 zz~|^_oU$)b$6cLzIb-0J4{!T#F4tuK8q_n}BpOkIPs6-^ur~lznKvuB z^KSod4h4i}h2O!Qx0iM2-G`q$!D>VaJ~Q*Yi)URNgHOPG62=p8KxmeJ|1qzq?O=0j zvvhp%J7)$SJ@4@R%K!h{4`6T6yGdp<~r5f}MI&+epf>>vG?>Tb< z*21Sh)yrx`iSQV=9++fW;_0qz(VhXJS?C#b<|I1>F_-M*>82zc-qvT{Lc8KQF19+{=LVeZ`jv;FUAZ8vJjF}s__jx%92+iVs zF7J17-wWc(ZA(mqJN^7_^Ap;Ie(m1f;rlgqb>Bg3*|N&qiMx#NhRs#OKH@V$mf#&e z@APqJ4q|U-YnI_ors2G?0ijv4+5%$fx7O6boqomqxxtlG;6pB4_t;$8?rX9_wO>|1x zB^AL7Z93-)fQLPXB8ejsmTI-NT#9E~W!>pQRWxZZ=14mvA6a7H@lv`-Gi>s`^obH25JY#oJjuHSU93BX1cYYs zO5;~pKs0GEG@+YOwzsvqQ(Q(*}XiyF~X)u-ltv=^m7r z+EaB{l5;#J*x&q0@XB?6K;1D9?^UmnNpfX6u3vXzu$P_^(k+Jfs?}8mN!zQ@N49!g zKxh_sG~#uhHFcO_nK8)=c!I3mt-sZX66ghRT}Z6-qxa+ZDVY*j#o72s<3!I(dcKnW zG7y!zoR)0DO3~M!ZwU4sR07W>?!1eu5QxnemQBvWy3a>d4+n&1>2HXMw+C-a)-Q&e zQ9KHELsSB$sq4RDzXNsx>+w}aqD1?5HaNOrpI1Tr zHn(`hV|-nGTSkADW-X|A&>dr1w>cm#?Q>Do5XYE%QjtU>N^HM;mpjI?;*&tM7+KaG zV^Gm$86`Ap;CDp~U*GsUxSQ@nTZg+>p1%F;j zjVQ7E@i*Kt`uFB8%_|Rz6(TEbW2cGO+`L%Zz0Wp8=)$ZMGw6tnK zXqJ9@up(S}^nb@_e|_+|Qld=#Yuz!@&-{sZckM}YbL-=k?_Aw7AT&!qW9a>O?dc5P z-640Kn>=y;QwiV2!CQ;jGNW20e1EF9J)HDCyB1&9Z zvyP)XoWxK2rV%aOF^bQx8W5Uw@QGhCJoc^su&RIVn$8*i1^11v;FkngO9%&C9fL$LKJo9Eb-l-M@mzC^NA`q7fxtF4@E#-B=$8ef|fCx8@vnf5Dnp)Jrs?#QN5w z-7(tb@we*J>J@j4-Itvf5Spc*(43s9%inj$sJAu_KD$cPAKc9yqg0uLIL4t`uV;An znK!pZKxmeJj$ue&S2^M5DlXeMvnF$rg{0knb`C>*RN=&%>kfYE4ts{tU(`UM4?ASLhAT+DRy??uR_sjVcK(y=CB;jZG ztBc;tXhey7)_&`b(fx^`AWm6O)*YkI3rhn+vqtax&K)B?p8L>`I<3At#@MS4Wi+D1 z8@sl+V>CRG*V;Afio0W!+OjnuG)q6BIXMmMS8>Pq;MX#VMwIyI&}w&#!Ph4^Mu&c9 zx_9@iHKzxJX6fe`Hu<1h?zg(J`2SWM`Kp}zOU-+tR3`fIc+2ly?{ji8XKp^l{r}H% zKg6DZW#8`LeyiH+zg(daB|4NW?&!W(tpqV^&;{-o&puH)_*t5zpC0rx?7Pt&j^hkQSRh!XN$ z0nz{WzukHF@RV717=hV2=YwNEGh&2@=o|v+W|_PR+NxWI1sDaEC_4t@X>CDFkM@}0f4yTvx0EX zd!5rf(dU&C@<|OM_nqN_CWjb8yYx8*L;8~g=kb&C@=Vi2z7@H)AI@sY_uZTRs_f)@ zm&4J)Rc%W74tMIU=OtQELcTeH7T?pUC?Vef zL7dyYZrHmQ|EHlLv`fArgIK)RwPB5QMW-iPQ9{1Sg1GL+Yr`6wZ>(zw?b2rtuGaJM znAdv`b$F_(ebI?(i%1wV%&5uMZ{Un?BZ9 zTj`eEZv#VUm%dgob$aVDnT#ASN#qxHBEQ@5c*yT_Q&B>GtAl9!`$u8#9({2|Lui*A ze*p1Fqn#2yf;-&XIMIp{as&ZH^Wh7^8b7?an<2DIpP@KUzt(5r5v6 zh8&YIgm&rk7{?i|Iw0Y5_u7*NX3`BiJN`Ck`{T*Ub=`hT_zt&Z)TxOaDZ(1ZZRi+| zc>P?XG@}(ICimSC=s!NW8N?~8Ylk)7tNpMcv`dasf!Keq!mxK|P5C&Z6(!_Y7Kqh9 z?-JJ7JbsBGv`e2ocrUrGNmyg|DwPwhC?QAKu!bD#GlX{Oa}4Io^dzjYXTf_}x!qLm zM=JX;HG4O!6(wX(gXp>S5j2E$$s-Hm#)c<_<5%~unUvLv5;d>-D?EZHADw{cu-74B z@80+O1%}YBqAI(GXV0Q`RYBam`m}J*H%`7Os}&`_>9&L8b8NrA|HAjgFK;_EtZ~vY zyBR{e{QlL$8XF3SfcRwMIbn_Yb@s?=MTvvkR1Ryru(Sk3?Y>RI8b5Woxl{@5s^6eS zSfl*=?(P?z7uJ|p)Sy%=O5mtRSfiZSctF#z#vN6rv{gd8WbF*D0a3ktjbA$4T&NW# zWIYhYXEY9LY#g)95ZWbsJ;BlQ(zC<;`1-9wGFnkW_8ZpdRkuM{W8I-G4WV7~?7Of-ac$+Hr~1Et5LZIMm1+|Lxe>Du2?-j9AS)Jn9Xgk13m#9Mo3!Ww0#_tCv;jAea~ z!7=1j--k6$nbk?(^$lTNv4T=*Q+&|%mT;yKKv-G@#*>f6M1hp#OPB_ z3y;U`r|jzSEn``Ou*S)gSLu6us$KF9j(dK`iz~w#qj#F5@6?89Q(P3*xbUY#u*T85 z?i1GNJLY%&mXT_ge9OQZGfJ~zjm;%<^*e(hnhb#HfoJ8er?$l!vl{Lk))Uvw+ zCEq2mMx#Augf(VeyHvk3q)L2yMfI@8ifSigjqbC)&+_$gLb|^pv`fBafGDXsG^|lF zWQ~4j@JdJ?4PxF?uY@(~mNhnncFA{Y5NkVh3u|;9`L%vS)|}g1jRx-w>nDXZE;+xY zAtb5x^354*OlsaJtkLS!pY zhU}I2>x`P=DmOKH+={Kb`@Sk+jd^c&Fobr=cWMx||L73b=gJ82y#%wM%}Bf|$H|bcSop{HVZbMG3WT@GbnT-7{Qc^IaYESE|=8`7MeyntWI} z;TpFN`9ptm8bUoCB<|;38P@3kbz%tZl3%G<u*TbeFVG`*sS>S@ zJSwcQ_J_l;#y;JvCVb4honFll+9gNZu*N$#EedOtZhlOU+@(r1oN`=PtFQ9U8-Gjd=6_gIQiYMM$z3P6RjvAXN7|3_iV$k#;WJv&?9$x?r2`dQnvpW zVU5f8xGs@ndWMj5N3lkYA6kSp+^9$N$enRU<%l?=zVm!A3I*P zL35mpcFAK7;^k}p3Xey@${#diNtBSs21Mz7MPZF|-#^n3+9l6W5RFFs6xR5p;*t8S zR+HJB#fc$6uAoYtY=TyaquW_-fOz##47J z(0nk_E_p8jF<|!Uutu{RMxc=ieG9zm}r;0Ct{5$do2!Yyt4bF zsaBMb_b#k)MwdOq8odswYzWh}_5B!Yyg&Epu*O@bn4COOLf(V1#++LV!WtvG*G}cV zJ<%@tjKUhbygN3map~GOQ>`c=pCwph@rX6y^P~B|dWO(0`K$%;`^-DT8i)7%G}Vd{ z@|g(Ypnd0rHHLIK+z{F&-x)xhSpC?r#>llBQmrT<-v&UetUD;IamaIR4WV7~4F|-E zxx0ilx_$Dyp2?vGuo}l8?(5wutkJn=J448KAN{5VV&IDphVNG=JyYQ2+nu>x`K|@x z!ZYWF?{HuD>8R&^IPH>eoFFFjA0ECZetU35uN5WaTPBD}uXTBWpXZ&H9g`}dU3xSc z?}$b+4WV7~n-j0|sy`17Yi#^@ZK@R|L!x|s&usqd@67m}tYs`7MLdwTuRL5F|&@MR!fHhwG zV_sOJ=;Y`0%*;dy`E`#qs@+vRtWo#F9Sxyfa>N2_v~erK8h2EhtVcN#CFCdt)_DKO zx?znjZPx3VnTdAEF&V6J+qe(I8twZJ&|}4hkYh3+&Y#jOtTFF4uSbLv?UEx%AdYzR zyRgP}9nMO%qJ$h<0`bMf)?tk%HAm?YVZDM~BFD%;beQ{VSYvemI;mFlcI8+Wh;fyQ z!y0u8Psu8wU2?1s->;6txq5sJe$m3~5#fvya!d}ys`*EUHRi1Pq*QN9yYx6Cjwf!a z5Z1Wi>PlIyD51v|F*p2~+kA3mN%4@|zvh)&a#t=-dES5Y{JiYxw4mUS-3I!W@IU&l z-N|W13B5jKLBXz@yZgg#$LyN#$QoFFms)LR&gm%d*7{o3O zE(~kj+V29V6(wYH0fHV$iSdGc68XqUVbf!OD+_F;`C2lRAWQ9|qy5D&eyXISIV z8_zR@cF8*`h!+|k64vNbZ-CQ^5@L^lcCNIny>Rejq&neKQpEV>ghMPut{pI5?O zVSKN-H>P}Etr^?f5ZWc5)L3K4hU-#3uU>0C&S^yn@jpOpsr_S?YgDV)&k))r-#9>Y zyf@8qjZ5ZE(C;GZf_R;;hu=82)@;i)ZuzXAA+$@rIbn@cR-cpM8dp`AsNcfO?doJf z97#Rp&kWbNb39-nZHH})T|-wnMIa>WV|cVx#W&vq;+K4|3_Lui*? z@doEvE?<(IT(P8hpU-AFttery!%}l`C3o(5xT1C1*Xea?bTX}c>&I3-*=#R&E}mBp zcJA-AqJ&(x0mS$7sypthV_!Sh5ZWcbUO;?(U0cU}b=>i{JFO_8Q)=-UbxxD8M*Z)O zF@$!>uQ05!!`idM8e7J6cUnGr2oE_F!TW@beXqWsd#%I*j$NGgeZv3;c(~1&etYeMC1`Kkq;Qi|U^Y=D{cG;_o z9d|gUNyAv*V@>OD4fx!3$CR*FWugP%@+>g$EMz~K;!ra$G z=IQYZPJjy*KHj%dy^b3`ah|**?5oC~4l;yx$&@MR|mBqQ|Crk)yjIX~#q7@}{o;a-Ecl(7kzI=Lpp%U69|Bi1|1eh&(Cb0SD-Bz9!<%=xees?+{jBO~#o?Y; zyD;pl1<9_4&@Oq$0CD-*eZsz4@zoJtD@w>~9>mjMpBUD7w?}v@+Uv`ap(uvOWaEy6wTTBDD-PLUFNpKuj(T*LG_T+QnBV<#9wyY#9`_^ibo_ldY_ z_WOks&GnX)$X37Kzp&?ccfubpV5?dm*TY?jIqo}evR7!*F3fBQ*O|a|8$sOj`Sq?L zrm|nN-&C&^B`_b($N9A&>aM-i^#jrN@fn8DE_x^y*N^ifYz!b#b-Ozt8V#t^%b5rj>*#=bScJP%yLc=A_AZcwYCkGlX_whDw;E z&KZa>c%Cauj>Ko}W8d^O&vt%d#@`0!h$pU7^v?XG`Qx44fXOxM<5eIS;; zJ}CTF8{1{9{!-MbO*$nC#N&;hPUqsYw#v@9_O#rV{JINQx7m8lfn7dWnSPC{-1OLa zj@PRZC}Cawcbj~lo{Q)1q0jX)*G|xDGRUuRY*lHGYJMZWCoU|!ThChwS82*!#X){Y zgQzm4lIOnqYrjhjpIa#z|p~ z4kh&rpF8y9-5C?Ut0K$Oh7Fsw1N{Vs;kE;-tU?^hcp4)jOk@mR2^ zjvk>)l;E`hcUIf!saBMbc@tQpb^Si!p6`Cu*@nTPM4JuZ6epA*6wADz&{oQjp+>b7o zUagN*s)Xz}5U;iy;mbO~ul;3)A+$?p%)r&ZZ>HaKcYM}vUYTe`3H-_k&qN++!MDB% z4`o;Xjky5#cgkG%M}s0>`!5~2(%*7eo$&XSfBonOjNPwj*T<&26?ZT7IP1RYpmg*m zeB$iw60Imvd);nDyn51k3s-{p?6R-YFIJZn@B8^=Lul9P->L`VyPsYHvARKDKLFok zZmZkgyHD2)oh#s}C_U+FtDXzb%iPMS_i%%*jdiJ*|?$B!UKum1g z!yk2NN%4Nq)iZ>4oqgdBMeVy!bpzLyk{I9B|BBD3-v=J#w5#6nI}{z=b*ihstkhfL z@FwT_+Dcv?`hA zmj6cL&1G%;hRP)qeh_!%B*u zf3l-_eax-$z58I?WcSTubG*LNa7N1YclqXr;@E4~>!bl+xhvdcx9MyWudW~HyVSw6WW;GsD@y!%)2HtEvIkv*`=16e zv-M#AeocI;y?&-4OxNa5-E&JGbX}e&aZ=?Wey3_B#mDr*G+U`C@xb>Vx^Xu==#Cry z6xaA{h~Il>OhkD9d_!p0kC(1A!pvi;o zph-`H_+jjpyLjEBU7c2xIQH_j?v45n zx@!iJIO6tU{?$Kw7hl)4n<2Do|F>7W=iZs*y5IH$h{r|^_cd`e>aHFCn8F$p_CkCj*GBp}Vzhr7zv$h9fo7|eIQxsI-155P-Q@eGVvUcl9_=p#@zDN*453}! z4}QuG-F>`k*qOw}Hluwhj!axVeUQ_N5<@?J!d2ch&Mo_W3Wzm3jP~t8w5c`N5Zd+j z`Lo=H*T%UjgGe0z`Y8Y2g5Jfa-#OT6MTr;JJnl|>ah%)Sox}rojq+EKsBn)Vw5#K& zN8Ob}$GI5m~!D@xq_%0q76zT@0ZXOX~+hp@(yMnesuU3GSR$gS9UoO`$q zi65T0&yT_ytIr(jw4%hYMbllS9mlx|RY=UZ@jgEd#Gt{J(5_RbOmoM6HP+Rf!-<8j zA9QTSB{@UOm}e_Q+Vb;nRsAzCUqi z-neY6TV9jIikicHA&57VVNNSb)PH)St9J2NH{;g{Adc8^xIYm@a;zn^Yp)k3x%M=J#G4C-`QadnuCj!7HLE<)J<(~b+wT<;>C9pN zQ4qs#9p<#6M4KljxQC7#>+oL?-S!>hyDjcrT>I7mPCxs0?e)Ctw`#n*YteLXKL6 zh>gdL@mX90yXWEkomP}+R>ivkohP_O-ALSd^cerga$Gh0fqsV2uC=?DxwY3$a5q0g z;;6zgzSC>Hi~sziuhWVWFRq;L-WWT@jt zay*HC*ty5?vm6(S7~i1h-R# znIJCucC>%)&ECZg&MGm4cAZjpkt_Ing8Q>4i6tvW`vX>Cdc+aEomQ0i?V^|6k~$Ol zsRyFx6Qlh|%(ZN~^PPs!u8Lp3?0Pqx=qmp~;;HeY{l&;wcD?Klrxhjk{q|+|0El+K zkr;mSXg>#2Fdn`1c0*{_?@gDueJ+^jo}7*uAq6L%KiV(Eby8Q4zRhVxiAfEXxQn_> zbf--wQQ@~y{@XS9x8coBD@y$K>}zhw znu%^I=EdTe%&3um{`%gNM->%Ly#+TK6SUHD?Pvc}&pbj=q| zb61z_UiR{gg|6pw)7%@o?_P$P_ZP2BAHnazjeqRpw4wx#lZ5M};`btmT2FT~cdiBEfP=H?1FzyJPG8J$lZp~gv|JO`m_MK@h##8Vn!OlD zicVScVg^Tr9FG*?m`@pw7KOiY^r-AV6PCEWADHeA-Em(KKleT|U5+C~Etd~Yw4&?j zE#c}(58Rkm_y*IOm(NVJqJ-V5rRm?N-_%EJUzgONf<^34`%ASVME^L2T16vJZ?%h++$}E z&@Mghhwmi^ewltbtEBjcYZ{x^hd%Qse=*;cUOvrTT4`78-J6culpgjl=G}dExYLRf zuPrEZb8y^e=e_vct?}!Y^xlcMVy|y&2<@8la+zz>e42Z)28l;MtmywUwxoFMWzK0u zi9H`Ga}P9|=AK-?Gl;#e-q~*+R#LqB>|+d}U5Bj6x~*E1mf-#!bt*9Y;)co3eZ+)?Bx@Z+Z*X_@c8Rw5#swQg>{(scy;HJAf$ZyPv=Odb~5# zyufKiiH&tjU9-Zeu609B$Xna(Am8MwlHz)|cQu4|HGX@Z>(OwkJ8@hE5Ig@^&o9Ef zyV-+#IISpg&eRv&4j)Z%_3HDvyJc=eUvx1hVGg_85ZYDr<_m7@*Hc_}9*HwnHSzz& zk<{J){;$)D5?xk4?|yuIircaMpCDE=ZSL2cQBwS6zw4Y)t*PYrORnhyzY<>%T+tGxV|B+*ga|x_8!3b`##+=$~2o zth=KTjx=}L>~-yef@i0l?d#RR)mu*;?1n%7lv~~PLHBs4k9?y=bKKKYCc6tR{@(Y+ zafbKKe9$$#dmYx8anH$qVO8*Avrcx`p3Oa1F{9f%tp$9X`dk zrQbG;a#~Sh{EstT$NCf9bE{tlapvK7`3CrAdB!dy4WV83x54)nW|cCP*?XDK^e$@= zKE1l#TwHcwjpq`6?jCo-(Pg`Qv%h01^Xu=N^ta-ctFlaGo~SoH(TWn?hObSS%FO6> z7>Lp@S7w>Yd{k{0r-XJ@xxZ@ojJmaDGZ4F-(f&Abx5G%L%E>vR-4I zR+QMYYgxin=D4f&0deT6HYrn?PQQ#YgmxWp-I9c<%=uY6aKnyZri12~(NMmyu}s-ofeQNjRf% z@&!&SN>ptBd%{%a+g&+3^NV}-N}0+$Qtfy{XqSDq7ra_6Wh&Ea-&Rg5N*uc1&W@?f z)V@uzM&+Wy)X?t(B*l*T;fdGZLmUJ3m>YOkZg*+-_-= zGL>1?`yulhRHDm{4<<}yzT1<(4KAP1GG!_=Z>NV1pv+ui4 zI;|*i(i?*krZQ_?H4q1PZkjTcS$)#ehS09B77s|6%Dg^^-xD{CYm_pT>3qR#d^&Hf zD6vDQehE{Vb6@25_HR!-G-WFDMEg00(5?f|>X$H;Sv{Y`-q$xwnabS1Y>v~45)&5m zO_<7jHI>Aqx%E?~GKVakYY6RHU)(ccD)aH*{AT&#__`@mnS%G8b6Qbi)o$GrrZT_( zuoH;UcRZM7D)Zs!C9cc)volO(s@}Z8pF3kohN;Z-Et`DnNiSxY%1kj(WnaZ5-iY2D@n4MuNv#QqyuWREw+~yHkrZQJn zU23*UiK>T9%P^JMW$O1>ZMLA zN?iBzeHo@Q9hQ6xV&#RmWSPpiv6j%T&Wi?Qn997}?HdqxPPih=ROS-D)M-VDH_Q5F zn9B6};cE~-7I)4vl{s>~CA90VO&4XD%Cvotzt!Hl>*y>~nfEF!b6Qd2mj^p!n96+W zz5vnWfg`g_W%fA8654g~%;PgmWv(1eVy{ygW|_+D+H9HAiV}xi&?3WBW_+j5LELaq z-7Hg?!&@wK+EsK}iwsklJ5K-HTjJL}_s%kvd8zd>rxhi7H$OPTRHk;1^;qNl<$GqC z${bs03GMn}kNq-CWtLSXar9$VvP@+vx@Ar)N<9C|o*AYxPu=<%i2h>>!Wtd(2<@8u za-|GYnO|T26vRG9ZYpIevm{yOw4%h9^DAVS${aV8#Q4kBm4;NNttGVUwx8A&GL>o2 z_Y)BH&R$x|RA%Ur%bZq}xM<3Yg-m5`p7Sw?+h2dCl&Q>+CYI2yVHeIWWGZt;LSlH$ zDWyzhu0Ld%(~1&<4xd)YRHoW1AA#u9Vpu6tnSy;Rpa#4#yrZO{UlX!c}UZqTBI)9G$5~(Oru&_cQQ<)VNNHlt>QYllJ*FLa>c73xv{i*1?8j2-d;h-zoOIFG5!xyvn~T}v;T-Il4$ z%Bx9yKX2?jrZR;KmO8B{an!=TZJEk+t3_hr>37d#DpN0O3GHh7%7C^^WybACqSK%* z^O(vUK6k0piV~kr?a-E~%yI9p1##8a9p*8Wne?AsxAL$&sq$5iHy z$Cf&+DA8$Qg|$BC|Qe zROY?vzhaG%Lte@PgrZVYMByPHELzbz`bE94|gm&G~?BIl{Ov%s!d|TRe>gFs{nc925 z&PJOWu^cGZ-r%!W(nJFO_u?BU}RrZVlnA+h<& z>M2v1L4T%(&@TJ!)h(`_GL>0;Pu6Kgi5E6qlrWXqsVBeh?y|@JDN`9&W1b5YLDzn=Shn5{RX$Q|#=DI44%htbA(KD6#c5)-EG3w~u5~ea| z9@)xiMG5>)^gO~+e!S%MrIiwX9cKLc5;%`r5Fy&!RJIaW zFC2#}zaLeGpI*vT#vdB)$3KL2=}|nK<5l5+EK`}MhrZ9f8wef|R08`gtWo|fIqa9K zvrJ{a`SD#tXqO)M!@0Ff_eq$_Y#x20d41?Jzuk$yrA%cOu4#aM)%Df=6Q(jBJa>lE ziV`y>Z%moW{2Y$^eB0%agsIF~?_6jI?P_1LF=Z;#H4vMJ)=!wqjJ&m*(~1($zqcV} zD)af5JbtzQhDHffnUkLTuOYOn<~1LrOl8jMe-McN)0!nrWtL33#c4%};`(b-rZUAX zNc1|nMZ#2O@Fo2WpQvENgz5~ea=-8#f+MTu57ypl4N`Q~;W7yb3h)(KOY zG5zl~gmyI9 ziDvuwl&Q=I2l4ps+C$nVOl59r_JAR@>)HjgQ>HQ>y<8i_&u_O$n94j=Z@k<1{H&Cz z%t2SxDtl%;C7Q>HSrp5$@3 zp&eT%Ol2-T^+BfaZ7$}p8V|Eq;gD@yd+uTjcWrsG-sM)vr^ zi5aFc!~7yc*e?BTKu3nD44jz^9T~ps^Q;FtGW?roL(q|7Duc7{u?8I(rZRA560Imf zM~0szNX0?WkzpzWXT}iPMMs82`MDo-WSGjpnF)>zQyHAe@9D@em4VOV>BumZff?fq z3h2l%m4P!8?3r9e2|6-NWnjjDpd-Un2F^^dXL1!K=*TdYf!hLtjto;7I5UROE;=$y zWnjjDpd-Un2F^^dXL1!K=*TdYf#-sKMMs9I44fH5XcrwBrZVtcK+ut4Dg$RG_%^xQ zq9emp1_n%-CFsa7m4P!8e4E^DDM3eusSMl}tU*VHsSKPMLueNr8KyEYV?fZ6VJZV> zCfGB%iV}2Wn99Iy0YOKGsSKPMLueNr8KyEYV?fZ6VJZV>CfGB%iV}2Wn99Iy0YOKG zsSKPMLueNr8KyEYV?fZ6nT%8h&P=dpaup@$$S{?G+X8})3{x36GltME`)sEp!&C;& zjMIt|bYz&yz=pvZbYz&yz?n&u&@O##78KBtVJZV>#=Ji0$S{?G0pn?-kWQyDlj!Jf%g zl%ONSR0eJf2s$!MW#G&hLc8e5gjD8ynn-kHn99JJ3HD5`q68forZR9_NWhU{Dg$T6 z5ZVPVz%!MB83Tfj3{x36Gr^w8Rg|D3!&IjH{9QUSOl9EA7(%<~$S{?G8G|+G$S{?G zGZXBYTtx{wGE8OQxqzS}!&C;&OfYnEtJ9HTDgy(?TY`=ZQyDlj!MDlXmJ)Pin99Iy z!5VaAn99JJF@$!}kzpzWGX?}58KyFDW`aGFt0+N7hN%qP77%n~xCWdVLueNr8KyEY zV?fZ6VJZV>CfGB%iV}2Wn99Iy0YOKGsSKPMLueNr8KyEYV?fZ6VJZV>CfGB%iV}2W zn99Iy0YOKGsSKPMLueNr8KyEYV?fZ6VJZV>CfGB%iV}2Wn99I&0YOKGsSKPMLueNr z8KyGuTtLu~VJZV>CiphF+oB`GREE!VOVE*FDg$RG_%^xQQi6^QQyI7|Sc8rXQyDlj zhR`lLGE8M)#( zCfGB%iV}2Wn99Iy0YOKGsSKPMLueNr8KyEYV?fZ6VJZV>CfGB%iV}2Wn99Iy0YOKG zsSKPMLueNr8KyEYV?fZ6VJZV>CfGB%iV}2Wn99Iy0YOKGsSKPMLueNr8KyEYV?fZ6 zVJZV>CfGB%iV}2Wn99Iy0YOKGsSKPMLueNr8KyEYV?fZ6VJZV>CfGB%iV}2Wwz@KO zWSGjpnF&T|?$eTv3{x2xFy4L+(ve{*17{{!q`6N>CFsa7m4VxWt)e5tR0htBA+(E* z3{x4HF(By3FqMHb6YQB>MF~1GOl9D zMF~1GOl4rIfS@B2QkmwK&@MVMOl4rkfS@D8R0hsWuxD}=CFsa7m4O)pf{qMR88|b+ zp2<~|pd-Un25t)oIxl%ONSHOegrIx9?_9uDg!eH zYtWHlDg$Q*GtakHbUnQ#OoM_W!&C;&3{8uF)=@V?sxU zsSKPM8YBNyl%ONSdtUCC(2-#(182q%+C@i(Ym~b(bYz&yz?q@>@=rwxIx<|N+?Amt z!}|ee#t_=Y?dKZYYFwEDjto;7I5RYO{;4Rz?dKX?7gq#=Bg0e%&Ws_nOON6e6wr}j zDg$SRCelAg1eM^kgKKdA;ruH&GE8OQ%oswu^tc}!EI2YuW#G)1*M~my>BumZffbYz&yz?m_GcF~bxDg&zn1RWWsGH_;sBg0e%eu<|e!&C;&jJI1w zM~0~koSERrFqMJt;pxaQm4N}{>BumZff<7}=*TdYfin~AnOsE)`Z>9^F^>g~3{x36 zGltMEIxCfGB%iV}2Wn99J00YOKGsSKPMLui-%Z9qqcsSKQ%LZ0ow zcYU7yz(kyX^Na;LGE8M~_C401Bg0e%&P+xtO3;zvJ2g`A6vy=8$S{?GGh+zt;yE8A zc&-MH2*Z(KDg$RGp(Dd%#W<5cr6a>s20lwlM~2x8%owaeM~0~koS8%`O3;yE_5w2o z1RWWsGH_-Rttdf9hN%qP77%n~n99JJF@$!}kzw`%GX?}58KyFDW)iI^K}Uv33OpAO zbYz&yz?m_GcF~bxk^;{K1RWWsGH_-R?V=;YR0al2Y6&_rOl9EABwA5|jto;7xGh+N zjto;7I5UROE;=&IUSP(6pd-Un2F^^P6(#7%FqMJZ0)mbVQyDljhR`lLGR$6J#(EPwM`rRQoKy7P!HHIspd-Un z25t)oIx=_jto;7I5Wtfx4sUPpd-Un1~v>{A9Q4x%D|b)D4|{Y+AJub zBg0e%&Ww3|(2-#(0|O@2R~oVjI5JFS;LMoUpb~Usn99Iy!9AxV!&C;&j3Km(jtsLG zm@y#e$S{?GGm~gV2|6-NW#G1epd-Un2F{Ejw2O`mvlo~#An3?2m4P#pXhjJ+GE8OQ zwt%1`!&C;&j3Km(jtsLGm@y#e$S{?GGm~gV2|6-NW#G1epd-Un2F{Ejw2O`mvlo~# zAn3?2m4P#pXhjJ+GE8OQwt%1`!&C;&j3Km(jtsLGoZkn6jto;7I5UY>l%ONSU#~c~ z5Ck0=rZRA5GIV5^jKEvT(vjhDCY%MFr6a@a1!fGc7D`8ksSKQ%j8>GOBg11(I3pMY z9T}!FaApiaM~0~k44AC0T~I(rhN%pk8M9SN(2-#(1Gfch(2-#(182q%+C@i(*$d1V z5Oidi%D|b)XhjJ+GE8OQwt%1`!&C;&j3Km(jtsLGm@y#e$S{?GGn3JZ5_Dvk%D`;_ zK}UwE44fH5XcrwBW-l;fK+ut4Dg$RGqZK9S$S@aywE}{U3{x36GltMEIx@^&V8(!; zBg0e%&P+xtO3;yEk^;{K1RWWsGH_-x+C@i(sSFI5tR?8kFqMHblhKM2bYz&yz-_@A zbYz&Az?m_GcF~bx_5w2o1RWWsGH_-xT2X?I3{x4nEg;K(qQfiqL66(#7%FqMJZ z0)mbVQyDljhR`lLGR$6J#(rcf(N(2-#(1Gfch(2-#(182q%+C@i(*$d1V z5Oidi%D|Z^)QS>xWSGjph5?p8KyFDX4)vBU36ray}*olp`d_{3{x36Gi|h@1RWWsGB~c(0B5VikzpzWXC|Yc zeRO1)%D{lh+Rs5cGE8OQ%w)8p1RWWsGH_e)&Ok?osSKPMLueNr8D=jqWB8o`jto_?hN%pk8AE6n9T{dXFk?W_kzpzWXC|W+CFsa7m4T@Of{qMR z88|bB&@MVM%wAx|fS@D8R0hsWMk`9tkzw`%GX?}58KyFDW-?k)f{qMR8MrMV=*TdY zfiq(W?Fx_?hN%pk8AE6n9T{dXFk?W_kzpzW zXC|W+CFsa7m4Vv=f{qMR88|bE652&ahS>|u7!Y)1n99JJNwlH_9T}!Fa9cpokzpzW zXT}iPMMs9&3(Oc0bYz&yz?n(3q68forZR9_K+ut4Dg$T65ZYzGz0#3kDg$RG(TWmu zWSGjphQS)akwGd0XT}iPrQe+Kz6(c&sSKQ%l#UEj88|b+kzpzW112~!Ol5GkKi(ba z$S{?GGn3Mu$yI38CQExJSJCzKmSCU3kzpzWXC|u^CG1ww zkztzAXu<-sRoX?jgvYXIlwkTP92urEaAvYvQG#v>?>U_iq-1bpn99JJDOEzd=*Vyl zytmgcD4-+5R0hsWsaBMrBf~ZDy$AoJBg6ZFsQU#av`f~;Gm(xAQyDljg<4TU)&mh7 z8LRUuXqO)MgW(28hN%pk8T0zkXFeSn zrZO;N5*$f|Bg0e%&P=KmCFsa7m4Vv=f{qMR88|bB&@MVM%wAx|fS@D8R0hsWsud;Z z$S{?G+X8})3{x36GltMEIx@^&V8(!;Bg0e%&P=KmCFsZmSEl}25Oidi%D|a1gm%%9 zVfF$u1_T`$rZRA5QmrUKM~0~k+!hdYWSGjpnK6WR(UD>H0y72#9T}!FaAq)Xd22-p zIxBulqfbWsekzpzW116y(!|VlS4A!6{!&C;&OsW+nbZuM#6OIg188|bB&@MVM z%wFKRU=2DlOl9EAq*_tJ-VZu5Ol9EA7(%<~$S`|>8G|+G$S{?GGm~mX3A=ac$S{?G zGh^-t9T}!FFklkhhxpb9M~0~koEfusm7pWTR0eJfwu+7nQyDljhR`lLGR$6J#($yI38+#t_=2 zugx%5CZsZOX3Xn@j!c{@6Kpi*pM0f-xiTS@fiq)XgG$hmiF0K@(2@lWSGjpnE^pZCeD@dv}bY^CFsa7m4VyB zHQ>m^xiW^(E;=$yW#G(!pd%CK%6P3PK}ROel>tFVCeD>Hgm%%9VJZV>1_T`$rZRA5 zyjGN;BNOM!fS@B2=gJsDyXeR;mBIOaAn3@%xiVfWO3;yEDuc5QLC}$5Dg$T6(~)5+ z18*fbGE8M)zywEzsSKPM5OieXTp3S$CRd?VlOyQJFqOf%!XW6#FqMHbV+cAjajs18 zb8>5kxiTS@fiq*aN(nkLajp#3pd-Un2F{Ejw2O`mQyDljAn3?2m4P$kwW0(anK)Ml z1Ra?;SH=+9h3PRNm4Pz@f{sj_E914I1Ra?;R|W(fnK)O*5ZXmYhN%op0uXd$;#?W8 z6(x9{EmIk|Eg2XcrwBrZRA5K+utib7j0%l%OLM z=gNSfBf~Y|%oswu=*TdYfinYwj!c{@gnK)O*YZo1vI9DcEHCqWfGE8OQ%y8n&Kewd>9ho>+25ZofVJZV> z#t_;?M~0~koEZ>wWa3;IuN5UQ|E1iO=}3Z(Oq?rY2<@UH!&C;&3{ajuNliV}2W;#?UJbY$XO8AE6n z9T}!FaArWzkzpzWXU1zq2{|7Q1Ra?;SH|mSA03%ES0=ckTR#Ws$i%raUOyp~pd%CK z%3uvTGI6eqA+(E*3{x36Ga%^5FqMHb+#t_;?M~0~kyb};~Wa3;IuN5W4Zva6@CeD?~iZ@XtS6C^cBg5+Ce?}(;(~ynBg0e% z&Ws_nONB#U{G0x;K zq9enM1wKm=9T{dXFk?W_kzpzWXU1zq2|6-NWnjjDpd%CK%6P3PK}ROel>tFVCeD>H zgm%%9VJZVN1_T|MI9JANMF~1GOl9D?fS@D8R0htBA+(E*3^NvZE+FX0FqMHblBoGatCq68h8I9CP)=E@{YW#G&hLc8e5FqNr%8P}jA z!&C;&jMs`1bY$XO84z@2n99JJF@$#6XFDAkrZRA5yjGN;BNOM!U=2DlajuLZv`b%U zVXjOP=gOGZ2OXI>SEfi`X<@ER66ea8*Ps$~Wa3;IY!w}uI9J9H+C@i(sSL~*5OieX zTp6zwCFsb+xiTQ=$i%rahR`lLGR$6J#(+1_T|MI9J9H+C@i(sSL~*5OieXTp6zwCFsb+xiTQ= z$i%rahR`lLGE8M~ejf-rGI6eq*NPH!WSGj}+(Hm^WSGjpnc-}gERzvpW9M`j!c{@gEi>LFfoBMV+ie{Bg0e%W(){AGI6eq*NPH!Wa3;I5Oid?2Aml~ zXcrwBrZO;NK+utib7j0%l%ONSR0eJf2s$z$m1(=o5ZXmYhN%q97!Y)1;#?W86(#7% z#JMsc=*YymGKSDDIxHt_%n|GI6eq*UvsWGI6dEPwM<&jd@mf)Wjto;7m@y#e$i%raUMot_k%@ClBoGW7p?V=;YR0d`Y2s$!MW#G(sttdf9CeD=sK}ROel`({N(UD;)12YB$ z9ho>+#%o0hIxep5;8Xh1Ra?;SH=*w z>!SwT3-DY((2-#(17{}1`KJF=EU};gA3?Y+An3^Oe!!VA1RSM*y0En=*MJ!Vf{sj_ zE5ogl%2opF<>upnpd%CK${0es^eA4KE0c+HWw>|48gOQcl)!!qYruxV8kj4SiF0KP zp+#%o218E|CcTp18_WSGjpnK6WR(UD;) z12YB$9ho>+#%o0hIx=yt3+#t_;?M~0~k%oq@KWa3;I zuN5We$i%raAn3?2m4P#32<@UH!&C-l3M<&jdDbjry=E|gT zu8i5chJYi(R0eJfwu+7nQyDljhM-B4>!KsWR0d`Y2s$!xu8h};5_DwZTp18_Wa3;I zL)b3;ZE#W5v*y#F?0Mbp^KqVj(KEN-<8i)(d-%sa!r$-WiYWYdetz)ZVYt;eBM|*g zsUC=2MG2(gfi8DtzOB|N5c>|TZ3yi`mLAr?84FnB#m`O*#4h{oH(x9H1h=-FIIjA! zfoRnHU_+43bs^yoYv7CptZ~*^M+f4^UiIf|C7&Q&PMowf3B)B|G&Kb2To=w%2;Y|Y zU(Em5)Fu#TR5)V3R`Lnb<5oShq-QbDKH~RXoQ)K2k6pYKo{7ZozBtbakB1Uk(PzGWwkx4) z@T?7fPr$hvW<9%x-mVfnA0u9=G;gbv&@OImw%I-Yf8UQ>MG3BV?AwERZb;r5$You; zzPaPy7hhiD`Cn$ieD^^DoJVLSpE%|G{!D&xy>nP!53?qiG=o?6q1)mxJ;cSSBv@lxgmz(8jvIMVUk?u`kHE|i zSEG6#PqzoNIb4m+B_7^E_&d)3$RjX=#T_%KkB46pe3JXF>*L{pY-g)XYkKnz{-9x?S)nQn~sU&#>Cfv9ZK`$y!^VtreT|DRf_)LGEH=ajmMF~E8;!LFN5Zc9a&WB#v zpXZI|5xN(3@9I9Z&qS>#!N+Mvqdv56^43s7yYv}q*U;_N`@!?ttB&r^bJO$I(25d# zeZ(16+aa`z=e5sR(x2z1=Mh>_0yD8(oVB$bLc4fg`yLJM;<@R01kK2Azw1l8(P5sK zt6SFB!&Us3uR$faUgu$bJuJk$HTbCI-et6F+wUcO_T}EA_-udi`92;t-M`!_CHP7! zn9|3?liSW#X_vk$*=LEqYW4Lc`qA*oTSE!$(&w99gYTAmEiUo!$Q))Oxv5WNLwn_=@;=kv9S=cr7@laatpCz=S1lNnx zpz^j#3GLFy$*$3}%>tMG6yJnL>{_J1KU>_g(4AZ79-o=B8-AtgHyN!c!N0fuN>zf_ zUx<@Qi@09%Tc$a#$7?^dnmm}-Z^&B%QzP9KV+VK`@!_f`S|L=REK1=x7&is_0`dmBCW6E2DM4WOOo=ZF@k$7cWbgL##xyuGW0 zcG<_{`3r6j$7JrW(xHr3A?5cEo?)^0qw>GM`TAF#j)8mLaZ5Q-rR!0F;F0)zg4del zEg?rwaILVlcZ4JK0BTFEC!^Q;J5$7?}3G5YBv4M95Bwe>onydr64Lpd?(={c!Z z@(I%A*Dw_#QG$Qxx@2opvsF$j`9$185OU8AAzPKoJ_I3q*J&l6;2J!SV(TN=;mjS2 zl#sof^3mk8hi6-CeU_BGbzqTJl#pjA_Sel%l|K_Fw#*npyZCo}hJrZooS)11n7jXW zozLs~GXLN?OG1RdbIz8_lAt8Ch9 zP3k>YLc4Sy+O5)SvFbHbd2Lf3*)G58sji_{p(VkrfM<~KmY7YHU+-0k{M*f4O?BIA zXoY|02)#z9y&pGRDJy5IHj;4_~|6VIKo zgjST$tKM##&@O##T0$#I=oM+VO=y?Cf(=p32{%lBXzy^w43DbPpV0{=+a|P&^LUv2 zl+XE*XGt;ViZJ=1Gr{>EOn&G#=qwPs2Issm`JuzYc`VFv=$hzyme5K*!Ayr1$+ij7 zxh|cdVhOD%p>tC#q4!YlxlSmtgig`XsXaJL-80`QpX{J}S1U^B#2~wd657Ry4@`c_ zXF=#1T2VshBiS{S&@N7VVDeKw3qse>y{LOv_n}=wD@yQjV)9cyQAgKMLc8=CYS+;1 z)%(F25lnu{=S}DuT2VshRoOL^&@N7uVDeKwZ$j75iV`|^%dVk>c5$i%kCBzno6t2l zmyF2|olDLPWAZ~El6#tI&GuhWN^m_UKjl-#bPc^N?b`NxiM~hi+0NvL#-84iz2{m{ zg0D0tKjm|t4rrqSwbsHa25=cpYka&x>ZVOm(HuQYiLCY&a`3j zQ$FoR*HA*cbRXI^w4wxO^Dy}-pI)bHD4|{Ye6wrt-IB=3-a{D^6JF&(X}eWgQG&BtnH7~!an;8| z3GE`ibtbD4oPNo4iDtjf{pI9MW=Q1|J(bXk5;_Ce-VY_TixWh7q?lJnu!Mff=*-D& zf8uCG37wE>*HA*cILC{0h7vlT)e^eBeBaGYFVp*H39Tr>Pll~?$@G3Gp?HWpG7q^h946o*539TrhQ?<8EXczA}Q9PVus+QltoDpNkqTBysSJOg=_}2y zp%o=`*50-W?b7G8CA6Xhf5~i}!l(B`3GLE%RJ(?L-s$I{?l((lMF~DOOl8Wavg=kU zphD2qnv>E5eRr7h9I5mf?E>SfD?i>;Fbge zc1^KX@(I%A1pJjiz-KW8>0B3_7SBDx{{}}U5O8LSwUSSeE+^Q@+yHisAz00Iacj5+ zZzb3@f#B9@C7&Q&PQb1S1owav{5#jhy~;JXH-cSLzE#-ETFEC!mlJ&Cct7|^D#5>V zU3_+M4L+*41_YiRB)-A3MJr11c}AMgNL+vS!#x7A+a6~cLc91k*C;1&K6nw=z!^{T z;j4sHhS&GiXTE*5Z;#;Z^7i3ugj9xCMGfbi|FZ_p1Pc>k`CtA&o^9q~kA!O*@=Au5 z&`LfL4V64XSJ!Qafe}&}UPslgp%o>#N1}a_Pm3GL$FOlAHrp%o=ycHp;QFh=s$ z(8rd~vFMU{efHR`(n>y&+lSjGbWg+V38@UP&ua;-D6##=BloB&q5IITp%o>#b~LK; zwn_=@(&w99L-)Hr9(?9U|0iz^tti1;inh~s2<_6>rrj#7C;{sxTxFM6rrkE7UHS?x zf4}AXF5gXY&UVN=IQ0Z)N{4KM(@FSuJX0QP@Etlwz%d9p4rk-w?D&x5a5~MuBeV-= z-G>~9lYHzN`CFCS5}d^z(i+Zzv4n0rOp9<-p3_itz5h$(ZdVDo86iXBG?Z-<+J$q6 zL(;_ACYHdN%jFYJFzJL{(ai~eM=L3hz?uDFIuEDmz#a&5emK1c=S+oEhI1V38d_0; zk4^M(wnJza&a4Wl3@1O>HMF7xp9|5)*$$yyIJ3$}A19B{{lmQ*4X5qwE8Xu(@X?G$ z)&E!{x8JpE+s_i+UcDbU-^)iICvOd{D8XlY^l`RBXcx{S^U=r2BebFf&QA{Wyf}Z$ zK7vYU7tU4n@yz8s0%sD3REG1(aOQGIWjH%*+xto@N^rgC87bGhyr_sDyU$y)ybZd4yJ! zz?sq^mEmj~yM_|lrH_*(w4wyg>Jy!xw zOGsrni^;B``%1g?_l_m>@laatpCz=S1lNl`PTp22pF-SVA3pjx z_?4>PWVE6L|K9q$Rta4L=kogKv6%Jj8hX1*;4EDq4W7KMQbM~(M;9oMz3l;Ar< zbY=3^P(r)lQ21z!VEAub+l@eS#x-xld=-$;X{(J6mvinN+JA9Kc-gxSKJ7`$yl zyY%&F34N{UYmnmJiLka$! z>yqndf`B6v2$~~W$tOtD3BlBbr;iK-of#$g_tvgHGq|s4s^FTkPxB1)oHMhvl24HS zhd@61e+lfx8M!Xd3D@{%tMGg*cV=wG5?i;Bb`Xhp&;PkC(z!0|h4AnH?A<`bz57ok zpCDaMz>&fIFL!42w)l6h3y)^FrSfM99GO7yS)vss@a%D<%b$sGWCB5FMhWfW-&>!% zaAZP`!}Jo4jHfF@_k+*M-0kx3e@EoH;K-zOW#|V459gmXumc{B*BU4#3Ii30Z`2_E044Z~YvDnlE>68X2wjD@$m?KQN*zjFkPmo#2kHE#_iw2OZ; zm7z;vw@NEYz>!Ir%Fv9kgg&->j>Rhhm+7;|5?aY8a{F-GgzjlLGAUgddMB39iW1v@ zJaUhk61ornA7keMZ%I)l?h7WO2rCGRnP33-WgPfQw;81Vmg=!7M1ShX48McHjA`?(6I2_uHNJo%8jn&|O_s z=blr!4NFX5yU8P5l*)v){JiBh-0toVo_xGA#G2%UB__C2ll68CVJ*L#xeZH9L`K?~ zCd+PN!-Tc`1}7WI$HKT95hx3YMB!J`@$2`ki5TJ6%v|HM;5sKFs%8PvHN*i#RLugS zYxo8GWQ4UMs%8PvHT*I@w^5d=ElI@AEFgx4-;L*l%N{WjTN5imG=%Mq6779WL`2Wl zMD`Fr(M?z@;(oSfub*E8=S2Lvd+X+e6QYB*ZcbE5*Ygwc%l!q-={&>$ENIU8Ax373 zSQ&mhmD{ky1bx$-S2TvOR{REQidY$bVU^pk#01YmbMDd@!dej{Glf?s{lY3m$uciV zGXS*@t=pVkGp4QF?k4EX=0u&MR3@y|{gk-8u1CbkOyQN`cVBs1Sz>~xy*US~D3u9o zMU2c8UKxH*mfNtzL`0)3XwLI0Y?!cC#K=tHmEkw5xs8aCSwO4|zbK9vnFYkk@C)Yd zwz9+o_VCK^>*?Hv32Swa3?6ZK+VRQ|0pmM$+c3eKhF2ymQ?`5s-(Z_GC-$w|% zGNa>_B_<+9W{OxDercT7!-TaME1Pq$3c?Z-5hF82tPH=H&TW{mmRlqzEHM!=G7E^6 z;Wypggth#<;M#+_z(iB_<+9W-DT4h(XD1LmIbn$j>@_D&6*f#{TKY;9HdJ0ph*ySa5!Wv#EHM!=GFuTVL)=L>k!vkq z?-Ydk!}eUioX91;;VKM!&52V*sZ3bQ{gm5?7?~-&GQ_jQI%>Gij2M}eC5_0KoUp_M z*X{Z@AXE5omKy9sMSH)paIM8wEU;g#X{$niV#spdrB z*@(}W!Yf1cMQ+0q6Y-n#spfRxF@&`uMrI1H48P;gZTKt0*PuD2lBmp%FODT97#W%q zGK;6ggta0@W(uziu@rf!EHS}I)SNO_*l_Fe6>Uy{n#DH$gwZc2M03h%>H~Z%^nve` zm&y|QrX^_I=G@n!9xgBAZgYAW(Loc`+yq~S=3KI(=DwG;B1UEkuMEG+&+B1{3BGX6 zxnzY6w<7kMQ&lHyD-+mm&V4OP<<_;9`zf!7+dU#srkeA8CoGkTh%K3F&K4e1Dr@3~??wVTp-|mzZi!=pI8@i#p+zAu=YnVTlPw?dF8;F@&`!Azm3`G;$k$ zb6ABnXZ6*7({jQR6Rc$L%8ahOOjyhBO>V;y6Rc$L%8agxOjye!YHq{dJAVh=ZaHCz z3Hk=F4AC&%gthYi-~^hO=k$n~iQi15xdFeQ=L8z&3B=6scXpupd#}d{G!StjO(I%} ziHLPb^e_q{5yZ^+Ue=0;h-70JX_1H~(qbqn2}(GO=12rFGrkwstyV;Kq&p2FMmT|n zdNdIuLrF=O9B4)-C6Y&HlnqT+ydJ!X&2x4YTSc_}gYCy!Vkfy0QzuD%@8qTgE zCV;1sQt^ay)(gG~VnUKP9qi6Sta6PB3ZR26o%`R#r;VJ%9F z*J=KGv=S58!@EQYa~tt%v-a#7el=IMF+ZF@gLjGOl$@}nB=E|NC!kv`PN2an!|(WW z8g@10tZQ{1#8lTr_e^_FIvtHQKCzc|&VZvIR+=35@h>M)y zEEIex#4~Va37#0@C%DFs!*xzrVuI61@B$I-F-o-eMGLPLTHS;tCO91izX(x8xeXK6 zqUQL#Mr-aifxxfEecgt+4NFYeb~j-y`UYRoXb)OqqPret54OF=lZaPl^hvbDy~&;M z%J3}Y^)O*AKlwRfiHV4jNhbpl4bx3nD}SS6yp5huf(bJhz! z3w{foM(BA7YjI``J{ErGo)er|gP((V2F|R(AHi>7xyDbybxv^B1Kt;YAI_OI_>K4- zx9#PGB_)BUX|x_DxNfyL@q|5nVkvSPmYAS^_z5c5oX>z)hTn8| z6V~$cmJ^JYDOM&%OU|spD?_Y_=fOE)i3v`l!7D=yN=|Sh3|<*xG0?&*gO*3_oUp_M z_VCJ3!fwJ^-CqNjmlEQYp@gnqZo?82oLPfchPab%!dl#^U0LLW`@{C!A~|7+3GCsO z87-9wYq_6t8=N77SB7{NuQNF#g;*IPV{*b06I`?YjMZO3*am04;FaMwy{2;;mYCp_ z8@w|7TDP097BpTN?BxXK;^39x_sHp7oH!qcUzc;130@hZFLJ^X6P(Y0SBBq>cN5m) zTpV_a`5k{w_$$NL0Iv++kM1vyB_ZNUUQ4&HY_oLZM-t0r7~eH{@(Ue zZo}=)X)SnVh$8Wwa>5c5oWp`whWL_#_X zElP-2X0#rbnBa^QyfVZc{!7DS`=O(O`_s15$x+Cp=9Q*b6%Kk@$~nrzWVHb?9l)FcN6jab>25;Nl8Eth-Y4NaU%Zr;=MBh zy48B<)E$$JE%$v+*m&$;&P&9eD|~3ql9GTP5a)gC!)b^9f)_68A9V5=)ls`0SD(Mp z6SI1_ei67ZhG37Kn%}+Z$<=RfKc?Pix0Rw)CVVgKJ^a8~752IbOG@G$`z)zOZJ6M? z)q2@$PN+6p|Csug<5w(7Wl2e#{guVlcmlfBdi1SFRkywW$ogrU-C5-|x1=Oq(_2)H zC!kxce>wc1>X5r*FJqT$3LBP`#P9bzwHgp#c-F?L&)@s2ZKn5LX{~DWT~Dlzf78j; zhEqSA`tq%xs~-9NG3ok)$A75iy4N#-Rx5!%@TC1B3gYC-cghJ%OuY5Ylm>?8HF z9$Z}5FkvmOU-!k&SEGa_CeD4sboKo^4yrf0{l5wuCalHvt}C8gjS`laaI5DvH(@QV zm-okRdkjudI_kRPt8)&xd1}8sPpOW6?02ebwz+ZYnv+hgeslNF)AegtJiO*QJc%OE zY9-JseD$L>wC|J?mYDeAdbdoS`1C{S@9xNRWg8}}#dZJeldDm}5)+T!{YO(D-t8mx z;%9xSuwlYlT)*Jj&sU>_B_=-h+PkLyvCfC<_1^r6!iEWJas9y4PN+r+OHBAJ$lJ<< zwfuJVdUHprG7+UZB@ zR%d3oid}p`mrF_l8$+Uv`ppRF zRx9WkYz#{k@9wZvlH|nldMJ9CdJGA!Tdin?^!H)wCL2xb4kaZ4Js>#ej#4!}I3&1l zs};SO{yun0IOh(6r^FHy@g&yJJa4@o=iEU=3~xqQi|h6Y&3;YQj~K=DYmtaQO;31x zU(Ua4B3a|^`kj8?65ffH;QF82h^WS?CJr*Qm)r1tO++l=R1*hTl*)v)C~Xs?To9I+ zz+MxJToAq9OE+p_k>fcyY{MoNxr%7nsU{Y=AaY4gG%>tm2m%Bd!XxBrtkwXTWb?b8ZPymLXgP25)9ge4{-wsWe904;2ou$D`kKP4`E#E(uj zQNLsAVH+kQ8g#0O6CP74Yf-``zP2DNF%i+AQ%#iV7{XfAyor!52un;v{OD8@Wjcni z7H!zX_7()sRr~xzEb3GfQ``6RmiLDxCMaPOAw7?c_NlfObQAAh5SEyrrTJA)#BGlu ztmRh7>tTrro|q=ay|7`zS|hESX0H)B*^gh!&NPuBjDy3`nd^2$O{E$V5$Cn6iTbS~ zg6oPV>Nj0CF|jc!DOSH9k&MflsNX7L@Rl`EzY`MJXzv@beao7t-@-;&s+Nezw`EP# zZ$WT+QWIZWMa0k*O?+*-ZsKbT!nKVE&?}la;W71a*-b>m=@m_!@H{r!vRjK1&R?pC zA6(W%{ZV|;GfmWQVZ#y=^i31>JBF}U{6>7HiTW)FOHA-AG*Q1}2y4Y} z#AlkQ-@(&9d=lMjv{e)JJEjNSiYDlrChE5+l?iLPXY;4s<#j#cm+Lc4)NfG_OHA;z zH&MSusZ3Zaei1*@MEw>vEHM$0R?C{G-@=9oYem$}OcV86*oc^@Wlhv?6){-LnyB9i z-wzYmYodOOQn}r&)jcwJ#NlagqJAeVl?mRoChB)gsjSsK`uMH&`v}oQ{T4PXF%hv+ zGfmX*7{XeNmHfUW@-`HNB_<-~Yo>|%9Ya{l{gl5SmY9gBv}H}yZ(+lPwfwy0HX_pV z@+Km;;%vJnB6q@(!9>K`Ufx9H7NzpYkZI|=l9!4vP7{kM1F-7vEgF~YjF}|6J=fyE-y2uCQ`3* z{qoke#00aCCQ`4kVZvJUe-i;-5SEx=_R&P@jUlYXX@5;Lc|llWg4stCEj@;?7AGz? z5v~Pci3#4#CJK8DVXcUXooS+F3&Ii;Jkw2F@)*Ke-EXZWCg|BFdbzM+!diak^XJME z`lg8{?{|+3mYAT`oA~phR3@wyF|jjEv}{3GVuDt0;;Y9H){5xNnI>AcAgo2ZHIdi- zZo(21jIK={g~EmjYeoF%OcP~V5SEyr4V!EWV+d<8jx|{$3c?Z-w0aZiJ%+Fr^=sm` z3&LX`V{nuGqVLf)e-bSziSBx|W4P-?8#ZyY%9SvULa(8oS@P;M(rOmNK(J#n20QoeRk+$r?qHZ6V{@%?9k6&k5*y=d+g9t!n{432Q|j%Ram6u{T=~kr^`f_>QS#zjB8CN%kpYUol;?>&$gt542i|iO7Q4X9qI& z7{?IS;+lQ&QNj`vk(;y6j&ST<7B);+i<+}fJz8_O2?U-7?&~(pYi@}N+wLZ;Mc=SP zKiY$qnCPxY*@JE0FeHb3lO`~g$)zd z^5~k`n2U^&DXKB{#}-7!$Q0EWJ39*^$7G6Kiamm@y9sMW#>f=a7&}G_aw4)erl`i) z8QePZF{Y@-SnH;1c89sniO9{Cq8ejwW&yh??2E@9%9v8QBqhO4`e;2&aNTM}hRPJx z7`u{1sVp%;{n#U=etA8pZCgXvJhG;xs7A7=5c5^d`H`^kz3eS~1wnQ<&9 zEHM!|CR0>n?79^FVZvIBcI-McKIS$oF%dZ?Q&eN@9u+oBSj%mg+pxq$&YtV4^Z-GsHE z@!exDx8Wzz?dE48CoC~ROXCF??GF>y@)Mfd@OaL+%YHi}b@$kAi3#38_S+fra~meC z71UT4cFAL}WGeE__1SNay_u=Vq1k62KK9TG88^>!=hA{nBdF6e*5UG z&oz%cmVNdUW0!EsZJ5`?5)+Xnw9kHG?Ee*|GGVRAy4PnvF?Og5!V(ja1+mY5V(bNu zA*>Zy_fni!>=+e<+k{yrd-}{+-G+J1Eiu8|jy?U+xu^+i(dz8!&;KO05);hr*wY`K zC;DF2qHoyKr#JI@SYm>?9eett^F$NYqHoyKAMJBXOz{4*r$0JRG+`}zlRf>>KDWdK z?+ttUqhpB)YjwZpmYASt+0!3=2TfSZZ(80TeqN#3*=EG)es(P}!Pv#lHltl`!-TaW zZ(@qni=Ebju*3v!GdtUiuDJ~p*77$oCoD0+`_Iny=*VEgTGWr7?a}w#5=zKUGqv@d zx=U3O>|c-00DLd5TdjNs&_DIv>9N^!K;E@6$1p zdB)#&PsGIs-a2bZNk9*XwSKl&BA)!Obw)t9S`nL=Y!KVf>mB_34<_Q~WnY}Nq$HpR zL_{;rvfobRp-bXAMbzOe(TBto_If5FO0Fh4izqFwiM8W8BJ^rv@QAF-2}??XXu$CV zbgNb0dVjrmhcl`}Uvhk5!x9q_n>b7KAu)xcrSg5Bf7!=t?%PdRf;|&NPLA3z!F8+E z-MW^P1ktCX{b7RZR?9ux>qRu<9DPo#;*~GDq(1!jAFZGN#kXWV=$_4qh+wRVgCz1W zq6=%{5{VGxnutTLbHWl6w%tuwi|b21aY{vLbHWl6-Svog&6*faqRqG_Qj_aHzv5H% z8}>M%di&~+#F*%|vZN%IeeuKfcmlfBavSD0EGY@%M``tL0=m_5OZR#aF5c5ToXAtYQqu}?*H6|32SlPK5r3qcIkb|Ye`ffBXv6>M>N|k zQEkMqc?2IN_~I~zo7m>B&zRld=;P|%<}Ztm&7pU zL`3_|67@&KUPKqp5@kq)AO!J|ql9hvzTJc+Ca_1WCHC@CnXr~in-i9l1hJOXubY5w zwcOGwYGfaJCcn*?zC~}p3u8A5jU>0 z_najq0X-n@`tp)QY`Er!GXlERil;x>i1#FPcYoU%iTL2@A10&2P*M`m1LD9l-kH9G zx4-ee*`K}U`Wa?2-@oMUifd*vTtDZIhi8}>{AP|g;V!~jTr>9>B`h)V);Bz>W;Ss3 zN>7Ly*oFyfam`F-l(59az0cpaW;XD?1Bny14HMSlnpxi{VTlR1dTzsnwYXm1A4k55 zSkcI0{*hC%K5*Y`zVrXgFyq*62~qJTEGY@*C8I=q?Prw5VW!R1aMmTa%`n5+;`hvV zZNn016MT0^2};#kzv!SJ&rHvpSbcx(rIkyY+pxrhZFdvaf``6gZ2}?|Hy}TZ~ z|HpIEYT}SPUpjr^Y5UfHI5F})9)DGJ$DiJu<_TLJcu95CK?kS#!-tN)Hf)%%!~}PG z_r{TstPP2@gzeR=(*TaOhxMt2UN?2mz ze^yw#zId-T=|l){DyYjORWZ=P6<5|)_oQ<>Mpgthz@^m^Ca{^8W;U%c`3zI)Jp zu=~s7Wqt@@u;IX&9Mk54jZ&56}!V-UR{O!sK zm&zsK`sA|?uSZK|iHUuFb5xqitiLH4Xk022*5aC(%qU@ri8J2u*_wIDHTV6!uwlYl zTr+bTB`h&Pt25)E)$@9ou$KENCoC~RKQT`n?LiaPa&Pu}nwLyVGOK=`)ofrko0m*m zQWDIZV_p)3<|P>c-D+tz5QOF>)0UJ3bj(YF(7Yrgpj$0{)q>ExWZIIFfM&*@_F~dI z$WBY_rlcJf*0EeS*^KHl_CB;e_5Yn#-L(eUA7b}rNLW%58=i4^J)VGWwPG(O?c%V9 zlH0JvMC^K`c?r7}IpJP&|HmFinwPL!krS4bM3W0^3<2G0QK}}JRY6!%5>1|}F@$SN zi!e`|zpYw{3AbC?i%C7me#2j0yl;KZ#}BLTKL5(B&;2aqMC=NrJsH;jvHz0xWLW=m z-DH7^9*q5-p$$t+*mgHzEw0yH_tc8g=7c3Cy6d5D5qmN1{Hp%??CSNFo19o3@UhPq zHY_QL!#Cfr9#25GT5iL<9+s2@vn5)+n}BY$+|p?;W{&wTdo!{BGSg(RO4m)!B6e10 znk-jgBX)0wgeA}>nANan(@j9PTCwXf)8vhshp<+YkBYsR4#E z?wqj11lP;QcH3~Tx&LFIWTwe%Rg}tvwYY9FP!)tFCSso?%}dzd$m?OkT3k1IqYAP>E{!iEWJxo>(s`EmN%B_}Io>(i;_J&D$pAE$3gNwBUB zKTZ(x<75PMtHqa}r-agFew@A~B>_DkVh^LwSi;JFuZ^EM`mXriv>QNgexNfy#*CTmP*ty6{Wl2f!Js(d% zw_34#lfLKdz~nY8DGBy{#uL!3R_rgO`5e0yxeZH7f?cWs5&I-j|G~;$yUR1$b)JbG zi8M1{WuJCdhJ+<0!S`yEpj55(6*s)N-e~%y>bZOVV8*4*ZCGL=_F~e!guRY#!dlSp zeA9t7_Hx1!6Rux3VJ&F(mPSiui3zTkw^i(ur0)m22eAv0_DI-0h<%H+f5FO?YrfQ6 z_j)EQf#$ml?K|a!B_@vh=Ee2rw)<%P;JP~%HcVKH>-t5fRHK9?CSunk?U%4~k(bJZ zwYX-MF-lls;$0Vgy1r%eeWM<|!iEWJalOlzPKbJxge4~Y1; zoxvK~-;Y=)CqE7=Vt*M%3C3F1Hzr~wpFAn7t-A?pLGvBNUQSqIf@{9cqc$ut5jzrT z2EeXDZo`DNxMufblZVl=tzUoiw`a(G-TdBTCOq*~ z^E;6Es+q9F1b6!Jx(h4r)J<56J2k&MDTuOE%zfCQu)W-dC0w^e{Q9D5el1eiFkvmO zo8NvEge4|cdD5xX4X@d+KIX*R#}L-y`qr&atVRh-O!%qHYi`0?T(@sQ`mI5lm$2Uu zdl>!ZcNwe)ha+n2Vf35dn#6NOer=u-2un6U zXEbMX+;j2X)0UJ3be!f9gwFrS2%XJ=-zeFRFLn?*V+8NgP*M`u7!a{flD<*wX~fP$ zI?aO}1DDG6OFJt=BG%tie92hfa^3t|q>i=!6kk!+>^WgcNi@GN8ACv~T1$SuUiI_a z&a7Vd`&Fanu1Bf0_x4BEXmt~oaNQEIPm<36V1FaGVZvHmGe;REEHU9$&uy5n7T3(R z=%<{p#6;eM@k@@>gY27p;8ow9+WtL<)O+lHZPtVC*|f7VBw{~gs`*t2I|NhBuTau; z^9zsYLEAv9m6)*YZo*nzFTDQbiqhtUB__J-5qsY4*(K@suFY>)>eW7Q*VM9=PN*(B zpB0PiVF|Q}Pu=&SdOQK$YPk(_8#L+n6MVt%q#~){K_Kr2m2}=B_Q* z&F@Q!npuJA)c${{Rgnm!+U7ir_QdHS~$*d(M!P67_B|&JvBqN|(E$vbSq5YCsOG*Md z_Dh1$eo00^w_2Ko2ci8EVt(5Bc~uh7d=HbSA=-HG1&tX@T9fm=;F_5X*H>-waJ5&= zEPwZz2c~kul9G7%xkuLH3FuZUW=Uz!fq6@A!x9rQyGT1B%n)+IHRrmmZOj$Yz7Mm4 zoUo)M8c)+00=m_rRP6hVmdcWnXgp1Y4HK>{Ey4_N{)5&dEQWA}?s32V4#cP~ZUH;WLA#Ky=rFyjW%Wb&kCTzQ#uomxJuj6dCTR7>uU6PF zVJ-JfueaYmYos@7*Hw0$<3x0Nic`&hbk9xc`n*3qq0is>Uh(%{?}%5gm53Mq%Nr8W zN=&@vs_!OxojV^N#8W=GP9lE2`fD@7T3_DsC&|X#QL6;8>iX*^;_Cl><(wrYL1_oX zb2ocdBDP;^yNrNtwchpNUnU!WT*3)he>!l(MC`cZzt34x63_!;w_j|Mh#hX4$_VII z>&TlQPB!A-=#Mw7u=$`=e|*WDB_#npAh!SGOA--eMnJb(QJPs=J?;`VqBMz!(#=^? z63_!8YMh8a9=KsfK(|`as>w#QM%ai}O+>WvoFydzJs_gz5)nO_5zwtxJRQkK^lI3+ zfA!ZUBA%8xOH9NQnCN&SgLwQC-k6AQ{qzYLVJ)s{s{!$~8~2-Igj;)y&&*zY-E2+% z&8z=qmHy&i%++M?eAi=EE1q@}eh*AM@3&XgLRSgooI!@8)f1pUp~F& zJg@kd|EtMn#PyfYKEEbI>_)TKM$JuFQW9i{9VJ{3N=3$2%I+4)ZCGOB&ik&c$pgE~ z)tn&dQkk$8?M5b7S~@2_^Tn^!XPUPa{ zPPq*e)^Z!>gv(2v$Ro=Wy0}-svy30 z(->?Ss`@zk6v-_SQ#l^Vf7u9#F3HQlZsKO!U8ZSxxrVWtabB3}G#<$=*6j zSYqONKfF9*vyQD_dFl#9Jxo}Onv=bCwB~LT2(q_wU$oR0PGoQ8S?DIL%U%;z4i1T{h_d7!diYG z(|8*_pKMLX$?vmdD*M*Mv&<-lqq9ftoVfZYU#vMZ?7??N&fxz(zvj%aSG;I(RnMMP zlZo+~$iLG~SnHEN`*O{hVc&dYNkRPbvc)y0aNU2~qUvv#oLO_e*2g|GxF#Da*SU@T zZ#bvsG_l9+cxLtKYtOF9_j>wDXO1bAOHvYKaviOQ39ehM?=M?Yb4JyhHY#gwi3#dQ zzE|p(*Mr)&HFV9_y7-KmGtt)Cwj_4_=D9VejD0Bl{xAE^c{Qhu-ErTU)dg!`S#!$R zt6zRzVZ#y=^d|XU>CL=UCaiVPQ?9N#Wo(0=mNqOg!P7&&SDv2Sh6!uE`kB|(w2ts-*q+lULX5^Wj!o0!TUkJ*U|UG zgtZ>o3rPb4Z^R=2&#`b+qWI^m487wh@J@UPdmdb>+y2lcaQ9SMBd*%J`o$`8E zVuCk~e6PG|-GsF~D&>UVTEATo2cgtZv$$oI&*ubl^;TkH!>=x?InV3dhfXg_^}fAB@|K0wP4}E$p+&w|v^;9( zHY_oLJ@UO$!fwJ^-CqNjmlBfil@hvsxeZH9T=;@THRpN#_IqW`O<0S+w=1OFhWo>` zTO=neF@Zg@o{pBvgtgpHxebqMj6P&NWxVPh;Vd!1lStN6M!wvJ32W{2x*ybJJ-uTS zGE?|zx5NZbK3Pvk-;Z(*$6A&Z_T$%HWtMz&`(8g=*s#Piy#*IPewO^ZTO4rJ7{Xf5 z{_JYAoSe1aORg*kmzVdPJgJNyu3vY}O)wIXCv|j$^S!LK-Ft7Z$&>nlV=pX9Wr+z! zRPv;b&X)f3jE8D+%Kmxo8`XiI`9n=k*?YhC_3HIsxxFT*>@&_NZCGOB>nr`XCa3KE z7hGJF%ET$Z{b@}u*6ly@mCCmBwz9;;U-$iaO)l1rPX20P!-Tc!FaDz@7whwGzN{cD zF|pDS_toTL{ma=GjUlYH(=Lyi1>mi(IUub2#72TJ#OMSn18Y9+sG3-bF6f(K(z6Ytc94Vjb;sOH42- zk&AV74rjtz^d`AjNBi6o6TF+`VjUgfOjxV?{jkIYJxeau(f8bhwfv^#{o&^onp~{B zsol@6B_??1$;HYjk=rm~t#$8t>@25@t$F`UL0Dpfx0zh5j7qr;6V_tP=X9?5zXq+u z1n)n&SVu<&-^*Imk6f&y@43Gde6KiVj6DZ`iSl|_QW9-xy9t+&79scR{H@zcOyu=o zucX&IEbVR|bo2G~jz2%Q`u39N_FwbBQRzDVP4g@M9&?rGkHLQfVuu|*KZWFu4YupY z^-OymcifQcCtkRHT64h+h>y)~Q6YK9{?oGuthQgeUhUdyc9jDjm9Fo3VB6WoL_>sD zDhXP{>;Kq#cFQH(rN7_3pkENS;rqUJ^L4fD2&9;|5H=)qZfj%#|7p5vO?W=^d9FSALq;u)LG&YbYwbiL32 zZ8Ur3D<4ePZ#nU)g$+wg92_C!*m(bfwZ{Pv{uJS}IjRSYkrY^cccgYLSA_*PySFns0j=+xa)Ixg{nvj*TI# zrE#SoEHR;xuOQk!pa)I2f2TL|dRSuOpWEPG*3ws^uwjV_eY^U3sbb7a?auS{xGx=^ zu6Mb8s=xo9UrpDPIwyQzeWUu_HY_oruV`VzgthdYF9=Ia_=(BuVZvIPeH1nhsUD0FIiWdj zU$bTA@M(t3d_E^EF`;?z7{XflI$>aCxSB{aWUQNr>vrZmYQw}(OS9#Iu*CP(oO%pl zt!U|*rzF-T1rbkTlEj>vaW`G_CdXTlu47JJ5SEx=p4-f+#}L+vw>c3pr!ELfOvEUW z2;Stp&rMh>M!rPEoO*Oj97;???bF|RlXDxsm$l;EOT_5d9^Z`AihMibdzG&FZkf() zSYjf+49N!Xem7yQ?owGYAHism+c42yqZPA(RH~R$7lb7y;(L+^MvL5r32VjtArXug zIbn&3n6FGgSSw~{iHJFMVS{xmPc`F6j7{m9v8t_8%&7~)_chUN!x9s=o!8uiwPG|% zCEVjDoIW)8Z!lh2VuH0l^%3GZ+H17b3I(CnMD|>1olra_ zmiW11Pm!AQRme+a!djFJB1&2imYAT8{y9-Cn<{LP1z!B1WZDs?jmggtfHCQP{A=M2x}7#%K?kuvUB}5`ot#uel{A;>(bT z(OHHGYsL2}5q!OK844xZ%Lz+N@B~8eR(BKDqE#Vy%W}e! z`3S~=Zla~p;%&u7jMN+Dge4{z5e7u7-#+aotku%IWi2y!KP;J#;H~Z^S{g02LP2=P zYxsV|&W+yxes04O6MBQk5Z0n(v{jU}AS^MVk!TE2Xl;y*XuqQ7QLCXOC+^w^BKm6# z5$AjiwW74C&*!a&B+H4gr@s%{cQ{fHCD!7-pj6S5Ma?ZS!Mg_$Z`>HdTG5+{7~Q$E zWL{#vz1QKrhID9Y23VBJ5)+y~jv=h2nPov(VnVa!F@&`=pDzeYOlS^2hOm}a76oC6 z39WbI*?s@F_e;NDIe6XAq~9=XeAn5@hja7MH&v@$aCUXn!u2!%*C@gB6W@uxi7gJf zrn>L%ORKwHOe}I~qb01R??+K8OH6!k_NwZ*DfhgfR<*&)iS0AtdtGtmY_&`Lp7vMktkSpboUp{i zj@!;wYdvLYwe>bD7dA{-%O%WhxV+C<{qpLPhnG~>@6emDR3;X@?$YY)Pc5ldTKveE z{;<|ACtgw=vi_3l8|OVx5SA=@;Nt403l~?nt^GUZ3Kh=+|K|0u#Ka$Wx~STtT3qdL z)UU=6)_UuuU#-4zW5hE&`169WzxOEx%$TcoKZdXhqo4lC4c?N7po`ld`5M^%f3HhsZ5+zT~K}ECyT0wFZoVk z!=lS~Z+V!oAsxvmau^=pY>BHw&r^IhvpYrSLCM=bSh`On6d~%d(*Xs%!E|s+& zx5D|=eLp_Edh01y7lbAEY<^yK%fi#EtG_!pVW~`9`;K#~quz9SwdqQH&%1iiT4$el zPPNuLr&p)HlwU5Ju;k;{o?RXBgVU zR{t8&3V-<3*NReo>xql1TXtVqt+wVF)xD3LUR@heDNnjAMZR>rgC=b6q?a$Mes{pa z>cOjtYILc5-xYp#dUe^G7FN%C+c+D(uZi_L}`u%rKt$w&Ou^C;ZvQ|U`R`2`dsnxb85))^_k~hD8 zadq*Yr&b4V_Js*cW#Wckomo9LVmrU~En+Qg!);})7aehC_0H#=THU)ls}>WMocH82 ztD9FowR-ZS&zZ1PCZ2fl8P#^bT3Eei3BEhqaH*_yZkh>;bt2ym9_Gx{jm#QHOEZ+&Y!L~7kkrb7ZBes z^B=xstd0+O!IS&UqTctnKZT7SK7YqV{Gq?boFyi>hJfz%o_6TAiMV8)4Km`hE3Tci zmYx0&ekVG#9os=G^b>LKXP%#x%EXT!vudLGH?pccddo!cukU3o>P4N9_j;6{no}Rj z+0GNWZs&8ocK^sBPW|o-9ZBSzfTEK+0s695QTdzlrA!q?hOt?;QCQ{6EA?SPe z`S~la-T&Q-BU{TeuFHPIloReX6VG|{Q~K+ka(4Be)A@4Rh6!useQx59%O2f-^k>hi zPF=dJy6~Qr`=@NWv|96=+2Uz8VXc*)6j?7~F8ZCAle&I+sVp&Z%NlF+_xr}u>bi4@ z^Rf*S)^aQ4L_Kw5^|oCWRac#xk80nz^}1@?4Hs3X{fT&I+pxs;xL!WCo3M?yU4MJ^ zzD>@op10(}32Sa*7ae*DHWtHa~VkeA9OvDPYI`c-xOOBYvL?RHT?tnk-|tM44X zq`Ki5msT5W_>byQcP**@|ue@aapce_L|Nm{M8GEz;|Kbgw_hyW8u1|J`q&X0L+xnH>tQ z8B4hS@8kY8y;0LwKDo{bOH8n{0?kfKH({;MK5?`3&hLKB;|pSXi)W;FaC*brXYT#w z2I(EV^vA!SVTTAC1FwwhVM#`;ygc{wyt*FefZA@$1FUO>gZzH>_CH z!-TcEYku~gEB1M7|M#LTvf6ID;|hJ=+9TF~Zcz_QvN}au@z##Em2I5xtyTNHwM&jU zBD0s*-1jx{&?&3+d20_@`RJllCam?P3)k%P*8cRJiwfe7XRO!ft=)9JdglIvpVH^8 zebI+*n6OkPR{haa(_8zQZ{1SZaH*{2=Pj?f%lofeKe5kSd)w#EpRiOW?z(QBK5y;b zS6(!xRMv8fWTl$ZbCq@*o42-l=#ee^>>90l|5Kyi^?uA*qPI5D&HG;vx5hicuF8gs z|1jlt`}JxY_u0i+ahpe`avPSIaA~^SijFs(Qn@T z%?V3oV*5SU>$6j|=G$ir8!nZ#&i~pveRhgY+x?<~u;itYmyw;KQ~KvmSSk~LU9@JO zouW#xvfr|9+nx^ZE{rLxw{SN@T9iaz`J^$Wt1 zCvEh%v{Q8VFP|`BsZ1QO=#jKj^s;LnQ`m5+to7ry9!fh!dn|ZxLH-U}QXThT+9`VL z@9$jTJLQBWCeHrHAJb0Jo6o(muwlYltL*>#v{Urfoi8eg@9uR++9|qe*Ne6~b^SZi zPSGYe9JQ72l$XkcwH7?#&a_kXo9iF5bx!!c@BG&7X{Ts~w{0=ThVN@)lY?$gJ4H`> z+eI(QZJ4kYf1h_=GUqng=hweUJ4L&!v1r2nF!958+@E%e-gNCzMeDj$*4paFzf3zt zAOGX71!2kiKL3lfQ}nj;Up`@}Oq}-Gd(%$Q3;uJ9!iGy_t#7V!PueN^-4oU?2umKi z?&oQzXz_KAnXptQHah(7v{Q7@19uiriA!azH%$F3?G$}_mx~I*l8^r7r)j5Xzw3|M z+IQ-HN=%%8(Vc0h=&ieMQP}Xktd&3Q7a#c1v@=ofyGB2LBb-(y#7t=JQ*Zx@e@|sw-i>vpx&>;2-Pk0s*FH(pwqxO8T4->==b_l#}#diPu~ zIQjkfFTKt&l`|&JJAK<^qt|=F`K;0oOE$Rjy{x6b$C#*k%&NTEJW-_$LTxo`iE8fB z2BDg}6{lPh)hP(oytc%I>lD@9>a?^P87>#U=6g)gRw~^Y%-tU%rF2b7`X`tQEf(PHRs7%?V3P9P;MX`y0ou(bVtBGhrK+ zEPc4wf6=>^REItN%fy0AV8g_wANX~3_5Yk%z4VRjI@^ZtWv%T#dULhu6Bbn~+{vE4 z2}{=4{PODZbxx};d-ll_mdeD=TV7Dz`L%`Bn(zHwVZ)`e7JuLU4JRdAz242$+tSm1 z-zksGy3e_8`{tLwdO>;?ZvGV6dOrM~!Fj3AfA0OWmY8VQ3H&Cj*E{YLgY#1NdeZ-7 zgthM2b<1Sqw^Kx={CSr>Q>h+#`%SZ!n26t~r4sVnvR>~SU*9Vcr>`}e5!Slv)h|gl zo^k)NL9DgnJ_8$1zi8GH6Y=}~WFvlg5yaFF2WRkH|CiGUgz<{s=k$8NdG-Fu z#urZb#H=MHK}!#aCvEcUv|GF5v)?(*Z*7pUpTIS}#`Ur-epCH+-P5YW&)P2Da}%c> z^!Wal;*7IbEWLhe`tE1K|Ir1J0c?+T!)6y@t+sFY z)lg1YV&d0d+PuH>=4V%*IAW7AgtchH`P<5pl33m!u7_LkQ|tVtT5s*st5dGod&(`6 z*TWJM+Z@pAuO09C^LPGa(H|zP<$lU+%ZDg(pXm1K=_Y*N+fUpejnrR#*_w4uSYkpwJBF~;tn9#E@hOidb%~MhkZqb)VKQo?hzw;-@w65F7#GdQ^rFum? zV{iG^-ZOdYny{9ig>0nmYpf;mC6%3DJZU_RdT6B12y3X+(bDc_-KU z?$-Oii_=bg7DMlr}FaIHPiRwnoBP&2un=Zc3uw?)>{9ytEVsA z>+bt{VZ#y=c|Dlth9&xC_ShRgS?#dXDb@KWoSs^=nIRReYl3+$V@A|rmYFd#sCEyoDd@FL-*=0-IjM#F!bnf4lnXM7-vz_h*E)R=x4WWaF02Ulh9A z-2RP3T=CSsr!6tTJQo`=W`^$6;-!gr_w0uAX~KUFNoYabgxbVa-ik^w83&_icDab>uG|Gp6R&a;v9O zrIDIGXP(Qb7W3Y$B+ObFMPsfyurVZZ$?{%{7OAt=otLl{b5O?ln0Xd9EHM$Sn`{i9 z-JuN=*5W#Q+J}T|e)U$5t3Q3rS=BmoPtRH*Z!14nCRiUZw#V$YsD}w_G3RB}ju~x1 zSi-7>(K%+W+56aCDie?W!ErPUwaRNAn_L|zYijt-<>HeLTy^$-7gQuWY_j!iAv_JQd^U$+Er4DTIv;F@=W z>odN;(d=zMKD&Cy%GWVU$c81%rJG&nM7MX!3EMEiT)NqHE^L^vR(CzD#az1CX)c~C z*TeTR!Cbo8LoP~X!dfdl`n&Z7>o2N4yAtQP+lD2~rJJ4R2}@;yxpcDwUD$A`tmS8+ z*L%-pA53rU%8S0x|KAU8nfm#QJDyxKHqmR0Db>nT>F?jV@ZDkK=r;~xu%7qo6Z)2z z;EM^(sMqWL_M7`B8(Ti{*o?3i*F0kb;*KxwmWU@U`vbclNzy)v?Xz^#uV0w{K6B)m zVdI4tzB>^gdivdcOZ>zz!-r<1>-8>J^u9zK@Y8Q+gtgovz1~hSdh&k!`kgmrZDoS- z78{JLai(mH&=6a$c3DPP%k4Ip8AHT;agLdBvscWXRT_6=4|$_UcD}WK*P|9z&;R*P zm*s>dCb;IEht3JxV1C%_g=Y40!uK`79J|@Sp6Mp6b=9-ioPAIHx^26Q`Q;h&!?xy@ zFkf%>!i(r-6E2kr=IhN~c=SgXVXd||nF;2EB_{G`*EUR8%TIo0W15*UV^qu+(|U$y ziC$x7%$OMS;rQROF>Q%kLAJ*b)?#LyX2|DG6@(=wRF5%)wbTj);hG<_?wYd?Y_qsJ z@#D8lxlVb_Eiu8&xYL#qk%(&SdE(lAQ88g<#ym!JjC0(g+^Jif0T)>bvgv_N*l)+NUzc_8{~%$OvocyAs6vo7d2X;+YI{vIRM^106(bIoQ~Hq9a#uVOY<=^I=SmN4&Z31*ax zS1~IbLs&~+xPq|6#5U_~Jp1msv#Z^8`JXZCU%zORXMVn((!W@Oi_L^PmFWx`tS*=*k4XFk%b z6#KCwoc0#@wFQ6YDTy|V@0nIbnZ(2<=UiH!a`e*b(#30zA*|)n<~A%b5qryNhb892 zg$+w$4>|46@XHI|soRE$*iTL~WPV4{O;{^-htu4b-&Ev;C9xx%#$A3pFOP3)y#4a{|GnP%XMG?etfd``(4A^_Cib{%pE*lRXwM;tqn7V}WQ4Vt z;q%_aS15@1bww%_K0HfGf;VbFFf*ne@dcfYUCx|gFc{Y+y-u;}J+hRBBmR0YK zznjP<%L!=uJifUFVH>e8I>YG0?*VKtw_%Bi*cY8?cB6xKsZ3bwH-CLxedi%(Rli^V z83kcU>{F-x3w{IQJ9XPI5j)UnFC%8Og$>`!TG}Hm2un=3XY*2-uol-@pQm*ceZI|` zc3p62_y-L*}3c?Z- z%-5Tp?J-2I)m0B`u|8;a(&N5ege4|ocX+DVLoP~X!dkES5J)AV|*0m(| zlc$=U<_Sw>f_Zhb13h>LhyCGFSu1}QFXoIMh z`_(eSTJq2ZA>ZAcB_?7-O*Udi8$|0LeDziD&j@SD(-?$&kaL!pU}nr)FnD(5=gbIe z$zvKeJ+Qpva7x5Pwz z&r_-Rx0|pQbN6OPxUgY~iP%q0zsum47r6~)#?9_IvzK8>o_fH>nIKY~i1mm`AJZS!^3#*o+~p-wo!HliL!YozCWurg_BCSCi<-NwtmPKT;^^nd z@?jUlY%`gPaC1R2`!T5k2+hTDW(XGF3_ zCbJ3q!vwj`h-8hdW@AcaEpnX^$r>5X3c?a{oe{|znan0El?ig45y=`^%?cZCt4!;` zpQoH>k>RW$$bv?UD-v>@5y={v%qA?A338ng$r@SB3L7q!wa9fwBx__iD+o)-bw(s> zWHOtuR3^xEMkH%wH7jhmRMsNb8Ii1!;jADmA=ep^tS^1|{0U2Cf?Q`rvPM?3!bVmq zX_4!UoM(~YtRO5Q*BLp_B9qyKr7}UTGjg6qRz*l?+=MXob)o<*Lof*{u!InN@KSxv4pa-KzwvN5GHVSD5{Bj;IU zgDPzJzT`S1=UHSj8)L)wH9@X3a-OY!0~wUNz6RFfPRnN*Cfp|EIwR*iTi8&x zw`ogExK4vSOY~sm|ClAW673$bwdtA}AlKwsVm%nym7?ZkW@-sblt+428Lh_<)*{am zE7r(9R1%SAi4|nz!I>q`5-Z5aq7+)OGZrO`nCqyyOJ#`(@+`5MjQmK24HMRK33D5k zm>|y*YtCOUCZ@rqGGVRmnv-XVHD}~R%4$oVCDxpgU8%5iP*G9ggthVG?Vyzb0l?ofVWcicm(&jcy zSc^PMtT`jQQendq6Ruxw!}TD~66^EGqLkGsC;XI{AkPx(^T?=Fl*)v)$g{-yJhCel zgeBxzVwDyCQX`{MVZ&`@E%Gd}N{#GF z1z`z!mRO}m7NrSGWr93QtWqPRQenfTvKD!kSfxgGrGl`8JWH%nBa706r7}UDC041C zQK_)uQduj1+R3woX5gWoS%QdsMbnmejl=cw*%En{AR_xv zMv!L-t;j1hYumjZd6pm|`%qRY6CpkiISH7Pop?-Y z%Fe&|H=E4dcr#Kg06vSHu*3xZ%_cMV7{XfIiMATGfq%2f%w6N(Y%+7RCo?QhUMk<$1pZCdoZ-nVN@c=Y_&1x(+y#Muv&qa|Qd!N1v@?KEMjOyJ*a&UPwnxK!4{zuBDaR1lWn z-)zoyny^$R@NYI}I~6uuDr@22Y|eHn2utv9HfK9cSSl0vH=DDa3L7q!weW8?XFC;y zCHOa+vz;a^l?nWt&DlM|j|7P+#ZFu_>{!Lbp;k_geeVV;e`rL*k z84+F@R+HhEoa!d1ih5Y$ zR^Xbi!Dw6A2L8?FT$#*XUUT2q1pZCdoZ-nVN@c=Y_&1w#WeNiSW^=C06#mWTT$u?= zWdi>uYtHaw7B*ZeYx#N0Ywq&m-)zp6nXptQ@NYKf%8V(MwcH|EsiyT@)p`eO{F}|W zGIdT^VuI`D{Vxdoo6Wg0Gj2Eho6Wg0Gr0{*Ot`e>hQ*vgQo0W>G3jOt^lz4c7zz zW^=AgR;QeB*-hZzY|fP_YHq?>_&1w#WeUO){F}|WG82}{1pdwDT$#d#OJyzmo2*j9 zt6311;NNV{m6@d^kmf+uHl^Wj52}@-H|0b){@MIP?TqPS^ z+2g+W^K5(I--HN%XKjfI{F~5mqRfWq9+qryWx`tedyI+rH_^s#tMX>^M3puOwG}7o zB4+>$>%s86 zRS}(;)=}ZTEJ}q(l+h=idd>}RJ)jv8k(y~86`sr}RTp8ch+Uj*;yDXK`-WA-bEegA zcrTORlQBQu-g$^tVgmnW6VEw@u$JrBT@MoxshQT!;mIs)_+Hj>tLHY{CJ~*PR*>Pn zoUlJkM5Jc&bA~5#OsT9DQJcxn8D7nTuq2{0lbDiaZ@nf#pL$t-NRRMv{9&E)3{uVz75649B-&l%p! z2}@-nA~lnrGd!7v4VTJV5w)58oZ;0h2umV5Gx<5gdpTjLOhi0q@^gkKv#^nsN?H-M znO2bD)hq~0B04jzAj5k(VW~_+q-I({h9|SI;Zj*EqBheCGQ64vVM#=1rWIs(FDERO ziHOupE6DI<7B*ZeYenp0T0w?yuOK2iGp!)Qds#)?Wm-XoUvf;TOxRvTxTO_jcz_BU zzAygGw1WKEI2*pNiHOupE6DI<7B);+i@z_QW%&EyHi_uWw1N!p<(Qh=hKY#OOe@In zWR5A7wIXUWtsujzSrC>)bY@yXhWB#9QkjTI&9s6HPiA4m^{`e%ZKf4ucr^>cl8DYs zE6DI(PFN}v5viG0km1QJY`9d`im1)Bf()-_L0E!+vx(=Nuv8`@QZua}!;@LqaH*`7 zKkaxcnaL2{=+%VR1M<+ttOrjb1QC?-xb@|!>>s?`qZkA}R0!fBZNvA?3Hb--EHNQ3 zVA#MTiVfl+O<2pN&HS} z8NSG@wh^^C)x>iaHgbvEr?)X*gVDCKjfl>iYT`LFdwI>>RwnRoHu0QAsZ3Za;v=V; zc+P@|=*6ifp0gj(nNv+X=Y*v)fq%1!=PYcvRMv`k&f)Wx*WBfe=*+1mo^!%dnTSZu zsV1ItOsTBp7D=T_?>TR6JXdK28J<4g+H}oZ8&Qqv7p>v-8`u~UmYCqWegAVC8%88_ z6VI8|HexVmnt0B_MlM>(ybMSQ@jy{&)-)!PJLu>gc(ftmZz`xnVa~3vyFKgl7Y~nc!!V>(OO+4p> zr80qkvx(;{Y`9d`!oS(Xa~1^t%_g2R`8S(*&M~DjVSD&Dn|RK`27c4_z7d^yIjhw0 zUXHQh`>(yb4;nMg@3b&=PU?I@NYKp zoD-JH1pdt?p0lvwwz3xf%_g3+AS}VZ*~D{BSSl0vH=B6Q!iGy_E&Q8JJZC{zf`7A# z=bW%qCh%`I@tlPXm&#iC(~h??H1Yb)d6mL-JKs_4BID!mzr*Hwy(>3DD?D%g@Q%)~ z<_I4i*KOov5Q>A$Z1}!8p*YAnOH3%*F>K%wrC<>UnGw0x^3rB;sg!CsyW_fD-QmTg ze&N*|)FahD{GD@_m~bm3&n|t6zcVAOg?|$p;qM&OBN5cY5)*E9?#_SoMX$HR4xgX7 z>$RV%@7Q3weq2wr*Z6|De&U7Ory49L$X1VJwQH;X@H+BEM;__)_d(`*^jjON9Pp?l zx#xjx)0`TbIkjyM^jpFb+Nvd}6W2U3-GsIBIt`d%&4;x$5!dPO^V%>m)Qb95l#2T0 zrLx5LjXEWQR_G?IMFwqb(CRtyv(Ifai{x)>ZJRvqT+?QU{A0WH_ucM0awaD%i4r6& z2z=?#v_>~!E!}CVlSscvXzwd}GGa>gOV2rW20h5xKHQfK=Bh_J$A-U?r#>$gzu#;n z^AWM`8AG%*TAWwJod&0j4Xg}GWr+!XMKU1TGPU(EVXc)s6H(80EEz*sOYh1k(Y|*fS$t7!olH8(znA70-0CG4J~^l$eO;IQ@Oz_hU#{E8ed3_tEzpPYgZ9D8rd* zTr*nW3*$QeEyfZ{OvGsniQrU*!86i+IZap#&lWZq!*aqB6H&563{LYHFoUNg#@$qQ z#_$*)(=}tQ>zCWG#6F; z2Zs_9ZuQ)T?`5s{GNe24Ey)Q>Omz3432SvfyOx-UZ&xbS=+kb(THWuUXTqL~cF%V$ zG2wY|-c}~8b=xjg>hpN_i#N&=6P$6$8#SJ=)`_>jC=uV@lixE8{u{hemYCp-OKk8h z?k23|cO@q*nU7!=(oM89THWv9d~YIYF#Dt!OF@&|$ zHw9sd2|Yby2y3Zt3c?Z-dV0nX)@oat_j3OJKr$Z@BXvROY2fRUo>xX8eM<_$5)=A% zjUlY1k!Uurheo)RZ>Rb8&1!Tl2un1IlFK{Qi7!NM!-Tc;T`34lOz7(~hOm~tqD5O- zV!|z**TaOh+NWf+&n+?GXCb#?!dmU$N1sIZv-_jF&n+?GXCW_@32RXro)}7(6PB3J z*KQ19EqwCn;&pdc(Up*j2*!dhCF6oe%v zv=$jd6k6xe=j=V@HIM%_loUh{g0EgTfuz-n(pK|7SEZyS!rlagwW8G%!B;OYl_e&k z-4emKv74|~^kyPrtyU10nD9PRZX=%XVGZN$8eTK!p%wV*<;2iNJk`VNC`mVAiHUgf zlZ{y26*f#*%cadr6=Ox8@-kYs*Nhf1+NHlU*5pL|C0S=YjPWX6Gn&TtF{TQTHU3x#6*-V)q{~Ww_(CsZ7Ym^Kito5QMX8L!x9rQ2B(_Gs;KBe6V`IO zHcVJ6?wttc5qUie#q2y0@$MIdB_?8i zJpo~@7;h87S1)hf7*~^o?^CP|(lx%RSnsCmQSXu^Ch$oz#_aKvFBSeM6V}q-3-6Nd zi?66HVI{gCEHTk-!|fw`_*Rm=(YCV0gzOcqYr8CC>TGV~$Jb*qY95n6Or4B(A>u z?PF_BV9g2Nm$>R*oq1f%39hDd!V(ii6#wnE<7&==?Ix_%U2~#(S32&PnzLDn3Eu3H zV`@%wwe4;jCWuGg<~_&OoF3avSgX6Oi0b{fEsw4_o0XX02mkBnn$uh-E0qc2k#~B^ zF*T>hc9+UpZjqcIUiZA~KVEaXDiOZ__U}j4oYUG}DihWscK1my|9H)*tGNx|m$>7r zPC2UP#8}fgVTlQ1o=>cgN@v=36V`I8=L9jj`)_w-%}J|7`0jYjku@i{+IBZ#E#i20 zdCZYDr>^FN?@J8wvp;`i&55z5bHWl6#5v!0!;v+o)pirs>h2FBd>_Bf5jE$r5)*vp z5l7UV>}uQHHcSwMyymq>)SMpMO<1eDt%!47_mIPDP9-HK_{#e5n)6L3E0qaikoWw@ z;Weknc9+UpZjn*qZSOs_rW8c@e()oQ)||~cS*c7!Zsh8iV-Kx43wG27-wf_)En=P* zFFZ7zX`2(o&z^AUVKpb85{Wx~>tQwLrgoRgT15E%`JuyV&S~u?EHObu@gZ9uUUL>~ zUMdsTa?j=j5x3vl>9Cr!Qi5c5#0UTG{wvTD zmw(~VniGRrYq_5Wvm|Cq%xIYBFhgP%Lr$V|9`%VjvJdflhBPDN@1q1ydr6QF z>ELsYuOrXT7{XevUv9$^6J#4&;n~O6kyog&VZvHuH=162TphWK#t?BTN%ih4kE$bU zPeoRsKQBD0j+{RQVF|g4?!W2CI`Rq?J;)riZC#hj1R0I~`*TOuk;ka8VZvJcy&cE$ zwsH;Q9Gm{LPdl!TJWmsr$^?0&KKs{W>&Of=rc~C7b5r`4pLc8>d4&qX5;7Wn=2gem zk*{dNQkft((p!FeOdXkl3L9=KYmseew@)5ZM_!?Vu!M|8Cq3<$I`S1wSSl0ba$4uh zN7s=nsj%TvS=&)sY0X)wOhk-(8Zr1cJFPh*tff8KAaq(Y(fz~G$0H6krXG|! zJFS^m{h`D}ZbPRvXN0w=JvOM@AUgqV)kOCXB_>>_K~z6PM8{8SuZLf6B$^%1cF$q3 zt42g|OITtevYV$dnA4nd8z!t3xxCZ3%h|;_VM%2FP9rC$9s5o>VTlQ%`WZzd8h@sn zu$K4da>A0x%-v_)jmY(x$m`u_+~pkOoUnv=ea2nRO7@*{!V(jatGv&+%h}A`gtfR6 z>_gM#lFv?sCGlZFk!+5!t`fxXWqB-GsFwcX%3iIV(9QEQy@tea2nRV4kd0 zCL;THpK+Jdj&mEnm$f2yc%N~XvyyYdlE_KkXWZosX5T3%EHM%J(EE(Lod4WSSj*2? z$~BqB-6k(*n&S{(pf@;0YcVnqEjEa3IF_sXm1<~Z?91=umabIG} zymvN;I)iBPat=#nf*3jIUhfI#qdWNZ99O=Vwe#z)S;?z20{$=5kyiHR+5cy6D)z85_0Q3Vm%*!%3zar$)R zZ|}43$9dI$3vwIQiX8EMb_Y2VyPL4YMC7OMv+o!A8{%nqTbZzy>y#6gn25~$eRc;q zSG=3BR(D%Pj`%*igPe&SS>^le4swdNOPkxU#6)DV@3T9|somX#wcJlR5jo=f><)4! zc4U?BvpdKs+P0k&mY9ev_I-8-Ikmf+u$EgSCnC#xpWQ)DwT^u8eRc;qAKSLO32R06 z_ddIWoOYcPzHel%@3T9|N!_M%!V(jaDZkI|ASZ)&6V`I8=R{MoUu$YP&%2RXI7o3K`QTSa#Cv^&UY(2-|7?G8pBf(c7yBC^=0 z-9b+6?k<(J+#;hyJG+Y<@o9IEGqERYD-&dOV0Vx+xJPZYUTlNB;J-I~e&5#WLC)aLOXYi6%RQSDk+VJR4su3y zWPDG%gPd^fJLQBWCL-H>+8yL{?QX(aZo`~#yMK4DJJRl8WcJv~wsXP~6Or*f?GAFn zbvI$H$QPe>2P2bpY!^uxkQOuZo-*+Q2BZqW|*DqrnPe(QULXpSc@AFxE z?eF)!*4X=X&p&g&zSs5M*R|H#d+l}YYp-kjyW6x~Z-azt;D@J!{^oZ*K`oAxmU}yW zFGQ)GjZPdgxBcc?Yj>Z#d2aE{jGyNjcM#0DlbHFn4|g}*<$_|*3xBD#4{ea3mjCY6 zpmX0TL9hJ#sWVRT8~1AU^_?R>IJ=m5_$3)Z$vWFD?Cdt@tYX1t^Ey0Iy$uq(pK)(z z;puaV36DApz;^Ih)Y|%(6`kq3o?CospZ~}RO0IsT)xG^U=M}RzzF|bKNSwa^THTv3 zpIfy5?2JjBSJdLzv|1i(ae?H!2LA0a@L2rv)>}J=uK$f<;b5Z9k2-={?2(k9gv4k6 z__NNpPnlb6wD($>4HDE^bcky3?s0Ch+7&C*a(ZQ=Ix|R5T6$sUz2}@!ocV3HPNlUoS41@l-Z~w87(&czxLwovUN5HFqb z&j~@TgASh;Y}|N>E90GV$kIUk{tHJ9DItNkjYYh1`|W|4zWC^bpw>H=d@IwWxufDVAuiBoecRy_HjNo|e zao~k*-vK^-vfn8gr&F&eAu;`htJ@D@J+*r4!C{XeU0QQ8o-Vvbb^IRM@scNtuhiSny0h@?;}s_9 zl%Rx!)}V!FIIleG32JFYS$G!p+A$?4QA|*HKKH7Uwo`%<5>u|Zwb<;%xy7yXGlvJA2*BBc%i-B(z>H zJZpQUTu)GoBim}tT=3O!Ca!tKb%Q6rxPf0BM;UR%of6?;;o>x4Vmado@ zi2fYEg*5fX!vb;q#*YsuA)z~e@X9OmR_ppJjts=f%kN1DYOzOJt$n|6R3KIyx-{u4 z5}I#=4X?~wt$%*vm_Y3Ct_2A}E%sYj8SC0D*I8N_hk4g4Gw)jUwc_e)H}3y%vCr}| zi+BBIxtdjrqAUdxeAZBRl&E6RcAU9aWp32L3U!NkGr z8_zAib&kIwO|N)1@GQ}KeGt~|TEC|RB_yh`@jAPnpqAF_1JCnbbEgC)B-kVM1huqY zANY>rReDNLLZY^>hFTeiSk5@=HcK`o3^Mo^LyK99W~O1)w` z7H>9j@WPK2rQCdfpB|t5PU2}(%3 zdf>ywa$U8PpIE-Ao}iYGG=9|{Ik}t@XMFd?E@m}9w+i#1@8wlbdo7pDiCs!aV6GIg z%9Z7u_}H?05`tQoyF^@gS2-u1cidfFN=RT96@fW1A*h8pQ3UQ$T}nvcP9y^NsDz*v zW(g6vM|CO5iFl6^f%|#y%K!SvVCL=@6f@SmGZ_z#Q%Y!c8dj-Zhics!W&^J_ai7m@ zP(niM(J)_mwVB!=L9KePC?TO0Wtexpc1&%MpcZ>1B@{)3yPBg4dbqV#oQt*M{M(M_ zXErDy;oosxnh~_2C?Z4?juA+wUQt3~g4S?5Y7KYs8dqjENKlI-o23mNj*gIp)QJh)UyR5Z}sju_Gns^-7SGD$nM{w8oESfM@%*Z* zm2p2lL-y4fuY2e#YtA1S6|!yU0t<~BK&u+rc#0u5?XzSjH1`v^+c*w=M}ZI+7DSoubSC!sSQd{Lg9`L5bGS?f9g5M6XC_UEPjPpv!A;Y&_@{wbGGAKFTxo z*r;(dk=c@m$a(cBA>k(=9&@ieb;lXct0e@rkf9TS++B|n5`J1>8(u+==Lh#%d~`xk z3zpSUa1PB}0NX{GLaA-k#V?ZSc4x{%!qhIv41j zfJ+a0D)Wj2wK%f6vd7=7>G_?A_=Gm`L@VQNd?M@_90Vn_r!%nYvt7O1Kv2uSeI~9< z(5q**o6x=L?(>SZcD*6-F!hR_knkHE@fmXF6$xtjU5WT~I3pm-LPGOx zu;CSSt98rIz7mM8eONodWZIVh|IhFZ^tk@DUiziHul#VcC>-9)+P zCnqWiiK8}nx%1#zXBP+j+It#E&@2D0Jn`EV@oBB>kf4M_H8x&5))Um)@Vnb}m;CS> zMQ6V$89@mNzmE~0?`8xgB$c8!zn=V=4=XS4d>j`SH zeJMdLzcJ!_iPydL1SKT=c13)K+)izfpqAgRh|iESf|85g_j2c2T}7Au^4K9>J{EzQ zIw7cq8C3*k>H#GrFdvJ+Oq~$a!i*{cGxdNH61)nMnK~h;#j7i+YY=ut`&!eE-+`+W zxJrSl6(p5IS0+5y=7g&gxJrSl3V7W?Ry)ZUhv z^%Jj1V6VQ${KZvw2!#Gm2x{rrVa``OMWEV34^sJtK>u1?_9t9qbE2?@3-sT4B&`gb=9yJA%#FVwfI#(-nfOn3}D zYOaXqy|1c+rx8TOlOZKMF3-1mf?BSK=iRcZ6PMX=MLh42RlU1V5zl*HRmm>9KIjz* z+HgfY@4Hpix6H;TcUd#+sr7MP5zjkhRqw9B29Ha^74f|HRkiOj8ziVz-*Q*P^WIn0 zg9{b$y!Tc0?nd;=HS{XN74f|HRkiOLyrNcpU%4Wl_r9uDTd0WVy|1cwH=3QXfc;5S}dUv5Bp7*}0l3jyWBsey%i08eps>qgk3IsrFrFgG8c*UQb)@ig>P!rwVz6E8==Q<{dl+{o-5<29$cu1=gN4hcQ>L} zuAx^Eu88N#c&dHZ;1#v%`^pvZTp3Sw)Ivo(SH@GlyAi!|4ZVtRMLbu=Q|-G3uc*Zy zNzW4ZZnai(MLbu=+vu+EkLVQ%SHuf@U;o?BUODe_1gW+Df-Az_S5<1u2v@{&Wjs}P z3l;HP8BewE8oYAdyh_Uz@mv{C_3j!7dPTw&@mv{CweK>oNKlI-o3`8)@mv{CmDfT= zJXgk3y}J>;at*zTa78><##8OP2Ct~aK1{u0zq=ydLRH37y}J>;BH@a7u8gPJcMV=q z%N6ll8BcZaGJ+CU#B*gl)w>(fD-y1V=gN4heV5tb2vUpVRMv9x`bt$W2Cj|b^^U59 zgx_8*`L}C1`R|I~wIXx%r;4D&bVaz9lOtADZE7H>;#y9QQdM_n;95?OMODEmvq6b#IXOyI zr6y^OAF1933Dl3M)Zn=YdJYeRn?}<2K$OyuI1z?RTZ2vf)dwqa+In{O(S|m z!nK?nrK)OEW`kZ)i|1HbnaP@}aMaUv7oOe6t2X3M{o56rd_Ag;QSi|E{x@4!@9b+W zQI(+qzgeArb=vi!tgo6#i47h%C0zZq>%gKb>K?w==La1WZG2wQQpq6VnCG7}=+d&Bl_IkL^LtGo@ z-LX;QXu6h@YdZbyRlf(I*=LNPgoJB3B{TI~64Y`nC&#s_;FQ^*goJB3IZ9Q%qKt4Y zC&!km88mP$Cr7NR+9a)Ph8y#WTCU~fxK@>#8VDYXgljoDVpR>M%qtSqVw=+5rG$iQ zIXSLX)uzk_32N2%m1{XUu2m(YfonNAN>!z%5nE2ewVWK+s%lf_6sn5ZYgMVK!3K{@!nK@S(@9mEG8-hQ#a>Ta?pjWcYgOAR)N*oMs~SuV zUXh?Z*K%@Pt9nJ6aXFW`MpSiN*K%@Pt4d7`Hh5eTuI1#oR#lrCT28I{@o+6C$F-_t zRJfLtqf}LD3U`ZY-Icb3UXgGuC&#s_+LX1N1hwk>%C(#v*Qx?g;aX0PQdOyGM6XD= zmXqUJRc&hUidyWEm0Mn|?p({sajhyfjp!8#*K%@PtEx>6UQx@noLuo;HHI?6wVWK+ zsxDFCT278wRkf+XD{6&WPKs+)si}eB2$FCur%>^I#-B2;NKlI-oA$12IXSLX&7i`y zoE)X9QqzcDk#H?1$F-{3)Zi7h*oUcC?0464a$KuQO(S|m!nK?n*Q#n$gICmYEhopd zs^F9nl(?3Y<62c}8qq5fuI1#oR#lra8yrDuah$?4fUY%_?{v-Of!At&j_(|5toR-> zrJhUt_mzoCLc%%JSn<7qpq8TW5Ig(-)CMIaoI{Nj-x~;OIfoi6zBdrgp~i~uA&2TH zRhiR_aCWtlIENZ5zWd3<2<;%@9BQoip4s5BsO7(V9`pZcU$KSGp~i~uBYH)`In-G3 zJ+nctsO21LtoWW0lsJd#C{-EK5xpYe9BQoip4p&R)N&3rR(#J0N}NM=l&TErh+dI! z4mDPM&uq{uYVjNk8O5HjL1jptQ4HsguSNg%_2}Qq8;0M?oNCSBY^4eRudH6UYW=@6 zl)fI7^~=7{tsG<^oP(qd9@muVGS8_TWFVY_q=bYrjlnDBSLKznuJ+0~ND|bdw`Ge> zD5vW0O^nSx{$0&0Zn1m8c0=Ad*l>F&A;De!;tJtU}Q|82vbmj2r-w}%oEX*)c7 zn$Q#Ou5+mID`UwBve(P`wvKSi-5%#q<5$MiyR<ifz$)cBRLkVAFMsSN3eUODSp5ze8;uZ-zz zuWJXj*dr<79BTZ^SjeF|=2Y&p!7CE%H|J2}SH?20oSUtV>l|wQ%21m3FlDbSH?20NKlI-oA$1AsPQXfA%_~jGB%=D&bn5F zbExqvV+~$Wi+z}S#eR1V)iI|sq$7Go!a3CVm9Yk|sO21L{K{BHP~seF{L0vfUXgGP zHGX9*v%wLh7RRZ~p?dA(r)$o@c)jDN^ZxBsn14Hm>c9JmaY|4^!Z}n&tjd-)5Y%!G z)lsT4rx`(sbEu9pl_4F`D-zD3#_!|k-E(I#s+O}I)N=08Ew^4uP~seF{60?GIaJ4@ z%A964C~*!oejmqm=trL^ti(hB$`l$)L)4iBb)^_?VKTPml;tL%8+&_A>sV3Y3uo)GrQ$K64b)q)mP4;THoLK zfxltCs^%_uE5bQc6V44&f|k=;5okGku}x3VCK1k|+D7;?(0KnO1lyEcgZ?gA=o8Jg z;oX(kj*vr*-^WpZVZQ1)yIM)mj_|fioT(cK%yuD%8o!T|5zekw5)#g##_!`~gmb9z z`#62)P~-P;`aGx8c2LVX)cAdz27<>T;T&rGK2ATiL4sOrQ%X=m!a3CVeVoh&32N2% zm2;@hr7DBicMjE2sxqV_ww#1>sPX$anOAH%wKz^`%bi1w-^b}Yhw3O*8PXBGBHDSJYyUq+U6P8o!UzcMjF@r*fYSUXfrgIENa)kCS=D<2r{LzmL;kgU2P|9BTYN zPG*Aywb<)v%bi1YT&oOe-#JvrpUQnUctwKtoI`b7t2|-m6_4v2YWzM+gmb9z z`#6~m64a_659d%F*D8a!$T?I;smhQp;*rw6qJ)HVsE%uuEp70MTJ?S99IE45W!@G! zhw3O*8PXBGBHbO?H311(2@}CgeKN{ZnRqnHapcbO=PHKY^654SZ-WT@wvFizHY1d{E z_oX%v+A|n(ss6&TbEu9|{jKcO1|`~M8gi-rCN{lI2}($4$7#r=`uo`R1hsr5&tv*O zBiKUiGA$gX`kUCaU2lVgcAOS*Uur{NQA@i|i?}Z}BPekWHSS9tv9CyI$7#r=`uo`R z?Vy%+pN3qjzm=U5lsJbP_oa^L6$$M)4Y^c*A3L?dey0}Cu_Qk@M82+z{9p%JK-qBC z)p3;fby7mYza2s9>J{OPs0r`VB!OIEhqjZ9V&WAEWE3^#$nYivwUA>K;T)>H@;+P7 zGWOSV31=MSZbcv`?5}`V`Q?O2Z6GI{5Y$4pS2mCn9#TSrZA#u}=xJYSh&h#0?Qje@ zHqC@*RF9f=pN7a%nNy9R^R(_O<-U59@VGqR>IrITcV>uEm08SeXqRb-OqC(+X#Z%4 zIhFg&t`B-ef;P0*GQ_*e6J|DeTsWp8uz7U1SQU)#(k-Y?Ru|B zXb)yP?n}*Vu!X5s>!V%)Dt=e*vgKO*jY+g;upRfMcAZ0Yl&Z{WW`h##GHu6wsnQxh zQoRil+Hu;B`%*I-JXWgpi;sBbTe%%v4$e6KZLQeyYDcaJ?5}k@#v~+C8`xi) z5Y$qe!jY6yl@08#9a2JqZ3@?Uh_;m>4Wm}|yT_nvhjyQaH-VKol?}~4V+186G>-*Z zxxEI0TH1XY-Vs*jG$SY>p}m&jjbG&nGeY|v`*B}tS36GoabK#mvKely9n{h;(|+8S z+CcDFB(#6DANQqZUXh>{+m!Y$B_y=tv>*4SW;RGrtG=(CLv>uM3}V+gRL8Z-kdD}L z654UvkNZ+Huh?>Gah%eYYlmb%?n~`Dhw8Xi8PXBGBB33p{kSi+!7FO9M^dk}%d{W& zrFNY|bzH05XM2P~*PTawRi%4f43!W!jJXQX6dWxFodWv>*4SHnf~t_2c0j zYTTFFaSk=^OO@|+a|tCRoI{QKQnQwmpjLffIfokerFNV{jr&qZ^ooRYsBvFvgICmI zkECab+fl9VoI{QKQb+WPgm#=RjQdg>yrPzKsBvFvMmUEW_oa56Lv>uMY-xj6)CxIN zJ|Il zIaJ5B%8-ue6$$51RFuPz(^u<6?ZaqN?43@OP8(iVH+jUJ*9j@{DebO!gQsz@pbcewv9V}yqawM zdQ0y@S3Ax)b4W=}m@bL6-`yLSm~@t6P8`d>E3JQ@vv%7yK6B_Qvhn;)GXwF_qfQx8 zk`ty&;@AVruV?@DeJ3V_=}K#zshklc( z3DYI9&3y+1V*WX+Cxq!rYyMe(4mMtU{3Q3)Uk?t%yDxujKuJ!RE{P2uo*9U>_g$6{ zrYo)EX1o$?Ecw=S**O1>BLZ>hO}`mXk`ty&;b=cf9;(Q3WF ze^o)kzbh@@o7@iFk+imW@}7#=G~Bf+NlutviRkcH{#|LowpIY}szXUmL=Q!vU=T}pDoHgsNzz?qm3I7|At3Pj*+?^2Qz zwxR1o#ChXaR6^iv@8fC~QC+p~-gjA-lAN#&UFRY&Gb9AA+CF9_5!LMTZ|AJuqa-J6 zL-Umg%y0>T*{6@$RRm_y9wj+p8=7}TR5SJQk4#Po%%XkVB}CwE(4!UlCu~FO5)oL*Bm`C&eXOEHY&yPL>QRytwxRWviSZR#LSVJj$7)anR((B6 za>6#WP85NaWkO)p*TbMJBEtJfYSIbj=G?~1?*IU%rmEwI)WfmL{qlAN#&t=mOl zrJoR3g%^l2L?D{zQIZq3q4+}tB9??eG*LKu@tsIfkqAUZJxWM8zOoJ7Q$!&0N(gEp z>Jx$Ju9r&2kBhiX1R}_UpcbN65l@UqsXa<^!tGF8D*};lLLf>l5L1glwB4g5Cu~EJ zw}=(D-q;PX+SSJ;1fuO?oqwI)_jr6{A74>Fj^Dz*NZ-PyBqwa6B$mJTo?zqBB}XQN z=}K$rxrYZE?_B3EvN37O1A&8^;yuRCWfw*PfjD#>?03P&w0B%1 z8$aK6w?J&V%Vs@Fa>8^;?C>xDD-Z{6^PYq-U1`m{^O<1d$W!LZ#$l883&d_q-_fHa zCrp>bUWXkLh-Hgk=#ud7O6xm^y&P&2W zLYS_!EVk~Xda5jfii zl;nhM==u?)#~MGx5KJwr-z!ZtMTioi^r5ST^VxJ!t@-C#&bPS}R-A0k$bcbo&K zO-%^g4cfTdiNIZLNJ&oEhVFwRaOX@2+|}B+Ym30$c}Pi4*oN-sBCrBT2;809Sbd1V zDq~1VPS}RlB_gnrNeHYm+E_)2z-nnoNlw^?)>k61B1;IYmfBbiiomLGNJ&oEhSrH9 cu(C`Dtoqtm)oLci>NUwO<%DfG)6{DHe@U_kI{*Lx literal 0 HcmV?d00001 diff --git a/GEMstack/knowledge/vehicle/model/meshes/right_I_link.STL b/GEMstack/knowledge/vehicle/model/meshes/right_I_link.STL new file mode 100755 index 0000000000000000000000000000000000000000..e0769efe778ebe005cc7db9fdfbac6e5a0e5b7d9 GIT binary patch literal 2284 zcmb`Iy-fr$5QQ%$rT`>#8KMG~lSmL<5I_|qTLXpA!Ep^7F)^LsZ|vuNws$209N_VI zKELOmTXwtuZ8x#pe4=}Lf7yRL{v0p9ukYS2Z|@agTkCj&Mqt2KHL})Zb{GY-vJ1ciS#3O+^1ShJvob;qT zJuUx6P-oN=rXBOEM0|aiDR&-~#N=qLM(>1Epo%;_EfYTD4!2!7;Z>IJT=`5#MCG`T U4I*w3@2mF_J7dN);*~7KFMt%h=Kufz literal 0 HcmV?d00001 diff --git a/GEMstack/knowledge/vehicle/model/meshes/right_antenna_link.STL b/GEMstack/knowledge/vehicle/model/meshes/right_antenna_link.STL new file mode 100755 index 0000000000000000000000000000000000000000..9a0c069b0de86a4162da067ea0dbfcb2b709b41a GIT binary patch literal 50684 zcmb__d)!u2`u<7^9i$>DlTs?As3hLK*OJ4Ch$LeulN`pOk%VzpC>bRc^^$ZDIo6Cr z4)3$~ikc!B$_!%UJQ&F_2GQ?Y_jB+4UQgS6rtjzT>koF__qEsF>$%pw?sd4 z$(~pFbL+P(AlR$&sXiJy%vUx0To9cSrd^UQQ&wmhukU@L|2S$S z2(~cd_=}n*!-l`7b#+3U{{E_0b}k^;>&K{RvT>L9w2Z$u@9V#KbT>h;g%Q_vZ=5vV zuuc*FN9&KfY%f8ug%QU-^nK~28QTb3jX80fUcOD8o&^MZz5o5j(hE)NCuQzF{CsP_ zZHIn>7&H6%(xv@d$-TbW{hy_EuQwMjMjP{i@92lvLj=JVM$8}keQDYC+h`fT?$p(v zJh!TVV6V!j+G_Q8>1}m~3L@F@*3yg@I%|7;vb6u~-Q>Rfw8s2%`)&PS*PK*%k97lT z5p|DzzOoYRZ&H(&g($6cFsiHDb)ZkFQMM zzvo;*u!Rw$>fc%#mUPxK`lf5sy~mtYK(H6rn=z3&Jsm#hGC}a0^E+*-Z%R$Z?yqI6 zp0{_pbm*0WU<)G#+&HS{**_nkb+zP*kCOU>uPz|i%Xb`A)9A_rw2WQZh^{ym_3xIa?Tk_p7RS^Ei8RMzB}qQ+0cMrOjA^-#NmYjTo!%U!U#m4 zD2u_yAX2+5QnQ5-h{sWFZ-7YcvPjJc_CgGfDk8PZA~jnWfk++I_8&j@>h1Plx}UIw zEsQ{a71#Eh?H_h->0kCNAlM7NU0mA_qIY&#?~EQf&N3GC)N$5_GujyR&Mxbn*}@3) z!Er_J?6TgO5$sj@RLEppmdPL&iL;CanM|BzNXT&FEE_cDlBs`iw?CO?nM`hB1ahr7 z%g&7HH}h<_|B8PU5bVV@VhplAmt}oyVFYrbILihlTXI>p#0d7{dNT$YnaeUVesg|X zWMpxc`$~rFvJ9Cmj6fb7XZf{c$S%u}8Npu2edCG@*<~3rTNr^1Ij+syk?FfE(`O4K zFan6P5r8pE{&tNUo3@c2ixKRVU6=DKMc^JXnvi=1OXd~+UGG#?M(9%sf-Q{DC#(u+ zV=y*w=hSa$!!;w=OKU{S!1yE7t{~XL2(9&~{8Sj@gkMk)Y+;1{nivshDPc*{8Ac&>Xb(;#vg)U3nMh|(x<{0$6}0AK(LqQb6UnL zcCwjMYMBSwOH?-)luDNMHqkl5+aNsvNFQRLd(EYg-ky~qSfmR!4CIo?&8sPT$n_C^af#;ORmvNgjqH1oiR4> z7#j$JEsQ{a73Qz>sWATV7=IKH?8P-=jLt?0f-Q_dzY^xJv<#i`Dj?X4>rKWVVRldu z{O0^l=+(jur1pbh1~SVs*un^824S{V>k3(h&$0|guov=&Fz>5n=!~#r8Ejz$vWzf0 ztO$%hJjNe_U<)IVYlRtaeJYG`JjOT$1bZP<3v4b#kQvI@ARsgv)UF#a z0@-=EQ*EXnRvHQj_Tn0mOy6gjK3f=pd_Jrj)Mol&rJ+!}?8Ws~ewXrpN4t-%ZWvFp zTbEv3xiZ@7jP2uX_840eu3^6?)Pi2;pwWTxxrGsX4sL??{9g$6Qgl_ZjOG(RkJ{fn zQ=aOQT}@nP!DzYWvhzp6Mded5;_XHCr6=GK*KF1r%J7Dntjcv5sz|Ns1tr(!Rzk;*b&IJI6)vo=lSNpM}2U31x$2(~cd zgigz=?&#V$d#4;!Sy$}EHIlpIVzk5Cma_VRS1GGEF1r%J7Dk}Fnk{;&+>2|ZvJ5bz zlyM0)TFN-aWmh8D!U+5}r7ijeb1$xu$}-T3lC0fncO%pvpGLUR)!&J1#~$<*VFFf9LGJTToYw zP+n!|yqLK!#2dg|;q*n+2Gg!XV5IxnX3sn|<<(O-BEw4#u`$i2Y6kkw@O-GZlLgk}R7 z`oBCCdvT5A?owBX86ne?7=@M^GQjM^TvsC4i|4EvHQHme6;`TbEQ2vlSZUI6&3`L{@5=~`OTzk2hR%x_?HR#d|NW^j zYY^6DWt_mXgM6pF09;g-!3du5{O<_%;u@($@LUhB^O-4l{g>Z^EsVhYOjsqC_p2;} z5$we^Qi-^z88COjZ`AkQVRd72)X7vRU+8J2z|mVO5~u*_Q76UBe^>+ zMtiMAWM9T;?aDR&x&?K`2>ms)cM3O@Kb23#UR)!YcliHkuZ)u?Q6~N$o{AC5{0yBJ zQ~6Zv#Wj+<%TvKC-$#Nn@*OZRZb4l!LZih0cq;bd8mW9L)M&m70lx?Blh~4{Vg%lt z_I}isQdw8*#WhmvAAUiwFJJWrck?{~TUJ+$088?n5tU`|z1WLu#F!ZmUFO!TKfz9X zwL0cCVP5U+d2;u7*^YZg@3o$Yp6%)37q~GGJZSqbt&VxUmRDjAh`Yp>J$tz#8r$Ex zJDS&bE8eS)d2N$d_-3}>CAK4&8rE+fm!E3d zzAxATJJ?FxjXia>X_Guc$H-N?4PSTUE5O; zcaFIsKI^Hg-GzUxj(J^$S7nYKyI0lRAA2ccP`763m-DZ5V?Po^*u^HZ%e;DmGHPne z*i^GVz5Bk?+&$mPd*tf_JjY(I-xH-9N^P`^ZF}tKZ+h!k*Y1_-m}ljAZW?t}s;#Tp z!@K&BQQ}BV4?#Py)rT1_ol5@%FtG;2r$usiC&qQ?@0p_ z^WA1(Vgx2C0!(yZqE{y7d$}~0WWQjDCHf13i4IImm5KR|Esby)uR?@V#PFx5#|OUC zxHRI(Yn+aXWd2*nIHfQjFn;9Danm~|))>D6F|po$E$oVazEWzj$5oCkj5v14j`5fG zHY$}7$27amc52-%Y5u@P6$tivy+PY}QDt_-1cc?~T>T#Fwfn5bX6(_pb4V_vY5T^v%O4 zYkp-MTNp9@_ub;tkL*|~BOW~OJolGFnx&5puCa_@ue5Qmcx2TBHRX2x)eaZ9^>uzO%`yscGO9TNv@|u8re9vz}7K#>p++ z$jMwpSbD5Mn3S0 zEsVHk&cCY~4(h0ghi7-QPo2=&2VOCPz253^WYlEq&Ph4?Jo{E#yZgQe_zT)&dj5Ih*ykYuevYxk6!t6m!uqho;o15J#IM3hj_&nMqF^-4^`)l z+fNZS3(mI#?mf$gc*O|zdgRx~M@y!6)1LF#9gnlawi@9>ykZL@G~ZRknrB-kyGi+uS)nx%$^gCelTBAthwWp(x|PMDodjKze%3xut<2t7W9KT0{vB~wjZ2#!SM9URR;;L z7{Ol0to^q1&>k;ouV#8oPv4n#itvgpj6i>t)b@idj(I*keb!9j6(iWI%dk4hjCO0X zUhT0@(#xmaC%j?{BhX(Zwf*4vUAFUWfB1*=gN$IWCMVZVT3q_B_G;h#x}|URpEsl* zWD6tEUnRBu;Ek_!^fjyMNW5YMdo|d(LDC}qNPD$`JN5LBcdsM7VhbbCUnRBu;0GNe zfBqiLgjbAUuQum2N}ApMsrG7*zWHlE@BHn3=m*)th{~}V^7aIId!%`LSQE}xGs2p1 zq>5W1$ldpKz^MdZ;$f4Jw@IgYu=tC*bCWtg1o&d&)ZYv?Xl+V zxrGtPuM_0$QJ%M_$lGJh+j9haAv;fyw^!wPyGPz0Yu=t)7=ipcLEawadAmp69&6s7 zBiIYsd4jyXD$mJw@JbHE+)? zjL^8E2;}W4@^-6vdyZf)w+pY>!U&Bkia_4(k+)mT z+w*&|7qasNd3#jm74mkEyxnTvo?94EIY)-Py@b47c*QI0yyA{ryM(+w&hz#JdArrT zJ-09d`E?EQc10j>Pms3@ulQcB<+f(H2R`d4! zUhIWjyM(+w&hz#JdArlRJ-09d`E?EQc10j>Pm#Af&D(PXdm+~@A#acKygfzU?lf=D zEsQ{ZU4y(`5y;z9wB2ISfi@^)nj^7a^cyTmKD zFar5?guGqj74mkAyj^(32=+p*9U*U5mLPAp$lHZiY+(fQ>j-(fB9OOR-6C%nUa^G{$gd;h z?TSF&ZjrY;&D-;Pu@`df2zk4*1bMqf-Y&di3nP$UN66b1fxO)!Zx>!Mg1vOMR(XZI z-63xmUa^G{$lGa+1$ldnyj^(3drEXRO8P#wR(ho9%y^w3i$lJA7L*DL?w@W|B7Dk}I3iDTrK;G_m+u6di^*j%6%WtfDzaH|ZQpm3u!Cs$z z7o&Wy%(t_J5j+oXOv^X+ap!!vtQ7h|MzGf*!@5Zs<$iE!{VF$W z-=Rt92id|1o`*MPuRa6ava7x?g?^9`>^0`lo>E4+AAESzVAt>PaY^V0*}@2(RS$~g z^W7saG)Y1~$O!hT*DvVdI(I7fgZoKCEeZV~TNuIf@W#yk;!1b#?AA%wjV&t> z?3L{=3+s5sd^+}Ock$er$$dXn$82GQYOQO^h>M0?>g=V5rlAa;?dR1cMjLbe*ejfW zq-(lqeRa$hM(9esmhsGXSGnB}+9o~Z#YzNwRX&xj(aXxHuFK0hm#){#wXV_YX#4uB zM!KQN^z@J4w6ttt1iv44F>E^9-SF|Pvi`vc_PX?pJ>xMmFDaE-a?x#Px;E8Um)BUx z!U$eH!Fd3C4|LtC$CcM{2*F;r{H;Sg;)@ZbGTU1(>F0*`J}o^O++_#%f`C*r4_WliBWgdT7Dn(Y zsWInGm=q8E>E!}~SIoF7Z#gDBmyg7Su9U9YT;RCkO z&Mni>8?c2D7@yO++S{Ezvo|(yGCRl!_F^s=bM7DNx>I`&FR+9WycTB6KjL<7*d5mv zn8;qtX=ASZW-mA5usdXSkS&bhwJ>AquQ}AM>O8B^qS&jlo%dLOq-*=cqC%@>1h0kR zM4)+t9oAk8k%7H9#uzhv`KhkCSs|-rY+(eio*}lMa<1!mjF(8w2=?MwY0RD@&UUZv z{z`g3dIPpFLeFQAhzbShLnpb#Z*Aqfp*P?)I^LbYXk#XJKh=FU?8mgpSJg3F7@>Qn zvNFCL=1QwSNk3jziD0kFr|LB2a5wb9cK(s)s$)HqLGGoeEy%UzaM~N}^!bsl>D-on z?&mGT+-u0;#KH)EKVt@7(Z`LLzmu#2FoL}_f7ITf<$wCPodz}VVTOe*jL@7>5z%?w z+`X4<<3pCg2=>xESbKxt9ni%M?6E;sc-g`T&3zS7Z_8S~8}+=jLAEeLb9hBuH~s@V@y3PH&Kbd8Ixf-PV29Gn*4;f-dIPpFLdPPC`0S=z z?Y>V8lX%4l_R{f{_6C!lyTtDOS(h|q$ZTPRj;R!(qdSSaj9@PvCu(mn{g7+ocJFse zLZ;6aM(Eg35jy59AXLX7UR<^@m;Upu__5PP6---M8@O z?8S9x%<9v|*^aM{Dby|_W^{Zj`r-Hg*56}e*VM*uKOnsU-;2GN3 B<8Su&9&}td+@Y&x*m$#{#l=H-Px9{st`S)&x$iQA4 zV~lxfWmh+=)!v2Z!-&d#WUH^Oau05|mqcp57khE6H0Hu%d%3lbboZe*U<)I7-u$RtECFLx9!_f`h$6M_tEMW^H`1d#F z*8c14p!rRGh`WqnFP&ja%2{}u$sgLQp4>`S+}Xki=CLvRfAF|H{@S;tMKOZCbfz#V zXW?U-+;1O#!Asm_3nREa8nbETaC^X{TO=|tg1vOcQ=`wt2lusS?{k_&AGR=pX<;#&_oRiY?c7{T$;nBP88*DYLdvfuXQFcPla@u{aA z33qkYQ1<~0eW!uDcFsWm=x1THUAr%o5zJ6yKA*jnTlivs;VvWCOXo6`yO(dM?^d30 zn5-hRg%Qk9WcpiwW=9=WCER5Md+98$a<|pW&+R>}y9#&N!U$%lF<-s^oPBIq8y`lH zj9@RFTUPEaz5lOv;+{>i-6CNITP%!Vh8nYI(H(aGUwtjy<$JN0&XFs3OZQH;ZQHJv z9)~TAV1^nqVeXN3)xep;T}H5%&h_hlpWC15Vw-++iEx)Kj9`Wuqbm)uHW=x;VxSk!JIZmwE(gMTlfD9UsV?%*Qy0j?q0CZn|5)RGkm}ATUxd-f*ESe zpvzvd-%TDY++_rNbz6CJblTWGl)LYbS!+Lf@OX*4Y+(d56g}r>-u8d)2;nXx*z30S ze~S7yXs6u$)#AU}Icp9Q?y`ju%ur)qeP*tG=KIdVT}H6ipclqQ&+gP(xw~tNyY0^p z>>}J{3nQ4J#`Jpsa@+ffIxH{)VFWYOn0-DNAD?vOwz6xI5$vU^U)ghM zjIP89ciF-S<}}nb^}dR3JZwS%!TUP7Y-3)YcU(N{*d~RiVg&ElH0GTFYvbMxClubC zy|@mI8FKh{agP)KT&P_}@QzJm9vy#>ZQ6K!;TL2t=7KRJzlrRUHrp0h!U*26iI_O! zN;|UU?gb{Y7jxQ}n_j=j{_TkUB;REVBY4LqW^1>(-TEC4FSIE3;nag4#)hJU}y&O7<{lJByG5xmFKm|0^M+0Lzp`!G+< z2=?MwY0Q@+?y;M$9Vz)PTNt5d=}APzTt=M}?KNlrQF3bDNy-`%MjP|5winow+Ft4( z`Mf%23nNsUrDe1pdXqhP`o(_Lib@1~RX&xfwnQtVN-epUD!AlYRa@E{3~BQBcv9&K zf8$pzEn67D?`O=aAwFJk{wVo97{OkvAMI3i{)Qgf8+7=#j=gm2;qsfag%P|n7aEi0 z3*ukjJXm2g#~scZAlzjOBY1}~W>SaW79W1sLDCyAg1vrf z`>U#DcXrm^pwCT<)eYujoI46 zjwlTpS5;v9W{8^F7Bywlr0A*N4lJ}N+&A~)wuxWx>&r?jZXZ%;wVNSoY9qteZ_S9t z?{|J7GT^?s7snW^$~3;Ebl@!)NiNEk%@Cvpyy9Q8qBomgCA|S7aGiT`tTg7K4`-Bq zjINR1fGwLL=&K8=eHFzaD;f2yQHi^Vc0v1E8+Vf|?y`juT%IvITvRu0b^3)8cNxK6 zx=%{u?t|AaN`Bnq50Ztmg%MnD#=Q92x}@E`r^qkJ2=>zbUK)27kDr~)9C^I3ge{EV z-yd^*|5}#x`0zlP{a^%p>Ap3MyS=WxHtE}aABnqcVFdHom;>uhPo}-Ly|gGsu$S(? z)42PubydmCX+KNcWeX#?JsR`PJ}&v{_;TE31bgW|LXEpqK3`p$uyZ;3u!RvES0wJ1 zvbf6#_R{^38g~&zYqBWH7DjM<#LV5$o6;=H&@*L)uX-Y_Tq9ozd-0UJN6tP!oxkZ~ z|KR$TL0ywu7{LrR=IGr8dH7ODQT0Z zPZaJlg1vOtq;hxFh5M!7{<*&o>*s7?1Tz#XajgzaM=#!Aq9`NSOLu=NcdO&3={@cC zl1R-KMleJ1rHz4&)8iL56z(#Dy>zdta<|dMSCSR&e-Q4ng%Qk9V;(e*C+qt?F1;Ef z*h_cNDtG_U@uFn?O;e@kWD6shq1bD%pi$VrE4?!#*h_Z;*X9hREN5T~Bbd|1=&oYP z85p7Gk;#3zY#Bi&*$9#?jKG+)R6BM)erb|iS7%b;&Do3V(3rP>teYObYC)lP8G$ip zsdf%vcKi0}PyN4=oPqDfUd#n!UW<-NFT1;bfhCNa?NDGMdoibR zHci`c>9mgBWCY0;Mqp%Fs-2U$^jG84#U1)eZ@>ul;3cwu_Nug@q%A4XuDNT(E>`PAKMw{at6bjSB%FOHSi zz2l!q-`(eY$r;$f2tE}7v*+d0FXYStJ@GB!8L0t} ze&F%+-uJDyW(DN#+r1$WE*KwY+(e}TSzB-=nbXxo-fu&i(&+OVdbw>yK`XBxLIkF zmCL0?v4s&>Zy~*NpBbalgCCnHEs7EBg_XZj?GA_semp3>_t@dmqS(R+thbPE8*7kB zwg$-v_QHx{eugpP)yQ5+wvNLVMqnL>PCCY_WsUy!|+3&u3Q`S0n_ zTc0hkgb~;+LdxP<_kNcicG@>-n1|zgu@`gNn6WoD@Ta`KQFa2dg%Q{jLdxPB=e6+T zj@_})qS%YurZI25)!y$~wNs(hG6K6rl3Hc)Uq9K?A7wg8Cd2n)FOD(DWPa%B+uYni zG8wio0y{iNS=@epPd}~yeiEq}!Co9Ijp?!}@;BYNw`4MGVT69ILU-xa{CJF?(5AVR zfgNq(WGvZ1$0toO+L+!+Kfl-NUHqais$;e=LeJjPGWM8qxIazz^)Z6IDxd0vFNgVT z@1TC!LGGpBg^+9PLJZnP-3hqw8H0V@y5FbkzGxXvBgrj{;P*3Te4`Wn9!uAyA-`e- zd#MIf_w~(ty`PWfe4Cw-610|LVFY&Uk(&HBZ}subUVT+|nDV{YOO>IzZ|U>rdir{M zyqTT#67;8HVFY&Ukt*J9Xz!P|TO|9!`Cja$YFXWXb^il9`u!F>Ci}10!U*ixBX$34 zkNlXfKW>7wb4IWicK-&YuI?l27{8HzimZ$@ykcPlcI?q91t+hYo8G*sm&7Z+7kjCC zS$CwoeCX(OX6rT*6WPKD?AW8z7F6#ntNM&!FYLz7&yF_+I{}kyCm>rGp=xQ}2cRl! z8P_rbyUO#^*tu-k7oKMO!r8(I>?BWWcf|LZIzD~kzXBBOgj1Ti>Km zyNtl@@1%BT|HB7q+EMWw8k|(tag#$Xa@y~v7OM!{( z#hf7tR(&@EL^0=xK;@1|6Sgs9&OyxC<3bI1N$bF7!A))8nv( z5nLYDwr@SpUvS@bqQ_wbd+8Ym8h3lI80I^DJ6UR%EsWrLGv=ss2Kj&Y86m$QBiKvN zYS6elpzD!->KkK3J-`-5@b3@x*`Ip)&OQ1`++_rN>6sH6cMrXK58vX76NT+;VFdFS z^Kf$;_zmChDlLi;>;)A}IFm!;?!nEzPItMnjkH>}FoN47=Je-0n(p@6i=xM21bgWj zAR2ey-ELC)o8Ki8eb~YXjw_*;g+@8|X|D@Mq|2xcgDCwy|Uzw5>ZWmO6x*h^15(US`Qa>}uO*bN;d!m))B z%ur~T4mi+n_rs@2*a^r8_R^DE^u)!Xx9{cKb=_9D%N9m3LybAE&-VU`W=~{iG=`H~ z5=SgAJ$O=n0s| zPM(@xa^fiAE?XGE43#r8!`VC8nVI>$*sJn8CeV^4nU;(#j9^YW~POtI@j{3fI!e(q|1oXpFMtNU&kDB9s!-K~qbRv+nHTJ4(=UF=KM>%4t??VT3YN&%c5yK7}eiQdPW^5wxM~#f&iqs`wPD_()apf(RUCgmPNX zzk(`0g(^N$ReX+MFJ_D}P{n(w;^j0ewlG53URCBURPi3F_()apQbw?_7c<5fsNy|T z@v*An1ra#P2xYsTe+5;%hblf&ReX+MFJ=sO>1`V9p^A@H6)%XuQAQ|3_53TS;yqOH zv8v*81bZ=K@U8gwM|r5?V^zfqB5;%u%1}N33aWSyReY?f_#DArl}v;x-a{21t14a) zfuoF2PFLlscn?*)RaJa`%D3je(dKAT#e1mYt*YYlQ@I$S`Gb}b@)D@xt*YX41bbCJ z6;$!zyl^?WUh{K#63waQT65p1+|D%%x2lQ{qXw}sLNg9UKo#$yikH*H_+IR#xo?!K z;yqOHR!%T0kAB3$2+cSY0ad(*D&7WO@x9nfbKfXe#e1mYt*YX~C{8Sl(2PS7P{n(w z;;pLUa|C;7?i-ccAXM=ls(2gPAX^xr8HXaEiuX{(+t5cbg1t2NjdE3d3RS!fnG9PP zp&5rFpo&kSikH*(7{Oke`$oAcK7}ei4l$7}jL?ij5m3d4EIbaUaxsFvG^dVoReZ=~ z__3L7@>0<`W{flr%=Tg-kiO-4n-B8LKSaS6(43f zq}~~!^CkLwKoy@t6>mdt!1rP==7Ol=Jyh`pmM}u+OO#ho#e1mY3ru9M%Juv|2{!9EY}ZsNy|T@rB61UL0eP?=C;p zLlrM)(6NOPI>({$3aWSyRlG!MMz9yhN>RmosN$`v;`49%GD2rXB%+Ec-a{4dR283p zB|>Mm#f#CRiuX{(TUEv9XX!CQXP~n($}`(mRq;83y(*sys(24oyi-+t{%vZVJ(v6H zth&|}RPi3Fc&DoPu%aLqM(CWiBA|-*P{q5@JM+EROV=s%H-{?TLly5-6(3ec#KH)j zvsMID@gAypr>giI!Ct!FqTGcl-a{2{Lngx(M(CWiBA|-*P{mtS#fLQ^v9On}8)+Ma zD&9jCFKv)5jLt7m6po&kSikIGiEsW4PYehg6pF$Nc@rn`b zrR#Va6QPPvp^CSviVrJ?Vqt{NSt~-%Dwep*_hK(ykJQ+%bK$Y7;=>nD#li@k3s;1m zpj<%cDyevJ+4;(7;i(v*E2jD$P{pTE#TVY3y|@lV6`w*CU#MM1=vu1&9#F-nP{m7c z!1rP==7Ol=Q>fw#EMbJMe=4t_iuX{(7nsOi+zLb$@1cs96aLu32wgGN_5oGAhbrD} z-lEv6vYkT}@1cq>v|2{!`e&T0;yqOHg~-5O9AiWk@1cq>L?1@z`e$6uccF^+P{m86 z=6kW1t|)5Ug(}`d74K9PpGQ$f=!$7v9veUvAHJv~-*(cSE@ILBC33C%K=i4?jufck zovPyVFBvg{%M(?+hbrEwDn3WBm+k}6+J!3KLlrNz%N9m(y@@K`LlrN-AS2jI_kqN@ zD&9jCFDzjTBl!0hReTCnyi-+t*sCJd+DA+7GL6E>!U; zRPn-HwlIP@Evonws(7cW_^{Ve?!{iZ3sJcXReTCnyl|H-j9`X}Dn5lOUbxE$_R>9t z%3Y}9Q>fyl$6*U2n4zMIPoatz?lOYCbWdSi9zjACpF$Nc++_S9enhciF-S=Cr8d!*|K#3wgThR`{wrW#w9Tv?_O@iVu5hovPx)USP2>f*C5R z_!O#m;V$2cy>v&bau=%j6smZMyKG?uGgMUZDOB;oT}H5%?r2r+LKUAv6))Un3nQ4* zqKZ$UiWlxOg1vM{t8y2r_!O#m;VxSk!3-5ud(3$q`LU@zU#s@#PtK7}e?xXTts zFhfNZpF$Nc++_rN>5f+AE>!U;RPn-HwlIPjn(wW(GW$_h3CO+JOLxk~<=GGYu8eS( zEsS7J=euzW2-P>pefeo~O+(?S7@=AReRHVd6R6?~Z_Zv^hoXv4po%ZlE+bUApuZqg z@hMdCg0(x6`w*CUtl78F{ecppF$Nc`7T=+p~?kqQBcLF zP{kKo6nk;o6jgi*ReYh{a#f2vwpf0;>1~s(6W4j9@R-L~2ZgDn5ZKUSc9!7@lzVK9=A;Nh8`W{flm!OI- zygBZhdvP6#D!vM;_(JV&h6v{x=)eZDrKsW~ zsN$tJV9RERs-3s$t&v*4!z*8e)>BThxEsF7E7yp2^wnuSjYQ%uTM&111eYhOcnej$ z#9c>6(2(tFD;4@?1g9-zEY{J7OMCd zs(6XJY+(eqM^VMcP{m7RU<7+1+J&!eYV?6BK7uM7inmb3J5|N! z7Dg~bMHO$MiWlzkz1R!+T=;gTau=$23st;C2DUJQ87iuH3st;uml5oRyfl0RRJjXP zyoD;>sVY9VFoGG1mAF<1TBzbBit@eK3;A{UmZ@?Vs(1@kyhLiYFoGE>s(1@kyl|Hh z?1gbc_$I4z7pnLes(9fpTNuF%6;*r;RlIPQ5$uKWPWZO0au=%j7^-;TE?XGE3>8&; z_!_Nnml5oRaa(liiQCoY4B;dl;VxSk!JHOVeE3Fg0fF&nv|w&sxi6QUpQ~1QDn?+; z8BUbbH-{=dhAO`B=Iq6FD5`i1ReYg#8G$ipI2liWL8#&_RPmBC@V(fJxge@|3sro9 zC5*tBGo0|JOoS@lLKR>y|`_P zD&9gBUudi-{|b=K1y74M*mm-d16i2Q3}dLH&Ka2Kk0 z2UWaNRea7wMqu?M+R(6-whuk4SXO12?d+vz7%Kv*c-Q&tgWNSss$;B9MlUq2FBYsQ zM$4|>My|2)7eN)TEh?PM4OP6XL9&Gr{C=W}cTmMki(&+OVdXEJd#>>cs(1%gytF8` zFaql>^wl@0;vH1+(xMo_URe1H=eO%hHB|8qs(6XJY+(e}Tj=X`P{muQ;-y6~g1xZv z7tW#A6?drOEmZN+qS(R+thdlt_@IinP{m7&Vg!3(xE!geu-b6)!D{EsVf=3w;$)Pv(|&97eDgRurR)C%#;} zjuTEdmKMbpMqnK$+GXR1wX2rlEbjtBzo#HxTz39Ngu+uX0=q@%yM0i_Td3j-Z_Zv^ zhoXwNP{kK&ml4?ELEr6zD&9gBU-$*ti@6}Gcnej0fhCN#Xi@CNZBtb74yyPKWIh4;w4uy-(S(`%tzV}D{?`>kK7;vH1+R#ox2 zg%SLIqKbD=#amUy=Lq(~F3q_1o5fJYJE-EbFA(PzMqtMteX9|wcn4Ly>@ekfu@`om z#p)6msr9UMqtMteFGG#cnej$#4ARy7j`knwcqrH zD&9gBFENoVjKGdP`j#nF@s_>%JITX$;*Q$1haz4yt(B7tZ%$ zugZ7@RlI{LKKnL#9(@>r-QRJhZ^3Snv(9o*#amUy=Lq)VSShM_2UWc63ug->^ebu_ zsiBH@FEtovr>v`v_3M{nfx0F>yypnHh6*NzDqisKm8kHZ#5aCxGNcTmNP9)}U^ z1r`Z=#BKP{qqH$O!g=3MQ`ed^=?cRPhd~cu^0qg%SMw ziz?nh6)$m@5$pvOOnml>t(EOi#XG3th3#x%1oK!_@eZnZX;F+|FQ{O`Hz&2#LKSbJ zikDW)7DjM;6ji*1Dqi$Bj9@RQVB#F>NBX!;yb%ND7rML&tlv6E4hX~E`};zb$3w3JE-EV zs^W7CBbcG0ig!@OOU}UeVlU|YVyNO(KL}O4gDSqP7$FNIn4zMIcTmNbRVjpEFX$EH z4e!lW9VAro4yt&GaBN`&GgMUZ4yyQARq^?~*bBPL7)o~4b3zsGpo$mnvV{@MP*KG@ zsNzL4$_Vy?el&)XU3IBY#apQ2V^ziH7Dg~bMHO$MiWlzkz1Ryn*chsK)z?B5Z=s48 z?y`ju%urFqTd3ki!^;Tvf}S^ql3f(Q`4?7&yKG?ua~flVr>DmUzSFpX;BRkp*`h2C z-`g%c6(gWHjw@907OHqr7W2K>i|bHS@fNChQ5Lg>5zrz_8M!LnLKPneEg2)&i@6}G zcn4K{q^kIwag2cCSjs5xr-mxtK@}f|{nUIf_Tp9`s(1%ge59)Qob8N&7Fo*3Rq+n0 z_*hl(IfA_^+c{M6ZuPPzqAX?$BcMf=GICYCgDPH>#f)GtjxnN&cTmNPvY0K5fEHQG k$W`$Us`yw{@p*(}FOHR>ig!@O$Eu3YqbMWzJKVlUR zn;%JAWD1!c^5Y|CW@n|{?*ERbOgEokzJB^Mz5D&)@ayeuv44-SpC4Wq&Objqo{7{% zc#jtU}j$MS^+_ryGQh{5uPNhTet1RY#7AJ|xFnZHipNp%{8*xLw1`RTwj z4_%Det1=@!nir=8QB~(1(L{Ns>V~Tbc$A=B-PBi!h&rRHp+C21e&(Y&;6&o>Z=vYidR zRzp3S*Y?H<)j)Og1w?rlc`n{+LyeVy6&)sFQ`w(Kp741%99~2N&qV4;wM$Q622bY| zBG)QOR-y#*vMSd=G={&Y(jyv9BZ4_Zx3hSPFn3qg2eaue4 zR1MlPAAQ)l+Ka{{Hg=F26UfpBiO6-0a1t>X>wZ`zN+2)S$~8PZ3H;X*yVkSHt0d4qqd;g5nF5e(k&vR3wCP1qOZJ95*ZQ}ileH`1nBna1FReU}Q zfn4EnT8Xez!+#IPxq8gsXLwuMZMT$6<+mC&3PBH|P@xjA;pdny8ilvoHUd0yDIxDf z*I27+qe27U`aF_V)xiDTF#&c!c>N^S8_w$0yl$gg%rjG|2A>$}A*}@0szhVWG|Kj-(-;%r z;ZXuM=ka&#qmAO(y-hHe(2EcY{2cQ|qok)h1bFLXQ35vS@ptW`jfy?5ep&PcbCI@v YP69Uk9P55W)Y58<3Gf5L*QgNx0JAh5N&o-= literal 0 HcmV?d00001 diff --git a/GEMstack/knowledge/vehicle/model/meshes/right_fixed_hinge_link.STL b/GEMstack/knowledge/vehicle/model/meshes/right_fixed_hinge_link.STL new file mode 100755 index 0000000000000000000000000000000000000000..0307a31e6c7ffe4b9fe4923a6b43754d0fdbc27d GIT binary patch literal 23384 zcmb`P3A9wjna9fnq9}@J2$4l1vKTdaAV!6EU*A#O!X{BcL>NVl3m_nZ$|5|ML?eoc zI0|MWLU@cQ=mBF0yh~rnAc6`iL=eG<%Ms0}m^g_BGhx2}S4;n^yWdRaoO$Q;;nMZ} z>Z|2js_Nd`#{B>OZ8^Z0jvIEZIpVe%IcmOce(S~q$M4FvA3r?n{M8|iCk@`2J#qJt ztl#&CG@fz)&a8dSo0%~!w=b%@^n{ry2q~$Rk_4sx+DaKC|0aQ0Lj>vqk+^yxm7q39 z$n}@Q+otc{I7oGTxBs+c&w;BU2ODuH@@Ni{;g6Jq<<&rO%E=u|;? z8d4iOtxjIrKQ37|?>9mmG2p_qORH8&L?uoih_iP5dvfdp1C!^|CqX=Qe!6^Y>qrNr zFlOkze9DN~zZ#j|^o8Va!i2Y9 zu{$A7Y&E&K=)RkEKG0^g27Z9LLCME^l(XGa>bewXKQ&zm@`df@laYs@>{XXYo? zEUq9}YS|q-v+d6gtG)gE7~T1gP0#1;>7w(&B}`zvU?p}27r!ty-*u~YwtL5OupnR8+`6CA9J!ZC5f=ie{^pyC5=qEjw2$%Z^$3!IMh!90{ilSPVmQcM~H%IE+ zM`~X$2$q7)M%f^zY!FJAKwLz`L*IcJnFdZu{@zC=yk>9Wf!2$tfAAu(~;hT@Pr#wfuh)d<*{G0nOzEWWm7Vg=!8NO2_6 zT#KIP@MqU{jS6&~xDj#D;@A^9<}Huxrv#TYK_td3_~696+lHiqAX>9B=Eqt|-yffn zUsK;p2{-3j(gYzooF!HeL?_NdGn;F#XfZh7Rnta^sKi<#^f4hiT8_9RfAFtgtsscj zxyJlhuRX8hrTLsgzAR#NoeyeB6NKoHT$@X-tssa_B%@}MYcrc`S6)6QU)yh^5?sQB zi!qtRE79@T%8B{p=NDEGEal>3qm80pd3|#J+YPgo;F2Z?(IL4umt0#x5S>Uy4VlQ8 zfBEI~{Nu~JD#0a8xR~E4`9pME)OBXw|G0mv$Z9Ob`O27YOCB6>XLlvIq#7Z%COWF+ zLCmJ7Aw~JB)|eAI&&c=g{EOy6E@8s;30X}DS!LvYmBCVO6tEW2bpxa=;YPQBmT+Cw z2$@0YN3}eNx;zaj%2z`49yvZ=?^a}7!i2LiWHljV)t6u9R(&kxtP*QO?;nnUwg0ZP zvec}Gx~dW4QKF+-9t7cA0x8N@LdXg^_bX&BVZ!GXi9kZg{v%`qAJ1i8bS*74pne|{ zv4#^u_8-+UPDD`l5kmGKA*;ElrgcS9rOYXW>_4hyPMe8sw)9aH-wDCl+4m4p&0j;x zMI!7!gpmD5PWunPHi(F5+|17w4=C<@ZE6Zj^y^QIiN6*P(6zf*kQ*yrA+wZNqhBGH z5zVV-wWJyWJ;uCw&CcS)fmds*eC|W5{57O_W{v4lJv&DP;=1%6wkA57SOLJYgOt|+ zi_yJ7f%XRQHysn_hwyQXo9?NtUCG{{KzoBwQjNe!SKptz`S5#nkqUbQxt6^_N_zwB zey}%ivjtfzjekQ-OlfbR^`XSJ8FIQe(7vEQx;IE^Zx9Hy84~zN3{KqMK+0urkkZ~D zlrVwu!bsp_jO-0k+8YFdrTle>iPd(HIuE{H%#m1)esph;(%wL|yT}=&Bqt_rZy^1U zy+KNQgHXct!k!Sr@G(aA1}W_g0>M)LI>f|kJ9@QKUoR|BtWiI@H%Mu3pqgFe3{nyq z{Kc9N}1s>MbKA zwpVLaR*jGriVlhG1&ZyyAE91I`H{A*lGt8tbR&YsO>{IdgBeSC9Wt9jEIRh)H4E;X zse1$Ic_YRKbAH2??W=$N+^%fcU6&+?i)c~%nvr^q|JPR#Eak>fYm)4|VP3K2cPA;a z;Ee;b%`>)S56=2-(t6#N#!p_^mUX@9j6~)m!w5jPF{^%XYq8VQHz~m-O#E%(eT{q4 zH?j`Bejvn6FApyc`Nq@=f~B~B#yr^AqBv#gEfxJ>qR?VUW3T=@v%gFkB08?td;R+)k|dyf~}JWvWBQJ;Rt|B)fL$olSasL-yoBe`@^X-hSEL3)f}SS1fNd zX8$)2$d?^HQVA~Ub;Z!^m?>+s1AlpOBiCfim?_QjPY=7KLI)GiTsI~#NX zV}3N}ko@w8hgJ|QMLMMCvwqP$Peu+eClV&cj2@A#crMQ-T{5SSF~?19md~hcRl-t} zMi0%7zG-dtaF2^6503x(0r{{aZO^&nJLCFgzkYmO_T?EXYU5Tt()IJ=cY0NfZomlbb) zV?qVtX-Kgb7<0`SBUq&_&I%wFhj?=I`$TpZETe8S~q- zmlmHs;`(wORSD52gj-ow5WZeW(dY{C$=ElGmu|UA2`*t`Z%yZH>+((6?h$Q-c&7CS z#Y=lujBdtKZ26MU8wM0Ve9d|-c~o>C$LoXN7_;N}QN_PCPO0bz-}yQI)LeT3xtoN z858gQ>8O?Mqz`RtMoO!W+rsVk)`Zaw1WQTJ!-yF3 zRLjE)gC~V38cM1W9hVFh9ap}vtL|WT?~d#8*O20IlU&pGfb`zhHZshb(J!fAye_-{ zi{-TvB@!P$#6q$9K+h9nx=(ACzIUjNi7d5X{D|ZviGx@D@MnEu;_W$yq}@s}G1S!r zA^mW7`@DYyg6j2m`&_H!1Tv))NUZL(qzOWF$O&XhCy;?~>p9SwTR-Z#pD}U*nbHX) z)`wcs1R*-ydRO}q)n!+&dVcBF!8n1G(UlX(lujVArnV*33DF@ZkSU!&27>C@!m18`asrvs38eJQ{#7Hy)LOC}!LJ9+B;4OyE(f5I9r z=r(5ODIXL*>K-y@C}HBSt2-wvmu|{7ZbGj8;m_YJ^nN~M=RmMjoDD{7U0E3R$vB@m zLu_Ya$EFU+m{pszP2I6(XmQ%o!i8v z|5u;;Igq){@Ga&T*Y110_R{#bK9}}pI9DJkv6%2ofL=FE$cSdL-l?Etf?HKaV5O#X z(}d8Glms4Ap~rp3c)2+2&LnGFyXFMN?HqxsiK2Rm~iu7Nu)GuxUYiM8FZBS zV5wd8sni=hstTcWNnZRTb)%~#G|yf~6~gJLAZVT>GL-&8tCV0VZf!~4waSm8*5!Nx zt@1NisUs@!gd5!|{ixFOiay1y;_-3UpBwjo~nnH zcnkM;-;{P^6PIev}h_=Pf6xgC{A`;-k3{!8>p6lQGMVu}>P#{digt zD`d0^=byZ$=GGcBdiE`)y9Le`Mghy1Ms0=aoM9N$%07)~;?} zSd;S_msiNRMoo4V{_;I%X{#2z+BxSECU^~R%wcB@RpPR5w2TOr;t?_C@GGuVV&}j; z(O8uerTxdi<>Qt3^p&S0g7+dkZpLglY?b=p^~=YFH5|@i_!I}HM(8g(3q}!+iO40KCpi@R!qeEkNOTZO3Yc)Cn8vi zXV#c)Up%D!xc$aSQO~(g@oCg~-<+jH?@MpYxul%HSmBv;IobYfw?0*K(+x8s0<@Rn zb3bE>&yHVZqkDbMB}~Y*#$Bu9_20j(PX~Q(!i;hvNP+O@m&Tmiwr>$S9yxCsS`|vT zUOrVd=E+Vr8%&unDd!RnS~mf~|*IsItYCr7K!dZ8xgb7P5W znqP5FEmo41e6YTGjS`)=>YRrXCio;>o?H5RdnNAwvLCD@5G=(lH0HM7G*e>D2g6~z zp@-!}$=X{zwp)9C+QI4{fdK8L;+~)Sz*(we(T2`Z&$)&1>G`_@?LC}b2er((gbDF^ z?Vr87)OWN!WB6guJw+y13fHArvUk;ZZPmLAHI{@DCiqU1F)wz%S&4S{PAhT=6B2{9 zRrY?=rk~mK<6Y}oMg&XYx)j^TyVLm{XYWRA4<$_SohEsb<7j)}k)zwm{tDGpUuihGak`fJbPR05v5V-bI+$UZ2DdARqVN94H zpO6|}dTNSK?iTK|3(VvY`;*Jj5^FXi^?-@`N{_1s3aOL|Ex5R#ra{p%u znW+Q>{6OYhudTf{MSur^f0+<{wfNr7AWF+yg>TBGd}~pLKievaYT6RSSBWKhZKGOA zx0Uw<{^wi8g!sJDHu_j59xHsuQamD7-s_NztUbiqKr)VA+l*Y&9TWJUZxs`gOSDyX zy=$4uRORH}0J|G>|xUb=BliNiEOU2J}9{WI_^zl~v z8XC^6@jci3oOFLMVcM8BBTrB3YW6jJysmr7B}~XO;^DrbG2K?5lQv2}T6FnVM6eXy z$CG}%b=-ioUiwjcL+FRzQRI7qtlOADqX(rEKib!D?AW%E4kr9b7e?8bFRmGsUMR$W zUKbNA6^|9>y!ZWs7h}$&nJV2AF0&HY)sjQIFNR%Ju@b#&O?P{xRm0|=kQSfa*RbNV zx`<$@$U@DYQKzP-HQ(2;fBs2+2K9+?CgQQGGUrOLl$*`O-l=|W`043kGUpFH-#z6L zCfF*~qjK`7%)QBm@yUW0MbFU7=;q#|~1wuwWoHH6D{*jY^;JHM9-x+TJ z>KirE!c6?5PwYDAYf4 z@{d5Ul=uf)TWjyQi+|+gAEAWbF^O9x{*jY^1RYFZ)r8m?{39p-2n0*TVxiy_N}QmFl&T9U~j$J~BilRIjsL7uzKplh$x$+s6tD8Aq!h1kZwmKxpicN;);wF<*1xXm|&}nauiyXxyS&I z^4SMt<$Y6hP>w>+OC?0esQVlx1o?SHu#~%YK1f*&cI9I`JPHw2-)omXAs%DZCpyHV zd{&DHmU5B0);=3WS*kMdb9B3R1x4_R9X z%4)tJTH*;!!@UMFdO5V@0tY9)-EJGgXT1WmX~{mAm{A z%{k={Sbi2FI97eRTlGZ*OGOsSdCDAk}y#H{{)e!;O zOU13a>XB4ib?tAzo#Ocpv`Xs7yHFZSu$tx88Y927pag!qCMqc-&^P^oQrstF;&&<@q=W@70lp-Y8y0I?4%=R^OL<^cxS-8NBVvVG%(QE}G3K?&=Jp z?U)NDWG*mv2}ay-yov~xifqC7C!_H@4Tu7Md|<0$nfhxE@CJNubBcf08NUU=CFO)j zyB*7M6Bg-d`L!p;1ZXcsnMnE}ty03Z%I7F4DG{PipP+>Q$a69~2581Pd+Su4LFz}4 z;+d6P>we8aerpT!k$}M5BHD;O;iD@-Uz1pg`+Y6^dIXPEIpM8GTU9`tU8}7taZO}^C6t`A$trGa1hNz^BKn>`h+O86kYa;@*m*PHYEKvf#C4?EnOu_%q2lPcg z>Kpi8TZ>$)1b(f6`%z9nk0m76Dj~TxB0vWz>XT*zC0zc{R{1%`zus=qDqL$eP(rc+ za+D|3Zao2Ofz`l zFGZsug#T3vtd_W>yicWmNOo2olATksEApr@qc`{Ce6-D zNOq2N__{setWtDHc2+{Nb3~Bs>U^Mu=u63?@Qygo8WS|7 zqmN|gl;V|IH(KIH9RK2@*;xsDk_7N`9fnG9!R^p@CS;tDUb3~wC zFNG2Iv#Hrx3AZZ>B}`y0Fn0Jv5l-ja*TquMQL+-rI7Rpae%(>pp82*T3i$ECwI8=A z52jqg1fmXX8J{TEMno(XRscfC3P7_n-o--epdH>@PPp7IgscGSASo+=h`@JVN?Pdi zqivNEczY`@DG~7ZQa@w`pmQ#{HX>LGHTiLaZv2%ZkncyiKAk5k+ysHIy_C>29~QGZ z#0oMUu~+FpEGe&^7sjD3JYKDkRQ41y`-x5afMa?=#c;H z`}dO3O|B>ybMfat7W+@?C5Y>0_Dl|Hz9jj4)t-g3iWenKIxkM5{=1T9CtR8|7?(=f znAxMwPoIn$31ap7Lb7DfzR8^*RTZ8cy&(DR^S38S*B*tRezhR!wC5d)Xx?N*+_GuA z9Ji|Jx9>$C_UTm7_^ryqk_+F727UcP#pPo<`!d@T8!_3489_E8vJt6`h-^e^BO)7- zMf8YIjN8oXD2NrKXGHHDJ2`57WUs=;!UNIUht7)jp3$e!**q8>d)X{Sd~)Z}asK(v zf`SF|#0=39j5&24Oym85@Y0@b`JqiO2s>G-&vRG=eSi9pll*pO`_Q7J9^(u7?hfcmHghjE5To z_M$8Ec)Zr|ji}ETCuu*bhYX8f95y{bu-3J|S`*#>+x?=xub)v1aelYK@#6Z61%Y)T zqL{uO&7FTzbk8rkP(N1h-zUEQ{4X;I)IuK`bNaizjqvGg?Muas65w6TyZ*G4t8d_74zhZ4A>D@AEWc>7D8w7z8M5w*IwbB2O z5%K1p?TTyz5vb+LJhH|-e$h>F?uwfPff85ddZ)Hu6MZmYzhv&}GYE0xz+v%~vGAisXXT0 zKkpqMaQnA{KnWsr_Gqh4U4L=BpiRA$eT4|rdVNhH>e#4n^4Q<2$i`M;pILJ|3PRU& za_FD>6b>FUBf9U{$;nTNiQMnD=k4C?7!PcEVt`-?B7UEr7fpZa-sJ8}c%3I*PKz6D zY?VQv7Pios6UUqz|NZ+WfDB4N}?-G6;ueE%ci(LrTmL zvke{dNZBAE9*md=-S5^{#G)y&Xna9uPsf^T~eRc zhmG4UC!TWZmg3~uS7Z>VwR6*P$#;{NC++rVLN?~^*imf#!)1cNdhwiqXk%8qzpGeX zWls|*DTlDLgt$F*+>QuWW-Zz!5{kl0`$tMqxU>o-h(HE6h9doxBK-^kwJ7RO=$w%7 zIl&k@O{8?15ClpP5psLK1#OGZ9X3J`c*4Sy*B;OAo4k7Q8tuod9%mNsIqAOzff7VK zJ!^b^UA!@w_hxHq)u{unF22#?<_rS0p4pz}r+m60`Rn;d6XLsicNe>UIb0AZNe=il zzr5?Zq`{Du1+;C<%X1zo_MCft#zr~BeLIgJ8&ivE@r7Q4GYD5NYq_zpGqKs%uM{VA z9V7^pAY$auLz4Ptb+V=Y;bbE}b4~G^3$Dr_P%E6f{VrV*J@VNoLC|PvOQ)*zfM#J=^Vg zEN%U1#maNmC9hxIvOr@~;YN+T5S3=hO_f*YI=Av;?j?xWcIxc;_C;GBO99@SyDMl^9+b^W!6H!NuD9+@(eWQ zd`6bohw==O%QFy5L@xgzT#^GW@d(s%HQ9O9ZRd{Mknb&Dp#%{Rz1ua~XW7!^!=yg- z}pJ#Q@7+EDY2-R{B6^5(N1E{j>Mc;lQGZET$B5@GzaX3zOI(?~p#2cEa7m81B!fUL zSGG1T*l=TRRNtEfff83{8#*i1#ncDbFbyf)`l{*>$zyvM$p(K zoWEjw#?S~B-3Ve`sO8GmhVJKL10}A^_3EyzHt0Oa`*{X|S{MfzLubyE&YXfkNjU_c zMdf^+()m1taA-ZNLwq%^)sMM$D{Uk*|MBio&!?6oPxe}!IKG> z?koB&k2tHwr@M-iceeFqi_lD}v`SAu(FNaZ&g+>oy6;a5^Dbue2+oV9yaqK-l_-Mq ziHRaO�}^45T2aE-%r1q9Di%oEKGuW*`ND5=3ZjF=;SpTHa?MGYHhu3}h1jdl z16kyLP~;u)Ntk;`zT%8<9?R@EV>AOP2&cso%_kz?E3}nUzA~aK&JUD58 zvY{Es3<9;#hdu)-2$Uc~bBoEM5qpyj%|K?x1GR8ueXg&PeWg9GVEO59dphn!bzBCNyG@vEk=!2Hg~NOkNBKruC}krA*>C}i)Ikc)2xMl^EtAZZRnUs zCofx=*SuJC<(AF7Y9-fieWm%t0KpPO(213EmeI>Id6sC-Qd)&|p_a~e@rcih3IZkN z5ZCYBfNXH?6;8t5yAI7-=r^BF4En)6#};aCG3rq9D6MnNSqcIrh)|BverR4agFr3K zkw!ZXV=mFNnjrK{7BS1{xh)!>J1S3T&h@DcJr4>3C5Ui)$q8L|Euy#t_9#T4mfPX% zm}>@7Y*24G11Z*#+p#8j^1~U(Osf!~xy8uyE@vP!2-HH4_za|*?XoX%dug`&J&ML( zvLd!0nt==u%DbF_jFfi)p&3Xw6TL(;kb=-mVdQz2GmsesYM~E(22v0xL4@WOBhR~> zfy|5tYT+I%PkuPpCoEcSKWG0C+tErg#3G*8T)nKNdAL0D zyw8gY0wsu0d$Nlfqq)8!w-XVl<;s>5>B$f069s`1SLRk}jx1pgmM1?cJo(`~rAQE= z^D41D=R6!d`SA$Ua%Ia`^yG(gebOqFxH8vEY{&V;#Iq>p69s`1MCk0%R%y;MWnUoz zwKRX3FwgtQQV_bHlWW?v%xktTVUBXY+n#H#FF>#a5t=njJd1KZF@r!YY@yFt3IZkN z5X|5{zneigwC-@6xz(O)6dtsSdyc(TeoO)u6$DBUp)9K7f!RSspq49J8^3P5CAWHx z&2ldK;<#wQq~*zuhO?7(*Thl3{>zdr(--=<-6F0iY|EW}W0(VA2_nAxuxnKRm8Hq} zX|K?1f4IYr+}CY-OFvM8=LBk%oZGF9PEB^@YR3A!sF##O*jb{dZLxuMxiV{!NBDL^ z$-8_z!Fkt95J8@XNMCP2WDuxDdm`VTNO%{Oy_RoT2m&RD2qXOl|F|dDYOKw8-Ll8x zifNy0NOFDdNjA0pq2kF-Ym>DzC-R9^@(Jn$%%U^5Eo$ zXgmfK)7+9$2GZAsTFwjB#$*3{H5YBZI^$hLtXa`4YFKYoa=_^6WaGhkYja>yizd()ytzu3Gf>D_oF)oY(TEqP~zl==U+i48r`>)4jG==TcF zW!irH`7b>xm#Ph{E52({rvYT6)4?N?5Yc+^g37IX`&Rk7${}{Ve;c(*^ChlT9^vX` zt#AaVGW{3EDrE5gSg6 z5vb+L)&^x#eLfK-uFN)cwyO=ySvoDQ3$zl)h%>3y24zxx4%umOUDPM9<;vCuWm0{f8YQmG^^(^k&ZJr!m*Q*hL+Q9pXPK)b8E#0Zb>yk<3+dDE#P*M)Tv7Nu^ltDPO#=d;( zNzdmz%k970Qu3~hpk~Zv)VQpzO>EZL>GNLbTB3PliE03$Ib=k*p4WjWV*?S`5;soS zR-ptDZuZoP5bLTXWkNG6mG6g_AVPgurXSj>Oug8`lBd|aD8ZIcP0VBETg9_lY@n95 zstkfg&_BJ`vS_J2sVUPc?zu?HAj;Uly2|vUj16tONDxt{cVpKQU3bzaUFR}RcAb}c za$D@`tpkx{5jxJYo?V|-OexsgBJk zzL!QvPEM1#hkTX1I^mLN-l8-)dGUu*W(1dw89R2YWLMr_G(5(L72{nlGr~stE8o2- z5&ZqOt79A~96^p=x#xUV zH>UkL9|&UmwElu{=OsKxg@~~e_Lf$)yW*l4CAAUm3`f)BR(p4M%rR#K2#llAhm-^O z_-L^)zgOpAJP_en!p7}O`<*O^hi9D zTM8!%f_+sRQDV{GRb3^B=tbdOkKlTp7W$3u8vJI6AZ~4uFYK-=N`w7+kowh?3ff(tWu3#(KA7_uU0V;O#c_2tC2dTg3Xg%L^z$g!8n$y>rRi zHUgN{>d*jzS{NA^Q*(r!?H3)_ImNqUc=L?Q+;e-Eb8E-;((`>@ZYVic;gd2VoaZN?atX| z>F~f;h;VzNyfXuQp=i!>%KO@u-a`d3WZ}6|y_edQrwh zZ16~Ny-o|qhPwRxHnCB0bDyB+>;>0byuWSCG3OkRvai0lxqFHdM9|z#N~`vz0Y4YS z(79a#1Zug+$=(Z}a`@STIFVK@ts<$5IT7z^BifiRJGK|ZuGfSay!G0M(oNZ$zqV1| z+U}iseRu?yomSYY$9_FTY@FOK&%7%LW@LQ70b5Hu&MSQdF(EI^;QLVI}IrscA$i4FEH*Xy*< zZ#)P2pMBHFM?wU)3K8M{QCF)_3q2Cr!1atQfwn^gN)UnkST_Q-&?6y&W`?W}jzw_= zqwNrZ5=4Zn)?&(zpxEPaMvsIxa2?R>lQm(_PXEaWB7)|z*t2Jxx>|)==n-Qc`{mYR z_ow>BjKr7|W6=k9H;pD7vr671F=qd3KFU4yo<*>K9E&=>;%6blCpAgF9<)mDmrVZs z*4*wHSp;e!qtbKdZ$2vaTx1c>I@jx3#bsU}&bBd)-rrh$Xq30%CD6gq2i-+ug@SHnzjCV+VqOekG`utA2i{*;v3J~vlL3oA*_wZPy4QL zM++loGGq4vZN4E6lLW8^Pi2^0%5Z1<)RaaMbeISc)Xx6&$H;?3- zEq47FcHZ{Ny<*!cl$1kQ8^1XAnq1${Y|jzl%B+RsPkEmoAI$Clx%Dne$|0vOM8)*=Rc+h(HM< zC|Z(do>>IWa5qa>i)u>vNkbNa5=6N1&mzzUqOrB5UU1J*f(VWJ%C|~#_iP=t(1)Q7 zx&!Cmo6zT+GQ-_7&ul+Xf(UGFXafOV#em0arh`q4qSXY@Ama##;^0&DWq5UX>C^LehMK?kD-g}u=p#;Z9Ybs*{ z5vZlV*NqSf-IV1wU*tUotSR&rN)SO=+lV!@BZvspQncO?E?K!P#ntIp^gkbSL^yuT zwhG4_wQ# z`lH1Wp&Dc9nJ9kKc`W4+ zfwRH!uJ)r28)zL7j`Pd*!`Fpc$T4B7a5lIdhwH`B3=t?ngw`bA{iz#)S~`!*%o3C! zLg#TA1Zl}TQP!iD=fS&W#zVa;61QhCLTi%mJB9r~1Zt5-Bsybsh(HMwi}BLat~0+o}ms`{UPi?0MZ9Tcw^T2=GbnPICC5x$`?m3rQ;!GSezQqQq2)IyKY4Tw%H;&&%h)C{}) zjKEijz;~bN+4ktK9pZJD?5rO0L)#eN z;ly`FL&V#sw2hlxx4Qa=v_p&%M7UL8-}%|M>#=dSr)#Retjq-n)CzmPro*vuk;dbQ zs$7h1$9KcgwlNES**4y_12RF)?c4JJlg#;!jVHuP{5Sk6zI-@Gc_Wc;L0D-^2wSj~~7-t-+(dJw3j9kDb+j zNLmC4)N)*6-&cEJTDSOY>PL%ZjbnU+m{zSs`uwgPqUr7K^UjTLK4oWh^U9_%N)Qpg zk(-}zR{Tceoz=5?HV+V}6}IYv&8Nq0s2{&v+aku^;v4H|+n7$bpA`=|WM}oZfuRjV z;5+rkoY(!__;%{YRUN{9pqBP2Z{IjLQI9|^ZIyC6v1oc5@vgF{ zZ!d8ofAdP-kPcf#ESe4_ZdVrdHV{E<$KN)TcdaQmOg#q{^$66$w-1Fy)8RC)ltsO- z5P@$p3yY?}q8@=-#6AhJ=pxUeDX^%2Hx%FD3=zbl=`+Mv%A&q5M7X`yvuJwc#Z@)R zq8@=-Vb6(0)7>;4%A)*DNqM6i-}DY!MJ$?*AZ}L{^)?U@zP(H=ngWY@1Zv?MuEL@z zuqc1mS-wVsZ%Bs-V$l>>)O!~Zv}zM#(U&}nrof^efm$y1^(>kKi}JT0xc;7UM3bzfkiz6wZc{ri>AP${H05I&m7-B4_ienngWY@8;HO+F(qLF39Uk(gg#j&WeXkY^o8Z*kb%7sN;EE*tC3q4|EQDxDiOYB!qAr?(F#*r_HyI70A_loEs7EMut2#qrJ>)#NI z1_;y&TLrObioMmyQoak1wu4wSuz?7TGUc1}K`a^|P)qwHe}}*rh(%MBXk;mWxgcy6 z#G-)>M7Su^et8&T(Ex#3I8H$<%FMv=RYzq}iRY9>xvXzHaV)AQdS2)L`?MNa%6DY3 zCL4?Di9WD_2#qo$`&~6+(Ns_L0RpvLglyl5<5*Nr^vt5Zy&732%A&r1^!-GNMfF4< z*g%BFjQX8zh(!YgYN1DLEUG8^z*mUSC{w@wO)TnS(Ex#3#6BE%b@D9gVo_eT9Q(+3 zk2SKCFDQoyjz#rE&+OytLWD+{@-1d#h(%L9(FX|B3VY76sGjJVMg8~9HL{ey=7F|_ zMN>V|2R0C)QKtM|5Mfaliv|ePLXQNoD6^>l8zUN7%2&lh1jM3&cM(CWmgALNpub&V|LEAMDqSk%R$fel1xlqp}B4`R^(fm+(9y#2yBv8anhnMK(@BGJfFzK$NY Y3S!Z~1|nRP=~>jpq5%T6aGZ?!U+Foei~s-t literal 0 HcmV?d00001 diff --git a/GEMstack/knowledge/vehicle/model/meshes/top_rack_link.STL b/GEMstack/knowledge/vehicle/model/meshes/top_rack_link.STL new file mode 100755 index 0000000000000000000000000000000000000000..33cbd12b11c1623b2262268c1a96b00d86eb80d9 GIT binary patch literal 5484 zcmb`KJ&qMQ6h=EHKw5GoSVuJe1V>iNwtwGZOH{_p?IcKw(@ zNkV%i?3}FHrH5}$fptIQbXnaapwUiS|NKU`X21RBN8KCNi}ydSk3=d-K(VttkBRgm z5;NQK*vCYA@)Mh zW;eC@{o+C*y=I!Kn)ghoB!Qh3jyaOhi>h32d8{gxIj;0Efuh%O=d&Ww;^xn+YMf&8 z$|*cNuM?>xL7&pC=Q69B zBZ=9IJ?~X9uX4A4vZ_K3wHt}`mO~;HY2vy*_5sS|e(bV>{ z^}&tIS>l_;vkOgCu1hr{l_c5lbcGVwWiOz9QOKRT6mFpX;5N z7310yG~Rs1SrIF}j5K^Z*UnQ(LfcvOcM!!Br&lT93cKXpd81O9iCX;cA7c(9 zZ}62snF;9qKFE;-UeNTnpF_nQ61o3lRY~Y&4&SJiK*1{s_rFcUo58<7=1Tk~vh#lX zq%!BoSsfF4l`89Px8_JCXVq%&`_XeGkzTAb!~Gni(&IX}7Rg!7vGmFrj>N1;@o-QTyvJxk<5~*Yk_vSp2UheElq>=5ZC2ag zJ`yN1;Thv3t~rt@WIe}Jwe9(m1H~LkV2`JrH^*4m#iM>_xKHNjH$y5(uusxsjwI5{ zoi#^4iK*-n_OTKuGeK3YqB7m>?3yD9yj+*y*}ucc3DQR=` zcd+bGy#Y|Lov7>Eer)exDl-A?H|LszSQ2;{NuuuuUFA%ysyw%9Tj&0FH!Bk6v-6%K ziS)9nPPiWu^r7wC+?#PfjCDk;Ijn>@o-1tE%k%dQXH}^rp}i8GJ``;#IVMusBi247 u+-LR!+x24t#h#M>GXgJjtevM~4&zdxHWTkR9E!2@l6Jilvm${ Date: Tue, 6 Feb 2024 13:56:25 -0500 Subject: [PATCH 083/232] Better model name --- GEMstack/knowledge/vehicle/model/{gem.urdf => gem_e2.urdf} | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename GEMstack/knowledge/vehicle/model/{gem.urdf => gem_e2.urdf} (100%) diff --git a/GEMstack/knowledge/vehicle/model/gem.urdf b/GEMstack/knowledge/vehicle/model/gem_e2.urdf similarity index 100% rename from GEMstack/knowledge/vehicle/model/gem.urdf rename to GEMstack/knowledge/vehicle/model/gem_e2.urdf From f04dbb6802c17600c02bd935e148f1df2c0eb618 Mon Sep 17 00:00:00 2001 From: krishauser Date: Tue, 6 Feb 2024 21:20:26 -0500 Subject: [PATCH 084/232] Added simulator and changed launch to --variant=sim --- GEMstack/knowledge/vehicle/model/plane.off | 8 + GEMstack/onboard/execution/entrypoint.py | 24 +- GEMstack/utils/klampt_visualization.py | 276 +++++++++++++++++++++ launch/fixed_route.yaml | 22 +- launch/fixed_route_sim.yaml | 69 ------ launch/klampt_visualization.yaml | 7 + launch/mpl_visualization.yaml | 7 + main.py | 2 +- 8 files changed, 343 insertions(+), 72 deletions(-) create mode 100644 GEMstack/knowledge/vehicle/model/plane.off create mode 100644 GEMstack/utils/klampt_visualization.py delete mode 100644 launch/fixed_route_sim.yaml create mode 100644 launch/klampt_visualization.yaml create mode 100644 launch/mpl_visualization.yaml diff --git a/GEMstack/knowledge/vehicle/model/plane.off b/GEMstack/knowledge/vehicle/model/plane.off new file mode 100644 index 000000000..5ce7162d9 --- /dev/null +++ b/GEMstack/knowledge/vehicle/model/plane.off @@ -0,0 +1,8 @@ +OFF +4 2 0 +-5.000000 -5.000000 0.000000 +-5.000000 5.000000 0.000000 +5.000000 -5.000000 0.000000 +5.000000 5.000000 0.000000 +3 0 2 1 +3 1 2 3 diff --git a/GEMstack/onboard/execution/entrypoint.py b/GEMstack/onboard/execution/entrypoint.py index cf6f74af3..33c707822 100644 --- a/GEMstack/onboard/execution/entrypoint.py +++ b/GEMstack/onboard/execution/entrypoint.py @@ -5,9 +5,31 @@ from typing import Dict,List,Optional import os - def main(): """The main entrypoint for the execution stack.""" + #first, process settings variants + if settings.get('variant',None) is not None: + variant = settings.get('variant') + variants = variant.split(',') + for v in variants: + if v not in settings.get('variants',{}): + if v not in settings.get('run.variants',{}): + print(EXECUTION_PREFIX,"Error, variant",v,"not found in settings") + print(EXECUTION_PREFIX,"Available variants are",list(settings.get('variants',{}).keys())+list(settings.get('run.variants',{}).keys())) + raise ValueError("Variant "+v+" not found") + else: + overrides = settings.get('run.variants.'+v) + print("APPYING VARIANT",overrides) + config.update_recursive(settings.settings(),overrides) + else: + overrides = settings.get('variants.'+v) + print("APPYING VARIANT",overrides) + config.update_recursive(settings.settings(),overrides) + #don't need this to be saved in the log + if 'variants' in settings.settings(): + del settings.settings()['variants'] + if 'svariant' in settings.get('run'): + del settings.get('run')['variants'] multiprocessing.set_start_method('spawn') runconfig = settings.get('run') diff --git a/GEMstack/utils/klampt_visualization.py b/GEMstack/utils/klampt_visualization.py new file mode 100644 index 000000000..b66b3720d --- /dev/null +++ b/GEMstack/utils/klampt_visualization.py @@ -0,0 +1,276 @@ +from klampt import vis +from klampt.math import vectorops,so3,se3 +from klampt.model.trajectory import Trajectory +import numpy as np +from . import settings +from ..state import ObjectFrameEnum,ObjectPose,PhysicalObject,VehicleState,VehicleGearEnum,Path,Obstacle,AgentState,Roadgraph,RoadgraphLane,RoadgraphLaneEnum,RoadgraphCurve,RoadgraphCurveEnum,RoadgraphRegion,RoadgraphRegionEnum,RoadgraphSurfaceEnum,Trajectory,Route,SceneState,AllState + +CURVE_TO_STYLE = { + RoadgraphCurveEnum.LANE_BOUNDARY : {'color':(1,1,1,1),'width':2}, + RoadgraphCurveEnum.CURB : {'color':(0.5,0.5,0.5,1),'width':2}, + RoadgraphCurveEnum.CLIFF : {'color':(1,0,0,1),'width':2}, + RoadgraphCurveEnum.CROSSING_BOUNDARY : {'color':(1,1,1,1),'width':1}, + RoadgraphCurveEnum.PARKING_SPOT_BOUNDARY : {'color':(1,1,1,1),'width':1}, + RoadgraphCurveEnum.STOP_LINE : {'color':(1,1,1,1),'width':2}, + RoadgraphCurveEnum.WALL : {'color':(0,0,1,1),'width':2}, + None : {'color':(1,1,1,1),'width':1}, +} + +SURFACE_TO_STYLE = { + RoadgraphSurfaceEnum.PAVEMENT : {'color':(0.5,0.5,0.5,0.2)}, + RoadgraphSurfaceEnum.DIRT : {'color':(160/255.0,82/255.0,45/255.0,0.2)}, + RoadgraphSurfaceEnum.GRASS : {'color':(50/255.0,255/255.0,50/255.0,0.2)}, + RoadgraphSurfaceEnum.GRAVEL : {'color':(0.7,0.7,0.7,0.2)}, + None: {'color':(1,0,0,0.2)}, +} + +REGION_TO_STYLE = { + RoadgraphRegionEnum.INTERSECTION : {'color':(0,1,0,0.5),'width':1}, + RoadgraphRegionEnum.PARKING_LOT : {'color':(0,0,1,0.5),'width':1}, + RoadgraphRegionEnum.CLOSED_COURSE : {'color':(1,0,0,0.5),'width':1}, + RoadgraphRegionEnum.VIRTUAL : {'color':(0,0,0,0.5),'width':1}, +} + +def plot_pose(name : str, pose : ObjectPose, axis_len=0.1, label=True): + """Plots the pose in the given axes. The coordinates + of the pose are plotted in the pose's indicated frame.""" + R = pose.rotation() + t = pose.translation() + T = (so3.from_matrix(R),t) + vis.add(name, T, length=axis_len, hide_label=(not label)) + if pose.frame == ObjectFrameEnum.START: + vis.add(name+"_origin",t,color=(0,0,1,1),size=5,hide_label=True) + elif pose.frame == ObjectFrameEnum.CURRENT: + vis.add(name+"_origin",t,color=(1,0,0,1),size=5,hide_label=True) + elif pose.frame in [ObjectFrameEnum.GLOBAL,ObjectFrameEnum.ABSOLUTE_CARTESIAN]: + vis.add(name+"_origin",t,color=(0,1,0,1),size=5,hide_label=True) + else: + raise ValueError("Unknown frame %s" % pose.frame) + +def plot_object(name : str, obj : PhysicalObject, axis_len=None, outline=True, bbox=True, label=True): + """Shows an object in the given axes. + + If axis_len is given, shows the object's pose with + a coordinate frame of the given length. + + If outline is True, shows the object's outline. + + If bbox is True, shows the object's bounding box. + """ + height = obj.dimensions[2] + if label: + #add a point at the object's origin + vis.add(name,obj.pose.translation(),size=5,color=(0,0,0,1)) + if axis_len: + plot_pose(name+"_pose", obj.pose, axis_len=0, hide_label=True) + #plot bounding box + R = obj.pose.rotation() + t = obj.pose.translation() + if bbox or (outline and obj.outline is None): + bounds = obj.bounds() + (xmin,xmax),(ymin,ymax),(zmin,zmax) = bounds + corners = [[xmin,ymin,0],[xmin,ymax,0],[xmax,ymax,0],[xmax,ymin,0]] + corners = [list(R.dot(c)+t) for c in corners] + corners.append(corners[0]) + if not bbox: + vis.add(name+"_bbox1",corners,width=1,color=(1,0,0,1),hide_label=True) + else: + vis.add(name+"_bbox1",corners,width=1,color=(0,0,1,1),hide_label=True) + if height > 0: + corners = [[xmin,ymin,height],[xmin,ymax,height],[xmax,ymax,height],[xmax,ymin,height]] + corners = [list(R.dot(c)+t) for c in corners] + corners.append(corners[0]) + if not bbox: + vis.add(name+"_bbox2",corners,width=1,color=(1,0,0,1),hide_label=True) + else: + vis.add(name+"_bbox2",corners,width=1,color=(0,0,1,1),hide_label=True) + + #plot outline + if outline and obj.outline: + outline = [R.dot((p[0],p[1],0))+t for p in obj.outline] + outline.append(outline[0]) + vis.add(name+"_outline1",outline,width=1,color=(1,0,0,1),hide_label=True) + if height > 0: + outline = [R.dot((p[0],p[1],height))+t for p in obj.outline] + outline.append(outline[0]) + vis.add(name+"_outline2",outline,width=1,color=(1,0,0,1),hide_label=True) + + +def plot_vehicle(vehicle : VehicleState, vehicle_model=None, axis_len=1.0): + """Plots the vehicle in the given axes. The coordinates + of the vehicle are plotted in the vehicle's indicated frame.""" + plot_object("vehicle",vehicle.to_object(), axis_len=0, label=False) + R = vehicle.pose.rotation() + t = vehicle.pose.translation() + T = (so3.from_matrix(R),t) + vis.add("vehicle", T, length=axis_len, hide_label=True) + + xbounds,ybounds,zbounds = settings.get('vehicle.geometry.bounds') + #plot velocity arrow + R = vehicle.pose.rotation2d() + t = np.array([vehicle.pose.x,vehicle.pose.y]) + v = R.dot([vehicle.v,0]) + front_pt = vehicle.pose.apply((xbounds[1],0.0)) + h = (vehicle.pose.z if vehicle.pose.z is not None else 0) + zbounds[1] + vis.add("vehicle_velocity",[[front_pt[0],front_pt[1],h],[front_pt[0]+v[0],front_pt[1]+v[1],h]],width=2,color=(0,1,0,1),pointSize=0) + + #plot front wheel angles + wheelbase = settings.get('vehicle.geometry.wheelbase') + wheel_spacing = 0.8*settings.get('vehicle.geometry.width') / 2 + phi = vehicle.front_wheel_angle + if vehicle_model: + q = vehicle_model.getConfig() + lwhindex = vehicle_model.link("left_steering_hinge_link").index + rwhindex = vehicle_model.link("right_steering_hinge_link").index + lwindex = vehicle_model.link("front_left_wheel_link").index + rwindex = vehicle_model.link("front_right_wheel_link").index + rlwindex = vehicle_model.link("rear_left_wheel_link").index + rrwindex = vehicle_model.link("rear_right_wheel_link").index + q[lwhindex] = phi + q[rwhindex] = phi + q[lwindex] += vehicle.v * 0.2 + q[rwindex] += vehicle.v * 0.2 + q[rlwindex] += vehicle.v * 0.2 + q[rrwindex] += vehicle.v * 0.2 + vehicle_model.setConfig(q) + else: + left_wheel_origin = t + R.dot([wheelbase,wheel_spacing]) + right_wheel_origin = t + R.dot([wheelbase,-wheel_spacing]) + wheel_width = 0.5 #meters + wheel_offset = R.dot(np.array([np.cos(phi),np.sin(phi)]))*wheel_width*0.5 + vis.add("left_wheel",[vectorops.sub(left_wheel_origin,wheel_offset),vectorops.add(left_wheel_origin,wheel_offset)],color=(0,0,0,1),width=2) + vis.add("right_wheel",[vectorops.sub(right_wheel_origin,wheel_offset),vectorops.add(right_wheel_origin,wheel_offset)],color=(0,0,0,1),width=2) + + #plot gear + if vehicle.gear in [VehicleGearEnum.NEUTRAL,VehicleGearEnum.REVERSE,VehicleGearEnum.PARK]: + if vehicle.gear == VehicleGearEnum.NEUTRAL: + gear = 'N' + elif vehicle.gear == VehicleGearEnum.REVERSE: + gear = 'R' + else: + gear = 'P' + vis.addText("gear",gear,position=(t[0],t[1],1.5),color=(0,0,0,1)) + + #plot lights + light_size = 4 + light_color = (1,1,0,1) + turn_indicator_height = 0.7 + headlight_height = 0.6 + if vehicle.left_turn_indicator: + lp = vehicle.pose.apply([xbounds[0]+light_size,ybounds[0]+light_size,turn_indicator_height]) + vis.add("left_turn_indicator",list(lp),size=light_size,color=light_color) + if vehicle.right_turn_indicator: + lp = vehicle.pose.apply([xbounds[0]+light_size,ybounds[1]-light_size,turn_indicator_height]) + vis.add("right_turn_indicator",list(lp),size=light_size,color=light_color) + if vehicle.headlights_on: + lp = vehicle.pose.apply([xbounds[1],ybounds[0]+light_size*2,headlight_height]) + vis.add("left_headlight",list(lp),size=light_size,color=light_color) + lp = vehicle.pose.apply([xbounds[1],ybounds[1]-light_size*2,headlight_height]) + vis.add("right_headlight",list(lp),size=light_size,color=light_color) + if vehicle_model is not None: + if vehicle.brake_pedal_position > 0.1: + vehicle_model.link('rear_right_stop_light_link').appearance().setColor(1,0,0,1) + vehicle_model.link('rear_left_stop_light_link').appearance().setColor(1,0,0,1) + else: + vehicle_model.link('rear_right_stop_light_link').appearance().setColor(0.3,0,0,1) + vehicle_model.link('rear_left_stop_light_link').appearance().setColor(0.3,0,0,1) + +def plot_path(name : str, path : Path, color=(0,0,0), width=1): + vis.add(name,[list(p) for p in path.points],color=color,width=width) + +def plot_curve(name : str, curve : RoadgraphCurve, color=None, width=None): + style = CURVE_TO_STYLE.get(curve.type,CURVE_TO_STYLE[None]) + if curve.crossable and curve.type == RoadgraphCurveEnum.LANE_BOUNDARY: + #style['linestyle'] = '--' + #TODO: how to indicate crossable lines? + pass + if color is not None: + style['color'] = color + if width is not None: + style['width'] = width + for i,seg in enumerate(curve.segments): + vis.add(name+"_%d" % i,seg,**style) + +def plot_lane(name : str, lane : RoadgraphLane, on_route=False): + if lane.surface != RoadgraphSurfaceEnum.PAVEMENT: + style = SURFACE_TO_STYLE.get(lane.surface,SURFACE_TO_STYLE[None]) + outline = lane.outline() + vis.add(name, outline, **style) + if lane.left is not None: + plot_curve(name+"_left", lane.left) + if lane.right is not None: + plot_curve(name+"_right", lane.right) + +def plot_region(name : str, region : RoadgraphRegion, color=None, width=None): + style = REGION_TO_STYLE.get(region.type,REGION_TO_STYLE[None]) + points = region.outline() + pts = points + points[0] + if color is not None: + style['color'] = color + if width is not None: + style['width'] = width + vis.add(name, [list(p) for p in pts], **style) + +def plot_roadgraph(roadgraph : Roadgraph, route : Route = None): + #plot lanes + for k,l in roadgraph.lanes.items(): + if route is not None and k in route.lanes: + plot_lane(k,l,on_route=True) + else: + plot_lane(k,l) + for k,c in roadgraph.curves.items(): + plot_curve(k,c,color=(0,0,0,1)) + #plot intersections + for k,r in roadgraph.regions.items(): + plot_region(k,r) + #plot + for k,o in roadgraph.static_obstacles.items(): + plot_object(k,o) + +def plot_scene(scene : SceneState, vehicle_model = None, xrange=None, yrange=None, title = None, show=True): + for i in list(vis.scene().items.keys()): + if not i.startswith("vehicle"): + if not isinstance(vis.scene().items[i],vis.VisPlot): + vis.remove(i) + #set plot range + #TODO + if vehicle_model is not None: + vis.add("vehicle_model",vehicle_model) + xform = scene.vehicle.to_object().pose.transform() + vehicle_model.link(0).setParentTransform(*se3.from_ndarray(xform)) + vehicle_model.setConfig(vehicle_model.getConfig()) + + """ + if xrange is not None: + if isinstance(xrange,(tuple,list)): + ax.set_xlim(xrange[0],xrange[1]) + else: + ax.set_xlim(-xrange*0.2,xrange*0.8) + if yrange is not None: + if isinstance(yrange,(tuple,list)): + ax.set_ylim(yrange[0],yrange[1]) + else: + ax.set_ylim(-yrange*0.5,yrange*0.5) + """ + #plot roadgraph + plot_roadgraph(scene.roadgraph,scene.route) + #plot vehicle and objects + plot_vehicle(scene.vehicle, vehicle_model) + for k,a in scene.agents.items(): + plot_object(k,a) + for k,o in scene.obstacles.items(): + plot_object(k,o) + if title is None: + if show: + vis.add("title","Scene at t = %.2f" % scene.t, position=(10,10)) + else: + vis.add("title",title, position=(10,10)) + if show: + vis.show() + +def plot(state : AllState, vehicle_model=None, xrange=None, yrange=None, title=None, show=True): + plot_scene(state, vehicle_model=vehicle_model, xrange=xrange, yrange=yrange, title=title, show=show) + if state.route is not None: + plot_path("route",state.route,color=(1,0.5,0,1)) + if state.trajectory is not None: + plot_path("trajectory",state.trajectory,color=(1,0,0,1),width=2) diff --git a/launch/fixed_route.yaml b/launch/fixed_route.yaml index 6ccbb3050..1596aeeb0 100644 --- a/launch/fixed_route.yaml +++ b/launch/fixed_route.yaml @@ -44,4 +44,24 @@ replay: # Add items here to set certain topics / inputs to be replayed from log components : [] #usually can keep this constant -computation_graph: !include "../GEMstack/knowledge/defaults/computation_graph.yaml" \ No newline at end of file +computation_graph: !include "../GEMstack/knowledge/defaults/computation_graph.yaml" + +#on load, variants will overload the settings structure +variants: + #sim variant doesn't execute on the real vehicle or log ros topics + sim: + run: + mode: simulation + vehicle_interface: + type: gem_simulator.GEMDoubleIntegratorSimulationInterface + args: + scene: !relative_path '../scenes/xyhead_demo.yaml' + + drive: + perception: + state_estimation : FakeStateEstimator + visualization: !include "klampt_visualization.yaml" + + log: + ros_topics : [] + \ No newline at end of file diff --git a/launch/fixed_route_sim.yaml b/launch/fixed_route_sim.yaml deleted file mode 100644 index c34fd6a83..000000000 --- a/launch/fixed_route_sim.yaml +++ /dev/null @@ -1,69 +0,0 @@ -description: "Drive the GEM vehicle along a fixed route (currently xyhead_highbay_backlot_p.csv) in simulation." -mode: simulation -vehicle_interface: - type: gem_simulator.GEMDoubleIntegratorSimulationInterface - args: - scene: !relative_path '../scenes/xyhead_demo.yaml' -mission_execution: StandardExecutor - -# "recovery" pipeline: Recovery behavior after a component failure -recovery: - planning: - trajectory_tracking : - type: recovery.StopTrajectoryTracker - print: False - -# "drive" pipeline: Driving behavior for the GEM vehicle following a fixed route -drive: - perception: - state_estimation : FakeStateEstimator - perception_normalization : StandardPerceptionNormalizer - planning: - route_planning: - type: StaticRoutePlanner - args: [!relative_path '../GEMstack/knowledge/routes/xyhead_highbay_backlot_p.csv'] - motion_planning: RouteToTrajectoryPlanner - trajectory_tracking: - type: pure_pursuit.PurePursuitTrajectoryTracker - print: False - -#visualization methods -visualization: - type: mpl_visualization.MPLVisualization - args: - rate: 8 - #Don't include save_as if you don't want to save the video - #save_as: - save_as: "fixed_route_sim.mp4" - multiprocess: True - -log: - # Specify the top-level folder to save the log files. Default is 'logs' - #folder : 'logs' - # If prefix is specified, then the log folder will be named with the prefix followed by the date and time. Default no prefix - #prefix : 'fixed_route_' - # If suffix is specified, then logs will output to folder/prefix+suffix. Default uses date and time as the suffix - #suffix : 'test3' - # Specify which ros topics to record to vehicle.bag. Default records nothing - ros_topics : [] - # Specify options to pass to rosbag record. Default is no options. - #rosbag_options : '--split --size=1024' - # If True, then record all readings / commands of the vehicle interface. Default False - vehicle_interface : True - # Specify which component's output to record to behavior.json. Default records nothing - components : ['state_estimation','trajectory_tracking'] - # Specify which components of state to record to state.json. Default records nothing - #state: ['all'] - # Specify the rate in Hz at which to record state to state.json. Default records at the pipeline's rate - #state_rate: 10 - -replay: # Add items here to set certain topics / inputs to be replayed from logs - # Specify which log folder to replay from - log: - # For replaying sensor data, try !include "../knowledge/defaults/standard_sensor_ros_topics.yaml" - ros_topics : [] - components : [] - -#usually can keep this constant -computation_graph: !include "../GEMstack/knowledge/defaults/computation_graph.yaml" - diff --git a/launch/klampt_visualization.yaml b/launch/klampt_visualization.yaml new file mode 100644 index 000000000..2265debf3 --- /dev/null +++ b/launch/klampt_visualization.yaml @@ -0,0 +1,7 @@ +type: klampt_visualization.KlamptVisualization +args: + rate: 20 + #Don't include save_as if you don't want to save the video + save_as: + #save_as: "fixed_route_sim.mp4" + diff --git a/launch/mpl_visualization.yaml b/launch/mpl_visualization.yaml new file mode 100644 index 000000000..b9642e4de --- /dev/null +++ b/launch/mpl_visualization.yaml @@ -0,0 +1,7 @@ +type: mpl_visualization.MPLVisualization +args: + rate: 8 + #Don't include save_as if you don't want to save the video + save_as: + #save_as: "fixed_route_sim.mp4" +multiprocess: True diff --git a/main.py b/main.py index 4f0d9a6f3..64d6afadc 100644 --- a/main.py +++ b/main.py @@ -21,7 +21,7 @@ else: #set the run settings from command line run_config = config.load_config_recursive(launch_file) - print(run_config) + #print(run_config) settings.set('run',run_config) if settings.get('run.name',None) is None: settings.set('run.name',launch_file) From b50a61894e9843d58016b2d8de8b428d571671c1 Mon Sep 17 00:00:00 2001 From: krishauser Date: Tue, 6 Feb 2024 21:20:38 -0500 Subject: [PATCH 085/232] Removed print --- GEMstack/state/trajectory.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/GEMstack/state/trajectory.py b/GEMstack/state/trajectory.py index 50b31a751..427f99dcb 100644 --- a/GEMstack/state/trajectory.py +++ b/GEMstack/state/trajectory.py @@ -254,7 +254,7 @@ def closest_point_local(self, x : List[float], time_range=Tuple[float,float], ed Returns (distance, closest_time) """ param_range = [self.time_to_parameter(time_range[0]),self.time_to_parameter(time_range[1])] - print("Searching within range",param_range) + #print("Searching within time range",time_range,"= param range",param_range) distance, closest_index = Path.closest_point_local(self,x,param_range,edges) closest_time = self.parameter_to_time(closest_index) return distance, closest_time From 808391b0814c92b27e4ac9f9cad4709c9a7290dc Mon Sep 17 00:00:00 2001 From: krishauser Date: Tue, 6 Feb 2024 21:21:14 -0500 Subject: [PATCH 086/232] Added Klampt visualizer --- .../visualization/klampt_visualization.py | 110 ++++++++++++++++++ .../visualization/mpl_visualization.py | 48 +++++++- 2 files changed, 155 insertions(+), 3 deletions(-) create mode 100644 GEMstack/onboard/visualization/klampt_visualization.py diff --git a/GEMstack/onboard/visualization/klampt_visualization.py b/GEMstack/onboard/visualization/klampt_visualization.py new file mode 100644 index 000000000..1809f9d23 --- /dev/null +++ b/GEMstack/onboard/visualization/klampt_visualization.py @@ -0,0 +1,110 @@ +from ..component import Component +from klampt import vis +from klampt.math import se3 +from klampt import * +from ...utils import klampt_visualization +import time +import os +import math +import numpy as np + +class KlamptVisualization(Component): + """Runs a matplotlib visualization at 10Hz. + + If save_as is not None, saves the visualization to a file. + """ + def __init__(self, vehicle_interface, rate : float = 10.0, save_as : str = None): + self.vehicle_interface = vehicle_interface + self._rate = rate + self.save_as = save_as + self.num_updates = 0 + self.last_yaw = None + self.plot_values = {} + self.plot_events = {} + + self.world = WorldModel() + fn = os.path.abspath(os.path.join(__file__,"../../../knowledge/vehicle/model/gem_e2.urdf")) + if not self.world.loadFile(fn): + print("Warning, could not load vehicle model from",fn) + input("Press enter to continue.") + self.vehicle = None + else: + self.vehicle = self.world.robot(0) + fn = os.path.abspath(os.path.join(__file__,"../../../knowledge/vehicle/model/plane.off")) + if not self.world.loadTerrain(fn): + print("Warning, could not load plane model from",fn) + input("Press enter to continue.") + plane = self.world.terrain(0) + tm = plane.geometry().getTriangleMesh() + v = tm.getVertices() + v[:] *= 20.0 #+/- 100m + #plane.geometry().getTriangleMesh().setVertices(v) + v = plane.geometry().setTriangleMesh(tm) + plane.appearance().setColor(0.7,0.7,0.7) + plane.appearance().setTexgen(np.array([[0.5,0,0,0],[0,0.5,0,0]])) + plane.appearance().setTexcoords2D([[-50,-50],[50,-50],[50,50],[-50,50]]) + + def rate(self) -> float: + return self._rate + + def state_inputs(self): + return ['all'] + + def initialize(self): + vis.setWindowTitle("GEMstack visualization") + vp = vis.getViewport() + vp.camera.rot[1] = -0.15 + vp.camera.rot[2] = -math.pi/2 + vp.camera.dist = 20.0 + vp.w = 1024 + vp.h = 768 + vp.clippingplanes = (0.1,1000) + vis.setViewport(vp) + vis.add("vehicle_plane",self.world.terrain(0),hide_label=True) + vis.show() + + def debug(self, source, item, value): + if source not in self.plot_values: + #draw overlay plots + vis.addPlot(source+"_plot") + self.plot_values[source] = {} + vis.logPlot(source+"_plot",item, value) + + def debug_event(self, source, event): + if source not in self.plot_events: + #draw overlay plots + vis.addPlot(source+"_plot") + self.plot_events[source] = {} + vis.logPlotEvent(source+"_plot",event) + + def update(self, state): + if not vis.shown(): + #plot closed + return + vis.lock() + try: + self.num_updates += 1 + self.debug("vehicle","velocity",state.vehicle.v) + self.debug("vehicle","front wheel angle",state.vehicle.front_wheel_angle) + self.debug("vehicle","accelerator",state.vehicle.accelerator_pedal_position) + self.debug("vehicle","brake",state.vehicle.brake_pedal_position) + time_str = time.strftime("%Y-%m-%d %H:%M:%S", time.localtime(state.t)) + klampt_visualization.plot(state,title="Scene %d at %s"%(self.num_updates,time_str),vehicle_model=self.vehicle,show=False) + + #update pose of the vehicle + if self.last_yaw is not None: + vp = vis.getViewport() + lookahead = 5.0*state.vehicle.v + dx,dy = math.cos(state.vehicle.pose.yaw)*lookahead,math.sin(state.vehicle.pose.yaw)*lookahead + vp.camera.tgt = [state.vehicle.pose.x+dx,state.vehicle.pose.y+dy,1.5] + vp.camera.rot[2] += state.vehicle.pose.yaw - self.last_yaw + vis.setViewport(vp) + + self.last_yaw = state.vehicle.pose.yaw + vis.add("vehicle_plane",self.world.terrain(0),hide_label=True) + finally: + vis.unlock() + + def cleanup(self): + vis.show(False) + vis.kill() diff --git a/GEMstack/onboard/visualization/mpl_visualization.py b/GEMstack/onboard/visualization/mpl_visualization.py index ea311c88c..ef9a24851 100644 --- a/GEMstack/onboard/visualization/mpl_visualization.py +++ b/GEMstack/onboard/visualization/mpl_visualization.py @@ -4,6 +4,7 @@ import matplotlib.pyplot as plt import matplotlib.animation as animation import time +from collections import deque class MPLVisualization(Component): """Runs a matplotlib visualization at 10Hz. @@ -15,8 +16,13 @@ def __init__(self, rate : float = 10.0, save_as : str = None): self.save_as = save_as self.anim = None self.writer = None - self.fig = None self.num_updates = 0 + self.fig = None + self.axs = None + self.tstart = 0 + self.plot_t_range = 10 + self.plot_values = {} + self.plot_events = {} def rate(self) -> float: return self._rate @@ -35,25 +41,61 @@ def initialize(self): self.writer.setup(plt.gcf(), self.save_as, dpi=100) plt.ion() # to run GUI event loop - self.fig = plt.gcf() + self.fig,self.axs = plt.subplots(1,2,figsize=(12,6)) self.fig.canvas.mpl_connect('close_event', self.on_close) plt.show(block=False) + self.tstart = time.time() def on_close(self,event): print("PLOT CLOSED") plt.ioff() + def debug(self, source, item, value): + t = time.time() - self.tstart + item = source+'.'+item + if item not in self.plot_values: + self.plot_values[item] = deque() + plot = self.plot_values[item] + self.plot_values[item].append((t,value)) + while t - plot[0][0] > self.plot_t_range: + plot.popleft() + + def debug_event(self, source, event): + t = time.time() - self.tstart + event = source+'.'+event + if event not in self.plot_events: + self.plot_events[event] = deque() + plot = self.plot_events[event] + plot.append(t) + while t - plot[0] > self.plot_t_range: + plot.popleft() + def update(self, state): if not plt.fignum_exists(self.fig.number): #plot closed return self.num_updates += 1 + self.debug("vehicle","velocity",state.vehicle.v) + self.debug("vehicle","front wheel angle",state.vehicle.front_wheel_angle) time_str = time.strftime("%Y-%m-%d %H:%M:%S", time.localtime(state.t)) #frame=ObjectFrameEnum.CURRENT #state = state.to_frame(frame) xrange = [state.vehicle.pose.x - 10, state.vehicle.pose.x + 10] yrange = [state.vehicle.pose.y - 10, state.vehicle.pose.y + 10] - mpl_visualization.plot(state,title="Scene %d at %s"%(self.num_updates,time_str),xrange=xrange,yrange=yrange,show=False) + #plot main visualization + mpl_visualization.plot(state,title="Scene %d at %s"%(self.num_updates,time_str),xrange=xrange,yrange=yrange,show=False,ax=self.axs[0]) + #plot figure on axs[1] + self.axs[1].clear() + for k,v in self.plot_values.items(): + t = [x[0] for x in v] + y = [x[1] for x in v] + self.axs[1].plot(t,y,label=k) + for i,(k,v) in enumerate(self.plot_events.items()): + for t in v: + self.axs[1].axvline(x=t,linestyle='--',color='C'+str(i),label=k) + self.axs[1].set_xlabel('Time (s)') + self.axs[1].legend() + self.fig.canvas.draw_idle() self.fig.canvas.flush_events() From f090548012e9ec377b04e3fbc7c352251e822bf0 Mon Sep 17 00:00:00 2001 From: krishauser Date: Tue, 6 Feb 2024 21:21:22 -0500 Subject: [PATCH 087/232] Better error messages --- GEMstack/onboard/execution/multiprocess_execution.py | 11 +++++++++-- 1 file changed, 9 insertions(+), 2 deletions(-) diff --git a/GEMstack/onboard/execution/multiprocess_execution.py b/GEMstack/onboard/execution/multiprocess_execution.py index 69064be57..6d92d748a 100644 --- a/GEMstack/onboard/execution/multiprocess_execution.py +++ b/GEMstack/onboard/execution/multiprocess_execution.py @@ -39,7 +39,14 @@ def start(self): old_manager = self.logging_manager self.logging_manager = None #can't be pickled? self._process = Process(target=self._run, args=(self.c, self._in_queue, self._out_queue, config)) - self._process.start() + try: + self._process.start() + except Exception as e: + print("Unable to start process",self.c.__class__.__name__) + print("Exception:",e) + + self._process = None + raise RuntimeError("Error starting "+self.c.__class__.__name__+" process, usually a pickling error") self.logging_manager = old_manager res = self._out_queue.get() if isinstance(res,tuple) and isinstance(res[0],Exception): @@ -51,7 +58,7 @@ def start(self): self._process.join() self._process.close() self._process = None - raise RuntimeError("Error initializng "+self.c.__class__.__name__) + raise RuntimeError("Error initializing "+self.c.__class__.__name__) if res !='initialized': raise RuntimeError("Uh... didn't hear back from subprocess? "+self.c.__class__.__name__) From 754d3b1b7f93e3979059d04c0596da99882bbc0b Mon Sep 17 00:00:00 2001 From: krishauser Date: Tue, 6 Feb 2024 21:21:41 -0500 Subject: [PATCH 088/232] More flexible in accepting timed vs untimed trajectories --- GEMstack/onboard/planning/pure_pursuit.py | 47 +++++++++++++++-------- 1 file changed, 31 insertions(+), 16 deletions(-) diff --git a/GEMstack/onboard/planning/pure_pursuit.py b/GEMstack/onboard/planning/pure_pursuit.py index dde99b592..00806a775 100644 --- a/GEMstack/onboard/planning/pure_pursuit.py +++ b/GEMstack/onboard/planning/pure_pursuit.py @@ -15,35 +15,38 @@ def __init__(self, lookahead = None, lookahead_scale = None, wheelbase = None, c self.look_ahead = lookahead if lookahead is not None else settings.get('control.pure_pursuit.lookahead',4.0) self.look_ahead_scale = lookahead_scale if lookahead_scale is not None else settings.get('control.pure_pursuit.lookahead_scale',3.0) self.crosstrack_gain = crosstrack_gain if crosstrack_gain is not None else settings.get('control.pure_pursuit.crosstrack_gain',0.41) + self.front_wheel_angle_scale = 3.0 self.wheelbase = wheelbase if wheelbase is not None else settings.get('vehicle.geometry.wheelbase') self.wheel_angle_range = [settings.get('vehicle.geometry.min_wheel_angle'),settings.get('vehicle.geometry.max_wheel_angle')] self.steering_angle_range = [settings.get('vehicle.geometry.min_steering_angle'),settings.get('vehicle.geometry.max_steering_angle')] self.desired_speed = settings.get('control.pure_pursuit.desired_speed',2.5) #approximately 5 mph - self.path_is_timed = False - self.desired_speed_from_path = True #turn this to True to use the input trajectory to determine the desired speed + self.desired_speed_from_path = False #turn this to True to use the input trajectory to determine the desired speed self.max_accel = settings.get('vehicle.limits.max_acceleration') # m/s^2 self.max_decel = settings.get('vehicle.limits.max_deceleration') # m/s^2 self.pid_speed = PID(settings.get('control.longitudinal_control.pid_p',0.5), settings.get('control.longitudinal_control.pid_d',0.0), settings.get('control.longitudinal_control.pid_i',0.1), windup_limit=20) - self.path = None + self.path = None # type: Path + #if trajectory = None, then only an untimed path was provided and we can't use the path velocity as the reference + self.trajectory = None # type: Trajectory + self.current_path_parameter = 0.0 self.t_last = None def set_path(self, path : Path): - if path == self.path: + if path == self.path or path == self.trajectory: return - self.path = path - if len(self.path.points[0]) > 2: - self.path = self.path.get_dims([0,1]) - if not isinstance(self.path,Trajectory): - self.path = self.path.arc_length_parameterize() - self.path_is_timed = False + if len(path.points[0]) > 2: + path = path.get_dims([0,1]) + if not isinstance(path,Trajectory): + self.path = path.arc_length_parameterize() + self.trajectory = None self.desired_speed_from_path = False if self.desired_speed_from_path: raise ValueError("Can't provide an untimed path to PurePursuit and expect it to use the path velocity") else: - self.path_is_timed = True + self.path = path.arc_length_parameterize() + self.trajectory = path self.current_path_parameter = 0.0 def compute(self, state : VehicleState): @@ -63,20 +66,32 @@ def compute(self, state : VehicleState): #just stop accel = self.pid_speed.advance(0.0, t) # TODO + raise RuntimeError("Behavior without path not implemented") if self.path.frame != state.pose.frame: print("Transforming path from",self.path.frame.name,"to",state.pose.frame.name) self.path = self.path.to_frame(state.pose.frame) + if self.trajectory is not None: + if self.trajectory.frame != state.pose.frame: + print("Transforming trajectory from",self.trajectory.frame.name,"to",state.pose.frame.name) + self.trajectory = self.trajectory.to_frame(state.pose.frame) closest_dist,closest_parameter = self.path.closest_point_local((curr_x,curr_y),[self.current_path_parameter-5.0,self.current_path_parameter+5.0]) - #TODO: calculate parameter that is look_ahead distance away from the closest point + #TODO: calculate parameter that is look_ahead distance away from the closest point? #(rather than just advancing the parameter) des_parameter = closest_parameter + self.look_ahead + self.look_ahead_scale * speed self.current_path_parameter = closest_parameter print("Closest parameter: " + str(closest_parameter),"distance to path",closest_dist) print("Closest point",self.path.eval(closest_parameter),"vs",(curr_x,curr_y)) - desired_x,desired_y = self.path.eval(des_parameter) + if des_parameter >= self.path.domain()[1]: + #we're at the end of the path, calculate desired point by extrapolating from the end of the path + end_pt = self.path.points[-1] + end_dir = self.path.eval_tangent(self.path.domain()[1]) + desired_x,desired_y = transforms.vector_madd(end_pt,end_dir,(des_parameter-self.path.domain()[1])) + else: + desired_x,desired_y = self.path.eval(des_parameter) desired_yaw = np.arctan2(desired_y-curr_y,desired_x-curr_x) + print("Desired point",(desired_x,desired_y)," with lookahead distance",self.look_ahead + self.look_ahead_scale * speed) print("Current yaw",curr_yaw,"desired yaw",desired_yaw) # distance between the desired point and the vehicle @@ -90,7 +105,7 @@ def compute(self, state : VehicleState): # ----------------- tuning this part as needed ----------------- k = self.crosstrack_gain angle_i = np.arctan((k * 2 * self.wheelbase * np.sin(alpha)) / L) - angle = angle_i*2.0 + angle = angle_i*self.front_wheel_angle_scale # ----------------- tuning this part as needed ----------------- f_delta = np.clip(angle, self.wheel_angle_range[0], self.wheel_angle_range[1]) @@ -107,11 +122,11 @@ def compute(self, state : VehicleState): feedforward_accel = 0.0 if self.desired_speed_from_path: #determine desired speed from trajectory - deriv = self.path.eval_derivative(self.current_path_parameter) + deriv = self.trajectory.eval_derivative(self.current_path_parameter) desired_speed = np.linalg.norm(deriv) feedforward_accel = (desired_speed - speed)/dt feedforward_accel= np.clip(feedforward_accel, -self.max_decel, self.max_accel) - print("Desired speed",desired_speed,"m/s") + print("Desired speed",desired_speed,"m/s","vs current speed",speed,"m/s") print("Feedforward accel: " + str(feedforward_accel) + " m/s^2") else: #decay speed when crosstrack error is high From 5bfdd764bc257f980ffcd24719bfa72f479a381e Mon Sep 17 00:00:00 2001 From: krishauser Date: Tue, 6 Feb 2024 21:22:00 -0500 Subject: [PATCH 089/232] Utility needed for --variants flag --- GEMstack/utils/config.py | 19 +++++++++++++++++++ 1 file changed, 19 insertions(+) diff --git a/GEMstack/utils/config.py b/GEMstack/utils/config.py index b283b32bf..025e0f466 100644 --- a/GEMstack/utils/config.py +++ b/GEMstack/utils/config.py @@ -2,6 +2,7 @@ import yaml import os from typing import Any, IO +import collections def save_config(fn : str, config : dict) -> None: """Saves a configuration file.""" @@ -85,3 +86,21 @@ def _load_recursive(obj, folder : str): elif obj.startswith('!!include'): return obj[1:] return obj + + + +def update_recursive(d : dict, u : dict) -> dict: + """Updates a dictionary d with another dictionary u recursively. + + The update happens in-place and d is returned. + """ + if not isinstance(d, collections.abc.Mapping): + raise ValueError("Trying to update a non-dict with a dict") + for k, v in u.items(): + if isinstance(v, collections.abc.Mapping): + if not isinstance(d.get(k, {}), collections.abc.Mapping): + d[k] = {} + d[k] = update_recursive(d.get(k, {}), v) + else: + d[k] = v + return d \ No newline at end of file From 1356b5466cd270095accef1e89ac07058195e8cb Mon Sep 17 00:00:00 2001 From: krishauser Date: Tue, 6 Feb 2024 21:22:23 -0500 Subject: [PATCH 090/232] Fixed --KEY=VALUE where VALUE is simple --- GEMstack/utils/settings.py | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/GEMstack/utils/settings.py b/GEMstack/utils/settings.py index 3845de515..b2470ce25 100644 --- a/GEMstack/utils/settings.py +++ b/GEMstack/utils/settings.py @@ -23,7 +23,10 @@ def load_settings(): k,v = arg.split('=',1) k = k[2:] v = v.strip('"') - v = json.loads(v) + try: + v = json.loads(v) + except json.decoder.JSONDecodeError: + pass if v.startswith('{'): set(k,v,leaf_only=False) else: From 0c0c588f8698e9a7779658eec37bfecb56cff2fe Mon Sep 17 00:00:00 2001 From: krishauser Date: Tue, 6 Feb 2024 21:22:45 -0500 Subject: [PATCH 091/232] Fixed simulator, added brake pedal / accel pedal state --- GEMstack/onboard/interface/gem.py | 12 ++++++------ GEMstack/onboard/interface/gem_simulator.py | 4 ++-- 2 files changed, 8 insertions(+), 8 deletions(-) diff --git a/GEMstack/onboard/interface/gem.py b/GEMstack/onboard/interface/gem.py index 65cf77902..c5482de19 100644 --- a/GEMstack/onboard/interface/gem.py +++ b/GEMstack/onboard/interface/gem.py @@ -27,16 +27,15 @@ def from_state(self, state: VehicleState) -> None: """Sets the readings that would be approximately sensed at the given VehicleState. - Approximates the pedal positions using the current dynamics model. - Does not change the battery_level, fuel_level, or driving_range values. """ self.speed = state.v self.steering_wheel_angle = state.steering_wheel_angle pitch = state.pose.pitch if state.pose.pitch is not None else 0.0 - acc_pos,brake_pos,gear = acceleration_to_pedal_positions(state.acceleration, state.v, pitch, state.gear) - self.accelerator_pedal_position = acc_pos - self.brake_pedal_position = brake_pos + + #acc_pos,brake_pos,gear = acceleration_to_pedal_positions(state.acceleration, state.v, pitch, state.gear) + self.accelerator_pedal_position = state.accelerator_pedal_position + self.brake_pedal_position = state.brake_pedal_position self.gear = state.gear self.left_turn_signal = state.left_turn_indicator self.right_turn_signal = state.right_turn_indicator @@ -58,7 +57,8 @@ def to_state(self, pose : ObjectPose = None) -> VehicleState: front_wheel_angle=steer2front(self.steering_wheel_angle) turn_rate=heading_rate(front_wheel_angle,self.speed,wheel_base) acc = pedal_positions_to_acceleration(self.accelerator_pedal_position, self.brake_pedal_position, self.speed, pitch, self.gear) - return VehicleState(pose,v=self.speed,acceleration=acc,gear=self.gear,steering_wheel_angle=self.steering_wheel_angle, + return VehicleState(pose,v=self.speed,accelerator_pedal_position=self.accelerator_pedal_position,brake_pedal_position=self.brake_pedal_position, + acceleration=acc,gear=self.gear,steering_wheel_angle=self.steering_wheel_angle, front_wheel_angle=front_wheel_angle,heading_rate=turn_rate, left_turn_indicator=self.left_turn_signal,right_turn_indicator=self.right_turn_signal, horn_on=self.horn_on,wiper_level=self.wiper_level,headlights_on=self.headlights_on) diff --git a/GEMstack/onboard/interface/gem_simulator.py b/GEMstack/onboard/interface/gem_simulator.py index 3c19596a7..376de4c88 100644 --- a/GEMstack/onboard/interface/gem_simulator.py +++ b/GEMstack/onboard/interface/gem_simulator.py @@ -99,9 +99,9 @@ def simulate(self, T : float, command : Optional[GEMVehicleCommand]): reading.steering_wheel_angle = front2steer(phi) if acceleration > 0: reading.brake_pedal_position = 0.0 - reading.accelerator_pedal_position = acceleration + reading.accelerator_pedal_position = accelerator_pedal_position else: - reading.brake_pedal_position = -acceleration + reading.brake_pedal_position = brake_pedal_position reading.accelerator_pedal_position = 0 reading.speed = v if v > 0: From 9247af9360d6bb1f7f52552da4cfb42e128f4ba2 Mon Sep 17 00:00:00 2001 From: krishauser Date: Tue, 6 Feb 2024 21:22:58 -0500 Subject: [PATCH 092/232] kris_v1 model now accepts active range --- GEMstack/knowledge/vehicle/dynamics.py | 14 ++++++++++---- 1 file changed, 10 insertions(+), 4 deletions(-) diff --git a/GEMstack/knowledge/vehicle/dynamics.py b/GEMstack/knowledge/vehicle/dynamics.py index 8c19221c8..248bf8197 100644 --- a/GEMstack/knowledge/vehicle/dynamics.py +++ b/GEMstack/knowledge/vehicle/dynamics.py @@ -53,18 +53,24 @@ def acceleration_to_pedal_positions(acceleration : float, velocity : float, pitc internal_dry_deceleration = settings.get('vehicle.dynamics.internal_dry_deceleration') internal_viscous_deceleration = settings.get('vehicle.dynamics.internal_viscous_deceleration') aerodynamic_drag_coefficient = settings.get('vehicle.dynamics.aerodynamic_drag_coefficient') + accel_active_range = settings.get('vehicle.dynamics.accelerator_active_range') # pedal position fraction + brake_active_range = settings.get('vehicle.dynamics.brake_active_range') # pedal position fraction + drag = -(aerodynamic_drag_coefficient * velocity**2) * vsign - internal_dry_deceleration * vsign - internal_viscous_deceleration * velocity sin_pitch = math.sin(pitch) acceleration -= drag + gravity * sin_pitch #this is the net acceleration that should be achieved by accelerator / brake pedal #TODO: power curves to select optimal gear + if abs(acceleration) < 0.5: + #deadband? + return (0,0,gear) if velocity * acceleration < 0: accel_pos = 0 brake_pos = -acceleration / brake_max if brake_pos > 1.0: brake_pos = 1.0 - return (accel_pos,brake_pos,gear) + return (accel_pos,brake_active_range[0] + brake_pos*(brake_active_range[1]-brake_active_range[0]),gear) else: #may want to switch gear? if velocity == 0: @@ -79,15 +85,15 @@ def acceleration_to_pedal_positions(acceleration : float, velocity : float, pitc brake_pos = 0 if accel_pos > 1.0: accel_pos = 1.0 - return (accel_pos,brake_pos,-1) + return (accel_active_range[0] + accel_pos*(accel_active_range[1]-accel_active_range[0]),brake_pos,-1) elif gear > 0: accel_pos = acceleration / accel_max[gear] brake_pos = 0 if accel_pos > 1.0: accel_pos = 1.0 - return (accel_pos,brake_pos,gear) + return (accel_active_range[0] + accel_pos*(accel_active_range[1]-accel_active_range[0]),brake_pos,gear) else: - #stay in neutral gear + #stay in neutral gear, brake return (0,1,0) From f13d6f7aeecc447206a4090576ee5272f3fa49bb Mon Sep 17 00:00:00 2001 From: krishauser Date: Tue, 6 Feb 2024 21:23:37 -0500 Subject: [PATCH 093/232] State now has accelerator and brake pedal positions --- GEMstack/state/vehicle.py | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/GEMstack/state/vehicle.py b/GEMstack/state/vehicle.py index e4c37e58a..89852e4af 100644 --- a/GEMstack/state/vehicle.py +++ b/GEMstack/state/vehicle.py @@ -23,7 +23,9 @@ class VehicleState: """Represents the state of the ego-vehicle.""" pose : ObjectPose #pose of the vehicle with origin at rear axle center. Includes time v : float #forward velocity in m/s - acceleration : float #current acceleration / deceleration in m/s^2 + accelerator_pedal_position : float #current accelerator pedal position, in [0,1] + brake_pedal_position : float #current brake pedal position, in [0,1] + acceleration : float #current estimated acceleration / deceleration in m/s^2 steering_wheel_angle : float #angle of the steering wheel, in radians front_wheel_angle : float #angle of the front wheels, in radians. Related to steering_wheel_angle by a fixed transform heading_rate : float #the rate at which the vehicle is turning, in radians/s. Related to v and front_wheel_angle by a fixed transform @@ -36,12 +38,12 @@ class VehicleState: @staticmethod def zero(): - return VehicleState(ObjectPose(ObjectFrameEnum.START,0,0,0),0,0,0,0,0,VehicleGearEnum.PARK,False,False,False,0) + return VehicleState(ObjectPose(ObjectFrameEnum.START,0,0,0),0,0,0,0,0,0,0,VehicleGearEnum.PARK,False,False,False,0) def to_object(self) -> PhysicalObject: """Extracts out the geometry of the object using the vehicle's - current geometry in settings. The object's origin will be in the - middle of the vehicle. + current geometry in settings. Note that the object's origin will be in the + middle of the vehicle, NOT the true vehicle reference point (rear axle center). """ from ..utils import settings xbounds,ybounds,zbounds = settings.get('vehicle.geometry.bounds') From ac10a83dc1cf6feda4c08bf5ddaae5d469a58cfa Mon Sep 17 00:00:00 2001 From: krishauser Date: Wed, 7 Feb 2024 00:05:02 -0500 Subject: [PATCH 094/232] Renamed to Omniscient state estimator. added agent sim --- GEMstack/onboard/interface/gem_simulator.py | 105 +++++++++++++++++- .../onboard/perception/agent_detection.py | 28 +++++ .../perception/perception_normalization.py | 8 +- .../onboard/perception/state_estimation.py | 2 +- launch/fixed_route.yaml | 4 +- scenes/xyhead_demo.yaml | 2 +- 6 files changed, 139 insertions(+), 10 deletions(-) create mode 100644 GEMstack/onboard/perception/agent_detection.py diff --git a/GEMstack/onboard/interface/gem_simulator.py b/GEMstack/onboard/interface/gem_simulator.py index 376de4c88..5f49b0488 100644 --- a/GEMstack/onboard/interface/gem_simulator.py +++ b/GEMstack/onboard/interface/gem_simulator.py @@ -13,6 +13,92 @@ import numpy as np import copy +AGENT_DIMENSIONS = { + 'pedestrian' : (0.5,0.5,1.6), + 'bicyclist' : (1.8,0.5,1.6), + 'car' : (4.0,2.5,1.4), + 'medium_truck': (6.0,2.5,3.0), + 'large_truck': (10.0,2.5,3.5) +} + +AGENT_TYPE_TO_ENUM = { + 'pedestrian' : AgentEnum.PEDESTRIAN, + 'bicyclist' : AgentEnum.BICYCLIST, + 'car' : AgentEnum.CAR, + 'medium_truck': AgentEnum.MEDIUM_TRUCK, + 'large_truck': AgentEnum.LARGE_TRUCK +} + +AGENT_NOMINAL_VELOCITY = { + 'pedestrian' : 1.5, + 'bicyclist' : 5.0, + 'car' : 20.0, + 'medium_truck': 15.0, + 'large_truck': 10.0 +} + +AGENT_NOMINAL_ACCELERATION = { + 'pedestrian' : 2.0, + 'bicyclist' : 2.0, + 'car' : 5.0, + 'medium_truck': 3.0, + 'large_truck': 2.0 +} + +class AgentSimulation: + def __init__(self, config): + self.type = config['type'] + self.position = config['position'][:] + self.velocity = config.get('velocity',[0,0]) + self.nominal_velocity = config.get('nominal_velocity',AGENT_NOMINAL_VELOCITY[self.type]) + self.target = config.get('target',None) + self.target_radius = config.get('target_radius',0.1) + self.target_path = config.get('target_path',None) + self.behavior = config['behavior'] + self.start = self.position[:] + self.yaw = config.get('yaw',0) + + def to_agent_state(self) -> AgentState: + pose = ObjectPose(frame=ObjectFrameEnum.ABSOLUTE_CARTESIAN,t=time.time(),x=self.position[0],y=self.position[1],yaw=self.yaw) + activity = AgentActivityEnum.MOVING if self.velocity[0] != 0 or self.velocity[1] != 0 else AgentActivityEnum.STOPPED + return AgentState(pose=pose,dimensions=AGENT_DIMENSIONS[self.type],outline=None, + type=AGENT_TYPE_TO_ENUM[self.type], + activity=activity,velocity=(self.velocity[0],self.velocity[1],0),yaw_rate=0.0) + + def advance(self,dt): + if self.behavior == 'stationary': + self.velocity = [0,0] + return + elif self.behavior == 'target': + if self.target is not None: + self.seek_target(self.target,dt) + elif self.target_path is not None: + raise NotImplementedError("Path following not implemented yet") + elif self.behavior == 'looping': + if self.target is not None: + self.seek_target(self.target,dt) + if np.linalg.norm((self.position[0]-self.target[0],self.position[1]-self.target[1])) < self.target_radius: + self.target,self.start = self.start,self.target + elif self.target_path is not None: + raise NotImplementedError("Path following not implemented yet") + + def seek_target(self,target,dt): + dx = target[0] - self.position[0] + dy = target[1] - self.position[1] + d = np.linalg.norm((dx,dy)) + v = np.linalg.norm(self.velocity) + if d < 0.02: + self.velocity = [0,0] + return True + direction = (dx/d,dy/d) + dleft = d - self.target_radius + if v < self.nominal_velocity: + v += AGENT_NOMINAL_ACCELERATION[self.type]*dt + if 0.5*v**2/AGENT_NOMINAL_ACCELERATION[self.type] > dleft: + v -= AGENT_NOMINAL_ACCELERATION[self.type]*dt + self.velocity = [v*direction[0],v*direction[1]] + + class GEMDoubleIntegratorSimulation: """Standard simulation of a second-order Dubins car with a double integrator controller. The simulation is deterministic and accepts @@ -40,6 +126,7 @@ def __init__(self, scene : str = None): if isinstance(scene,str): print("Loading simulator from scene",scene) scene = config.load_config_recursive(scene) + self.agents = {} if scene is None: self.simulation_time = time.time() self.start_state = (0.0,0.0,0.0) @@ -48,6 +135,8 @@ def __init__(self, scene : str = None): start_state = scene.get('vehicle_state',[0.0,0.0,0.0,0.0,0.0]) while len(start_state) < 5: start_state.append(0.0) + for k,a in scene.get('agents',{}).items(): + self.agents[k] = AgentSimulation(a) self.cur_vehicle_state = np.array(start_state,dtype=float) self.last_reading = GEMVehicleReading() @@ -72,6 +161,8 @@ def time(self) -> float: def simulate(self, T : float, command : Optional[GEMVehicleCommand]): if command is not None: self.last_command = command + for k,a in self.agents.items(): + a.advance(T) x,y,theta,v,phi = self.cur_vehicle_state #print("x %.2f y %.2f theta %.2f v %.2f" % (x,y,theta,v)) #simulate actuators @@ -117,7 +208,7 @@ def simulate(self, T : float, command : Optional[GEMVehicleCommand]): self.last_reading = reading self.cur_vehicle_state = next_state - self.simulation_time += self.dt + self.simulation_time += T def pose(self) -> ObjectPose: x,y,theta,v,phi = self.cur_vehicle_state @@ -136,7 +227,7 @@ def set_state(self,state : VehicleState): self.cur_vehicle_state[3] = state.v self.cur_vehicle_state[4] = state.front_wheel_angle - def advance_state(self, state : AllState, command : GEMVehicleCommand, T : float) -> AllState: + def advance_vehicle_state(self, state : AllState, command : GEMVehicleCommand, T : float) -> AllState: """Advances the vehicle state by the given amount of time T under the given command. Agents are not touched. """ @@ -163,6 +254,7 @@ def __init__(self, scene : str = None): self.last_command = self.simulator.last_command self.gnss_callback = None self.imu_callback = None + self.agent_detector_callback = None self.thread_lock = Lock() self.thread_data = dict() self.thread = None @@ -189,7 +281,7 @@ def hardware_faults(self) -> list: def sensors(self): #TODO: simulate other sensors? - return ['gnss','imu'] + return ['gnss','imu','agent_detector'] def subscribe_sensor(self, name, callback, type = None): if name == 'gnss': @@ -200,6 +292,10 @@ def subscribe_sensor(self, name, callback, type = None): if type is not None and type is not VehicleState: raise ValueError("GEMDoubleIntegratorSimulationInterface only supports VehicleState for IMU") self.imu_callback = callback + elif name == 'agent_detector': + if type is not None and type is not AgentState: + raise ValueError("GEMDoubleIntegratorSimulationInterface only supports AgentState for agent_detector") + self.agent_detector_callback = callback else: print("Warning, GEM simulator doesn't provide sensor",name) @@ -224,3 +320,6 @@ def simulate(self,lock : Lock, data : dict): pose = ObjectPose(frame=ObjectFrameEnum.CURRENT,t=self.simulation_time,x=0,y=0,yaw=0) vehicle_state = self.last_reading.to_state(pose) self.imu_callback(vehicle_state) + if self.agent_detector_callback is not None: + for k,a in self.simulator.agents.items(): + self.agent_detector_callback(k,a.to_agent_state()) diff --git a/GEMstack/onboard/perception/agent_detection.py b/GEMstack/onboard/perception/agent_detection.py new file mode 100644 index 000000000..c2ca700c2 --- /dev/null +++ b/GEMstack/onboard/perception/agent_detection.py @@ -0,0 +1,28 @@ +from ...state import AllState,VehicleState,ObjectPose,ObjectFrameEnum,AgentState,AgentEnum,AgentActivityEnum +from ..interface.gem import GEMInterface +from ..component import Component +from typing import Dict + +class OmniscientAgentDetector(Component): + """Obtains agent detections from a simulator""" + def __init__(self,vehicle_interface : GEMInterface): + self.vehicle_interface = vehicle_interface + self.agents = {} + + def rate(self): + return 4.0 + + def state_inputs(self): + return [] + + def state_outputs(self): + return ['agents'] + + def initialize(self): + self.vehicle_interface.subscribe_sensor('agent_detector',self.agent_callback, AgentState) + + def agent_callback(self, name : str, agent : AgentState): + self.agents[name] = agent + + def update(self) -> Dict[str,AgentState]: + return self.agents diff --git a/GEMstack/onboard/perception/perception_normalization.py b/GEMstack/onboard/perception/perception_normalization.py index b8f0031a7..f4ffcd157 100644 --- a/GEMstack/onboard/perception/perception_normalization.py +++ b/GEMstack/onboard/perception/perception_normalization.py @@ -21,19 +21,19 @@ def update(self,state : AllState): state.vehicle.pose = state.vehicle.pose.to_frame(ObjectFrameEnum.START, start_pose_abs=state.start_vehicle_pose) #convert roadgraph to current frame - state.roadgraph = state.roadgraph.to_frame(ObjectFrameEnum.CURRENT, current_pose=state.vehicle, start_pose_abs=state.start_vehicle_pose) + state.roadgraph = state.roadgraph.to_frame(ObjectFrameEnum.CURRENT, current_pose=state.vehicle.pose, start_pose_abs=state.start_vehicle_pose) for k,a in state.agents.items(): - a.pose = a.pose.to_frame(ObjectFrameEnum.CURRENT, current_pose=state.vehicle, start_pose_abs=state.start_vehicle_pose) + a.pose = a.pose.to_frame(ObjectFrameEnum.CURRENT, current_pose=state.vehicle.pose, start_pose_abs=state.start_vehicle_pose) for k,o in state.obstacles.items(): - o.pose = o.pose.to_frame(ObjectFrameEnum.CURRENT, current_pose=state.vehicle, start_pose_abs=state.start_vehicle_pose) + o.pose = o.pose.to_frame(ObjectFrameEnum.CURRENT, current_pose=state.vehicle.pose, start_pose_abs=state.start_vehicle_pose) #convert predictions to current frame. for k,a in state.agent_intents.items(): for pred in a.predictions: if pred.path is not None: for i,p in enumerate(pred.path): - pred.path[i] = p.to_frame(ObjectFrameEnum.CURRENT, current_pose=state.vehicle, start_pose_abs=state.start_vehicle_pose) + pred.path[i] = p.to_frame(ObjectFrameEnum.CURRENT, current_pose=state.vehicle.pose, start_pose_abs=state.start_vehicle_pose) #TODO: advance agent predictions and paths to current vehicle time \ No newline at end of file diff --git a/GEMstack/onboard/perception/state_estimation.py b/GEMstack/onboard/perception/state_estimation.py index e9e0eb2a9..db8727110 100644 --- a/GEMstack/onboard/perception/state_estimation.py +++ b/GEMstack/onboard/perception/state_estimation.py @@ -70,7 +70,7 @@ def update(self) -> VehicleState: -class FakeStateEstimator(Component): +class OmniscientStateEstimator(Component): def __init__(self, vehicle_interface : GEMInterface): self.vehicle_interface = vehicle_interface if 'gnss' not in vehicle_interface.sensors(): diff --git a/launch/fixed_route.yaml b/launch/fixed_route.yaml index 1596aeeb0..e89db77a3 100644 --- a/launch/fixed_route.yaml +++ b/launch/fixed_route.yaml @@ -59,8 +59,10 @@ variants: drive: perception: - state_estimation : FakeStateEstimator + state_estimation : OmniscientStateEstimator + agent_detection : OmniscientAgentDetector visualization: !include "klampt_visualization.yaml" + #visualization: !include "mpl_visualization.yaml" log: ros_topics : [] diff --git a/scenes/xyhead_demo.yaml b/scenes/xyhead_demo.yaml index a5cb0f58b..8b614fd93 100644 --- a/scenes/xyhead_demo.yaml +++ b/scenes/xyhead_demo.yaml @@ -3,7 +3,7 @@ agents: ped1: type: pedestrian position: [12.0, 0.0] - velocity: 0.5 + nominal_velocity: 0.5 target: [12.0,10.0] behavior: loop \ No newline at end of file From 56b6517098f38348a4071006d62d9066dacad959 Mon Sep 17 00:00:00 2001 From: krishauser Date: Wed, 7 Feb 2024 00:05:15 -0500 Subject: [PATCH 095/232] Noted about sim variants in readme. --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 714c09834..45f2bfee7 100644 --- a/README.md +++ b/README.md @@ -168,7 +168,7 @@ Legend: You will launch a simulation using: -- `python3 main.py launch/LAUNCH_FILE.yaml` where `LAUNCH_FILE.yaml` is your preferred simulation launch file. Inspect the simulator classes in `GEMstack/onboard/interface/gem_simulator.py` for more information about configuring the simulator. +- `python3 main.py --variant=sim launch/LAUNCH_FILE.yaml` where `LAUNCH_FILE.yaml` is your preferred launch file. Try `python3 main.py --variant=sim launch/fixed_route.yaml`. Inspect the simulator classes in `GEMstack/onboard/interface/gem_simulator.py` for more information about configuring the simulator. To launch onboard behavior you will open Terminator / tmux and split it into three terminal windows. In each of them run: From 89033912858f2510140563059315de97632219ac Mon Sep 17 00:00:00 2001 From: krishauser Date: Wed, 7 Feb 2024 00:05:40 -0500 Subject: [PATCH 096/232] Added filter for velocity in visualization --- GEMstack/onboard/visualization/klampt_visualization.py | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/GEMstack/onboard/visualization/klampt_visualization.py b/GEMstack/onboard/visualization/klampt_visualization.py index 1809f9d23..fa03b6f01 100644 --- a/GEMstack/onboard/visualization/klampt_visualization.py +++ b/GEMstack/onboard/visualization/klampt_visualization.py @@ -2,6 +2,7 @@ from klampt import vis from klampt.math import se3 from klampt import * +from ...mathutils.signal import OnlineLowPassFilter from ...utils import klampt_visualization import time import os @@ -21,6 +22,7 @@ def __init__(self, vehicle_interface, rate : float = 10.0, save_as : str = None) self.last_yaw = None self.plot_values = {} self.plot_events = {} + self.vfilter = OnlineLowPassFilter(1.2, 30, 4) self.world = WorldModel() fn = os.path.abspath(os.path.join(__file__,"../../../knowledge/vehicle/model/gem_e2.urdf")) @@ -56,8 +58,8 @@ def initialize(self): vp.camera.rot[1] = -0.15 vp.camera.rot[2] = -math.pi/2 vp.camera.dist = 20.0 - vp.w = 1024 - vp.h = 768 + vp.w = 1280 + vp.h = 720 vp.clippingplanes = (0.1,1000) vis.setViewport(vp) vis.add("vehicle_plane",self.world.terrain(0),hide_label=True) @@ -94,7 +96,8 @@ def update(self, state): #update pose of the vehicle if self.last_yaw is not None: vp = vis.getViewport() - lookahead = 5.0*state.vehicle.v + v = self.vfilter(state.vehicle.v) + lookahead = 5.0*v dx,dy = math.cos(state.vehicle.pose.yaw)*lookahead,math.sin(state.vehicle.pose.yaw)*lookahead vp.camera.tgt = [state.vehicle.pose.x+dx,state.vehicle.pose.y+dy,1.5] vp.camera.rot[2] += state.vehicle.pose.yaw - self.last_yaw From 3e9fee6a7f036a7f668931cb25ee75ffba2d7c10 Mon Sep 17 00:00:00 2001 From: krishauser Date: Wed, 7 Feb 2024 00:39:27 -0500 Subject: [PATCH 097/232] Fixed agent simulation, looks nicer now --- GEMstack/onboard/interface/gem_simulator.py | 6 +- .../visualization/klampt_visualization.py | 6 +- GEMstack/state/agent.py | 2 +- GEMstack/state/all.py | 9 +- GEMstack/utils/klampt_visualization.py | 109 ++++++++++-------- launch/fixed_route.yaml | 4 +- scenes/xyhead_demo.yaml | 4 +- 7 files changed, 79 insertions(+), 61 deletions(-) diff --git a/GEMstack/onboard/interface/gem_simulator.py b/GEMstack/onboard/interface/gem_simulator.py index 5f49b0488..9999b7f34 100644 --- a/GEMstack/onboard/interface/gem_simulator.py +++ b/GEMstack/onboard/interface/gem_simulator.py @@ -2,6 +2,7 @@ from .gem import * from ...mathutils.dubins import SecondOrderDubinsCar from ...mathutils.dynamics import simulate +from ...mathutils import transforms from ...state import VehicleState,ObjectPose,ObjectFrameEnum,Roadgraph,AgentState,AgentEnum,AgentActivityEnum,Obstacle,Sign,AllState from ...knowledge.vehicle.geometry import front2steer,steer2front,heading_rate from ...knowledge.vehicle.dynamics import pedal_positions_to_acceleration, acceleration_to_pedal_positions @@ -74,13 +75,15 @@ def advance(self,dt): self.seek_target(self.target,dt) elif self.target_path is not None: raise NotImplementedError("Path following not implemented yet") - elif self.behavior == 'looping': + elif self.behavior == 'loop': if self.target is not None: self.seek_target(self.target,dt) if np.linalg.norm((self.position[0]-self.target[0],self.position[1]-self.target[1])) < self.target_radius: self.target,self.start = self.start,self.target elif self.target_path is not None: raise NotImplementedError("Path following not implemented yet") + else: + raise ValueError("Unknown behavior "+self.behavior) def seek_target(self,target,dt): dx = target[0] - self.position[0] @@ -97,6 +100,7 @@ def seek_target(self,target,dt): if 0.5*v**2/AGENT_NOMINAL_ACCELERATION[self.type] > dleft: v -= AGENT_NOMINAL_ACCELERATION[self.type]*dt self.velocity = [v*direction[0],v*direction[1]] + self.position = transforms.vector_madd(self.position,self.velocity,dt) class GEMDoubleIntegratorSimulation: diff --git a/GEMstack/onboard/visualization/klampt_visualization.py b/GEMstack/onboard/visualization/klampt_visualization.py index fa03b6f01..2927eb7ec 100644 --- a/GEMstack/onboard/visualization/klampt_visualization.py +++ b/GEMstack/onboard/visualization/klampt_visualization.py @@ -2,6 +2,7 @@ from klampt import vis from klampt.math import se3 from klampt import * +from ...state import AllState,ObjectFrameEnum from ...mathutils.signal import OnlineLowPassFilter from ...utils import klampt_visualization import time @@ -57,7 +58,7 @@ def initialize(self): vp = vis.getViewport() vp.camera.rot[1] = -0.15 vp.camera.rot[2] = -math.pi/2 - vp.camera.dist = 20.0 + vp.camera.dist = 30.0 vp.w = 1280 vp.h = 720 vp.clippingplanes = (0.1,1000) @@ -91,7 +92,8 @@ def update(self, state): self.debug("vehicle","accelerator",state.vehicle.accelerator_pedal_position) self.debug("vehicle","brake",state.vehicle.brake_pedal_position) time_str = time.strftime("%Y-%m-%d %H:%M:%S", time.localtime(state.t)) - klampt_visualization.plot(state,title="Scene %d at %s"%(self.num_updates,time_str),vehicle_model=self.vehicle,show=False) + state_start = state.to_frame(ObjectFrameEnum.START) + klampt_visualization.plot(state_start,title="Scene %d at %s"%(self.num_updates,time_str),vehicle_model=self.vehicle,show=False) #update pose of the vehicle if self.last_yaw is not None: diff --git a/GEMstack/state/agent.py b/GEMstack/state/agent.py index 063f293c0..757805837 100644 --- a/GEMstack/state/agent.py +++ b/GEMstack/state/agent.py @@ -40,5 +40,5 @@ def velocity_parent(self) -> Tuple[float,float,float]: def to_frame(self, frame : ObjectFrameEnum, current_pose = None, start_pose_abs = None) -> AgentState: newpose = self.pose.to_frame(frame,current_pose,start_pose_abs) - newvelocity = convert_vector(self.velocity,frame,current_pose,start_pose_abs) + newvelocity = convert_vector(self.velocity,self.pose.frame,frame,current_pose,start_pose_abs) return replace(self,pose=newpose,velocity=newvelocity) \ No newline at end of file diff --git a/GEMstack/state/all.py b/GEMstack/state/all.py index e23f54e76..fc976fe24 100644 --- a/GEMstack/state/all.py +++ b/GEMstack/state/all.py @@ -54,8 +54,9 @@ def zero(): return AllState(**keys) def to_frame(self, frame : ObjectFrameEnum) -> AllState: - scene_to_frame = SceneState.to_frame(self,frame,current_pose=self.vehicle.pose,start_pose_abs=self.start_vehicle_pose) - new_intents = None if self.agent_intents is None else dict((k,v.to_frame(frame,current_pose=self.vehicle.pose,start_pose_abs=self.start_vehicle_pose)) for k,v in self.agent_intents.items()) - new_route = None if self.route is None else self.route.to_frame(frame,current_pose=self.vehicle.pose,start_pose_abs=self.start_vehicle_pose) - new_trajectory = None if self.trajectory is None else self.trajectory.to_frame(frame,current_pose=self.vehicle.pose,start_pose_abs=self.start_vehicle_pose) + spose = self.start_vehicle_pose + scene_to_frame = SceneState.to_frame(self,frame,current_pose=self.vehicle.pose,start_pose_abs=spose) + new_intents = None if self.agent_intents is None else dict((k,v.to_frame(frame,current_pose=self.vehicle.pose,start_pose_abs=spose)) for k,v in self.agent_intents.items()) + new_route = None if self.route is None else self.route.to_frame(frame,current_pose=self.vehicle.pose,start_pose_abs=spose) + new_trajectory = None if self.trajectory is None else self.trajectory.to_frame(frame,current_pose=self.vehicle.pose,start_pose_abs=spose) return replace(scene_to_frame, agent_intents = new_intents, route = new_route, trajectory = new_trajectory) \ No newline at end of file diff --git a/GEMstack/utils/klampt_visualization.py b/GEMstack/utils/klampt_visualization.py index b66b3720d..3d7069fc2 100644 --- a/GEMstack/utils/klampt_visualization.py +++ b/GEMstack/utils/klampt_visualization.py @@ -1,34 +1,46 @@ from klampt import vis from klampt.math import vectorops,so3,se3 from klampt.model.trajectory import Trajectory +from klampt import Geometry3D, GeometricPrimitive, TriangleMesh import numpy as np from . import settings -from ..state import ObjectFrameEnum,ObjectPose,PhysicalObject,VehicleState,VehicleGearEnum,Path,Obstacle,AgentState,Roadgraph,RoadgraphLane,RoadgraphLaneEnum,RoadgraphCurve,RoadgraphCurveEnum,RoadgraphRegion,RoadgraphRegionEnum,RoadgraphSurfaceEnum,Trajectory,Route,SceneState,AllState +from ..state import ObjectFrameEnum,ObjectPose,PhysicalObject,VehicleState,VehicleGearEnum,Path,Obstacle,AgentState,AgentEnum,Roadgraph,RoadgraphLane,RoadgraphLaneEnum,RoadgraphCurve,RoadgraphCurveEnum,RoadgraphRegion,RoadgraphRegionEnum,RoadgraphSurfaceEnum,Trajectory,Route,SceneState,AllState + +OBJECT_COLORS = { + AgentEnum.CAR : (1,1,0,1), + AgentEnum.PEDESTRIAN : (0,1,0,1), + AgentEnum.BICYCLIST : (0,0,1,1), + AgentEnum.MEDIUM_TRUCK : (1,0,1,1), + AgentEnum.LARGE_TRUCK : (0,1,1,1), + None: (0.7,0.7,0.7,1), +} + +AUX_BBOX_COLOR = (0,0,1,1) CURVE_TO_STYLE = { - RoadgraphCurveEnum.LANE_BOUNDARY : {'color':(1,1,1,1),'width':2}, - RoadgraphCurveEnum.CURB : {'color':(0.5,0.5,0.5,1),'width':2}, - RoadgraphCurveEnum.CLIFF : {'color':(1,0,0,1),'width':2}, - RoadgraphCurveEnum.CROSSING_BOUNDARY : {'color':(1,1,1,1),'width':1}, - RoadgraphCurveEnum.PARKING_SPOT_BOUNDARY : {'color':(1,1,1,1),'width':1}, - RoadgraphCurveEnum.STOP_LINE : {'color':(1,1,1,1),'width':2}, - RoadgraphCurveEnum.WALL : {'color':(0,0,1,1),'width':2}, - None : {'color':(1,1,1,1),'width':1}, + RoadgraphCurveEnum.LANE_BOUNDARY : {'color':(1,1,1,1),'width':2,'pointSize':0}, + RoadgraphCurveEnum.CURB : {'color':(0.5,0.5,0.5,1),'width':2,'pointSize':0}, + RoadgraphCurveEnum.CLIFF : {'color':(1,0,0,1),'width':2,'pointSize':0}, + RoadgraphCurveEnum.CROSSING_BOUNDARY : {'color':(1,1,1,1),'width':1,'pointSize':0}, + RoadgraphCurveEnum.PARKING_SPOT_BOUNDARY : {'color':(1,1,1,1),'width':1,'pointSize':0}, + RoadgraphCurveEnum.STOP_LINE : {'color':(1,1,1,1),'width':2,'pointSize':0}, + RoadgraphCurveEnum.WALL : {'color':(0,0,1,1),'width':2,'pointSize':0}, + None : {'color':(1,1,1,1),'width':1,'pointSize':0}, } SURFACE_TO_STYLE = { - RoadgraphSurfaceEnum.PAVEMENT : {'color':(0.5,0.5,0.5,0.2)}, - RoadgraphSurfaceEnum.DIRT : {'color':(160/255.0,82/255.0,45/255.0,0.2)}, - RoadgraphSurfaceEnum.GRASS : {'color':(50/255.0,255/255.0,50/255.0,0.2)}, - RoadgraphSurfaceEnum.GRAVEL : {'color':(0.7,0.7,0.7,0.2)}, - None: {'color':(1,0,0,0.2)}, + RoadgraphSurfaceEnum.PAVEMENT : {'color':(0.5,0.5,0.5,0.2),'pointSize':0}, + RoadgraphSurfaceEnum.DIRT : {'color':(160/255.0,82/255.0,45/255.0,0.2),'pointSize':0}, + RoadgraphSurfaceEnum.GRASS : {'color':(50/255.0,255/255.0,50/255.0,0.2),'pointSize':0}, + RoadgraphSurfaceEnum.GRAVEL : {'color':(0.7,0.7,0.7,0.2),'pointSize':0}, + None: {'color':(1,0,0,0.2),'pointSize':0}, } REGION_TO_STYLE = { - RoadgraphRegionEnum.INTERSECTION : {'color':(0,1,0,0.5),'width':1}, - RoadgraphRegionEnum.PARKING_LOT : {'color':(0,0,1,0.5),'width':1}, - RoadgraphRegionEnum.CLOSED_COURSE : {'color':(1,0,0,0.5),'width':1}, - RoadgraphRegionEnum.VIRTUAL : {'color':(0,0,0,0.5),'width':1}, + RoadgraphRegionEnum.INTERSECTION : {'color':(0,1,0,0.5),'width':1,'pointSize':0}, + RoadgraphRegionEnum.PARKING_LOT : {'color':(0,0,1,0.5),'width':1,'pointSize':0}, + RoadgraphRegionEnum.CLOSED_COURSE : {'color':(1,0,0,0.5),'width':1,'pointSize':0}, + RoadgraphRegionEnum.VIRTUAL : {'color':(0,0,0,0.5),'width':1,'pointSize':0}, } def plot_pose(name : str, pose : ObjectPose, axis_len=0.1, label=True): @@ -47,7 +59,7 @@ def plot_pose(name : str, pose : ObjectPose, axis_len=0.1, label=True): else: raise ValueError("Unknown frame %s" % pose.frame) -def plot_object(name : str, obj : PhysicalObject, axis_len=None, outline=True, bbox=True, label=True): +def plot_object(name : str, obj : PhysicalObject, type=None, axis_len=None, outline=True, solid=True, bbox=True, label=True): """Shows an object in the given axes. If axis_len is given, shows the object's pose with @@ -58,6 +70,8 @@ def plot_object(name : str, obj : PhysicalObject, axis_len=None, outline=True, b If bbox is True, shows the object's bounding box. """ height = obj.dimensions[2] + core_color = OBJECT_COLORS[type] + bbox_color = AUX_BBOX_COLOR if label: #add a point at the object's origin vis.add(name,obj.pose.translation(),size=5,color=(0,0,0,1)) @@ -69,37 +83,44 @@ def plot_object(name : str, obj : PhysicalObject, axis_len=None, outline=True, b if bbox or (outline and obj.outline is None): bounds = obj.bounds() (xmin,xmax),(ymin,ymax),(zmin,zmax) = bounds - corners = [[xmin,ymin,0],[xmin,ymax,0],[xmax,ymax,0],[xmax,ymin,0]] - corners = [list(R.dot(c)+t) for c in corners] - corners.append(corners[0]) - if not bbox: - vis.add(name+"_bbox1",corners,width=1,color=(1,0,0,1),hide_label=True) - else: - vis.add(name+"_bbox1",corners,width=1,color=(0,0,1,1),hide_label=True) - if height > 0: - corners = [[xmin,ymin,height],[xmin,ymax,height],[xmax,ymax,height],[xmax,ymin,height]] + if not solid: + corners = [[xmin,ymin,0.01],[xmin,ymax,0.01],[xmax,ymax,0.01],[xmax,ymin,0.01]] corners = [list(R.dot(c)+t) for c in corners] corners.append(corners[0]) if not bbox: - vis.add(name+"_bbox2",corners,width=1,color=(1,0,0,1),hide_label=True) + vis.add(name+"_bbox1",corners,width=1,color=core_color,pointSize=0,hide_label=True) else: - vis.add(name+"_bbox2",corners,width=1,color=(0,0,1,1),hide_label=True) + vis.add(name+"_bbox1",corners,width=1,color=AUX_BBOX_COLOR,pointSize=0,hide_label=True) + if height > 0: + corners = [[xmin,ymin,height],[xmin,ymax,height],[xmax,ymax,height],[xmax,ymin,height]] + corners = [list(R.dot(c)+t) for c in corners] + corners.append(corners[0]) + if not bbox: + vis.add(name+"_bbox2",corners,width=1,color=core_color,pointSize=0,hide_label=True) + else: + vis.add(name+"_bbox2",corners,width=1,color=AUX_BBOX_COLOR,pointSize=0,hide_label=True) + else: + prim = GeometricPrimitive() + prim.setAABB([xmin,ymin,0],[xmax,ymax,height]) + g = Geometry3D(prim) + g.setCurrentTransform(so3.from_matrix(R),t) + vis.add(name+"_bbox",g,color=core_color[:3]+(0.5,),hide_label=True) #plot outline if outline and obj.outline: outline = [R.dot((p[0],p[1],0))+t for p in obj.outline] outline.append(outline[0]) - vis.add(name+"_outline1",outline,width=1,color=(1,0,0,1),hide_label=True) + vis.add(name+"_outline1",outline,width=1,color=core_color,hide_label=True) if height > 0: outline = [R.dot((p[0],p[1],height))+t for p in obj.outline] outline.append(outline[0]) - vis.add(name+"_outline2",outline,width=1,color=(1,0,0,1),hide_label=True) + vis.add(name+"_outline2",outline,width=1,color=core_color,hide_label=True) def plot_vehicle(vehicle : VehicleState, vehicle_model=None, axis_len=1.0): """Plots the vehicle in the given axes. The coordinates of the vehicle are plotted in the vehicle's indicated frame.""" - plot_object("vehicle",vehicle.to_object(), axis_len=0, label=False) + plot_object("vehicle",vehicle.to_object(), type=None, axis_len=0, solid=False, label=False) R = vehicle.pose.rotation() t = vehicle.pose.translation() T = (so3.from_matrix(R),t) @@ -227,7 +248,7 @@ def plot_roadgraph(roadgraph : Roadgraph, route : Route = None): for k,o in roadgraph.static_obstacles.items(): plot_object(k,o) -def plot_scene(scene : SceneState, vehicle_model = None, xrange=None, yrange=None, title = None, show=True): +def plot_scene(scene : SceneState, vehicle_model = None, title = None, show=True): for i in list(vis.scene().items.keys()): if not i.startswith("vehicle"): if not isinstance(vis.scene().items[i],vis.VisPlot): @@ -240,36 +261,24 @@ def plot_scene(scene : SceneState, vehicle_model = None, xrange=None, yrange=Non vehicle_model.link(0).setParentTransform(*se3.from_ndarray(xform)) vehicle_model.setConfig(vehicle_model.getConfig()) - """ - if xrange is not None: - if isinstance(xrange,(tuple,list)): - ax.set_xlim(xrange[0],xrange[1]) - else: - ax.set_xlim(-xrange*0.2,xrange*0.8) - if yrange is not None: - if isinstance(yrange,(tuple,list)): - ax.set_ylim(yrange[0],yrange[1]) - else: - ax.set_ylim(-yrange*0.5,yrange*0.5) - """ #plot roadgraph plot_roadgraph(scene.roadgraph,scene.route) #plot vehicle and objects plot_vehicle(scene.vehicle, vehicle_model) for k,a in scene.agents.items(): - plot_object(k,a) + plot_object(k,a,type=a.type) for k,o in scene.obstacles.items(): plot_object(k,o) if title is None: if show: vis.add("title","Scene at t = %.2f" % scene.t, position=(10,10)) else: - vis.add("title",title, position=(10,10)) + vis.add("title",title) if show: vis.show() -def plot(state : AllState, vehicle_model=None, xrange=None, yrange=None, title=None, show=True): - plot_scene(state, vehicle_model=vehicle_model, xrange=xrange, yrange=yrange, title=title, show=show) +def plot(state : AllState, vehicle_model=None, title=None, show=True): + plot_scene(state, vehicle_model=vehicle_model, title=title, show=show) if state.route is not None: plot_path("route",state.route,color=(1,0.5,0,1)) if state.trajectory is not None: diff --git a/launch/fixed_route.yaml b/launch/fixed_route.yaml index e89db77a3..097f2fe46 100644 --- a/launch/fixed_route.yaml +++ b/launch/fixed_route.yaml @@ -16,7 +16,9 @@ drive: type: StaticRoutePlanner args: [!relative_path '../GEMstack/knowledge/routes/xyhead_highbay_backlot_p.csv'] motion_planning: RouteToTrajectoryPlanner - trajectory_tracking: pure_pursuit.PurePursuitTrajectoryTracker + trajectory_tracking: + type: pure_pursuit.PurePursuitTrajectoryTracker + print: False log: # Specify the top-level folder to save the log files. Default is 'logs' #folder : 'logs' diff --git a/scenes/xyhead_demo.yaml b/scenes/xyhead_demo.yaml index 8b614fd93..121a1a527 100644 --- a/scenes/xyhead_demo.yaml +++ b/scenes/xyhead_demo.yaml @@ -2,8 +2,8 @@ vehicle_state: [4.0, 5.0, 0.0, 0.0, 0.0] agents: ped1: type: pedestrian - position: [12.0, 0.0] + position: [20.0, 2.0] nominal_velocity: 0.5 - target: [12.0,10.0] + target: [20.0,10.0] behavior: loop \ No newline at end of file From ceed729b41773bfb8aecf6218760564872955f93 Mon Sep 17 00:00:00 2001 From: krishauser Date: Wed, 7 Feb 2024 01:04:31 -0500 Subject: [PATCH 098/232] Better warnings with variants --- GEMstack/onboard/execution/entrypoint.py | 10 ++++++---- GEMstack/utils/config.py | 11 +++++++++-- 2 files changed, 15 insertions(+), 6 deletions(-) diff --git a/GEMstack/onboard/execution/entrypoint.py b/GEMstack/onboard/execution/entrypoint.py index 33c707822..3656eeff1 100644 --- a/GEMstack/onboard/execution/entrypoint.py +++ b/GEMstack/onboard/execution/entrypoint.py @@ -11,6 +11,8 @@ def main(): if settings.get('variant',None) is not None: variant = settings.get('variant') variants = variant.split(',') + def caution_callback(k,variant): + print(EXECUTION_PREFIX,"variant {} defines key {} which is not found in normal settings".format(variant,k)) for v in variants: if v not in settings.get('variants',{}): if v not in settings.get('run.variants',{}): @@ -19,12 +21,12 @@ def main(): raise ValueError("Variant "+v+" not found") else: overrides = settings.get('run.variants.'+v) - print("APPYING VARIANT",overrides) - config.update_recursive(settings.settings(),overrides) + print(EXECUTION_PREFIX,"APPYING VARIANT",overrides) + config.update_recursive(settings.settings(),overrides,lambda k:caution_callback(k,v)) else: overrides = settings.get('variants.'+v) - print("APPYING VARIANT",overrides) - config.update_recursive(settings.settings(),overrides) + print(EXECUTION_PREFIX,"APPYING VARIANT",overrides) + config.update_recursive(settings.settings(),overrides,lambda k:caution_callback(k,v)) #don't need this to be saved in the log if 'variants' in settings.settings(): del settings.settings()['variants'] diff --git a/GEMstack/utils/config.py b/GEMstack/utils/config.py index 025e0f466..a50a16249 100644 --- a/GEMstack/utils/config.py +++ b/GEMstack/utils/config.py @@ -3,6 +3,7 @@ import os from typing import Any, IO import collections +import warnings def save_config(fn : str, config : dict) -> None: """Saves a configuration file.""" @@ -89,7 +90,7 @@ def _load_recursive(obj, folder : str): -def update_recursive(d : dict, u : dict) -> dict: +def update_recursive(d : dict, u : dict, caution_callback=None) -> dict: """Updates a dictionary d with another dictionary u recursively. The update happens in-place and d is returned. @@ -97,10 +98,16 @@ def update_recursive(d : dict, u : dict) -> dict: if not isinstance(d, collections.abc.Mapping): raise ValueError("Trying to update a non-dict with a dict") for k, v in u.items(): + sub_callback = None + if caution_callback: + if k not in d: + caution_callback(k) + else: + sub_callback = lambda k2:caution_callback(k + '.' + k2) if isinstance(v, collections.abc.Mapping): if not isinstance(d.get(k, {}), collections.abc.Mapping): d[k] = {} - d[k] = update_recursive(d.get(k, {}), v) + d[k] = update_recursive(d.get(k, {}), v, sub_callback) else: d[k] = v return d \ No newline at end of file From 81a2981861cd7dc5d240d65024e6902e19ed7c83 Mon Sep 17 00:00:00 2001 From: krishauser Date: Wed, 7 Feb 2024 01:04:41 -0500 Subject: [PATCH 099/232] moved ros logging to variant --- launch/fixed_route.yaml | 12 ++++++------ launch/gather_data.yaml | 11 +++++++++-- 2 files changed, 15 insertions(+), 8 deletions(-) diff --git a/launch/fixed_route.yaml b/launch/fixed_route.yaml index 097f2fe46..3d71b5c66 100644 --- a/launch/fixed_route.yaml +++ b/launch/fixed_route.yaml @@ -27,7 +27,7 @@ log: # If suffix is specified, then logs will output to folder/prefix+suffix. Default uses date and time as the suffix #suffix : 'test3' # Specify which ros topics to record to vehicle.bag. Default records nothing. This records the "standard" ROS topics. - ros_topics : !include "../GEMstack/knowledge/defaults/standard_ros_topics.yaml" + ros_topics : [] # Specify options to pass to rosbag record. Default is no options. #rosbag_options : '--split --size=1024' # If True, then record all readings / commands of the vehicle interface. Default False @@ -50,7 +50,8 @@ computation_graph: !include "../GEMstack/knowledge/defaults/computation_graph.ya #on load, variants will overload the settings structure variants: - #sim variant doesn't execute on the real vehicle or log ros topics + #sim variant doesn't execute on the real vehicle + #real variant executes on the real robot sim: run: mode: simulation @@ -65,7 +66,6 @@ variants: agent_detection : OmniscientAgentDetector visualization: !include "klampt_visualization.yaml" #visualization: !include "mpl_visualization.yaml" - - log: - ros_topics : [] - \ No newline at end of file + log_ros: + log: + ros_topics : !include "../GEMstack/knowledge/defaults/standard_ros_topics.yaml" \ No newline at end of file diff --git a/launch/gather_data.yaml b/launch/gather_data.yaml index 465f9abb6..4f3d03d4c 100644 --- a/launch/gather_data.yaml +++ b/launch/gather_data.yaml @@ -26,7 +26,7 @@ log: # If suffix is specified, then logs will output to folder/prefix+suffix. Default uses date and time as the suffix #suffix : 'test3' # Specify which ros topics to record to vehicle.bag. Default records nothing. This records the "standard" ROS topics. - ros_topics : !include "../GEMstack/knowledge/defaults/standard_ros_topics.yaml" + ros_topics : [] # Specify options to pass to rosbag record. Default is no options. #rosbag_options : '--split --size=1024' # If True, then record all readings / commands of the vehicle interface. Default False @@ -44,4 +44,11 @@ replay: # Add items here to set certain topics / inputs to be replayed from log components : [] #usually can keep this constant -computation_graph: !include "../GEMstack/knowledge/defaults/computation_graph.yaml" \ No newline at end of file +computation_graph: !include "../GEMstack/knowledge/defaults/computation_graph.yaml" + +variants: + #"log_ros" variant records standard ros topics + log_ros: + run: + log: + ros_topics: !include "../GEMstack/knowledge/defaults/standard_ros_topics.yaml" \ No newline at end of file From 13899a91b260e96e434e826028057f574ed5d336 Mon Sep 17 00:00:00 2001 From: krishauser Date: Sat, 10 Feb 2024 14:03:54 -0500 Subject: [PATCH 100/232] Cleaner cleanup of visualization. Lights look better --- GEMstack/onboard/interface/gem_simulator.py | 5 +++++ .../onboard/visualization/klampt_visualization.py | 14 +++++++++++++- GEMstack/utils/klampt_visualization.py | 15 ++++++++------- 3 files changed, 26 insertions(+), 8 deletions(-) diff --git a/GEMstack/onboard/interface/gem_simulator.py b/GEMstack/onboard/interface/gem_simulator.py index 9999b7f34..3d36f5a63 100644 --- a/GEMstack/onboard/interface/gem_simulator.py +++ b/GEMstack/onboard/interface/gem_simulator.py @@ -185,6 +185,11 @@ def simulate(self, T : float, command : Optional[GEMVehicleCommand]): #print("Accel %.2f, steering angle current %.2f, desired %.2f, rate %.2f" % (acceleration,phi,phides,steering_angle_rate)) next = simulate(self.dubins, self.cur_vehicle_state, (lambda x,t: u), T, self.dt) next_state = next['x'][-1] + #braking deadband + if v > 0 and next_state[3] < 0: + next_state[3] = 0 + if v < 0 and next_state[3] > 0: + next_state[3] = 0 x,y,theta,v,phi = next_state v = np.clip(v,*self.dubins.velocityRange) next_state = np.array([x,y,theta,v,phi]) diff --git a/GEMstack/onboard/visualization/klampt_visualization.py b/GEMstack/onboard/visualization/klampt_visualization.py index 2927eb7ec..2a689c35f 100644 --- a/GEMstack/onboard/visualization/klampt_visualization.py +++ b/GEMstack/onboard/visualization/klampt_visualization.py @@ -64,7 +64,19 @@ def initialize(self): vp.clippingplanes = (0.1,1000) vis.setViewport(vp) vis.add("vehicle_plane",self.world.terrain(0),hide_label=True) + #note: show() takes over the interrupt handler and sets it to default, so we restore it + import signal + oldsig = signal.getsignal(signal.SIGINT) vis.show() + signal.signal(signal.SIGINT,oldsig) + + def cleanup(self): + print("klampt_visualization Cleanup") + vis.show(False) + vis.clear() + vis.kill() + self.vehicle = None + self.world = None def debug(self, source, item, value): if source not in self.plot_values: @@ -92,7 +104,7 @@ def update(self, state): self.debug("vehicle","accelerator",state.vehicle.accelerator_pedal_position) self.debug("vehicle","brake",state.vehicle.brake_pedal_position) time_str = time.strftime("%Y-%m-%d %H:%M:%S", time.localtime(state.t)) - state_start = state.to_frame(ObjectFrameEnum.START) + state_start = state.to_frame(ObjectFrameEnum.START) if state.start_vehicle_pose is not None else state.to_frame(state.vehicle.pose.frame) klampt_visualization.plot(state_start,title="Scene %d at %s"%(self.num_updates,time_str),vehicle_model=self.vehicle,show=False) #update pose of the vehicle diff --git a/GEMstack/utils/klampt_visualization.py b/GEMstack/utils/klampt_visualization.py index 3d7069fc2..6c53ad010 100644 --- a/GEMstack/utils/klampt_visualization.py +++ b/GEMstack/utils/klampt_visualization.py @@ -173,21 +173,22 @@ def plot_vehicle(vehicle : VehicleState, vehicle_model=None, axis_len=1.0): vis.addText("gear",gear,position=(t[0],t[1],1.5),color=(0,0,0,1)) #plot lights - light_size = 4 + light_point_size = 4 + light_size = 0.15 light_color = (1,1,0,1) turn_indicator_height = 0.7 headlight_height = 0.6 if vehicle.left_turn_indicator: - lp = vehicle.pose.apply([xbounds[0]+light_size,ybounds[0]+light_size,turn_indicator_height]) - vis.add("left_turn_indicator",list(lp),size=light_size,color=light_color) + lp = vehicle.pose.apply([xbounds[0],ybounds[0]+light_size,turn_indicator_height]) + vis.add("left_turn_indicator",list(lp),size=light_point_size,color=light_color) if vehicle.right_turn_indicator: - lp = vehicle.pose.apply([xbounds[0]+light_size,ybounds[1]-light_size,turn_indicator_height]) - vis.add("right_turn_indicator",list(lp),size=light_size,color=light_color) + lp = vehicle.pose.apply([xbounds[0],ybounds[1]-light_size,turn_indicator_height]) + vis.add("right_turn_indicator",list(lp),size=light_point_size,color=light_color) if vehicle.headlights_on: lp = vehicle.pose.apply([xbounds[1],ybounds[0]+light_size*2,headlight_height]) - vis.add("left_headlight",list(lp),size=light_size,color=light_color) + vis.add("left_headlight",list(lp),size=light_point_size,color=light_color) lp = vehicle.pose.apply([xbounds[1],ybounds[1]-light_size*2,headlight_height]) - vis.add("right_headlight",list(lp),size=light_size,color=light_color) + vis.add("right_headlight",list(lp),size=light_point_size,color=light_color) if vehicle_model is not None: if vehicle.brake_pedal_position > 0.1: vehicle_model.link('rear_right_stop_light_link').appearance().setColor(1,0,0,1) From dc1a46e582e8b09c0d2a86e58d182646ef0032a2 Mon Sep 17 00:00:00 2001 From: krishauser Date: Sat, 10 Feb 2024 14:05:36 -0500 Subject: [PATCH 101/232] Moved format conversions to utils/conversions. Added numpy subscriber to top lidar --- GEMstack/onboard/interface/gem_hardware.py | 22 ++++++---- GEMstack/utils/conversions.py | 48 ++++++++++++++++++++++ 2 files changed, 63 insertions(+), 7 deletions(-) create mode 100644 GEMstack/utils/conversions.py diff --git a/GEMstack/onboard/interface/gem_hardware.py b/GEMstack/onboard/interface/gem_hardware.py index fb01e5b47..2242e4498 100644 --- a/GEMstack/onboard/interface/gem_hardware.py +++ b/GEMstack/onboard/interface/gem_hardware.py @@ -15,7 +15,9 @@ # OpenCV and cv2 bridge import cv2 -from cv_bridge import CvBridge +import numpy as np +from ...utils import conversions + class GEMHardwareInterface(GEMInterface): """Interface for connnecting to the physical GEM e2 vehicle.""" @@ -140,9 +142,16 @@ def subscribe_sensor(self, name, callback, type = None): raise ValueError("GEMHardwareInterface only supports Inspva for GNSS") self.gnss_sub = rospy.Subscriber("/novatel/inspva", Inspva, callback) elif name == 'top_lidar': - if type is not None and type is not PointCloud2: - raise ValueError("GEMHardwareInterface only supports PointCloud2 for top lidar") - self.top_lidar_sub = rospy.Subscriber("/lidar1/velodyne_points", PointCloud2, callback) + if type is not None and (type is not PointCloud2 and type is not np.ndarray): + raise ValueError("GEMHardwareInterface only supports PointCloud2 or numpy array for top lidar") + if type is None or type is PointCloud2: + self.top_lidar_sub = rospy.Subscriber("/lidar1/velodyne_points", PointCloud2, callback) + else: + def callback_with_numpy(msg : Image): + #print("received image with size",msg.width,msg.height,"encoding",msg.encoding) + points = conversions.ros_PointCloud2_to_numpy(msg, want_rgb=False) + callback(points) + self.top_lidar_sub = rospy.Subscriber("/lidar1/velodyne_points", PointCloud2, callback_with_numpy) elif name == 'front_radar': if type is not None and type is not RadarTracks: raise ValueError("GEMHardwareInterface only supports RadarTracks for front radar") @@ -153,10 +162,9 @@ def subscribe_sensor(self, name, callback, type = None): if type is None or type is Image: self.front_camera_sub = rospy.Subscriber("/zed2/zed_node/rgb/image_rect_color", Image, callback) else: - self.bridge = CvBridge() def callback_with_cv2(msg : Image): #print("received image with size",msg.width,msg.height,"encoding",msg.encoding) - cv_image = self.bridge.imgmsg_to_cv2(msg, desired_encoding="bgr8") + cv_image = conversions.ros_Image_to_cv2(msg, desired_encoding="bgr8") callback(cv_image) self.front_camera_sub = rospy.Subscriber("/zed2/zed_node/rgb/image_rect_color", Image, callback_with_cv2) elif name == 'front_depth': @@ -168,7 +176,7 @@ def callback_with_cv2(msg : Image): self.bridge = CvBridge() def callback_with_cv2(msg : Image): #print("received image with size",msg.width,msg.height,"encoding",msg.encoding) - cv_image = self.bridge.imgmsg_to_cv2(msg, desired_encoding="passthrough") + cv_image = conversions.ros_Image_to_cv2(msg, desired_encoding="passthrough") callback(cv_image) self.front_depth_sub = rospy.Subscriber("/zed2/zed_node/depth/depth_registered", Image, callback_with_cv2) diff --git a/GEMstack/utils/conversions.py b/GEMstack/utils/conversions.py new file mode 100644 index 000000000..75bf5568c --- /dev/null +++ b/GEMstack/utils/conversions.py @@ -0,0 +1,48 @@ +import cv2 +import numpy as np +import struct +import ctypes + +try: + import sensor_msgs.point_cloud2 as pc2 +except ImportError: + pc2 = None + +try: + from cv_bridge import CvBridge + cv_bridge = CvBridge() +except ImportError: + cv_bridge = None + + +def ros_PointCloud2_to_numpy(pc2_msg, want_rgb = False): + if pc2 is None: + raise ImportError("ROS is not installed") + gen = pc2.read_points(pc2_msg, skip_nans=True) + if want_rgb: + xyzpack = np.array(list(gen),dtype=np.float32) + if xyzpack.shape[1] != 4: + raise ValueError("PointCloud2 does not have points with color data.") + xyzrgb = np.empty((xyzpack.shape[0],6)) + xyzrgb[:,:3] = xyzpack[:,:3] + for i,x in enumerate(xyzpack): + rgb = x[3] + # cast float32 to int so that bitwise operations are possible + s = struct.pack('>f' ,rgb) + i = struct.unpack('>l',s)[0] + # you can get back the float value by the inverse operations + pack = ctypes.c_uint32(i).value + r = (pack & 0x00FF0000)>> 16 + g = (pack & 0x0000FF00)>> 8 + b = (pack & 0x000000FF) + #r,g,b values in the 0-255 range + xyzrgb[i,3:] = (r,g,b) + return xyzrgb + else: + return np.array(list(gen),dtype=np.float32)[:,:3] + + +def ros_Image_to_cv2(msg, desired_encoding="passthrough"): + if cv_bridge is None: + raise ImportError("cv_bridge is not installed") + return cv_bridge.imgmsg_to_cv2(msg, desired_encoding=desired_encoding) \ No newline at end of file From 15c75cbf2f2e62e527b1949fab1cfc2b7c3e943a Mon Sep 17 00:00:00 2001 From: krishauser Date: Sat, 10 Feb 2024 14:43:02 -0500 Subject: [PATCH 102/232] fixed problem with closest point --- GEMstack/mathutils/collisions.py | 31 ++++++++++++++++++++++++++++--- GEMstack/mathutils/transforms.py | 3 ++- 2 files changed, 30 insertions(+), 4 deletions(-) diff --git a/GEMstack/mathutils/collisions.py b/GEMstack/mathutils/collisions.py index e893c953a..a59c0d052 100644 --- a/GEMstack/mathutils/collisions.py +++ b/GEMstack/mathutils/collisions.py @@ -141,15 +141,31 @@ def line_intersects_line_2d(vertices1 : List[Tuple[float,float]], vertices2 : Li Faster to create a CollisionDetector2D object if you will be doing multiple queries. """ - return shapely.LineString(vertices1).distance(shapely.LineString(vertices2)) + return shapely.LineString(vertices1).intersects(shapely.LineString(vertices2)) -def line_polygon_distance_2d(vertices : List[Tuple[float,float]], polygon : List[Tuple[float,float]]) -> bool: +def line_polygon_distance_2d(vertices : List[Tuple[float,float]], polygon : List[Tuple[float,float]]) -> float: """Returns distance from a line to a polygon. Faster to create a CollisionDetector2D object if you will be doing multiple queries. """ - return shapely.Polygon(polygon).intersects(shapely.LineString(vertices)) + return shapely.Polygon(polygon).distance(shapely.LineString(vertices)) + +def polygon_intersects_polygon_2d(poly1 : List[Tuple[float,float]], poly2 : List[Tuple[float,float]]) -> bool: + """Returns whether two polygons intersect. + + Faster to create a CollisionDetector2D object if you will be doing + multiple queries. + """ + return shapely.Polygon(poly1).intersects(shapely.Polygon(poly2)) + +def polygon_polygon_distance_2d(poly1 : List[Tuple[float,float]], poly2 : List[Tuple[float,float]]) -> float: + """Returns the distance between two polygons. + + Faster to create a CollisionDetector2D object if you will be doing + multiple queries. + """ + return shapely.Polygon(poly1).distance(shapely.Polygon(poly1)) class CollisionDetector2D: @@ -162,6 +178,15 @@ class CollisionDetector2D: def __init__(self): self.objects = dict() self.collision_pairs = set() + + def remove(self, name : str) -> None: + """Removes an object from the collision detector.""" + del self.objects[name] + for name2 in self.objects.keys(): + if name < name2: + self.collision_pairs.discard((name,name2)) + else: + self.collision_pairs.discard((name2,name)) def add_polygon(self, name : str, polygon : List[Tuple[float,float]]) -> None: """Adds an object to the collision detector.""" diff --git a/GEMstack/mathutils/transforms.py b/GEMstack/mathutils/transforms.py index 679d5063a..97f7610dd 100644 --- a/GEMstack/mathutils/transforms.py +++ b/GEMstack/mathutils/transforms.py @@ -67,7 +67,8 @@ def point_segment_distance(x,a,b) -> Tuple[float,float]: elif udotv > vnorm: return vector_norm(vector_sub(x,b)),1 else: - return vector_norm(vector_sub(u,vector_madd(v,u,udotv/vnorm))),udotv/vnorm + param = udotv/vnorm + return vector_norm(vector_sub(u,vector_mul(v,param))),param def rotate2d(point, angle : float, origin=None): """Rotates a point about the origin by an angle""" From 2a7d46d6ae957a7589b7ee95611c4bfd4c18a0f2 Mon Sep 17 00:00:00 2001 From: krishauser Date: Sat, 10 Feb 2024 22:19:05 -0500 Subject: [PATCH 103/232] Fixed trajectory closest point and arc length parameterization --- GEMstack/mathutils/collisions.py | 2 +- GEMstack/mathutils/transforms.py | 2 +- GEMstack/state/trajectory.py | 15 +++++++++++---- 3 files changed, 13 insertions(+), 6 deletions(-) diff --git a/GEMstack/mathutils/collisions.py b/GEMstack/mathutils/collisions.py index a59c0d052..6580c8585 100644 --- a/GEMstack/mathutils/collisions.py +++ b/GEMstack/mathutils/collisions.py @@ -165,7 +165,7 @@ def polygon_polygon_distance_2d(poly1 : List[Tuple[float,float]], poly2 : List[T Faster to create a CollisionDetector2D object if you will be doing multiple queries. """ - return shapely.Polygon(poly1).distance(shapely.Polygon(poly1)) + return shapely.Polygon(poly1).distance(shapely.Polygon(poly2)) class CollisionDetector2D: diff --git a/GEMstack/mathutils/transforms.py b/GEMstack/mathutils/transforms.py index 97f7610dd..833ecc80d 100644 --- a/GEMstack/mathutils/transforms.py +++ b/GEMstack/mathutils/transforms.py @@ -68,7 +68,7 @@ def point_segment_distance(x,a,b) -> Tuple[float,float]: return vector_norm(vector_sub(x,b)),1 else: param = udotv/vnorm - return vector_norm(vector_sub(u,vector_mul(v,param))),param + return vector_norm(vector_sub(u,vector_mul(v,param/vnorm))),param def rotate2d(point, angle : float, origin=None): """Rotates a point about the origin by an angle""" diff --git a/GEMstack/state/trajectory.py b/GEMstack/state/trajectory.py index 427f99dcb..d7a57db00 100644 --- a/GEMstack/state/trajectory.py +++ b/GEMstack/state/trajectory.py @@ -13,7 +13,7 @@ class Path: frame : ObjectFrameEnum points : List[List[float]] - def to_frame(self, frame : ObjectFrameEnum, current_pose : None, start_pose_abs : None) -> Path: + def to_frame(self, frame : ObjectFrameEnum, current_pose = None, start_pose_abs = None) -> Path: """Converts the route to a different frame.""" new_points = [convert_point(p,self.frame,frame,current_pose,start_pose_abs) for p in self.points] return replace(self,frame=frame,points=new_points) @@ -26,7 +26,7 @@ def parameter_to_index(self, t : float) -> Tuple[int,float]: """Converts a path parameter to an (edge index, edge parameter) tuple.""" if len(self.points) < 2: return 0,0.0 - ind = int(t) + ind = int(math.floor(t)) #truncate toward zero if ind < 0: ind = 0 if ind >= len(self.points)-1: ind = len(self.points)-2 u = t - ind @@ -59,9 +59,16 @@ def eval_derivative(self, u : float) -> List[float]: p2 = self.points[ind+1] return transforms.vector_sub(p2,p1) + def length(self): + """Returns the length of the path.""" + l = 0.0 + for i in range(len(self.points)-1): + l += transforms.vector_dist(self.points[i],self.points[i+1]) + return l + def arc_length_parameterize(self, speed = 1.0) -> Trajectory: """Returns a new path that is parameterized by arc length.""" - times = [0] + times = [0.0] points = [self.points[0]] for i in range(len(self.points)-1): p1 = self.points[i] @@ -70,7 +77,7 @@ def arc_length_parameterize(self, speed = 1.0) -> Trajectory: if d > 0: points.append(p2) times.append(times[-1] + d/speed) - return Trajectory(frame=self.frame,points=self.points,times=times) + return Trajectory(frame=self.frame,points=points,times=times) def closest_point(self, x : List[float], edges = True) -> Tuple[float,float]: """Returns the closest point on the path to the given point. If From cab69a3cc2042b467c51241afab66f90c220fdb3 Mon Sep 17 00:00:00 2001 From: krishauser Date: Sat, 10 Feb 2024 22:19:55 -0500 Subject: [PATCH 104/232] Fixed corner cases in pure pursuit --- GEMstack/onboard/planning/pure_pursuit.py | 61 ++++++++++++++++------- GEMstack/state/physical_object.py | 16 ++++++ 2 files changed, 58 insertions(+), 19 deletions(-) diff --git a/GEMstack/onboard/planning/pure_pursuit.py b/GEMstack/onboard/planning/pure_pursuit.py index 00806a775..eb925423d 100644 --- a/GEMstack/onboard/planning/pure_pursuit.py +++ b/GEMstack/onboard/planning/pure_pursuit.py @@ -21,7 +21,10 @@ def __init__(self, lookahead = None, lookahead_scale = None, wheelbase = None, c self.steering_angle_range = [settings.get('vehicle.geometry.min_steering_angle'),settings.get('vehicle.geometry.max_steering_angle')] self.desired_speed = settings.get('control.pure_pursuit.desired_speed',2.5) #approximately 5 mph - self.desired_speed_from_path = False #turn this to True to use the input trajectory to determine the desired speed + self.desired_speed_from_path = True #turn this to True to use the input trajectory to determine the desired speed + self.speed_limit = settings.get('vehicle.limits.max_speed') + if self.desired_speed > self.speed_limit: + self.desired_speed = self.speed_limit self.max_accel = settings.get('vehicle.limits.max_acceleration') # m/s^2 self.max_decel = settings.get('vehicle.limits.max_deceleration') # m/s^2 self.pid_speed = PID(settings.get('control.longitudinal_control.pid_p',0.5), settings.get('control.longitudinal_control.pid_d',0.0), settings.get('control.longitudinal_control.pid_i',0.1), windup_limit=20) @@ -70,29 +73,34 @@ def compute(self, state : VehicleState): if self.path.frame != state.pose.frame: print("Transforming path from",self.path.frame.name,"to",state.pose.frame.name) - self.path = self.path.to_frame(state.pose.frame) + self.path = self.path.to_frame(state.pose.frame, current_pose=state.pose) if self.trajectory is not None: if self.trajectory.frame != state.pose.frame: print("Transforming trajectory from",self.trajectory.frame.name,"to",state.pose.frame.name) - self.trajectory = self.trajectory.to_frame(state.pose.frame) + self.trajectory = self.trajectory.to_frame(state.pose.frame, current_pose=state.pose) closest_dist,closest_parameter = self.path.closest_point_local((curr_x,curr_y),[self.current_path_parameter-5.0,self.current_path_parameter+5.0]) + self.current_path_parameter = closest_parameter #TODO: calculate parameter that is look_ahead distance away from the closest point? #(rather than just advancing the parameter) des_parameter = closest_parameter + self.look_ahead + self.look_ahead_scale * speed - self.current_path_parameter = closest_parameter print("Closest parameter: " + str(closest_parameter),"distance to path",closest_dist) - print("Closest point",self.path.eval(closest_parameter),"vs",(curr_x,curr_y)) + if closest_dist > 0.1: + print("Closest point",self.path.eval(closest_parameter),"vs",(curr_x,curr_y)) if des_parameter >= self.path.domain()[1]: #we're at the end of the path, calculate desired point by extrapolating from the end of the path end_pt = self.path.points[-1] - end_dir = self.path.eval_tangent(self.path.domain()[1]) + if len(self.path.points) > 1: + end_dir = self.path.eval_tangent(self.path.domain()[1]) + else: + #path is just a single point, just look at current direction + end_dir = (np.cos(curr_yaw),np.sin(curr_yaw)) desired_x,desired_y = transforms.vector_madd(end_pt,end_dir,(des_parameter-self.path.domain()[1])) else: desired_x,desired_y = self.path.eval(des_parameter) desired_yaw = np.arctan2(desired_y-curr_y,desired_x-curr_x) - print("Desired point",(desired_x,desired_y)," with lookahead distance",self.look_ahead + self.look_ahead_scale * speed) - print("Current yaw",curr_yaw,"desired yaw",desired_yaw) + #print("Desired point",(desired_x,desired_y)," with lookahead distance",self.look_ahead + self.look_ahead_scale * speed) + #print("Current yaw",curr_yaw,"desired yaw",desired_yaw) # distance between the desired point and the vehicle L = transforms.vector2_dist((desired_x,desired_y),(curr_x,curr_y)) @@ -110,11 +118,11 @@ def compute(self, state : VehicleState): f_delta = np.clip(angle, self.wheel_angle_range[0], self.wheel_angle_range[1]) - print("Closest point distance: " + str(L)) + #print("Closest point distance: " + str(L)) print("Forward velocity: " + str(speed)) ct_error = np.sin(alpha) * L - print("Crosstrack Error: " + str(round(ct_error,3))) - print("Front steering angle: " + str(round(np.degrees(f_delta),2)) + " degrees") + #print("Crosstrack Error: " + str(round(ct_error,3))) + print("Front wheel angle: " + str(round(np.degrees(f_delta),2)) + " degrees") steering_angle = np.clip(front2steer(f_delta), self.steering_angle_range[0], self.steering_angle_range[1]) print("Steering wheel angle: " + str(round(np.degrees(steering_angle),2)) + " degrees" ) @@ -122,17 +130,32 @@ def compute(self, state : VehicleState): feedforward_accel = 0.0 if self.desired_speed_from_path: #determine desired speed from trajectory - deriv = self.trajectory.eval_derivative(self.current_path_parameter) - desired_speed = np.linalg.norm(deriv) - feedforward_accel = (desired_speed - speed)/dt - feedforward_accel= np.clip(feedforward_accel, -self.max_decel, self.max_accel) - print("Desired speed",desired_speed,"m/s","vs current speed",speed,"m/s") - print("Feedforward accel: " + str(feedforward_accel) + " m/s^2") + if len(self.trajectory.points) < 2 or self.current_path_parameter >= self.path.domain()[1]: + #past the end, just stop + desired_speed = 0.0 + feedforward_accel = -2.0 + else: + current_trajectory_time = self.trajectory.parameter_to_time(self.current_path_parameter) + deriv = self.trajectory.eval_derivative(current_trajectory_time) + desired_speed = min(np.linalg.norm(deriv),self.speed_limit) + difference_dt = 0.1 + if current_trajectory_time >= self.trajectory.domain()[1]: + prev_deriv = self.trajectory.eval_derivative(current_trajectory_time - difference_dt) + prev_desired_speed = min(np.linalg.norm(prev_deriv),self.speed_limit) + feedforward_accel = (desired_speed - prev_desired_speed)/difference_dt + print("Desired speed",desired_speed,"m/s",", from prior",prev_desired_speed,"m/s") + else: + next_deriv = self.trajectory.eval_derivative(current_trajectory_time + difference_dt) + next_desired_speed = min(np.linalg.norm(next_deriv),self.speed_limit) + feedforward_accel = (next_desired_speed - desired_speed)/difference_dt + print("Desired speed",desired_speed,"m/s",", trying to reach desired",next_desired_speed,"m/s") + feedforward_accel= np.clip(feedforward_accel, -self.max_decel, self.max_accel) + print("Feedforward accel: " + str(feedforward_accel) + " m/s^2") else: #decay speed when crosstrack error is high - desired_speed *= np.exp(-ct_error*0.1) + desired_speed *= np.exp(-ct_error*0.4) output_accel = self.pid_speed.advance(e = desired_speed - speed, t = t, feedforward_term=feedforward_accel) - print("Output acceleration",output_accel) + print("Output accel: " + str(output_accel) + " m/s^2") if output_accel > self.max_accel: output_accel = self.max_accel diff --git a/GEMstack/state/physical_object.py b/GEMstack/state/physical_object.py index e21381b5c..3e3838ddb 100644 --- a/GEMstack/state/physical_object.py +++ b/GEMstack/state/physical_object.py @@ -239,6 +239,22 @@ def bounds(self) -> Tuple[Tuple[float,float],Tuple[float,float],Tuple[float,floa """Returns the bounding box of the object in its local frame.""" l,w,h = self.dimensions return [[-l/2,l/2],[-w/2,w/2],[0,h]] + + def polygon(self) -> List[Tuple[float,float]]: + """Returns the object's outline polygon in its local frame. If `outline` is + not specified, this creates an outline from the bounding box.""" + if self.outline is not None: + return self.outline + l,w,h = self.dimensions + return [(-l/2,-w/2),(l/2,-w/2),(l/2,w/2),(-l/2,w/2)] + + def polygon_parent(self) -> List[Tuple[float,float]]: + """Returns the object's outline polygon in its parent frame, i.e., the frame + referred to in self.pose.frame.""" + p = self.polygon() + R = self.pose.rotation2d() + t = self.pose.translation()[:2] + return [(R.dot(pt) + t).tolist() for pt in p] def to_frame(self, frame : ObjectFrameEnum, current_pose = None, start_pose_abs = None): newpose = self.pose.to_frame(frame,current_pose,start_pose_abs) From e2b09cc6d0cdccc1d8353cc058c7fd733fa12e00 Mon Sep 17 00:00:00 2001 From: krishauser Date: Sat, 10 Feb 2024 22:20:10 -0500 Subject: [PATCH 105/232] Better debug information for malformed config files --- GEMstack/onboard/execution/execution.py | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/GEMstack/onboard/execution/execution.py b/GEMstack/onboard/execution/execution.py index 4a03e1d50..81d8f86e5 100644 --- a/GEMstack/onboard/execution/execution.py +++ b/GEMstack/onboard/execution/execution.py @@ -320,7 +320,12 @@ def make_component(self, config_info, component_name, parent_module=None, extra_ if identifier in self.all_components: return self.all_components[identifier] else: - component = make_class(config_info,component_name,parent_module,extra_args) + try: + component = make_class(config_info,component_name,parent_module,extra_args) + except Exception as e: + print("Exception raised while tryign to make component {} from config info:".format(component_name)) + print(" ",config_info) + raise if not isinstance(component,Component): raise RuntimeError("Component {} is not a subclass of Component".format(component_name)) replacement = self.logging_manager.component_replayer(component_name, component) From 6801fce34f113fc37d40f3350b94abd0ff9b1383 Mon Sep 17 00:00:00 2001 From: krishauser Date: Sat, 10 Feb 2024 22:20:47 -0500 Subject: [PATCH 106/232] Fixed some issues with cameras and agent demo --- GEMstack/onboard/perception/agent_detection.py | 9 +++++++-- GEMstack/onboard/visualization/klampt_visualization.py | 8 ++++++-- scenes/xyhead_demo.yaml | 4 ++-- 3 files changed, 15 insertions(+), 6 deletions(-) diff --git a/GEMstack/onboard/perception/agent_detection.py b/GEMstack/onboard/perception/agent_detection.py index c2ca700c2..5d600f792 100644 --- a/GEMstack/onboard/perception/agent_detection.py +++ b/GEMstack/onboard/perception/agent_detection.py @@ -2,12 +2,15 @@ from ..interface.gem import GEMInterface from ..component import Component from typing import Dict +import threading +import copy class OmniscientAgentDetector(Component): """Obtains agent detections from a simulator""" def __init__(self,vehicle_interface : GEMInterface): self.vehicle_interface = vehicle_interface self.agents = {} + self.lock = threading.Lock() def rate(self): return 4.0 @@ -22,7 +25,9 @@ def initialize(self): self.vehicle_interface.subscribe_sensor('agent_detector',self.agent_callback, AgentState) def agent_callback(self, name : str, agent : AgentState): - self.agents[name] = agent + with self.lock: + self.agents[name] = agent def update(self) -> Dict[str,AgentState]: - return self.agents + with self.lock: + return copy.deepcopy(self.agents) diff --git a/GEMstack/onboard/visualization/klampt_visualization.py b/GEMstack/onboard/visualization/klampt_visualization.py index 2a689c35f..41e05e858 100644 --- a/GEMstack/onboard/visualization/klampt_visualization.py +++ b/GEMstack/onboard/visualization/klampt_visualization.py @@ -24,6 +24,7 @@ def __init__(self, vehicle_interface, rate : float = 10.0, save_as : str = None) self.plot_values = {} self.plot_events = {} self.vfilter = OnlineLowPassFilter(1.2, 30, 4) + self.last_v = 0.0 self.world = WorldModel() fn = os.path.abspath(os.path.join(__file__,"../../../knowledge/vehicle/model/gem_e2.urdf")) @@ -111,10 +112,13 @@ def update(self, state): if self.last_yaw is not None: vp = vis.getViewport() v = self.vfilter(state.vehicle.v) - lookahead = 5.0*v - dx,dy = math.cos(state.vehicle.pose.yaw)*lookahead,math.sin(state.vehicle.pose.yaw)*lookahead + center_offset = 1.0 + lookahead = 4.0*v + dx,dy = math.cos(state.vehicle.pose.yaw)*(lookahead+center_offset),math.sin(state.vehicle.pose.yaw)*(lookahead+center_offset) vp.camera.tgt = [state.vehicle.pose.x+dx,state.vehicle.pose.y+dy,1.5] vp.camera.rot[2] += state.vehicle.pose.yaw - self.last_yaw + vp.camera.dist += 5.0*(v - self.last_v) + self.last_v = v vis.setViewport(vp) self.last_yaw = state.vehicle.pose.yaw diff --git a/scenes/xyhead_demo.yaml b/scenes/xyhead_demo.yaml index 121a1a527..c6d97477a 100644 --- a/scenes/xyhead_demo.yaml +++ b/scenes/xyhead_demo.yaml @@ -2,8 +2,8 @@ vehicle_state: [4.0, 5.0, 0.0, 0.0, 0.0] agents: ped1: type: pedestrian - position: [20.0, 2.0] + position: [15.0, 2.0] nominal_velocity: 0.5 - target: [20.0,10.0] + target: [15.0,10.0] behavior: loop \ No newline at end of file From 7e2ad0738a8fd22b912a423dd06fa64150a07f4b Mon Sep 17 00:00:00 2001 From: krishauser Date: Sat, 10 Feb 2024 22:21:00 -0500 Subject: [PATCH 107/232] Added reference speed argument --- GEMstack/onboard/planning/motion_planning.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/GEMstack/onboard/planning/motion_planning.py b/GEMstack/onboard/planning/motion_planning.py index 7dfd53c03..f0507d36c 100644 --- a/GEMstack/onboard/planning/motion_planning.py +++ b/GEMstack/onboard/planning/motion_planning.py @@ -5,8 +5,8 @@ class RouteToTrajectoryPlanner(Component): """Copies the route directly into the trajectory.""" - def __init__(self): - pass + def __init__(self, reference_speed = 1.0): + self.reference_speed = reference_speed def state_inputs(self): return ['all'] @@ -18,5 +18,5 @@ def rate(self): return 10.0 def update(self, state : AllState): - return state.route.arc_length_parameterize() + return state.route.arc_length_parameterize(self.reference_speed) \ No newline at end of file From eb89d98f3ab5a1adb3cb09cce6ba57654f90446e Mon Sep 17 00:00:00 2001 From: krishauser Date: Sat, 10 Feb 2024 22:23:40 -0500 Subject: [PATCH 108/232] Moved zed and lidar configuration to separate files. Tuned PID constants --- GEMstack/knowledge/calibration/gem_e2.yaml | 6 ++++-- GEMstack/knowledge/calibration/gem_e2_velodyne.yaml | 3 +++ GEMstack/knowledge/calibration/gem_e2_zed.yaml | 4 ++++ GEMstack/knowledge/defaults/current.yaml | 4 ++-- GEMstack/knowledge/vehicle/gem_e2_dynamics.yaml | 2 +- 5 files changed, 14 insertions(+), 5 deletions(-) create mode 100644 GEMstack/knowledge/calibration/gem_e2_velodyne.yaml create mode 100644 GEMstack/knowledge/calibration/gem_e2_zed.yaml diff --git a/GEMstack/knowledge/calibration/gem_e2.yaml b/GEMstack/knowledge/calibration/gem_e2.yaml index 9cfdaf5f3..136627af8 100644 --- a/GEMstack/knowledge/calibration/gem_e2.yaml +++ b/GEMstack/knowledge/calibration/gem_e2.yaml @@ -1,6 +1,8 @@ calibration_date: "2023-08-31" # Date of calibration YYYY-MM-DD -reference: rear_axle_center # ground point below rear axle center +reference: rear_axle_center # rear axle center +rear_axle_height: 0.273 # height of rear axle center above flat ground gnss_location: [1.1,0.0,0.3] # meters, taken from https://github.com/hangcui1201/POLARIS_GEM_e2_Real/blob/main/vehicle_drivers/gem_gnss_control/scripts/gem_gnss_tracker_stanley_rtk.py. Note conflict with pure pursuit location? gnss_yaw: 0.0 # radians front_radar_location: [1.45,0,0.07] # meters, taken from https://github.com/hangcui1201/POLARIS_GEM_e2_Real/blob/main/platform_launch/launch/white_e2/platform.launch -top_lidar_location: [-0.12,0,1.6] # meters, taken from https://github.com/hangcui1201/POLARIS_GEM_e2_Real/blob/main/platform_launch/launch/white_e2/platform.launch +top_lidar: !include "gem_e2_velodyne.yaml" +front_camera: !include "gem_e2_zed.yaml" diff --git a/GEMstack/knowledge/calibration/gem_e2_velodyne.yaml b/GEMstack/knowledge/calibration/gem_e2_velodyne.yaml new file mode 100644 index 000000000..a13d93c4a --- /dev/null +++ b/GEMstack/knowledge/calibration/gem_e2_velodyne.yaml @@ -0,0 +1,3 @@ +reference: rear_axle_center # rear axle center +position: [-0.12,0,1.6] # meters, taken from https://github.com/hangcui1201/POLARIS_GEM_e2_Real/blob/main/platform_launch/launch/white_e2/platform.launch (almost certainly wrong) +rotation: [[1,0,0],[0,1,0],[0,0,1]] #rotation matrix mapping lidar frame to vehicle frame \ No newline at end of file diff --git a/GEMstack/knowledge/calibration/gem_e2_zed.yaml b/GEMstack/knowledge/calibration/gem_e2_zed.yaml new file mode 100644 index 000000000..f83307b4f --- /dev/null +++ b/GEMstack/knowledge/calibration/gem_e2_zed.yaml @@ -0,0 +1,4 @@ +reference: rear_axle_center # rear axle center +rotation: [[0,0,1],[-1,0,0],[0,-1,0]] # rotation matrix mapping z to forward, x to left, y to down, guesstimated +center_position: [-0.02,0,1.5] # meters, center of Zed camera, guesstimated +rgb_position: [-0.02,0.06,1.5] # meters, center of color (left) camera, guesstimated diff --git a/GEMstack/knowledge/defaults/current.yaml b/GEMstack/knowledge/defaults/current.yaml index 533c56b14..e043a2d00 100644 --- a/GEMstack/knowledge/defaults/current.yaml +++ b/GEMstack/knowledge/defaults/current.yaml @@ -26,10 +26,10 @@ control: pure_pursuit: lookahead: 2.0 lookahead_scale: 3.0 - crosstrack_gain: 2.0 + crosstrack_gain: 1.0 desired_speed: 2.0 #m/s longitudinal_control: - pid_p: 3.0 + pid_p: 1.0 pid_i: 0.1 pid_d: 0.0 diff --git a/GEMstack/knowledge/vehicle/gem_e2_dynamics.yaml b/GEMstack/knowledge/vehicle/gem_e2_dynamics.yaml index dfff67b00..4a6cd5c21 100644 --- a/GEMstack/knowledge/vehicle/gem_e2_dynamics.yaml +++ b/GEMstack/knowledge/vehicle/gem_e2_dynamics.yaml @@ -12,7 +12,7 @@ max_accelerator_power: #Watts. Power at max accelerator pedal, by gear - 10000.0 max_accelerator_power_reverse: 10000.0 #Watts. Power (backwards) in reverse gear -acceleration_model : hang_v1 +acceleration_model : kris_v1 accelerator_active_range : [0.32, 1.0] #range of accelerator pedal where output acceleration is not flat brake_active_range : [0,1] #range of brake pedal where output deceleration is not flat From f73a607010b8e0d96cf5227005b4ed07b888aba7 Mon Sep 17 00:00:00 2001 From: krishauser Date: Sun, 11 Feb 2024 16:45:36 -0500 Subject: [PATCH 109/232] Updated args for more demos on how to run the computation graph --- README.md | 78 +++++++++++++++++++++++++++++++++-------- launch/fixed_route.yaml | 11 ++++-- 2 files changed, 73 insertions(+), 16 deletions(-) diff --git a/README.md b/README.md index 45f2bfee7..51f26e290 100644 --- a/README.md +++ b/README.md @@ -60,7 +60,7 @@ In addition, some tools (e.g., pip) will build temporary folders, such as `build ## Package structure -All packages are within the `GEMstack/` folder. +All algorithms and routines in the package, i.e., those that would be run onboard, are within the `GEMstack/` folder. Legend: - 🟥: TODO @@ -70,22 +70,27 @@ Legend: - 🟦: mature `mathutils/`: 🧮 Math utilities common to onboard / offboard use. - - 🟩 `transforms`: 2d and 3d rotations and rigid transforms. - - 🟩 `filters`: 1d signal processing. - 🟥 `cameras`: Contains standard camera models. + - 🟨 `collisions`: Provides collision detection and proximity detection. + - 🟩 `control`: Contains standard control techniques, e.g., PID controller. - 🟦 `differences`: Finite differences for derivative approximation. - - 🟦 `dynamics`: Contains standard dynamics models. - 🟦 `dubins`: Contains first- and second-order Dubins car dynamics models. - - 🟩 `control`: Contains standard control techniques, e.g., PID controller. - - 🟨 `collisions`: Provides collision detection and proximity detection. + - 🟦 `dynamics`: Contains standard dynamics models. + - 🟨 `intelligent_driver_model`: the IDM model used for adaptive cruise control behavior. + - 🟩 `signal`: 1d signal processing. + - 🟩 `transforms`: 2d and 3d rotations and rigid transforms. + - 🟨 `units`: constants to help with unit conversion. `utils/`: 🛠️ Other utilities common to onboard / offboard use. - 🟩 `logging`: Provides logging and log replay functionality. - 🟨 `mpl_visualization`: Tools for plotting data on knowledge, state, etc. in Matplotlib. + - 🟨 `klampt_visualization`: Tools for plotting data on knowledge, state, etc. in Klampt. - 🟥 `gazebo_visualization`: Tools for converting data on knowledge, state, etc. to ROS messages used in Gazebo. - 🟦 `settings`: Tools for managing settings for onboard behaviour. If you're tempted to write a magic parameter or global variable, it should be [placed in settings instead](#settings). - 🟦 `config`: Tools for loading config files. + - 🟩 `conversions`: Tools for converting objects to and from standard Python objects, ROS messages, etc. - 🟦 `serialization`: Tools for serializing / deserializing objects. + - 🟩 `logging`: Tools for logging data streams of serializable objects. - 🟦 `loops`: Tools for writing timed loops. `state/`: 💾 Representations of state of the vehicle and its environment, including internal state that persists from step to step. @@ -115,7 +120,7 @@ Legend: - 🟥 `heuristic_learning/`: Driving heuristic learning. `knowledge/`: 🧠 Models and parameters common to onboard / offboard use. The file "current.py" in each directory will store the current model being used. - - 🟨 `vehicle/`: Vehicle geometry and physics. (needs testing) + - 🟨 `vehicle/`: Vehicle geometry and physics. (needs calibration and testing) - 🟨 `calibration/`: Calibrated sensor parameters. - 🟥 `detection/`: Stores detection models. - 🟥 `prediction/`: Stores prediction models. @@ -140,28 +145,30 @@ Legend: - 🟥 `agent_prediction`: Agent motion prediction. - `planning/`: Planning components. - - 🟨 `route_planner`: Decides which route to drive from the roadgraph. + - 🟩 `route_planning`: Decides which route to drive from the roadgraph. - 🟥 `driving_logic`: Performs all necessary logic to develop a planning problem specification, e.g., select obstacles, design cost functions, etc. - 🟥 `heuristics`: Implements various planning heuristics. - 🟥 `motion_planning`: Implements one or more motion planners. - 🟥 `optimization`: Implements one or more trajectory optimizers. - 🟥 `selection`: Implements best-trajectory selection. - - 🟨 `pure_pursuit`: Implements a pure pursuit controller. - - 🟨 `recovery`: Implements recovery behavior. + - 🟨 `pure_pursuit`: Implements a pure pursuit controller. Needs some tuning. + - 🟩 `recovery`: Implements standard recovery behavior. - `execution/`: Executes the onboard driving behavior. - 🟩 `entrypoint`: The entrypoint that launches all onboard behavior. Configured by settings in 'run'. - 🟩 `executor`: Base classes for executors. - - 🟩 `log_replay`: A generic component that replays from a log. + - 🟩 `logging`: A manager to log components / replay messages from a log. - 🟨 `multiprocess_execution`: Component executors that work in separate process. (Stdout logging not done yet. Still hangs on exception.) - `visualization/`: Visualization components on-board the vehicle - 🟨 `mpl_visualization`: Matplotlib visualization + - 🟩 `klampt_visualization`: Klampt visualization - `interface/`: Defines interfaces to vehicle hardware and simulators. - 🟩 `gem`: Base class for the Polaris GEM e2 vehicle. - - 🟨 `gem_hardware`: Interface to the real GEM vehicle. - - 🟨 `gem_simulator`: Interfaces to simulated GEM vehicles. + - 🟩 `gem_hardware`: Interface to the real GEM vehicle. + - 🟩 `gem_simulator`: Interfaces to simulated GEM vehicles. + - 🟩 `gem_mixed`: Interfaces to the real GEM e2 vehicle's sensors but simulated motion. ## Launching the stack @@ -266,12 +273,55 @@ for every 1/component.rate() seconds, and while still active: component.cleanup() ``` +### Creating the computation graph and customizing your component in a launch file + The computation graph defines an execution order of components and a set of allowable inputs and outputs for each component. This structure is defined in the `run.computation_graph` setting and by default uses `GEMstack/knowledge/defaults/computation_graph.yaml`. -You should think of `AllState` as a strictly typed blackboard architecture in which items can be read from and written to. If you need to pass data between components, you should add it to the state rather than use alternative techniques, e.g., global variables. This will allow the logging / replay to save and restore system state. Over a long development period, it would be best to be disciplined at versioning. +In a launch file, you can specify a component by name, i.e., + +```yaml +drive: + planning: + motion_planner: MyMotionPlanner +``` + +which will look for the `MyMotionPlanner` class in the `GEMstack/onboard/planning/motion_planner.py` file. You can also specify `module.Class`, i.e., + +```yaml +drive: + planning: + motion_planner: my_motion_planner.MyMotionPlanner +``` + +which will look in the `GEMstack/onboard/planning/my_motion_planner.py` file. + +You can modify how the component is constructed and run by specifying a dictionary. The valid values of this dictionary are as follows: + +```yaml +drive: + planning: + motion_planner: + type: my_motion_planner.MyMotionPlanner + args: #specify a dict, or you can just specify a list of arguments, i.e., [3.0] + some_argument: 3.0 + rate: 10.0 #overrides MyMotionPlanner.rate() to run at 10Hz + print: True #whether to include print output (default True) + debug: True #whether to save debug output (default True) + multiprocess: False #whether to use multiprocessing (default False). Multiprocessing makes the stack run faster, but logging is not yet mature. +``` + +### Variants + +A launch file can contain a `variants` key that may specify certain changes to the launch stack that may be named via `--variant=X` on the command line. As an example, see `launch/fixed_route.yaml`. This specifies two variants, `sim` and `log_ros` which would run a simulation or log ROS topics. You can specify multiple variants on the command line using the format `--variant=X,Y`. + +### Managing and modifying state + +When implementing your computation graph, you should think of `AllState` as a strictly typed blackboard architecture in which items can be read from and written to. If you need to pass data between components, you should add it to the state rather than use alternative techniques, e.g., global variables. This will allow the logging / replay to save and restore system state. Over a long development period, it would be best to be disciplined at versioning. It is generally assumed that components will not maintain significant internal state. If you implement a component that does update internal state, then the executor will not be able to reproduce prior behavior from logs. This causes headaches with replay tools and A/B testing. +### New pipelines + If you wish to override the executor to add more pipelines, you will need to create a new executor by subclassing from `ExecutorBase`. This will need to implement the pipeline switching and termination logic as detailed in the `begin`, `update`, `done`, and `end` callbacks. diff --git a/launch/fixed_route.yaml b/launch/fixed_route.yaml index 3d71b5c66..3f31e41a3 100644 --- a/launch/fixed_route.yaml +++ b/launch/fixed_route.yaml @@ -5,7 +5,9 @@ mission_execution: StandardExecutor # Recovery behavior after a component failure recovery: planning: - trajectory_tracking : recovery.StopTrajectoryTracker + trajectory_tracking: + type: recovery.StopTrajectoryTracker + print: False # Driving behavior for the GEM vehicle following a fixed route drive: perception: @@ -15,7 +17,9 @@ drive: route_planning: type: StaticRoutePlanner args: [!relative_path '../GEMstack/knowledge/routes/xyhead_highbay_backlot_p.csv'] - motion_planning: RouteToTrajectoryPlanner + motion_planning: + type: RouteToTrajectoryPlanner + args: [null] #desired speed in m/s. If null, this will keep the route untimed for the trajectory tracker trajectory_tracking: type: pure_pursuit.PurePursuitTrajectoryTracker print: False @@ -48,6 +52,9 @@ replay: # Add items here to set certain topics / inputs to be replayed from log #usually can keep this constant computation_graph: !include "../GEMstack/knowledge/defaults/computation_graph.yaml" +after: + show_log_folder: True #set to false to avoid showing the log folder + #on load, variants will overload the settings structure variants: #sim variant doesn't execute on the real vehicle From cbe4bbe340618f3c31a1ccac31398aa86e0c7b0c Mon Sep 17 00:00:00 2001 From: krishauser Date: Sun, 11 Feb 2024 16:46:32 -0500 Subject: [PATCH 110/232] Added debug functionality --- GEMstack/onboard/component.py | 8 + GEMstack/onboard/execution/entrypoint.py | 6 +- GEMstack/onboard/execution/execution.py | 266 ++++++++++-------- GEMstack/onboard/execution/logging.py | 110 +++++++- .../execution/multiprocess_execution.py | 3 - 5 files changed, 264 insertions(+), 129 deletions(-) diff --git a/GEMstack/onboard/component.py b/GEMstack/onboard/component.py index da6a8e11c..d26d2c779 100644 --- a/GEMstack/onboard/component.py +++ b/GEMstack/onboard/component.py @@ -25,3 +25,11 @@ def cleanup(self): def update(self, *args, **kwargs): """Update the component.""" raise NotImplementedError() + def debug(self, item, value): + """Debugs a streaming value within this component""" + if hasattr(self, 'debugger'): + self.debugger.debug(item, value) + def debug_event(self, label): + """Debugs an event within this component""" + if hasattr(self, 'debugger'): + self.debugger.debug_event(label) \ No newline at end of file diff --git a/GEMstack/onboard/execution/entrypoint.py b/GEMstack/onboard/execution/entrypoint.py index 3656eeff1..096c0c144 100644 --- a/GEMstack/onboard/execution/entrypoint.py +++ b/GEMstack/onboard/execution/entrypoint.py @@ -157,4 +157,8 @@ def caution_callback(k,variant): if has_ros: #need manual ros node shutdown due to disable_signals=True rospy.signal_shutdown('GEM_executor finished') - + + print(EXECUTION_PREFIX,"---------------- DONE ----------------") + if log_settings and settings.get('run.after.show_log_folder',True): + import webbrowser + webbrowser.open(logfolder) diff --git a/GEMstack/onboard/execution/execution.py b/GEMstack/onboard/execution/execution.py index 81d8f86e5..409b6088e 100644 --- a/GEMstack/onboard/execution/execution.py +++ b/GEMstack/onboard/execution/execution.py @@ -22,6 +22,32 @@ COMPONENT_ORDER = None COMPONENT_SETTINGS = None +LOGGING_MANAGER = None # type: LoggingManager + +def executor_debug_print(verbosity : int, format : str, *args): + """Top level prints. Will be printed to stdout and logged.""" + if EXECUTION_VERBOSITY >= verbosity: + s = format.format(*args) + print(EXECUTION_PREFIX,s) + if LOGGING_MANAGER is not None: + LOGGING_MANAGER.log_component_stdout('Executor',s.split('\n')) + +def executor_debug_stderr(format : str, *args): + """Top level stderr prints. Will be printed to stderr and logged.""" + s = format.format(*args) + print(EXECUTION_PREFIX,s,file=sys.stderr) + if LOGGING_MANAGER is not None: + LOGGING_MANAGER.log_component_stderr('Executor',s.split('\n')) + +def executor_debug_exception(e : Exception, format: str, *args): + """Top level exceptions. Will be printed to stderr and logged.""" + executor_debug_stderr(format,*args) + import traceback + executor_debug_stderr(traceback.format_exc()) + executor_debug_print(0,format,*args) + executor_debug_print(0,traceback.format_exc()) + + def normalize_computation_graph(components : list) -> List[Dict]: normalized_components = [] for c in components: @@ -100,9 +126,9 @@ def make_class(config_info, component_module, parent_module=None, extra_args = N kwargs = args args = () if parent_module is not None: - print(EXECUTION_PREFIX,"Importing",component_module,"from",parent_module,"to get",class_name) + executor_debug_print(0,"Importing {} from {} to get {}",component_module,parent_module,class_name) else: - print(EXECUTION_PREFIX,"Importing",component_module,"to get",class_name) + executor_debug_print(0,"Importing {} to get {}",component_module,class_name) module = import_module_dynamic(component_module,parent_module) klass = getattr(module,class_name) try: @@ -111,7 +137,7 @@ def make_class(config_info, component_module, parent_module=None, extra_args = N try: return klass(*args,**kwargs) except TypeError: - print(EXECUTION_PREFIX,"Unable to launch module",component_module,"with class",class_name,"and args",args,"kwargs",kwargs) + executor_debug_print(0,"Unable to launch module {} with class {} and args {} kwargs {}",component_module,class_name,args,kwargs) raise @@ -137,7 +163,7 @@ def validate_components(components : Dict[str,ComponentExecutor], provided : Lis else: assert provided_all or i in provided, "Component {} input {} is not provided by previous components".format(k,i) if i not in state: - print(EXECUTION_PREFIX,"Component {} input {} does not exist in AllState object".format(k,i)) + executor_debug_print("Component {} input {} does not exist in AllState object",k,i) if possible_inputs != ['all']: assert i in possible_inputs, "Component {} is not supposed to receive input {}".format(k,i) outputs = c.c.state_outputs() @@ -150,24 +176,55 @@ def validate_components(components : Dict[str,ComponentExecutor], provided : Lis if 'all' != o: provided.add(o) if o not in state: - print(EXECUTION_PREFIX,"Component {} output {} does not exist in AllState object".format(k,o)) + executor_debug_print("Component {} output {} does not exist in AllState object",k,o) else: provided_all = True for k,c in components.items(): - print(k,c.c.__class__.__name__) + executor_debug_print(0,"Component {} uses implementation {}",k,c.c.__class__.__name__) assert k in COMPONENT_SETTINGS, "Component {} is not known".format(k) return list(provided) +class Debugger: + """A simple debugging interface that allows components + to send debug messages to visualizations and loggers.""" + def __init__(self): + self.handlers = [] # type: List[Debugger] + + def add_handler(self, handler : Debugger): + self.handlers.append(handler) + + def debug(self, source : str, item : str, value): + for h in self.handlers: + h.debug(source, item, value) + + def debug_event(self, source : str, label : str): + for h in self.handlers: + h.debug_event(source, label) + + +class ChildDebugger: + def __init__(self, parent : Debugger, source : str): + self.parent = parent + self.source = source + + def debug(self, item : str, value): + self.parent.debug(self.source, item, value) + + def debug_event(self, label : str): + self.parent.debug_event(self.source, label) + + + class ComponentExecutor: """Polls for whether a component should be updated, and reads/writes inputs / outputs to the AllState object.""" - def __init__(self,c : Component, essential : bool = True): + def __init__(self, c : Component, essential : bool = True): self.c = c self.essential = essential + self.do_debug = True self.print_stdout = True self.print_stderr = False - self.logging_manager = None # Optional[LoggingManager] self.inputs = c.state_inputs() self.output = c.state_outputs() self.last_update_time = None @@ -179,6 +236,10 @@ def __init__(self,c : Component, essential : bool = True): self.overrun_amount = 0.0 self.do_update = None + def set_debugger(self, debugger): + if self.do_debug: + self.c.debugger = ChildDebugger(debugger, self.c.__class__.__name__) + def healthy(self): return self.c.healthy() and not self.had_exception @@ -197,14 +258,12 @@ def update(self, t : float, state : AllState): else: self.next_update_time += self.dt if self.next_update_time < t and self.dt > 0: - if EXECUTION_VERBOSITY >= 1: - print(EXECUTION_PREFIX,"Component {} is running behind, overran dt {} by {} seconds".format(self.c.__class__.__name__,self.dt,t-self.next_update_time)) + executor_debug_print(1,"Component {} is running behind, overran dt {} by {} seconds",self.c.__class__.__name__,self.dt,t-self.next_update_time) self.num_overruns += 1 self.overrun_amount += t - self.next_update_time self.next_update_time = t + self.dt return True - if EXECUTION_VERBOSITY >= 3: - print(EXECUTION_PREFIX,"Component",self.c.__class__.__name__,"not updating at time",t,", next update time is",self.next_update_time) + executor_debug_print(3,"Component {}","not updating at time {}, next update time is {}",self.c.__class__.__name__,t,self.next_update_time) return False def _do_update(self, t:float, *args): @@ -218,13 +277,10 @@ def _do_update(self, t:float, *args): else: res = self.c.update(*args) except Exception as e: - print(EXECUTION_PREFIX,"Exception in component",self.c.__class__.__name__,":",e) - import traceback - print(traceback.format_exc(),file=sys.stderr) - print(traceback.format_exc(),file=sys.stdout) + executor_debug_exception(e,"Exception in component {}: {}",self.c.__class__.__name__,e) self.had_exception = True res = None - self.log_output(t, f.getvalue(),g.getvalue()) + self.log_output(f.getvalue(),g.getvalue()) return res def update_now(self, t:float, state : AllState): @@ -233,8 +289,7 @@ def update_now(self, t:float, state : AllState): args = (state,) else: args = tuple([getattr(state,i) for i in self.inputs]) - if EXECUTION_VERBOSITY >= 2: - print(EXECUTION_PREFIX,"Updating",self.c.__class__.__name__) + executor_debug_print(2,"Updating {}",self.c.__class__.__name__) #capture stdout/stderr res = self._do_update(t, *args) @@ -249,7 +304,7 @@ def update_now(self, t:float, state : AllState): setattr(state,self.output[0], res) setattr(state,self.output[0]+'_update_time', t) - def log_output(self,t,stdout,stderr): + def log_output(self,stdout,stderr): if stdout: lines = stdout.split('\n') if len(lines) > 0 and len(lines[-1])==0: @@ -259,8 +314,8 @@ def log_output(self,t,stdout,stderr): for l in lines: print(" ",l) print("-------------------------------------------") - if self.logging_manager is not None: - self.logging_manager.log_component_stdout(self.c.__class__.__name__, t, lines) + if LOGGING_MANAGER is not None: + LOGGING_MANAGER.log_component_stdout(self.c.__class__.__name__, lines) if stderr: lines = stderr.split('\n') if len(lines) > 0 and len(lines[-1])==0: @@ -270,8 +325,8 @@ def log_output(self,t,stdout,stderr): for l in lines: print(" ",l) print("-------------------------------------------") - if self.logging_manager is not None: - self.logging_manager.log_component_stderr(self.c.__class__.__name__, t, lines) + if LOGGING_MANAGER is not None: + LOGGING_MANAGER.log_component_stderr(self.c.__class__.__name__, lines) @@ -287,6 +342,8 @@ def __init__(self, vehicle_interface): self.current_pipeline = 'drive' # type: str self.state = None # type: Optional[AllState] self.logging_manager = LoggingManager() + self.debugger = Debugger() + self.debugger.add_handler(self.logging_manager) self.last_loop_time = time.time() self.last_hardware_faults = set() @@ -323,15 +380,13 @@ def make_component(self, config_info, component_name, parent_module=None, extra_ try: component = make_class(config_info,component_name,parent_module,extra_args) except Exception as e: - print("Exception raised while tryign to make component {} from config info:".format(component_name)) - print(" ",config_info) + executor_debug_exception(e,"Exception raised while trying to make component {} from config info:\n {}",component_name,config_info) raise if not isinstance(component,Component): raise RuntimeError("Component {} is not a subclass of Component".format(component_name)) replacement = self.logging_manager.component_replayer(component_name, component) if replacement is not None: - if EXECUTION_VERBOSITY >= 1: - print(EXECUTION_PREFIX,"Replaying component",component_name,"from log",replacement.logfn,"with outputs",component.state_outputs()) + executor_debug_print(1,"Replaying component {} from long {} with outputs {}",component_name,replacement.logfn,component.state_outputs()) component = replacement if isinstance(config_info,dict) and config_info.get('multiprocess',False): #wrap component in a multiprocess executor. TODO: not tested yet @@ -344,7 +399,8 @@ def make_component(self, config_info, component_name, parent_module=None, extra_ if 'rate' in config_info: executor.dt = 1.0/config_info['rate'] executor.print_stderr = executor.print_stdout = config_info.get('print',True) - executor.logging_manager = self.logging_manager + executor.do_debug = config_info.get('debug',True) + executor.set_debugger(self.debugger) self.all_components[identifier] = executor return executor @@ -385,7 +441,7 @@ def log_ros_topics(self, topics : List[str], rosbag_options : str = '') -> Optio """Indicates that the designated ros topics should be logged with the given options.""" command = self.logging_manager.log_ros_topics(topics,rosbag_options) if command: - print(EXECUTION_PREFIX,"Recording ROS topics with command",command) + executor_debug_print(0,"Recording ROS topics with command {}",command) def replay_components(self, replayed_components : list, replay_folder : str): """Declare that the given components should be replayed from a log folder. @@ -397,11 +453,11 @@ def replay_components(self, replayed_components : list, replay_folder : str): def event(self,event_description : str, event_print_string : str = None): """Logs an event to the metadata and prints a message to the console.""" - self.logging_manager.event(self.state.t,event_description) + self.logging_manager.event(event_description) if EXECUTION_VERBOSITY >= 1: if event_print_string is None: event_print_string = event_description if event_description.endswith('.') else event_description + '.' - print(EXECUTION_PREFIX,event_print_string) + executor_debug_print(1,event_print_string) def set_exit_reason(self, description): """Sets a main loop exit reason""" @@ -409,13 +465,16 @@ def set_exit_reason(self, description): def run(self): """Main entry point. Runs the mission execution loop.""" + global LOGGING_MANAGER + LOGGING_MANAGER = self.logging_manager #kludge! should refactor to avoid global variables + #sanity checking if self.current_pipeline not in self.pipelines: - print(EXECUTION_PREFIX,"Initial pipeline {} not found".format(self.current_pipeline)) + executor_debug_print(0,"Initial pipeline {} not found",self.current_pipeline) return #must have recovery pipeline if 'recovery' not in self.pipelines: - print(EXECUTION_PREFIX,"'recovery' pipeline not found") + executor_debug_print(0,"'recovery' pipeline not found") return #did we ask to replay any components that don't exist in any pipelines? for c in self.logging_manager.replayed_components.keys(): @@ -445,66 +504,59 @@ def run(self): self.event("Ctrl+C interrupt during sensor validation","Could not validate sensors, stopping components and exiting") self.set_exit_reason("Sensor validation failed") if time.time() - self.last_loop_time > 0.5: - print(EXECUTION_PREFIX,"A component may have hung. Traceback:") import traceback - traceback.print_exc() + executor_debug_print(1,"A component may have hung. Traceback:\n{}",traceback.format_exc()) if validated: self.begin() - while validated: - self.logging_manager.pipeline_start_event(self.state.t,self.current_pipeline) - try: - if EXECUTION_VERBOSITY >= 1: - print(EXECUTION_PREFIX,"Executing pipeline {}".format(self.current_pipeline)) - next = self.run_until_switch() - if next is None: - #done - self.set_exit_reason("normal exit") - break - if next not in self.pipelines: - if EXECUTION_VERBOSITY >= 1: - print(EXECUTION_PREFIX,"Pipeline {} not found, switching to recovery".format(next)) - next = 'recovery' - if self.current_pipeline == 'recovery' and next == 'recovery': - if EXECUTION_VERBOSITY >= 1: - print(EXECUTION_PREFIX) - print("************************************************") - print(" Recovery pipeline is not working, exiting! ") - print("************************************************") - self.set_exit_reason("recovery pipeline not working") - break - self.current_pipeline = next - if not self.validate_sensors(1): - self.event("Sensors in desired pipeline {} are not working, switching to recovery".format(self.current_pipeline)) + while True: + self.state.t = self.vehicle_interface.time() + self.logging_manager.pipeline_start_event(self.current_pipeline) + try: + executor_debug_print(1,"Executing pipeline {}",self.current_pipeline) + next = self.run_until_switch() + if next is None: + #done + self.set_exit_reason("normal exit") + break + if next not in self.pipelines: + executor_debug_print(1,"Pipeline {} not found, switching to recovery",next) + next = 'recovery' + if self.current_pipeline == 'recovery' and next == 'recovery': + executor_debug_print(1,"\ + ************************************************\ + Recovery pipeline is not working, exiting! \ + ************************************************") + self.set_exit_reason("recovery pipeline not working") + break + self.current_pipeline = next + if not self.validate_sensors(1): + self.event("Sensors in desired pipeline {} are not working, switching to recovery".format(self.current_pipeline)) + self.current_pipeline = 'recovery' + except KeyboardInterrupt: + if self.current_pipeline == 'recovery': + executor_debug_print(1,"\ + ************************************************\ + Ctrl+C interrupt during recovery, exiting! \ + ************************************************") + self.set_exit_reason("Ctrl+C interrupt during recovery") + break self.current_pipeline = 'recovery' - except KeyboardInterrupt: - if self.current_pipeline == 'recovery': - if EXECUTION_VERBOSITY >= 1: - print(EXECUTION_PREFIX) - print("************************************************") - print(" Ctrl+C interrupt during recovery, exiting! ") - print("************************************************") - self.set_exit_reason("Ctrl+C interrupt during recovery") - break - self.current_pipeline = 'recovery' - self.event("Ctrl+C pressed, switching to recovery mode") - if time.time() - self.last_loop_time > 0.5: - if EXECUTION_VERBOSITY >= 1: - print(EXECUTION_PREFIX,"A component may have hung. Traceback:") - import traceback - traceback.print_exc() - if validated: + self.event("Ctrl+C pressed, switching to recovery mode") + if time.time() - self.last_loop_time > 0.5: + import traceback + executor_debug_print(1,"A component may have hung. Traceback:\n{}",traceback.format_exc()) self.end() #done with mission self.event("Mission execution ended","Done with mission execution, stopping components and exiting") + #cleanup, whether validated or not for k,c in self.all_components.items(): - if EXECUTION_VERBOSITY >= 2: - print("Stopping",k) + executor_debug_print(2,"Stopping",k) c.stop() self.logging_manager.close() - print("Done with execution loop") + executor_debug_print(0,"Done with execution loop") def check_for_hardware_faults(self): """Handles vehicle fault checking / logging""" @@ -526,14 +578,10 @@ def check_for_hardware_faults(self): printed_faults.append(f) if printed_faults: if EXECUTION_VERBOSITY >= 1: - print(EXECUTION_PREFIX,"Hardware faults:") - for f in printed_faults: - if f in new_faults: - print(" ",f,"(new)") - else: - print(" ",f) + fault_strings = [(f + " (new)" if f in new_faults else f) for f in printed_faults] + executor_debug_print(1,"Hardware faults:",'\n '.join(fault_strings)) elif new_faults: - print(EXECUTION_PREFIX,"Hardware fault:",", ".join(new_faults)) + executor_debug_print(0,"Hardware fault:",", ".join(new_faults)) self.last_hardware_faults = set(faults) @@ -551,6 +599,7 @@ def validate_sensors(self,numsteps=None): next_print_time = t0 + 1.0 while looper and not sensors_working: self.state.t = self.vehicle_interface.time() + self.logging_manager.set_vehicle_time(self.state.t) self.last_loop_time = time.time() #check for vehicle faults @@ -562,15 +611,13 @@ def validate_sensors(self,numsteps=None): self.update_components(self.always_run_components,self.state,force=True) always_run_working = all([c.healthy() for c in self.always_run_components.values()]) if not always_run_working: - if EXECUTION_VERBOSITY >= 1: - print(EXECUTION_PREFIX,"Always-run components not working, ignoring") + executor_debug_print(1,"Always-run components not working, ignoring") num_attempts += 1 if numsteps is not None and num_attempts >= numsteps: return False if time.time() > next_print_time: - if EXECUTION_VERBOSITY >= 1: - print(EXECUTION_PREFIX,"Waiting for sensors to be healthy...") + executor_debug_print(1,"Waiting for sensors to be healthy...") next_print_time += 1.0 return True @@ -585,6 +632,7 @@ def run_until_switch(self): looper = TimedLooper(dt_min,name="main executor") while looper and not self.done(): self.state.t = self.vehicle_interface.time() + self.logging_manager.set_vehicle_time(self.state.t) self.last_loop_time = time.time() #check for vehicle faults @@ -595,16 +643,14 @@ def run_until_switch(self): for name,c in perception_components.items(): if not c.healthy(): if c.essential and self.current_pipeline != 'recovery': - if EXECUTION_VERBOSITY >= 1: - print(EXECUTION_PREFIX,"Sensor %s not working, entering recovery mode"%(name,)) + executor_debug_print(1,"Sensor {} not working, entering recovery mode",name) return 'recovery' else: - if EXECUTION_VERBOSITY >= 1: - print(EXECUTION_PREFIX,"Warning, sensor %s not working, ignoring"%(name,)) + executor_debug_print(1,"Warning, sensor {} not working, ignoring",name) next_pipeline = self.update(self.state) if next_pipeline is not None and next_pipeline != self.current_pipeline: - print(EXECUTION_PREFIX,"update() requests to switch to pipeline {}".format(next_pipeline)) + executor_debug_print(0,"update() requests to switch to pipeline {}",next_pipeline) return next_pipeline self.update_components(planning_components,self.state) @@ -612,34 +658,28 @@ def run_until_switch(self): for name,c in planning_components.items(): if not c.healthy(): if c.essential and self.current_pipeline != 'recovery': - if EXECUTION_VERBOSITY >= 1: - print(EXECUTION_PREFIX,"Planner %s not working, entering recovery mode"%(name,)) + executor_debug_print(1,"Planner {} not working, entering recovery mode",name) return 'recovery' else: - if EXECUTION_VERBOSITY >= 1: - print(EXECUTION_PREFIX,"Warning, planner %s not working, ignoring"%(name,)) + executor_debug_print(1,"Warning, planner {} not working, ignoring",name) self.update_components(other_components,self.state) for name,c in other_components.items(): if not c.healthy(): if c.essential and self.current_pipeline != 'recovery': - if EXECUTION_VERBOSITY >= 1: - print(EXECUTION_PREFIX,"Other component %s not working, entering recovery mode"%(name,)) + executor_debug_print(1,"Other component {} not working, entering recovery mode",name) return 'recovery' else: - if EXECUTION_VERBOSITY >= 1: - print(EXECUTION_PREFIX,"Warning, other component %s not working"%(name,)) + executor_debug_print(1,"Warning, other component {} not working",name) self.update_components(self.always_run_components,self.state,force=True) for name,c in self.always_run_components.items(): if not c.healthy(): if c.essential and self.current_pipeline != 'recovery': - if EXECUTION_VERBOSITY >= 1: - print(EXECUTION_PREFIX,"Always-run component %s not working, entering recovery mode"%(name,)) + executor_debug_print(1,"Always-run component {} not working, entering recovery mode",name) return 'recovery' else: - if EXECUTION_VERBOSITY >= 1: - print(EXECUTION_PREFIX,"Warning, always-run component %s not working"%(name,)) + executor_debug_print(1,"Warning, always-run component {} not working",name) #self.done() returned True @@ -671,7 +711,7 @@ def update_components(self, components : Dict[str,ComponentExecutor], state : Al updated = components[k].update(t,state) #log component output if necessary if updated: - self.logging_manager.log_component_update(k, t, state, components[k].output) + self.logging_manager.log_component_update(k, state, components[k].output) class StandardExecutor(ExecutorBase): @@ -682,11 +722,9 @@ def done(self): if self.current_pipeline == 'recovery': if self.vehicle_interface.last_reading is not None and \ abs(self.vehicle_interface.last_reading.speed) < 1e-3: - if EXECUTION_VERBOSITY >= 1: - print(EXECUTION_PREFIX,"Vehicle has stopped, exiting execution loop.") + executor_debug_print(1,"Vehicle has stopped, exiting execution loop.") return True if 'disengaged' in self.vehicle_interface.hardware_faults(): - if EXECUTION_VERBOSITY >= 1: - print(EXECUTION_PREFIX,"Vehicle has disengaged, exiting execution loop.") + executor_debug_print(1,"Vehicle has disengaged, exiting execution loop.") return True return False diff --git a/GEMstack/onboard/execution/logging.py b/GEMstack/onboard/execution/logging.py index db5262010..31ebd962b 100644 --- a/GEMstack/onboard/execution/logging.py +++ b/GEMstack/onboard/execution/logging.py @@ -6,7 +6,8 @@ import datetime import os import subprocess -import io +import numpy as np +import cv2 class LoggingManager: """A top level manager of the logging process. This is responsible for @@ -23,6 +24,9 @@ def __init__(self): self.run_metadata['pipelines'] = [] self.run_metadata['events'] = [] self.run_metadata['exit_reason'] = 'unknown' + self.vehicle_time = None + self.start_vehicle_time = None + self.debug_messages = {} def logging(self) -> bool: return self.log_folder is not None @@ -132,14 +136,96 @@ def log_ros_topics(self, topics : List[str], rosbag_options : str = '') -> Optio return ' '.join(command) return None - def event(self, vehicle_time : float, event_description : str): + def set_vehicle_time(self, vehicle_time : float) -> None: + self.vehicle_time = vehicle_time + if self.start_vehicle_time is None: + self.start_vehicle_time = vehicle_time + + def event(self, event_description : str): """Logs an event to the metadata.""" - self.run_metadata['events'].append({'time':time.time(),'vehicle_time':vehicle_time,'description':event_description}) + self.run_metadata['events'].append({'time':time.time(),'vehicle_time':self.vehicle_time,'description':event_description}) self.dump_log_metadata() - def pipeline_start_event(self, vehicle_time : float, pipeline_name : str) -> None: + def debug(self, component : str, item : str, value : Any) -> None: + """Logs a debug message to the metadata to be saved as CSV.""" + if not self.log_folder: + return + if component not in self.debug_messages: + self.debug_messages[component] = {} + if isinstance(value,(list,tuple)): + for i,v in enumerate(value): + self.debug(component,item+'['+str(i)+']',v) + elif isinstance(value,dict): + for k,v in value.items(): + self.debug(component,item+'.'+str(k),v) + elif isinstance(value,np.ndarray): + #if really large, save as npz + folder = os.path.join(self.log_folder,'debug_{}'.format(component)) + if item not in self.debug_messages[component]: + self.debug_messages[component][item] = [] + os.mkdir(folder) + filename = os.path.join(folder,item+'_%03d.npz'%len(self.debug_messages[component][item])) + np.savez(filename,value) + elif isinstance(value,cv2.Mat): + #if really large, save as png + folder = os.path.join(self.log_folder,'debug_{}'.format(component)) + if item not in self.debug_messages[component]: + self.debug_messages[component][item] = [] + os.mkdir(folder) + filename = os.path.join(folder,item+'_%03d.png'%len(self.debug_messages[component][item])) + cv2.imwrite(filename,value) + else: + if item not in self.debug_messages[component]: + self.debug_messages[component][item] = [] + self.debug_messages[component][item].append((time.time(),self.vehicle_time-self.start_vehicle_time,value)) + + def debug_event(self, component : str, label : str) -> None: + """Logs a debug event to the metadata.""" + if not self.log_folder: + return + if component not in self.debug_messages: + self.debug_messages[component] = [] + if label not in self.debug_messages[component]: + self.debug_messages[component][label] = [] + self.debug_messages[component][label].append((time.time(),self.vehicle_time-self.start_vehicle_time,None)) + + def dump_debug(self): + if not self.log_folder: + return + for k,v in self.debug_messages.items(): + with open(os.path.join(self.log_folder,k+'_debug.csv'),'w') as f: + columns = [] + isevent = {} + for col,vals in v.items(): + if ',' in col: + col = '"'+col+'"' + columns.append(col+' time') + columns.append(col+' vehicle time') + if not all(x[2] is None for x in vals): + isevent[col] = False + columns.append(col) + else: + isevent[col] = True + f.write(','.join(columns)+'\n') + nrows = max(len(v[col]) for col in v) + for i in range(nrows): + row = [] + for col,vals in v.items(): + if i < len(vals): + row.append(str(vals[i][0])) + row.append(str(vals[i][1])) + if not isevent[col]: + row.append(str(vals[i][2])) + else: + row.append('') + row.append('') + if not isevent[col]: + row.append('') + f.write(','.join(row)+'\n') + + def pipeline_start_event(self, pipeline_name : str) -> None: """Logs a pipeline start event to the metadata.""" - self.run_metadata['pipelines'].append({'time':time.time(),'vehicle_time':vehicle_time,'name':pipeline_name}) + self.run_metadata['pipelines'].append({'time':time.time(),'vehicle_time':self.vehicle_time,'name':pipeline_name}) self.dump_log_metadata() def exit_event(self, description, force = False): @@ -149,34 +235,36 @@ def exit_event(self, description, force = False): self.run_metadata['exit_reason'] = description self.dump_log_metadata() - def log_component_update(self, component : str, vehicle_time : float, state : Any, outputs : List[str]) -> None: + def log_component_update(self, component : str, state : Any, outputs : List[str]) -> None: """Component update""" if component in self.logged_components and len(outputs)!=0: - self.behavior_log.log(state, outputs, vehicle_time) + self.behavior_log.log(state, outputs, self.vehicle_time) - def log_component_stdout(self, component : str, vehicle_time: float, msg : List[str]) -> None: + def log_component_stdout(self, component : str, msg : List[str]) -> None: if not self.log_folder: return if component not in self.component_output_loggers: self.component_output_loggers[component] = [None,None] if self.component_output_loggers[component][0] is None: self.component_output_loggers[component][0] = open(self.component_stdout_file(component),'w') - timestr = datetime.datetime.fromtimestamp(vehicle_time).strftime("%H:%M:%S.%f")[:-3] + timestr = datetime.datetime.fromtimestamp(self.vehicle_time).strftime("%H:%M:%S.%f")[:-3] for l in msg: self.component_output_loggers[component][0].write(timestr + ': ' + l + '\n') - def log_component_stderr(self, component : str, vehicle_time: float, msg : List[str]) -> None: + def log_component_stderr(self, component : str, msg : List[str]) -> None: if not self.log_folder: return if component not in self.component_output_loggers: self.component_output_loggers[component] = [None,None] if self.component_output_loggers[component][1] is None: self.component_output_loggers[component][1] = open(self.component_stderr_file(component),'w') - timestr = datetime.datetime.fromtimestamp(vehicle_time).strftime("%H:%M:%S.%f")[:-3] + timestr = datetime.datetime.fromtimestamp(self.vehicle_time).strftime("%H:%M:%S.%f")[:-3] for l in msg: self.component_output_loggers[component][1].write(timestr + ': ' + l + '\n') def close(self): + self.dump_debug() + self.debug_messages = {} if self.rosbag_process is not None: out,err = self.rosbag_process.communicate() # Will block print('-------------------------------------------') diff --git a/GEMstack/onboard/execution/multiprocess_execution.py b/GEMstack/onboard/execution/multiprocess_execution.py index 6d92d748a..208470dee 100644 --- a/GEMstack/onboard/execution/multiprocess_execution.py +++ b/GEMstack/onboard/execution/multiprocess_execution.py @@ -36,8 +36,6 @@ def start(self): 'print_stdout': self.print_stdout, 'print_stderr': self.print_stderr, } - old_manager = self.logging_manager - self.logging_manager = None #can't be pickled? self._process = Process(target=self._run, args=(self.c, self._in_queue, self._out_queue, config)) try: self._process.start() @@ -47,7 +45,6 @@ def start(self): self._process = None raise RuntimeError("Error starting "+self.c.__class__.__name__+" process, usually a pickling error") - self.logging_manager = old_manager res = self._out_queue.get() if isinstance(res,tuple) and isinstance(res[0],Exception): print("Traceback:") From fd5404124a61f1bfd0b10cf579090f7303523291 Mon Sep 17 00:00:00 2001 From: krishauser Date: Sun, 11 Feb 2024 16:46:42 -0500 Subject: [PATCH 111/232] Added reference speed = None for untimed path. Fixed pure pursuit receiving new paths, using debugging calls --- GEMstack/onboard/planning/motion_planning.py | 2 ++ GEMstack/onboard/planning/pure_pursuit.py | 24 ++++++++++++++++---- 2 files changed, 21 insertions(+), 5 deletions(-) diff --git a/GEMstack/onboard/planning/motion_planning.py b/GEMstack/onboard/planning/motion_planning.py index f0507d36c..4268df20b 100644 --- a/GEMstack/onboard/planning/motion_planning.py +++ b/GEMstack/onboard/planning/motion_planning.py @@ -18,5 +18,7 @@ def rate(self): return 10.0 def update(self, state : AllState): + if self.reference_speed is None: + return state.route return state.route.arc_length_parameterize(self.reference_speed) \ No newline at end of file diff --git a/GEMstack/onboard/planning/pure_pursuit.py b/GEMstack/onboard/planning/pure_pursuit.py index eb925423d..1647f3c58 100644 --- a/GEMstack/onboard/planning/pure_pursuit.py +++ b/GEMstack/onboard/planning/pure_pursuit.py @@ -29,7 +29,8 @@ def __init__(self, lookahead = None, lookahead_scale = None, wheelbase = None, c self.max_decel = settings.get('vehicle.limits.max_deceleration') # m/s^2 self.pid_speed = PID(settings.get('control.longitudinal_control.pid_p',0.5), settings.get('control.longitudinal_control.pid_d',0.0), settings.get('control.longitudinal_control.pid_i',0.1), windup_limit=20) - self.path = None # type: Path + self.path_arg = None + self.path = None # type: Trajectory #if trajectory = None, then only an untimed path was provided and we can't use the path velocity as the reference self.trajectory = None # type: Trajectory @@ -37,8 +38,9 @@ def __init__(self, lookahead = None, lookahead_scale = None, wheelbase = None, c self.t_last = None def set_path(self, path : Path): - if path == self.path or path == self.trajectory: + if path == self.path_arg: return + self.path_arg = path if len(path.points[0]) > 2: path = path.get_dims([0,1]) if not isinstance(path,Trajectory): @@ -52,7 +54,7 @@ def set_path(self, path : Path): self.trajectory = path self.current_path_parameter = 0.0 - def compute(self, state : VehicleState): + def compute(self, state : VehicleState, component : Component = None): assert state.pose.frame != ObjectFrameEnum.CURRENT t = state.pose.t @@ -121,7 +123,7 @@ def compute(self, state : VehicleState): #print("Closest point distance: " + str(L)) print("Forward velocity: " + str(speed)) ct_error = np.sin(alpha) * L - #print("Crosstrack Error: " + str(round(ct_error,3))) + print("Crosstrack Error: " + str(round(ct_error,3))) print("Front wheel angle: " + str(round(np.degrees(f_delta),2)) + " degrees") steering_angle = np.clip(front2steer(f_delta), self.steering_angle_range[0], self.steering_angle_range[1]) print("Steering wheel angle: " + str(round(np.degrees(steering_angle),2)) + " degrees" ) @@ -131,6 +133,8 @@ def compute(self, state : VehicleState): if self.desired_speed_from_path: #determine desired speed from trajectory if len(self.trajectory.points) < 2 or self.current_path_parameter >= self.path.domain()[1]: + if component is not None: + component.debug_event('Past the end of trajectory') #past the end, just stop desired_speed = 0.0 feedforward_accel = -2.0 @@ -155,6 +159,16 @@ def compute(self, state : VehicleState): #decay speed when crosstrack error is high desired_speed *= np.exp(-ct_error*0.4) output_accel = self.pid_speed.advance(e = desired_speed - speed, t = t, feedforward_term=feedforward_accel) + if component is not None: + component.debug('curr pt',(curr_x,curr_y)) + component.debug('curr param',self.current_path_parameter) + component.debug('desired pt',(desired_x,desired_y)) + component.debug('desired yaw (rad)',desired_yaw) + component.debug('crosstrack error',ct_error) + component.debug('front wheel angle (rad)',f_delta) + component.debug('desired speed (m/s)',desired_speed) + component.debug('feedforward accel (m/s^2)',feedforward_accel) + component.debug('output accel (m/s^2)',output_accel) print("Output accel: " + str(output_accel) + " m/s^2") if output_accel > self.max_accel: @@ -183,7 +197,7 @@ def state_outputs(self): def update(self, vehicle : VehicleState, trajectory: Trajectory): self.pure_pursuit.set_path(trajectory) - accel,wheel_angle = self.pure_pursuit.compute(vehicle) + accel,wheel_angle = self.pure_pursuit.compute(vehicle, self) #print("Desired wheel angle",wheel_angle) steering_angle = np.clip(front2steer(wheel_angle), self.pure_pursuit.steering_angle_range[0], self.pure_pursuit.steering_angle_range[1]) #print("Desired steering angle",steering_angle) From a6874aea5eb67d5d9478c69621c85471ca899109 Mon Sep 17 00:00:00 2001 From: krishauser Date: Mon, 12 Feb 2024 14:23:55 -0500 Subject: [PATCH 112/232] Fixed some typos --- GEMstack/knowledge/vehicle/dynamics.py | 2 +- GEMstack/onboard/perception/state_estimation.py | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/GEMstack/knowledge/vehicle/dynamics.py b/GEMstack/knowledge/vehicle/dynamics.py index 248bf8197..0418bd893 100644 --- a/GEMstack/knowledge/vehicle/dynamics.py +++ b/GEMstack/knowledge/vehicle/dynamics.py @@ -17,7 +17,7 @@ def acceleration_to_pedal_positions(acceleration : float, velocity : float, pitc Returns tuple (accelerator_pedal_position, brake_pedal_position, desired_gear) """ - model = settings.get('vehicle.dynamics.acceleration_model','v1_hang') + model = settings.get('vehicle.dynamics.acceleration_model','hang_v1') if model == 'hang_v1': if gear != 1: print("WARNING can't handle gears other than 1 yet") diff --git a/GEMstack/onboard/perception/state_estimation.py b/GEMstack/onboard/perception/state_estimation.py index db8727110..b51ce00cd 100644 --- a/GEMstack/onboard/perception/state_estimation.py +++ b/GEMstack/onboard/perception/state_estimation.py @@ -30,8 +30,8 @@ def inspva_callback(self, inspva_msg): y=inspva_msg.latitude, z=inspva_msg.height, yaw=math.radians(inspva_msg.azimuth), #heading from north in degrees - roll=math.radians(inspva_msg.inspva_msg.roll), - pitch=math.radians(inspva_msg.inspva_msg.pitch), + roll=math.radians(inspva_msg.roll), + pitch=math.radians(inspva_msg.pitch), ) #TODO: figure out what this status means print("INS status",inspva_msg.status) From 1bab1b820cdae40e3718b2878c3e439b8e682a57 Mon Sep 17 00:00:00 2001 From: krishauser Date: Mon, 12 Feb 2024 16:56:06 -0500 Subject: [PATCH 113/232] Fixed pickle problem :( --- GEMstack/onboard/execution/multiprocess_execution.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/GEMstack/onboard/execution/multiprocess_execution.py b/GEMstack/onboard/execution/multiprocess_execution.py index 208470dee..2ec0e8841 100644 --- a/GEMstack/onboard/execution/multiprocess_execution.py +++ b/GEMstack/onboard/execution/multiprocess_execution.py @@ -36,6 +36,8 @@ def start(self): 'print_stdout': self.print_stdout, 'print_stderr': self.print_stderr, } + if hasattr(self.c,'debugger'): + delattr(self.c,'debugger') #can't be serialized via Pickle self._process = Process(target=self._run, args=(self.c, self._in_queue, self._out_queue, config)) try: self._process.start() From 6113fa9d2795830ab465920454dee10f9d4396fc Mon Sep 17 00:00:00 2001 From: gem Date: Mon, 12 Feb 2024 21:22:29 -0600 Subject: [PATCH 114/232] Fixed typo --- GEMstack/state/vehicle.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/GEMstack/state/vehicle.py b/GEMstack/state/vehicle.py index 89852e4af..364046a71 100644 --- a/GEMstack/state/vehicle.py +++ b/GEMstack/state/vehicle.py @@ -54,7 +54,7 @@ def to_object(self) -> PhysicalObject: c_x = center_new[0] c_y = center_new[1] if self.pose.z is not None: - c_z = center_new.z + c_z = center_new[2] else: c_z = None center_pose = replace(self.pose,x=c_x,y=c_y,z=c_z) From 97577c62228af326861bb01a3d4fdb621f7c8ee3 Mon Sep 17 00:00:00 2001 From: gem Date: Mon, 12 Feb 2024 21:22:55 -0600 Subject: [PATCH 115/232] Avoid exception if start_pose_abs is None --- GEMstack/state/physical_object.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/GEMstack/state/physical_object.py b/GEMstack/state/physical_object.py index 3e3838ddb..71da16985 100644 --- a/GEMstack/state/physical_object.py +++ b/GEMstack/state/physical_object.py @@ -277,7 +277,7 @@ def _get_frame_chain(source_frame : ObjectFrameEnum, target_frame : ObjectFrameE if start_pose_abs is not None and start_pose_abs.frame not in [ObjectFrameEnum.GLOBAL,ObjectFrameEnum.ABSOLUTE_CARTESIAN]: raise ValueError("start_pose_abs must be in GLOBAL or ABSOLUTE_CARTESIAN frame") if current_pose is not None and current_pose.frame in [ObjectFrameEnum.GLOBAL,ObjectFrameEnum.ABSOLUTE_CARTESIAN]: - if current_pose.frame != start_pose_abs.frame: + if start_pose_abs is not None and current_pose.frame != start_pose_abs.frame: raise ValueError("Cannot mix GLOBAL and ABSOLUTE_CARTESIAN frames") if frame_chain[-1][0] == ObjectFrameEnum.CURRENT: if current_pose is None: From fc4b7655983e475dcae62a5c592d20222bec9587 Mon Sep 17 00:00:00 2001 From: gem Date: Mon, 12 Feb 2024 21:23:27 -0600 Subject: [PATCH 116/232] Remove annoying print messages and multithreading issues --- GEMstack/onboard/perception/state_estimation.py | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/GEMstack/onboard/perception/state_estimation.py b/GEMstack/onboard/perception/state_estimation.py index b51ce00cd..de48d069f 100644 --- a/GEMstack/onboard/perception/state_estimation.py +++ b/GEMstack/onboard/perception/state_estimation.py @@ -21,6 +21,7 @@ def __init__(self, vehicle_interface : GEMInterface): self.location = settings.get('vehicle.calibration.gnss_location')[:2] self.yaw_offset = settings.get('vehicle.calibration.gnss_yaw') self.speed_filter = OnlineLowPassFilter(1.2, 30, 4) + self.status = None # Get GNSS information def inspva_callback(self, inspva_msg): @@ -33,8 +34,7 @@ def inspva_callback(self, inspva_msg): roll=math.radians(inspva_msg.roll), pitch=math.radians(inspva_msg.pitch), ) - #TODO: figure out what this status means - print("INS status",inspva_msg.status) + self.status = inspva_msg.status def rate(self): return 10.0 @@ -48,6 +48,9 @@ def healthy(self): def update(self) -> VehicleState: if self.gnss_pose is None: return + #TODO: figure out what this status means + #print("INS status",self.status) + # vehicle gnss heading (yaw) in radians # vehicle x, y position in fixed local frame, in meters # reference point is located at the center of GNSS antennas From d9efda21fb7848f44d6a1eb503d0a178ac0bf93f Mon Sep 17 00:00:00 2001 From: gem Date: Mon, 12 Feb 2024 21:24:08 -0600 Subject: [PATCH 117/232] Allow setting items to None in config files, showing log folders in Linux --- GEMstack/onboard/execution/entrypoint.py | 13 ++++++++++--- 1 file changed, 10 insertions(+), 3 deletions(-) diff --git a/GEMstack/onboard/execution/entrypoint.py b/GEMstack/onboard/execution/entrypoint.py index 096c0c144..7d267bf3a 100644 --- a/GEMstack/onboard/execution/entrypoint.py +++ b/GEMstack/onboard/execution/entrypoint.py @@ -3,6 +3,7 @@ from .execution import EXECUTION_PREFIX,ExecutorBase,ComponentExecutor,load_computation_graph,make_class import multiprocessing from typing import Dict,List,Optional +import sys import os def main(): @@ -106,12 +107,15 @@ def caution_callback(k,variant): perception_components = {} #type: Dict[str,ComponentExecutor] for (k,v) in perception_settings.items(): + if v is None: continue perception_components[k] = mission_executor.make_component(v,k,'GEMstack.onboard.perception', {'vehicle_interface':vehicle_interface}) planning_components = {} #type: Dict[str,ComponentExecutor] for (k,v) in planning_settings.items(): + if v is None: continue planning_components[k] = mission_executor.make_component(v,k,'GEMstack.onboard.planning', {'vehicle_interface':vehicle_interface}) other_components = {} #type: Dict[str,ComponentExecutor] for (k,v) in other_settings.items(): + if v is None: continue other_components[k] = mission_executor.make_component(v,k,'GEMstack.onboard.other', {'vehicle_interface':vehicle_interface}) mission_executor.add_pipeline(name,perception_components,planning_components,other_components) @@ -159,6 +163,9 @@ def caution_callback(k,variant): rospy.signal_shutdown('GEM_executor finished') print(EXECUTION_PREFIX,"---------------- DONE ----------------") - if log_settings and settings.get('run.after.show_log_folder',True): - import webbrowser - webbrowser.open(logfolder) + if log_settings and settings.get('run.after.show_log_folder',False): + if sys.platform.startswith('linux'): + os.system('nautilus '+logfolder) + else: + import webbrowser + webbrowser.open(logfolder) From 615a95fec11c820bc7b5738e6fadb63c99be1bab Mon Sep 17 00:00:00 2001 From: gem Date: Mon, 12 Feb 2024 21:24:27 -0600 Subject: [PATCH 118/232] More informative delay messages --- GEMstack/onboard/execution/execution.py | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/GEMstack/onboard/execution/execution.py b/GEMstack/onboard/execution/execution.py index 409b6088e..a65c2acc5 100644 --- a/GEMstack/onboard/execution/execution.py +++ b/GEMstack/onboard/execution/execution.py @@ -251,14 +251,19 @@ def stop(self): def update(self, t : float, state : AllState): if self.next_update_time is None or t >= self.next_update_time: + t0 = time.time() self.update_now(t,state) + t1 = time.time() self.last_update_time = t if self.next_update_time is None: self.next_update_time = t + self.dt else: self.next_update_time += self.dt if self.next_update_time < t and self.dt > 0: - executor_debug_print(1,"Component {} is running behind, overran dt {} by {} seconds",self.c.__class__.__name__,self.dt,t-self.next_update_time) + if t1 - t0 > self.dt: + executor_debug_print(1,"Component {} is running behind, time {} overran dt {} by {} s",self.c.__class__.__name__,t1-t0,self.dt,t-self.next_update_time) + else: + executor_debug_print(1,"Component {} is running behind (pushed back) overran dt {} by {} s",self.c.__class__.__name__,t1-t0,self.dt,t-self.next_update_time) self.num_overruns += 1 self.overrun_amount += t - self.next_update_time self.next_update_time = t + self.dt From a2169bf26da3799c91efe64a5e523aace13519ee Mon Sep 17 00:00:00 2001 From: krishauser Date: Sun, 18 Feb 2024 12:22:56 -0500 Subject: [PATCH 119/232] Shrunk acceleration deadband, moved to parameter file --- GEMstack/knowledge/vehicle/dynamics.py | 3 ++- GEMstack/knowledge/vehicle/gem_e2_dynamics.yaml | 1 + 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/GEMstack/knowledge/vehicle/dynamics.py b/GEMstack/knowledge/vehicle/dynamics.py index 0418bd893..069f74807 100644 --- a/GEMstack/knowledge/vehicle/dynamics.py +++ b/GEMstack/knowledge/vehicle/dynamics.py @@ -55,6 +55,7 @@ def acceleration_to_pedal_positions(acceleration : float, velocity : float, pitc aerodynamic_drag_coefficient = settings.get('vehicle.dynamics.aerodynamic_drag_coefficient') accel_active_range = settings.get('vehicle.dynamics.accelerator_active_range') # pedal position fraction brake_active_range = settings.get('vehicle.dynamics.brake_active_range') # pedal position fraction + acceleration_deadband = settings.get('vehicle.dynamics.acceleration_deadband',0.0) drag = -(aerodynamic_drag_coefficient * velocity**2) * vsign - internal_dry_deceleration * vsign - internal_viscous_deceleration * velocity sin_pitch = math.sin(pitch) @@ -62,7 +63,7 @@ def acceleration_to_pedal_positions(acceleration : float, velocity : float, pitc #this is the net acceleration that should be achieved by accelerator / brake pedal #TODO: power curves to select optimal gear - if abs(acceleration) < 0.5: + if abs(acceleration) < acceleration_deadband: #deadband? return (0,0,gear) if velocity * acceleration < 0: diff --git a/GEMstack/knowledge/vehicle/gem_e2_dynamics.yaml b/GEMstack/knowledge/vehicle/gem_e2_dynamics.yaml index 4a6cd5c21..8df21ac71 100644 --- a/GEMstack/knowledge/vehicle/gem_e2_dynamics.yaml +++ b/GEMstack/knowledge/vehicle/gem_e2_dynamics.yaml @@ -19,3 +19,4 @@ brake_active_range : [0,1] #range of brake pedal where output decele internal_dry_deceleration: 0.2 #m/s^2: deceleration due to internal dry friction (non-speed dependent) internal_viscous_deceleration: 0.05 #1/s: scales the current velocity to get deceleration due to internal viscous friction (speed dependent) aerodynamic_drag_coefficient: 0.01 #units in s, scaled by velocity^2 to get deceleration due to aerodynamic drag +acceleration_deadband: 0.1 #m/s^2: minimum acceleration to be considered non-zero From b7ab3a4d15ae14b179b935a9c0687eb3ed54578f Mon Sep 17 00:00:00 2001 From: krishauser Date: Sun, 18 Feb 2024 13:16:07 -0500 Subject: [PATCH 120/232] Fixed absolute value in tracking speed scaling, added option to use trajectory timing --- GEMstack/knowledge/defaults/current.yaml | 9 +++++- GEMstack/onboard/planning/pure_pursuit.py | 37 ++++++++++++++--------- launch/fixed_route.yaml | 1 + 3 files changed, 32 insertions(+), 15 deletions(-) diff --git a/GEMstack/knowledge/defaults/current.yaml b/GEMstack/knowledge/defaults/current.yaml index e043a2d00..90bbd7906 100644 --- a/GEMstack/knowledge/defaults/current.yaml +++ b/GEMstack/knowledge/defaults/current.yaml @@ -27,7 +27,7 @@ control: lookahead: 2.0 lookahead_scale: 3.0 crosstrack_gain: 1.0 - desired_speed: 2.0 #m/s + desired_speed: trajectory longitudinal_control: pid_p: 1.0 pid_i: 0.1 @@ -37,3 +37,10 @@ control: simulator: dt: 0.01 real_time_multiplier: 1.0 # make the simulator run faster than real time by making this > 1 + gnss_emulator: + dt: 0.1 #10Hz + position_noise: 0.1 #10cm noise + orientation_noise: 0.04 #2.3 degrees noise + velocity_noise: + constant: 0.04 #4cm/s noise + linear: 0.02 #2% noise \ No newline at end of file diff --git a/GEMstack/onboard/planning/pure_pursuit.py b/GEMstack/onboard/planning/pure_pursuit.py index 1647f3c58..e4b6f4f4e 100644 --- a/GEMstack/onboard/planning/pure_pursuit.py +++ b/GEMstack/onboard/planning/pure_pursuit.py @@ -11,20 +11,21 @@ class PurePursuit(object): """Implements a pure pursuit controller on a second-order Dubins vehicle.""" - def __init__(self, lookahead = None, lookahead_scale = None, wheelbase = None, crosstrack_gain = None): + def __init__(self, lookahead = None, lookahead_scale = None, crosstrack_gain = None, desired_speed = None): self.look_ahead = lookahead if lookahead is not None else settings.get('control.pure_pursuit.lookahead',4.0) self.look_ahead_scale = lookahead_scale if lookahead_scale is not None else settings.get('control.pure_pursuit.lookahead_scale',3.0) self.crosstrack_gain = crosstrack_gain if crosstrack_gain is not None else settings.get('control.pure_pursuit.crosstrack_gain',0.41) self.front_wheel_angle_scale = 3.0 - self.wheelbase = wheelbase if wheelbase is not None else settings.get('vehicle.geometry.wheelbase') + self.wheelbase = settings.get('vehicle.geometry.wheelbase') self.wheel_angle_range = [settings.get('vehicle.geometry.min_wheel_angle'),settings.get('vehicle.geometry.max_wheel_angle')] self.steering_angle_range = [settings.get('vehicle.geometry.min_steering_angle'),settings.get('vehicle.geometry.max_steering_angle')] - self.desired_speed = settings.get('control.pure_pursuit.desired_speed',2.5) #approximately 5 mph - self.desired_speed_from_path = True #turn this to True to use the input trajectory to determine the desired speed + if desired_speed is not None: + self.desired_speed_source = desired_speed + else: + self.desired_speed_source = settings.get('control.pure_pursuit.desired_speed',"path") + self.desired_speed = self.desired_speed_source if isinstance(self.desired_speed_source,(int,float)) else None self.speed_limit = settings.get('vehicle.limits.max_speed') - if self.desired_speed > self.speed_limit: - self.desired_speed = self.speed_limit self.max_accel = settings.get('vehicle.limits.max_acceleration') # m/s^2 self.max_decel = settings.get('vehicle.limits.max_deceleration') # m/s^2 self.pid_speed = PID(settings.get('control.longitudinal_control.pid_p',0.5), settings.get('control.longitudinal_control.pid_d',0.0), settings.get('control.longitudinal_control.pid_i',0.1), windup_limit=20) @@ -35,6 +36,7 @@ def __init__(self, lookahead = None, lookahead_scale = None, wheelbase = None, c self.trajectory = None # type: Trajectory self.current_path_parameter = 0.0 + self.current_traj_parameter = 0.0 self.t_last = None def set_path(self, path : Path): @@ -46,12 +48,13 @@ def set_path(self, path : Path): if not isinstance(path,Trajectory): self.path = path.arc_length_parameterize() self.trajectory = None - self.desired_speed_from_path = False - if self.desired_speed_from_path: - raise ValueError("Can't provide an untimed path to PurePursuit and expect it to use the path velocity") + self.current_traj_parameter = 0.0 + if self.desired_speed_source in ['path','trajectory']: + raise ValueError("Can't provide an untimed path to PurePursuit and expect it to use the path velocity. Set control.pure_pursuit.desired_speed to a constant.") else: self.path = path.arc_length_parameterize() self.trajectory = path + self.current_traj_parameter = self.trajectory.domain()[0] self.current_path_parameter = 0.0 def compute(self, state : VehicleState, component : Component = None): @@ -83,6 +86,7 @@ def compute(self, state : VehicleState, component : Component = None): closest_dist,closest_parameter = self.path.closest_point_local((curr_x,curr_y),[self.current_path_parameter-5.0,self.current_path_parameter+5.0]) self.current_path_parameter = closest_parameter + self.current_traj_parameter += dt #TODO: calculate parameter that is look_ahead distance away from the closest point? #(rather than just advancing the parameter) des_parameter = closest_parameter + self.look_ahead + self.look_ahead_scale * speed @@ -130,7 +134,7 @@ def compute(self, state : VehicleState, component : Component = None): desired_speed = self.desired_speed feedforward_accel = 0.0 - if self.desired_speed_from_path: + if self.desired_speed_source in ['path','trajectory']: #determine desired speed from trajectory if len(self.trajectory.points) < 2 or self.current_path_parameter >= self.path.domain()[1]: if component is not None: @@ -139,7 +143,10 @@ def compute(self, state : VehicleState, component : Component = None): desired_speed = 0.0 feedforward_accel = -2.0 else: - current_trajectory_time = self.trajectory.parameter_to_time(self.current_path_parameter) + if self.desired_speed_source=='path': + current_trajectory_time = self.trajectory.parameter_to_time(self.current_path_parameter) + else: + current_trajectory_time = self.current_traj_parameter deriv = self.trajectory.eval_derivative(current_trajectory_time) desired_speed = min(np.linalg.norm(deriv),self.speed_limit) difference_dt = 0.1 @@ -157,7 +164,9 @@ def compute(self, state : VehicleState, component : Component = None): print("Feedforward accel: " + str(feedforward_accel) + " m/s^2") else: #decay speed when crosstrack error is high - desired_speed *= np.exp(-ct_error*0.4) + desired_speed *= np.exp(-abs(ct_error)*0.4) + if desired_speed > self.speed_limit: + desired_speed = self.speed_limit output_accel = self.pid_speed.advance(e = desired_speed - speed, t = t, feedforward_term=feedforward_accel) if component is not None: component.debug('curr pt',(curr_x,curr_y)) @@ -182,8 +191,8 @@ def compute(self, state : VehicleState, component : Component = None): class PurePursuitTrajectoryTracker(Component): - def __init__(self,vehicle_interface): - self.pure_pursuit = PurePursuit() + def __init__(self,vehicle_interface=None, **args): + self.pure_pursuit = PurePursuit(**args) self.vehicle_interface = vehicle_interface def rate(self): diff --git a/launch/fixed_route.yaml b/launch/fixed_route.yaml index 3f31e41a3..c05de8ff7 100644 --- a/launch/fixed_route.yaml +++ b/launch/fixed_route.yaml @@ -22,6 +22,7 @@ drive: args: [null] #desired speed in m/s. If null, this will keep the route untimed for the trajectory tracker trajectory_tracking: type: pure_pursuit.PurePursuitTrajectoryTracker + args: {desired_speed: 2.5} #approximately 5mph print: False log: # Specify the top-level folder to save the log files. Default is 'logs' From 31b246e4091f90731695281899b6ece9b424b559 Mon Sep 17 00:00:00 2001 From: krishauser Date: Sun, 18 Feb 2024 13:17:02 -0500 Subject: [PATCH 121/232] Better control limit for steering wheel angle --- GEMstack/knowledge/vehicle/gem_e2_control_defaults.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/GEMstack/knowledge/vehicle/gem_e2_control_defaults.yaml b/GEMstack/knowledge/vehicle/gem_e2_control_defaults.yaml index 3f81bc831..6767511e1 100644 --- a/GEMstack/knowledge/vehicle/gem_e2_control_defaults.yaml +++ b/GEMstack/knowledge/vehicle/gem_e2_control_defaults.yaml @@ -1,3 +1,3 @@ brake_pedal_speed : 3.0 accelerator_pedal_speed : 3.0 -steering_wheel_speed : 2.0 +steering_wheel_speed : 4.0 From 23e09710b570bbb3d75e263e7dc7bd2a2db6f873 Mon Sep 17 00:00:00 2001 From: krishauser Date: Sun, 18 Feb 2024 13:17:23 -0500 Subject: [PATCH 122/232] Added ability to simulate sensors at different rate, adding noise --- GEMstack/onboard/interface/gem_simulator.py | 48 ++++++++++++++++++--- 1 file changed, 41 insertions(+), 7 deletions(-) diff --git a/GEMstack/onboard/interface/gem_simulator.py b/GEMstack/onboard/interface/gem_simulator.py index 3d36f5a63..2abfde71f 100644 --- a/GEMstack/onboard/interface/gem_simulator.py +++ b/GEMstack/onboard/interface/gem_simulator.py @@ -176,9 +176,12 @@ def simulate(self, T : float, command : Optional[GEMVehicleCommand]): acceleration = np.clip(acceleration,*self.dubins.accelRange) phides = steer2front(self.last_command.steering_wheel_angle) phides = np.clip(phides,*self.dubins.wheelAngleRange) - phi_deadband = 0.01 - steering_angle_rate = self.last_command.steering_wheel_speed if phides > phi + phi_deadband else \ - (-self.last_command.steering_wheel_speed if phides < phi - phi_deadband else 0.0) + h = 0.01 #just for finite differencing + front_wheel_angle_rate = (steer2front(self.last_command.steering_wheel_angle + h*self.last_command.steering_wheel_speed) - steer2front(self.last_command.steering_wheel_angle)) / h + front_wheel_angle_rate_max = 2.0 #TODO: get from vehicle model + phi_deadband = 2*self.dt*front_wheel_angle_rate_max + steering_angle_rate = front_wheel_angle_rate if phides > phi + phi_deadband else \ + (-front_wheel_angle_rate if phides < phi - phi_deadband else 0.0) #simulate dynamics u = np.array([acceleration,steering_angle_rate]) #acceleration, steering angle rate @@ -259,8 +262,17 @@ def __init__(self, scene : str = None): GEMInterface.__init__(self) self.simulator = GEMDoubleIntegratorSimulation(scene) self.real_time_multiplier = settings.get('simulator.real_time_multiplier',1.0) + self.gnss_emulator_settings = settings.get('simulator.gnss_emulator',{}) + self.imu_emulator_settings = settings.get('simulator.imu_emulator',{}) + self.agent_emulator_settings = settings.get('simulator.agent_emulator',{}) + self.gnss_dt = self.gnss_emulator_settings.get('dt',0.1) + self.imu_dt = self.imu_emulator_settings.get('dt',0.05) + self.agent_dt = self.agent_emulator_settings.get('dt',0.1) self.last_reading = self.simulator.last_reading self.last_command = self.simulator.last_command + self.last_gnss_time = 0 + self.last_imu_time = 0 + self.last_agent_time = 0 self.gnss_callback = None self.imu_callback = None self.agent_detector_callback = None @@ -322,13 +334,35 @@ def simulate(self,lock : Lock, data : dict): self.simulator.simulate(self.simulator.dt, self.last_command) self.last_reading = self.simulator.last_reading - if self.gnss_callback is not None: + if self.gnss_callback is not None and self.simulator.simulation_time - self.last_gnss_time > self.gnss_dt: vehicle_state = self.simulator.state() - self.gnss_callback(vehicle_state) - if self.imu_callback is not None: + self.gnss_callback(self.gnss_emulator(vehicle_state)) + self.last_gnss_time = self.simulator.simulation_time + if self.imu_callback is not None and self.simulator.simulation_time - self.last_imu_time > self.imu_dt: pose = ObjectPose(frame=ObjectFrameEnum.CURRENT,t=self.simulation_time,x=0,y=0,yaw=0) vehicle_state = self.last_reading.to_state(pose) self.imu_callback(vehicle_state) - if self.agent_detector_callback is not None: + self.last_imu_time = self.simulator.simulation_time + if self.agent_detector_callback is not None and self.simulator.simulation_time - self.last_agent_time > self.agent_dt: for k,a in self.simulator.agents.items(): self.agent_detector_callback(k,a.to_agent_state()) + self.last_agent_time = self.simulator.simulation_time + + def gnss_emulator(self, vehicle_state: VehicleState): + position_noise = self.gnss_emulator_settings.get('position_noise',0.0) + orientation_noise = self.gnss_emulator_settings.get('orientation_noise',0.0) + velocity_noise_const = self.gnss_emulator_settings.get('velocity_noise.constant',0.0) + velocity_noise_linear = self.gnss_emulator_settings.get('velocity_noise.linear',0.0) + if position_noise > 0 or orientation_noise > 0 or velocity_noise_const > 0 or velocity_noise_linear > 0: + # Add noise to the vehicle state + position = vehicle_state.pose.x,vehicle_state.pose.y + yaw = vehicle_state.pose.yaw + v = vehicle_state.v + position = (np.random.normal(position[0],position_noise), np.random.normal(position[1],position_noise)) + yaw = np.random.normal(vehicle_state.pose.yaw,orientation_noise) + v = np.random.normal(v,velocity_noise_const + abs(v)*velocity_noise_linear) + pose = replace(vehicle_state.pose, x=position[0], y=position[1], yaw=yaw) + return replace(vehicle_state, pose=pose, v=v) + return vehicle_state + + #TODO: agent emulator, imu emulator From 71ff6eac18c8434af6f63b72eceff9a17802f7e5 Mon Sep 17 00:00:00 2001 From: krishauser Date: Sun, 18 Feb 2024 13:21:49 -0500 Subject: [PATCH 123/232] Removed errors from simulator --- GEMstack/knowledge/defaults/current.yaml | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/GEMstack/knowledge/defaults/current.yaml b/GEMstack/knowledge/defaults/current.yaml index 90bbd7906..a09532ba6 100644 --- a/GEMstack/knowledge/defaults/current.yaml +++ b/GEMstack/knowledge/defaults/current.yaml @@ -39,8 +39,8 @@ simulator: real_time_multiplier: 1.0 # make the simulator run faster than real time by making this > 1 gnss_emulator: dt: 0.1 #10Hz - position_noise: 0.1 #10cm noise - orientation_noise: 0.04 #2.3 degrees noise - velocity_noise: - constant: 0.04 #4cm/s noise - linear: 0.02 #2% noise \ No newline at end of file + #position_noise: 0.1 #10cm noise + #orientation_noise: 0.04 #2.3 degrees noise + #velocity_noise: + # constant: 0.04 #4cm/s noise + # linear: 0.02 #2% noise \ No newline at end of file From 27750b53c5f50e4ff83f039bff0ded07c3746622 Mon Sep 17 00:00:00 2001 From: krishauser Date: Sun, 18 Feb 2024 18:54:12 -0500 Subject: [PATCH 124/232] Smoother simulation with accurate inversion of acceleration_to_pedals --- GEMstack/knowledge/vehicle/dynamics.py | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/GEMstack/knowledge/vehicle/dynamics.py b/GEMstack/knowledge/vehicle/dynamics.py index 069f74807..9bd33a92e 100644 --- a/GEMstack/knowledge/vehicle/dynamics.py +++ b/GEMstack/knowledge/vehicle/dynamics.py @@ -110,6 +110,13 @@ def pedal_positions_to_acceleration(accelerator_pedal_position : float, brake_pe brake_max = settings.get('vehicle.dynamics.max_brake_deceleration') reverse_accel_max = settings.get('vehicle.dynamics.max_accelerator_acceleration_reverse') accel_max = settings.get('vehicle.dynamics.max_accelerator_acceleration') + accel_active_range = settings.get('vehicle.dynamics.accelerator_active_range') # pedal position fraction + brake_active_range = settings.get('vehicle.dynamics.brake_active_range') # pedal position fraction + #normalize to 0-1 depending on pedal range + accelerator_pedal_position = (accelerator_pedal_position - accel_active_range[0]) / (accel_active_range[1]-accel_active_range[0]) + accelerator_pedal_position = min(1.0,max(accelerator_pedal_position,0.0)) + brake_pedal_position = (brake_pedal_position - brake_active_range[0]) / (brake_active_range[1]-brake_active_range[0]) + brake_pedal_position = min(1.0,max(brake_pedal_position,0.0)) assert isinstance(brake_max,(int,float)) assert isinstance(reverse_accel_max,(int,float)) assert isinstance(accel_max,list) From 647bffe19e4bb7f2fef91080586418bbeb3a9ef2 Mon Sep 17 00:00:00 2001 From: krishauser Date: Mon, 19 Feb 2024 00:09:25 -0500 Subject: [PATCH 125/232] Made visualization work better with simulator --- .../visualization/klampt_visualization.py | 24 ++++++++++++------- GEMstack/utils/klampt_visualization.py | 11 +++++---- 2 files changed, 22 insertions(+), 13 deletions(-) diff --git a/GEMstack/onboard/visualization/klampt_visualization.py b/GEMstack/onboard/visualization/klampt_visualization.py index 41e05e858..ad9578f9e 100644 --- a/GEMstack/onboard/visualization/klampt_visualization.py +++ b/GEMstack/onboard/visualization/klampt_visualization.py @@ -2,7 +2,7 @@ from klampt import vis from klampt.math import se3 from klampt import * -from ...state import AllState,ObjectFrameEnum +from ...state import AllState,ObjectFrameEnum,VehicleState from ...mathutils.signal import OnlineLowPassFilter from ...utils import klampt_visualization import time @@ -15,7 +15,7 @@ class KlamptVisualization(Component): If save_as is not None, saves the visualization to a file. """ - def __init__(self, vehicle_interface, rate : float = 10.0, save_as : str = None): + def __init__(self, vehicle_interface, rate : float = 20.0, save_as : str = None): self.vehicle_interface = vehicle_interface self._rate = rate self.save_as = save_as @@ -94,6 +94,11 @@ def debug_event(self, source, event): vis.logPlotEvent(source+"_plot",event) def update(self, state): + ground_truth_state = None + if hasattr(self.vehicle_interface,'simulator'): + #simulation mode, show the actual simulator state and show + with self.vehicle_interface.thread_lock: + ground_truth_state = self.vehicle_interface.simulator.state().to_frame(ObjectFrameEnum.START,start_pose_abs = state.start_vehicle_pose) if not vis.shown(): #plot closed return @@ -106,22 +111,23 @@ def update(self, state): self.debug("vehicle","brake",state.vehicle.brake_pedal_position) time_str = time.strftime("%Y-%m-%d %H:%M:%S", time.localtime(state.t)) state_start = state.to_frame(ObjectFrameEnum.START) if state.start_vehicle_pose is not None else state.to_frame(state.vehicle.pose.frame) - klampt_visualization.plot(state_start,title="Scene %d at %s"%(self.num_updates,time_str),vehicle_model=self.vehicle,show=False) + klampt_visualization.plot(state_start,title="Scene %d at %s"%(self.num_updates,time_str),ground_truth_vehicle=ground_truth_state,vehicle_model=self.vehicle,show=False) - #update pose of the vehicle + #update pose of the tracked vehicle for camera + tracked_vehicle = ground_truth_state if ground_truth_state is not None else state.vehicle if self.last_yaw is not None: vp = vis.getViewport() - v = self.vfilter(state.vehicle.v) + v = self.vfilter(tracked_vehicle.v) center_offset = 1.0 lookahead = 4.0*v - dx,dy = math.cos(state.vehicle.pose.yaw)*(lookahead+center_offset),math.sin(state.vehicle.pose.yaw)*(lookahead+center_offset) - vp.camera.tgt = [state.vehicle.pose.x+dx,state.vehicle.pose.y+dy,1.5] - vp.camera.rot[2] += state.vehicle.pose.yaw - self.last_yaw + dx,dy = math.cos(tracked_vehicle.pose.yaw)*(lookahead+center_offset),math.sin(tracked_vehicle.pose.yaw)*(lookahead+center_offset) + vp.camera.tgt = [tracked_vehicle.pose.x+dx,tracked_vehicle.pose.y+dy,1.5] + vp.camera.rot[2] += tracked_vehicle.pose.yaw - self.last_yaw vp.camera.dist += 5.0*(v - self.last_v) self.last_v = v vis.setViewport(vp) - self.last_yaw = state.vehicle.pose.yaw + self.last_yaw = tracked_vehicle.pose.yaw vis.add("vehicle_plane",self.world.terrain(0),hide_label=True) finally: vis.unlock() diff --git a/GEMstack/utils/klampt_visualization.py b/GEMstack/utils/klampt_visualization.py index 6c53ad010..3b6b4a9b7 100644 --- a/GEMstack/utils/klampt_visualization.py +++ b/GEMstack/utils/klampt_visualization.py @@ -249,7 +249,7 @@ def plot_roadgraph(roadgraph : Roadgraph, route : Route = None): for k,o in roadgraph.static_obstacles.items(): plot_object(k,o) -def plot_scene(scene : SceneState, vehicle_model = None, title = None, show=True): +def plot_scene(scene : SceneState, ground_truth_vehicle=None, vehicle_model = None, title = None, show=True): for i in list(vis.scene().items.keys()): if not i.startswith("vehicle"): if not isinstance(vis.scene().items[i],vis.VisPlot): @@ -258,7 +258,10 @@ def plot_scene(scene : SceneState, vehicle_model = None, title = None, show=True #TODO if vehicle_model is not None: vis.add("vehicle_model",vehicle_model) - xform = scene.vehicle.to_object().pose.transform() + if ground_truth_vehicle is not None: + xform = ground_truth_vehicle.to_object().pose.transform() + else: + xform = scene.vehicle.to_object().pose.transform() vehicle_model.link(0).setParentTransform(*se3.from_ndarray(xform)) vehicle_model.setConfig(vehicle_model.getConfig()) @@ -278,8 +281,8 @@ def plot_scene(scene : SceneState, vehicle_model = None, title = None, show=True if show: vis.show() -def plot(state : AllState, vehicle_model=None, title=None, show=True): - plot_scene(state, vehicle_model=vehicle_model, title=title, show=show) +def plot(state : AllState, ground_truth_vehicle = None, vehicle_model=None, title=None, show=True): + plot_scene(state, ground_truth_vehicle=ground_truth_vehicle, vehicle_model=vehicle_model, title=title, show=show) if state.route is not None: plot_path("route",state.route,color=(1,0.5,0,1)) if state.trajectory is not None: From b6578fe940693b8602efed521c38f4f72d310987 Mon Sep 17 00:00:00 2001 From: krishauser Date: Mon, 19 Feb 2024 00:10:01 -0500 Subject: [PATCH 126/232] Perception normalizer doesn't mess with frames except for the vehicle state --- .../perception/perception_normalization.py | 41 +++++++++++-------- 1 file changed, 24 insertions(+), 17 deletions(-) diff --git a/GEMstack/onboard/perception/perception_normalization.py b/GEMstack/onboard/perception/perception_normalization.py index f4ffcd157..c5b64de10 100644 --- a/GEMstack/onboard/perception/perception_normalization.py +++ b/GEMstack/onboard/perception/perception_normalization.py @@ -1,9 +1,10 @@ from ...state import AllState,ObjectPose,ObjectFrameEnum,VehicleState from ..component import Component +from dataclasses import replace class StandardPerceptionNormalizer(Component): - """Updates the start pose and converts all objects to the current vehicle - frame, in preparation for planning.""" + """Updates the start pose if necessary, converts the vehicle pose to the + START frame.""" def rate(self): return None def state_inputs(self): @@ -16,24 +17,30 @@ def update(self,state : AllState): state.start_vehicle_pose = state.vehicle.pose else: return - #convert vehicle pose to start frame state.vehicle.pose = state.vehicle.pose.to_frame(ObjectFrameEnum.START, start_pose_abs=state.start_vehicle_pose) - #convert roadgraph to current frame - state.roadgraph = state.roadgraph.to_frame(ObjectFrameEnum.CURRENT, current_pose=state.vehicle.pose, start_pose_abs=state.start_vehicle_pose) - for k,a in state.agents.items(): - a.pose = a.pose.to_frame(ObjectFrameEnum.CURRENT, current_pose=state.vehicle.pose, start_pose_abs=state.start_vehicle_pose) - - for k,o in state.obstacles.items(): - o.pose = o.pose.to_frame(ObjectFrameEnum.CURRENT, current_pose=state.vehicle.pose, start_pose_abs=state.start_vehicle_pose) +def normalize_scene_to_current(state : AllState): + """Normalizes the scene and converts all objects to the current vehicle + frame, in preparation for planning""" + state = replace(state) - #convert predictions to current frame. - for k,a in state.agent_intents.items(): - for pred in a.predictions: - if pred.path is not None: - for i,p in enumerate(pred.path): - pred.path[i] = p.to_frame(ObjectFrameEnum.CURRENT, current_pose=state.vehicle.pose, start_pose_abs=state.start_vehicle_pose) + #convert roadgraph to current frame + state.roadgraph = state.roadgraph.to_frame(ObjectFrameEnum.CURRENT, current_pose=state.vehicle.pose, start_pose_abs=state.start_vehicle_pose) - #TODO: advance agent predictions and paths to current vehicle time \ No newline at end of file + for k,a in state.agents.items(): + a.pose = a.pose.to_frame(ObjectFrameEnum.CURRENT, current_pose=state.vehicle.pose, start_pose_abs=state.start_vehicle_pose) + + for k,o in state.obstacles.items(): + o.pose = o.pose.to_frame(ObjectFrameEnum.CURRENT, current_pose=state.vehicle.pose, start_pose_abs=state.start_vehicle_pose) + + #convert predictions to current frame. + for k,a in state.agent_intents.items(): + for pred in a.predictions: + if pred.path is not None: + for i,p in enumerate(pred.path): + pred.path[i] = p.to_frame(ObjectFrameEnum.CURRENT, current_pose=state.vehicle.pose, start_pose_abs=state.start_vehicle_pose) + + #TODO: advance agent predictions and paths to current vehicle time + return state \ No newline at end of file From af6d98e48cefb7f9042d56ee0c01550b0d30c231 Mon Sep 17 00:00:00 2001 From: krishauser Date: Mon, 19 Feb 2024 00:21:12 -0500 Subject: [PATCH 127/232] Better error message on invalid variant --- GEMstack/onboard/execution/entrypoint.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/GEMstack/onboard/execution/entrypoint.py b/GEMstack/onboard/execution/entrypoint.py index 7d267bf3a..b1e7a8d10 100644 --- a/GEMstack/onboard/execution/entrypoint.py +++ b/GEMstack/onboard/execution/entrypoint.py @@ -19,7 +19,7 @@ def caution_callback(k,variant): if v not in settings.get('run.variants',{}): print(EXECUTION_PREFIX,"Error, variant",v,"not found in settings") print(EXECUTION_PREFIX,"Available variants are",list(settings.get('variants',{}).keys())+list(settings.get('run.variants',{}).keys())) - raise ValueError("Variant "+v+" not found") + return 1 else: overrides = settings.get('run.variants.'+v) print(EXECUTION_PREFIX,"APPYING VARIANT",overrides) @@ -169,3 +169,4 @@ def caution_callback(k,variant): else: import webbrowser webbrowser.open(logfolder) + return 0 \ No newline at end of file From 3f698bbb0ee74b089cf284e59bc2025f1187e1c6 Mon Sep 17 00:00:00 2001 From: krishauser Date: Tue, 20 Feb 2024 18:48:17 -0500 Subject: [PATCH 128/232] Fixed bugs identified by sonarqube --- GEMstack/state/physical_object.py | 2 ++ GEMstack/utils/config.py | 2 +- GEMstack/utils/klampt_visualization.py | 2 +- 3 files changed, 4 insertions(+), 2 deletions(-) diff --git a/GEMstack/state/physical_object.py b/GEMstack/state/physical_object.py index 71da16985..796f97403 100644 --- a/GEMstack/state/physical_object.py +++ b/GEMstack/state/physical_object.py @@ -296,6 +296,8 @@ def _get_frame_chain(source_frame : ObjectFrameEnum, target_frame : ObjectFrameE raise ValueError("start_pose_abs must be specified when converting to START") frame_chain.append((ObjectFrameEnum.START,start_pose_abs,-1)) elif target_frame == ObjectFrameEnum.CURRENT: + if current_pose is None: + raise ValueError("current_pose must be specified when converting to CURRENT") if current_pose.frame != frame_chain[-1][0]: #global to start assert start_pose_abs.frame == frame_chain[-1][0] assert current_pose.frame == ObjectFrameEnum.START diff --git a/GEMstack/utils/config.py b/GEMstack/utils/config.py index a50a16249..60202a00b 100644 --- a/GEMstack/utils/config.py +++ b/GEMstack/utils/config.py @@ -26,7 +26,7 @@ def load_config_recursive(fn : str) -> dict: elif fn.endswith('json'): with open(fn,'r') as f: res = json.load(f) - base,f = os.path.split(fn) + base,_ = os.path.split(fn) return _load_recursive(res,base) else: raise IOError("Config file not specified as .yaml, .yml, or .json extension") diff --git a/GEMstack/utils/klampt_visualization.py b/GEMstack/utils/klampt_visualization.py index 3b6b4a9b7..0e9219e76 100644 --- a/GEMstack/utils/klampt_visualization.py +++ b/GEMstack/utils/klampt_visualization.py @@ -76,7 +76,7 @@ def plot_object(name : str, obj : PhysicalObject, type=None, axis_len=None, outl #add a point at the object's origin vis.add(name,obj.pose.translation(),size=5,color=(0,0,0,1)) if axis_len: - plot_pose(name+"_pose", obj.pose, axis_len=0, hide_label=True) + plot_pose(name+"_pose", obj.pose, axis_len=0) #plot bounding box R = obj.pose.rotation() t = obj.pose.translation() From 262591d2237010817ae90380372d6020b3274524 Mon Sep 17 00:00:00 2001 From: krishauser Date: Tue, 20 Feb 2024 19:04:54 -0500 Subject: [PATCH 129/232] Fixed identified bugs --- GEMstack/state/physical_object.py | 2 -- GEMstack/utils/config.py | 2 +- 2 files changed, 1 insertion(+), 3 deletions(-) diff --git a/GEMstack/state/physical_object.py b/GEMstack/state/physical_object.py index 796f97403..5147c1ee8 100644 --- a/GEMstack/state/physical_object.py +++ b/GEMstack/state/physical_object.py @@ -304,8 +304,6 @@ def _get_frame_chain(source_frame : ObjectFrameEnum, target_frame : ObjectFrameE if start_pose_abs is None: raise ValueError("start_pose_abs must be specified when converting to CURRENT and current_pose is in START frame") frame_chain.append((ObjectFrameEnum.START,start_pose_abs,-1)) - if current_pose is None: - raise ValueError("current_pose must be specified when converting to CURRENT") frame_chain.append((ObjectFrameEnum.CURRENT,current_pose,-1)) return frame_chain diff --git a/GEMstack/utils/config.py b/GEMstack/utils/config.py index 60202a00b..f8800102e 100644 --- a/GEMstack/utils/config.py +++ b/GEMstack/utils/config.py @@ -68,7 +68,7 @@ def _load_config_or_text_recursive(fn : str) -> dict: elif fn.endswith('json'): with open(fn,'r') as f: res = json.load(f) - base,f = os.path.split(fn) + base,_ = os.path.split(fn) return _load_recursive(res,base) else: return ''.join(f.readlines()) From d2b3061ef3dbf92689e40b58c6cfbb1fb4572ef0 Mon Sep 17 00:00:00 2001 From: krishauser Date: Wed, 21 Feb 2024 10:10:16 -0500 Subject: [PATCH 130/232] Fixed possible bug loading text files --- GEMstack/utils/config.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/GEMstack/utils/config.py b/GEMstack/utils/config.py index f8800102e..9112107e9 100644 --- a/GEMstack/utils/config.py +++ b/GEMstack/utils/config.py @@ -71,7 +71,8 @@ def _load_config_or_text_recursive(fn : str) -> dict: base,_ = os.path.split(fn) return _load_recursive(res,base) else: - return ''.join(f.readlines()) + with open(fn,'r') as f: + return ''.join(f.readlines()) def _load_recursive(obj, folder : str): if isinstance(obj,dict): From 5ed5c8d208d62d38459b6b34e6c01692ddfc3f6c Mon Sep 17 00:00:00 2001 From: krishauser Date: Tue, 27 Feb 2024 19:30:47 -0500 Subject: [PATCH 131/232] Added tools for selecting lidar points --- .../calibration/klampt_lidar_zed_show.py | 80 +++++++++++++++++-- 1 file changed, 72 insertions(+), 8 deletions(-) diff --git a/GEMstack/offboard/calibration/klampt_lidar_zed_show.py b/GEMstack/offboard/calibration/klampt_lidar_zed_show.py index e3e7de4ce..4f8f89dee 100644 --- a/GEMstack/offboard/calibration/klampt_lidar_zed_show.py +++ b/GEMstack/offboard/calibration/klampt_lidar_zed_show.py @@ -4,6 +4,8 @@ from klampt import PointCloud,Geometry3D from klampt.io import numpy_convert from klampt.model.sensing import image_to_points +from klampt.model.create import bbox +import klampt import cv2 import os import numpy as np @@ -34,14 +36,18 @@ def load_and_show_scan(idx): pc = colorize(pc,'z','plasma') data['lidar'] = Geometry3D(pc) - color = cv2.imread(color_pattern.format(idx)) - depth = cv2.imread(depth_pattern.format(idx),cv2.IMREAD_UNCHANGED) - depth = depth.astype(np.float32) - print("depth range",np.min(depth),np.max(depth)) - zed_xfov = 2*np.arctan(zed_w/(2*zed_intrinsics[0])) - zed_yfov = 2*np.arctan(zed_h/(2*zed_intrinsics[1])) - print("estimated zed horizontal FOV",math.degrees(zed_xfov),"deg") - pc = image_to_points(depth,color,zed_xfov,zed_yfov,depth_scale=4000.0/0xffff, points_format='PointCloud') + try: + color = cv2.imread(color_pattern.format(idx)) + depth = cv2.imread(depth_pattern.format(idx),cv2.IMREAD_UNCHANGED) + depth = depth.astype(np.float32) + print("depth range",np.min(depth),np.max(depth)) + zed_xfov = 2*np.arctan(zed_w/(2*zed_intrinsics[0])) + zed_yfov = 2*np.arctan(zed_h/(2*zed_intrinsics[1])) + print("estimated zed horizontal FOV",math.degrees(zed_xfov),"deg") + pc = image_to_points(depth,color,zed_xfov,zed_yfov,depth_scale=4000.0/0xffff, points_format='PointCloud') + except Exception as e: + print("Error loading zed data:",e) + pc = PointCloud() data['zed'] = Geometry3D(pc) data['lidar'].setCurrentTransform(*lidar_xform) @@ -72,6 +78,54 @@ def print_xforms(): print("rotation:",so3.ndarray(zed_xform[0])) print("position:",zed_xform[1]) + point_selection = (4,0,0) + box_selection = [(3.5,-0.5,-0.5),(4.5,0.5,0.5)] + box_geometry = bbox(box_selection[0],box_selection[1],type='GeometricPrimitive') + data['selection_widget'] = None + + def select_point(): + if data['selection_widget'] is not None: + vis.remove(data['selection_widget']) + data['selection_widget'] = 'point_widget' + vis.add('point_widget',point_selection) + vis.edit('point_widget') + + def select_box(): + if data['selection_widget'] is not None: + vis.remove(data['selection_widget']) + data['selection_widget'] = 'box_widget' + vis.add('box_widget',box_geometry,color=(1.0,0.5,0,0.5)) + vis.add('box_widget_handle1',box_selection[0]) + vis.edit('box_widget_handle1') + vis.add('box_widget_handle2',box_selection[1]) + vis.edit('box_widget_handle2') + + def print_selection(): + if data['selection_widget'] is not None: + if data['selection_widget'] == 'point_widget': + print("Target point:",point_selection) + lidar = data['lidar'] # type: Geometry3D + pts = lidar.getPointCloud().getPoints() + pts = pts @ so3.ndarray(lidar_xform[0]).T + np.array(lidar_xform[1]) + dist_2 = np.sum((pts - point_selection)**2, axis=1) + closest_dist2 = np.min(dist_2) + closest_ind = np.argmin(dist_2) + print("Closest lidar point is",pts[closest_ind],"index",closest_ind,"at distance",math.sqrt(closest_dist2)) + else: + print("Target box:",box_selection) + lidar = data['lidar'] # type: Geometry3D + pts = lidar.getPointCloud().getPoints() + pts = pts @ so3.ndarray(lidar_xform[0]).T + np.array(lidar_xform[1]) + mask = np.logical_and(np.all(pts >= box_selection[0],axis=1),np.all(pts <= box_selection[1],axis=1)) + print("Number of lidar points in box:",np.sum(mask)) + print("Indices of lidar points in box:",np.where(mask)[0]) + print("Points in box",pts[mask]) + else: + print("No selection") + + vis.addAction(select_point,'Select with point','s','Select a point by dragging a point widget') + vis.addAction(select_box,'Select with box','b','Select multiple points with a box widget') + vis.addAction(print_selection,'Print selection','q') vis.addAction(increment_index,"Increment index",'=') vis.addAction(decrement_index,"Decrement index",'-') @@ -87,6 +141,16 @@ def print_xforms(): lidar_xform = lidar_xform[:9],lidar_xform[9:] zed_xform = vis.getItemConfig('zed_xform') zed_xform = zed_xform[:9],zed_xform[9:] + if data['selection_widget'] == 'point_widget': + point_selection = vis.getItemConfig('point_widget') + elif data['selection_widget'] == 'box_widget': + handle1 = vis.getItemConfig('box_widget_handle1') + handle2 = vis.getItemConfig('box_widget_handle2') + lower = [min(handle1[i],handle2[i]) for i in range(3)] + upper = [max(handle1[i],handle2[i]) for i in range(3)] + box_selection = [lower,upper] + box_geometry = bbox(lower,upper,type='GeometricPrimitive') + vis.add('box_widget',box_geometry,color=(1.0,0.5,0,0.5)) data['lidar'].setCurrentTransform(*lidar_xform) data['zed'].setCurrentTransform(*zed_xform) time.sleep(0.02) From 80b9f970415b3d71625f36304dc9b8a05c673474 Mon Sep 17 00:00:00 2001 From: gem Date: Tue, 5 Mar 2024 18:45:17 -0600 Subject: [PATCH 132/232] Added GEM e4 model with hand-calibrated stuff --- GEMstack/knowledge/calibration/gem_e4.yaml | 7 + .../knowledge/calibration/gem_e4_oak.yaml | 3 + .../knowledge/calibration/gem_e4_ouster.yaml | 3 + .../knowledge/vehicle/gem_e4_dynamics.yaml | 22 + .../knowledge/vehicle/gem_e4_geometry.yaml | 11 + GEMstack/knowledge/vehicle/model/gem_e4.urdf | 919 ++++++++++++++++++ .../vehicle/model/meshes/e4/base_link.STL | Bin 0 -> 801484 bytes .../model/meshes/e4/front_camera_link.STL | Bin 0 -> 1884 bytes .../model/meshes/e4/front_lidar_link.STL | Bin 0 -> 684 bytes .../model/meshes/e4/front_rack_link.STL | Bin 0 -> 12684 bytes .../model/meshes/e4/front_radar_link.STL | Bin 0 -> 30884 bytes .../model/meshes/e4/gps_antenna_aux_link.STL | Bin 0 -> 50684 bytes .../model/meshes/e4/gps_antenna_main_link.STL | Bin 0 -> 50684 bytes .../model/meshes/e4/headlight_fl_link.STL | Bin 0 -> 61484 bytes .../model/meshes/e4/headlight_fr_link.STL | Bin 0 -> 61484 bytes .../vehicle/model/meshes/e4/i_logo_link.STL | Bin 0 -> 2284 bytes .../vehicle/model/meshes/e4/imu_link.STL | Bin 0 -> 684 bytes .../vehicle/model/meshes/e4/lightbar_link.STL | Bin 0 -> 13484 bytes .../model/meshes/e4/rear_rack_link.STL | Bin 0 -> 12684 bytes .../model/meshes/e4/stoplight_rl_link.STL | Bin 0 -> 45484 bytes .../model/meshes/e4/stoplight_rr_link.STL | Bin 0 -> 45484 bytes .../model/meshes/e4/taillight_rl_link.STL | Bin 0 -> 8084 bytes .../model/meshes/e4/taillight_rr_link.STL | Bin 0 -> 8084 bytes .../model/meshes/e4/top_lidar_link.STL | Bin 0 -> 42684 bytes .../vehicle/model/meshes/e4/top_rack_link.STL | Bin 0 -> 13284 bytes .../model/meshes/e4/turnlight_fl_link.STL | Bin 0 -> 66884 bytes .../model/meshes/e4/turnlight_fr_link.STL | Bin 0 -> 66884 bytes .../vehicle/model/meshes/e4/wheel_link_fl.STL | Bin 0 -> 476284 bytes .../vehicle/model/meshes/e4/wheel_link_fr.STL | Bin 0 -> 476284 bytes .../vehicle/model/meshes/e4/wheel_link_rl.STL | Bin 0 -> 476284 bytes .../vehicle/model/meshes/e4/wheel_link_rr.STL | Bin 0 -> 476284 bytes 31 files changed, 965 insertions(+) create mode 100644 GEMstack/knowledge/calibration/gem_e4.yaml create mode 100644 GEMstack/knowledge/calibration/gem_e4_oak.yaml create mode 100644 GEMstack/knowledge/calibration/gem_e4_ouster.yaml create mode 100644 GEMstack/knowledge/vehicle/gem_e4_dynamics.yaml create mode 100644 GEMstack/knowledge/vehicle/gem_e4_geometry.yaml create mode 100644 GEMstack/knowledge/vehicle/model/gem_e4.urdf create mode 100644 GEMstack/knowledge/vehicle/model/meshes/e4/base_link.STL create mode 100644 GEMstack/knowledge/vehicle/model/meshes/e4/front_camera_link.STL create mode 100644 GEMstack/knowledge/vehicle/model/meshes/e4/front_lidar_link.STL create mode 100755 GEMstack/knowledge/vehicle/model/meshes/e4/front_rack_link.STL create mode 100644 GEMstack/knowledge/vehicle/model/meshes/e4/front_radar_link.STL create mode 100755 GEMstack/knowledge/vehicle/model/meshes/e4/gps_antenna_aux_link.STL create mode 100755 GEMstack/knowledge/vehicle/model/meshes/e4/gps_antenna_main_link.STL create mode 100755 GEMstack/knowledge/vehicle/model/meshes/e4/headlight_fl_link.STL create mode 100755 GEMstack/knowledge/vehicle/model/meshes/e4/headlight_fr_link.STL create mode 100755 GEMstack/knowledge/vehicle/model/meshes/e4/i_logo_link.STL create mode 100644 GEMstack/knowledge/vehicle/model/meshes/e4/imu_link.STL create mode 100755 GEMstack/knowledge/vehicle/model/meshes/e4/lightbar_link.STL create mode 100755 GEMstack/knowledge/vehicle/model/meshes/e4/rear_rack_link.STL create mode 100755 GEMstack/knowledge/vehicle/model/meshes/e4/stoplight_rl_link.STL create mode 100755 GEMstack/knowledge/vehicle/model/meshes/e4/stoplight_rr_link.STL create mode 100755 GEMstack/knowledge/vehicle/model/meshes/e4/taillight_rl_link.STL create mode 100755 GEMstack/knowledge/vehicle/model/meshes/e4/taillight_rr_link.STL create mode 100644 GEMstack/knowledge/vehicle/model/meshes/e4/top_lidar_link.STL create mode 100644 GEMstack/knowledge/vehicle/model/meshes/e4/top_rack_link.STL create mode 100755 GEMstack/knowledge/vehicle/model/meshes/e4/turnlight_fl_link.STL create mode 100755 GEMstack/knowledge/vehicle/model/meshes/e4/turnlight_fr_link.STL create mode 100644 GEMstack/knowledge/vehicle/model/meshes/e4/wheel_link_fl.STL create mode 100644 GEMstack/knowledge/vehicle/model/meshes/e4/wheel_link_fr.STL create mode 100644 GEMstack/knowledge/vehicle/model/meshes/e4/wheel_link_rl.STL create mode 100644 GEMstack/knowledge/vehicle/model/meshes/e4/wheel_link_rr.STL diff --git a/GEMstack/knowledge/calibration/gem_e4.yaml b/GEMstack/knowledge/calibration/gem_e4.yaml new file mode 100644 index 000000000..da971c253 --- /dev/null +++ b/GEMstack/knowledge/calibration/gem_e4.yaml @@ -0,0 +1,7 @@ +calibration_date: "2024-03-05" # Date of calibration YYYY-MM-DD +reference: rear_axle_center # rear axle center +rear_axle_height: 0.33 # height of rear axle center above flat ground +gnss_location: [1.10,0.1.62] # meters, taken from https://github.com/hangcui1201/POLARIS_GEM_e2_Real/blob/main/vehicle_drivers/gem_gnss_control/scripts/gem_gnss_tracker_stanley_rtk.py. Note conflict with pure pursuit location? +gnss_yaw: 0.0 # radians +top_lidar: !include "gem_e4_ouster.yaml" +front_camera: !include "gem_e4_oak.yaml" diff --git a/GEMstack/knowledge/calibration/gem_e4_oak.yaml b/GEMstack/knowledge/calibration/gem_e4_oak.yaml new file mode 100644 index 000000000..cb9a6c0d0 --- /dev/null +++ b/GEMstack/knowledge/calibration/gem_e4_oak.yaml @@ -0,0 +1,3 @@ +reference: rear_axle_center # rear axle center +rotation: [[0,0,1],[-1,0,0],[0,-1,0]] # rotation matrix mapping z to forward, x to left, y to down, guesstimated +center_position: [1.78,0,1.58] # meters, center camera, guesstimated diff --git a/GEMstack/knowledge/calibration/gem_e4_ouster.yaml b/GEMstack/knowledge/calibration/gem_e4_ouster.yaml new file mode 100644 index 000000000..5987373a6 --- /dev/null +++ b/GEMstack/knowledge/calibration/gem_e4_ouster.yaml @@ -0,0 +1,3 @@ +reference: rear_axle_center # rear axle center +position: [1.10,0,2.03] # meters, calibrated by Hang's watchful eye +rotation: [[1,0,0],[0,1,0],[0,0,1]] #rotation matrix mapping lidar frame to vehicle frame \ No newline at end of file diff --git a/GEMstack/knowledge/vehicle/gem_e4_dynamics.yaml b/GEMstack/knowledge/vehicle/gem_e4_dynamics.yaml new file mode 100644 index 000000000..d20d2c357 --- /dev/null +++ b/GEMstack/knowledge/vehicle/gem_e4_dynamics.yaml @@ -0,0 +1,22 @@ +mass: 300.0 #kg +gravity: 9.81 #m/s^2 +longitudinal_friction : 1.0 # unitless +lateral_friction : 1.0 # unitless +max_brake_deceleration: 8.0 #m/s^2. Deceleration at max brake pedal +max_accelerator_acceleration: #m/s^2. Acceleration at max accelerator pedal, by gear + - 0.0 + - 5.0 +max_accelerator_acceleration_reverse: 2.5 #m/s^2. Acceleration (backwards) in reverse gear +max_accelerator_power: #Watts. Power at max accelerator pedal, by gear + - 0.0 + - 10000.0 +max_accelerator_power_reverse: 10000.0 #Watts. Power (backwards) in reverse gear + +acceleration_model : kris_v1 +accelerator_active_range : [0.2, 1.0] #range of accelerator pedal where output acceleration is not flat +brake_active_range : [0,1] #range of brake pedal where output deceleration is not flat + +internal_dry_deceleration: 0.2 #m/s^2: deceleration due to internal dry friction (non-speed dependent) +internal_viscous_deceleration: 0.05 #1/s: scales the current velocity to get deceleration due to internal viscous friction (speed dependent) +aerodynamic_drag_coefficient: 0.01 #units in s, scaled by velocity^2 to get deceleration due to aerodynamic drag +acceleration_deadband: 0.1 #m/s^2: minimum acceleration to be considered non-zero diff --git a/GEMstack/knowledge/vehicle/gem_e4_geometry.yaml b/GEMstack/knowledge/vehicle/gem_e4_geometry.yaml new file mode 100644 index 000000000..1d671864b --- /dev/null +++ b/GEMstack/knowledge/vehicle/gem_e4_geometry.yaml @@ -0,0 +1,11 @@ +length: 3.2 #distance from front to rear bumper, meters +width: 1.7 #widest distance from left to right, meters +height: 2.5 #meters +bounds: [[-0.35,2.85],[-0.85,0.85],[0,2.5]] #meters, [[x_min,x_max],[y_min,y_max],[z_min,z_max]] with origin the ground point below rear axle center +wheel_radius: 0.33 #meters +wheelbase: 2.56 #distance from rear to front axle, meters +min_wheel_angle: -0.6108 #radians, 35 degrees +max_wheel_angle: 0.6108 #radians, 35 degrees +min_steering_angle: -11.0 #radians, 630 degrees +max_steering_angle: 11.0 #radians, 630 degrees + diff --git a/GEMstack/knowledge/vehicle/model/gem_e4.urdf b/GEMstack/knowledge/vehicle/model/gem_e4.urdf new file mode 100644 index 000000000..c2b1bb728 --- /dev/null +++ b/GEMstack/knowledge/vehicle/model/gem_e4.urdf @@ -0,0 +1,919 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/GEMstack/knowledge/vehicle/model/meshes/e4/base_link.STL b/GEMstack/knowledge/vehicle/model/meshes/e4/base_link.STL new file mode 100644 index 0000000000000000000000000000000000000000..952b788ef6efa9898c3a7c02af38d56d5aff00d7 GIT binary patch literal 801484 zcmb@PWq1_X_Vo*i5cd#*1|2j&(4^1C-Gc{$2A2c~79hbjKp5Ozg1e>b;O_1+gEK&I z2=?w%33FF*FaJ;Pe3+*n*81gicUA4P>PWSw{r~-MzQDg1C+{AdDEI80tk<|dn65`n z`uDZ^_sOdhg!*@bh)d;CiJuA*>h;fm|Jg>IRIkSVl_0M!%PF@M-%0BaOfg=c4%tnk z?@u;fUu(BFwGH+fL>wweeC!%;5dA!o%!Gynx|+bvsWG{aEdrCUP> zU!=aC>b{O%$ILYT{oJJ$zqEnG^dhOmu=(puwE2_c-$mkb=yaov29BG4X#)v#HSCs3 zKpCb+xB%;=)9@)mVcKp%?66nICX|xfScFeU; zKL!}@*Wz%LLXu+seVr~-obh^n)Zx@N{v}XBqUW4Z2GQ^0!C&4Lo*5mNrk)vo2Xy+c zvxMJT>Y0cN5(}cn8f`dN*#Ao#NTBPt?vyb+tpU2?m>zdj$`9@ zJ+pTas34(UDFL!j+rqmAOx9VIGA;I*P@za!9<_L@?!!F*fojc>PQ zpXL%3B=8E>wBHfvN_$PIwdCaVY(^Vf_SKZAAc2)g(|$*wEA2I@YNu%j9u_y+nB`Me zqJjk0%HI>{N_$PIz4OizRgE^birf+vB+R|R?+A3Iy(X0(H0}0{rbZjZ0v#nPNMP^t zdjef)uPL=x8@(aIXd`#_zjRcPz&=saen+4y?KP$L&i3mgjW+hiY|v3b0{eDN`yGL< zwAYlHGKLHpXtYtQYJVLSBrv0B+V2Q-rM)JVgEZ~bprJ+^-=kc0RFE*&#NQF+ECnaD11-ZK$~PqO_Snm-$_#5!z2e^_;2~MgseJ zO}of#glt<^sv>`mYmX+%i(U&w_7yQy^>~6j)6+#xt}~g;cV4diIm$YH+4ipFI)Mrj zD+VP<+ZGOTUe9>`1R0r#h%2%!Fvv`xt3|s>vflnRdO+wfCLZ#;a=Pxk^)3^ruGZF_ByA6_5icGLHGOZImYzTPjC4OrgfM~M4-$CxXxd-g#*xq^ zC7=I7pi3RWZOL9~X{iene|}#RG`q|?feI4lGZD`cB+#Y){XdB;H7TavrD9e?7t-cr ziG3~hiD`GpWV+i{XZ+85XG1|E?H-QQeY?30bYY+Pdjb_Cu(va}fdsnJ?sw_mJK;FK zXpQ%W3KH1cncF}DU1@jWq{ahGL>zv*_>E$UG83pEk#?U*|Bg&Bmijr6Ko_P#a~r52 zk#?U*raNKd6Cr^vOtq#qH2i+BZ~w3FD(>g!Km`fxwaslHfv&XsD>9AAsLv6H?-xG@ z-T|1}h(iU5v=Id3zQjamNT3VvWXuHK38md_8@-IV=S*c%k2xwxq}?Htx^FkPfdsm+ zpEnbzAdz-YO{TkTqctSZg?Yu?1}aGW_6TZ7pbK-Csf{>PkiauW(|&kINyXI+TBoaT z^hjTCqlT;3KYRT+eywVI;!bt9Etz=Ut3$C(rPk@FAaQW;w0{$ariG-nF|}+eQS5JT z<8L8d_s?mvz&8(>b)IUY91|nEPTIPJ2~?0Ux8dg#CCd(IQet;WGl8zxp3{s3pfZuB zz}UWU;fkY8vVK4cPDE5?2D};!lq6 z_rml^|7I=xe42KiKlzHVmD}s^F-HXn^T_tMwC}3P|M=uT$G`D2sUukVxz8WNOOz9f2-o!=Aa!fdB$H*6XhZJY@5CRC8X`JLYr=)$a} zX&33OrB(zI)c_K5slBCojdwCX-C7(M zAc+dzvEX0&m*5xXHju!3pWhScO3PiwyEPN2q*XY>^g)a5) z|G9&7oM6#Q-%Pe{KQu_TvYy)W=-T6I%E=*^s zME@o!mT7!EP(cDmseVtO%bfaLL)VE)K}C}ioT7|l{xkbvZZ}`&T7h+`^HG_jBwh!< zULQY`tfozFvd*aOE^bkTf9uyae%9mvCVnbNsMkO5OEhhM;5sp8W`1kCTal*PjxKX8 zX+77EW>sHg{p(_Fi3$>UC&Tw0P1cH#`)90YulF_)=)yXtX`7m^5+mP5=}#(lGgUYw zuvTiC=T<+uSbc$hGo!^+MUlWfuW7HZ%@_8~FY23ShM5R-;TWl=y}K|&BzO9%58mHU zq6_a{%*1>qUNbR)2~?245mvrq2@Mcs({pA&8f~i7cwd7xSkoFT4%Qo=&Zj>vHc+C1 zggW2;b6$Pew^lfOm}q@CHqu0(3(rbTyBD-fysfrO|2wv$>0ROYF1Dv>4o&8XGGA}$ zvj?@1s32kfK*8X`M9Uy63pi`FG_FgXfRVYROO-$W3s^nfKP(h-etph!oGe^w38u&dUVU325%oBinXtwMzpz8xWoZ&qrwAU zvKF?Aj7K_<%T^z{6Z%S=v$mm#C?Bf0Qx{2h!Un2C(@1_xed0u>}0x_Hx-J1@oAqAkBxQ;!)4o}5#jZ(X-DHH>l-Im)Tg>f$$Bx_jI+A%_?nbF&&#-q9_Or02_>@`ugA}< z!EIRAPSw+2SYvTp*-xT^MAyAuMrCL=u{INuiFfD!n?P5l&};^gqSa*Lt;;xl=!7j| zws$9q3KIB@a394)-2WiZ)&6QW;~SZ?uNJp)bbB|w>1H2V)vuaF1qt)Fn$rJBmEkmUQf1 zX0j}f5Y7oLs9Z!&`nsx{_|zekKl$6-jjioB$H)?GO6un(cpJo>i(!$#%mJZnYX zCAKGa=EA|FVE+c9x#|G2%6KE=v` zRXQgjfiC~g=(?Xfhe71dt8${dPc!}T`$F>Ftx^&dB(Nt+B_1*H z{ucsW$$7FHz1o8#sy`ony0`8S>L#5I){>|oVeZwo#t+wnxmVk>D$GQn3)6?D^?o&6 zPigW%U%e;HluM9U|F@UXCr$}bJUPIqKKHk(+TQxLo^<1RtlTo%AqfeSYkL-> zCNAHn>eZ}+14BM7iIr2DHnM1-AhD!QZiA>+T2-HB>snZ5_m7eLoXQF$&}FXeLnrUG zOz$&5j?Nn`P(fnK-aJMxQQcMb2Gxh|whZO|V-)uvNT3Vryrwk@^c0;ETgg06KACzP zB(|r|NBhG13B6q>ZX=Y5&P?R`g+SLvXCH%@>ero#85J6ehXabs0xtsz6(r7O%1@1U z4j1!oc4cB26W^I|`Gr8&NiSc6==EnWCT^UJ6)nrY(GS*WPN*OeZp}}xUQ7`8%lBX+ zi3ukrZv8@_tNAfsgV_2;tzZ3PW4svd(MHcVr#GR3gp*qVIuoso`A+6(k-H&rj21)`){q>IjB15&1s|blsoiYY;R3P~TPj zvfiS^csH85s1~7u#KN`tsC2e1!frvA|ARo+oE<&}alNtnq4q4LsM4G(>>Bu;Hc-fMg*cl#8}xKYh$GLM(Ue*9v& z*0d25&6iary=8XVv%uR#pewwVFWsH@-I8IwYGd%+_hQMSw$!Y`h+XAQc~i5I8N|)f z&FT0y9)}r|PPBT|j56H!reRGoi2ILJ8-0pprz_cOl6?Ln2^Ay`-SVM@w&}#otEvrg zJw*6K^X?b^8?R@0(d#xD#l~69>GC{pYI-PxSW~Sz71-`&91qV}l`=wS$5O#IWvn}z zI9i@Pa-vmrSBQs)iqrmwPPEx?g}BPE*FJEfWv7;lcbkhdG3`+-%?@~wRC9*s9#oJ> zNphlViE~7+J&LHYqdRSp^Q@&_925m6I?)(?g{T}_lAf-0q8qDMhKh zF)2t?E#yRzPgaP*pGz`vJ?5OKoTap0pjm`zy!CNzN9veur5OD_h?-vJ*Hbo#=omFR zxOsdawGGWFY}1#bEDs%NVo1Cw=^aEP$2!u4JnHYrG4^L3;Y_ju9usQMf}DPdIPx~=%(@=YZ2x0t2iDAD|NNh&zYi9BY+i-3Ph z&srLKy^5UOk^_9E*=*H7GV*I#pYIM<$w%2(p>JAL27EAr< z^7*&IBfbL@wZB%Pw^Opn;*TRu1iA{h^`n9JUyCez)R^VQqOZiQ4XtI-2c`AyZkegu z-><~Snr+DLWo8=wF*COv6)keM0%v8g!s>vqxm zYkm~}A;r?Ee`_i-B{LPD``z+(V{1ARm4#+~`f54VOr<{e!>%;KwjLcmSVcz#iAmiu zQ>L*$ED!goESj#S3pFcWpNgNUXd=+nvxpykDwAIPu|TzP=2S4*UCl)+n#G#l6}HzW z*pG&G`edg&fCo1&}r-Y(D#(RGh+kyJ5^`#6GGKfbu z>MSWY`mz{Qq$3T19pCn#7_oL;W>2*|)SkT;;ihoEa z-WFBo?(+#1#ht2yX^pMbiUhjM?IbLn%wq?N(HfaBu2E1E!=G^+y`l$MVadx8}?V8?Kys=Y6_x9WLabuQ?5Sw-; z0$nR>+f&iqZA3=ja!kbLD=9aQtS$Uj79&)U@GELZE6TMNJ^^K!c$%w}tk-t9`24zn zi9lCaiXBb*R8u^;RGx`!GkQufu(_qvfh2(n5>un>Xl`UR@qWH~S4qCTWXQqcmh1I) zn+SB>>19v7J%U8y`w%9&g~rICM@jF|+}?r;5CZg6 zm#&M=$l+dE<0ckVuHLyj+*t;uFD(l{zoVmq#E?K|x|Z2N%Eo*aIagfJQ9+_idLQzA@wX-4dPPKBC`|bS3&_YzYfS{Y z9&vuKS$)IeS54*i5^fRnPt-g;VCgCy6(n91&rI_+Ke8k?Rz!z=o#~t1LfyXa3=@H_ z_MFb%mjBx_^;#r>Hjm(z%6T}=eKu&(fm_*KQ_lX~vLW_u8!f<)hVTMF0`C9LU7a~qSn zUajGJ<;e9433Opy;XBAeJ*9J{f|i0)r9cIVnhR~ITv$ud_JV377uPFau2)UCULk=l ztSg!}{PGYv|3ePF(?2akP(i|DiX9bnt1K*)RTWkBY7EyaJFZtqpbP5?k1hRZB`e3B z)gv6{>Zl;my+tM}k+Fz4G)dLn%3QB%aJ`D-dW8hKu&!|4t?4QId<>A012afeka%>_ zkxtL^6N`>pxQ$a>ugY+}>dy5F33Opy(XnJ zxn4Epdgbh$-bA1a>k7|?XBjSLa!s7o!b_rpgx6+w+CA&L#rK-3aPzocHRF19mg^M~ z=)$_fck~-`(X{&hvR1*5Ix0vU?96K>_P?>bs-P;|M6Orgxn9lWdW8hKu&(e}Uu1h4 zIcugqyZvq*6(n%%MAJ%hy}HQtDj(M?B+!MGhp6k7nbpVsVX|MP$w#}?v&`dvb2t)LpYvbAg zbDt9?0$ro;c~IDZ3}UOd>d!0inK+ft#M*o&qJjjTl|1?}CM(tJ?k}Z6}5n`C{&QZt4q^9X6+(WWf;({pou`&!!T!~mh5VxYRP7<49&PQ z%;U;{3KCc)c%5b42Ku=sCFFpdfhGc7$L2ZE)JBDbmZ*|t&$J2`#T5<}B(U0XO&pO~ zib>A0OMthDK-ZzV_O!J}1u;H@O5tU>QrF>1J)SEyDo9|}*0e2^+R8-F^?Lg3n@j|{ zJht1?qxsFm>vpQIRXxsJ?s3*}kAn&l*!yT&ao1ro-I6cX9l_=HB7rXdPd4;sY;Vzg zu^Nr~T(GAs&pl@&?m1CG0(((Sdvv3R4A1p8V4f&``- zUa@r}QNPyT*OHPu%0!^+7~g+%oj*qm`JvkI?N@>>X=SKHoAy>5`NffD94XecIlIGn z&ftp}e%((;1qrN5nwH~I8*-TaR`@qQWJLm9DGuJ$<7GyXw~|`#lb7q&QLa~RT(3|; z0;>{_!?hkjcj?R3KCeAG;NCROZEBAt82+@5(#u2z3*b& ztJQC&s?R5=SEwL?Rf*Rp_Guuxa9S$gQ%EGxbu_n=QGNVMtLlUG3Kb-RU3bCy=uqx z%4NfTfeI2>mH25SD|^U`#V3bs@H}WD(6#2O4f#!&EFRBOZ9L_AHIeJpYpz$QAc0kh z#{fzO%Ji-FhJ-IHXClxw?u9K4SvE)9>93AQDA%h$2KZXualJwX33I(V@48k$_GqAW z^zld&fv%+!?a8+Aa^Y_DI5if1uvRS)DSa!h6uD-4(xsd)L~Q9MRKwlFm=hd3qY15D z>_&D+o{1|v)H=(s*WdMf)@m~1-eG|X5{>G((y8(P2(KfGxH0FoKD4xud9=4C0$nM8 zJJSU5M6}4D^3_hSYBGPV=lU&iSD=E#$~R6FyyF?yE45ChS;0!uv;J*8_ukJY0$mkm zI8uM_hoYLTs&FssMao8bcUucIN))Id5meZbLU%tF>&vOTiP;l-%gr*;+BasSi9pwb zJDF&vevj`tRlX`?KR^y>IYg9cvCD!A68YU6D2vnIV({JyOq}-_B!}1-63^FjW6F{|6`>c4J^?>qJl(dgo8okY@mqDLr3c6zFZS`!op1iy85ij zM9V%~Me^xDCcX~NE-W>Uh`H;!NK}w$SI&_N#9BqoPl`CV-a};HpCFu8^)V6Xn!eG2 zN<7;v%H}J^#8V%8`X{l8c$>G8LeE6(S+G`W(CLL#bp_J*3P@Hxq%b^h2EJ z?(R9F#%}el8tsmuYA3X$;X&nfRFJ53#EG7)pCf{5t9j>RNilRx&JW&WVkc0Ko4dU|JU$htafEvO)Y?eR_| zn^@Xk?QT*@`$Q9gE}U1_w1)i2H}WT6!k-)!B=B3{x$QYI)Y*PjQpvx9O$55${^LX+ zCu|ax%cxJjfRErnK7zaW2%>@n9!(zK^=VA41|PP#ly^1}=-M~MiP|kn5>s}oHvZ-_ z@j0J~ANfo~1qnPWd2MY42Rhv(K`g&q%S52-+B-*TI{uhw&_`W^dHISe%~#ZNzM@b; z0y7fvz$S9H>h0Z64ECqiVif;R3kA?coZC3KCfDcz*D)yUcYZKRurFO-BMH7guUWuGFX?fmK`67H$ib;Cs~GY zkCTmioJri{pn?SUK0Jneq@V10Zk%`#{@z5OYrzaBS~2m3u+daso6J4u)jYec0o-$< zf&})WJcgVzN@`aRS+gEnZX(c?t&7Cm*jHlWEH&aaXHQn$|3iQ2G$f2a*?$xyFn962K{IFFZo~lT>fOpjpv$~#YxcDA zqWh6SGI8{03o1yo`Q%Oed|rv=u`T#r(PZ8mRaaU+)UPjal@3-rTnEInGF;&zxWX0X z3Wo|3SjRLirF9IgS!iReXHO;qU9EdN)AzW&qIt4fQ*?wYTr;k4Kgu~vRFJ?r#^0__ z6FSn!RvfsN$wZ**Y&B={?|f8j%%d{(I<9bsxWbL(3Wo|3SjRMNsf#nU+qqp>T2wR< z=nA>(WTYk6iK<@RNULzGxx%4>1lBR0`Ds%@ln{eUv`vn z70Xk^=u0L7U4w-aZ7lnb$knWh`W#&0g1N#;u5hRzfpv_}-HY|)6FV>JxATb=33Pq9 zlf|WyYWLY~u5hck!Y$wmhYAu{$9R4)tdFc6oggOm@)t;;>!!C0oy+k?%=A?C zY6@4lJ6z!cxWb`=1lBRWqyH8qo31@=z4m&ci9na-nX9o1$#%V}S3kJI9pegDo+}(G zNMIe)wDmFdzJnf6X`6^ z+0>VL4%IUe=&I-BP1`agi(-jt)qOet7IZ1ePp|Boo^bshu2nRz1l*K$Ankj5#@f%m zlRyOttV)_T&|v^+yK?9bcbb_9bj5FWrcq7yh)11NWl;5M71ygUu2-lafmMmeknLjV z$>CDgvhymN2y`9I=|bz?9u^&HsPWyYT(8b?y*kJB3Kb-lG?UV2#l<+fPk|AJ>vy`^%XKbgf$NY*ZghH&uO>Rjj2ualNX}^$Hav zuqyHT-F3xu%Z1uhe1eyWKv&xd&Xl?C3$bvzT9;9r>(vsjSChD2p@Ia~7`~zk+sK3O zYtogNRVD&mt&*InTbnmxM|-uuwj$T7hg`3^aJ@nW39K=E$1<~~e94$GYwu94p&HH&8PT4bo;BP(cD`2Y6hxizoHsbr}`!6p~1wYcW?iwUQ%CRW)x=iDw#m z@JvHlo@qb@37j2Jxjk3}^DICi-v(v^<|8(GIU4f@WtONO2WJ{k!M}_13H(g*RfBc+ zlIi5+SD_LKbR{HmVyoR)w8*T+0K(E{8iw#p11d=1e1fL+ot{%J*|l5W+%wQbpzEb> zOLwkz7YlSXmNAlN8vf>)hIpQ7Km`e$9niGBPdm!=9V_W|XPz|?=n9--L;vI%A-=_` zHh#`DjOo)q2^A!8K7rS;%#M|b`5IXZ)v}rhbh(Gv(AScaMXNmO9>! z3Z8Y^QlLU>CL*Fwi#40O%Ft_btf(MS<(Usvk2q%8v`P`zBCVoi^{#SP)p9x#=o(VU zn@VRnWm&YZ857f6Zb-^fJywqB@uw9PB!({YG>9=lYA?X)TA)l;B?ga~#r=AGM}QEBODvuL@AYx@J|M;0W|RqC39(HqRk zrbfITXN#06_qJP3FIX#3LBhF;Bky?1B9^~Z#E9_T^2v>rmOkq?nFw?h&g4LSOBWF9 zPpEmE8|y5xY@eed+}VjxLE@4dk6G3!EG9>*J}RYGdD&t57LhxnuZcic(;t~ASAByIl3f zQy*hJ^|UP^cDzR-rE)z&1&Iv)PW19leNpSFnk&jODX(SI;jiLU`*0J1u3;@5=}5-* zqENW%)jGx96YH56Ua>%7lPt)X{W ztSZAvmul3SSHvfua3oZacvZmJSVO@B2eeyIB=)%2OymBCH0KMWh zEdGUCnRaap@IZfC7$_7STA04^*PgUnu$P{O+QbgUe$QhklR=q(B8U|D_mu+aHt@GRf%)^ z!)?|JmHNtN?`E3_bXBk9W~@D@BWg}~KUcU+T;cL_g+m1itV(>xvhasqmsfw54IF7A z&~>+!v$0^hFsHwMpi-iVKv&$fOjKiZZjtVsnnfPX6>c|IxDH(5 zP(cFgn5Mnk)Jq4z?t}!oJP$f>Er=FQ;c85#Fju%J zCZf2)p@Ia~G2YMV`%)0^D;gcr%tWBeyf5`ESGXHo;r4TdLj?(Qg&Ui_7JdDpiN^>1 zOa!`cPb`ng%&JU{n|-i2R1GlgmPNw6ll5{5jp~dD5VtP1Alwy;J0kGi@|~CO8*zPC zHu1wR-1M%HFz=gi) z;97zNy09woIx^n1HH3FlYvbSHTXXIU5s33tm7kCXlXSlqa;d*k0 zLjqlx?fBfi*^ip`?q_LMVVWuRAz|LrFetVkMRmGni9QlS^3sP(k9-M-LbV8tl#HBYb#%OJqS&B%>QdJh`vDdoS9-0Vr z1yAAG48ix-57azow>~fR?wp&F)_xPHAo2JgepeHGgw1%m-N%u2Ne(xGA#t1mxUCa!@Cp@KxSAXl1uEkHzeRK)X)CzCQ=sYK&nb|!`mxlW3S68c+*&K5fK7rv z$}iY@Dy^*S5LKG^z`Ql>C0NqYPZzMC9In%0!^+T~S+OePWaOYMgrX@nLc)ulH$u zqjnN1NYu${Ypf8G#`D6r93Lt#@cj9mD%Hy)fvz2=ZH*cC6MfX3*MLer<+>xKtQ}tK z0u?0Qh1pTn-iJg%tGWhvZs{p6R_|c-N!e>6(ABwwJvDuBS`3_~?oyX*EG2hc9;UIt@XXiUM4&6`u$Qr?;cR}@JKuiUo<7!mu2)NJ zYefZ#;LhI0ipD<%tI_jiXTs?KuilyV@vezL7d~5vQ+S>Jl#6HFf1Da_dg>4o5h*^# z9KB7MP;TSavVN4l(lzUk)00dDy6}ldyhFNVl9sD$G8?I{Z$byc1X#7b zw=rWf%U@-<+nf`Zb50E8oQMh%mXt!l=^n{(oL z&WTewC!&G`ra^vY=6;eT`EKG-ri~UP(A9m3tMSx`f2OGK%9V5CNzRFbIVYlm1g1eA zTk0Jthw!f7sEAS~0$sg!I2-$fubxxK{3z$df+tQ|PIFE~1qn=pygK@yNLh{N&-<%i zih#d`t{S|uU(LA34pHasSI&urIVaZQoQMh%nC+OLin3Sd>tgLcKTHI=s#oH@0Nb*Q zCBxJ;*qd{r%l={%$T<-eBrpx~`jYNf^id(XsNI14CIVgeW1Nf(mu0I;eRVUW=EMn{ z6H!3|(;$!5E-$icBd5MbVZkN>T^G_hQ$YujW_^2dUm*I_JcqoD-{ZPDBL>OoN)%^hPDB%i}(^-f4scx{e%j zHlFVz2dZ8zk#k~8&WSfUC!&G`ra`W|x1;G4KVhR|a&;4du7t_X#xpq*l2z~gnsZ_$ z&WZk<6H!3|(;%=_O49BE zElmWvEM*<2@)`cElxZr%#c)ovPbp}9#5oZaBrpwXTB-83Vl8L5^F_@Bx|STWH&WlZ zGr#6URFE*GL2YTr$$E|s)y0gHkrD}X-TTvyMu{!rNLQ5;Cvi@!#yRl}=R{PHz%*_j@@H)%zxM?9spliZfJIauB zRyed%cX#_ZC)TRg!TR#^UV#b{mUR6+zK!e=yH1JY-G5WYgOv=U-2W!kyGCh&WWfXf!U7dSZ+mGM|0|% zQ`z1`peyi%8|6!RD7^Qp)YtgW^&*;yv78f8K?2htKW?eoLUH|iglsW-v57#}*hQYk z-dDd%D)l*YP8`lTaS!K2RFJ?lsA=_&=A^s4$0TF>Fbfjs!lzbh+9J-0mpCUj;+%*I z66Ty}v$zF)xBaefIT55Ifi8TOChu`C+mL)NJINaxi|ME!VSb+FKwep+Qr{R}S%a%- zFf-x`7;~~j1qn=p{Dh6L)Ri^ecx4R|=)x5+npTaIrJCDr!O0R8Brpx~GdXx=%_|f zS&EY-Do9`&kscf&}JAzMJ5cH9@?xCX83sAb~Di0mIKWmKRFJ^@$m8u(w}fO$TUmnyx^M*y?>OXS z>Bz(?PL`-3foYKEig;zsN}j16#w%-(Ko_on;hM0-Pwd0VQgE`Y#mN#CBrrenuC1dvWHsK4e066L z6M?Q}i|vfv%U^b@vGAOnEH84hY{JPB6(leX^0UH5w~=Fbca7D5t%*R_-zV&h{Ww#c z)%ubroGhPkvJ4$IEd&)LFhBDB`Ln_DYmVyTP`B(BB+xZ+i#^3`zb2;KP;(Q`oGdSM zvV6hG5)~vcKk|I-^LELQMp^%)iqR$;t8vC(D~{!YrsD zfoYIy;)%@E=0_bF(4(Fe33TCaL@+TtE3L^7nzK?MnXmJMeHz6MwEHCT|ZK_t+HS2O=656(sOkHat4WwZw;ONj%pQB+!LbiDxbODK`W8DK~zb<1DBkfzPtx{RUhU4{=S5 z>Ym+1pbKjyj|lTqZuau7#$@;DIx0xuvut=b2iNw2T-(=kZASuK*h}!!diW_fkN8;@ zhxsWts33vQvf(w5+(&tHAGMqNC?wE@y&c~V@>6d7_$fCR_$fE2Ac4=aG557dpbPt8 zUQfNjLloh@R^zAKpn?QG%ZBG`IWvTDW>~5HZr`(`|1U}1# zpGeBt=TFW)_c;3?fi6r@Oz=}~T=*$BAt&8TX$c8@mJRn&oZ;@T?woXvGaUXcbYU9g zU%cg~+TsvCAs~`&el$p`rerq@zc0Z?y(Wi__wP< zviQ-Gy^dmD+n(HWc08I>p0!q^7Hz|EM$M#UG&O3h>0fpKxwxx(XwPr zdlP}K(_?v8!HFDV@1&tjxLymBHChhQpL~BPP(k8sjjR+?%wK4&hB49icnjGiqJwVt z^sR|N*Y;uAX!xN*!nOQxCT4c`lG`(V(BDNBAXJc8d?-6bB@_^Mhbdxse>Z9Eb5#$& zRLVr4YwV32v|?PaxY&3k6K~p7&^Rko*=ckL?$w4I=5GqLYzLnb`n(b1=qssZGsJqTOIcY}pe)HTNgzu3O5O z2y}G}&quZT4i()xjA7!)kd9=(wu!!L+bMwx5^db`Q;$`{guYR=@#r%@>wc1re)z~0 z6M?S55&5Z-Hc@=Gs5Vv%ilqy;`dfdr-4ucf5)o1Psd3kdBD}9^WBAorD$`U?dg5}; zM4;>Z)co}6=}a+lwIY^J?LkdWY9XzbAJkDnV%EESl>C0CNPMo2N748m)JV?Xdtk4b zKv$N(@{#mgDmtH1#OacOw6)dVq+tuoNmP)ivnMYdII~2|uAqpMiGh^s;~J~0Q&|&% zuCjyj@&j$wiAfjKnV3CnooLrNlU{R9FNq2gJ3i;8Mb7I)(F8?IpR`eQdEHHaQKGAf zK-ZB;xoJnK9pe495lr;RGu}GxZM?p}b+kkUiA^7J(XlVvMU&@>7&*3sb@K%N>p9`w9d-Y z)QTqT*mCHZ=;9v*z>{8%I4As34J0-JiD1c_Kc(S48)5t>wK=W5mmZ z8zur>;<_IdeDYGH%h8{SFJrRGQr+F@fvq#4g2YDNcl-2PvRKec5zRN|lD+HuQ+UCT z0ts~44D=&Qfe&JodlVDb3s2Ge@htCczs~{{B!<4qLhV|A6s`V>WMYc@LcMsMaN@P+ zCIVf0RX=)O>Wk=6sXG(j9&WRos??Wa-pv-MAYnb7#UMtX>BdBOKzqv?zZh}|A`^kG zsy=>HbHO)JREuE3w)}mOxqk%xS*e2s6(rL0@6??S{VMjyb!1{)%kv_fe?iivR4pqK z=z5&Qzvm^siNDu{Gm$>I94-D@kouI#r=xy0Y$x*XuEo9=6DFuOa%AX3#ikY4bBD#72y~g(Ep_Ld zc!G0cP0op!4KKv_P?$%0G1{{$VV={p#b?6h`77^5tB-drs30-6kuP1=GKh(LRIrI_hNuR1qtu-nJFUBR`|5($8D&bIG%H2Db9&V zpbPUHx8WBqSDzcFZ?j$zs37q;ISaKv<|J;OQ_0enbK)Y-iSIZkB7rWPK_$+Ke{fFh%{dVXbYY(3m9h`oiO@?qU=SjtUZ` zujHeks}n^nBZV*EoY?z>7BZA`A`w2*Tm66nG_r)h_7B#IFOeXVzMM@dwW=us{Y-JZ8ZJpZcBt1+At9XKbJ z zKlgd57h+;p}zh>i*pwe)P1ut??iH~+NY$%PoD(-h z%&>mvoQMRvFwgO9U&9u%8s3KC0ZWu*x@?u(h7RNg(tIk7nB#3;^*NT3Vz zoTly3eWmDPL-k7X_W=nKiA%9rDPi0*(WPMwxAB;BVnxo0FF7Y7fiBE*n$|hXaD8b+ zHJaPPi%>zL{^+da5b#Dk6e?LZD>6mz$T{&8=R_pXg?UcXKKOjFJiObPMtGhRs30+9 z0RO@SC(GzwDp_JqL;_uy=XmaJce40aJDln*%_UGl;z9nbRQcU!Q7S|w%V(Su??*?_ zUllu8kU$saIex0jexi593eWPjPP z?1d@ZN&P25BJn3b{bEs<_o8$6Fm7X9e1FRHqCwL8mE%nWx-bFqiY?A?zE|Ii@|@u? zw{rrD2fE1N_o@EVgN0u>~*A^bbMhcvO`ZcR91`flti?N#D%BG9iDhI+#zKS&5|b|HGE(22 zTB?d-hC>2fn6)%5xSlWZ({$x5S9d}MiKL==j1kE1n^bRboHN{0&TywV!y$n#%v!uw zZFC!Ivva#1>%Uf@g2eudd1>&VMq=?y)pM5M47Z&#oF`{EB+!Lfi+?%m_)vP=$X4Is zUVRTLNDNqzkG56qCcZeSB*QzZXe?*ACwFRxAb~E-T0F1zyazp6Xk+PDe!q?i5?#jT zBbUc<{EM}!jn16mW^jfZ%NY&{bYa%wXOiCvq|>X9TGB<7k*FYXU_)N|tMnw{T|~9f zjWb;G8$Zhs&TvSe3$qr_zPhaybDs>fG&~+DQ9;VJ)b-! zDo9+KnuB7l?+~LNs&n@+XSlwc;ohEbG!f{+ti{#mcC=hFvbOG(TwO;6iHQ@kla1X0 z(P^4$V*_Wn`kdhwa)v_!U6{3a_I2A}*?wSi>+Mg~1u94cyw64xx}O$a_tkYC#2GHb z!QuR?w>&QZc@SNgwKy|OY9@0XCGmJvIzk1B@rSa}+!@zI-c71rUFHmT_GBxukTV<- z=)$a}X?41I%At>5ikf!{5h_T0y_$_0-up{L+*YY?7-zUvoZ)(LhC>2fn6>!MD_a-6 zDF4z&S5?12OpTliC82^u^UR!{SAP`8mv`khnsSEA5m}an5it_6tQb&TvSe3$qrd z*FF7cXu5t@k8FSH|BtM*438ptyZ$T?BxnQ)A#S)NcrsNu1c%^Gu;4+0B)Ge~ySqa& z-MG8EyR$e!-c!B%T<@vV6ihLY3?L-7iks7x#A9 zvP{wlRf>o!tdCPVmKMI?Rx~^*BDmj6xW=LY7j zFFqp2;?x?!s*cCKWq6-MqD3Y3JU@%4S`j?eGJLNrxWWWK;c$|fcY^6wF0Z3`^Ku%& zs?dBs^61Ik!gZNy!yQlOm3TT=!_%27Oz@K$z3rxb&Fr;YjF9}zG=fzgHeYLGbkkDR z#(TJoV{jR>;4-+v1Un9lJG)jj6OoZUYT=;~teR5V&q~#*c2jLQ;FkR1mcATpZgPbQ zc1|D;eKaEB;li)9(g;??ZTFY&(#;kV^Qtxm!}T==5ewJH6(-mL+HCnQFLGRNJ*; zYO$037(wJc{0wo)VQ-ZdZ~WsrS3p4l`Bkej}`l>J#&$s=xsll`%5svD$g0d zR{wlz1Jyt0-Zod5;GQ=e^2S0U>|!+&XDCP}Sk-2=mmIV)wfN-*(z zUTp1UhBSC9m|)eociCm36>seaSE=W@6H=TG|E4%vg%TDm(Xst@X=7$eo^1qs?G#L~ zs)dx`tK?KchgEsQ7t0U`<{A2w5I>q1$6YRS%yRBOdd8|jW z@o4l$jbK&XLSFLg$`4}8sTj0@9kXPGe;pZDm|)+9nKegy$dHq#9J|{rF_>Ug{ggg( zjPD0=w~ZQo#cm670UTMzcEt>?Fu^VgGnYU2l)1-G7LJN;8o?^((!SOVh=>T4!^Ogp zO@$+SFmHgJD@?HO!rZ|OwPg)t;Sb-W5=^iv9ZsH8>A8_k{XUk#k*R)^a%5a#f?br& zcC|%DX@^@X^Xjffu#Y1$iT1@sGdQv>aAaIzf_)cGyschaT&W)_r}-Av z2v+@^=_{xFxG8G>QT|H8kqw6n=~`^dIe4vQl<)$@Ei9GMA6 z_GeLQ$rUEpciC(yFVr)0E={(-!=A28uxeH}A9?rQ9ueJA&2Gcq31$g6vYc>aTw#KJ z7slwjCz$PgKPK(<6B@y)XA6B~dXJ4FeOuMWcQ`T+II@rVni*VSf_)cuByH5s+>6<5 zyGD1^2v!v+>ub%2OU$g=*a}B>5{~Q=92r-bVBdw*;8Im{K2o)zFFZAZRX)}ItQ;$dVGDZl^Y$R@#&afJ!?U07)`D@=~B+*o|iQ&1yV zb*_1k4DQ%S90^x#jD;iX21n)$N5&N<*hOIsa$8rKRI!cyvf@fd zbuYng3vwr%*`B}4G_Ki?80l&hL<%A=<3rEHkCfG$`U*{|7 zqkOaVuB3XW_A92r-b&|H))rDK}$dv^n~bf!0g304($^N?}7pV$W^DSy=!j_ffU znI9Y(SD0WIg}G|Oa+~dA1I<>p6B@y)8g;VC^uZ78`wOVi*VL|U%P5G(~N*<|L&78DonMSbcUY%UhUz_u$@NBjXAa?7NU(MY_q3a7)elrIbvtD%s25@>fldsC%M29NFc69T``cVBdv%N$w6} z#*>`#WAE~k30AqU^pg#PF9`F5dPXHr3^!`Rk@>@safJ!?UFfkGd5l(muSLD!mKwpT zbYFetiDyT|-^G+?C=5r|2aYTfj*Kfzu#3Wo;<|L^LEkaLU{#Y^zVhbty<*Q# z)rJcknGKHY1{@hzm|)+99T#y9#Hh8~?VTQH)CgADpZLh+a~nmP+-em>N;tBXaAaTL z$hg7;`!1X9!SV#NL6J#GdmDsn1gn1D_pw$e47{S=$9_1nO>ks);K;bb1p6-JSLgbf z<(noZt-a7)BUqIy%Ga9RmZ_j>BPAS}Cmh*aI5MsdkptAVTV(u9 zhXnBsj*KfzuC-Ix2YG1_T_tN1gpk(4v@vu#)`vBl=qnkM>Y?RtQs5{SD0Ym zg_&n(cZzGPHj6HcT4)5TmX!^Zb22s+OAo2v`4Kp>>2PFe^A|wgOm^^r8 zw7BaUq7kfWIyz9M7+g_!Ur^r1fFld5)W-e;j*Kfzu#2+UvV?b&6B0++AGF+~5v(ea zCQ$CVT}T8qQGHJ3$d0!MZdj%*60Kk*~3Ai_yMwK|?fxRgGE& zSmT4=qSSr&3>;Z`I5G)G#uX;mMS&QWLwdt41^H*y2v)fj2(bLssmbaY<(jvH7zju9 z7>i|@Tl;sqMqlo9C?fuaAYmv$hg7;`z|Q4Pve^TGaJ~*@m1&)j>OtA05P6!7h z&1XoXGS$hU5v=O^*w@OhmfTj??vT(A#z7=rX%=AjbPO- z%;oGdGFD94uKd;dkP(g>|2i_RFu}eHyZj%k@90zZviLD0#$-aUC7p7E`lT5y=91lD@?HO!bn5fzBr?CfRVTH9*tnt z_Bwvn>a%Qb`=X6`aAbBkva4`pTw#KJ7rwzuHRVH$_MPAT+|C56I{fms#s~jgP&vaz zII{I{WY^)yxWWYcE@ZEneu|fHOYI`NX#}g9x*#KizjDs1{8hmrIFS^NtPmU-SD0Ym zg`JJ2udtsT5@${c8Lttn+Hxz047qyIo_I@*4?cqN*gs;$NYA&T{myW6-}+w~!KyKNedMWB&&01<$|t_fSy9$6^4y4mv*ZdB>>q8m z7qYCJ-{FSgc>PBsShXw8PkN4fB(juMzw?)Hmdoz%bR2-QE(Q4T1u#`MZY< zb#M28vs?^k`2)_9D@?F|L~{41nOuoc%e&6=G=f#XI|o|hoU?MMXKhpUVMzAV0bD-rD3uaQjq}$4P;TiUq+yZCG6(-m}Vz#<{q*xJg zN|cRitr4usP%1!1jje1ZUY9&XOxkuzy5G)+~#WIB$gbw6M2Eu>O|3!Eiam|*{il}I7|%ra|_ z*}J`NuMw;&^1{cONA`ET@}j%oEFZ&JW`wik3KQ%fF(&+_vbh$iT5!0lMzCsg7hfxf z^LJIhk2G+W@8J{E``0(Q!UVfPjQoswYIKB8T+^$nMzAVlQ9qe8p}8o$O!>r&C+j;D zp`0aGm|*{i`R!%g9nRZQ$=H2OG=f#hKmFui537m?Mb*9J7M$f=ILldZmRwWmp(*65@QND2s?YKMvf;fFB4MQJJBPwqo`u`mto^Uj zB&!vm#o;Vh!CCHZw8y~}CfE&P@93kwr30(zY%M-(1glQp#(FiZySr~wKCuFvmZ6VS@c5`Z%*9( z!KLWuhBDZ?GZf)J z#?=_`S94kZ)K`NER^`u#vz^9#6c@LsbKH02cQW^Xj+B=YRvTPlqFGW#*{S8zTT}wMMY2Km`|Tf1kuFO+a*g*wY+6=#nGg$sEBICYtqkk$ZzaiD!Q+ z!tHb~b7RC+$A&%AG=f!YGP+5>HJ?P)s;xkryk6H_?rbwpJ{}{u!bE}dZnDVZ529gu zMdZV3#`#PB7+*R!&Vt(-Inr6tq$ zY>6JEi5?_ZnBab*&GuLF1My;iAv5Teo5=*L2K4onF_901`!4l7e}W$5+JAeHTw#Ly ziI|bH!7gKa9y6jdW-ysx)$A?))=q3`JE{C?Xp8Q$(5+RDUg$w`g$eE_+HCK(bd$xg zciX6PJ2iq;Pq0o{?cy=YM|rr3=s~tY5Au*(jDssoa6b{hsHg;45vzoDG)k)xtlFA4 z$XZvF)KBH2714vtjUHqd^dPyy1osnh&QG~kat3Buob%eE5v&r`f~Zz+@#vrjvi!p^dOs}2gwyCxSxnCagUSPVCj#D{kfZH1gmle z`N>gtXNkh?RU3WLgN#_#A>tZ(kX&Jc`-#{SFm04ssF9IW?vzfjsvgD%)xMn5#;EV3 zHhPd1j@u#*p$EwoCb*x7yku^IStIT0h{g}YHG)-DNBLO$0eD5IK4(kxAU|MTkq>&1 zTw#LyiP#6yxv!ZS>x%B(X{ZsbdW`whYTm2Q2Gt+TfF9&7^dJkP2gwyCxSxnK6dF}D zZ(|goe%o{!!Kzaye5`SU4Zl@?@apKN#sKsOx1tBh6(+c!h-ACLT_ZjEgZbx1XauWX zcl4DdS634)tE+p-AmQ%F45B-FkX&Jc`-!;P>x@m>8094|Jd4x_Rt-(>C-ZkGEi#r; z{lNzR_8?cH2gwyCxSxo-PxM*QbCbJ_%2Z4vSXHgHpG#oxXRs{$8TD$LUE~=h`_tAr#jvnMb^dPyy1osndwy>r>Wl5|OTHejmV1iW* zYI|GjihdnZ&+{nsAYY;fSqMEyt}wyUwKKrM9)yas7bBQiqZHD_Q7wEUyD`z zYsNPiZ-kdv7bYh)Ew24)nWz-+BcrN^i;~^conb-!u}SN2FS&$!3BMMr_^yNxthpK)nbWOggDXr7 z#|mjRgYM8Y<(8h~-kywmdkpUFOt6Zd64;BiOPpB}QAW}WoR!D~tJrXn7uUahhg4D7eDJ)>OgP3b$x$HThxm4JM#(a14C|CRoM23?$oE z2FL`giCh1sNfK9>2(1!i?WA-6lyXa5(8pg2`J(gk~Yr%#pL!mVr#nngtK5$PIoTQx0{vQuS zssn{gZ}gq{wOGY{YPcnPeS1LbdS$uSR=!-Sp=Ow7L?&ZatY(@!<0JUBSjAZlM#*M2HTPika_c#sf-6jf zFLk$epb?8zQj{Or(mZ5K-;gaa!75Ivur_>mZ*$(QD~_1q6SOpniPleXf<5+63~HwG zE0vLzv|n{BM@Gi4#VStQFq+Y)lbHcKbH{oN*HSemmTz^j_VVsFPUUbzkoDz5);A4V zAHNo>I5kASwvjL!dE}8Ne6QHK!o-XpS!9iMKg7}|DuE0_X1NZTWrubzBA8$mXPFp3 zx4ki%G-@SJ#iTX3!bHrPEOKtQZ(^N~N>Z0*{)sa)8b~K(uS~FtQ(R;+L!LTTeeEO% zKRKwSwM^ujnZ-(kUqz@ym@{O4Emm>14By^!gxH4+dF{4LT29Tx=4n~v=8~^P-^?nf z-ij<7`zOk2$in%xSjDM2W?xUTZ{PRR5>BGXUR zGq*;tibn@*wvHzn%Q-k}%j?BQgDXrdaLQtxCYXCmINA^xn{dY1#HRq8Hg3Qw9_6sv z?q!OX8*u*MaYt=~D@=?G%Pbo_J|n6RDTOu)VT{EcV=S96#=-=vc(eweRa7sz^U7#r z)v_SL6(-7j$S5;-9TEjIt5KPa7%K|JSWyhdikM&(k2;}^Miu4zRhx}EZPQ7vFyU4s zgLEw3BVx0taU3KQav8?F!Z7B=1grFMwH?=Ai|45q7=ixvwNWxAN_2IWRomi}rEoQZ zC11Q3;ZJHB;~zEE2v+4Q=q#7wWZ!P>i-B0VZ@%5P)NA|n@dIU|ud}R?a-#TIvY1TF z?ktl%CW~=7i^+yV(#jucCX2hJ6*2SDVtcDJCG7pa4ALr0)J*LxpU=ga_xIFDT+rpk z_Vgh7{D)xG@os5l#|3l6fIo^Dd0~-#fAlOzp|OJ`SD5(V?<_NBT_JjxQGeBq^NZ|b zK@|B9!K!8B)5_HOR|uEZiby|vu6=a_H^ZDiKyrl%{j=KI=!!i=Rxs{g>8}y2iocrH z8W|03p}vol&!^jq;`>;E{T;Z%1b;V}r=Mqp9V?NHmgReC1gkPW#%Y_a_lOy1)OF>+ zRq_&qAFdLvFu_+0R!)w7D%O|1Y^?27RU=sS?Og^ru*5;pqJ;VlIybH;Kj3OFg{z$_ zOz@SD(eTe@Wyi(0jKepR1rw~Qav+mj5P4c0K3f`Xe8R8x0DiUEmIn#0Fu}iIjEo+S zm3wjK{mUXLHG);gi)4{qrd}1|b_CkEkGs!K+-c(j^GC(~2{X`>Jb^ExBTrFRU z8*S9{!}VScHB(mJ!qb2&Oz@KdE_}b2e455xHhq{@BUm*xi>o!xnZZ*%2Rq`awg*qO z)p)9Lg$aJbA@Ood6IfRyr)7F$Fu|%0grJfTxE^7$>RR$D74Y`&ue20T*e=`46ZQ2jsu>$%^hRa_V)7kvM)(Yu$Xv~V>8I}dsjdC{BbhTa5MnBblT(vQ@6%sv?Bywok&V1iYDa59h@8SUb) zW(cK3uc$V9MP1P=;tCVoL$cZS25&Vy&{vz#;=V?(s>?|1LR;dVsCZuW2P4YVx4VNF zjouwsnBbls_Qp+dD#HD0IdkB2qEJiQ2DSD|~VS;r4g*^iu3B!Sz7_tX@WV>+s=dDc4qXpxxxhZys=l4($HCP`djf|C%q*UW=tG}fQbE>kL;308${3AR?OH%PB?pT0yYAbg$Yh{;9g&}l@jw_2hBRC5v&U97i`Ux%`{n!_N7M}^%QATbEHvRVS+;?*Y zNfW8sp#xGQSXFIYkd?!gpR6)6PSv==1Sf2GemG4PLp{Rnw<6*s6RbLvEl_SbKTBME zrP{C~9lZWMul)nkL9Q^tNg=NGlBtdQ1130b7Sst=)oJA~b8i|ap3YHi3_;5I_(KiH zAEcaIVS*D+jBU?NZI+zqWMnDSP$O71ZHupU@}l2T^?fWvTHEGMAIDy#wOnC>lUumH zZ1v1@*uUMmbViL}Rr{(w){gH5{nd5#6RGn~?B5=S)R`+xZ~~3fn$skh1&$W8XPsYO zBUrVynYXng(5(vU_pt)$d4HtmH;|rlg$Yj5E!SrnSRa*Vd5}i1D&d=#wW8{KsQR6^ z!ze%*i~=mVnQU-{2_6x^-XhoR=Jz5gDV~Dj|hw|oyF)<3ydytMI*EkEb;y^`v0M_+lx#Z z!Q)XUu6SE#6a)6#B>dm6#2l~LZ-`D!iK zbU_SgV?Smja&v|-1nC1%hW z?J#P|6()ED6Eiu`Ml$wj+=Dil7BnCQ{f z%Q~}oNjLS*&)~Cq6ZuM<#An5?#VY>PF_V1m2Qd(*9Q)foYM(9>5Bqyb_ds`%B}9FL zz44v9;X7}S@0?$YRebee2Hk@m_C7@#$#vz^YF7ypk4k#U`tN*1=QHX`+)LLkzZR?b zSAh8?mlKU|xZ3;LQ)pK^6A!=TvPMRI`YI=r>&kJX0De(n_zm)Fv5J4q*cmTVDYFyC zQpc<@4X!Y8^)D}L4*h;>q@gYDCBc|={|5IGCRoLHB|O!R$C^hm>)t4mQoH*wAx3#w zdvX-LsqS#-37d(yCkEi2$gjmJzPnl(nVGV38~dKIk%B8sB+v1-_QuWgMct{@z1@a; zyFc#jOt6Zd5?HU6t-iSqyXhXeo=$Rwi4<5rElG5a$a4jHTa zOLXrO!4)P}<9(<-GYeK#Bko1ush=%LwolDpDx3*cvDZdgo42ccP&Til<`mQ53KMI` z2U%x~)E=v54&+4NK%j5X3w;A7SjD{ztXK0xQi@Ya{(Q)7a)pWSs{^bvi;tUX21FP1 zanj_PZ)`;$hY413ZwdL;rh{S}PC2e{t%}wwVq!(4pBy&yf+(I|IhoDqtEEO?Z7BL` z{93HyULO+3+ht46?p4r?X&SEe?wBaH$y<6Yye`rusr#;T##0fWu9P#EpwG###VYQ- zVy?5dX{1Ciwd~n6S}&D}?{2xQk7svqmBLjGf41iyYRh$jjY>S?^F+H$acH-T9cCIjSVpDc& zFTE*$t7O6pSw?zf8Extv)(BQ{#(}x#!~2+VCr&xCG##SlB~0}3&t{!zaizLC<@g3N znT<^@I%Xh~;n!jnr#tvXWoc*rg;OxHEnBUnI85BhoYgv6ZvNYLXrnQ*C0Cp=k_Xum zzZR=Fb3(s%d8j!9XVFzp7@?(6Ol*sBw@x{p_(`oMuY-(iJ~FaW$jJD$SjE{H_OggO zW6a*#QFgpOSIgm;c%9i@=K1kUlwIB!ZLCMuw*pz;M`V5cTCCy>5RPnU8Ape>0n&cN zU&|AjaJ%bfC6M16sRS~XGE06fR&kbzUF&epd{bnWoxJyHDJK)tSGiehOiK2%l2l`w z*n;e}1F~0sEmmb)zVrf4%yvg)3WbH<~k}7jzxz27#VV7WXSwl ztl~5pV~`##|9~u&F;)H|BlPzQx-M)8iBEi6&Rc7h_MMKSjD3pm@RV6E;EIuFgK^TuZ?Cfu_7^} zycT*&6nm~lUu$EGB?e&X0zp(vBg+}vD8*^9kfw0CVDnZW34#Mc1Ml&-Tbk^aP8=4R2bh?BUtrU z`ZV%Omla|hRybmf;_brb>b1ulf$d62t}rq2k&|40dWG;k90sC7g~H~Z4<3%C?MrC{ ztMVUllFv8J6|I^pV$qZ?=Ij%;q`oT-39c~lA-9vfw|B1C{HO?sJQKT^8xj|U-%8X8 zR=Gqt$)919M6w@b#3RiV# z1gi>9c9O3HhlyW<)nD~4yuJCd)g#CBk=G5bFfpZUYFTQ*P%$T)YU9X@wq}~PG_vI9PU4!O+UPRF*Ic}3ud%0V zVU1wb)OBg4S*@OEoI`ydSm|msjyPq6M71`#!o-wNXN%~$LVda;R>vDIVSkyE-bHBy zt2Vo*mno8kD6v#siRH{ZqOsp=qk3>llPgSoUz$N~?@~tGOH{;+N#UZ%gp6i^?6oz5 zRZFneGBi~Ik+Y)u)pnebSymo$&e(Onq{$T~N`KBI2jnU&I$c&oOpKds@bs-A?&i}7 zR{8m7kqgrL2=B9Y5Q%jf%lfCA8FyU2V(j_Nb_$bNd)W zN4(GoR#nR9D&MEhDndV&1JU_aKRNm4D*KJVRt8s?$XC%-_7BS``aLKQB6a?La^d}* z_TX}zG=f#_7r4pn(V0Y4C-qdDeyD?-(&2_U>FyT66(*Xbb(1-So9J0dtpJ_=yp60> z(xxB@NWLn z>rDl@uH`&C6RgU;(_QBNnp(IGRxV>w;52dkOIP{*XE(tWCa#9N$v-l!$mOJFY*j5f zOw5kKo_#-4XauW1%ygF@TBZ`4XEy>d`cNcJYmS!%K8~@wG{`3VPEH|e4R0Z%F~V15 zMhcPrS93WRc}k@+e~EHkTYzXXu(*+aPk(v8c`CsbCjM-7m%+JHiRoWd8-+k*1o7ZM z1gmNna+9^Mr4VnMDGzsbWT4UVQ(qa@y`10*6Z-oIjZ0&=*Xkpk|LUy~tg61t#rky5 zw^pCkh?;K39DG)BV-o~dnBdP1`#P_F>NtV#aJA}p8NR_I zAim-oHmrD)ly(?*S8)uC4|vdg$^qKa!(wBd{^5$ieSJY0!fVS=wp z>{L5s5Rd?TIlzFq17yVkP z8A5$Q4Tw#Lm+UN<_&LB6sZ8X~4EUyu)+IKL$%+;^HxNuxOqk7_rQxi{| z8hGMxg$aK8V0^H$rx=eX=g{cR8o{dFL(*B#+V@q}vzDKnTw#KrqKNuRjyFWEsm7?T zolPcKmDE3tjHxqJG8Q?6tz*%yI33izn z$Jx@w?3s3T(y}v{^+m76s-~f-<%y)tV)a?&kW0fMzgTn3krED>D@?Fk#@dYUMaYqIQ>{S{U|tnt}wx_A6MepoyKF#RqM2^9Gw>UVzhczydi^jO}Y$HEmRxc7q5KIv|Mh|&=a1Do-kLK;9fCCWd?VWD?Cmc zpO==@2v)V2#K)k0y_eULr5mL!UU%jHe0HZtz?(DsUmHQqZ+}gQYYQ5T|EAts9axT zBrG41uoOnZ!WAYsZNWPqmRt729Qx+A6B@y)6E(A1v+lpTD%a?!azeTEvD(gGf`;2iC$z4q(cU)nDQ#{N)k98OgDtDCaDwYyVuNvbE3R9_^i zTw#J!Ra}X&(dHqXUbixOuST${!j|mTd3O~j#iET6B*L$d2>)y{L~w-(PKR;cUGu(X z?lK1*7xTtx1gn~Rd06{}w?5e$ZOliq9gJk#4aqiFnBbHfvn&pEF#BK^kMXWQ^tCXe`F}_r4g+9u-iv&biE)>2sOsicV|S&#UNT^#DptM z@aPHF{EXd}^lfBzGi`;M8o{dKq5krY>k096k{T=evH74lcKnB7$H)&?nBY+$%tJoC zPh2Z-!Dw5sfkv<@SGPb}_Sk-LJ(C*qO2!D5FGjH5Vg!pTOz>zH)&c~F$tau-?7XUw zMzE@O{$T4o;h%HVxN|Z_;;v&Pt_DWpxWWXF%E6J{>>~fD(^WPe&i9wVb~F)}(8 zBcohlf=5Z=eQvdvjj;ALYTs>*VAZ}W!PaWok_FUw?R1Rr=E2(6NR04ug$W+*#oVZC zLAbk3a1<}C6Rh$b2o1)z|MXLB{5~*6EZH~LQ5PfCTw#Jot!=jPZ6*nyHkA$IRIEm@ z>hZz=x$5Kq(b-3}F?52n5rYx;Z5VOq3KKl~j{Itat1Z7jhI zh@qGPk%$=(Tw#J|L*RWxH!%C+^txGnoHT+}xf8vt^X}3OR=+{)C}%#xc`PPoa&UzS zp4EYQ;hEyiquBlXsiU?=uqt_UE^EK=i2UkaV#kb>xtNjC7c)}0!UWGw!90MAUCkKm z;t|(qmxBpb<$vyJ?fc==S>1PkU}jAWlAuwTS;G}3c$N)LOy3x0Zo^!)4i)BW1gmZx z^|WTU<>;bjM^C32LR?{jXA5EXz3Cf`9+PoA==YYI^YJtyphP!wx@u6-7jF!PKnOzjNQpoM7`DS@=@6v_6!r-%8~x=a(II$_SR$D$~r?_<;T*G>|atS4|i{1Z!KBdFEoNx*ZXFXZacG!nd?;6_bux(Q5OVOC;3!I0M9;VMaIEVa7J$dEul+u&T-X%yLihlH&7kHI}N< z!74}xhaw&13KN{@Vf9&PyqtJwsQvK0ni|2XrH3=gd9jtmq@F6vIE8d@E7HLNNC&yX z1ZRMFsyR212fp|izZa#}2v*(8no&Mo&`{(XtVXbYBOP3ebTAs}AXk{+3=q3)u1hCx z_>M6`FILwGRt31Fw?^VV_EGuOtxBF^=D+D6SD4^L4>?@ZEMhZ~yT2CoHkn{m;$P{k ztgp|)f@otxiSdR9(!nK22f4xoXMjjp@=P{dlJXe&J$h;ctNIm6BV7kg6os;>Hr62> z?22@7GSWe=Fu@t1&35H;km>a!uft_YIgMad+Q&|^{Mosp;!V|tGt$8=D}E%cLORG5 zCO8Ac-c*O%o83RuuzwHK30769=Okw>UnvglQQwD32ge~D^mMtN#1$qu(Zj0W{)5dl zcly{5MsLvwRy~~SB)^W^BG$E5*Hu%bgYoHBC+$Z%$Q33y1H`#~uez9x7CAX~l|G;m ztm?icwY6ifYk!r6XF)pn5b5AZq=Q^xf-^wO)1MV)CScw6t2_lYf>nO~(poFMdv7d- zHrgQ_bY8vLh($Wc6(%?XwAmibOfu?Ymc^=&D2-s%@g!$!UdG=iRn}LgjJy3QvcAzs z2f4xoXMmV_7Bx2F46?pG&muK~RRd*4x#`zMG4QC$`nDq-RKyUZgIr;PGeBe+mye6E zbzx?+(m6DORS))OmdWRDidhad`f5Wu*c#~|Je=SP6Py8JX8*=8x%p3^*`mUHjbK$i zXIJ_9_(O5{rFwpNBOP3TbZ|1#L9Q^t86eJ;xzS#&H!w!WS5IVuRfj*i$?#n-#o4K9 zy!OwJzA^*S!4^mdxxxfzfVkT8^p*13VMo6=I46!?i&d{1SbtE?{<(!o_~S74-rTw#JUK$~r9 z>4H-2;xVM=GL2wWs+8HSm8{LKs?pb69k+_*NC$sMjWoEz1Sfj<1{)p_bCBFQJ@eKG zRt;*H-OBpBJd{u5bdW1daH5A53QadfcvK!N7j~I$XM$CgCS{kA3xA2My;ati9qC{T zq=Oxh4swMF&Hyo=ddfz_rB6F~vCcG&VAbYJ*=6}p-^IP*D(h>5bTAm{U;@%Xt}wwF zAf9T0A?B}l{u1lgG(uC=#Y)zXAH|W6D(j0vI(Q7};A*6UHmWee86f8AzieqroTNOi z=ShuVRj+&=*4fMZrl_?UDjf_$I(P}`AXk{+L=RVc{(fd!oDG<(TqliS)tufrtutRD zqWYtac}NF)Asu|-;+Dh}CO8Ac?)VKln<3caw_&mN4vnA;@q8ilqp(9$=jQ6nmwHGC z`yd^RM>@zAeqGK0u>!P8X)_CEM^AivOe0uzysEb~pZen)mG!xtJY{S})_0?nm&p|- zI0M8feBZ7bX-8!@NB9@k2v+T1;3!I0HmqEqaF-K5B&#=+s&x zSoJYokW9F-OGIZ=SzlwMgZV~OGfE&GzwOowSJBw-rt5Pivmgzk< ziqB0{Ci4>MU=O5&FOUv$g$d38(N|m5Mb5)Xf1}(EX#}gb4Ggi)2FyQZB-+4yIO!Zx z*Pf}GBZ4bTa0Y0N@XD1q^QCLs+Zw^DXCp(bJ$}#jR{51D(!u#i2U{W?O@jCs;LVN3gY$)#bBl<22I2P_>SwR5{5NCO89BX9EVxVo2`RPZ1iysz*UV zR@T?=iE4w>L9Q^t86Z}Ae;6xn4qj~3#NC<+R@HG0ke%wa6K%p&8-H(hHE!&mYW#(C zkSk1Z28jG>fVXk6@=;^{h8T@t)vLq4GG(#aBJ_c}u7)5TT!wUTHPS(@Fu@rh&N9uE z(Tv-@)2P$9tVXcPZIZW~5Gll$RO*ffGw z!8>wUXD?SesO}}Vkq#C?I_PQC7F=P16Fr=?5!>G^hqD1M=4z}FtXka8(>n8|%P@7{ zeTj519_io;q=Q^xf-^uQEQ33lOR-OCt7RoMf>m=i=d^ZK{Sc|vf1E@*xC-fDW2A#z zVS*DqoLG3QfcfWnsJxWaUL#nQIw7aE4)RR8o@gUG(!u^n2Uj5-0mt4L9Q^t86eIQaw%#KshZDhyev+byRyp07tYxmw`eOl z_q+VnRTjv4&A#@AO76NM9eiGEk#P~}AXk{+3=n-apU&omG>eRh6$WYqt8U-TBIj>? zYIhl|lDnr!2X`PH?2mMiD@qnQqQU;UrIL1gkFpoynU088cgDeSaYx3_vn3`>H9GGMmr3h?X#}gDz0PFK>vQ_7vc6vrRykDG_X_DCSD4@o5c3&CeFs)l$>Fs# zNhVm;uxMsE@4CN;ZCeR#TtYgS4a6{{gIr;PGeCH1Z&PHwT27Wan?^FhDo1=~+0eC+ zXntPJFNsDv*c<6!6{Le)VS+P2jF?m@Ex$C+BB#DRrV*@)>z7%kx)?61msT^E=OZ1g zfOOC}f6~qsCO8Ac8mt~Ykf>lkhYh9_PO|a9Hnt!zo>EKDEgSN$~O|CG(86fulyiiY8 zTAJ*5cgR^ISk|Zb|N+Vcx zWTvyV7U1n!m673`25|@JU@D}8Tw#JUK+K^JN+%ph?r=_nMzE^y?zC3cS7liNv~dmT zU`wQfZb%2Y!USi4Hd}6|sm2J8aL4V4IE~O$o@r$6OLN87^Qw(wNC&Tc&+G6;I%uN` z6Py8}uXZiS+?6oFp02b`u*&X~T5kEgQcSC=<|o4SnaAGOu$xE+xxxfzfEbne-p;%- z!AU$ldQ~G>)pm`O^sl{Dl)9q6bCnMMyxqq>9qAxfnBWW$bJb1^GUvn}v0u1RO(R%U zJy&Y^dq|=%v7;bTPNah;kPe;3!I0M9v4&}OnpO^a&;tMb&zBt2{26gk?ebrVOB4i*Pd5$PaTnBWW$=Lug<6i(5V&7t-b8o{dP ze`k^XN<9z@kE`d$d8C7DkPa3{I>;3!IMKs=>SG1ux96ee=A`x-!77jDZgQM>F5KIx z=U{21gEx^5ejZUhktq%ivdXRj??j&XnrNdL(!o(k z2b&@t3F#nLnBWZ1W*fNK&#Yg| zQ;NJ_HG);*hKJ1i{H^%QN6nd7gmf?;(!l{p2ek@ii<|-C+8xu}Jl}qlxHt8tMzCt& zq@1#q?^7|XtlAGirGwd!4!R>90m3Q zgIr;PGeE3-d5*^$_Gc(p`k6+ss!5oSHLtINP33TbNC$1m`ZgjR;3!I0M8yfQg&M!uOqwOQ9V#f>kB^2T7y<1~K8H zm6sqLj6^zE5$PaTnBWW$-^aSb(&^h;N2v@YHG)++9|lX)W0~l1TID{OkPenbI+%cT zkSk1Z28gR5-GGEsSR>ijqu}<^&ZXbm<{zf`j9_ip+q=Q^xf-^uk;3!I0Hm)`$S{&LAy3a;ERuf z309pM?J0+!^bv^@)O}Z_gZq#UZbdrC6(%?XgnKpmnJsZT*P&6-8o{cz0XePnyylhZ zhc>b!9ZWKstCD z=^$5_;0(}aE6^*%jKM6uA=zCtf>jYYJ*;_s^ILUA8-@wxJl;WvV8@YIGb}LVOIWz`sKp~cs?ZN-0f;-21hP1#)U7}2v*golg&D7ZGVAIXk#CU<{$=x z;0hC*!(uO_(gn@j9(l}!npiJPuf?h#ow8f!#5w#_8y7&hftUz_D@<@wjJ-u-wi^4k zw>NJ_jnoKM{pX}{5Q!kJgWw7i*Zs1~#8oHlO`O#C@qKU^d#AVorpFO~jbN32dR?2L zW$c|nJUZ;Joqx{6wY52{HhN7}*HzOtcf=n2RkfCViQv~_6`zBLIjJCagYW~v6(&A8 z=d@Dw&Dm5NFB@UDFFxJ(epeh!uu9)+@*xNx5Su`7g$duZp4Keg%Il)h#^5|%r4OzW z$M)6+6RhH0E3wx-2mxX~2(BMn+LbcK3VNW?9zYo7Bb2Nfg`mEyaAfAHA z1A;3|bSUF#{RYpJRc*{ls427IS3A4oDve;3KAN!%#Md)F#RL#sVd7|yoYuYMbVJp~ z#^}_tJnlXfa?REVR_S-q6(FjBs0@NDOmr>aVciq+EL3ew*q2Lq;4WHnKvRui72l7M z^?}F=q9_QiFv0g=_{2eRrs=yUY-PTw;{3R*a?|d%;_juUGHYm7Xq z?F7Qtb6(NDAh^PNC-5ubx&m>mO3kpH|7n8>-rWKBL=cY$CWRgP55cOMsk6(wF>OVQ zYpw8EwE!`7y4*QC|5U*hCV2mef8P0%YWqXipbaKiwKFNZyc5-4R4$`_gM$Xe$v4G6 zZ8!2wHM+0zm8aW`6(h^klkWq)<$>kH#N(sYWCkZ+S+mb%vCX^gzr^Zo8+Ysh!4)QI zCV0ukzsHOGW7W(v)kf_%rFQK755cPZhL3bfoF$SA)&YUfN?z?7P;@^Ct}rn*%u5a{ zKTC|ArB<>kBCPGE{~=h_>Xwf@T6~c>Fjcjo{;CRrZNrk#Muj>4a>2FXqTJ;sGT?%r zb;TSFZ6wD`@RI}Uj}%7LhW`@&eX574&x$KdlxpWIf3EH%zO_;Lm1^T~-kG7Q4JKH{ zpE~Y7AO=mZ6m}E@SD1JZ;3HF?h!X)pYFtgVvGs(eAy~zq+dqGmsFStWb`T3n1j&Hclf>0+ZRGiMA+ql7p<@26j`Hl}KzTlSjHsE= z`rkHwzbv-%FbJ+Nu`@-m+~2gfFj}|&m)OuU_s#?VAy~zq$UpBqZR0&f)jQ`36O$7I zW!nQCMdi%u4yWFE%mWdo+F*iJ{JCK#HV~aouPAl~#DgD!a%|@nqUV!n`D|#2oRP3r z9O}_ortT3W>n>X;QpG6;puY2s6Q31T-ym0**qa<8v&~p6j%HLY9QP}kre*Jmg(F11doxZvD6M7=s5bWW>RD7>?M$$WzyE*QIDEvvs0pHdkiQHWxgnc;rI{1D!#`4`E*|=4z)gA zzSpM1zVY2RFA+a%ky5|!s^7<^VehQ(oGVO3U-Ob<2CNfv_p8wi^;bo#%)dijS4^;K zcOzf9^XUq)p_IDss%y7w*3V(;YUc_Qr*?VE-S4-FqC0B*+s2#`>9?zQ&IGF};5_=( zkJgHTZ|eU`RNd%e5nN$n`+Xmo(0Q*ou>Aj?IO8J9{13q@zC!|M#w@Mt&X-YUo%8B1L#{gDZ)2a@x{+&hl*fiNf`T8lw*y{11_gHke@5_3Y{8 z50{Ce<1s}vo6^v+1#Lu>DsFIP_~`U5@V2sWwpr-3GW6_GpA zXSDuZbwUyOYkdYebj?H&wIvk9?V$}F8$c`o!4)R-_wgY9A0i*#2NSHyJ3E7PojFnX zzgBJZ`S%-agEqLrg#JG6=9y|VN!=r&W#2gSz>^GetH(-l?QjwK@@WRSy2eWJ1pf}m zk#?eAOA}aldVAYSL4D$NAxuV-XMSKaKYMjp9BjOYYt}wx$0%lnR z;q3GLJtAEC=>)6zQ@7a~T`uN0bZvnAXm}WWn%sa-E;7%pP2%&`TJl*ydfCo);bH0os}594FL&lxCF)yyW}dkAPaE6N z2CMj;^Cyi}ji>%0mZA-={MwsA7F@VenAbujzY=ygwiS0A#b4DVQE!8Z7q}8{u30H+ zrcl@Jh5f}G2SAM5uM@1wJwAgRWvmqCqZHBl#y@}65WEkrRLqw_#y(#u;=hOe=dT)b zznJ3)+PLe`+hF2BmJIUr`<3EYF7y82HWC;#(Vu}c4R)zhHL)eS|}(_rHxcdMT< z&aJw3H{dJgpXWz~!)c2u7tWvJL7CNh%6zF><3CrsY9l_;bB7}MTVtYQqPz8kYdF3d z-iIOzuFCj71grk{uWEZfdAn+ZD@?qf?{4*Rp85V?8#4zE-I4eof>r#9;C}ULiqXUo z>$v6;XI5#FRnE(32uGo&GWXx^^4RgWV#>M3GC3_0Vf=pz59Qk*zno$uB*i*DfZz%f zEx%=z`?I|hE3Em6onB8dUZRa%{~=iQG+;(UORxM4%+$c|JZo#~ar0pLP}{xS5DLM4Yv-fkd$!`MGb8H>}@LVWSU~ zxeXE7$XDne)RKL*s(b>w9ax6h7aYW$67%vKtzWXgja_-od-=GroRL`_>d9YT&CAn* zUa}cG#A&DA98)+FVWX-Dkre)l#j^;WE)7VO?Bf}9=~CeCkY$v$i_CZ zv7KySs!*$3H#a`)_G{+8M-bMP5?E!jv4w1)q)mP|9veV)>AGdALQ5sER%GLwg$*RK zzsS!=e|*K7y%IK_mQ7%nh-hj-pqA|2>iZ}8Kl~KS7gX(QKwqJEXSZ|X%lf@%eSOS1 zXlF{57*khI{Jc{TC_w^Km`Su=oHbF*Ymq=LELpn0q|bEb`MsVt;qQUGb%qS1J$7ed zu7w0qx8HO&kZg1y0wvQ1Pz2S)pX&X+oh93JdlK2G`yZ)7qI^PrUU|_E_3buMg7b)| zLBtY^RH0U+;>P1Yd{O&E3L=c|_xVow$aiKSN68?6Hy+dHlWHAknJTBS>1-C+73uBtQLPprY&;_GHY8$zMXFE>OP1oPwMl98M(J&9_f20@DnD=f{<#`jqb)C5 zG4r`v^|svmeSYq@__^B1L-gnAt0t$>8>P=J);Ap`NMMbjU4Z?QOvH!!GJ#rHL+Kk; zi)LtxVv|&>DMNHzJ;(L-^NU@1n*-U{hI*pMsknHC7DL4I$wPFMAaUdtechK<>m6r` zp7T1{XhXzj3j($LPPp>6W3#cVRfUabWFwl0Geqon%Fm0AdZU(W-j*X#!973Ua`TmH zRbQ;{?p`uO8%sny5hy_d{YK-f1v9i9lf?s zMV&NGP9a4C{xw6}MZ_jb6{ZALhK&>u~^6{ICf2i5E z2*QDEtRdn!5hyuuEiYeclZDN@Xql>)l=DZUlGHks4@?yjN0ah$eL@!2>4C7(fl?Ju zHXc}{3bo`C97gSK^XL71Zc{6&B)gl|rdRLnDzye!D>K(iHng89c4Z_2wZ{0lnb!A< z8_ny~-DbY=7HvC9kigP3?XmFdb?zk6?vg~H7J9_g8|a^#txpm=Kf^}k;U097`JaQm zd7@2z(+cf^gAx2`k34+i*1uRqI(wZ-l(IIhY%`P~aeG=m)9UctGU9|Z^-+46e~Khi zk0TMN)#_nx-s{i`R_Y(I^CJkGkE4A>s%DkW!++eH!7gp@#oHapXIgJfd^3<^YE9nN z{TFG8v@R;;0|^_C{H7J*Hg+PuMC_9Fcs;^5$$~&F%u^dX6>^$( zN#0*;{U1d20iVR47sKB|qRK#L(>~5I57Cy0e6&8(yUGp=0<|!;rZs)t@8oKq(?o2b zyZMujt!A^Dci~%}<}|Gc&hFTTH;i@RoorUJmD|PGN7#6g?3PGtmJB6G9HMW5w_U=ze-o`J?JnuJI%Z8eO2oHfx%tw>)hw2G=Q}fU znZ`SjAG&f(ZKijNXDl>%7bQr1Y3O2Ffo%8f*BhmOX_z&U_CKVYqZZ~V(?;agqdv4w z&9J^M+?Cg~HhnoTl*@IOc1-jIDG!oP5rGmU^x3Ya)$@`uA|i!W&vmD}n|+p95U7P7 z$=pl5(qvT?v6qSxB<}m=G3^3`KNTzV;*IjURwRjbEhPfA&~KULF?jAyvD?Rf#OCIm z9!z6fBYW^|j(JVHRx{j!Ilh~jzH-S@O6;XdZ!HqX^W-z_n1#&_qg09a!_ipHRD$?h zsD*EEW3z)1$L%6b5|0ppZz>Xt+vYa4;Q3#Oy*p9c zyWch>iM9j@)IyJB5>4yYNfPe|N|2a*D356;&h7B8-9EiwpFyUYhy-e(-!gsGxunld z+67=WZ#nauALg-r^V;(U6C6$JOh0NiTZlP+&^4I2XT#D#O zpjM70c}@MJ%}3F5B7qVl@J*vz(mqbmKF>{OKm2>?NTAls7kN!1gKQ3B1hC-41TCBh zZ$mE~B}mA}f#8FLmKA`z(7<6>UZD5JA!hu5a#4DHKnhUh3k0!JTo zwy%AJwz`>s0e#bvK&>Ks@|b$<*RFA zv~-XN+g}7qkiZs$d^KVc`#WYU^E%OoBY|3@mghE&?fmEq^t7)=#5p3$5P=dTuyv)# z%;Y+(mz&D3jwm4!sFfCw$277`wiP4Gv|q$EB2a<^jvwjnwwklm`zxaO*{s7E5~zjk z7`0bKJS1WX5hy_d+pf%hFeLY}Br&E&0^6>&p04~^%LS~?N3p^p`r0xpYKnLUhTcWL z$%N=XjAQ;0F+~g|NMQaldxP>ZCq(3cM4%R?R#C>1jdrK!CM_lc-w&+EXgkx!IlDr> zqE|x+5?H4*bDn;Ba-x_`Ac0!w5mQ`-{^)wwr1L~zn}{tD{!->h|H87y-W0tf*+2r@ zn9R}Aj>ny=h*3EH7HXkKG6{ChIZ+T;&e)gWFJ+DyI$gF(rl=Rm1`^n>WZKA)WuC7X zi{fvg7J7tE57bOb?^Gj}yYydREIhhCH=NkazSd~LyMC%?in19Q(u`x&0^Ox|=%}%$ z!$4kp@kS}00SWa}T~m~WubtTQ%0@&FBI;NWsD;rN6l)MtQ)`#RxmTj6juIqxl&x!u z7U|VS#10lCqCF91EC|%Xm=HQ&`z=nZ^Xds3Q@DeU5+pio4KPI;4&PdjY?LKp6cIx# z2-L#Z7P{N8%?$1HhbwCByhC)9AW>pwfGKJ+v9Yj`M8r8F>R1q{h0&DM?s`wt@?06G zeR2)eQG$fcr2td(=K%luWJ3@+|ARm+j0&Y$Dj%SgsF_b+>s(Jq2@?H=*EL0+vd$u2 z^nVekg|U$oEfQHkd%dQu-lMUVjuIqBcdciN<&5mxglx1T;tLV2EeO=Yh)p_)RH2XY z{?ie9t>v|)SWYC=;QFRG(l4(>WMh(xag%&NBM~5mWSxh~-4A zupm$i<1guM-2A=SkvawS?a8&Im`x<++BGu8cuqep#ti=uahZsf76fWxydSl@*{8Cq z?PqISJc2n&kf_|gktw1v?6Md$j3B~+h$IUFwJ>f`Q8uK_U=5xxRln>V!cl_6&pM4v zk(ox*I`ujt=KcqPS{SiOzPdYxse`UFuXdfKC{HA=o@{7}3iZk=eD#P3TOxcd2-L!O zKZ;>7)?@RR*Wkf+r8!EFNVREbicj3!O+>dLNuzk3FK1MgAb~v*?UJRasWoUv zF}_{20SVNS`zR5CZR5Q?={T+LVxNJ1RE5a;rt#HRS23d(@w@gr_a&Vn0wqYGz09cM z^2LrNZL=Uy3-e?e`|y!Xt0s$xUu>PRH$dB&Hm3D;@Y!x*0}1S}G6~<_fj*Y0LM`-& zY0SVca~I#kWCPnlY0Pzybh8CATn>gS{tL|~1>w^mM-h+M8@ zboM=GVFL+lS2Ev^K1FPO&sq?ug&v`CqUm28y<1A$*DKH2$rBE&!JeY*qR&x-`PuyU zh`g2AFMvi4;t3^4n4cv=7sM}#CT#qoP0!}P|8GJ_kT5@+iOdw4Q+0cU6))pk)kM&< zZhodbY5z@_CE|CH5YPW2OuiB}%&8L3V1xZPAw2p&i2t3c-vp*m{F3mY$giApvjqKP ze*R6E%0jTh@8;b8dN$?bS9$!&heVk3VM&-hVoH@n2pb~jmiEkf`Zr;g{0H&BQ)TiZ zrv2BmsgC`(4Xo|v6qGLO*>AsUjOp*0x@H0;n2%q7*F}wy2p!Y= z>)BM!mL+JW;&hb!2l2a>2qNzHJ7_Ksb4tuPH|Ock?~AAZN;}l!Klz9wW%}<=s!+>p z!(6hY`}<$q@0|Y^VNUIDb$a+sm}(=$_h^dei|Uu(&*JZayW<5QiMa;U-e5Tp*Z~i$X8@FcOX8O1sJa&e? z$-8t91QDIc21+nhbLjMrIfb-(-lWS;L3FktP^%SvgMD&?` zkl6Zg5o=!1g%3O~ygNH$lg}X{8e0&k71r@@=5^D7@BAw_5vhePCT}Gooe0eN@ad1) zohI4&GSx=%0<9-jJe6q92j&)uiB`|q_GD|`F(fP52%0;`_iwV{PBxH0Ei5Nduju=- zL=++dB}k0@`a+B{f0cRuf41#3=N!w{-+O=>o;3&8+S+maCA!D!@chL6WTU->4J3}a z&sFE>c0AuWC(1|VMa6th5K+N`K&`DIyVXxY4m_-NE+T4QEtArihjOBCY zF>UCsgt11}h3DkmTe$I*+J~8ISts5kH7^lmuk=maOGIC?fhC0{C=;(7%K4roqBIdG zL1JP1^(7c?iG$L?%!RQ%hgZ{y92Hq^cj;z#O*nzow2^<;b56 zcD3}bGTd8~M?(u=ArTstg?-bV_{Ku{DOFV+8z&wlqPYcuT8ne%Wl?K#^5DAeM64)U zDtQkPqlrMt`2Ja$I3ySFHJ7qv#FB^-oXoFQsYowued*B+NbXNWJP~1Wd)U)Y_Pl+iqWsRc@aeOJjdjoa`;IHAX=y~DBxe3nHgc>ZFL%n)Mus&{`a;Ai3mZsusT%*=Bbna4 zO~iT&0=3YG&NeET_<}Ub5`VInfEa7 z=R~X}8z{L`@{Ag>E(d>K+tODv9>x78(2GdyslHD2ex9A@oMnDLev*xq7WqJ}yS-yo zb85|RlxZGiDyg89T&7Wxu*a2brZL0uA_Y|Q-(>nXGDL z6W8A(G7}Xi2$Ud^uiO`dy-!wC3S}Eepq3cbm`7(aff7r?Jl2v3eOJ51Dt!&jG&2#; zWjehyJ&T^x{CAl^i6vpC|4o=B*dxpRIWcjWT%5itOl@eN^zJj%viBENpot8)-f$XtNh+XSBxkZGvb@#1s2_tYg`4s%ukQ?pf&y z%Rb?my6p#@#+|!S4Gw;xx`aB=dwwg&;Y!q>>rE^O)T$f&h#9VAWqSvTG4=fqYs3gZ zuWykmObOC-vyt2PD#wZNCITf$G~&-#alahQcWD-~F{hUz#&CK&3j(#|RCVYu$V7-y zUz7Fw*z?J!)Un@b^wP5e3opN4&DqC|hju!}9!|NYS|1au2BAC4nDWtx2$UevexwVl z()5&?mQ#%3zW(U2^8lqP(1JiM^fcW(9CXB6l!x#xN|3no{GM90-F0>FG?6N%DV0Ue z+gcE)g+5di$7@xp2%-ZKyLT*N5AG(b<9ie|jZ3OjNmRwiV)>qR>?2E4s~pap*U~+7 zM06tpC1PA+Cd7Ef{H!Pw@;my_%uBCrL7j$;JW;0<{i5Zq91u zxS+nJagd@kDOt(;CD~X*1WE>P4q=JbXVfBRGe=8*QdQe4!pH0@(d(NfNc4=2`|W9y zca^7PLyUcpKrJjAiqj9zR^>Vo8;HP?YE^Ryt9JLST62$Oswy{&OKwRyH;)s|sY1e` z*g96<`=aVLR^Z?<#wh@66t;jy+pYlYl zIoYxVwTT};F-3mZsO-gT0-Jn~8PJ}<^_X@x)f_99}R1%X<^ht=;`v14Dwj3wCh zgtqy}0RHfT%PyQ@ylnK%HX=HeVzFR-2iJYf&zb9RGuGSd zyQa3`FR!giLrGu1_l9g`tWB$R_)FAt_O{iJtZc_GH1$TE!!YuLas$D2SqENrx>QP!@ zsl7_3!p5Mc z1GMhm!}+RWu_eoz z)rHp%5v@Ab~476mvH!-uS3ZEU$HFnE?sZI=-kP>lN(G-&7Jd zoLrU~Z&HNm)S(a4P=bW)tB8o>#>;7=c=)1gzDS^!2d!l-ptY>flEOyt&Ywo#pD}#K zmea{7K?2K0QTl(r%idNOr!?s9*Iz5!)w6kU^Rrmx-kI|r>-@}?r;ZS9N%=ZASvI;i z9i5jFHjb6v$%-lidDz!l{wP7hxaJH?+d%6j>7r$LAHI=!_le-Wsy*6+5+raHmu~rA zyo9ZrIha>8`XnKNS~qBgK0mF{pZHtYxYcPIt5i9XHya;N6(vaEx-Z=zkTjL$YZ%G1 zml{w53DoLv_7L;+bK;3@#Cv|=T_;xP({R2wvfCb%Ac1SvbdJTT6T56Rg1hQ@cOijV z&uNvr6|HjjP8T*}R@PvRc8%l#O}bV^2@;3(IuT7bqj%sPM_d)LElqdHoXO({aT-_WDxR)Y^q_ z3oXoXU7XIJUz)D=?iS0lc-T}!2@(%zy}ci;w|8tJY#1ioR>LDkas9BKj09?73Tdu3 z{jln;jp9Yz64FtEMB1h;tZt|?&*d#_EFSqlt=?r6f3@pU8WN}_=iEN+tl|8*Si0Zv zf&p`mtIn7w>TzzrGHkdTOV%iE4g7%7YR7SztLI{#DSlTbmhK&{4v2}>`@9@yKmxT=5|^;aw|A-g z+Y4X4ynI#77&c0`-M1_qB}lBGneZo?2|LjJwTkjF;Eeil{V2U`YCj*8Ab~SvIx(^> z8#{k9MnC3bBN3=|`uI9_yMCJbm#46i<@l^rlpujKWJPHnRD^B07_Il; zI>iqO)OuPinaw=5U;UXP-l!cF+OfMeM(7m+C#0eTiJ`PA;yUG&I*`hSMoVAYveoJc z{lT4uz9>Ng=hQTt$UT&GNEoL3Z6D)}1ZoZJl)_Hny9O-nO?Qiv3{TONT z)#F{PibuHKe(>#7Bv4Dv`Kb8^w2*EgrkrPQ`M^-^g1sqLMa;s?Q4i+l%=O*i^sd^> zzlZC3`E|(^N4T&=T5r4UU5KY1w56ME&#H&B6ymsEMz=Z^jM0AB57WbsW=}^65_aFt zs}l#^R@c*ar06{7&B5Br6~pwqU+4HEfm*o2MrRsAXK99JL-l;q!qZTK#D`fM)u0es zNnI*@75I08Hh;%Z{ezEHRU}YLUb!orxI}vxKUiPbskQkA;NWGcxRu%I$`u>OS z8ZEflAbs^}t287~3s;I2WlFF0noCB6-uC#ERFojG=|wm7vS$`{>YS)oZNk&EziNc( zP1E-HA%R+Q34UCgqV4+-rmxNaVGl}>us`phPOg^YSKLy3^ggYERj9tHf?FyQsD-sh zQF899uYJigQa8SGsfx7(OVe#rNv7RAsM;?qLX4j0c&T)hAc1R(G={7G#c1U^N*}b% zqY4tJb&%F9U(uT7=d!|v-OVG$;z^_Q^A{2gxU%`xK7_@6PEuD#6y``P%HC-^jJs@O z^>_8hr=bK1w*$>s^*npj$jZWoVecbjpSGj)X{+1&Ac0zPs&e1#c zl@smJ9%TCp#zhA*#|$Vz!u0*ukZ8T8kvepd74O?g5X!*{exZ{xj9V{`k_gliHva4n_HI2nH6!JNF~u{J zFiVhVoZC(Hs+o|0c{@SFOU;!kPnHZ<-r~o${?tIafu_QG&lKp5?vNRk@C+6At~G zFl*tCDUA(Z%w~rshw`WGBN)zDaAxu9!6A0|kt5$tYXfx0mi21Cph2lxp`~Fwj`sVr zoN?s#&x>;0)yJ3sMak>E*}v(z2(8P$VG@B_g{sH1fgw)(?_8c_<3Q{LgIB*&ENFZ* zFI^*^RcMfttJyvIXuo(i_J&OAq25kBzFQnrC? zCoLCi`gR3=80K9H;%&yz?YSU90#i$IkA1!y?0GalcBU-DIRM(jIRl;lh%Ti5^c}{} zjE`a{K>}^lSB?uTPBS66+B|zOr$+L33nCdxka*v48~beQ%o92a8&&STS4&Qb zc3{&BPd~wj+U2Jv3&xw87vo%t2Ep z$OLLF>a~S!D&fQ*r;FO2`{ql-(r`yDCOn2p=#K;mj4z@u(bRuw*gVWpYhgj4)|R() z-?ozzzd~;pz2|G))gq&uG@sTn93@D|u{a-cxT~EXI%zkX%LHo8eYb}NmUHB>?S+jZ zRXeNYpSWm$WsTt|K>}lcXss_>C-q1|E^YJoXo*0rrd1BHryuS4f*YdD`#-yBNI$cU zB?S(Y+AAzIxh*M@6s!h++RDy*4wTvwB+%=$o8ca;#%x%NN`FS;>?j~0JkW8S~>85GyK?^5t|4eu{YgIS4A>TT7_C**+2@-O7 z+~}8|bt|=&-7gX@5vVn0%OMs-x7TkNC~P!%=dLdHXFNJbS*bU`Qp2{3Mz5RJsErn? z{Beet)KVjXURRXHHP)!l`>VY4XPH1PY`f@G*)sGVzU=V2@>daMLGHKks36~ zz-y<-1ZrX1Mc+4=otHfxWpt>(97 z=ZaP5&qkEtC_zFlkA}0_u(NZk@z!O$Bm%YMaY?dYFIG1#f>+8jjG+WaGH9FDsRIVE zs7>L#;rvMqB}m|UsiM3JsK+)=8O+^dhDro#$!+_>lWUm=8^9;7AIxyo8OK@+v@`5z z8wXzai5QC(Y%`zT>KV+d?-<8Wf&}J|ygM(RC4_kM58cXeBv7lykTWb|l0DCUPK@Ea z=-%4(m8$T7KBYNIkU&o>O2aD+*uhmx*>JBgi9oH@7yo8=LhbmfTH=jb<<*D{d$EkQ zza7d^f&{*giZc274At{ZJ}q`!v_zm5#&y!yPjAmu$J^)APER2MVnmU^R-5k2D4EXY zyy?yL`;iQH8nA4JdR$`@``PgaWlVE}XS7n(rw^aDB$S~93G_ORG8S%UbHlm?8(RwjuIrWoan}rN=a(Nf`zq|J0m3mwZ#0x9HmRQ6l_mc^&bVb zO^-*K=22z|5?D^Ad6crCb2RVsQXakH4knIEY3^Lxx#~e8>O3tgjj567NBf`YzsA~% zGWg{^-w)#k@cWJBQ8;Q@!H7IFRn>@S+WaI#2@>IC!#sx1B=()%t+^P(q_}XL6~$4! z`0}&#y%d@)DN5Um0V$p|k18YPQ6P~Bm|szJ!kz4X-q8a!*NZfd0s?1YH3!GRJW8ai z$H@q7L&h+U5+rcMnVFBBbrRCL{fw0e)G9Y9j*a^@3!~XYk19L21Y{B@K>}xC)PJO( z@kts}idBq{=18E{#)!Dzvp!R*;zq@lV)cnY2@>+mioZu&p%95ct$qXJOf$XN zrm^UEhdIfc)@87#M4$u-oaxaURX9AkMl~p#otLQ;$uOp* zwOgo~?=bC7PbkP=tX`%%zp>-xyNEWiR+0Sa#a;*T+GGP$h4vh$j9?o-I`gHeqBr{m!Bcwpf!(5XRv~dh2NHm;Wk+m%3%vbajHYUxxWDKD-fR1UA5`kJ6uR&v< z?{kgTTcY^%M^OwVNK`)El7%EY^H$4*jkE=GjmCXZeA}i-i9jukJE66u2iMa_H6O-T zPl;kEK?3VE?e4J4W+P z56emfYGI#9Hv;AFtX-%-h4fD^eeLnF+QZA?JYT6n3?)cllods>#*EWy z^bF_Ss63EBtw9Bkt2Zo zmfT*AvD>K?cJ9ZIR~^bwf&@mo(fI1#-&!HB9{l6QV2MC2Y%3LI`(K@ngG(_!>H@Vu z(CT9eVymPmrESipFYC$p)2wBs_6iBCWAxR9s%O(DbzuCfgG``S{d+B$&7GY5@D$M| zZay7vOg*pi?dQEXN|3;Jg(7RLrW=QBQ+do!nLw?IyDGB!jdSt`&4i7EZ9W?f{S5r? z7%z?zB=DW55zkrf zPpGCn4fo@lg1saHwVHW-QBQSucmq&ikjH&VngGK#@pB!N)<|wz#6J3->n)Me>iPp{Z*MjE&F_xSa2~X z{xMD12<^ASxWC30R_Jy(M+p*GL+OiCb9NX54{c@(-pd4PUF@8fWpr@lkAsDcMNPA6 z=QnI%EHIp-1PQF66rIpBt2XoMdiE(wCQz%(nXhUI?!Yg65w(4@M`i8jrB%!?GK`}H z39O-ta;i{et?^$gSg2#+v}H~s;PD}Sh`BbyqxAGg;$>&Hm5BCO%^7|#CP#k37E_S(k9G13?g39O;CkK=GD zZOnLkt(OIXT6p?YQTAM%nLap&gLX2W;_l!CF%noq73JoOnd$o~IcQ(BsD-CmY1CKEV7!#eSu0l|hNA=ttf90b ztQw4;S2$}(W{#Jvru+E^p%KuS?ge< zbN4_VUZOGce`uv9wYKJYR~F!SZUWC~C`xcaeHrD z^~kwwoc}Dyard20h8<5aE~w|t7TJxIBuL16^l2Zg^c>#;`SkyzQ-4=Xofb=gA$MrQbrWr|~(| z(&w%CDJHNDTu`nHt_)IuN9 zSaeJ$ZJ$RTzN2?T$-78YSz@iO$YaF=O}7qx@*AYZwbz;JLi*wmlm}{|r)gF+SJ7Wb zwBZFebYxgFu*~IJQexmwZQ7f*{L{R~3?)d&<&mTLP3`jEWq9;P4~_(CZEEYU?jK>p zKbc~-ztp;+9X?WpFNkpFC_w_fPUj|S&(Xd%OJ%1o^pFVD8e6%x8aCION465ZL6wmU zv}F+wSv+scQGx{ekRr*SrWtLr6i=`5Xp}^t7DlJg&GjAb7*|!bWkZWcbCe(4bmIG}hD)nB_y*&6j!v@vc&3%T+JUdW6V6bA1bUrzmyTZ6HoPjzZ*DKakw7i% zMHR*K&;{*TfpXlgL;;QxB(R()p1S#5E#vJZHq<>>B2Ww4F50Q?IZso{>}J-fJvd5` zz;aTQpTP%>le-tw>W&>L5vV1%iJ#hEGkOeNkX~ZgD2@^&u$&a7TWFHj?urd>VqH(V z8Eby@UBj(_Y^L{4MAn(_VWRQXRA((q=`Jj-UKF>~GT+LCw+YZ45Y{Wx-z+=ICf5$; zC=tJFCd9M(hAu^MTld=NxyF|T7as91!mK5TKerStoNTWb>(qwV-&9t`R#a%2@6{5| z=KHqjp6%w@^p08E@OQf0?xGg9sPw&w9k%+cvdwwbwWHB+OdaqEehp z!|Pg3tpe{yU&KQR{;qibQ|57NcW9N0D||KGV{b{AwXh9Vl!?c8XqW74dFPXLIZE(% zvG&kyRtKWAZ*z>S-Gbf{fm(9gUSfPzZS9f(_S7j#>XDJa`bMjqv#%Hj8%nWtc}7YE zYRSEGoa-k;pNm2Ig$WKkC+)t}+n%B}rueHJ^t^vwvMOSu)U*UP^j5MOWxBcL?AY%H z?>+LrS@Qj|^eUDOI)Gc>ymAv}ckQoJkfS4AAzIEpFDe=c2} zM=Sq56BC$Kbh`R>rI>kDY<=2rbc(%hGqH^%LE;wC2ffqPscQvcTlK!-=FIZ?mK+9& zKrPH4tu4){Vc2?fwtwEQbS|!PJS*gQOg%%Z%Ljbo*}CY1s)%muw=#kCKX6dJl~csS zJ=rlJVtvV>pZ;&> z4rTSm50g$vBY~-<4VIhF)VHaTdUf|mHvHl`Hap3v-VZFoPo&Y8gtnNc~=&VN$B_gbI3uR_NUv*nn?Cb-TH; zuaLl#Bs8WT=EZ*A9ipGTH$?I-YT-!|TE+R&n+?esp`Y#+$MF2e~On}_J*o<&InYRNgDo@Weu_9$F` z{$z-hDm-t3_9$wy;4Bt*GF12aD}tc}2|P)nC@T|Zv7|1cdLvprM*_9-1fFKG-nUfG zRbmX+JNFKjV?{qbv12$x2@-kVU1h!3y;iluV%)y?=T^4uLm&OajtLAUNZ{EMioaT6 zWC^c(>pr~(Nd#)iXEUzk+M(8)tLn2CdP!{})?K;1YCC&`+VqF2*SzK>wLVDT+eN#U zZX?yYmsNeaRauEZtwQUTu$p&t^<0!_;hO0;)v_lHdi^C{93@D|Wj?UVEj8OBgC2BN zCQz$V>N<9z;Q{pn7d8?H7iBp<*3bh>dU2E>fpv`HOLiA!&t}!oeN|3<%M(d(Qrm*SmRdip9-a!JjS~#9&RW>|O>rWH!V4bFGnNvyy z{nXM@93@C#4W;;!{%hI$f6D88OlgTgt=`M7vW1SH)Cb$d`*Fi(ygJ)yo3`agxYToE z?UVbc9UZ*Y4pX*itNjK_eH0Q{d+40kU*77nrrWeB0WyJFqed)Y8JU-Tu2)&6 zHb1mQ`$Q3qC_w^i53McrU#3nPyhZDgW1vK!){m%l>|E?gwagY#6FVf{SDTdDq`jUV z&QXE{)*d>YdFj47E^eddu~{ZiYk;1_ZofRQ4z49^7{_|B2iw`PaL z{VXJE`)iK`b@O0H_UUo7G+M&ihc~*=d4pSVhTd1~+3uM!(ntmgtUc5_XCG}yw{l=? zhD@Lq-upuBmGuL|aZg7!Xh;l42@+U)D1Nuj1B0=%BWpWICQu7+iXj^>OQ_M=aWmU3u=dd1yB|xarHAHZfpug8weX%98f7f)rYco)u^Zo_r5k9Fz}iEziE-W3w-<6T z&yO;JT6h}`tr|qftKm_3S>U2*juIrW_Rzj_t9Z3m-Fz(DY?(kUyuXHgW!R|t9P(g? z3rBO5AR*VQ9gjDtgZCC-@AJw8YKiE!KlkE@IHXpcqxF;T%Q8F%g=517VR7ui@A*fz z>qn}zAmS?#C_w^8nbb05?UdAg>;T=f^+}09tu183JVP?YMk$Smm`Vg{;jHN2gy-8J zz4L4bjuIrA&<=LpUo$eA39q}H6i9>%5hy`Ip5vT5?3dii*GunMol692ou(MCe7|O4 zbZ3pRNLrIk<@Kw14AR&K=TS1TVQ&SW<;(5$t25hhlpulgHd=dK`nJmYwHaE`!yyuZ zT33d~{hlXgdN+dz4+l- zf&|X=s6U^-F8T4f>Hgg*N)HLt`Z6N!_sr6ikGRwZ3H~Ck4<$&*vpZtqehwPSq9+fN z2-K=Tw{i`p*<=vSCMlje+q|lNqlU8MlZJ7WAc3<l6oY>1=w~DhFm46C-&SiP(-I>;XHh{`e-m z+aUjx^bdXJ`e*$hmmq3kU7)?xZyD)ps+7`J$H?^x39O;C7Cxr5aZKuxF!VI7*PX9MqikYjHviFrD)XejaP=v3sj_)NPFNhl>|o?=qp^RxDE&;kNQT4~&_Yks>6#kWT1lHoz2N@g z3{QIFIclWo{W$W`=rAEtKeUl-!0#e~C$ecI)6;0IQ7cOKycZ=As3oVWK+j^vy)T^D zzJ@UzZ&}1U8vR<;Wqx~4sl}IwcktF7PvhXGIazwW7>*JojI&FziPP(+jjSq>Sc=fZDm_n z%W(A9PgVAk2-G?~D}cGZ*VJ19;;mH|7t$6OYv}GXyf{jbm^`&4+ZlL7jXNdg28Bv0 zMrE5LtJOb7x@!{shP9IVs3Skq_Z@a*m-VHzspp62NxP#Y z0=4ko28u~-AE;fqI!K>AX$V6J5_p@0qPQLk)p|6G&{w4nWq6+mYJFd7%l7U3NA)+| z&@{PBXYIbzKs}<#RE82H&>qF&BsbSOyI0qHczSUpP-}dS9PF^)RkbJGNl$lHH*BGe z9#vfr+gOI91PQFibT@8%ZmsO?wOZZE^hUvNp;qd%9PE6(duoL#!p4Z~d9;uz>$LAq z;T$DM;QL57f4K%3$LG$)^4rEp1Zv^Uv2-fsY>@H#Vi$JAK1RAz771)u=>C$c6Eve| zxITJ&B*QTkmW@2V3h|hzUFaCDS6VxWp#%x^I;{xz9;G#U&MCq>f;el z)Tj=kWq4jVR*UZJs|VVZ;V3}@y-qtnGkmnN)mLiDoG^(%tsfbe)XyPr)pbXNjSm%l zwdOxoYU>9O0TLvzoM_C@dW^Anh%2j=9xV~5h4=kZ)XU#vjQZ_7ti#@DjuIr~67(sz zPTNv;fWB<+V1{?d;MjLp^F`{%QXkY(Q^m@5`lMyrw!Z!K2>ZzlB}kyx>AZ8;T&=3)!NiN_4IX{?M;yb=C5#x9bWU-xnyE&p$x4pmEfZLMNMBU!!L`O z?{t!H>j@8Npv`jd(#!9xF4@4}752ts(`id5hn&+N7I@-Y&DTEfPkuP&TBVAO&l z`{_jw)@OJ(5qetA`ID6=G((Z@dQ8MPh7u&u3siS=jn!;thUv!>#!3WgiBy@rPPag9 zOVq5lwbjQP&Pe59NtjEM&H{{Hs9D(=^g0(kq?+-xxr=)Ir#%yqU`W%+`}pNr-C>^k z+%rCs1PSysjbzI9)(*cdtG_rV6R0JZ`SUt$v@B7I9(1)$W_kSjf}AB`t_w6S`8Lnk z=23eO=pAB2WuGO@ynj zR$}dGZS0)hQW+qDB}-$5#WC8dFem+(Lt}|REji~2r%D)Y{&Hlw17oDN9q(SkeuY*I z=H4@UQ{ZQfKBJ`m0}1p9^&gY#YBftP)AG~`lL*wp{*mGt<_*^TgHC8ocl40@K_p~f zb(_3UyOvN%znd!ewWx)?Hr;EmYL)g#_tSG{Eg<#hNMMbjFEyoZ*4EYPuODwXNE$Ps z7LGm?rNqFk+TG#<^oWODq;UxnSo0~ubi`HG>3CQEDWN~ZdxY`azE_u^5})4wzunhiQTMN zj0Zg}&QXE{p5doEox&4Yv4|P$@$z00fm+#@++b(#X6Fwb#K^M5l+|qhhp}vXK!1)B zB=8JB-M~M*F0;SutnHmSOd?S0@`~$h!C4z_`$Od8`G7pEVex9(#lpimN|2CG_j?_9 z$G$h~z>|8nWq5Zqmd($ScUhKOw*0TVB04&8(L45{W(Pjhsy#yq66kf>CHrE_my9mN zk9g+hNT61H?YpdXK3o2ItLQ(@cDLcT{5|;Uhxs{5kic@Hb%xzv*ypIpOz9LT5vY~t z)E#yte|ByxCVaK}&{H<(RTw+WJ93mDf#swqKCO~iTwhylVd+qbK&=BeZ?o%pZ1~2q z!bWnL1uVk3rj|lClAr_$EGJr%sW3ye-D=dfyJda_!+hI(p%J$tLw7x1wY$xPx}T8B}iahp!vr{H@>{C2fwt;nj?W)Gv3@|hcmKs z+ft&I+&PwqKdRxzKNNA~C_w^i53Sre=H=D;PiAKm>qrD@)tY~g{d2~KuUIN<6ewcP zJH8vv?Eh-YQGx{49z_{&?KNw?;-zu>s;&}&TBG;gWz{ZO(~UmD#{4`dSiXCOv@U)6 za+Dw;m&b^#Hr%Uk5T7#Ehna7Z7x&O(*=%n9fbH_M#wlpuj# zr+Mw`!hCIk0z7@gXNf>9b=CuRl)mS;XO1XyH>(2tj=J8d8jk}9qu!(gZ8`mu9X1dwmEI|UxiS{OHW|o!Vm3TDP!QW&mf_xh`FP}tXHt2fr)?r1v9)x< z?Xc-PCie4Ocv9Wwe9ojiQZ2#q7dDp6&Cbtxi&|1^T~5AuMl(L?sX-!8OXOqc&+Pn1 zxcF-5-baOb)&~LnN01#u2@>1tJ!TzhWall83L=%hlGS@?T|Rb3X^B9sO3NRysjIT{ zpxlC(|Fbe*I-n{q@Zo-w;~)_hQX@g1z~{yu!$=}KJnE5ndLt;Md-*d1>h z?zl&MFICHypWl9OXS{a2sZ>j_)a3GTH|FQFa^*6{s!cgckPx;X<+J9Oii#3!JGwY8 zcz#v-p*#T+fm$L@&u&_CzuTfb?tS&*|JZvN_tj?{B}j;TL|3-rjVB3T4Xp3a2c=I| z-M5vO2-Ff@D00M#AE+jX(yk47iu+8%@fC$RN|4ZgykO$~)bEsMnt6Ez@{vIg)HQ() z5`kJljb5^t{@Hk~a6v>gEywNeEnvab%1gB!{U+DlzD=ue*8wxwhfAe6N{~R0P?SZH z>fCT^HtUyBR3cDoMBHPxV2KT1*@G_LYCY)rl9fD_ zjVI(5-W@%$49`9wA3rqtsnjx9`t8qqo^_KiFIduT#d<*?3yi9)=Pm&?7YVnOcu;*_VwkDV`<~s3rXN=RNnU-;wXR zd4t`4OlJ*1f`sg=>8v9^r(a`>=+<5&P)m6FQW-1$U~4||?&T`2_^CZk+$!*kiV{)V z=g?Q{*VoNwdJF!fYH9Y?{7eZ)-ezDn$p#YZt)DX&`lffzCZYsCgw)}~s}8#ciSBND zSCoIOR*!Ee9Gi|3B;-^LZg0=E)Hb|t(Ut}zPz%3oPG5FtTb)l`R+*1tS<+F01bTs@ z+tl*B_y`04KBq@DBv1>#Y))(8$GY*9doS7QLx)uS1}J{_QzpWX#c&tZhQ88DH(RZI z%fxp^1ADn}^Ru`^f6u-*Y}FuzCpqRJUv1hvl6O)4S+g(p=_o-0ZBsr5(Vc@GmomS( zBX=W#TD4xkW)%{%@M2D`WW(C7120>`hL66}$qyw+$oW`*qZ{{L{El4?ZJ&+=YGJKZ zl-q6%c*o7u6XYq9f)XUq({$VPn>sx3;kWc#@x}S@V$V$dME3}HE@*R~AxiU49~EC- z;o-gwwN-z&HPun`s7TZp^H}S~QZTka1Luvloga zKa#{I{urrk%-xscZ=nrAd>?Pc2YnQyzA?cz+&W^EHnCd^DOE^gze{t@!CCl`v+Int zuXW@oK|(wWFLD2VbR;|blK1Ga6y48>f)WUL7lu|9W{@IPMd{lmvajkkf3N;5 zxX)-y_wS;_k`Q$5v!*fi_#`&ZW|z@^M3_Vf+N_0s6W=mj#&+DVn1089uvCIb1f9QY zq7$nL8>LHLVm;b!H~zGe%N(`PZ#0rQe}L86n5u;awwFfwIJ(FD(aPQ1)l3^QNozK( zpOgo}f**HCQ6V@0zuQ-^{n>)1EMScQ1X3ZxazHu_Vmv0dxlIR19yJ zV$H^SdetzuIHJA6c4foGH|$j*g}3h|+N^f#d(1)?Z8uDb-^g7+?bagP_ zIB=%MV{fV-QeU%LC*9cFx~@E{{TpT<>cNh`$-^&Je#7pUD9F6~iT-0{a3|izBdeai zZlPhqv*&DUFGm(JDnDP5@SL5?=fEz|90-4jVp!~=dH!nu>>1Iu%J1)ki*gn=#(XWr z`d@Ihu(9RfVBV?HZDZ+cGZ|V(VikQPr01-Htag3zeP>}Ku4@(Tkl#NwFzuoqcl0f9 z>UZ&%Xoq)if4=%=igr`0%P=39c2|cN%lu4*$iYf26ghWa(t$T>kyWpI z|C)+g_!V&cB0TlAmkd1VLOH#}PnQ(@Eu^u=&^`37LEQP4qdrBwl7C|tjkvy$-J+?X_!Ac5}<-61qKjKBMwsx^oz znt}vs$=;19{Wr@srH6icQ$L1ZnZj>W{aAXPJud!EZM0bQwR-9)=KZFJ?iJpbp#+KU z{3h$X{Db~s7VwRCJDA}W@=!1mTItv8A-!cl_6 z+tN2#uP!&Y4hAAxTxQW`$8oea~wT2(N#++wmVQpRs!hueJmb@}s8~(Z%M+p+g z7u{eEd$Y1{rc-o1SG8fD@l{x_T9FcgS_|)7WgW8Eur~OGN^`PEmR` z``PQhrS%d)B{}{UYT*ek+K-xMWWBx1>i^^{!BK()mXo4fT0DnoWv6LFi~}SBweV~X zeLZ5$G&b@5d@Zf$0FDwQu$*W`_?aEcYEzkI(}qg~YKc+QpEE!6B7< zHcODeauQMZBdJuBxcK!x(wmB7E$rdw2D3deJbFp~w5$bf8A_0l`}1xs!?;quXN|zG zdn5w2uxFs?gdu}?!uP5v6I-ulC_w_p4|GS$tPXta&g<1C*0ttHpqAX@guJ`Na(m?T z8+yAh$8q$REB8$OQn4QeOrvx2>_t(AoV4PF-Z<>Bxz<6FAaQN!V-uZynplUcTG@qf z?%leE)1_7tfm%3wQIx1-rTNL*^HX09tI1J<#Q$ULEWooko(6sd2_ZsocMWa{cDIYC zcyV`^Bxr)fu;T7sS}0aD0Se^3gJQ)g#kENB;uI_J&D>?kY?A(;kLLmQd1rn*YqvYM zw}S6DICA2|W?LU1khtw=P`Z6bDXY303^6KYvSrK=-@cc!lP&nopz zm}_xA7*0ay*j0}D{o|g3GyhRMWKQt9fjQ*9{}`B$Cxz5|u&{;GZBYCTNz)p?x?yDM zb*So?QIYoh2fb}^;>6sWHXV8gd+HJMR*F0+X6_y#oi`RDxE5~ZJ|bgTk@w2ILHO=m{)@XS3;l$Rrcg3JCZeqYiB)rn*ls~jAXtmh*PH=*2VLrB`cN5(@;uAGEI;WiTV*zVd zc zO|=G#w5%lGj^1Go3(BJqT&rHe$6|VrhuAX~ZCv^oAU{XUHp3Rc{40}if|oj+#rn=) z{;@ct)h7Gzf)iW|Q`@+syZHVE`iU!Y1<0B8GFm4l{VuqK6TF__EQ^Xo<>TjuRjXS` zh2UD;%ha^&rSiyWYXhx`-@G@tgcH1;VD=+#P1*5OHgmy_LiRf#K6m(@!Rv;Urqf&h^uY|2u-qpC4+A}-~YARcu{Al(s|D*B-$q8OhaDL+bdNOE9F6-je zVhX{vc&`LsewI|0GaHn%`s}-+^jDnV^#tcx4u2w+KJ8@v@I?xKw=92(?)`K}Y#I2; znA-!N+Mu9^qTzwgRyvrV;1W*o=TXyqr~AkQQwm$%x2BPt;9BXS5B_CA3gHPY3f>2A zq?Nb2`dKX(q>)_03Er>3sVa?pWPyK|nW1o+6(_is$HY5gTieuP>RPl>`BrNA`tPmg zzoCJWOE`h{68hbZo=?Q3h8vB`#k(s6*XnlcwkX!hLoDBiHdZdWC|1llsav`FN-p69 z@8@A|sr)TbTXwNt9qu6bdkwD}{w@Nmyh~mav&wg~>Ue%DxP%kD)M2&Z_bFtD)cGv; zyg4K%xE6mGf$_ZX8xhvClywdkDRK!Xc&WpRE%{934jpQa{@hL>xE6mGfpz-1Z;3%` zV$HXMTSzY91g|Gp$q}?sJeXczWWPT^A-I*3zTSC9bgH)5$XuhRLU1i! zH{kURJSi@h*=|G!_mf=03GT_l3ZdRVit{lejGlRhCdR@ zMDUq~pMQYZ*>)+smpEbi-MMMp1{^};5>8N<2s?foq36b`lt2mDBO6IlWm}@wfLatUg?SA+ ztq>6+&_-f{+t8vx8U99Fm=fMzsRk(~vY8~>;T*WxL3RPBG` z2`W)eP@R9Z;Q+}HiR(Nm!Rvs>i@y_%(I>Pk)audtt}rVsws#EWYWb&l(PfDpPP4za z*c7wO?iv1@AT5lkuJ_+!&+`Sz5IE1!*)`pccgWxra&o{-JKUvVSK)hlNiqaUFkVg! zZt|}Pel~M7fS?VR#WvGoaBn7i17|sTggrdhOrDWrlbT(5)&c0imGLWsGSc^kQUOE z!lX7Ry{Ls@$`i$ulpslBLNA*|lzEQ(CKBhI6QqT7-R^EOd4eRU#fc)DvV9%Z)Y9by zX(4_5*A(_@h@`3N)BCWfUpdyUj{|QeeGUKmrmr~aTJazGpw`Y?CFL)v4U%9=I5Ew$ zwf$`VZ-TUtrq+{`(0d&dIrBRC;CU+F{IV$Svn?SX(a2(4!s;jLW#4M&9CJH6`xZOg zJKq>F?vI!R0s)(#xRB;Hri5RyV?sT(KByFtNL;#TFL{De!im5C8E@zBe-osI_WnB` zFa1V~9_?f7+`fA~OmyG1-3~v!79tKjXJv)P?40wS^Fo{JqW_+yHbFhc*HlFlK@v;} zCniN-6$L6SPbTM_AT6Y+43pX*32JfTn_E}@qwR8nw2-FS{AvROcFswHTAaXe@->*4 zpxXTJR>IrW_MnS)9iY8Ux6avh^EFk`lqz0>RBK55cb$_2wK(xI(?Iq4KofS(IYC-T z({qD*YHO$TqE@*hzkh9Gl)t0|NfHwW^;7?kXOOgzrsv`?mN{E#3n_A{zgq7Mx;Z*DZyyAH*=$?Ayp4PTN%o^gm{2pJ{7h z7~eUNxR%>ZE~*eeo>Qu98zez3PM~*2Z!EUwim9^m!3okrdSa`$;=zsi38_NBCP;!> zoWL-q7WGsci3!Tn!dv(4a!X2(glrIzq;wIrQ$>=*ME=aV#gfi*5>k~cL0U*t&7z{? zN8*21!th6J+my6QqSSwzsci zt&%E|P}->_QvQDB({k^$ci(epd-DL7Ed3wuxx?7yd?D z_s{*NPt5DAjt%?%jBbo|v->NINg-?u2`=FT_PgA(j0X}CT#KicwDEt(2IY_w7$#3P zDM9Hic5yfAfY>2j^g?`P;gKTjBOC@;|#mng&`OP@I1 z_v;vyJW-ixU97TRFImVZp4hg@-CB{go!l_oC!ko4ow^a@E1y*!BKr(Gp{FU7L8k9N zK>D589JghUhwM>#GK>akHoIH>fIv&s!f}+ra@!o3K~7rO^J{o~Xiv~f2Sjfm3Vg~E z%e6So?ZN&iAld>E(r(}mF5$!u-wduCqugbUFH^zB6UfI%AZAzc^XCNDQuFZ+h{1{S zL4E?ZW6aZpLvF6L9%*IHPsPDTdPr3dAZouk7{etzRS&}^#q}MPPI~St4@71lx&krE zH9WS=;~~1&`1G=|-cVj$b)$N^>OOMOzqRbXo$SHN8c0=mU6IGji8a5C**jsZ zmpm-0fekOP(F=&jgBHhdf@`U%iUS)9fvC{)r9Ur|jOjAO72V@0pVazJ^0uI9--8Vg zAW~!-x06da5mfb2wUYFF6e+89Umml-q2fD9cImG1laIv?|Q z%SybgIC1~q4f@v6zOqqF3$XDRh*4l;$GO!0oZwo#X1_jvz-rNJzyEAM6PPNVLi!z_ z6@}2agcB5Yh?QG|q;E0PL^fNezjR!|KPGgtr103srR4#yv_{eL9X;88W)(5b zMvp4{mt0uT_^q|K%nE1gf83wL2z%ox8^P-7Ty2XOe;@R=pI}&11jJLYktK4}4ld!u zkC!qUZnx6OGf(i%V+jy`K=_oM8p{c;bv0i)qtJK{+4v;3l1)GyEoz$MyBw>?)BE^d zHpAHHDK)S9U-N|dgWXO*JO(0h&N(slZUN&)HE&t}LTe!Q0nrbLe#JBUQ~6+AT&rYc zVdKvqyyeW}oq$*hL?Ot>^7W@#-l}xHQL1Cu`e+J?t5FdQsSLAVV zts@UV>jN*l%gjH02dUZ&#C{;G(MBaM;e=Yc-tc_%%-YV1F`LKE$=f8(z1Ll%f2E1i zui2Tn78hR|=`&5STV=(HF@}?>_~*mQQ+H}5Y;h#vM3ISwT!Xf!6i<&&gH*-$K32Ib z5q95B1lPjnCgB|?z8AHy21$bb?u42dTr)0e;@?8W?58$?cm>bkaL9+J$5FdaBnc<# z`!9)m-~EZvv}ZX;l^f)I01%@yG}}%#us`QoMVgs=f8Tx8X!W295SPHl1RyT&b@LBy z7p||HyU%#nakNrC*{*ER=PcT7Y@IX=i1;zeDm`IRIWFPlHgU;OJ?dDj5&Zo?AmT?( z>)qPC6}gQWOEi6sIA;8oc8p>VRtQ0=hCr%Doe5LwgA;Ri?%(rwnG43<^5enA8z6=P zF)47SLU1kK7GMVt5W#38ebI`%Os@9WQhnc`lg6s;H51hb)nM1gU1NFaa>8eRcm2zP zUyW*68bGQvsE>hQW98vKN)2+YHWSzAQ9*l*nEB0tNEu&)*h;u$m;WKX#;6@e_)IuC zMrl`Rf#?G^3ZKZPq>2+%H;!MD3W)wdpbZ`u*P`&(o;n)+HvsIuomxBB!X6xdcWhwX z@r2#ClY|o#c8JCBoR=zQiX7EX*uAJx|Fj(!_C#yioiVVF!X5)xDmZ=OZXl)?HAR(X zw<~c8C$P7RS^S6L^ojBPl~~hbdqwOsrZ#UQq>jsV`u+IyKjF76|M|%46xVRRMM7{Q$HE<;Q+PCBPvS=cxuch45 z?@p?Af{kThqeAtMmAHhL0``@1&1b{uMRDZxfqXn0d@qI*T#J_o+}j7lQ?TLJyjBHX zia6rz&HAT7V-%&(84Yd&(YtF6yKg56Cvdb2x&O*=M(0&vBNe0y+X_!R*P`EXY)3s9 z+4lbC8gekweiNqmS8T@=#y6HKZ^w!7F8D^@;d0lwMf(EH9X_LNf+U>4FrNc}wXfgL zGd({HOG1zq+MuwLs_+gk%)y7c*#t>=yhzL#Ib2-o9}B4}a=vR^hX5Zd*M*igK@v`2 zm}V&)8#VeAv>M&5n}i@Ov_WBqNOQNYwV+Qyn;;2~7m07$^$}-&+778&cByMzrVA~t zJ^?;9K@v`2nC5338%qy$v#z&)A$VL|3x8LM>>q|%*H_N736dlxO2u{&729rwR1Lb= zHEyfVXzSy?K${>5CooJiNKUE-9E`M%yM8m!IwwdAf2XibL{ksPB|KjGo#x1pvin4h zOE^JchnN^xBQCaOKkL?vv!dAaN&2I_Dd0T#X|hk23Hs05Qi|Q+S#Xa7_QYk+UoC9d zKxLEW-0{NDpu|{J>UKF#?$=h0kj{NanDM>kyf580|b|F zg8L6}Cz80e=SH59)`}}C!L@d+x~%6vaLnjfZVcGKKhGXVS+ir0=`?y_k4$49hE?CE zkH;9puW6K(p;b}>@eyJ7bw$LD&8^37%_J{5l+ zHLYan@PKNAdx4jHM{o%~+vJgRuV2#+6z{t8@Pq+Y*iXMH1lQtEm(#9%hqbjrwx+fF zUH)}}!q~@*4ap&XzJ%X#+P}=ZcVpg8)*3B^O^^grMFdYFJW*BBR$E!Nv(>oSXFKPd zpnRZ>&kemq+7C0p#`?XPcK4ay!>Tpskxh_<$BP7&p_32yB2}#4FO;`a#lL1y7zzK< zhRAYuA=tS1ceA|>_ExoSlrCozBtaWQV3>bnf!*F0T3eMXdn#px@m7DBM`YhU$F5B( z1-MOcinh1S#c!<>KA9B>Couf*LMid2J$}LJR~;^nsMXlY_9lB0g0zyRs_~+F){7|x zY=Y9uhtO{2hkP_k zTYT^3heNFKi&rHfNQ=L#!znkPi|^TAWvJE4wbJAg9n{9F}^akG4e`S1Et+X;90C(i>{j{U{hfu59 z-tSBv7bo5Ztk!Gxd}74*z_INBb>zvv`trb7 z`Mu6od0$MpJarygBKu0hiM3fS=?|;<$eSN)K|V%REV;|A%xIbQNL_{CTKroG+!|W? z>7Ii%N6WS4>zG`^34B%>uJMx2GgzzX=W0tojgY^+3sMNK#Y-CIkWbzU$ewqk9C2xY z$t9d9ws@T$0N;ul?8I+HsgF0?Ikj|{jH@w0A-I-WgV?)&^CU_(e)d}&wg&wAhOGfx z35EHW4LCL8!@;<^e@4kN`&Y$r2`8{s<}Z>#VmpQ#>|;OZb;?A^MPi|g6I_e89(Zay zd$@K4N68FB2Po}|6ZqWxyw_Jc&tUH2F9W{K93@*#+N2O%i?=cGcWZyH*09%bdH39G zla~qh^HB}mC5{>VDS(}MwY9DOnmOf8*J?bgJ$dxz8?Dx0-Z z39g0XBYpFR`Q6^JyS)w!mXA6+BPU5XfnjkXmBew^8P8#KmN+`|xVRREDJF-2w{2vj zQNq`kP?&zFl{H8?E5o=1?GZuY1Y+5(TJn=t)bgyJ z=5owr$CDum#!Cc-X^oDPk0PbI!u{TFZEuMaq=hyp><}Bf50il-7TE+zc)UpL9RH_q z4M(qU@autk*<+(*DL2RKBMB!kOr_x1=o%9#Z)ZAX&zEq5w5SXdW`iqRN75_~Nhl>m(+U_TRWMT|X{Lx1q=hyp><};;C22N_Bxr-eNKDvrRh{vY zG~-1QPGFeU{x~*ZR!!2Z8Yf5#ZBW=D+QA%LmH3%ElJIzu=&|x#{OsUrm>t9v!Cai( z5=p`d4Abf)#|F$m3YvlB1ZklS3OfYMatfN|BngifiI+W(t23#BW>QJQ2@KPUB*zBK z)*3Wh%L&p#8x)3l*S~A+gsBf%q1-;fztQvc3>SSS>os8oL`HiB#P6%x_|Ng`FINVi z7F@!KY?mkM-Rir`DgpTIZc(>kdm^j$kw@dM3NGOUrmA55)Dq_gUdOKaSgb0rsTEy!$~RxE5bO0dJ`tymr3uA142rzgTby zC)R%aMfZU<8kuY3H{lTrLIT#E2$dV%Cn*Hi;_D|MAN5Da)gKWh?_G~F_(~3(Ba6N0 zD{=0PubTU+_SIdV8hc4&ut-1`Qj zWWmd=6@qK2>q{Ch6Fax394&k1sxP>N6Jgd(eHN@psb#N7S$zM8fT|nAW$fC*3cU)DyKaIK@xmYd3fB9A4R{RxIZfU^$c-m_BNM4waSo$ zAT9pP!^zxDy6wF&t)8;4JSV4g8=R;p z$5#)qZE%9LFjW+Wd$9b33<^yvFLpaE`h2%f&)yGCa9q1U7HfS>_jvk`sCQ?c>=Sxa zuRiv@80m|p+q0uC`&WD_y8QD|+@G;kKPB&rjBggpg{ObhKjpe7KCfFW1Do&AhYfio za%97Nyt~&x{u*~%Tw8iUa0w^4ZK#jI9c0cr$A$mPwL(crq7)W8|5S`>jq{@NP7S%N z?<+BV@&lV736GcCgT3KdyUI32wu>5fH!1|zLfhRw{UuVa!hFOY36r~=>EIEhy%^Bm2@Z=E?1uN6@k-F7+k^$4AVY8SkKThTyF935ovB5OhS;B zyZ7&U{o$Ity?YkeSYI|$-d}RYD6w&r!6iIi4AXu^=yUIe%UR34M9AiONeI$H0{4G8 zy8-`=93dBut1lij@K$op>jnub1x*_eHA1%EVTdVaZhK!dNjQOFswYkB0)*#ILp)4| zAT6|!u&c2t5M{EL7gPQ$VcQ@Hj~BxUHCPvjT|nGUh9E7pLAy`k9+Rafjp={Yl;4yn zBE!C&qvt(+Uj*k|Vn1E<6yXy^?3~JYEbZ)cN{RBV@lJ{$j@FqDctSQrp$@8I|O{Uh0i`9vT#J<2Oz)ZL=k-~@(W47ers`{8bkIbnv&!EUV}_NH$ChMP2&74CSGFJYA&c&dGG6%9=DIUZxWQ99Cz+>~$_jf1nj6rx z_wbwt7aAyYx0q|cv5*995P@N;O{ZrF0U}2-1ZklSn&Z&4!(e0C(zf#by{F3T2agxS z31w9W@(~F{q5DY*(o%c4Y17Avj{~d7_YVu({UG&yJYKb|%C1=?{wiHj)-LMI6cNF- zc<%~de#VU#uj++CIji$mm=c;VL3`L@oY^Qw*y~FY_oAppgfl1eDwV&)zi5L?D2xQP zM8^grG}6MjxE6)uZ9pC{WoUy-D2(x9?~|}E6>}X=XrzU4aV-ivHhNVElWSo#XuSW7 zy~={(BAW8i^vgA2RKXQO@8?yL__u8R8TM0)&l+k`o+y0z{0;GAQzXhf9w+*g2$imX z_8VM_*9V4a&IxWydo)fA10qi{1ZiPR2{u*$aVU16Y`S!&;1V7$hG}L>)0#l4z6WAu zG6ZR1O!wiO-~FSuK|TfmQMzb*X;yk@+aL*#7sE751#ezJ6b9mWG6ZR%jd6Ldih(n5 zRoG8J%=DM?(&OBAiIRlJi(#7Af<6(5a3F3aLy#8QXp!oY@QTKrdUt?W1lqfS;u0P& zhG||4@&Tp$8Hn$bAxH~j`olOU+SbE0cP)V!?f*~|f!uQmj~Bx<69)TOAXTY=D4q;K zS{PIDXQ#!s%V;Af5DTI9)7HLU%e2w9K@uJ> zhN*?Z8ZXF05D-0*AxH~tESqsz9BqiLy$BH1>v+lb)$Z9gNW$aAa6;Ry3Pi#GAV>>s zWZiZ_=q0hWHv+;B;?DyVm+*KooX~b3L(cP5zb7guLy#86)S%)YV#RH=@ezogkn5?C zdoJPeVmP7gPK8uu&bU$3PKF>YjA>@&)8bZtZ0(bPXuY+$c>7~%+XhK^yckYsyNe)I zfw9fS8mM<37uUkyv;B2U95>O%JRqunGsEZ(wzz~77*1%rOM&nNqGK`yX<kY~eoZ>!P&>vkD&g#e0YC)(8Y#BTTw-tu#!Cc-sfEHk0}ywB2u_9|EsTlI zB7ieYf%xlafARkF2ipcoc)S><7U~c;fcTIML0V{oPIrJ4_`ybt_G7f@Wn7=fC)B4lp3o8#Tnob(lQTwT zp5XYQ2OvLO!U=U8j3>0j1lPha+Hg+Tz|sx0&cspaq6Eu|=N7{mVJ^byudw$C_-2Ny zLwxT;IZvFzQ8~uPkLNf#FMqw?CE`bC${|k)hH2*l^jARWK-5i!AT6|)V52h-kxOTq zQSn{|NqD>%rkxA$whf-lqa`!VgUJx2g*H-MfnLz|eKG>k!~da~KHgg*36B@UwATT~ zsE6RgReET)OokvWwDGeZ8t=mu1Rw6F$GNSK@m?QEc)S>T&Iv@ro zLy#8Q_`$1N{Cm_wAljD*wYJB<6_JF;i{XTw7L$PJ0L1xZ2+~3u6SH-Ve-oYwPt=>h z8Lqy`JW<7OH99Kx_nJT`~k|p^bgbM#TGYNQ|s@&ukp;^^t_fYlpwK z-KIc<0`Z}?<5?<1ycXIh+In!jFIokNQgytn+VTD_NqD>%rWWdWuf>4Km<&N$Xe0O1 z0r5Vy02^K1^IH$WyW|ocFNUdwYT9|I!TCVki1*tmF0O?!eQw(){@vgT5YtzewjOVD z-akmf2@F#UgpwCdH_?+GjV48c+N*0YLz$!(-~{<1_?yn*-Knjyq7@|jF$)uQwxP} z6F`&z;_qY#(n1?__7<%E1ftOA53Z1SZ;2#4UJO%vgB>G4v27LE6JNy6jBFtszf9|$Yco8LK}3NnNwEjkM%c~fp^IzJYEb_3xzj&$oZC|{mt6(emlj*wd}I`dP*7+ z;lD~7^B%Z_OXCF20v4;hO1}}+#r_IJzdOWh@LG@5 z3$xbTajVWHoZwFve3cn`TTEZv%eIl67TQyZy%%%I8aW!;1eZ`4iHpbf>iK`^W~UI& zp$C5#{#rqY%Ty;VOfT0`%j);cqh+guf%b_GR3;cNg^|8L?W8_0U9Wf>XTZ!JJQrocD#CQypL_q7AAw3{#1~*S>PSBCjV=D7aWZuy(wlEeg+I@|`;%3E%2RmaK~0jot= zT)afpI**Gd@&myoi3utZm=~?pQnp>4(n_YTK&#ZY^LUGYFX24VvcT!QvELHqn*P0_6= zx%2$>xLz~++x- zJ#$1pQLQVkrh4BXLRR_yv+KdfMFy8B1kiMLIIO>#Ia-O-Vg3Ruow$S( z7*04fyAu!@cN%66D=9%*yl&vu9w0hqFK^=7C@$ggVwgMwO{)#WZXkSbB_&7;V4CAGJ~GE=d4s!Il;BmlUshSG+d6zHP>D_z$M8MPChQD8!cz{s%DP)GS?nI z+^eJ)&)+!r8&E#@lLo2E-cVMI_O#Z#nqrS??lryO{_Yv}Z0)QfKH?kq8M4je!@764 zuUH;~JzUBKy=19fM@(~9E5Rk`UlD<$57`DA=W@xIyA`cB^Wwx?eZ4-vpSP%Ye}?@A zQT=2((ZiTwk3M7@R$w0p6eY`av7&wN**!JwqsLyG_ReFkeXDLd@w_gkD(}Mx;mX+7 z>Js)!9BKBWzMyF<)6LBrGO4A@`$wfuTvV&G zT-fu9shu995WIg}_}tY0ZIxTRS%JN%Z|%9fM~i~Qr}fQ?i8Tg%9ef0^$tEEinD2|jjd+Vu6hywKIly3+2LO0W@b zSN&Lh)66nrOF0||UvDlW*RIKDm1qEaGhj@m_QOk5t@C`>%E%AP3t7K^idAZm6TCz; zZR^LZa{Rsu){H%;6@qK=_69ddrpYE(Z7gfGy>VG-iJagiqG>bVq?dp1DQ}g8b;dj{ zuC?&{Rr=w1d4=~zEZyCY)5{W8Y0K-?3&ACvP|NC7{?{VLyRtRxrkmsh*J?9ynO^Rj z(jvpRSi0+A_9oSzwXIn#of8E32@764Mgrm&8_xfY1MqNc+p0}Sr%^&wG`bix3E5qOPz!u zEne#IwtcLX_PwO8Q9nLOpVbAzB|pk8Ewa#$ws*npUrLsOA;g*(v@xd8Ytgqz8EgL-AIT-0;4KE8kI=kwYR#P1;5V8=a4qf) zYFaQn=MM{}vHX6xqIi~^PcL7$# z!)5I?+w_Lb30{VpW*%E4E`*e|bl(yR!L|5XF|5B@a73K)FJW!S4R7@9J)9G~4B@ne z18;@fnf%tV_qh~;YpEXcg5h~(-2xe`3B^2N#caZRI49K7Z4?wF^KM^c2BqvHvYoxE z%YXhgirttj`~31yzkbF|yxlrk?wWm34-ZW%S{_5cB>i_?#Ebept?aLlDJN#(el70LzGq3QBt+F3;Nv&^1YwB~C zLU1kjjz{!>gQ>*vcbKXnzeLG4x0b}!`nQbzUQ6B!PdoR6;9Tdc5z;%$Vm;`9o8S^o z@KVsU{iP#hSb_B7#FIdS6I_e@F2}zrdUBNXsF&MZS0c4Nt468f{tmaNX{*-skog;) zG&2qECb)zXYR-#?beE|f?K5j#o~967i`T5C)je2Dw&+{Z+Vgq4QsOuaA$xns&BzZfTVBw?>`ap%7e)w;oOV z5$2HJM)+HAzul>{5>BZ8)mre#zOB*Nns@S~LU1kaox#rg-GL(K%=uU@-|5%te+#*vPLNO0r(!JcL z5L}C&m7 zm~ax?(D}ne<{ySyTNl(7T*3){Vj7%b+9^V$`e%q03@0vf2`Ac^U-aw7N#k-Q++~_~ z+Hf(k;t=cl)6NRPwQ&Dv!dZGh`wSJImkqL>bQ~?XgcJ9RJk{?9T{0RL#S{L96%7-o zdkwOVZ5*W#T#KLl2WQYV8Z10r1Fg`{i#-3o>W+BO{nM@I?%d4 zTP3&_Kfw_0kX{@ii_L-)rQYY(d8_7Uyz-|2PEZ~cA#WA&7B%m@Rh|z{@Y7;7EyutJ zIeVqI80)4ITq|Y!+{VWI=Zq%;TS>Q~5pu@}Um@da8eGB&euk~4l`j+_r~K(FqP$gt zYc1`P#b|N!nz7yo>)hvNxXd>>lgKuCsKF(iP|uW2do^74&X`%$A2UQDxK_$pUdG@@ z_lM6sFK;%ugcIt>>6R*7dN0T$yiadZ2(HD)U6^}qK1fcxzr`FWFYCM~<1K^t zeDGFuEkthKw#h6$aihT{oZvMJe#z$$xhBOX^UjM63cQ^Pm%^>8IfLZ$ z;|t8wSq3WvZyBoZb0~dDd8)Fo=55Sw@X?FcKOY(3i%I_y^6+ZiI+p&0G7fTr*DTDJ z+$|x4tLc`1i{}c#wRk@dcXQnHlc^V0wd%&|f=f8TYgW^KXjVd=5LK-=xmAK|@qS*@ zBI^0c@v8%@dm%xBOE|%67S43K;3p534X{Qm8mJIli}&-e>Ls+eG+_4Q!8fx6mvDmD ztfuv@=qIa`tY8)1F;gM979SbleK4e$oOqzLrM=rAxP%jGoyT-5E?0V#w$fBk39hC3 zyN9gdqC%rS*2@#%i?TNp{>H*>!z|~BFfpfaAFE1=ol2@W!O#AMdFnSqMDOzbtxB!e zDg@V3$3fXBO!y5PVd3mK_pd07Cv=hL|dE#8S#w8TSc*&P= zZ2T9&wJ7Y^7;-vHOe+v-t=o~>MPGiyLC4@@#4H z^9=dR-WYsNS1-5nq0#2P4 zu1+JY0)th8Yw_BIZ;;+4rQSxE8NXP5X9P zgxojEQEu+RWtik;U{p9PO{?_6rp(dAb;$oj`dW+`&8l9Ws`H88=2Ftf8 zSDRD9%c=y^$~7mQVRe0E$imfuSQHa1gJ1n%&N0fGT*BksRr--${|7hGcrM!5csg8W zDhS^n$3(a|!L|4u0h*TYXt=C!JF~d?CEUd&oFMPa`L4FV{ScAnZHQI)=2)eyl-AD5 z4c2(oTPxmm=x15qN142QIKj^|1@HClFp=9Q*t(K&rb2Kn?1SlCR@mWIEJB{$&{Ufw^# z87Uh=#pI@8)?Ya-<~^H2i%U4cOC3&hm=huY{L@q1PBkKq6I_drC9oD}HjFr* zJVoVdBjUJ(6TF__-PzSq^iLUNrF_1^%ywqIKIc0(v29UN$xoifxkWk;8}_)vy4P1r zs+-2x$u3%7fcM<2R%fk7x^VG5!n9$>yUeRwzGyGny-`Z;q^WID~tmmJ{nOwpNoPjQV!&9`)hdGxS8p^`= zGg!ZV*Fhn;7B3MPKXMKgg`N+zywWbTPobsJi`O|HAK^XfMkgVr2V2YB=PTnNC)BdK z;o&D|4y$N=d^K4ixEA*x!0VfzOCDV(t*P@Tnq0yOULuA}CCqrW&z@Q2I5pVC39hC3C8AN3{5kK5xH54wTwKBl z-tslA7_9OhckR6C{vxx|+Ig*ExM2rhk!2j7znkLoXqoP_pBXxPh>PF#iq9k6a*JWT zY!*@GIT9mF^q2Q8pE6JH%@UWGAT54BE1dS$sIa`a6L!%R@-z9}tNcz@HC4HyRvV>* z2U+u8Z?K;zI;S6>E;@~$-v_H{dkT*i+x`l+W~Yl*2(E=Kf5KTWQKcg0<2dv_-PY-5 zj~?Tc-iP-RYRBM zwA!~1G`WNmyxd@(8rJFGDwWA<^`(*0UnPEO6Y4zMl}d8hjiOd$+37Yx5>BXPb>uVb z3=8zL=Jt+O2(HCz7QSYD{z*ig?P=ATvRtWiPVl;c6^*d}V|Sh)t7xG$N-v6aPW8|G zN0`MKHeS>W?`?fkCdT9vPH=nhHZkP3n18OVCEXS(1lPiFLcd!VdePG-rPXrY1d~fR z!OP9DG3{JiIXvFRJw3I=5devFIZ{jP&oMl7WGd;j#7^hD7Qw-=VVSl?me4BN<&>!U=q$>UMXNPG7QcLWEp>Gqot< zE){}nVL0JV?^Q6?KFt#(4;OS=37uAs^-m?O<{Vo|KzMIBTP?b_-L3&JGrql-~cx{5;4()3BNh$lpw<~HH*p?>mOeJwd z<}}=2d%2SQ=|)jG1fE(h;RG*fSZ(;QlAIV_T5kE!R3W&QTIX{=w~-%1Qpm28tC(EE z3EmdqO&EI73F~yRExs3})v>$=v40%$cS`B_aDAZ{jcXk&n&f(6`*0-T1hq7Ps~s{ldK!xCz6B{yxcVHAMmf-E7p*wyd3{(ke9o( zy;tz`iuFt*(bH3j$-f4Q^tpm%m9{JGRzfY2pQq2;n5G?j+EFa3A0)R_U2gY2)LuD( zJ__0X>L*I{6M0-*3)=#<9vBCqUHz7|hRpwDoL%Q6;e?uxd)uR=M~ZAl@pLI%=uOa? zW~>jYP4qa53`s2=pSu0aQPTTWc~LIseixT;Lap=s&$`Rft#622w+fk@;9BT8QAums zFAICgE!WP8Q`>Udz9>mJq1Jg`@LrqW&mhfs@0AFyrRKaVymS6O)62ZK$ldm@Xr(nT z1@zR$rgoRkY*d9kk@9AjvHIB7M{OUDB%I*+gZ&2Qf@Oc#kD_sZKif|vf@`6VdaO`d z>CCDXtKD7pzji@PSl`0-MM=U5wXC|d@{?sMSCUb|;}wEyp%*^#Ra%MjesGRg-(2$8 zb|HV?G~M>8Nx})<@oJHa4np_O1NF+^G}_`);hs5?BN3Ch6+yb zmJho=dkz(H^&r`B$taWG`N3}t!I`2pW@raFKV*FqyVv8I#{#!tYAKnUGJH ze55n8-2`S*UySlJ|JF9_#Tiq)?HgxI@g0}$zs5J@64!jBGrzkTh|GgL&7Y5~R|u|! zv$*3w``9tTZa|nr{wLE`QM~GaI4{(}$a02Hz=3erZ&U|~TR3#;RQj=R#ssz`HzB{Tb~> z$bzAp?b&mZaDv}y0`JZ+r+>232pOGTCAb!T9iY2e;Orgvh%@4Dm>k|c(w^Za*~S$V`J3f@|U2$?~P?r8BG6 z80LL$r4TaDcZ2OYGLmqDmo&6pn3H+dX^RM(Qc@wf7S5e~Gt@^qvue3v-ly+(Tf~Qp zCGA-?l5m2z7){F$b26cyJk3rI!t7Z!BDfaL$t2wTo(blC%G~laeOiyOXVpl;3EuMI zv{0D2E0ojQ%s$MSha&>#-snDhH6LZ57rh+iZGQLLQzccLz*)T6e|kx0*0~(aK>l-N zlhD>X^NExXuBFz;YM6oiC18_iSk;-cr260l&PL8p<0G9}=K?U3+RdfQ@~547Q6jjO z+OFJgl#uoM>e8t1%)L^(;)L3lJnT3^j2sdwFJ6D+;u7Bbs5Yi%gm0*EA=22C(&Q3O zsQ3K5KN2cpx`xS^tG_61muvA`f;8=VDOiP+)7Lz@!f^3Az;7W%%X>(?Z<&`HtQILA zA+?RZ=Dhd1i%U3xUmE`HmQFg~aT+!WkvUha7YnPTG&#Ywc)7vsM`(!r>(n}tV%o#`_SqH@^MHD<0UW3vGHF7*P^gvwVfnua9d_`K=`U78Ffum34#|TXKXvaL8Hl zi#3SpcZN=i}$yPfe$X}T%r)L&brP_ABpR% z;Zzk^PdzUCR^iw7vO?h6LDJ&2sc9jwiZx)Crn(8YJ>-uWsN++FleHjZ56Q`f_m%Cj*D0lGi+lO#9)xn49q_ajiv{8t7cB7A+ z>%PNY8$}XM;9C*hs06E{Va3)rjrzzvuwskH#kFuH7o`^NMA|z;Jl6ZmZ(7e+QpIVt zwO@s`&K|CTa&r7yXSzR#6S(TF&G%l?Sx@~gLzswaH%QJ8A8oIWCW33>T0DBvVCAxB zxLm&_xA|z4T7$gS)cVjzhs%advztcyx%Ns~swqz3THZqAJ!IpPxZ=0P*l^i%ayIk( zXqDhvxUTc?)^yTYBi!%`tSZi#*=+T0h`mObB%HuC$!@pO$um#zMnDr*E^ix~$vosc zR3W$)u1_tI(MvjOoqsJDAxr<|Yxe9@(_Xnu5>DXS>aaJSvQau*TYC&vU|$;MYo_R~ z5?l+{*?#f!mho%0FAbEBaxN18+)!IPFHu}an9z2AN*^qbms}yzH)v$9FeM2m)Uxuw z86;DGvrml_sp3+%c+xL%PdBtP3&|4R`SIUxv6KYwV-4raR{k2*w{8lBn z7Ov~`@b{L^8sRH_LgdBq>qM#-sqGcNB;kZwR)-sg$SuXzi=8)Af@|UW)V@u9q_ft! z{D@*Q?qX@#ew^Af@Dkd{Pv;9C6Y zf-}$l@RN6n2FPipgX|Ti^mKAUEvwh{{bct|0n+E{K!xC1>QmddDXhh*T2;22t}7!a zC)BbU{SdtHrB!7>9hKl(>gb$y@Gy~L>QFg&QlPy?n8s~Bo~x-kTyefwR%?)KG{aC* z#fdQGma$e%L&cDdL*$};uvee;OI(Y415mnGL&dd`Ve;|mE%tsKy6KI39DJmP+kuNN z5WlV-BESFe#a9L~wfIO4vj%rc$h=i_dG^9{d!0V{ z2Atp}4QnQ@hseN~O`=3qXD+d79ZO+?fHNR8NABdJlFTF&Ly1Sy&de%%-2c8Z0jy>FF&i?Kge%kyx4Jr zJ}|AjTwf7)XBOGnLHu;9tL(q@ir^AX;Flk|UlE8*qvfTSWyI%x`wg0#w$HC%=WyVB za>hSXN<2*hz5<9SnR9+`ePG`u_Bj(I;iqkc?Y#is?ovzlN4TG}`RrbDUEpCcu1N=b z#~~413umCW7EUGc%n7K$m)&LYIcLO|*sg+0IB~J>VSQAOG;&UM%=v}Afuicr?y}sY zOM>SRzX&YLom%2a5xhh+?Fy_fDHqUKPI`4xDJxFkcY{M8Qb|0e0`A~hl1sij=r1#; z-Kh{gcPg#2OIZk1rI zkNb?!GtABKJ4c3@{k2T zWS7@YXScsj()~fWhnsH86O7>atS^wUkM1)t!8jH$BI)%r2!RXsY8{L5TvEv+EWK^jgP#XUCuYvob%lB{K0H( zZV&0xzo5JeH!pGtC-@zHu+tk>V1N4FQ(mZ?QX#n3!V{bIGJdbbq%#X3=L2{8$))>p z$ZxOS62vpZ>G+oPR~}dRR%Z7CD^Wrz%bp439DEKw-zPlwwAjdX-NpuDmLIp zeNOola#$SNFk7@1?=Lo$^(S~rF5&TFnC|M-w9lO@iM45)OCOPxAg#bgEA+YDK8hiI zum)ozDv8qPzLBf^vr8`F@nV?n>V&gi^7I!sqwC04^>ZX4NQ*z4@QprmX5pT$j;t^s zf0Cz`2(&?WgKAoaFPX&h^ws6Br;}1LonjrI5!jm6GXe zc}Ondgxanim>0#o-c{sqZ*P@gBLnaGU_Z`@iy~xA3E8(-9?2yB>0NUIZwJX(^SHHck5L}D< zbMSp|UoLsKa(OvA_ORd*PN=ONrrDtna{izfKGn0eX@UoU;oQER%@?8g0%2=N+Ig0`5*~uaiag)O6HjFu&4fC1Zg4tzjKaj=ur!9ytOFj zHMEo#mPk??aJQ^oib%j+wsuM|jAe*1B_&9bn1EY+)v`j=E-Oxu7EfVP8_LKI%3DUw;QCmn#z}*8T-3-*b_u;SMz*|>L=WN`>&j;L)W!B5S z)ozKXh3AE%jRX2AbKD}S-44V3SmuG}+mf-N^lE8)n*H}IwF!Fuzosf0Luj2Oc9;=0cl9v~ zR9c>l4Nj02(o}{?ZIA@DI02`zt2KzIohnX{7ShxfzS{UokOZ|jf#Kw9Ffl=OV_5y{ z)|1o*NzlggOasm0KHHpj72iUW65IwS{=OFSA2rAc(n5Q0Uk|hE|ErB?455U#5^5Rv z`+v7~lAsnR$~C`i=jp2r4A?d}L0U-Dla`dA^rF@aztLaYG375QL6XD-+}ZITPc0`% z3u(A}B;gsf&=UR`ezcPdR;b&(C52~apD8g6J3A8kM1>$pV#0g9W-aNACr83_PDC_n zg~HkTAF3_;8ZX&^w|i6Oi}wJCuv0}6N(m8UJE@Jt1or1hU)uN5+))$H9ZZ}ml8_A| zlH?;AQPgVoOK1DZp)mHf7{*d}?j?)2@s%j_riq$$wWU9(AT zkObr91ljxF1Zg3SrT%qPQ&L3|N;}mDF>h8MB5P-us%kT`g-7X-iNG?o_km#qfXUgCvOw z&lTP6Jbkr+0XyfMAT6ZnDXKT_G%#@cxQ=1GGWE zs|1%I%?S$IL^S*hf1@qjQBhH3wEI5XH`8fLW;={ADTIw7!6lr)ewTZe@jxPiYw^^Q zHvaF}pd4}n!{o^(B`CePKPGiYZ#y46e=5NxoWQ*@>udRZ9Sw+5%Zh8^Zj~PfWk`nL z5>DVws|>G`v%zzSI~)hby4mB^|Ff(Zfjjux=1uwa-5?Va>mL4-DIUAh7J%gl$JM|hAAse4Ixm&?m+eyEaiz^k&u~Xl9VVCP!w zwz01C{Rc?DGn?Z|FMa0fQ5jD?O}*LO>JJ2_i&{AL`dDsomZA&S_)yqcS5TVxUS0|x;%H42O<>^ zSXMc<#8xQtc!*x-+x@P_dP8}2)s5=S79Dpj`nQ%+3XTmdtB>z0#qfAJvF5iidq;P? z>^dy)$pG!E=_ZLw>_(H0%mE4AX6x6P;#kDbx>b{p_T>%+7CMsPGh=D*% z8n{p?D^A@1cY|JF?rzur@pTr^RqRd!-$H?wwos(FyK7tQ-UN4d_oDSeTS^TIj|UHT zcke?hK-=Bm?(XjHJm68jncbVmZ0Y~&IUI8C%rCQ>WRvXdBxxPj32b0l`2q3bL2Y+h zx>SqSEIt+Zr~7`QZF?c9cvbWYi^_}iV@$6avO+qr8TXva}5vtMn5>|yo&LA_+9?#!CNZEDq)nKwZ$3T zwxUb|Vj|dxU70z7N+^L*PqT+TR*h(?4M03DqiLH5)u>4cs)eywQ`@~$jToGfjddP<(Vs^Z+@zk4$FDqaV~TOd}dvuen@MF}Nv6-4}^3u=qYxPM6s5K%yg zo%SA-pjx&)F4P$(^gW$`s04SOzuw7sDv|euwMlaVPbv^Ezy{VNl~6*ajT%e>;!hyn z*cUck71hGnIJPcTHDVy=17U%y@_(^8o=PZTF5TzQcEj@Y5S2W(xz8@rHf2uJC=)@o@VUXcgz;{W1qkRx1(ubRV81)DK@PQgXcqBrN%$gfBAkHm0^)qq#GO<^ zi54Ddp3b7n)7n6^0vil$_%EH1;M*hI zvT{jw@lWrurt-;qeX}LwSXZ(A&rv{FfoKZEtrY(RDxu{zY4I`3q1-uy?@DhVY-6qX zJ1!)i+L*pru{0WzO&oO?XR-(JC19ft*tp$rr>S%)F(+|fQmv=X;$d~%0rNi8c@z-6 zO4@tSE1_DnEhx%2AYe2QgSzE#r)6?u(6)L%e!7TNI~)9u`Uv{_x;{q9(xpVUc>^sT zy|RnCZY|-e?BG72-xV{~E-}>y)#^5BoyDuatB9M|5eTgFAwYP7)uuIe@1M<@^#1{Lt2t%MS?M2vY!2Cy*_2-*_mOa@!N?6u`nfO^K99sjqj7|@>_ znJ+#?@^{0A&cOT)|ECg4$h1K$falz!tj6Y_JQ|PBHmp(9uf(=eOJE;`eT?7rOv30B zRUkskXsmOGLV8~!C6utO3=>A5cmjwTK>Ts2y@xG2R$z~eJ$1%=Sq1jz(zekvL;-qgY}Dx3uqG`< z+v+MI$0%9q5GMn~Pavw@Q1vlNN+^M&UD@i6!Wf-b0O1N(g{_2MJJpiE8@tw_=HBF^ zYT&_0{Y_ZDzhcXmX?)9gH~54W-VfjCdtK|FvT$!REg{=josberV4C^>;4AOSxti0r zQNIyV3vI|WUK8%2_)ZHrG(ab$gyxIHz!ev@t0T}uU;0x2lwO|MM8V6QbwWxgfobWb zFl^KxT0*pb*yJ}tYM~98Hi*m*n~3>COX!4@(0q}Yxb22^cKuGcs-;)^r{ucaSq$~e zrV~;^2~11>jA3KRp#kDn&v*LwT1rSQv?0?5k?-3macjj~osbfmFA}-N-_dGz-ws#h zf2DuQ_H1Ltci4@cN+^M8=|M7Vj64`APN+w%X$h%?zss~vM8o4JAQep|G++6<^pPQD z^l(%{37Iws@2B09W|a;QH*d!3aee2iIf~4$CY$CZxWDX3n6HGud___ISn8NC$u2+~ zSpPSp5;`w2k81Ubj`dhSE=cT6U1lPv7OvBnU~v+0S#=xhrzGW@HCl|=GLumWCFm#$ z5nHoe>Ym&>T6BLf!$eRmT$@q-owImd3`ggh8*(NsE{yly6_7REa7=#owJt~L&A;NP1UQDW}S`fr@ZHy2&zTrM6j3l>9MuGq(+Jt?g>^Zp#+|L z@F~nyxKGySSD%;d8viCjbUSLtC_%O8EDGKS*JiQIKN2Bg+h%4|LJ5p2Kkb)YWC+5w z8J8a2Nd7ZZxX8A%riq|hw4`Cbr61osYKpPq+PylAN+^LRCDe!c+-aE4LA;OCFpqt+ z!h|^4!9-9ka}8FjQLOH;QQo3vt%IiL15elJIV6i%?l#r*tSHK>y7g1ecOEYKPe0G- zGeHSFr(-kB+xO`6_S$9oCu$Q%iY4ohnh2^z=kO3&QzhKfBfv{6%JYCx2_^73m$O0G z1G{pSWT(g>qTKP@jA~&o0dd-*dWY$0=5Tc$<=WF_+92`A?B|T;MF~v1EwL94-!Q7U z-j{N9FBj<}5*0gBUQ`Qn`t^rXPB%xt+&vMLk}1NN$^4M_jLLoCYN& zcA6_IbxY}3`k&clWiWu%Kb)2 zEhJ=#7=+u72r<5}*tdsWOyw!RM&J%+b55mbx5 zc|%{)^65h?oS z{;pCj+(Ee~cnTVTr@%}Uk2~O*$39B@rKcFZZm`^THiyikHqI-tFka%>+NyPA$A5O5C}=B85sQA?I4Z zyasO`Mu{oIUziB0W%e3aOHWKLur`=4FE?4E-zKQ%AKNkP(W+w0hgFS}`|PUI9Zov_ zl{>#I=_4&M@p5<5&ZS= zf*K{L7X7jTK9Y$)JP*W$^GTPWC6ccsl)ybXx-2@O-ud1T?qh8I#=A098Ow7YX<{O% z7X22YC{HY}llCl*V_X_+RR(6e^(vw#sGA;#F+N&`SRPW@%a_ibt^pDkZ2E zZ9R%Ith=L{=o`huMvpYLD@x$g)nv{t)p!OIomY5v%N@nvOx$83s1|KwFq3JJTDPUw zX#VozEPYoM*{ZRh?=;0u!!d(C1+W4%DlEBV-5~ya2aGu6s~#nA^nv}UHDgp8Hm!TI zUyC3}R7VZU#EwnPc3g*If`AYuoO;>|)A z>V%Zge35v(wU4Hb##!IJkKUH*$HVx)cE+qvN+^M8Sqg@YfpL+%aIVw3zl0J}OP1j; z?+18Txb(2da+mpHi6T)kzMt8P!=)ETN+^M883AKl6?lrc^b}D-YM~98Hi((vgUi&* z@J2}q%@>L0J%-vmURLmUxquJO-{$d>5=vlN#{L*Kz^lfkSB(-<3vI}>LG%D0Ty2}@ zPD*ILNK73w+U6Zx3*JHW!GSMMFGVS#1g2$ll3@cpkW6|YDIvAchD;j-csZH$a!Lu! z7l~S5Vr-t&0Pv(v2OnIb&66r6l)$u%NHT2voqW_Py|t8(T4+P2VbyQgki`AXe0b4n zdl~&kPvaSIRcmXAfXJywK#aXPHQ9NwH*XdR=Y|srju~*`t*U$2OpzS3#<#Cm&>FyZ zbd5FHpagotCQf~z8a}f1n`4sCZ4KlX{#k7zs1}V0fH;71D-!Z~j^c0TE@D(di4EU( zTijRPQFAxKyLBV-tc4O(OOC+?G4O#~%DG0t{PLl{ z^qpJe9im6D*po{tdIZh)@zZB_y;nKM@JHjl8I@21Jw4|ip)o7FovkYVvK`Qg1vzxFfAix(0p+RiQ}{F zwA!8+&#*N6eD_<MjF{_oATUJRgU0LpF>m!>-bFFAgT(O?V z<7M*hQC9xGoIywlB`_^#PDY(~J6V&5)brGBP(o_qJ;^kz04>jWi(m)7bif&g>%mJr zuA@ELFrSz0dfd|BW;LzpgSi~naNmlnsEu*Owp+iqh0m+`nyvo)o!L%h*K&SZ#Bn8S zx9E;q>c&MJSFew_&_c_f7w_ZQ;RU_d$%~@;E<}iJ|vy{+$F)dd(!l?Ez zoChy;X2ZA4{f&@XNXRv2it;Hklz)tA!D_T}G2J<>8zf{YD9YfdP@a%rWhb>l`dRT( zLJ3UEdQy}=K$J+dvMg}2F3pQ-;qSjzHMRkwVZQ2Y!`%uxAtjW+^sgFh0K{`3a^Cx$ zkXmR%u0B?EKSM{~Za2B>e(RaC#5}GfjfSGOLiU4t4Ib>OwX|EJ_m9#xoZAP)mghzIyC&OAHYkB<|GT}kedTezv&#&3 z{wEOsq(ew8bLpmnjnk|$FI}m-ZbOzX%@@%c2rEXCu7 zI_o>o{9%)%CF(qFr_KC{efz9x583)rRk*Sww~4@fr53Kd_np*EtKy7LZ2@>{?F$C; zi$#8aYGqkr&mesR;QhEC!+cA6^Fp2G=$;8FNn2L3HWlSP5Pm@9Plu3NXhZrqV7E{p zmM-bezdn9#@_wKVNtny3G2BNa5G9}dPRMdI_i$6E#jx+*wfWa)rSyJK_I)&8b6Hhg zw~#%mT$48{V|a=rLA7Y_3abYuK<@_UBEg)-jwAtf|lOiM47 zqD%*(6c8uUA*2@CXdN+3^PY}TVe5gI;lcUU7lrf^l@gjSrlns?QC0yl^M4Rh3vI-1 z^VOWAai!iSAeKS?8cc(iHBt%97t_DIYKwrV1q4rrkXo1%rd>Os zjqC6<<)7!y^QH4d$##s-znMWz!>UT9}jQ5UMS|k2Z1uQ4Q`o8t$G-Xug>K)pmn`Xq_{bwM&PPTA0(~QqkJI z5!l+pfEcp9BeREEq!OAhrhm2FSx|$u<2$k~=@3#2bIKVqK|7(LjoCn0n@_h623u4@ z^TqV9wz~v~@6D!Lv6RyiQVV~_bg>&~V>0fOZ@4NsI=hGpi7UuM8*NA~Yj2CAu8ni|# zq4{F^SKGyQ1z)o)IAcmnNG<#w)3}$7qTq}S=ZH9uLkY&s%Uy1ymf41lP|^}q3)7gB z@kGtB%|kn9^3b0_DWQb~JZtJhG_wj5#UF~J-edL{|y~1q`PuRwD9G#ba+@~_z z=q&G$UJ0h<$^}Ik0fYsJCg~7T3+?@~(HDrwB{Q@r+bly$Xug=1D;E^S4Q4XW7thcR zrb9?Av{ClW8Qa_^ClG@?o@v=_vn45^`C?kGb%6N9XE7|*{h8J|9YSiMjSJR`wmDo0 zn8U4qQAm8Z&HAK-=8I{$)&btn;i~Qd5uOeqwa`W<`>VFO=wl%M^njClZS!3zq4{E3 zu62O;b|~FxK%}HYNG-H6zVHp(oVqd)dCK$@>us}eDWUmdTCR?OuQE0wB^^R)p^e8Q zZrR=q{(<{g6z?tEZEq7&Li5G+uay?ffmj8^igXC6g*L8Ux@~)p!ndNH6@tZ1+gp*8 z(0nodYo)~lAUXn(Ass?$p$)J0cWiIMGvJB()NHysES)Dxwqx@%I0uM;9UZm1wpoUJ zIx$~KU|P0N*sB=w_KfSO9b99~WGErE(8i2fXKZsHKOnB=jMb{xW=m2+^To7mq2TcX zA{K~^=@3#2ZM3L)!8V6OVocq~S{vJ}PfBRMn3gS6QQ83!48*ra#>|ouQVVV5*>Tx6 z7p(`5c6$sER>L1 zXrt}Vn>IfKzOmTNa~B@Aw<0N_`C|H4+dTqAIUu}R8lDMCNG-In*8i5Rwc`xnFYRoK zoB_}gN482FwdFo;ih@LwS&LO+n`KA|<|_$I%NA2rqvcCG6VHcF;` zQ~hkSCAljX%@@y_gKdI51K*SbsZ=wE^4?*`EpJgLb|Lqv{88R}69CCty@=u!7s z!$n@Yjr6q8o|%Y(UH*OZx6%nJk!d7wzt{ZHxAiN8RYEY|{c7(ad=6KsC$;c;sg}8{ zF2lag9}YCr_fC*yg89lc(zyTfoy#|EHm<=ucX-SMt-<3A^{9jrW*czV9PVDXK?$lQ z(`Z{!%I0syZ(b>=-#L}YblQ7@y$n*r_^zGJwC;9SEoh_eom<+si%a$Up!+q-eHFpu z1;k(Rg|+ezjn+>0;*>jiVon_&-PM|A$M0%C8;0^SZ(3@Lj^xnaSR_HU@C#P|ACGL` zwrA(>%nJ;X3t*EP+2&#qYyH{Xzy@uad zBH%tM!ky3mc}4eA%R59HveqyyO9XnjYF<1y?9ta^+$jB|4Jo07ENP=YvSjbfONVC@ zT^o-#5mXDWs@j-4n#Vi*uC}jBGuHW1KQVmC1O1DMT#tj#id;8?Pr<6D547AP@Xl{K zG-b1AHWsCN71EzODWL?Wf32>mA9c!F|7}B&@}{KjC6^NX=27^}6a9;_*+%lx1uQax zi-y_qnQTx3zn%mvd}8|^mA9P>PdQaaxO-$W5mbxTjiOvU@tLjLR#Cj^;;KJ)vTiAX zU(8PNCwhd3q8wo*d7jP%#JCBc^gYQXLAA_vZU?1X+to*$oV`vjUAdwP%SV%RepKIWT1wIqveaSC9h@;2)1|Sv9uCnWBrjT`<~moqxIpYx zV^Jq!gMJ^fHKZlv{Xr~F!_K_R+Ki(7;{GOrmZ-Vy<^rMz5FS8KNm}C9QyUD=$E03$ zv@b=Mo7yhYQVaVo*-L;w5r`H*ECPZ`(h{F%&!Agz7ydC@XL0A{2@^rJXg$HML#OYuv#$n;VN*U^ zsU$5SM>tru1<#<}lTeXyS?1sBTxwy9k?l=U0<$({uO5erflD)+S|Zw`gk0wbXMo;| z;*BrgN+~{bgx+7#-KOQP*$Wn5u&j*8AP$bi$g{sPwB??ucjZiw8{HLtES*u%a(3^ z`P0q^HLqH$*-#=u8M-}H%d~%qJ@EPvFDM7VpFQF)NPDk*#k@wXUKbYy0Qp9#FOSjgu zGnN(0erk35V>H#bmJvMD%2f5z_k~s}F%dw^y~E+V!Hltd*1&vP-39l5Bcv8Bb=a-v z&#}Dtyn@=pLpQ8cf;J?9X}JeFyrqs0<+la=iqC3gUXCCeC9Aqzy`xw79l6ReR#yaF`rae?5X}qT+C$C!i{ADkG z&cyrp_vvW9rqgs5KFz)kC8(Bp=a%j6qj}$ga~NI~m83@)_i-ufSboK;uJ--s9DV%A zbvL8H6U*pT(I*Y!kn^?TUeQis(T6GesCHqQy}(nraJICgl)b>S$hy5aY{@wzqgWP) zJzS~zUR)#|(F*Q@Gxdms5;*!u+pwF}#e)3w!~$Wmyot$rQV@tEOV89Vw>w@y{DF|__05i`vG9D4X2t3Jk?B5#ypK+2Xb~7qeDKh zBOTUQwiUM%^N-Ea=US4cwqX_BlL&StwVUwMKA5fwZAijwqg=p!R=i7V;p}_PL{Kdp zujD;JOwrpwzQ=yNHg+V}X8^KHXdTcpgcwNAARe`AnznFrE_3P9{?XJYE^OGB&l!AO z%W`I%iJ<-Cg14Gw{z653T8_P_YoosWUAgPp`>Nv^l~98Ad=LR~s4G8E;;DA5;9?U& zwL(UwSnd`6sTGTv4K_~i>&jzdA8BtdFJn|f2|9KuO6N@$o@IcuDB1J4nII$Ft`_l@ zj=BHQwpGJ%@YB{ReE+(l;$#b0$3ofh1#@?L-i9R+hlhT^8EAL zUo#6lJ$=`#E0*AynMCK~I4^lRz8`aIIaqZ5c%0E)fN*V}+;3|ri?!4(l|{_Ug)3kD zFZi)LD+h_k4UaJ@p#+|`x&MZPz?0M!Wy|-1eEHCtqW@dfL{P0Py^mP3L}V5x{=usX z+#SVx-dmi){;i_F*UDKKy>>beg8i>kBKWA{+1b{Y z&8(E5T5{fH%&$tG3gc~>7Sc{s$fSGKo--7@MEMSh zrdC1;^ZaT9%*YzlZzE2fI%OiL7M-2JsFu`>eV9HF_QSlYdky3a5_<+Yvov4Tupa?z zcZGh!bMFn44HIG7F{^8GA2z=5Kp|dVG!b-XEBd5?Cv|ZI5BGIqj+YBr@a*L#GqQ;z zz5V$C$8y$*soC`XGtK*1c530zXXM+iIoe&b;91cdcV!p5{rq{odd00NWnFcG(u(rn zbp<}X3loh;=F`uqzB|QLM1=bDTroMV*6#*EX+`nN7s7hg3l%v$rDpPnuEfujVTo-J*|uE2AHS*=zfLiw=QL{KfdD;u1h+3IiBR+RI@Y7TT)m9dEml$Tc}MW0D_mHi3}%9A*-jl7FB!Iyeq|!~n^0F)A*F$p zN+?11uvL_*B_sIVyROXQVkW58l74R13OSv{rfgW}&UeCjz~o#k^v@tGl~BUGr)<_6 z;XGH)-0aD?Kodc=GR}0i9@(B%Wc`Bs>DM0@&I`@S%bJ{?W2F*G&^>HnrCxYA|K2bk zE1k_uP^~3L?5uSZN8xxCSKh}shVy&iiJEk6tCdP9VIDa%*oSkc`GuL?nJp%QYSD2Q zzH@f;=iyJbX#xD2h4y5$Wze1v_HV!G$CvHcqOnQFnfL$oiKIuRH4FaTR6pL?Zi}}6 z-DWGzi)wY6;AS1(E}Q5w6kADTOFurQ_$F;liOh^jC_!r$zQhgl<9q+wsEyc?$wW}C zniI2G9X(vcmU7riCdc~nBRAG+b2gV_R6+?_vx?IEk}tpIwpQEyZ&?#TwOVbH4DAymGXRURZr1ip|^>k zTC|^sQ7yO}&ko*?Dxn0eSy*{rvpn~#SVPoEm|-HQ79AO2mf=^HPd-pty#KP9 zQ3)l?b^c;NIUeFzS)8nHCa9KqzFS0$X3bj<6-g&yE=t}^=o<^Qttgg|5Eff%sQ6b& zG+h-X=>Ed+Cj2pw)u=u~jOw<*L{KgBI9Rhq2||01ZC zOdETP)N-lFJB2Xa29?M(<}05Y!^Zz2sFq9{HeU4g=Yz^^*Zu8OBGZ_!?7;#FxI!f|jrq#Cgkj@<5mZa24I8d!LfEY0!6GgplScOeq&o@*{j|5H zUd<*tt;3xP`y~gn1u21IZ`RHl-OrHjpLnI@bIY|Z&LZ$K?$KCrTnJmyBUFrW-kL(| zneOm+VM7k<+^epl`1U?PT&)|zUiAqTk)zB6)uOct^Af1@a4#mVD(h0Hgc7~_6|qm4H975NY!Cfc_!6I6@VCivTX`STpPw`&(Kk4T{sO0=p{)>`pqHnB=W8*{q* z^OTa?wF3=Cnh2^zYZKlemqu{!FekQi@1|rbp#(j-Kv8x8vDVLtO?KF9BB++EbEB2q z$XT8@$m%JoeF)ZQO+%UsqW&AK!J7xm^P7V`#MGC;8kJDu z%FvsZ<0TzL-*&iv;@5G$+}(bywl=(~nIKvPXJ@tk7?4%)QuTnC6z9v2e^{->S*vPP zLi62K`MD(~Qx?%?4%&!41M|cZxmm!t2$d34i=GjnC`FEi^BVVav*$mIj?aKAI&R92?ePRb49eVT1xS9=W?`&UM3w0tN*_cMjI`*0M?mCaWa%{9YB zP%Z3(<-V*ClUg={U)bWxUR1W4?t`A8KuZMHZG+$EP+nK&HNt8tD@uGHU%)#1uCv&B z1E2GQqy2b~6C1T*Uox2LgKE*X0Pi2|{CK5Ro3u_jGMeg~5^ zP=7RgF?Ez^vb?&fhokw@{!vl7Zw_X&+l7eu{KB;BDeX}QWzB9q=j$qJt;C&G_iS9x zF6Quue)o$?C6u7{Al5kod>NWWyczY>L{KfKy@jpI;cT8Jo6yFRTNU`@Ar>)Z%~O?1 zC_&2&zTG|Zdh==Z4s1BoJm0&L+t(eY40b+G@7{)pM|~nyI?B*} zYw5@UF~ZA2SgD60;_JIel}ac<>j~!6k1Fum8JO@a7GNT%79AOYP%84V&#YqLm;jYZ zC_(E9z8i3VuKlr1JF>WeLNQp%O~adV*0+>&^OQ^bx6VmTP&>ZnF40XAwIVmf>{g zY4k11{jgzo7>Ii&==!lbHAecNkCDQjnMPs4te-O)wEu%Y0Qy;B}svtG>9E8lzDOCC~#s zIniEpFN$|wBu6XW_DK%$>W^L~f@;wcQIxX_D7-on{ofxZi^9KC3r)A3PJJn!^j zRj2ui?OEoT#z9J$%j&CRd5B!DDU^?sO$61V^9MN7VqQW1Xd@RB=1tP5gc7twU>Ea& zzTCCqDlL0Gi;19Gbp8O($BKb`X{GC0`*%#E5=zh(13d$Hyn5uz&FoJHsFa{u=6MNg z9mTH|Ihj&DWx7fwl%OpiVzwd5d+N)p_zRGcpt~0_nElSqU{(IW9ofqFJZp(fh9xukFLJjy@Ky_Lf$PU%=hsT;`IMLI!60c zafgYZTIRCKwX8jFwBJee?Ac7C5=zi=gFA;f{T!8Zi6%c=oBFG?PwlTd&v)IOPqdsx8l^5lQMwbc} z*hf?@xz5y!Vx7zSr~M<$;esZx-r++;y()1Ul~97(gSUym`)v8e?!qy{0uw>CF#W6F zjf7rw>nSd>%$=xF2_+)IUEAXcY zRZTW%zVxJM_%fO_k_Q(~VVT}$(&#zW*b-aza@DZ^pl5HxNoKEt`O51PS&gGPRVtwb zK2escZko}TESL!IwRbYHz%1NEP%TXVI@9|Jw2}jbeYmr&mB`)7vHoRAoA2CX)CATl zdSGg4#1iwV0ciSeAFjs3r-jh3QRqTr^`2R|xvV&y{lVKwFeaPCx8He`9K{Mvmecp%hXYZ@C&-wSMR6+@J zoi}Eiqk>>2o+Kp#;4@ zc*nWu%l}Z+?iOP%WIJcIx=AYIxOJG#bd?-MGvuZ0e-XMWuui=CWGbr9A)S z>CW5uPB0Nv3uob%FMd+d?+4!phZW>G;~3Aeb(%h>mJ&+P76Vc6kwGk`iVy$V#hABC zf@-1vN}fXjHMpq{o7~u!$2^;FI-!CRwB>_u$t#G}UF*+17Kdr{%ny2E2zrX{@4K!V zUgwviN3(+4M)8xqs%Z4=5_(n&dP4SWJggd??Y7`ay%gr8{Zuw5qsJ6a`$mr`zT>Xz zaaKS78sCsR%{Z(Y{$2FF?)7uh79QSYBB&O6aihWy={Z4^H~5er=GxBo*BzNcC6qwl zz=&q5YWS&FfDd^^$?dGqy%8pYYN0p!P>mFujnUu>uj0k{yyok4ud|d;0(~5r{!Ua4 zfBVmj6?uveKLJ4}N3B;sYAugj&D0hXg z05mVEge}fYA_r57FNc;h}3;# zQbGxOg^H30KAEG>tbA3j024vA(08(X&R*5zePmKX30l&y`yTjY z?)2Hl_>_t!f@-1fWWeQPs^L{D3Vxq%e{5s>u2j^$YEnW8+F~H42z)ZFe>iEEpN8mO zHAzq{^vV1>`8_xIeRAG&(mHev)xBy`LJ8XPVUI2F+ zK`%Nn%0>Hh^tI`#D1lzQJl>a8!|PlVJdlr%Y++9~8vaCiA5_a+AFIFvdDL?YYgNba zS<3pL1bQRC)H|gbUS}(KQk$z5p7)I57nKCnGPkQo;7RQ_%)$d(7`|88t|(#dOIq{^ zWr2agJlpM0DwWXQ$82M5&JApTiXZQ^C8I_qlrW$3)9X+$d)PmO_qw**)OM*BJtYX% z_*IJF=kvR2MORo=S_k+o#Q(_$70+9y<)$dr%0=+^n_acVUo9$?Py)X+i2l!2<2z3C zwtl?A@=a_-?Ti{Fs1_|Z@R0@k@tS8gvifH;XjDQ8{L&EL>Yi$RkLr4>JpXvV4nH`l zwuzuxwA3M96e1uF4XeWkzbc8dH&Ow*fu#3Zo^KEBiOrx`jFpYy#4wvV( zM|kioOW>p;I=9y2V1#K7 zM+w@FVeZp9gq8OWg;|hsg1sDz921N+IyLB^YQ(+9 z6%S(lH~I5%Q^WLlpIg>bD#o7D6I|$tG4PEZ;&*3M4CV6<84hM5PN*2s4C@Ub zayh9B<3R~#f@;ZnGHhV%;FBlY*y*QNEmUG6ASy8G^HCM!tl|9w;;B32+s@v1yJjLV z+E8lI+Jv1cAd2!iKPR@g*PEm`Nr zeYD9C&dY5qtevX3)rv82w_sGj6&&)}##IRzbII1Fs=3!=%w6_8K0IW{eCD_+Kwk^M zKmV)B^&gVP_`3(bpHw53^KFlEJosZJzI6R&JvM5|?9VE$+Q4Y4|7eKoTQ>itYQ*)m zEisCHd^v)jN?C0>uZW)1gwa$HB_69rjIeiWKlb$YP@b42L641+5=!7(kvx40zHLLq zR*lv}`Fn`iqIpp*jO3D63oF)>rnBPK5j?Q#JkwQC+T7ajL9DZj>dk#@vCi_WB}!n_ z+f$#bsu559K1T=}+XKGxhL6>wqa{JLFcwcfX%GYH6wW_wE2QlXGuI%kHFJH`85_^Vn|l$A9_35?~P+U}j&<`hQ!b{-$jn@-NF{T*#4s20X`20nkH8ZpAHuZQ#I z1zOKqJMV{4B>1a^+muG+-`W`b&AobBJmE~-Y%cED9{KCi$+ zcJ{WpwbK&CIKp3TH!-^}52(1DJ!{cgk1&-IN|?*4`W+u$uK5Z!u#cIbS{M&`@bzug zh^-xX!Iyt?T+1w7%juD_QbGxHS)JeF%cnkC%NDdZ6I2W1I(r|zpc*m4*N6J?D-$*{ z`*)f2h+iq8gt@HFxANmYWj8VHwwa(>7@ykz({a^^b*>UxmM2`P%*V%=dj?vf^jU$u z6RMQwnF`n7$+>2lo?1$n%c@CuIj)|n!Mi-4VIrs&eYzB7o*bgSvAC=p^hk*#UlU^YEAke?T@ zR-g1sREy3AAcF3CFnc}*-lNWJ)7Rt3Q}O7GgO1d2!cm#|?7-SUp7HxnJvv&>4Jcv0 z^T3f6_@wm~?m5+nr-*uyH>Up0#`9P!l~95{E3iTVR;Bz~%0;_9_KUu1OU@Ih79HCmR&8Vi z->}L>J2C8wg-R$vdpkJCq-Y=Z?~Z|d$mOjP>4ZSw265wy7qr&U8!c#b)2@ z&-X34&aMy%CGh)>JO>R{@Z=iH=fAJQ9uMDVmA+|x{|d4X2l|t<)XuKqZW4;}nMLu! z^M+VP4uid&iG=R95t4k_5_8@`%kmu8b2gae#h*1h%+|NV6DvJg8alm5B@kyqKTkd=Bt_wUmC(@ zdvKqh35-fi1bofP+`w7Goi|`V0OwYGbc6$cxpTgWK(D;iq9p?L(Zi4Z-Dwctu>Uxt zGbDQcoO!l%Y5x$$%M9ijrX4fQ`Y2&8EAK{S`QIff@IROCF%z_nkvSurf-$QgZ!*_| ze}0^3nv2qWX^FslZLBw6=sTAk2#zolq@L+K7*<*g9?0$gJjSL)M>8s+`O+2xyNgu| z=L2>Y)K27IYnoG2Ejqu3$jrNuyjY7P_1YB|Rw|(cZTYai*2R&Bea*)M&*am;PRjFx za1Hma+U@nd)aW^Q5C>535o&f@v5x%RQfB7L2>JaGtHjLZq*8Hzr! zwi;{UJI=^?E*E-%UWC`nRk8Tuc1m=30ZsxclD0R!^)q*45ytt{$99 z@LBnffV4c-Oi@m)JZ-HsvL-Kk$o)4$YMD>%Y24V6PrjCqPu9$LPVbi9pQ02i>n$g_~lv|O$60iaB{2VvsZ2H&$D>0rFUX^zG82F-t5Lh zMkSP>=lQ|Pmr70f~^Vxvk z+6>}tgATEEL!(Uu)jE>6*OFyier^A^nP8(*?!Iip(60Q$AVqIWcN*u>7S=F!(vc^6 zPMWsX!mH%f+LgttT9vaet2wv}pOGU2rxI*elEAb)6;)Ao`gdjDXLsewJKk`j6Q>fIFQ(DZW8 z8d>bOr&i{Rv^*OWo^vHPTadjTPdWYjb1t=zkWVn|>Ikt0C2H4T?<3-WJKa(4&_zdW z_@dZ(5Fg@klJ)N~g3*>iwal$#z(g;eGwVTC|LY(|C6q9aQC8PheBfgT-m=&{6G64; z2&X8=a~9(JzE<*K^5LX6O;uSMpHrb#AZ9TC6)v&zW^=ow= zQtq6Ipjz}vgZ;0%<>kBJtI4T1Pfbr0C1_iKRYDu=cx1^seCzPHCW30w9s^dH?y%## zu2$l94IMd^P{Q119tcw3II8d1sAQ&Yk`eoVQ(kX1TfiRV|%1l7XbR^*rn zez^6`SlF9h{C%VMrdc086SD83^EpN7Sf(HI8rG91Zhp_Ggc7vHz^;y6?z1HK7QB6j zTPA{P(fORB%-ma$->+4jkBdLdsDu*c)(&oV=!1;EZ>vABvHSkfR=i7Pm|ktE@Lw8# z?>sn%uB#K#$VdVuX$hqNBZOhW*sl*`;L3Y=>U)`Byr@j$?`Ru!qmhWl6uuis38pE5 zX%m4!x&&&;oDQujXxztdHc%pMNCIt`i2rOz2@>Aj>;?BNq|?pwW)yR-75-)8KSD~< z62S%S#qDR%i@=|L=jjqs3+Z89G78`L^lV58YEk0S`-~#IWO_uc{Q0%w)r;uY9`!Ak zw&qh|Jw57cPOZT8G=#oW;nC6Aw1v-&yRCQLMYC=&(y~N;zYi(FtD;2G6=$vERZ<`S z-8m(s7Sh-jeyb1ts%YtMoRC2b%x&D0%<2EXDoQMlw-Z<*|34wM@Tz2q{7y&-YEeR# z`u|TzEu{0@%&zt5n5I7T)-ENeMTuWEIPP_p1kn~wEPQ!T%XMZ5^Zp#C&iY)KAMuN3 z`1J(u_WSi$Og?FNRWNr4q9YJgf;Oa9#!+RgyT@kKZf4H}W%X{yF8AX=)CMA8_9JGW z{j2(KJx7y`yR+`G4K3fPQ8S(N(lu;!0D?;BRn4_b`|k=N67b}j8i&9}`!odA>NxZo z>)!f-TJ1n~u+jSR@tTK$Xaxk7P-5$o#jMgF@v8p`EZskM&2>Kt1W!XyE#F>eS%;9z z>dvLPfZ$2};`am57YKUiW2Qf2M<>{6E3BDKr2yxcboQu;_t6#zdbgCAWdDlIxR*ui z<(&a+)ZVapr>qZ3P%T@KDOsAzZ35q>zoo)YpeHe>+QYQRo_lIffz8_ z%i|0X#eq=E#IY@jDQZO5f_zMj%Hl^KPzSWn&v!LE!oKA_skYve2Z$=yhw5d8_d#ol z)}WbqP->C;F|bh=2r8k(q8=MrqgT7s!iTY^j(g~lkPJk08iH!ktA$gP`nJ`t3h$iW zVaIwmtus5HRbK|Vr77L}qpSbdc4=8r!Y9Oz?e#yRZZ47!u4;IX!~fZ!1l3xSD-V0x zc&|FLNdX`}MkmA_fcxkQS4AZghgW1LUL>hy?-opRRrO0c{MUA=4N6!~H)r!&CaSv{ z;S+Ui;$Qj`#lQw7s21&&jJ7N1Ch|$WHK{0oLcF0S{pHqe!6c2A});$O7!)d z_Fst@rTYSi^=SyIMaxi8R+c>+cMgbH8)0u}rxof~l&^I@%O2MFpl&Wy%v6SO?rUCG z&mbVQG&U#^G4~LQDE36HwhPzYHLI_SqO8AKyX~2Z#^(@QJMKG(PY$N>jULk{iWRcT-{mui^Y&fto=^U6Ca5GWA?e=FM^Xv0ATQ}Tw6ghmH;WFWJd{nS{r3SWTp~+V%)%0HQ}4 zf@+zsDqrH7nlM`u^?+!-aUZ*K(?!JmfZ5BSDr{);>>~S+{M@JaX|}tNv&eKDy#|fk zy2qyg5e5X6P@>1!9L)Eji%8CnbGX_w9pdFxQG#mGl7{G=uqN*3!A1_SK_!&9|LUPN zM@DB6G*!Qk>8taTLA4x;B(Q3=vI}9!4`t=_ z*vsPq5aPu_jY=qSW#JHZ_KT|s2*4RxhaLOePXbW|Y*2z~(VB(*^hY@)>;Pg15L7~m zOE+4x1$|sa`=5B{^`HE#c?yVfX$Y!C>tFT^h6hAmJI?N88cSD}n`zc3fQ_b-^a!NE zzx!p6=ZlgWtG~mT!}(p$Bye_jpwcw<>Y$6j8DQh7Gg$c)7jfkwj^~&+%zYTneFhd= zWtBwNi8rjn-5f-z)kXC&QT`6z+PcMR9t2{mZLF0NN|em)#CCmh6paSr3?Q=grugu( z8k-CRl{APf$F7ZW()Ss_QB>vxXPFM4<-QYa>_}sS5;6ZaVFy+?3%4M=kFz6JxyJ$_ zXMHj+s&(X9JND|Ov-kk>AXo=^H9o#RT-7|VK_x+dd$YdNTtu<+#%xLEq$pbte{tWO zjtxo-ii-ZPr1jEOJ_8|VOENF2Me7E72FqXZ_Hb1=_n|e_vHmi)wS$YOpOp5hinp4W z&)xMK|Bm=xyS_qZu|9K8NGS^S z0Z_k>OdEc<$c;{7|6g7Cs%vYKsbpxKPnIURv+CYDniIq)4sj4mR(IzaI@e345=zwc z&1ikP-9an22Ky5B{k68&YalPkQ|eKIYSDXw9sbrRqHy~@oY%CbPzfc*=BZ_6mF%>T z8))PFgD0AUbuiyq`l1IVsFt~`=C8S?^-LJb@Uu*l2k80ySg*YvBh{fq~ zSo>h-&0|Y8tw$x4n4Nv4^<%vU>g?*+Q!j7+w^lx90GvTsG?@}qi+U3jC2yyVTA@P$ zJeV&^q!LOL8MfQnegAc};bOG0I{yrO9`q)eJ9YDZ179@ z@lO=6aQ28&;UOVr)jQg%Iy;x~I7OZoa&7>jQgrw09DjGRayZ6?kYKA-aC zbQDi5{mMcKsx|IP2R5&Ng4)m*HCl*&_k#0%q`)X)oS&rrE?YdE1oAM-?N+@A2E9e=K-Uh#&V2PLRhLGWeW z17DU;8MN_g=TEif&j{XNghwKkP=eMCw8U=@SYmB2y*{LWw|2&YT&B^>y)*kmw%g^i zx+e_#k|mAqu&4cp@Fy$(*+V6ipdN3CLh5;&Sr!f9`%W!45maka^nLcw>4WO^6m2wW zcZo&s8OAq1TT_QhDAD`-ZB}jJOLguV?Az@R9Az`2M)DOczb8=%C8&>FQS!Gw#u^SB z$?uiOo=gd<_2&~&mC9bMfQm|*Z<+qu6 z4hi71nmtXT5=u}nE|l()Wh`M<5Wlh5Ie`*X>o$1k?|_H?MBA5@kGQ2J&s8-MOhuNp~C)BvE_?!>>*qfF7XAECQVW&GCu;hiq1M@v zQT%14i7C`$9(8LutKBp~-R4u2Q@=Q@O1U!KI(C#BZW#RksP~)MPyD=bJjo`Bf=hAEqx<- z{F)S$x0cNhqQIJ>Pzfbu+IYvA9MIa@ zeruFKg1+O(G``o+cTtEuoB7aEvsIKhb!Vzta`y~2mE{naHvR*IBrr!(~eFo0iLnV}; z@4Jf9qDwKh^-8$N@Og3_N>HsAwG!9?_w3^5E_|XsSLx2~)(sPdohR*~5=x8)ugH1u ziumjAoZ9zpY^^m+JifokgGwkt->G4zkUXPV^%(5-_kOnKu!}fQ4zKEV z@?_>VGgyr6vNMTFD3Qf-hL!r}BoanppXfOBPZlJCg;UIux>Q05>Un{E)sC%YPx=Rn zP5q}QQG#l12Jcrr@P4&V!qFh$<{IWSIZ(Xt`{_X?l%T#Ec!O*a$5tKp6L(i7##4f7 z@oP8O?Ng4T%@VXx?R*NG_|Zq;^FjS^GCjI-L6c7oVzxsMvG-NIMWb1Fl4-t_m}UQf zdGvP>pZ#&Hojr6fD{1i&ht%%LRMPU=ZPvSvqws88D2;>a-m#68`i{rV>hg zp1s*R1wES!X zZ&Q>P?(4KsZ3D%%jrPfupjy;ZtSG^QH)?MC1H{ggQ}$2^C1PLqxAybOB2Hhxb~VZ` zS({(iS2RQI7enQO4jPq5SCALGV~hqV)use}?{ zU*DpSg|&jO!^P?Wx9U-XYE|Fdm^l`96^n9W-=4bAS-Un?fa&puR=8syg4) zpSdGN%=*HKl%QINY(C4c7173lJ4e;x@sZ-})i?|FY<_q0W{!n{uFWysdEU-4AjIuER8U~93s&$dtPx8RaRD3v|}bKN;*$(St4*r`kt<=bhYVxFPeD&KYecd>p;gJ`Vy-ar50NyG73QHo#naZP}T>R5S$|K)R` zto7aqg+Qx9)#6AA=cC5yY{i6+{V`)L9(~+Nz!Z(Z@PjV);@ibzY<~BX~+2F{!dr^A-yc~-#qr_zC<4nSSOWCQZWNgv^ML`1ZR?JLn%%B(T)sH^* zK0%!HIC8Lkf^ob{5o#l@W$Y#U;7A5_q>F zPEn6<77rRpKb$N}a14O{aLk}-aZ!cz`#upgU|cvs1qt=8>J*r#H`*OeZ|@0H2(-cx zlK7gDvRU6Te=sFerV&(-*paxAtPV*r7W9xQFZcMoe(-Y`z4%ACLZB6nsl@Ey-uL?8 zNny0yoG^k467L#pCRa)u#?%hd$Jg8M^hy)M=#yJ2fmZ5R%_(1DGNZ!~8sIjBpn}AJ z@MKcC{eGiU2I-^d_(H_3;t(2BIYJ@O3P;GAmZi`b%ST%$wti|9#X5@5hg#dO)L3UZ zQrn5W9v7w5b|i3BkBFLmajnHM!ikZwDuGrDdTb<(Y8^KorO4Wz{l*K+l3-^RC89y0 zf&{KF(zHM8y|8SEaAwWY5oopX%_j2o<8kA%c)G++*46p+qR}qQyJZwb1qpR6P8ElI zdaVa8>}FGyK&#nrcN5L!ZzHCi^f9zbCq4V)tZY%nD2fUaxb{b!e3Gf7o?%)xw(eV` zLZDS+uY;t))@#PR>$1!zJiTGLer7Y-)G9=2udvkAwq$QYe|^%&P2^;;5Tz|a0&`tN z;LqD%cV54V#Coa(T4h+Yk(|h~&p6gpraV)&)%vW?8_Dy}!4wrFFxNHh<>pm-gH{_! z7IE4b5@@xs!e-Km?=uqXN+0XoFX$JquP0mLgDEOVV6KZffM)0Q&UMxk_k${dR;L;# zli){34acW4cQaMVOXlZ}C+D9BQB;sn%i~6$JfxZXYVx2+utK2K$c+cd$Blm*YeS@u zesA;Xr~C=6WnWf#8(^tn+ofp{>sRT~^L4r<)kA5ik-$9Ev?SkE`j@^s&G$(q&e)>?KHr_(-?@$S}!nR9{YiH#m-h=$9pYB0XK>~AK z%&=t0MVjaKrmLz~f>q|B~LgGGd6B+yFj zm-P1SL24z3(m6RI2rAf)!tlYX?-+CcqXpo745(j=9;%iGqMNqDWw?Euu!0N+Anh_oO}Vg%SMHfMqiz|5ehn++*W@8Cf0= zo}`c=y?W6`S!H=F*u9m^8(xlH z`caCaf&`Y6SRLdrjQp{9774ySKq1hogLZ}VE%M2D6DxiE`FS{r(C3i*!v|1Qkic@% zG`mU(daZ(mS<>y{3V~K~{9&%r6|obxChG0J7i60r4Y!V?Oa%!nC+j#$+tDeK&U~u& zUhxYi_DjW?FK4Ux91ujUCuNmBH4=Tq_s@Ml``Tjtu6>esr_ufB(k5yz9Ib4iN1k?9 zRRz(w=?Q`g62a2P&pvz_(csKZ*4_wG)`jD!C|0Z&|Le+0BVLS_L`>QKBq>~sqlUVslQ$zS8B`O$N|UYrPJ%TgmKDo9|DQ_R+m z+FmJVt*Oafe#9sQT9q3ZOJoc&ISSJ>j|rK#z4}R@f&`Aj#O{Gci@k4-a3|H`A}JDR zwJtQ4l>a&E6Jvw;=3ddU?xda|P(eZ+d9_*f#w+{URI=irIN1|^3$6Nu#F9^9q&L&r z7Y!l(6DzDqC8q^}3KBTd6EhQAY!Y);^`J+pP=!FNWulhk{yDM~@k_2PNhmFdoq|9G z33YV0`PD%${cQl%8?9}C53o2ey;W%FQ)Xa$?57)4geC+d3DeZB=n?(P-2 ziwY8$>zek^t4H$cO;eLUeOGHc*2=E)hmkw;4jA^lxnvv$M5m8QP?48Sn|ly&z)G xyQ%8ibi1QK3z7izxX%?fqOaAQA+E7}p|73z| zN}BZeq&K>B%s4An8>*`l;%n7p8_y1+e$@sORFH@onUkEmm}+dxE=y2zwPVMf!|21k z;R=CPxH3ZY6PwzwJeh~kDr_`C1&Ia|Dw4d>DaP{d(nrJjmyG6O4j?2YOd-$;*K3Gp z@at^j&4zHg?NK;E1qshn%}K2TNk)sM(#P|;vyEeW!|4lg`Wq5xh3ihleB%9UDHEGU z&|4G22`WfnoffA-O}ds+G9ZE$@>B`5!u2y^1Uaa&@u)xqUHu}Apn`<@eB@2aosz3V zB<=X1tU{m_z7sWVNWM<&aJ_-_`kNt2Ey0yeSpFi`%dt`H^*`cN=u!g-DoEfeEAgC1 zjb^R72h$c0!W9Co1{OS~ZyI{h7;WwQyj-$`E#KFl*3UAKpn?Rh5Yx2o#n!Vw>-M5e zoW=Yr{1#fN?bSYqZ7iQ#AKIzP5P}L4xYA90!Mb~zmGkIE*In$d5NL&MrC9E}w389) zPH5x>aRxKA`dEV4Dv5adna`#y?M~>EjAfPf3JI)ZB5GaLvnj*d6KXGF#p7?GRlU2- z$>1)`I5bhViIJz`jE(1Y%Fm0K9H1b9&x%+xVKc=Txml;dKU4y(D(k)4CLW*l%H7TyW#Xid)80c_n@2vhX@)Ws6(q2} zi4!E(4rQlG_)yOyDuGt_OB~lj-(534ewMxPZV#8TE7>Yhm%Z*36(q2RYTDA0%h>JD z6=>{*(h7lA!`>{@6Y4!R`qq^`UiI0}%KMb20YyqtRFJ@TyI5s0XFof`OVRiV?h1ic z9U6z|{-eJc-2!C~V9SY8hJJN3`B*tb>0e>3#P_474I4N+#Ubk!GP{j9>k!_YNMH>W z^VH*JryRH0LQaV|rbwXGKUrIl!|{iVT_0pkEOoJgakt@S5+?2n6(q2RiWAdq{xCdU zH9N}!cv?nc&sO8D-$s)2Rxm{c39N6Te>H2X(c<6+GVh&Apw-1r zxyZByXN^bwrH?g@GqS(et|fXa5jztUB(R2RT7mB3bek({$m?*GK&wB`e9(XwLj?(}p(3K(h?Pdp==`j!w@RQD?zPplf7Tr~ zIt3PEw?+=9s34)%-2{ijhVPH!Z02Bw$6dBS4nY{~Zmk#zfN zH+@S}7q-B*5Ou6lIQIJr-(GPuZ!|Qx)MOW^t zN6`C+86PdPQXJUyMFl9{t@u`y?E{-Jz6PBwP8CE2iKIebEHM^GHpm)#XWQcatZq4f z+Pl4*@>^*2B+g#n+})A=6CqbR#WlIe>iL$V$rtidRFIhDl0m<@(1}&B?z`LhU?H2( z_#W}|X`>Kmg?T96AEP?5p!_-LwVn->+(p7`v8{fhrweOkjXE^PZy?*zmJ@Gr-YEVS zT47FWn(u6lXBgO;9$wRdV9mfXS8GY`kRNQ~>o&CO+=c`dBrw;-s>vod*qPI1=;U?z zDH3S4zKy?L_k<1mXkD{?rN(vUaKwu?4RxcaAc46qR#VlS#RfIqMG`M`QwX#gJ;&9qWx`SSrt1n zq(me|1qt=}_&VzzD}B8q-BKl3nZ>~;82fW#H1Yi@^SsiYHn|;4P(cE7T}0VD@()}4 zvM9Z=r6ffHt?(@>PWn4|fn6(5j^-&@fTDr~mXlb^*>pC$_hvi^%-3Hb&yB244Mh#a8v{Ku|FYT@xZbRm!l#Ga`s33vmB=)NX zC9s&wnQ3O*x=LiMxsi7)r~b-neeUGSIx`NFh>SMLjV*NllW=jyYBs!>e{;o;LYcoQZSc|jzm62_g4+$(h>|cawC5hir3PwzDez}(D>JT^yf)))i8ZNBGx63LThm=kZFkWMTU1SR*=omkm2FC|oEk<@K|)@eQNYCW zQQ$KhF{L`)A9DL&glUB>s))b4`4h|GM5+Gn0YL?SS6-X3w?w?~m)F?l{9^PdTI%$K zX@xDSI6Je!HMY~JK>5{N6czkkdHuW0m#p5(J{H&L9*2hiB1|i6gT)v3V_R80M>}eN zq7Fp`e-~?yh%~h?oF&XMNcg;-3V~K?+s;Qjyeb!}TwZ)zM zB_ev_Z=sd?cJ5H}qvgnj0M5oaQCIQx#c8J-Zz$GZZ57x07dI}~M(N2@N#@sXJlq<& zC3f~V%bH&O_)gyw1QjF>3VLU;to)K#WhK5~Ey${O>72^GuNgoGh;JzsMVtY-j%>78 zQ?@O;8=oU){=09VN@f*u<8M~Tkyn-0rz}e*JMzEBv{n=(ZVEcZ-HlILEr|-%?pcmb zFVFYbTNDDVFnuDgru$i@9GU5#>q`vv_lzT<16=qSF}u9qJC4MDcj5B8N}m-|$@q6J z{HCk?#N@_Vg{(BsLA$)nLC#=+zw z6nA-ueG{`s>$m<6=h^Rv6I77Ek`?dTlB4ya55svkvGNQFw8Fh7Vhu~;8vX9zUHxRXTeuZ{2^j&}$1YU1ACD|9BLVN@|5U z^K)$rQ+xPO7C7;(1=E={)6#}i)lpo4D zl3afn%zYjWR_+S-o1i~U^C>ukEISd%_bdn{s33tmNi=QM_8BDp&p>YbDoi2JDo3kR zY zL_}LyZjh0$dh$m-1}X$vse3clW#6h-ovrg_^F5R{5$mqnUPa6prdR*2^QKoll-36c ze7Z!WsXW7V-+y$z$)>DApjDyx#pJ|RSAH&Bws7Cs4ZZMj3lCWAK~X_ME%Sw5H}%x{ z7QX1LN}yGxUGd~{30MA}N*{KEi;{!y{rJ369uyTMu#Sn{nLCS;Co}x`kEtqwRvQW= z68{`7{Pj8cHdve5o^-uem8V3Np{O8%^-a?6t!`IMB?nhI@gpMM zmWa>rWdiy0j2DkzRa!*V{jDH@^-Y{EUt}WLlh2E5V)YIZXw}U56nSyUf!CWXpTVw; zR};Ua3VhxYcZv!USVP4uPT$p}*!l9@eq?EdK&zfhuaIsV?D+l7^7$CyGe*DbvY9Ow zD*^G%g0)Y5M}@SntZ$mQna%bMQQlEVVC~Vgo{K8$dm3+Mqs5tH_*-ZdJ!~;CCb;nH z)~G5@-b?k6gB#gvv7!+bB(U~~ecOGP>MaLtWc}?!6auZjhsTqA-<^4xjj|^8+}-!IC1LIJ^f+qI%dB?CD5uLPat_;iWovQq>q$Q`APk)tJ$50K@=4v zur7#b?Bnv26314tRJUM-K&u$Gm*``}PQ5L%CT7rTlNkq=v3PNg6e>ty?GfuFn5u6a2*qNpH&wMVp~HSb&Ab#f*F162a8Fj9LN-$JgG!(kMxzm50V3n{oZ-1hn+1^+6(q3sXc})3r;n(Un`D@&5@?0-YsB6@ z%Q`*qV19C-a3n>JJt ziiPpV-ovdE`U+y#o3aEIB(Rq$a@S8w{5+~3@6+srLZH<~;lmsurL8>MFNluKPY|@i zQPIDNey;=gkXcR?6(kyoFWBaYOpKk^S4`Y3h%YmpC@M&(W1N7uL5X2L9^9`QRS2{? zCDvt`qcAa_xT8pN)%E51^BfkX?}Otgm5^xh>4{ZgNzHtkMZ2><1%V0@IMNem zFYk{}Tz77Ye^;?e4+*sTJS_It$kKXOvGeOs^_T1VP(eZ+-3cak$iN|F%!CMqK&uKO zD%V&snhX%5NfA+Q+tMn1qKA;f<0B|4NZ@Ev?2oEe&gVm=WOB1^kV2pp#`H={M-wrw zeIv%Ts34(6{yI2fA#*F`_^(%F>SE1if_RFsmtNW^p)K&l;d;orZ?+^v^q zVoE}<+5Q>dt0jn5SQo@MmanNPdA!`&x+t|?A%Qhid}A3|+GyH;GwWYBM5((-^es4m z+r)*xMzQ4O=@vA>e~RV@V%mGd!Ot~X&LH7E{uwz zSTiuL9+r*R#TvXbrSN(u@^nNLMFoj}0-6%L5-z;9b)Q$EXEBE7&Q0uW-VlXAE6i!p zEYyoJ?D}kCIm(1kRFG(Qw+ZRm(3Kar?nF9$b-VF7Q0J3(c_;*0VZMoP!hN?JFNn@( zz3`x@D8%L_gov5D_tv$8zPAlyVB2u+)HaMDu@S5=r^Q^Kzb(s@IgDT4Ka}83Z`?T$3_pcU3iaXPT$R-^6R z4eY?HV2TP7n1^D9KJt^%x0!|4nJZ3ng(nBCu)c|yC67NEef%vvb*p$jpe7=Ld8lbk z4rgMvVz0>EjA~6pD|`yXzEp?OY{b{W{F#G@D+5s#kWkCx_8NEg*ZINRJ1JZt&pJo7A|}0+L& z$eaPjJMzg68z4@bgWhfG8^?k(!ednJJJiNVZ84eeY zVLdzf@DPVG6cr>e*EOx=G;dbE+6t!43Q`EP`ks18536p^;}1(8e^>NjUf)-+P5lG` z3KCdOVm7MfNaJb$oTOGtq(Yz-#`_g(Yfq0fvfs`@+U|*@s34)1;E%HLEU|1qzH!eW zf-z*U@4KVv0zKCwJMKP7&TKCoFXnuD_vH;8ClFMSz+4w|$U(E&C?8Lr^J8g>1X>*& zwopHj&yHsqEc?{HH)b=h-JZN(%hD7TB(R)BMAFAC+1(3^Sf^`&3V~KlUM|*qYFYT& z+tP==wH4cyxR~|c7)Vh;0?SE^Chp8LHq_5cR`iHe2`EjB?jd$_#LhSV*^q}g_Kj5H ze&Fw7If-4r<2SNWGh6XeVog#0AI|y{Pg^cm9<99PqH`BpF4qyY8THuGtGA8yT10p| z^B0?xqb`r%;AmYrV4lJyzwnx;bE(ASLaD5)D8Z<^MXe{6;mKlVOeZy3&->c-*>)!n zo_Sj}#RvYb^k<$7rfG#v6krY7r?BS7`&kL|b+6q6fs;`1i-p*_{x8Y+fXO!|t zPne}C*0+zC&&oMixZ}nAO3irEG^<{0lMR~AH%#oGt z$*#XC%P$^P3A9qne1EOhY+0Dbr(bDpEf2Fcq$kX}Al9CLonx$dTa6tO>i{s)43=QS zy1DfG4>NJO#!u7QIN7mpt$MNY1;QyRNT5H_BP(5&bzXOdIf}JvNTAh|VL5c)N;cM7 zDc0%F=+86e?wlFs|{g?$Uqh3;MTMJ2NEVd6<0r1j7j56{eJ zA1z2Rr^Q$O?nx}b=*tg^)rMFTF~%0wF|k+QE|J;1?!ybc@1(R0NT6>`^PIhb&E4OM zPe|96pcS?&B4+=(c`Vt-!fT|fS4gPoXj?n0(QWkclz`M2CF&5CrvHmRdgqC@d}Jfp z?hcrG(Oc8tA*?-g+_!0fxmLs#nW*DG3i ze;|Q5BEHd2sKcI@T*};Q1Stes;rmg1$C*2bbqP4mYHjVNya$m`^D1J(eD-Q;C4P99 z`mRMQd~1ul`fDZo!F~Db3<8$bywGjN;a)z~i=GCN1`Lru&`` zAgCaLJMu-WNt+wQw@XR-Y-kaR1X{JR+#uV&zcV7|%i6x9_a$<)VsYB=NePMy61az7 zoIMb{ofHn8Ms6GggT*;TtQMFk1m!>?(JhSnjD zcih;X=@ANnR{t!&MqUPHVs_tUI-d2*K^l~($}ScjN>M>V-QC}4|67uyX?wb$dmDnW zqp@s$l)6LahP*cx-I43UCoXtPo>gy8>)W;?s33v4F7}^)wxjVQ3ej`LvQs3`Dz4@o zl4ZwNauVMMcYY=rA|?=eY5ieme94EQszj!DRq;q z*(>gF$|#w<*|ORD$!WO((I zwd7EI2FiZ4rtR(P6I77Ex*)##jLS<`*U3*)m)cS!&}!Q2yQFvfABLT~tR=UP=AaM# z^3wN3oGB_uVC~VgJWQ5PiL7|0R?i?(Ot)rVOeWYRFJ@O5;06`+0ilW7Z@Y2wowSQl6iQwksXWkl0Gsn zdQQsKdSonF+{GH%-&BymauTO=`PtJYbcwOtTlImz8!+wx@fl^$c1@OfRd8x4>NRx= zseavCNjaveakYo!ap}yge=A8$ZeE7Q`sSuNmp@g?19Lia*h8{I>~K3|J;%gxPF9*w zrzxE^K8I3Eu>7Tu>s>W=uClBp_2XUXl4(uo=f@U>Kr5M!oP)j@--G3;p`9KUrVZ}b zrbk;l5LA%ZT=x-qcrpWPc0>|A#3@~A;z4sdA^zR!pNrTj) z3V~L`Vjq!LHEh_5zA|^aRjo}sj2TJ3J~9`gv)qRpC$(_AR}fwCX#0|&f`pn^`3`raAC|?D?GFDa1X|ti{(>aMxU#9)W$q3f zSBCcKmz#bX|3qmS(&yXn=e+rPAF7vfqvg(BA~Hu!1qsX%u@2y%52fYYXiQ&~Kr5MV zzn^pO8FguqcbRCFh}{GgBrr$B+Neo&>6N{iXw?$Q3V~KK-+n*mKJ_|K+nd+P*hg^$ z6(rQWnn*fOuRT{uVG*?#3ABF?`n9KmNb7UXZk8Ali~x3HMY-)%iS!@wUI2rJp*dd<5i2(kNyAF@vhKHZLdC$ z`b>J&>MU3-*6abu(`U?U*&D$2Se)SU!jXRH)SBKXJvA8>Y#&Wp{*stOep{5@ty-6s zDH@Z43KHsFwQc7}Pwi?=-xhCfK?1GtWOGdmX;Y0ZUFu1@STdxbf&}J*SQoCBrzMA3 z=#~$?t0I9`c(S?J^?S4nO}+bqY1(Qpqgivw(60Un%6Rh z{_ef6$-!p@Sb}p7kyq-ucv|mEXo*TXs3AC#5>J^#$ zBsVMWl2iDwb7)UXmCQ`XAL;0e3KD8MR$T8w>o0suvIe$GK?1F?R*Kr5w>}-Pp)d^_ zl|Km;BrvB%^zYZTXsZWbQ*OqUphJs4wZ131hUTM^mNB>GJ42S{?{`#Od5zloG+=8_ zx3ShyvsWZ*jM>+^{z&YNJ>keY-ji?6!W$=$<(o3_ojaNV&^-buXnHnL{Y=6? zbK05XSDPsP;V+4^8qaj2`JUgibp7y@U~8}-@f9h*Dj!>0D;LFHjhMyx7DyW%^d{Zs ztRko&fp2QjzdF>N77czxCeGVp!S)K@)M`5TsvtTj_ex@WuOdMO3Drl)D2DBrr{4F8pH{brO4W*3}xK5NIXK#>{oGC+^B1`XXdH zI~{dHf4}P$+3%Nuzp0axW^{Z_&YsoyvDZ21MbFn{Q4ft*?jzqHGy8X>q4_g%&lU46 zW1l`Fk6PLA(C9pL`P65m$Qm1dL5zX$mqZW1A(Ec1^7roHoxOgY4=&4D`sj202kUzw zXF4C74-BGzSG;AEygHqrcO+JBdqpA}XuM`UdA{>P;p1XwFZLwE-+p-SvK|lL`;ke1 z_)FsJ(w@F_$&Dm-j@2QU4!rlAPS44V=b3n!*Rp@Lsnr1b%`%T24j)QTK|=MB<3>N~ z(UY(sw*-YiE9v|4uuMF*t?cRF6Y+hw#gAc8k#nqfWhzLhDWCU8NBZLA(v+UfGgAC5 zw31~bPkBgMFMW*T#p$s_wYiZaxhkH-jVE-Mukn;z{L_}Z&zC9By|_JX*(@VpbN8x_ zR(J|Ho(L~mpGy|H{X#i@rJ!39{ua_$W5l>NX8?7*DbAm=Tuw#>3DrmZq4w1Fg$*CK za(gu-&*i;TZdc1+H~n@-C|@uVj6TAsZwM)d9)oj$P>U+tS< z!MwsWsYIjarKwl`>U>UWJ_8jb)(v<}N><6tzcrWT(d(is&A+E5-`%W23KD3AcPsWy zxDTgWYu05l9cB%ey-D+0)^^MVv0CKfa9Zh9RhCe0WHKs9;BzDTyQ6~W>rcDHd}5I# zB+yFD-4^brN$|vOywbWp1W%d5GpfEXxke(&*z-RY%6ILS-6zSXSKWBa;NAokB)ZZY z#Qw4!fBL5+Y;Ij4mpYZ?3&k2^B+#luziXs*M>}3RM$S{;D|vzBu2q_6i77%+LE=s6 z8^q4pjh~W`6Cw^pSeA2I;K1lIYVB6cr@=wqGOf z?%VQ^C6egS>Hu*Z+Jjr1LJ00A#j?SDeqv6a?;}m0^x$EAgOq)#NMNpuRg;Heq9Y~MNp5&V`R3Xqx_M(38`I#H{RNq(Kh0HyY7SY;Nkic>h zb@%IVSyy7?)_5yVs(c1lSUjxnD15_-mHoS;Xw>37$r%gU5mb;+-{)PL2hmLByZg2J zvRfh03f~Nxc7O0dI`vzXq;W0(BB&sN{RdImXSAoIwq2__u8u850gg;whLqfMXpx@-@h7FW-9lBFi;qT=jC z?DdP@(wpmg_MQiPM+}Qr6eNz%ykVuo?#R|BV%AbpFvHYc5j3qAZjL$73daeer~hug zb^L$1)L@EAdP3e|+V~^z?IkNQp6`io5^Gj~=`y!$Op@PKKC6BB=vP_oq zqI26;r26Y3yGxAmQwX$DOEBVSY59C;uOg}|a{%cHnGQKOAX@4_ELI{Rw7f#d-!-kU zzG+&W`Ss}X>IM182Oo8OBV+#odxK&>j^__T&R$OmJ=clKx3JxH8@^>v0c)ROiMK6( zBTm1Z*k#LICRoSk4Q=VLniKWrH`^(Se7BoKwcU5gAEIsV&{Ec`BByfGMMeU9 zP|H^#&?Bn`WV}=0KGg#oI!ZTkD`LamJfG{Z>}u7|3yg@vCBv2wJOH_ z)_){Opp{HV8ILTyYe!jvfwB4MhLuHmRO3$s6(pp;l1H-en4HqbwHcY|osF&d;MV>M zfmUiy=3BNOpK?Mo3Pb5#?6sKThE=mvT*Nw_q>rmN4vT?TIHudr=Wpnz? zV^TfQhUfYyYssgAMQD{Q-ul_VdK48bO|=AzxALYlh9|O_fdv%;t?CwgLbkQA<-12p zA1A+5p$^g0S@fLZ6cr>e*F~J7k3RIq{A_$ko-+gqw32t5@uDqX_Dc2>C*`j~7uC(i zACEsnP(cFAN$ijEDn)a@()s=_WfcOgu$L*m++ejb0>T_Mm4TO|>fb3s))_m4`vDZ8w+S4dzviFS9;Q{w!h6W^p& zCwR6jK1KIe-yt!Y9iQ1*DM1AZd>%EecAN{{FtG%$wJ>SEZkAlC^0X3-Hv|iQifNXlbND|1hy-pN7l%N*8IAN1&e4_NT8MdxI5%go6LMt zy!0{PmgtW>+rplN)uX5&A^rVscjr1jC7m0t*Kd~YrVwb=_2_MKtgS6yyhr+2HSZ$v zo_WH;^7o;rAc5_?rgibWMLcL{KITvdg5w%28yt&>`Q5Tt$y(2@e4Rrxf(jCt>td9; zECXF@TbLgxn3p1fRyYW6A-!zb-f&`Y6 zID5I;3_Y*I6HqGh&95|rRkQsw+JJB(TpY zPQtXwODpF#ENx3QRtU7h-hlWSVnLU4(zP98b zib{Gy_LkGeIAz~m(>HeAs}E=sr4W)ft*|u3DD~|%y+ilCdOty+lAe&X9EHg~zWgs% zUd75e#4;UUurfYX$d0xPb@ST%d)i6kRv?YgP(i}HHVNzRTS0T4Qu;7y^IGnLQHWTH zn1oc)6Y>sCLfXc1`LEm`A%6>hS6-Wc|KEh^BR#DUzw$~()--?Dyq0$;um43@(_t#| zPE5kQHVHMaL{G))!~9({P4e#w5i3(JtxP37VfvPK^1rmak|l*c%xm-SrjLIUQZfDg z&%3gEGHZjhGJn^+#u7}cg%U9d=_5U1rqBA*vEpCxe=L`Gg7wubLGzcSKPw^su@b0A z+9b?c@{17G^1oP)1X|%8rkPs*{YjWPiiBC_zkH+t|3R3w1atbQahfY@%FzcB=Cw(r z|9?W}iRr^EbCdp;k66cV~ zm{vd2VJ)ZsCNOu+JCwBiyOpq(g}jpaZl?CZlm8%o<*sZMtanF$-pQ~0G4l;eGtJf{Q29y! zs);785FGEy`Whgq^#;^#lHzf%5Rgz4`;32SZmd56~8_cKR+)e@8XbyxpM2p_-d zt|Wf9iKdd?hx|LX)W6$AQ$fPKHVJsn->+gFe99B~R$D5rFY2FvUCY1AZ-u|_NM1=R zQ%O%q`WNx*85~)``kY(uS6+)UAo5PkznkxKYYmB&K2S+dNLnEz@SlXVGJom7aydKr zvlhn6D^yG$CLw(&gaoXFsYqf)duKv}3Q&3N-60#9X+06)r;lHRsiY?&|8ODKAITY( z|Bo=OB%RnTD+x-F^9<<;Q;}9kXwO_oWbywZ4))GKWp7&&gEwcSE8i8gUMIcCNb_Az zN5oq1-OYy1dz_ZqF}`B=MSR+|nIr$cD^rm)5~U(+Xp2iw9uoam?wVGTmUa4HQVOmKau1T3_ zyB6un!=J84#gaDqd&JvqEk8otr}F`!zR>rq?Pu$3Ll-D zMkX*p1PKBaB%W>k&YBj?N<)sx+zkp{?|o1Z4bu^5RhArK9ygrmwnf1JUp6Bn)+su?>*{&%=cyLC0%Gx+k{3UU2#-X{} z_X!{E()mDQa2Y>7i#yQVqg_NgN-rqxeOwR~(h+D?h5PW20ZufiWi~;0Tq%>(P!MyT z?`PKr-e)AY8;xq6pBBw^mHkOwY1d|X>7CYRSWV?=_yt3JX9 zrm$NbPd;*`GkrQJXS&?=)`nJ=<2^0i1u;Sps0?^rlrL=NM%{1bPj^@QdXDk=TM(Jk`9Olq&&T)P zb)!kOC5{?sqZw-f-c)qIoB&zr1VWm z@ONiy&Xzz$L1LJ19{xDSneyW@=9y>y3yFON5hsZ9d2g^MA027CN=0eX>&MLLk`tXj zA-#`AU90XmC5VW0K9KN>BNqVh9AtQI~{c^O}shsN8}cOovlnpbfTV}B8-AhAQlsjvJj z3w50#;{nM3eh42c(xn5ff-YFNdADhV_%~KQhtfwtQZ{R^NM2JdleN#V$DtNC|E?0K zAn`i27B}f%gmfd$ulfC3Xtil+Z64Mr=dT`_m5P-FDo70YQky$^XSCj->H`V1lD!(U zccv1kq$kY2mO}6yU46Nj@v@Fg3dIcT`LcwvL1_<>s}f zUGTfMSrUx}u{AD{btwB)murE;`*N0L>{EU7cPE-{SXJJ?|8qTSpp$q8Z`vQKB;Mz| zQ91&x0xE1}mdhE*o)FomzW08W>;dq4>Fx^418Gf*&il>lm>?<(0u>~hw%^D~_}UYn zB^iW|Sv@q_hvRM25oo2}RqOTxt%U6LHGXxGJ)3Y+AN4IKJ?T}H2bbTcyY|XU%j?J3 zgNavl+oN*UAY@w^YdZcA1S&|p4=l~S8lTjYU1cBc`}g+S_KUk}m5x9w%xMuNE#Pov zSspTXQ9;73VkKU*?KOSSWO-K>rg_Sgw@F8!73QH>k#g0`OA_q`aqGc%cK=SIK1S>? zm%R)xukE_*S$w(vihUr-y4Rt!ajl5KD~K+FKm`feUomM>f_a?1#mI}-Oh=&A%;9%g z$)tTcx5)KAelr$&$yy>uET|wcr&M-cdRw9%Dx!diGM`h(`-mX?(h+EdB`Z!jzO_z{ zShyUkp@PJv*?IZXQM>hKKV-_AIn~`ROE4fEfmT@lX3LN^;x_MH_U_DUnY(7bDZM@} zSTP5XRtEozNbB|e-Nmm;&ytM1{rMi8-y{o>y}N#5mA&5JlrDRK>oVK&u2WCx7p*6T z$lpF#ijj?i*t4b@H;G~$J$a`CU-c3z3R~Zg=HJE6mwT zwYte3z=ZzUWiNxsUIr?bjm7wt<+t=P-_m*j<}ZneCzUFArwSjN(xn554UO~jxPh1S zoP%V)WUcS41W(~(UOED;+MmtCYuI1V--v#YSQlQZQso!I$0|XfvSoQzzTNhWUgT_A zZ|V1474!)8HuFlp^-Tqdd~r^{ayqTdp9mka?}G$dVcCfFSHYRQt_fnTAh4twwEN1c z-Z`sR-<|%h+?vEDHWw*3`-$dVArTk$n$@d(QO`R{ru@Znhs0unSeWjv&}w?idn|73 z4LvfCB#MUQ^x@*JHVXokYY~^2f6`;U`h@f)xO)3opM`?hk$4{?57sN7y(%4-%vMNn&&#(n5}F z*Lq~;e`Rhju0#wFnBT#9AM-kG9oL`=^qdmLPLVAin5@>~K(zIzSHSW-?6Fu#x zr=WsFuMRc1ZTBoR+#0{6)13#bq~3$JT{X)G3A9r4%67#+B3fu~dZcfz6jXLT)wxGu zds@3w0gAaU($W5)*m*X9PAyf}9~C4nAFamc)ODmYJY`EQj!I{K*+OZ@BZZTZKr5V0 z5MQTTtYPI2gwkfOSMERsiNj)s<%pPJskuP<*e7;>T8)RmgmDqin*kLg{VrrsL+hHj2}i*Hw7i4f<%ena{RTJFL^vcJ|BliRb=i}BB{g3 zMpckNE1VV4wCVPhShGrzwAb2_yHP=6d{1}oyxf&;yCr>WaQtDM&Jaxx7s~601X|(T ziCDk8IymLq#~8tiDBVBj4b8WjIa{mFmy}6xNlAPZLw|HRl5(<)3oleVD;+d8?ae6( zNvlM^f@f1coQ$DgOFXk6fmTmj=iwPMW~DU;$kwO%ioC|5V==Vi#Lg+GAb~SF;uP@c zIOAdK7+UtwQVSAjmG6EL-lM-8eO*cV$ewkHaluo;_pC3_l&+;{is33u5BMRZu9pdcU(^?+p{H~06VP4Bw z?ne_6S*NFVbk{K1Uj0$)2Km~h7hTx*<1SQ?z!`6`@~p#k@@8HyTG?Z%LZH>FJV|U` zBYWEOq4e>g$$2tkS05U=XQeMHNa#y;Gnf1hbk<7Qwm(ZfOlHOOr+&@8>_!C%oFf(%pVvV?% zGh`hp*DI8E@p`x$6(n#LSM1GLw3sZIK8WW0>YacDS|#g8SROG$f82Ve_sNcviI-;> zEitxs6;zPGd0!EeJYf>a+aQeo>Cw**3ACzl=q&T`b)nl^%jf*e+m58*$DuT3V3*yf zAc1q%;`wmtNG{n7qyNlz+JOXGZOnO1MhldYPgJ)F z5&Dei7&^G*m=v5b&!6&{HMY%4HwPA`I4`bgZ!b>Kdv%GSMNVi{Q9)umeZ~5S`SuQt zq>mzFZ|NbS(R4)j3_FlOE4)KZt2^b8o|i?_x_PFipn}AWXHQt2KsTDr8s$G_*nQpq z&uD7D=Tb5fXr-pSRPtHN`ExNeaO4FGrd*Ci%$6F{q-hUsy|k>o6C+Y2*1$skAYopo zjd2DKY@|2a6vHKfV;u8Zj%#o%D*Ek*6K?I$_qCJd@#UW@dTK;8Pua6H1r;PdiIMO}F%otv zE(ymvXY>ziqPgyS$qN-EaD=RBY<(v3_C^%%+&y6%5@>bo#4C2IUb4QZnDp`SpTcD7 z)kyy7^Nd}nAb}%f@m(#T2-$csl9!)8(H9A{+T8Unn|^ek{v$~~QJX8YC3pRX@j1iC z?m`8Ll44dQ=fsnGh$tJ;r~cB0tkQ?^Mb7a)s33u3YE7$^eF*6>HG&(jvv?zcR%P^y zY?A*eeP3zmBUj1<;yf*km+if6H!4WX>~xe(Sb9xQ6g$yG{F2_|NiYxNPbV()Lj?(( zs}XZDhyNl^yA0(2w4SmX3AB3AhqF^+_N&=$`NrvebtQ40Fpy96|LlVb5;#|*X(j&H zP9_}<=9i|ONI(LuI_xo6Qid0LwKki!m;$ch8F zvF}DQDoEJR-od^Feb(QH$an38-g`(%OCaY)+hkOl?%B-_t$L$Zsa+tQk2iI9llZ|w zyu-%DyU_;{XDlgfUyE1zhcKCrmk)Q4M)`wzpyk#sB+yDtx$C_BtVx#v)|A&?P={B& z;AmZ|B1d6zo>Gp_%*i`lcdLHu#N zmWT=xe}?(;8&luta@;0P^YB^4`ZXEIYpk+KMgpyHrdUL@?y-isriSvKMY6*T=oy7LO58|GM-|t2RiO3(d_=KwVKi4ho zjoizM+XQl->Unn|fmT?1M10Y`_1LEz!+E(Xg{ojJ!P3lJtT<;k4(N7^W$Uy56=CB? z4CjATO-x1w33aY-?c0JZ|MN(`xAQfBB+#n*iu}CO_!ND9Hrck-@Uy3=)Pi3W#UDppAB@?1~&%d`@aAx!5k*qxS zQ-c0iXkm)9*v~n6tFgl_hPSIdCK(kZ4(89xtL50Ohj~gL9oR!7uuU{Sn$*r43A9r0 zs?IHc<5)rr-^IG7;9cRoDEbpU{dN_M1^d(b45%PsUZ?dkWb4_l_%zmk)ez-dBYqQ< zb4y|e4_(+wmU*$I1$WK6IE$@#HP}j+3K9{;s`DWWY-sO}lK8&Af^XpXRAbY{XoWy4 z>ErkJ!JaKA>`F~~ZzL5WR@x4F88E5MFtSH5=`nV=Q?5VE2!N1nIP}X^GghHSdtCX3C z3~-^RvlSCQw#AIKxb$%+t;a;tofR|l3iVy7o~0Od5>}(WyU@Yei_s(3KeLf3E;R2a zIg{!$jaU|Co1XmabBv-Oq524|a>cT`gaMiP_!gtnEeV z_I+Y3a?h2Pm@IwxCGNMZnUYGDCk;>(B=ByummD z`Y~=AK?R9>cb>2xh27|a9x~-0ADq{he-5Kd8;2_dTH%;VoIkkxz20R~7Xw zRny1plbsu#+Clnga_601YGN22c3UOTN*$|J%2$|->oA1Ab{j%aL84-@>+EDPSK29q z^wDR0A>vwb2yIt6LLtx!N66yaM8PqZ44IwS`l(SA>nJ`SYHhDxbDia4Z723>oQQV^ z&jAv+sz=k>U0Q3&8sWtBu_}R9KfIr^^(9^CBkTE`gRZ}@tO#~yQNd9Z6(n$dkvO-n z{tL^Z2xrzT9f4NQRy}6#TwLg7@pOrKhSm9WhiDh((=v*pf`qyj=e~VDeZT`3cB83E zpq1^a>#S8dXByK^`uOhCNw4`hD_bbyK%#;KuKf`^Kr?mJ_f5^lHhhaz2()V4>l}OX z!I93pF3Y^v(;F6kW;01>6{56PST<@~QZ}K#9`bP$Iae%1X-km6To-ZA^Yzy!t=~lY zda49k&Hwg<65p-&ju;#|KkXkic9QQ5~C}*F)>9CnXN51X>+yc%9vE=0Y8x%G|Z9 zl9#N_9Z$|a52C0bp_a#?K6wanUrnAC304TS%Kh{#3&`V4*M>+R&EMwJm--VLVP95x z8(^tn+a9GE^*Q5_{(g#u zHrn7pQ9%N8U93)c@KA3v-a>07sRUYK+a=<+&&)+04fLnebPtLO5}50n=8!QL@y_i} z+pkjzw8GX-#LS%AhTJY*jb0sAhN6OmS{?y2T9YTUtI{fEJQM=0)PBhh-yWn^awx5v zBZ8oUJsI?^X}4b)C9o<-|d>XVegdKr6Lve|};$$x8as z3Tp-toOQ;&R)#Bw*pb#wwD4ou7j8e450O;AAs(AFf*WDdb2cFIuQqX^ILGnA4({ak)O(zj6tQ@CZ@}w0gJqFuNV- zKv&j~Pt!{eQ$a#4K{=9|*GYUCeWCVV@e3yQOGO;|nr>AN2%^@L zvPz#Ci9EBNc*@VdwpdmC;;zs8(f#PXhH5Vyt+0P>9o=bF1<|gF)orKfmR=d4|CLKy{p*hSa(uS5U3!bj=TgDyKYS? zN%}v^&H^l}Bx?Lur4&@`0J{)d!2s@zLD=2hT^L|c3U;^HvBug8s0i;JTi0G)yF1tJ z{GW4QM$Q2H{lCxW*=3&hoZp-~Gv`jv+@k{(f@&>>RdO8Z%`^L=Kb+>rZQgK@JqLnH zDDe!&S8{9!ZEc|;abDHj`NpbTA*j}Oupvj5@NK{!gX6rD2r8jOe`R#nW>Bt$B9!3CF+BXWZ#`#?Y!}idpG{Fd=R61N~(X;MV@1@Iz6!f zFMp-FaDJPKm+Opm;?6>O6N|rT#cP5M`c%|jefKP4(Zr`5F5 z9z7H4Y@e0z<)`ZH)GJ4n%pyL2&B8O9GZQX0s}oL#mSPL1hj1#P1ocq3F{{pny{DjN z$eN;Npl>ie3j%jXA2^ZFb=**6?8Q;axe`jyw;4_-T=g~{{u#)R^`Fk@o|4+D$_d9R zS@?O_ZK&=}I8>*$vHtvUzPS1bMkSOeKd_X@-vV}|iA0nvCLqObup= zgv3jI8s3koHxpf2jp8ROsRY%c`)6RaZ+IiiZP!t}*6ScfC6rL#kFC4%B~hy1}WJ2j`6J?%nyaD+3gQYSFq9zNxpYlLe+M`P579 zN}Whckk(2tpJ;bJF}eriZ_<}h>MKf6uY_G;RnI3*Y|r?2CzYUD``cK5RKV^gtC z+iu~;UQk+UCK|NH{qD!nYJinFaWiPoY z1l8)it-2^!A`|cDk2aq7J#5VObmMOemE=@H3EH-6+PQ^?jgg`x|1qVMLQt)b$8<5{ zhdu8;2zvm3oGfW+b7MPuUwNp~zoH&a+ehdv4O@^{Fxw6`r_E5M<)nn-q1v5E3lgW> z>|od1sRY$(T{o|AiO<60KcOdfx?In)xxsc80Z&CGl%O68_uJdlw`9+{o%PmLf@)UL+2>%DpjxY%mlGwp6TkEoy?vHTB_qSt zwahDMFsBkqP!ENcvtT77 zdMNDPx!B!kydj!-PE-l1^`v!m(J@O#J|Ygi-J{$zBRb=3RyTS8rxHr2zMJRiRHOI) z8SL9Pm7rRqI_u)hD?2{?CVG4RphlKSCmoGq0invMhCkBM`P2{P^Aw? z3F@IxUpZY#h??MN^h`leEqeMCZV@+D$(xYK0zhH6P27?9N8H z@}ZncC_z0`)3WJ4manUwjVz^Af@;w-u`s8TP%V1a7Iyz_K5lUx zRMfaXek`XFN~pejFVk^L>0iZ+c_UPUYSGnqO}kO(l`*b$2VVYa7e-Gg&@&BFTh|i5 z3fl9LuW{GQTqiqGAb(39?ACy_4f7STEo^!2HE@eLIgdflX~1_BwP%)(=WUr*AcS{^ z)4gu_ZTJ$~f_zIoUvd0G2F`yK;B@sJdH^T)SQh(NW=k@SRV0*9*XXx=v=I-!wdDUE z3t-f`hl8JZ_0xvWS?0>=(?ac&{gY8~axK1i_&p^Zl(_WHSG>Pv!-qe`l#3OI4Xvy< z@7>;6iHmBztl}%&F52*`qj0Cwtj3p(CpF4)`%5mIN+|Il!B@CWvf<^;b9XBqFEt7_ ze#r88wowSGMe`8)4C6Z*PhE2I1-Uq+9&ZTR)*28>E5p_YeNliNo2zf1FSn_M_0 zs8;hlwZx$@cKoxsXS+o0TSof7s&Ezv<2@pw1kH6=6RthqINCU#-MZ9WA*fdDpEbqc z1-3k>IkpBR#x6GA1U_b?c^gh8lu*m#^YaADuy4f@y`F?A1l6LuQ{eWC_V+A(syeVy z#X~riP(pn_rp2&zTvE~t0A zFEq}%?Pa;*yK^d`1T81%=?^?&>D;ZD5fC|6A*hyGC)&5aVTli1oLFL17^f0S&~k$N zkO#*aRj=9c{I>q)eoA?-(vuy2;*M_y^S#5Jb@Co2cx$IS8)Hg!W(oemJf)VT>1_hA zTf}Zn;@g#fu_?6&a4NxgC4pgiLl>MT-|)s#c%3KfTWCxwLTVwAd`m%zsgB}!ht~Y( zrZPIMMNv!MtA$~C-xhp#sYwR$HC=1|?VwukQY~7e!uO+gI*7Stn(%Vx$1p0P1cv1; zVDM#9*RO`(%$od2;Js9Y)S@*i)YRL*7`>f1uloKmqY@e~hUMK`Fm`@@)9`V1=YuY~ z@RWqqqBSa<=d6Fz_-rZ9TiwXbsf5Oh;p8%R*s#;6U0ma1Gc`y>NG)0i!~VomJB^Hv z4!i)|Tu&u5Ug|xXcJxrN(P6%Yja%GHA*hyGx0jeu)mXpWmp#uCthC6Kp#G+5f6cpQ z8SYbxZOA!RA*hzxI>+Yv>@)CkD{*R~6ZeJrX#X91^aim1>OFk7V-EM*Z-q+PlBF?0uS12_>EZ{kVOseg$?}!8ypq+4OQ<4jP&MgqxsXEv0gW zLptswn+ki%@?J>P7sAZH>pS?uM@XXnZVisS3b#D#vkyEz>!j9-gc2QrK2kYRpSB)} z0@WV++?-QRY|rSU5LAn%58978UOtY0&GXLvEu5G4uoDF{pV0q?+2#I~?Zk$VBRcMG zTl~#N^gDb+zmpaB!#Tu6`iyH(%D6u;$q1IH-R()RxD7kcC_%O8*%R2^ z7Q0b@xgc1yYaPU>gc7QkCYK>!I7v_54eN#DhAcl&7NS zO=yllndfq1Q@)QB9Tup0MG1P6MAJ5ma%Vs8j}Y%3j8JlyYSEJ<@ScC|#R9Viibq`| z7(M^7)9tb`%lKQr(6$g)iQbv|vPx$HMMRt7j7licr`ZGJP|c%y+ow3%ZjrwXE4*cd zIQAk~A*hy`@)|kEv)50Ch@Q_!C{IPtn^1e;R|V#>QKtuqWy=B?l~977B!PA3n7M3Q z=Rsl>%$`$%YEAMxVT4z{qZeI^eYiF`b~4-5eMO;;Ll~7%B66L@=(XXEZXCmY`yBWR z-`0=4MYdfN8I@3io;`tccdIRI{F`24bdO;QLABJg8MAWi)V&wzVp+7iQYTX1RqLxx z^Tz1@KXnms!(FL;C_&#YxEU|sSl#ccE>_u;Q3$FP`u3Yq^PbQz1Y-?XN8HxSobnL? z%iTGZP(m&97FF)(j!S$*qw^|3wffz8V_d3tSpUe;M&j@yEXOA=QMaT!rxHp~AA=Q> zy+zoMxnAPmSt>!b{tbCxoIG<%e|rI2gS!XYvypJW)tb=KoJuG`y$5zpI(J~-+g20J zvbrk-)r#+S*%)2>ivAbex20)izfEEK-&Mq^b#9zWC_()V_Tm(t%BJM6BD`St4kf5o zgXt%XDt|uG1E%9USf$Z==D4T4xU`}arxHp~4~1H^-+K1;pK`)~yqiK$EzhqOBRcbE z{gL?v$#k9*^j%rD8ykKOQCd#weQF!EwS8rM$kgq|>Ka3pHi{C|d*D4^R$1TDXuC1V zS0$*HOQG+^!J>cZx6E5r&Qw{c_c^-Ncn>=ose}^Ldti4$zm@vr;aiRF8HXwa)mmEQ zt#Kjzv|f5EdSd&ShkCI<;zev%8TeR7>)aUP-&RLkZ1W#fSVT|I6GdSXG%m&F}f zWvt3Nm{SQQsQ1A7`Qtk5%<`4SpS4wjYW-Q{q_JS~D?QO%&3N=~0DICk+Gw6(5T_DK zsD5>5`v4|BE;6pxQVFV6VY6X;?V_^AcPGN9 z*EL7BcTT9%lc5Cl9?gE z$S1K=X4YnyN>D9&Q;en^c~wFW$&i(GhFNDSp#=3F*fa5|gzh{tD{ECpC8!p?X9iaF zS9H~Hd1hyKzK19`&`^SU59~FF>Z)hDoShZ@q!Lt%-bMqr4u#Cnrw8X|EtZ6EDxn1R z9!Pof8G0GNJj`aEN>D9&e+|rq`)tzl9(7^I3x#khp@iyJ%bxzJkKgagKIB#js)f7T zlJCXAeMrqag^1H1$}oBkiuMg7U{~0q-{TLLo5!m(1>zeJR6+^b%Y>7Y={v@Di|j9o zwm7X2R4WK<$PtpcH%hAy#55qN79AC(CW^jmB|6P>;#5M3l3>FxX+#Enh7DI^TLO^{ z2r8k3I>tG2tVUdOPj}IwI#&p)^#JyGZ;e>{p%ZckbeU!cr9Y?9ep8e%L zR;_Xr*XOk6R6+?lZi78{E8bPvxc;C~D+}0&NE+$Eoq+S|coq*YWwZi}`dYTrwXhYo73p2gD!7e>YP_3r3 zoPLii&2&V>*PZ2!`}(Ma66)vWSQwwLYy$fy#Zysx^lmaudujVTVaw!^tlva6 zbJl%O68>p0`xEMo?2H+uLFReYBc!;WMVtG`%uTlhvg+>6uB*)qH9 zK_d!gSZG{Si@uwhHlSz$%lJ(0;!Xjsyn~dWbqw4C*|e|a*;iehg>w^BLWwn}vWcQy z_UOz0z`jq`E7dG#_p}mSN2>J|)uJ^Y+yfcwZTY88f04J~X+|ZKpfxz`*pZN|xbLluH*(VT`^=YVj_lRn#w z{H2F-Dxt*g9QnkGT!-{x=1HW;8!?t|gLE-1-d!Q67R@)9r|uhLImvV(Ub%BBp~Sty z`9y43qW;m`J2>*L#WJ96u-MWzh*5%S(VT`}xR~3WNX^V9u^C$6)Y~_4^{}Or9M^V9>pv>US?qj>xFW9%Obs_k&SW@ zHTIv;i!aA_aQD5Umbs0x!n#2yrxHrsdR$aYvcICQE{Q~m^7ky6eK#9b77bAds`X;A zi)cCZi2kMm5--Nzg&VUr8MeEIa4Mn1lbprG_WNgacXP*YABRH5z0BTXQzdtWpjvr1 zx`=!q4E>HTzO_}C7BtpcyhN7S?wm>}@vL+)v8&~AJ>m?G4IY%xERNeVvs(Q^mAfWs zzEQ7)n{$%Bh4BG!Nmc?EQ9HBJ8&s?VrKU8uI2)E$Wrf(|6oyd3t|~ zasAB@P9>C}c?f%0#(uHXZt5d~7P%_~)uR3eI|u&#Y>D^w5gm8Bb1I<(%|oc$|H@$8 zVL@V=jp~V1i@pUgj>_a_^!z?T>~I>XydRWM%j4_DQpU84BSh@pV1=Ms^xg)z5vW~D zuJ?dD>0wkD$B9S}2e7$5GeH=0%&q7YPTMKgDC(f@&7ek$5nWS`TRICX>ZDa#N}C6u7=BdlQM zYGoOgBRk9M5ULPVi{2ayH|d;jWwBe9jU9CiRqm9f1g%$KXU+AAhA28jMC}M-v`Ki3$s z{ed77O3-rBv|BC4Tiy=H#p)!&zHLHKEqdRtrgc6y-m>m)PS#<62&WQCs3n-K>;_{~ znf{{ef#HnaAw&DVm&Vr+pGtkyOHIR>?IV*{8aw**6I~pqFe;%0&2<>74PIdM@vJ1u ze|F=Ppjsn3)eyCoeAn$qV4wQitp&!e_(~#OOE*p>l%VCLY3ZM}Fy35RW^}v>I{`^t zRO?`t8p7C}p8a_bZ4}NU=*VgO3++@TQ;*t8ee7)7OQ4ODg@QSr;@o2yNb8R z7~tKAxl%!@{Nl&%4PBqxi7mYo^fVR9dYuPBg36wl!n%M#ww%JsG=g` zZx2O637XTeVp6u3vF}|OaqommP%X90o%~uGUxGAI_j+qD{sD!iTfqe zvoY|d9-Yp_oxg0@f)fR}O5Eka7!Ul)Fo7l)+?~PZPQ{S#?wbMNa0tMP}9-UH=E^X)TzW)2g8+HhiGYD z(cwO_nGS4xL#%f{&%9%~^QE+r>)senC6u7$1nuA?AH%lGB_rR49tuIVXime-T`o_f z$ojKJsqeRTK~6)wY&u(N-IJeSfSqO75>A64SXV?Kvf=$H4m$zr~2I)lW32 zKTPQ}P%YZ~fYII1ZN};1{l&^Bot1tGC8+1a+|roqtkcOZ{NSv9jNT(m&+QNK-e;_i z&&Z3Jw*p_u>9>}PK67)nq?1;~Bn^o#sf>#_k7qq`RBzsl~977;fMPGhQzQ6fwS55RXr7gYR&t;&p3bIoDM7U|x7ls9$m77jY{T~BST{Q!A3a z>tg&K<7Q4fzNrk_h%LRCHFBWn|k3>O+7Z1ZGJb-$gyjXLQpOGw9pzfPS2-( zY|Tp?uEppr=G0?;U5Ygtj&tBudZCv**pQAd`PG^)$W)h62_>j6z?{saeEhhd3tzm_ zmQ#XiW!w;J96M;w9ZI2>>^hN?zxT?=U5jMqR6+^rJ+O}~b8h~r?-Z6XwvIwjt#;|- zjDP;NJt$9w2$*}SS3W9%;Kz+G?R{h~Lf z+VV_5*nX?QsDu(U*P%UsQ-~jPb>-Rq{Gt$4tCM|<@fUp0Z{K_@b1xfLo<3WC-lB*N zrxHrga)SGomKNsU*Uo2$zgAZWs)bK`e~KNilo|7CmTMki5?el_3fefb^d&n{=c#4O@~-C1{!&5-T29a!cxB{+*$T^a z57h>Z*Dw1nBcPEjkDrct_0P-P5(mT1bii{|42Vx zY?hlsP^|%9b{Nyv+VfU9keL3f5|8O$l_wP1uTu#nT4ma5WV&F>hXvqwu=aa<@DXP# za?PhSqXgCZ6}i>8SJ{qd-iO~yU6&y*-}oVu<>kpnikHw*Q_F){^721(X1Dav8*wV3 z1loR*$Ch6yf+bjETyY+GV{PKioW2S{wJ=RDZrk!2cdCSzW04e;ir4@}Yj+Ez{>s21iz;o~;^a5W@G=BmrPmz(3$dvzgBC6u_iWRrpS zr~ZI6!-&PbC12U}k?slKjiCh9@@ulm2I$6UMXn zXSq3*P=clp&dNNi%Qp^M!t57jQV6OQcV~<7zO^m4If0(|{9rrYdiXH5r`>BtC6rL} zs_F5Lyv>>!?7hQPg`iq-o|}x4XEN|vIWTuSPb$qj^v}avPkFA?3@P(1`8^-K*^}oi z>CAIpxWX_;rGyeRM_|9`QBR()tTQj&PbH`p=3DZ6?l#w-7yXcd_ZhX1Q3)kzjzBv& z&7apfn1SagmY@(+3-c}cJ=X&|@Edn-u?$aUFe;&hnpcxq2fog@!6x;cqY@-XF{iJT zw&9Pq<$>ItP^CHVn~;SsX!2F367=@@@YVW_etFEdAo;15+qdB7N@V8KhGtM~P~zRZ zEk-u@rgzqcSc2h$>hKd)i}B`x|L8OwR7O39TO`jWNNU{qKwL9M%1K(*og%R6+^$se;=%^2GSod|%;aK9rzZ z^vmX&_NGmBo^NF(eyw)8L@J>K%?0RR>E(FwF+RM}j9%3!LAB_Y&B3oubmfB{ykeGP zM|JuQQ2O0ZmFRNs;&X=`c!H#SU*-Htk)o$YkqkK#{UMx#4u#q`adtR`F9bd7oV+|^y zgqn_(x4QC{OW(5%1KTB1f@)E(gkE31y1dJlLj2k~*F98137XT;;=HZHr$7CkcxXm( zULKTj9wK08E_KMJBWM3-*W?PT$v*8^dV$0cZ z%M>?@Nu9?z9roCc1dVyZw@mQAe=U8J;jy{~mMQtGQV}cDI_6d7^#sE8Be`uI7 zxNB48sVGg`UAPT#csjoI{02*b8yz^6Py)l43q=z!9o2Uh;BzuoH(s{&O+`p8HLreY z+4zVPP4!E2nsX|l@!nmw&9w328@A_}t5)D!Jque-b@fsRszu8Q?$dAfLBCn#faQI< zQ1gaAd4D^OAn~d2yE1BC^=R@z|5@OG#R2Z$rIM5c(zVZH?jD;E%a+*fwm6R&tPn^` zEt+qz-)HVhmg`A{#0TEPl@g?c-{Cluj;V$=-j=w+2DaH@ak5p*oNCd0gSDcIhgsQ8 z@y3Xj?UbHA?cLM#!8q#OAIumr*=Rhyuab_GMDl362ITIH{IiUScZMqj#w)cj-(;@C znlR+tQOlpl?^WzH4cykw1o^%bpG-W*tOye_Emc0IAa`nf2W z&(H_6(i8vIse}@=#(>itV8c1Olvlfbwr1V8X!bAWv^VGPIuY&BnBXq&bKUvTs}FtV zeSX1|+Ti{M<1d?Z{LebMIqlWJIO@kB{`X%V?D+h3j7okHLT%4)AML?24t>fxMDFmR z^%ZTY)pY#3ZZL13Yc0F-qynQ7N~kt^P7mY{-eqU}>SBeUT58I}g97>Fx6!QLVrNDr zl%Q#X6AGV$c#FNa^^(3L6@qGE*~nanvt-wY^J#%|j5^b9>+5cBFlwF7$KLtn;)`Z( zFdPTDu#<0d@&BnH#nOR_1Uj8NH7UM!5 zCw2+OKr|+pzseNC9Re@HH-4)8{ysRCGujyctsv`nDOU;`OO6cZFRR_Pyu3b#QR|fW z^k{?8V{QRfI{?4$j5eY>RWWuCzvxAu9sRh2XE}!UXiS>cV}C#1@%A3$is8p-I_R@c zn6cT&^fL=9{TBOIF)au3;`(C4HFz|m5=y8x3f+bk(O%3bEm@Z^HzmXvjkIsicGwYRdc6@5nzID-$iv(sLRY)xxsDuRQG8j5Y>~V*JiAU$Luj zLN)p&Zu*7pL2b7hAAB;hQqh=lm*wqwi>B$ty!$tFsztv7PQM5bx9MK-;fpSn74L>* z-9zJ|H1!xw>yoP#Pj@G?nC5*gfl4T$+Sq!mJ^%L7Mm)Y0Q=Jl2i_6|e|apgb+(!jR$+Vsl~97dH?Ws8axj1XJ>Ix{Gjovzz-e z`jsjAjjE+z6O5Z6*a&4Y5@=Z@pC6qY(bD!a~KRx?yo}#O>wlym^ zqYCR)D@Y-zR=PbFqkTF%cJm_I=y|6W`}8Xdn{;jzrxHqZd6Zy;x!SX#E08$c{0Ivi z-Ba{+916RHlD~0A%Z8rw)3j^*4>9d|Pf=sQVC7sYC1|e0J&<;X*sDHnqC%^ZoW@19 z=m{>o%fiCiRxTs%XDz|0gc7uz;2!#=^V#Dv(~W_a{t7|0=-C|T^{t=I8h==1>@Cut zQwb$#IYE8(A`|nntHgd;Mk@r>!d_JJnV(-XUg!^MW?}RHvfgMdC6u7$q-i$a$3m%S z5i>S=C~qq5Yta@C*1YzG^3F^0CcG%%z^H^0YI|Oy*J7t zc=+~ed*Yh^!Kj21wEqC>ICIw7gN83 zg&r=y21Q3mFcN-uOHbGHNR5awVdnTlj4 z_=|OujlSn>IF(R><~rono+fa|y1(hLA7YD1YWYF8lPLgqG)ySno?g;f|e89^)m7Wi+b5f9RI}`{kAN9 zi{jqK8QTZ`(C78Qw|2^)r>yp&&Z1->XH-H7`aVK^H6shZIJLO&-C@TmLA9nq9lUp8 zI_3x-1@}|ma^QEmmKN0)+HoqO1g%$KX1ie)Zu@LvgP~H#>K^#ng86= zJ~1wRIh9a?*7ML;sC1WA=3PXEV;vYB*U++|V-eVqQsxGWsMJk_IyPlgLJ6AdaDU0F zblk(XkZ>)Sk5htb(Xoi8>BT>=={?JegRn`FN+>~d9d54YuUKTzaAU;Jb_zkY=vV}9 zjc~oo2Ca)VJ_NSlR6+?_PGDouW_b7Nv3!pQCUBbS|Q`oaz3U(f;USf%|ux~SmGSA$-6$vHOblkID%K|s9WHDuWDV|6P z>^XJY>crYO;COIv`swUh#ki{>GWAP?QpUoTk4+H4xCv2Hu4+NE@B#_2cARKw%zX%LP z;2a|KnOSMis%&?+8bXHU@76Dkn}C(jsDu(SED1Ay6O{9mXhYI6jHh4}A_5Ufn6ql+ z2_-EF)Qx~=)-*gHfpO7zF)V-oZ$jEgNh`$fyuzC`WxO(sPle%BgqaR0!6%V~3`;`I ztI{1`{Z5A@&<6gl5D}PiDv?hjb3xihJ^W|QD=aB$Lx$z=(ne|mCDNX>k?N^TOVS%q zOU5h1=ws4`)e8}k1WHm8)P@!T%J5%=z$c;pDoaqtg!Vw!`Y!?rDnVKj(o235ppE}j zf@;wxw5po_PaBEY6EJq*z9|)<1G4*KufEkse(;#TPlOwL1@ggDV)Hb99wJ1^d?ltz8 zWknh`C?U0wKKP;Ue-JqPaW$@pncAsu^Rg*bXPIHF6FXaGq+#PY+_Jjw^+Ho?zy=RC zZsL41EMrQY4k^JWp~MiEl5Ft1IceCSgw#S>K4EGb@_A7U!!k`WrqqO#q$GSQGauCAQ}I-QuX8NC~Nh^vQ$i%$*9UpQ=yqqpV)FShEZc zeVF_^{NH6hEHE9HUPjng2EY?SCeu7SjLy4$_pEAXmVA`PZQsUo_Q7nJK*#8e9wb0&wKh@jPV_A>(G3K*>em{bB-?PgMzq~Po z9eTa_z&YEj~Cj)BZAOIqbY38{s& z^w88Pm$`^qm6~5QQco zxuP}Hl9H4};he5)N$0t$4Kp3`c_l4v6#vlpKb}fTQWDa(l5*2VNPb1hpt3bNV;&+Xf}17SdQ_V9BN?qy)7nA=89}{1?G* zS?d0di^hw;|2H8el)$k3UB-`pBLqrlT_WF9v>|_22`WLF5;ANO5oiEyl$_`}4QxDtbc_XJ_S{aMl%QH_IvxWNk|G_lwM0M0 zG!_5SQaEIE;Q4>JfsNwuRIP!i)i^SiO6XHfcWx&7j>*Iw_f!I+JP=KRa9m$Cu5h|~ z!YL{%Z{*W}PtMvvWb)3!7k{s9*4omZragqG3I*a|?syLxFC{vkYa}L&cj8Bx7uawD z8@+&dJ~TRp5>!ils*FJN0pk0K1+g?wJ~}rMCHFb<7qusH>I?9tKOh2t*jwyO9FUPnuVhcr+qF z>=^6J8^*K%8()A31Y%3vIHf$O7A@J|?;o&Q#PQ3%<~xB;MW0aqj_-;>XjDQ88MYF0 zcMRf6=YMpWS6~&@5@JWmsWlM$f#?TBKewEoGJh~Gs`V_Ywz#t< zGoN*`6A;aSnD1s7k4EI#O(il-Sei5@O8O=TYZJP@FUJvyC9+Pt?>_rn1(6bLLqDZzU8!JSrO=4Fk2FILKYYm#d$t2O@0dISh{8a$1;X*DZ5)-*T=*RBFTzj6>VsDe1mXsyBNB*@ zfp0yijqWGvi@EHCe%xW4VlSC^bn>+ajh7M|%QX`JmcOJws1yY@YQR&~0~_Z8W+^2| zwWu$^7ZHGfHcG50?i5G!#BOi{v47}kef6$dDazw1qyySo(SG(dvrd$`ONmjn>xo|r z59(gI>cdlI1{*zrh&$RRmX;vZn!74Mgb&)M$1G?L#67SP4#d)iRXwSs;97rCb4;8b zGOK-xr?LSX{ek$AwX|Y`5;701{gPi`V-OJ36J<{ZJzv(^@-09;Yo8teVofb2GG2U( zr5#wN8u& zVn#`WRd06BgGwlYwOvf~1>IUFJ_2G(34^^Z9Pf#B#OHk&gAbv~8^! z>H={Po~rt~9cF8QPlXanV9W6M@J$`t5;z3`EzXvr279}URi$xJEo_N;?K`hyO9cD$ z!A7A{2ClG0NCNYOrb+&8eX7MkR0blX*XtN6p#;{IeBDpoT8oYZ;tmj#|A|u4LA7X( zz#R}kyoB5>-Mn^Xnv2-tB;>xM%Qh;xJYs;@2t*M}TctcGfvw$;$M1A&>%0JnTGo`C z?fLJxh?Y!~*|wW*wLjswW!T{`b0jRsulRP!Fpe^+e~M%wU2wGB6YW zcBq;~xLj&!5>i4549l4ptBsm{ii(C0{8AB83vI}-m9Tr@Cl>Z8Y7$aH<3*xwyFTpP z`d#o;v#)eb%yFru=uK)szlBi=CDfKPHsMK?o8yLy0Y8>21l9WL86YN1 zzpuw+LL0AQrtZr!aOE(D@-&^L_sYJGkNL> zzCutf+V9dd#}MCYUw?*)2UX&9DxpMuH$U+c`fwgoun$)tGJem5SE0i0csfQ2szrNh zaL@KSd!GfzLdDI-c8p3W;XcPt)OdS9Pd^;n!K(MKCrq*p5!H89Q3$F1pV$C>#xu}oggfYbSH*6fGe+oVnkfX;QcF-TQ9i*YthWd_am%br zPR`57Dm9y_^r`6k2=@V$3#sZA*h@^veVs`5Ofi`3q>zMIF^06&faHXO7+ky$33w9Fgv~(sRC6u5~2;c3i z?%=huLTAya*-ta&l#uB_8$TO3F^8`+!N#hD9Pxc-^bob@J~Ig^q46Ri^U#_O`x4c~ z-pWEct0ayrX(9@lYB{@W~}enJg#t6W8skP@^Z2@K2i9jlEdms*Qz)f|<) z!g#%(7GQbf=bEJ{^9{ZxI8{q%bGfNFl_jSlp#+AXUMkC8v|j*E)!CaR`qyqG@_fjf zijZ2VpQ_PffAMB&5tES5OXJ0`{N0+4+O2AeLhsyC5mE~YnIl%BdrX)pkmHQms$uIT z*KTAOiO1VIG0RBYh4jz+fj*T^j1k|{H8M+3O7Phwfnm8$Wwo)n`v?&*YH=z;YM~7o zwh|@Eb`?eVCzFs88ZQ#d*S2Cc^Dl*`dhu?c&);*Kiz!pGnI$MCl)$hof2)nzcWVo$ zbR|;}QVVU!ut`L0_Y4$6$8R=Jf*y{eZ49@Yrz4q4F9sv$h5nKAszJ{+!C%n9VVipSEnMR79Fd@j`*K$`wmneE?QYu8dO5#-7>eX zXfZV%yE?xl*yvO!%xe&QRrl1X845wQ=;$8K8_a%}a5r$Is5D}ZLA9_q@S)y2eWF)6 zt`bKQe#Ciy4H8}n6Adb%M9$3tqE^ordTbAzXE?ZMN!5p&M~R2EhbsitqGM{<5&vtm zcZnyX#HwaP3@V{S*cN|L&;N=(_cqS&4ifVceBO=`ef!l{2&zR#-f$}yG^(_(L2UMC6v&z`U&58d-TI=adzr0kQgl7D5m;5Sw#QVAtwKPY+D;MIe0 zF>}Ckg`irp-(@92i%v+$`$rJp;WovfYZG+lAN}~EZ$^%u4?E(WJob3C4dZPlKC#f* zY+vXhZGidjSG!tpb!K}*qX?fj`NDYAgO3&}p#+xG(~?=awamAj&X!o#E|h!pcQGhI zwdl$QoIZP>r`rCQ5Ps%jF@s7dQP{~}JoU=LZ-1)|>DXGO%%1e+$MW3A{1k#}(X|lx z-bDGA`wrI{%QsZ=HK>FV_^vcq=fth=V9O>yy_WtM#gBg;q!3h#<}}>Ha{6x7yah+| zQC9{SR6+@x$pNA&tQFPYjcY~DC!6h_RxX$))|{XaR7)*EtljIr2E$Tg* zHllMzOWfdao@4j`#jhxV@6DD3XKsB5!%Dra+B9c4Z#8+VLQpO0W13c|&QGrfy+-l} z|I9IHo?ty6-oTz?n?c_K7)^waNhszuoIl&SQh7fpfvr!@fwtV*s$HJcHep!3;k;QZ zm7rSKKFT$3P5a&}Hs0w_Ab-}`+Hy(>B{0lR*>G%kt?fCq&Kz538W+{Vu#Cw{z-Sv; zb9^p$w;(OUNXY#Y3ZYR6C1hCcFM+wZyS4cb&DzVLJA`ByW9l&VK~hgmK#z>e9+{NTc#+s0btkFU*Aseu6;6!d zWz$=GeNsXR49k48+UOb+#_uKdEGZ$iWF98Ze!vV1moqFf-(|d*qe$c!e_Nf!;c^y7 zN+^M0xy#1-R4`M-^4q0u$ ztQwcIYLt*#XhVjrL_3&+tDZD-CnYpqBzmm;Cuw$YG0YC)6Tw`ZnTt|F2@K1i#jTecxJx{7LsZ7qKN(m(}EcY{6ZNO};E@x{gA+^wk z3~O5De{1g+0WiB=aX+JL^mIQ%>!`Y-7VLn?Ztj4nd3kz5#w7!JtFS|iO0a%BS1}{U zc`+Ij+!isrsdo`Qkk4wpS+PM0oTZBNapczdE4#Ik376nxX6)xR3PH8#o&fj~O$Vpl zZ#+lvhYO+^l~CffO@PP(`wnu}!FA4l3x`zQcq)i*wx6sJREzEjfZH$XjZLgKDx5#P z8Lrd41~~5%d)b-ed=lLg0{0GvE!3|R3g-*2U^&pB?AqD!y^zI9sQtYfS5Wo-AZ3}bmumwJp!C~@wLpO_81ENYv(EV@2kQ?8?aF`z&QFWayJqY_HsT-NC!S-EwNY}1BZ`k-uKyhr>iof1@w zmMruDo+j+M55)8g-;^?^MEUG~q8jXHs$P8<_?0EPrsrPwa6UQDI)$KGwEQ)#YvXPS zx2Ct`F59fD07JUN*9%V0F~`et7c0KCk!!!Pe#7U34d*o)^(=%^FVHz<7J-NzY4FQ|*~`NyNB6;D+Of45^+(5=cvXR^sn0 zU3d=ujnOBeTKIeNE~LiZrMw^e!2P)CKAD7+Py)k6>)CRgHH3SFhu28RxuZ7^|9UeO zA+>1TrD;pLjo24fqYwWp@j9at8n4aFx}sY>dtSXN?lt&(bsNvQPW}1H!DkhMYSEg{ zOu1J7R23fOUDeE8*%v_@Yid1bh3ZF}c_@F!uSeWXSeQxYTbGwrB$U8#q0{eJ)prZw zsTMlfB=#Jk^DSF0Kg(W!*Si(z>-OVfrt2;niSoS4`-KNTUhkdP;>;Fis>QM}5edh9@> z%u32>*&rcvLDPzckK&K^>TJ{jSMwyalu$w~!Q4PBir3)={?vplO|&6TqQUwH5TP!W zSi*gG(}tALcrlz@frK(=%A|RI8@t1)?Vq z_tPMx7RIzP{Vn#YCE7sZT(vNEVaW=eO3;QRFf7mAYFaiRs#OnTd($AK7RI!G*KM}z zE6!{?1F^VLKlWm=#;AnGi(z?w7`}20#J7t5*qt;8sf95m=PnX6_tt0WwwE<+NC}M> z!^vgdWy~l(CCHO~+)*+WA+=P$YBtM*&nuaUXY2UfBxF5^rS|B{eO5o+QnP-PwqchA z5N)3of*B;Wq>BvIC`;L0&}y;R3{}Gzh6h^H9@*fau7|@kM3Ynl@y<(|9qQ z>{o4p2nS+d8idqB8_8aR>4=!=!E5E7t9S{G7sJwzVI~TQNk9}ygOFNiL;AF)xt8?d ze(N>9)Agy6yR`K|8#1TizNLi@yy1o7{7!EtP9-S`r@oKb>|a>7w=DaBg^w)H*DlSe z5J*cc=fnUpZ1H1O-U;7Ym-~?{J-oGZ(|BuTUSV4+=LTSpFudo3iw)$iE#{dkKT?7= zB!OXBn%0_O2oU+wAfy)BkaHYx3l!K`wzMt(^5~^$LrQ487*5VBUr0w75XBy+CZrbH zNUq^#&4^^KgR1j?o)$OjK`Ei}s(ICG!(uk3Tovw7(mGQl393bFS6DxfjAHNngCU>Q z`73-9Id_8g&||E#QH1zCe}!`|R7-}fb22S$J^4HvPtyjK$S}q$J<)1|5SrA&xTuy4 zTWuVIG~}ERW$sm@5*fyLvGz$m`$`B+YGGVdONOmBJSqqCtYe~B)S+|cE(;l#q-8pq z{JO#P>bOIw{Q?iZWWEP~P^6`L9wP<-@ zSk5`Y&dg_#Yy=Pm(jcT3#*}Ph1rSGK2l6IMXE7?F@nTrcQo-Gy@KmdSSeXVPwJ@f~ z{co}ZV|GG11^`j6WP5ISJT+}d35^%Sa+V5if(D{E5GT_hq!!wUEO4C-oQb=_)&nui zlk+RjUCkVo5*jat<-C@rJq98Kh`VVJQVVUgu(`sVBJec%eIOQtc05p2LgU4-oY#VM zK<@qoVpST1)WVo9=>M>`{NJS*1SKU z`+_%835^%S$+K$FKvV;Qr$I<9j0wZeEzm{_c%#<98?`TuH%fXqzK_Z8U?U*%|51)_ z+S%M})uaUDl>~;Rhgxmq1R^dCLTaInO)y(~y&-yg6R=U=zA*ooeY0spN@%T*nT zRu{^h#znR8_dE|zu#*P9Q6GSK9WYZ*54Na;5*SYQ-S0r`2Lk`5B%~Jpj^V=B(MAnu zaqh!t;_>0sEspeKY@_7O0&p@6h$2VASnD}UbSlAkC4ph-p_+!R+F~Gbq(Mk6j7i>D zU?qB<>d)4u`)1mZ5*jatrH8^-z`;gGApS^$kXmR%-dF(h?Lb7HZp3mtax=%AQbOa! zaI)`K0V3i*2&siOl5avl8yz7220&2>jTghozUv1>zK3q?-l^1t)WVqLy%w-b4~PN3 zzUntm_BU-v35^%S(nDe12Z(v;zv%+g9)$1vXeqiNV9 z!+t3C<4}V8=H-n*QcJawL})1qs)b>U$@)gUOX`Q>Un-%5`qm~9T1tXyVHj;#+bG!& z#iyeZN~rB%5@F^5C8!pLo-LVW98QCfT4=-OT3AxwCp!>5Jf9j_lX^>1LgU4-JnI1SiBF*q=ke5N znFb-X(8d;@prk%rQRu_1f9@*2CH4BGgvN_udDg+&7lnSP!2T$Wi)xv_Zy%i07kvcj znC!{Lg{0o=mLv%!Ff30;z*!j}B7u061|hZ3M#Ip)Nqy=WK$I@oUhGTig-Z#I7sK*& z1nlbr!X1beX%JEiZA`e=BWY}~28cgm2MX_`(S(%Hcrh$bN5Bde5F3FAOoNbGXk(32 zx1@2@A|Tqk2Z>!tqarDx@nSgnq{U<)IskDo4MJ+6jY)aBCXIw&!<)1T-YAEp9ss@{ zSj(W6^kaO}lHbAiK&0E*+=xo*Wk?AnFf2V3P7_1iM|U+h`X=>cC?U1b#**R@NqwJl zK!j%BY+Oz1ElCND7sJv+;d@2+{6Mrw>XA`GYN3t&%|<2l;gI-M+bJQn(8kZUeUioo-au6Pqnrpy z8cj$EjTghxLp7}$5FS8GPlJ$JXd^DZXVN@_4-mWOdx%-}tn&;~LgU47vhQ{P0%j&e zY|=Q25>g9oI9~3N|p47{b5{y?8 z7?%E~X%&Dt3&ff<2&siO856<)Amo9>%sMpBQA5>g9o z$UDT~{!t*}AG#U)lX`tpLgU4-^iXTcuL5x@sb@(Esf9M=&2QHJ?&{Nxj5pA`q!Jo0 zhNZt*dwq#O_$Kv`Wn5GXW0JR-S@UYX zyS)F*N>n@&W)x2vO-Koi7sJxuz}vw_6CehpK}apMk$kUORUp!hi82N!&BI9vjTgho zzFQH9Qb062VjV|OLTaH6dGjB9&npT>UH-uW*LrC?A;UN$DBmdS?BIV9R7-|&-Vf$| ztn;F#4Jwggj8~?^YU95MswKl#8~dRTT6RK|c|QY{$S}q$Q*O2KUj)^XVXKWFgGcc@ z1$~U-ys)_vH^H*akzl_6te-JzbCp!ND|1xM zD_photJKdhlGg5IUSWAi0>kniQ0w~OL?CiUTh|9EA+^wkU5hSBD~j2{M#<`7M#iPq zRZA(M@nTrsh6??5AkqPGG-=h65>g9o^Hy)q(8Pn+8)Prmb$FY~6J;)_W!@Cl)fzo3DE7koAeGQEQ1faC z5I#Tzr9sGCz?cH>bVyo*>;l9HR!*#h^+773@nTq}5BBK;F$RdlGzh7MG5xaZlC-vs zD~jW0dI%R-AEXi*FNTxzDrrR#ZXQZaNG*&B`w!OKJ<%_cx&5dr&Q30=yiulB(z`<6 zO*khEt7J2mwiQp4*45-&O9>1o=hb0YiJJ~Ym85kwN=PlVAg9o$a8GgRm%)6LBcy})ly1myckZ-tA>#BANhmCnS$2c36zjp zXhWWlgE#7KI6pt=R-#wM0p@xXy*paoF#WlLzc_y&Cp$a&n*_++`exQ`lHr z+GeR`?(3m7CziRaQK1%n)tGKYTu}6?ptaP=L_Sf zRAd!3JfoO5S7$z;)&HaHz2mCNoq+G7f*>HGV#nS9#R}NCi3P#lbuDYdjx&8y9&{D)6N0#oW=0U5#P`ZU`@B?tzC-_4RwsX?km>jv5``1`clWzqix4jq9W0QIUlJZ-AA&K(D)MJ1BPcj}uxNZk6>g?*iZ@8S74hR3v-#0o96 zt3?T_rA9nC>>I;R6rOJExKl}Hg!vxRoQCsb18VDGjx#KMdjtuGnz`7^cN2~Ir+g3k zrNIfFf=zk#WM{Gb&95x>IS}<+*!{ATj9KxNvaYO=!z3O(Gf3o2aAOO$U=KHURv-Rq z>k<9&w)Tul@H>|TwXJE}E)?Na?o}6~W~8utqk_fE0XbRF!%4>MzRpP}*2^-9Q`_LD ze=wL8tJGaYyFD;`Kjisy?49MAbN2(m;&wwP_Oc;9Rk6p3Y)_t!qF>w_#x@6wSyc>Dj7lg$$1d>YTphr(_HYrY9gisl)k^XX7V9QgVjHU9IM{hZB_6)K zxES8}fYNqpiK=xz=2|7bY(Z%;>dRK81}Q;HMAIIB%FjFPttJw7pH>K}McW(19B?SW z|F@>H*mgZtX^E7eB?6uU?{e|td#Z|U;GawLqFP5qusA%U7|Xc^OSi#4xp4w8PN!rZ@;I(nC`n*i#%j>Czxp>}zjkdd>eX_~Ku9h6w3;@4R1@YtyNzfc z=cv2~%@@<@F(76hZpYfDwiR|`>@yHji~F49s`qit)Pj3X9I~G=-pAbpEJmt>8N^QYyPBu;hv|PoxC>=HYJgk*6#Nd~1j! z&&^07a%}fq1T8}t2migt+V3kPc4sTD5L64t54lPK5r+m9;}yrdi5173jnPs{ zD4~{a$9ImrcT!O?Kfv_BhJye5*;4+-1nxAVp}2k~ zD|^3j0^B?oBobmBS-WF6lW`u`ojq&ZTU2^`Oo>f}r|4unsw>gKBBFd&HZw1tWAQj2 z$xbcqC9*X5i%|(B0xkxLdDH&2oOy%Mtn`mXc%%N+#q*a|g`iqbrv?fCgLdrr2Yjm7 zog;Xa3v*L~K2$PRQssPyK0BQ`!LNy{iM&~{IRPv7Wo1-C30ey9JIW`KA1I!S6@M0N zp#;^EGc|KYcJ;(Ce!q!_{ik~=fcAG*_E!uj()9G>%J~7cxly0?MX(g0UXJmyU z?l7-<&4tIQlL|q#=zI>MC+!YqPLo4KU@Y7KPv)H1m&m!O`c%u)2C>!N-9>@DR}~wS zpz)+&T~zPNY7`9-HC~)o2&zTn#%bEJxrsb$xHD^T-Xmake0?$E-=mfzKS%K@%^;m{ z$cR))<3mE7H;&>v3T)JCXH5;5d%wQuzeQMfMn>_1yXuQW)lv+C(wg@6nK$p(fr)bi z3R?a>(?F~&w9AqhAI0Y{YakBH+GY@x*0iBT;+S`xc=1-0u;4jS87-6&G&UKWqH~XD z9V^5OR;8qcN+>~XLoAEwv8-9sIN|tuuR>5Q8k-DypQdYB;IjxZw5i6Zgc3h@4-_YQ z9ki4ih7ru(M^Lq;W(ps~rozoc6t`|>VY zL_usrDxt)cQ-R{T<)kIm7h|4%{XK?Fsva%+KkKFtR0~hFrbn$CkZUk|H9tyZ?>d}O z2_+VGX(%3sU$!(Yhq3e`%f+!1eWHZ@+F=SowP=hz@ZW7Vh`CzBM6a~jO7uNS+;9jI ziKQM`Qr$2n;Ed(5EF?Be?4POXn! zS|57-z4Cofg2rWq8*jrBdA5Z)Sxpa^{ICuAJURHP9U<;K{LXF;<_i6%v z;pWZ?jfqwWs&yh;pcwSzp~dMv#w2evGJ$`cT7XSBJ>5bjl%UaKHLYVp0{>rNLDt7b zC8$=Lje+8B#5+rl%Xr3pa1J<6z1M@CxxC&&C6rJ{PJ6oq{$NH?_Wtj63PH8#xC^lj z+eGoeM;r7hEH!}kWVB__o)7M$zZS`RZeFMF{bh}XN+>~V79yB^iR8}N*6DfPtX2rB zHGW6~(c|4QOZ$G3PH6l4+<0qp5L%kD1be~ z*sI~Zf2~FO;?vC-l~97#EW|a)6T#c^h5CckrV2r|?i6b%7R-8TnVN>JWZ&5^9$-IP zj|h)uR6+^0&aV^>=Pi%V(u?OCq!3g~o%?*qRe>+A!Ni9(1ub;+qV-Ql1_-Sl>dj{@ z3lOE;UMb@sC1}mU@AG@!oYf8x6WhL22&zTH4DF3E_(6jmHow$*$)+ve2|cB8F9K)=#`Xv5ip){l!9U!zt{zI5w|LKT$EucIBxkL8I)# zJtps>nRnGtG3uv36@qH1;~;Mq$GpPg1+KT#`ISs#EG#*5GNYvZh@e_BZAS43cB#NC z#52PNmB=*aE594l#*YZ9CDW#jyxpVtZ{;@{EA&(%)0nU9!A%=KBB+*3n>H3MNaV{R zoN@JBqY|0MeC1riwDBW?YRR-|!}m-a8&NV=?A&Ir(};T*yG_OcyqFLucC9>YX}cU_ z0{*)@md#Fy7G<2<=`?a6ja0aPctde}-xW*rMT~~{Y-Ajp)+t^jxvWp2^-N>wwc6YO zW^CInB{yOOGl=iZtX<W6Q zR)Mn!CeAcnt`Jm<)~2S3E>V11o{hT8<EVw6UjS6u(z$qdp*b zph8eBTAQ%8G#`GS4|8VokFMH7C6u6d1i(525MIzqe)m|d5L8Rnx!FoOe<@G>{u+0tx@RvOKp5^{EC?!<+3j%F_J zBSop3um?g~HEr#*6yQ#z;6GVvmjPnt;t@KPP=ZDdh4;8Ogt@y$i064GD+JZTK3GOT zh0-k#za}=gvHTS+%6rh;3TTPIFRzM;JWCNbcB`L7DJx3MFVjHe3%h7pe-*#;4Kb1Y z)bW-2wD(z+`k-30EdbFXl1D6ErEklfO{sHAJeb-*ysvZ8GIKlHunh3#cl*>54()3y z1l6LY4m&?Ly!e6pwZ!9~no508LhY|a@inYY%`g!*D^MY*7VXENFR2&9uKqqm6kJ$U z>ES3r`$w2%td3>Bwu}?23JWE^DD6?pU27nUe%xiLu^3~R&Rw~JUCtdP%5Hyer4mX| zd+^&J$(z^I14QSTM+!l;PQ0uycET+<4OgL!r0d@NYu^B|d+8%9l~96~8}vSpBYD!X zb^5O8{}Z*`N+pz_^$%xXqZ4_8M^3i7{EHMy zP%V0Aho-%cNaW6Aa^D;;HM>{mK6z-(zj94me= zPDH&*vMLf1d6w3brg`7@=3}xlakbbWg`iq=WYDxLS_NMAu|>2PHpogPl%VybX^A|F zv#}fWqVp>#1l6J=gQoQjisJjbZP5QdRKZFml%S;!o*dH>`ITGF?AoWe6iQGnI+keK zmnn(-AI*gos1ct+C6u7`1mn5&XVy1cxcKm5q24SBZe$vlm2H|`j?);=xV9)GPlNA= z`*8lp;yU{KF%zuPBSHFNNFN4VPadB&7wglzB(%hB2_tyDQZG{SJ?>+r66&e2w{Vcq zUpTV6cIe5GFtZO|RN}n8{&q2)5>yMXmxV`0oNCH2AWdkF`{^$ideM4M_-F+|z^Lj6zT?^{HyZs&j?Bb;a?t(K?k-0#~4YZaA}!#qrH~ z?xwuh!`vdQH-N@m^Cl9GEKE0Ws5LAoKA7Cakvj~5`l8fY-zvxs#30fj>+fAYG<99mkt@j?haNd1VmtZ7HF?$3F17?|6KuKE28&g`iq$Sq)v- zinrYBERJ^!)~SRNwA^6lr%+RVyJB9^{%bR(zxw{GO|SEzSA4nmjdJ2arHKY1C6rLh zs@zwIw-n?h7WYe52&zSE7FIvfRP;660~lhK8^&lHATaPN9pBCFN$?8 z>!0?I5C?L|7}hSKuXyOQMW+%AEeIrit69z4{Jn=SF?1sA?Cv@v&WJXxpr zAJco0Rbq0-GR!|;1aH`Ql}>MH#y6KSsWF`%(K@_rZGPU%n>XEES+PO$rFSyJF4?Yu zd~eAVHsqbXPH%+9mRSFfY#jR!ddsz@eRvwn|G7GrZ8@CBN+p!QFREckR&Mqse~g9I zkDKhP! zeCYU^I+aj@wgo(-Kb(JD7r>Hiy(s$D;vA0FAoh>Z&$4lI4p#?y(I=fESfj$Pj5(Z? zP=eZnGgx!`@LH)CSn_joRFeeN!nC))9XIE2&d?|3_Q}f|+WJH(p#&{Ah(ZhVE1&9h z`9~LXeih~7z;X79<9Yes**VViRAS?SV2DQ+!7FrJWV9055^3am+Q#75#EYNV)W+d_ zN38`$?<3nQC2)=+ZGW35a-1j9yr>qo1=)IF2MgL&)BJV$O8N9@l_wHvcg68S*e5)YMqaG5yFqRyTKxE zmDVXiwP;DhuhiLnc>gQsS4#25ZLDj>4sU&b6xN+?0!5BBcPM{w7ar7UiM zmoZP21l7Vh>ao&}++0-~*C2%Fx_XgqT-nx`i%JP4)UxW)-iueQ;mi9)j8O=xg|qOX zZyY(U`@#Ns|04X|X2x%>n`q3brGyf+#b{b!(qJ~BQaC@_-ki5ff@8?HcrM4qPd^+}?$otIk2OG0bhl5bpnT zC7s?9LT@F(m5?u&UAeik-5gd@-w$)vpXFV>2Ukq-UTs`4#oxH{rfK|z?0wCZo9nwN zKqN&t>y^%~QV6PrtGHv*T#cMyMHtqQf622E_IC%SPzfb)ZJ@lp8#mXfcf%U8Q|XN? z+s#mgpjx;Zy{EjJ&Bk`MzLJ3^sn10!fo9penVJ-Z>aK`UsQwget ztLg!tq>aB|O@CCUcwR1cy|H>OC6rKZ57FMin*PbI@%(33m7rR~F42*+Q6ZtI7MGv?ZXRNA8f@ET~rcOOKn$KZg}&C{R8-d#^&0qY*&;}`;s+X<5^gAEZ1(lvr-A|eN-FQ z^ZdznrbP1Q>$2%oLJ9RoosUOi+14I$yvNm@O50Vmlv{faz%D@jqHg+yc@`_J1KbNK zS2YL6n~iC?LF{PHL_T$`o8I$7fK`zY0(Tld_jKasKF)*Yk=$?bD#mJM(yr+9j zok}R7jvvKFtzveg!?^F%K!u=MbX)Ac7Yi zJ5d=2=?JHe&SfqvWw!TGFFasC-GVFb zdiw(j%KVCI;YygCsljd^><`u~@2=N7kf_YzC_!63ta6&(2`~#X?~0dWksOzB&s>g! z=KeV$41WemP%W7@cV8F4=zJrN88)ayrZHbRo|`rZp-C;wi)zWVX(K0iC#)^M(KvTU zB{Gfq%Grl$gAkh3!n~-KOq(|5fp@|OnEOcY1Ubi%T9~h#MVU5!L{Kf6Hf==Ah-c69 z#qzuh?HRrEgWec|zDDy(=HjN`>-f@x8Cw;_kNrN(@b~Emy*~P$qVK4@gN5GB0zSg| z;@N}>@jU#H>G6v-h|f#!6+v&Ro4>ko^c{wF1wO)$YRB`C3MCC6VM$OeSx@Ghe*urJ z%QYBx?@`b~C6qv4tUq_;;^@%~UP#Zq`G@w5&)udHR7=*AX`?jw4*vdV19N$DIea*Tr_`v;_o#P1(`EBE=1oXKK zOLgGxE70ezRDSsFv2hlgy#(Sy!TFD7xg7bo^B*=E{qJgOIk@S|*`>25FZs42Z?j^x z;TyH@sw2l!8J zwA$Klg0Hi)HH^pFe4XX3MwCFWx1ScfaMPdq-`sI5u~QUZl`!1!j+O+~LSH=jrD*3|m&8J@tOwkoJU?KIu+l$A9_3H0SHJthZleiA)?Lq;X=zkVs8 zzf4vMs)c@?hc`NL(?_`Tl>~mUpu0Z%L$u)|EG3jcpX98!o%orjcw65F@LX;&Ca*r) zZLmU6E%Z-oyw@c5MyN~mQux@jcO@3o3~!8$U{i)x{NYX6q5-1K$+ zBfdQEb;*a<7_IgUv_$E*0zF(MFTT*D8h?~`it^P`LM^Ks!##QNQ`LC8CzBO|YSFI? z<|XI6xO;hj9^n&ic$mtslM?j(V12g#j-wYqWOZo?G=J*(b)h*Ho6+i?hJ)Ebf-5M=W*oyb9BZ*M{4j}DmRNA zT^7yHeEe#7N6WbZCDb=xKG2(YS`onO{%-nHOM+_Aky_K9-1X+qYXorbOD_#SeK|Lv z1TATpGhC14|7}^va@RJ`0!V^t(UDryCc;^OcG^1Dx$YVZl~96yE1FgYPNjr<=G5(n znP*JoY=Uahu^l|m1}5_3i*oAw`@IjK5=zkCPSbJ~@5;7p3gLGaoKUcWSYkL>A=5`O>e%=*EC6vIOA9<@8_;}?R4!>9`F^BMd7P&T!5ie-84O~yo zb1NIi_!AIqfsNn;2lWk@J7BI6nL*b=lv;7+8dJ1kp`=G^n`Nu{hPf%^uBKH71NYXNt@&Mm^TAM)cD9JVV2 z)l#3TDeN>nn(D`Eeci^Wgc7*kes+N!$5ckZn7Am0xZTYaPpDPFN@S!08>r_Ew zcT(QeL+|;aH_pKslLGhIry(VHNQ=_E%A#N~>FyKuw%Q!yWVyWC2V0EH3C?X7e`skm zJb-sS?aiCO+_}NhH>}H(Sw{Q;c{ku;??&RZ*FUUYAl@Z(u<1j~spZwUOKv|-CHSpK z0@LZY2^L;>%Hlh)IS&BO(CdO{|>>TlGhtH{>&_R^Znc5tjyj*T)TRYQ3)mJ z&3SOX)+dOcE%=G`e11Y9s8&GUVDWD0N9NRU2G~d`7{nd_%E1eNhS?I4P=emIr)krt zb>ml8pJX1v(-nehl{g`dMmMkSP>ckO}iV2fV-LG&S( zt$(sYP_6t&p!aE>h42431#GO$*Ns&S?Z9Vt*NnC#@8QHcm-ln_SQ#wF+{waQmdB?m z>fVjj?cJWY$(@x`2_-Ns?*@hQYSA5-!}JdP>=P{mA+?5V0^i80S@@6?v~jmx2ln(* zOI~lRGyI-Pm(YAMoqmI4&+fkLPscXgfn_A5R_K*rF}>#}7TphPFn^LS^E%&%FZ3(O zsf6Z>X?bHMc()Y`WtWo!dF#f7G7wUWew%PU%H5sWIR)}6150H1Y9)a-tT6Ba1U$s0Q{K9`#_=U-bjfg;U zgrseZ+J?TpkO%(|Qjrg~zo^)t1Z_Rw>)gKpcmJ;{U+?+1LQpOGrNKF`p9=8vuxqmO z#Utg5q6BR{u&TBq3;(NhExvxhONF3Xw8zl20-Lh%N0%$|GWBzCDxrkhuEND77TLEZ zADlC%LQpN*^TAhp@)GO1+?%)TQ%(tC_FZ&7 zr)hc1cW0gZcjlW`zh+cI3EE;HMq|4>%-OFoU)K7%LQpL_pMwbe`-<>xHLCJ_TMsiT zp@iDnVVNEJAT1f!kZ~3cH=c?K{*w(4p}JZ&firUaJH(gOLwDmXmERM=x3B0JM-;W- zCQQAg?*bzYkz9?xXC&bEOCv8N;Fe1LRrk4>+d$NKDrxAi)2$8_d|)S^UCNLFF`^<`#55>gA_13YN;%n2z$ElPkVpeR|jSSC+J38{rNcrojl z6ZFj?lBZ5vW#(^A-)Mauo4bSWXV@To%o^wmd>!_oQsvVwT}y1ebCZ{Ne;(()_F zNXWb}-y;hG_1!OL8LeH~&PYhf_r!0`9e&W-DIv9x#=m3h$=rr)SCoLr)5iDs|4&FQ zv?1H^HzFBRD1rN~^q_(pjkm?}!8qjj_X7c^^wH<=ma*^q68Sx&7TjO_t*kQGKr}i3uA9tO@_+SIlz4V6@&|8DpGs<>z4vd280Gfusgf~; z5?Z>lM2)igzU?Al5VEFFixO4Zq#Eypdf%0fny)im-oKbx7EY=iQhk!lt>$r$nYM?h@zG( zMN9|gtfD`cUk&qJ9qJ%6FB;>zjW8H@mGL65GeoROSeG*K| zzsvmb|73v@+Ly>L6>Z4Bs|1xGO$nJch-5T?Ht-Bab(Y8Im++)b*A4DQ8go(z14DvJ zD1rShogv$R?+B_zpH^z)|E3N3hLpgxoRMcFfGqXVns)c9!nv|6`vaNRzq4_)U7QRD$?L30T z_KQ2LFKR?{?*TC1?YPyND|8@l(V&g+nfJols|LnN)qn^G0-sB^aO}ge+#vd*6}^IF z+Vlzw2BIzy?cO_YmlD*XG_|K`u0ZqxVt1p#Td9N+m#?=M&rfT5-LJTJcXgeE7!Aa0 zpA~+TpjzsCyaQtJckdxbOKivZPG$aUC%Solu@?T~2{t_7sk#8syQcS6DxpvHyIX6~ zW5Hvq^Ny-O6a}I)5ba7m+*%?_V-eVDpS5{FQ$9XdQ_*_%aqH~Q^_5b9_`C2_aX@@n z6YWd$r9`(g&BgGaQ>}*?#(Mb*1lGseP07_MLABJUY6MTkfq3rlcpEK~f8AP&s6{ue zPwS84v@JjkIt!*ww>UhgTzjcy24JBau1$WV^x^cV|?Pa7*24 z_0RqDccuFph!}XPZKduirAvtiLxM%g>AS4WwzLHsPViKHfoSBgeG4sJszqxSzY6?k zu9MlKCt2~S=o8Ann;vw8kTJG0d_|Hri5VNid2o5%@a4qazS%7tbo8^6X(JX6czj1a zd}Bo)aZUSuQ#c=3O4mbvYUGc*`n`9bwW7x#?&Lo@c-@NLP3YHWX?)tS4Y9nz#xYM_ zKQd#-HY%Y6`bkae|G;YcU)={{Q(0ZVI&q61C8!p9Z~fl#mDThL+XBR@a=L!=pYFcs z*(;wHece;?-?C~hjlaE<8Qpj}5HEpPY@J$7zAZ{9f#)W+&N*joe6a((c?u9CfDoJQ z{3t=SY*8_+laFH*sFpx1fH!w{D6pMMDcl#tLZfv281g-RS(Z4+o*&RYU%ET);>3XClN4agI|z+D>0;`vk3M5g?DJ# zR#eEFL*&Z)tI;aKA6A%8)d5<24ImO16gGNlDWL?j|49tpmt8zRj{Xd9!Nw3E@-3O{ zi)~aAR13cw`6~==yD`5(fvsLju;0CRtG%ci?;t*xE^mCb>4fbY6m94JX?%lHLW$Ug zt;P0|PNHS+D)3ZU;XMYzQ^n=}d$Y8G{W;Z&Xxu_v^>-2NAJqin1rV3=brRV&`fTre zwUJmnFPHf6^KhknKEu2u+i*9rar_V<0)Pkx8_Rm_*+wO_6h4dy5{KM#i-^TxK%9d& zp8!PGaSeT`jgVtaM1#Jr;;7?D#U7k21{+O)c$H)3HkvObR{As-H6FQ$dsQ)JW;r0* z193Z7h(b^;+7{p>D-dmf7}ovXR$3<6BbtgYUvr8jo9lg7ANS!s5`lPU@8m~ImlE;y z8w@^8m)8%{MEgzapXz&;9ljL0kY!t4{R zK*X2RS-aLAMh_714e@{WptKU$=ToLPb;uT#-2LcZ6|^KxwLKe3=C|% zhNr6Su-h07@TpKj2^<;X-#H7@Q#KB4Tq>ormua>AXhb*oPv-9 zmI-}Z`FHcFrUB6kh^l*rY^4%PU|$)Y>LAQsv=(UY zsb8IzqU}7EkYkiAb(kOnaTtg}J?i?>C!qw6cIB()5a#HN@6p_RbBz*IOa9%AbBFC} z@1CR9=z~edFJbxn6~8W-#$Oq)dLP#ly5q0ymZ?2bX73Hwx48~C2q~cirs=8yM2THI zLwEi-Bm*I}(1uK#Z9SpOD}B(Ro(3T$G+!h_7M<5GhvLe1p$k1yy7;?_A{W~kgp^PM z({f$Iv{AQTDbeg+!wiJfLK`w|64~!H6tnu3G6*T5`64lP!&Uvvip}s;Q!e*N$$PP# z=;!Zh5K=-3Ov@D=)5g3*J;n9TuZ$gDN=PlVA=4&N@Z%71ebEeqkP@0N5_w16)T?*g z2v61PQje64uEWJAh~G{nl)yAyBh$2j2b08c>ru=1gw(>n%e3)S$+Cx|5}L34yIdnf z%3QIf5=zLlNrXJ=xO-~ZLE_rAHHIhP-&Jym?9V1B^Ae0mI}qk8aWG%ew3+jBZ2Kk4 zAaP*DT1F*wUZRd_KNTPDw_@aAu{UjjLQpL{*)b--S!{7a8)H}ey1U@i7!kT|3ZoKA z&`}g3t4_;V`^5Sf@zdSO3PH8-G)L7}F5-C!9G%&pd3MkB8Y&|44K&VXNC_qA*sf`R zm$|+BTG63m`xTX-TIe0UslBWCxyneef&X6oGeXSRe9X8(QjT77T*97HotNauG1B7Q za)db1wy=dtD1oP|wq0@)E-_JHW7U+aDY*hhh~r^16oP8eIgzH7J~h0?`?MtSkMA}M zl~4k2N_aQSP54g0`BmY67wj1IB2oNwGz+5y)uOW~@UmFu5HRaVqFCD^JEIaxpdb3F z$Xp`pU_8xH@xj$S6YLX2&dt>of@;x{2I9*{zv^PRNWEQ)Q3)mRZiTuqpF0KfIq)5H z?(es6>M$Wrv{neJrPiQ#wGy@a4+#_1YaCR*54?|~b6*FsFyHUWw*oD(cHNY-?FNV* zlfVO;%m?>DHAn3Ml5qY_Hs zcP?k=5V6;%(jMoezQXg^4Mw%FmjKUhQML7?@8)n-@8{jseqt{%ZrT$@^P&W%^Ubpp zjvvtvx$1k*+82v;72CBeN?ue8b4uU;xH2_xPxs2*gk9@2!-kYl0@J>2vWT^p&D{(* zb1-4zKX zFunEV2mNX1nebHZby!M+`pre*cLg&LQY+(AHHW)nU;SFrAmsDXd@(KmZoWtT_H{+^ zH=Y>?sfC0r5tHb%B}sJ5bIKUi=su22Be8AFE!`Tk0Nx|;U08tcv0>swmgdIDDJA&q zlEAdwr!sA<2^k`S<7a0eq!!wcX_IiP*h9c<(IBLR=8Hs^U+?L43!`t;+1FtKC#JO# zQzzs$YEVijfoWO)rj7Zx>x(a1xeSEVLK`w|5Xl?-28pOqYjl+0*NMNjF%8kP#Fu=< zjZ&9?2XEY_TX((RKS+dhU#X*YDWL?W^M%<9?RE)xkA68k_gs4%E#l@Z$v{Xg`db}V z4cxqT@2fdjw6iYKsf6Z>@nn*lI*8O67?<;(97(nNe~uAPPfSz@szra@!+8Gdn?1J& z#fa)drs`A+&mLS1%pu0r_EFXYAYS;XFWahqj1{ByjMHgel)xCz6JecUYcE`9*#E~| z|NCp=#r^t&6@qHf-_&p;!q+u*%07x0i(5zPR6+@iInZpmi3b}%hlx%D znkWR-qQAVscd-5Y?Sl&s7q{C4>r_GsjG%l4e%;^OR1a)?UevNi{v8RT_vq3JLAB^_ zbxk|)zqCDXW+jNDeah)nLJ5q7@uXZX@y{BJ9o>3N-heDclf=;x@2!-eTJ)E`rga~^ zY{!z^NurzkCo9#$n9H4ErJx?H6sW}Cn-BQsw;LgT>$Am5C6vIJ!VsB899)X4gPt#! zr|hjgLTs-;MdaRDo=}&QErU9FlJ53vbn{pOFV!u>SpGb6c*iY>#Y|9Pp}85?^}nUn`YR0_zFxA+VZt ze)?SQluFqX`HKNXbV^Vyy0ZcIV2%Cae_%@j|K&nyok}QyQ9RnuIc~lAsXn~Nwz`2k zvQ`?--H$X>2&zT*LLjzb!1LYv>J8_&s|M;+LJ9m<8V6mrn%`i{I%%~Ret|o;KZGj; z)uJU0=beMD`WGrTly|*6P^S_~U<{BK3m;pXY{$K#uGVhbC;PD{wk!iZK0c#odhf)G>jo_=SOH!zW64)vi1aGxsJBIpL^D!W( z(g;41{b8j9)uOFO(|kJSuyMvN4e*%X?44A-Sv6@ARcHNIi-XWnC|$CvyS7gIi4@~ z8^qVb=uGpXT9}qOnFRdWMm8BG(pLp(nU;T-elkdzzGPHF37JkOrrfU2U9y<74C)~y z)0orzrR{AqnWt~U0{))XhEK4~WTXW1l?0}#pA4K+tk{E>w9S?%A+^wkOq*{GGcqn` zWKu%&MdHEwuC`g<`L|&KRgVqhpKY@~DWL?WWx1I)LbfFFqIu1kB_*VmEW`BG4_IO0 za)kx8q`!|$BT->%cXbtq%T*jHkxwFN>6c?Z6|59-xl%+4sf9LV+9amH8k~I>b2Umz z(1uJS(Wp~D+lp6JSn4Vg9xSmk7Ll~YP+ zzDU$~KiamE+6PurC&3!rcH2s-lu!cG(j&>Vv3AcFZAh;`v#e5GyYqMKlVL+jD1mADcN?*!3vV(uo6$<7gleIUot^XRY6rYRI55gEQ9!_4r`S9paiZOj{W_v)m%^f zef8))f3J_`=OE4&&5LSL{|PvM?zw1NLH{BA#f&+ON+|KtE?D?3zG-!DfRS`M#Le1)4J?cLLd$dWjEUCpu@Bx<# zTd0H*a{gfM%3zI50}qW6_tykaf@;b6ib+J?&6o0bgIIp?&~HXu9QlU0dRpS)1uL$e zs_&si?5y)F&rtqwR2ZWYO5my*+)QdU*F{5iIi&p8WEd}%+Cd?xmg-;9C(v$tO19zr ze}x+}Dxm~MsVH;pu(iJ7ky3!~^{=%ifp7Y=j6zT?>e~W0ldgY~Qm-h?cbipaR6+?{ zTdehZpVeHmEVw+MB`i1W`s{jPp#;^UHLGb8eqFZXE)WZ|eNyV25*P{NG5CJftQn2% z>g_=P-QFX(U4i8aLA7Z8!#Z{H>>X);bmr|W_Qp3TzqRkb!C93G>2r_cH)y|q%AQbb z8-BQhx%wd`l)$v~FoxgG*4il>CbZ*^)|k68l#p8Zoi`g)ULP=c2H3!VKb@$~%o@(~K>!IJ-H3e+Us+`1YFFIo>v~iemLRv~_ zzL=J0*B~CiJ-E4dkqg_saYhD0Y9S%d%E4_ON%4H@FO8W~i=4`v)4D-ImIB;9G$NkY z+ht+9_jwq%%S#C*XsN>*G7#&5c$WzwYZGnA({8W=3Bg9o$g^v(o3ZeuW!U|Cyp?xZj^}ps7jCIX6rP)*myo|pG|m5JcRtA3 z%KADkG1`^Pm$oZRUrX(z7qsH3l%{t_v(JTNxqtB^#yYk91%YR6#}(*doH4+3TK4Yx zn=o9b&R-RxCl4LNDs{UUfO$Dx>Sbu*v(pn*^8Bc#J>V{p|0?9yz_h>Ig7G+#{1 zlYy|?2Sj!tPG>?$Ewqtdx=4)K*@U@nsA$-b5}Gfj)9bv;uy}ql){hn3R4xM{wbXXi zYO*i?t(+4t`}02rA^Sn21`l@7n`D`1^pDaucv%3^@kud0qu~a{1|={Zb*qcM&uc!E zRRj>#ftZ&GA+^-f?G8jV^WmE-bTn+p(xv%gI=x-}1jKM4R%Sv-E!q~$_eh@P%j@Nz zrnC~8FQ#QXhC98%#xFpW%!H6yXhXJXh|p9vfDc-s@iQKemC~i7k72`B(hy1K4@bWA zY#H9CuZt10W}Hp(JyGjXOMS{$?AzN{xW|^oRN|NCxhn+bE4A>fe#9>=^-3=I)fR@Y z)~-k_KVK~4S1Zd3$6C2I0HeX3(JZ2L824y9-T1{KCEu5otWEHN1R@fMLYWX!3vI|X z4oy1@#Qb?3`F{_d8#bf_ZAd~bt3Y^5N=Y!IS^WxeWFa`>W5(u`bTp$iV&LA z!nGHwCDZ1bOgno&KHbjGut6m7e2=ZWdh3>&=poc;rZ1l}!0 z`aU*nND0js({hyx?zIG>3=qdNA*2@CXqMPt51WKuVJm=`?8o`#e>{v5l@gjSrscYp zrY!+t$`1&sg*Mh~h|pb<@oe8JAQnLWI#5(X^To7W*Mc7I$!M1CsRv(?2_dzNoC4r3 z;2`w5^8zB-?=ka+x2F=CFQ(;67_4l=Q(b^^s+0*KwJ@h_SCaHisc6F&h?!7(%b^yj zgyxHBxe^AqJ3bxFPR*UnW@SQ1EzD_Hp)q>6FM2c%0b({63iMs4__cEcBSvQfq_O15MC9@D?U8bJ6h^Wn*x+8CpnlwiJ+z_e_k z5TzLicObT9LP#yNk=C)Fezh64_Le|2aVWw6&9la^Atf|lOv@Gukt2cloV^6klQ$zF zwa`Y9c?0#onqq683&fKKE__q12ZjwPq4{Duz3r|A;@l4isf9Mmbr_@vRKV751!5lL ze;6n#q4^r=Z*6xV5dCUDVAnDuY+9I;XdSOFyn{BPfw%zWQ~}D1N@%{APH(&Cfq0dB z4f_b?^*tfA@b7cWBX`x@HR(JjzIpx$X-R15!} zCvJ>>T*oi!4G^z`Ct2*k7L`x})9G#ZGY}hr!2iD|q!#`i(VvNG-Hc{>5qA+$RqZz5E{Qxooo~DWUmdTAp=)TiG9vW@)~U^>&#MQVVUI zvz)ih;Yz_AZpA+y;*)LGCnYprOv|$lu)73LbsLC;ObDrkHrm=DA}OKyVmke##a$rU0FgBlLTaInKCN!rehI&XFKIP=QI5750Dd3X%b=EQ$M~hC ze}iv<$g-)8KE^i7kP=E@TDDNQ`5p2;yt$3u-!_w>gw#SClWUx|&3(=Qk(g(Vo@$#d zNeRst)3SxaiWfdV5N&NUGD=7-w9&ZwIoli#iLbRD=-C3zd7_lid@(IssHSZM;xiB% zZ1Y4)NG-IHf73g|_*wl+b)JEn6tWFa_cx5Jxg0q!!wkH!0ONr;Y)_ z)1iboYn!)A3C$PNvW03|Ng$w{#2>bKJ0+wR+E@)|m(1S=Wq_!+%txf!eoaUT%@@_R0F(Hd~T$ylB3dmhBCqW&>fL<&$-yZAL~3sf9LV3^Dk%4aBbd zp8DPs<~&hKXug=1E!2GTR3J{+=82S$T4+N?euHy;U}MS2=K3p`T~Z0n7t^x6nKR@R zAOdakU6~iv!klC@GqZFjoe0%~V0K9*l)$uXq3~-Pp2`P^XIe%=YGF?4QPPm8b0|rF zF~$7-Atf|lOw0CW&SZuIG0yh;gA!5;ZKTIls}45u4jZF~95R0uNeRst)9G!u4iGno zj?qu<&qzouv?1g8fv+>Hi(U4eW+J=_@3Ce@CEy=W<{}gOCBY!?+J+6Z`&~$274@X&Xy5TwmlYU9b1Xi z!u=LmhA=}e3BR^aH`E)hsh*)eWF62lgj2t;cUPk70DYBhw@;Qk)}SOXE#vaS`70oj zfbg1Q?kG}1YN3r4n{V3oAoBoGu4a;+W1hLsDJ3*tOsB{AEeJ$vjU+wEwlhizsf9Kc zWxZkBOGTn5eCNAuyRTA0^To7`2?{ZUfM^KBrmp4=FD0ZF+Q44I{622BfEBNB2XU&) z>kMsImIBs|tS5*80XuO6pA-}S!Hy!8&^l1dsxuHRf%r8OLY4yN^m5>B+pc9W5L1|s z7zsOyR6_H`w0u8Ubp~Pu5N|Req!#A1>hew7Zg?>uHcj#s^+o{K7!CIfWKPcpmqLk2lF`ZskxCaS4ilU%xN0Aaz3vI}gZ{W!R z?~$!Ytf*u2PLL9sFQ(JW>Q5lv7LFC!Z9AiskXmR1$1byU^W7f7dqmtw`M1hIV+Tt{ z7{+fxMz{V@IY=x{%qk8JL=V%U;JuSjbh9pO-aF+lJU2XnXkUwUF8g38s~4TQ#r=xD z#`_Nz@-z4jZT_N937%$nIypZ7*YI@e3?~ws7kIB%(ePAblYHIyqjm@NJ~jTws03|D z0@Knq?Bl#@!Plle&_~bRmw}L4o)5uKYW@p-@nrN{+C9D{Ul?*(za4X$Q3=ggeUH)| z0{E=2@AR4xZxw=Ssr_#7sYLFPc*j~dc9MmbA}!rf&EXqd@Kvwf1O1jhHc906i_@$Z zKFzjJi9$f#q(?U{FnKut+NYr2cFCO#gw&#?4rlv*8P1*N7SYe2xN4yiv>^#h%V^4Q z=gY`=9=WoCekw~or3R@MtsA&`5j=!y?6T++z^8~xD1m7i;~6|_fEWkFlS~MyMe7Fq z;eeQ4q^iCYypX7b=8I`LDR6+@iErKz`%-A9|=Ed;){ihgnI7(10nKmQP*xtheuaS&TMI(&MZyxP! z?qw&;_xNpn65l-Kv?c#h`(0EbX?&-?*&!O{Z+7DA6nqcQ$1!|Jn@McKJiA(ypj!A; z7>C7tk7K?ud~@OH#vVPDWJZ|pG4j$EOGCGYB4@J_#vG2GKbGg6=X!uA`I!&;v3A&( zbh%c7xgTsVK7Pq=5cCwbJV8F@b+AbBhgkP#@Ee@ple7E3b{7Mq9vGe+@+>>{obpt> z|4BGy8f_;+USOZ-cr=*hI^A73&b!N~gc7zpA_U$a1~EV2e$*SAxtKfss6tS!N@>tD zq-7IN&miGe%azaX$HeoNI-?Rw;9U^s7T5{%2C%Bu7W|66z1VYZl0s0et>Hl;v1K;# z=znOV&Eqf1?_$HiPw{{kK^$(0nC_(E9 z?tN|Wm<9H4DBfi$w2euNsza9Ce-vdOs#^)K8P=eMIe0Veccs)lC z;ni%LLQt(ztAoU+P)!`2f;JL%w%`%ZvWZ$Rr!gv_1g$4%iHmyk{JRe8GxHBn2&zTL z74Tb1f&Ia9z4RT=-zwt=C1^dtciy%jYZ%>5JY1c__@ZPi11w$nb>;aIEJhd6V8v=0 zyvNbd(yZZ-_9ACf2TmoFp!Ebd7N%ThojvM{*JJ-Z@))7j3Nh`7!%? zr><~Z1ha4=p#-fbXjgD6Y0ni!Ma3y66oP8`>u_rGM4G-Y25sD5I8=!{Az zLF)<5B1d)Q{=F~iw|}3g5LAnf!LVQZzuvt4mxFrN?GegYO9{0GJr8}c46M^q9DI_; zs1Ml>V(H4dQTxQgmV)f(J1vC6gWQ}-C_zhI)A|qD&F1;l7p%FHLQt)`V}r%6=nwjl z`q=OKEWggGT?!C6mf3MCp#-fbO?zpVk4Ja+60NhoW|W{>C9(vIk=NeqpUa|+z!N?^ zDy@(hG3gSc5=zi|(zM4b8}QF{vWsk0_bLR{qBBldnF#I5lTM%2TYZ?O%q%IP*5Kiz zCoDjg_!)(u_VfnIdw2}`Af8lv60D#~w8 zO3-?OTU@vGWqs>Z7jc7q6oP8e^&s%xff}4qzlxYQ%1c=(q6DocO`F}-%JM((7EQy- zDg@P{t445>^452ZUo0sc_7ve%LJ3;xa2hc5C9C?ml&CY?Lm{XZ{^peHOq$lvr7Vy5 z>MVZS<7lj3NeLy?8hrQ8k>^P&DnbHGk6%epE%kTQ{ZZXn?k2rO=-XqAMohx9eKI!L zmFQqmyNrXFnHNt^4mcOdt}N~)((3=ksDu)Dm+AhijsowghiIXnitq>hs*3|JtqMW4 zo=y!C4vE>t@eerPU3;)Rf8Vcyn3cAfQ3)mRF4N|@97XvXXyb822+#4)UOhVXcaX7PO%s5j-ib~;o)3tnyqVD`!On^`QnYGH~z~m-fu)3|6NVwjf>3*SiUc-LQpL_ zzlPfceG>WJ;<;FsXTcUKp@f{Bo3rpyHC_4nDi-mq&;faqnK7@WB~9myaPwjZ4_>K? zpGZ2p&A5e6&Qd8s%Mf~ogYEbx`}cainG+R)YSB3(#2i@Oi(hYgQokGB)3_a2&Qd8s z%TUuUofyWwn|kPPee4y2YN>P4*qtM|?}fQ3^*>ZHc1+}NCrZ#VggB{tg4w-EAtEvM zvQk#qm&jiev=qP(;PW7M+`GGQ-g{MPiIkwxy5Kb6o~~?E(GVe?pH~Q~MZX(OTRu0D zKL~SX?aq4y;62q1C%cLxKS%K@&FYJ>X|6`(P#UjO(_$J&@zeqv_19Ta1Mpt$l{<2Y zosm(z;I8^2rM#O#P#Pj%Jon~>IxtZvw4iaP_pM*uL}GjtpTDeuuzWHJN^4qV!8q2X zPP`C$2@9S@m67o%LF3VZe@VW0)~o^$RZ1E+jmrpll)#(DrEQ4GIX#wHn#PGQulFhh z)uQp};6~^sYgwab5n^#ujZq0DYFoc-Q|Mu?BU56(RHM&LQpLlk51EG%^Jc! zEg39!&uYl1gc39!9jp{}OJuL!MT?$r&Yemqfj7T*%I+#seKF2mz@!*9xq7tt^iMa1 zpjvoxHa$||c(=jq*8C{(=;z^#N+_|g3&fLI>>`?$!}y8e<>J_}K2f6J+F=SowbY1< zH=7M&&ekvyn>JgCxJZc`4iKgJv6D!3!#I#rmdCR0v0>uERF$AwG(IH!uAP&}`E+MC z;)_QBZPhfoE&U2$Z3%8=f8d#ut-EgC$}YbTO3*mD5Gx}rk=I_BlYO*P394ngp z*h&VLgPY&u+}KvVo`p&%L8JG={$S}u-tCSX+u@`VRO@VP1L2*=MXYkgI?r-5fj|8< zFIzHpu!Tw}p+?iqcQt{}cXMYu#zZRw)jE+aP#oFlB%I#kO#)3uCh#>=3$V+lr(39m z5;S@*^wbFnd_Z79Hq%8Vs8*Yefufd{L*%%O=jdZ{B=BK-J(y$adJC0MLLH;B+a>V3 zGm5f*{$8gLREv&qnpUDs6tDhhgZ>Lk4WK<4Z5g!ZgE`!_NZxAmI{o4=Yb;bk30kw@ zNA@L>@5;JPfAxB`LQt*oLmG$yEnP+Xe%MMZO(OZjQmgdCrLr?Bp#-g2c&h%9{QAU| zdj9qH3PH7o-D@Cn_~jJqJh7FOTob|1Utgy0T;s{8gc7u7VGZCy1fP?CnZEUNd4-@_ zmj?xkfHTgbLILa~VR?|A>iQwz_LOuJHrV2r|?i6b%>J@Pk zQ`4}OY&;vrC)v-|*MvtiDxrj0=NAfx^YG)d^fLJdDFoG`b1hgy&Q*aguEE6YH3cnn z^rH1oM+S&C9qP?zEejB(++Hc;ASGzcf(P9_Zyr@UKs;#sQX!}o?dM_E_rQy1|D%?e zzBPbR2_pCI0eI393c=d05K`^5XTE`HSBo!x@!Og4V32J-g_|MP+|6 zWpn!>ymvKmYwKi%pjvcffLUK;dG33_ zM{Iw;no$WQ)H*K~;>nxj@DaPKssz=dvwqnB5HYM#vwmXtiEWHZ=(8$V~w(D&)`?pG{*x&I_g`isMI9R=L9P1PoFK{=5&aY$|W0T35lNsmk zM+DW9X){vD0+$N>MjSJ2P>D=qzVf>lYI_$EeX%wW&ql_v>7C+5C+GDk zw4P~f!&aLch#8mNM9Ga9QSNf>IQFb-yhs|N5>$)UCd5dAI(O*HM2;-WQ>cUz7Z2AL zp7w5H$5ynlC0hmlDx8Utja7nb(b|MtV!A}}rFk~$E*C>nsDu)aI@K2yuDOaOI@;LQ zF^Xp|y-~m1aG*j^En1s!&TD=mj~wRAN*r6Yhe{|x?`(jGq(J0^RzS5#&2SET2sZ&1&LvA97XHOKD^`9K(TO)v#9$5Yw+6tN7!4(RkghD-^)fx z6$8Nz!WL1Gy=PRgj(I$a-Hi%}lnU5+Y{l+wMZsdP8N2(~-Cfx2Gqbnrcn#uXgFE(O&mhjtSQtx6-;d?}(-U>Y0y_a?ISGHF7$G0XO!)UA0~7*P z*fVI_X00r3_{7Xl4j!PR1qm!Cv9l44piM?^W+4m8Dg>&qXAsX(H-i4taWl(#sH~0_ zBrw-SO`M)U$K19jx4y<&kU$moCE_%}sR?wp=0M!4$63&V1eTNN2U&a4E=zy@_SGWR zC{gT2;gCbPl*>@ub6ffrjh(>7>0GWu=z%4H%yIO1-SB@JkuFAri1fV<6yK(MbT2My zVru+Q8eQU*#p6j29W59KvZs(Z{WLNgzn4|U$;2o1po@#0XPfR6VMw4#MppS$%gXyV zlxfs^)0N&BeUs&xU4o$ni4_a$aww}+r5{vay3i}fhrt7i2h@7S4zuXWn*6xh885S#)$7~!sAsgpDVFD zGeAcIRqD9Jx6x2K_m2~n?)qdMEl6O^*EBY_2d#hg0yDpIRcbqyn!K((I}6V@QtmvQ z>BkV7^M^OPG%ZrcGi&AhXq@jWuj_Wr%qzT>M7Vb-U3T*no4qifB_m;|@MKy|>)fyu zUABYr*2TRUo;r)C(W-YfY48fOe^>-x@NS*;jWSLskZ+f94gsEPt7-P7Mv;>b!gyq^ zVG4mNS@WX?W##_9@;Qcy*5}Jc6HDwhQfYm#l~AADuVgGO*EWn@EtGC0jHg9HeU1ZS z6-4>tgIH9hWQ9PLnpcAsHKR@U*z@D9>oK$-f%zt$+^r$aT|O_b^RtoCUS)i1f0y~- zt5s=@n`QWn3X`maVL?L8tI|KkUNUvPd9~id6arOPvSNh%a}{wt*PYM!d!bV1NMPA$ z+T25;6)oJKmnykZX+>q38|9Dfqlg0-IEsYF_vBZ~Z)0dd0@D*MoM?9=FSO)^yabG_N|7@8!f1ShwG2Un)MDRDTD zjus^38)d4PkJ;Li*`pKaid)%8WDcqjsFK&ePcwHsY^^0U^RHTB?9(pG-^gk8$*V<; zA|2y<(hH)Npaluc1yQf^jUol>hSSlb1}g-rFxSN>qun|3<#s!oXW{~-JdnWB)U+R$ z-07buDLwqFUKuq*)}`_{?V0S6krq1-i?_DS%`%jWw-zl(U`~s6_i0u7dT4p-{iUfw zph_+CO+Q-E^WmAO+jxJ579_APi0C%aik{nOBK3c@qB3$>j^VHbW&1cbvoo`e;e16a zTD@%;@o-PKj^PXo5}2N?S0h(1kjP)Xnn9pSUa!67$ZTUc578!mD3_N;{%R8q3lf-b zVm2YhS24adsmakczM4KJGn1oN*`IIo%*NzMPbEGbtVbRc3ZunZFSgbaqbA}>0$9hy zxFo$j32z`y^$b{OZGDXTii8}a7-?%-?ufgjkV6}KMvN2jw@@YPf>C?K%1O~)Mdhza zH$EF_Epx+yg!&wpwhpCs`3sn9IcL)4Xu^mwm*ruUrW|pwS9Z)crgnWZn2!EbncVi+ ztD^-8wak~j>PnlnxJfeIF3FHU73Q?2<($)l_PKVRG)OLF9g7-efP`A+6~yS(_fc-@ z_G|QN5U5h0JRv-Rj-KeiI?v5v9bXxd@0bg6q*i}fW@ht7dG1c6lO~KXMYKL@9m5$G zB=GsfO!#~l^|34`NqxMn<3xi%l^mn~)%=@o^Qx^0>Plx{y+~TF`O7*MH7rP|d9|vg zH~myi>^2oPN+D1sN8uOGzt^STPkeXo?M}_x2ras4l66dNSdhRPBgXBC14(>^{`5;r z+qm5zP$m6W#t9tal;gD>$jIO@I_k+RaR4837`JRHgR-Ee>LW8ONMKHD zT8!|?)a$gFyq;KAAy6fKCtWTc)oot2Zo=>La@1zxc%iJ-t7ce`z#5}z*{6v}4$Xn3 zUXQhU)eHhv(kJu#%zIbi_sMg|p8XjTXZ5NX79_Cdi{}uYyW)i%nR$TC4`&e4_h!j| zTbHLCtIv^7w4$3vII>p&u!z4VA zkNr22t~G2vOQSrHklx6TfhTpF*Li^Oq`K)QTIsaSFKQ5|QtQ>Nw&uIyCm zuA)*-Q94vEfxhr?VPzMXbu0tohz%~R=O>e{Sb&gU8hGcY zy6rp8y~g3R&XTpHZa@}>1gbFKgx5JHoW4B0hEzL~nV|&<`K2MH;T_%fJ*w3WZ~EbG z08JX}uMnuhTo-ZrA_C%l?*Q7-)t{jS3AO)tIASfiHKHG-(}EQORoJfxzv#CZ((ryH zeR#W>(&He3{gsH>Hbs-WL18re=t)XHh&`OzJ6FB1oZRZuhi*DEQt6$M!1Oe2!XaVQ%#TqBRH>tkk}lr#QnqR|JvdewGa!NaCeD^k38Ndt872V^6%_(i>S$@gurONw z=W;S@Q$=O$g9Mhp_#P#`-7UQ8${OyESH@SUlAbVQq^4;B;`^Ytrz8@TF&q+D^EHh& ziY4Ct;>0LO8-{(6aV@`@8~vc|`#BKScm|{QLX~lC`}$f>^v-4Dh&2tg7}xT5jXv0x z1`wK|lD~y2B&2KGGEjg2xaNXS`{ah8;(9TX8;RT}l8 zZ$!iv{uZiaB$siwnzm!tWKzW(O2b2vl)FM&t?ds)th2M;kGB04>uj8ygoKQGd))uB zZi}aWojaBcZWBT8#t*SZM;ipHWGtTXrU|dJeY{vP;=#g)s3nM{rk01#ka%kPvmm?M zW`;FV)+i|?WGwH*rs;a)lQQDB+XxZyJGKD(HcTZ@CF43HpFYxUF~aSx#?w^=UD?7< zk=7Vt!-9m2NuJ*Op?>DMJPUD?h+OVBDlbcP8K@AblJTi6Ze7=HvCi8{B+#c1U08!& zwXBiLh6M>3TmAUJ4ZTq=8C!cvL|{h^bYXkDs06BHob85U=XG1mw!`IqbdARx!f&ay z9dlHzyUm@$=+yFy$f`dYStCr1T8)I7R}Q!O(^K^qldK(80#z~|^1#cRx-GVr{u4%* z=UPF|gm_saWep1wYF>qH45RBFtso`-R0&iK7BRx@kNl(CVuWLQh0||i){rjg*{l)2 zh6M>VuO>GPr{}%al1jpljK75{8K2tu{W0AZ>pU~gleQPDayyPxTL#Qgd{;DWSp{#p z%A*S1nRlx4)*_+iRsMJ{`sQR6TJh-=g+LX)U1H|-k2k$nrW$QgzP~lX)Ob6Qz~|Gn zF@Jc|D;ug&pKJXT0#)i;`@N|TEgK+4$dgP;&xwSZSD{b5>6`fh^k9%mpi1qXt3*bT z4-*E`Yh&wKV}y-<8~bzht{i-m$nM$^wBls5a#u*;IcVa0ZPOSse0?On#9Jx^s&F)* zY0X5m$m>C|w9V`hNXsjgB_P21uw+zOt_mZN17w zCr`A+QyT=Tu%{N|-FrT?g1?D2y7bx_r*Di6kieW45%D*|X|9xwq+ku(S^$GU753EP zyR%pekXzeGy4757Mhg=7u84i3#HtieFGuDw*tW*R7)_uG`*yK*sju8m#*yvn_0fbD zB(Sv;Q5HozkZ;Ld>HG!fl#>_n{KhVRhGPAY5a;>G?_I70Uoz8T_{Hp{lNXYLy z#>tYJb}P>i+VE2a^0MDvv*DYT`-$LQCeojr!{3?N_L+E3hSIPBJxz1_%rm0}iP!nX zt}5s3SdOQ1<>aMlJ!qRche**T?W}A2jNd|)^gvH3?ZoQmkh@>pPwz@6%{W6QZ0}6a zg2b4)b$M@}Y;1Z#`Q$al+PSFB5!1`9+m*2>5||@ml(D`aeb#>_35iKi z2vp%nRzz8J?@E`BKT3KJ8%EHA1lAa_p0iRs4c+3-CKp_xjHywD<7-VjdOMN!E^s(7 zrYJX~1qrPA;=4iaoOIL2g0$1Ag4VB-#>q)|?h>8=C|1|xe?YvWi_x)7O43S;>+x#o z_1U{Bb19w-Bx{WEOJZbM^pUyo5EE^6+K2uj#?B`PRA=p;&a&=tV4T%>$frI}>0Y1J z3YKR(9ccK-d~IbF`oqPKqD8(d1|hG1pYC{a$tiQWzP{A+pxEUYehXFVc}2H_a?;CJ z3euTOeR6zSd_GM}bI(behnAq9HaRIzjs%`wDE90>=uP)7v8Su6XHf`L^$w}WKlJct z3w? zU|s5QG$*b9O^lYnf&`v@DE331-jRM>caqS0GZX?<#m?8|1q*qw4b$WfH0zgiq~%?2 zh^cTiK?@SeYhLj_hqU`W3p>Uvbo9Z7}mE$O7(nJHS3kk`ifqhd|NfDm$ddI4V5H}H&}Q%MXW(fa~1M)M9P28wKR52 z!(Lm{3byD*$NQZik6VWltQn|MYsu%)J?NVp2T10R-3VHcQ2QveOGDb{p&hMIEJ-0y zg*}|69n0fE4}Y#i&rdmI-E+X`A+e5O+M4#!&4V83T8_TXc2P+K39LQht?gZax_z!p zzj>Wi2vp&lrfJVZ3ed;mtI3&HkCitH39LP0CF|-;bZyB1x~b1=g+LXy7-A%ooQa;l zT#n|ios*&k3AJ8*WtYg5p8ho2(NQ5#g)N_m5k7H=M6dLrZF&@@Xh8zoe6bg6$91Ii zC0}~cp}0bzN^RSJikaiPS6*~@XgQ^&MndgB`1LvDTB!LAg+LXK=frLc zd);aK>XoT`${~UlB-Gk2-0Y$avi)29VI>=~_Y+&3{)5QtWhS40ujSucbkA+oT8Uwj zF$ihNNJ#o$g4DX-JEahC#?Q6hflbGz^O*`nAf+X_$wVu3sPvpK+z|?==1;3`<5L z#yu;)`NZS@hcHx!9X&4r%LgK=kEIhvC|01fpxv}Dvi&*b{=$E`~`TN4w z>!{CpSfQ&K2zAVrS+--Mx(cV*Spqes>cN3F9`1(DJ-k= zXZ>4XP9=?9Id-zuf28X}r`lU{*Otbgf)RIHX z`uiRhM6e(*btIy^Yw%1_kMshgoWygiD&W0UKDjJ&Bv4h2`|+E5uIgcbkR>@X(MIRzq+1J`yfE#0rihk*LYhb(u^6x5vmj6ZA+IEK&mueGA zGxlOjf0{Vm!5VGY=5cYFtE3Z;>2X?r{jfL-7! zpdkNiz*(K2kgK-NxUEY4QxMYyQQqwq`(y15y-lU!bjO>gEO^UBeeU>-Y2F!Sm3zvw~Rvi^!TO6Z7a)lzyCel-;lLR$u2)Ovyvx zVJYBJZJ;1nhBS~Uob5bIDE3INw4<1K^1zx})#v}?u26-!u4(5yrd4?(h?OD@EUCe( zi}CS!FY4jbGUip)v%^xVi}IMA;jWOFmDQ8a3BImZs4dH*OQqV|K8iF}WFSy=(Xl*_ z{&8PVI47UuhE}8MTtRFX1X^CNuEIV1UhD5`XUwap`SU7g5qGsTLmEhIe^8z0$?-#X zo^HG!IR&vK1A(frizaLIj;*%;dZ&iT_fXb$xzC+^bL6$0(aY;Sxq__wh}+&MB+!Dy zn|l4 z-dWA&nloAFOOlYIVmZe#=5WS5>NkNFg@C)wa922k1QpH=|4aNk&qP988_#DYhS|7b z9DhsRm7#jDVKsaGPl11DkiVY;ElB()uQb-A9}g3KR9$Dv2i42LmsHAboeBM$S0X** zTI`=F&g(fPh|+>co|MYgdD-!NjqPY`AMt(^&c!$XaG-exSLds5=j6HjJBar@W#ZJ7 z?Shz-fk0Ku3dwBD$Lyj{mt*RZHG`^(u@5ht;jXYekQU>_y2VoV3ZlCp(1JwMwj0@r zPT9EMqD&%;$>6h50>yCWn_k8q}Z*ktMzB703 z=|;<&kF%W~4m{g2={2aEuXTz=5Q7DQ79>9O_u^sq9eJ9w9K+R^YL{Z%6%wezoEFhL zgX>g1C(_6*(m)FmE)^^B+*us>z=`s%YCoU2ZHFMHWFSz5c__YA`>jk}Cx}ymxbx@- zo0IOsM|YL;4wMnla=)t5n^YbCa8Rj;arP_}vo(e|CVO1&LW@^71nuUHE_jazxfOd2iJdf~X+U zKmt`*vYPfP$}Tlo5Xpi-3lf);-1zJcF1*=K`Q$Yp{q#L42(JtTs<8ZxmciyZFz#KB z?u=`hKSsVOqdqQJ;RCRh!T*b}7ekVJ|0m3g0hcD&TGqSijq_$Bey)+pwCKoFaL z^|giti32%&_>T8Ec~Dn50vOV0ZA!c+BjW{u7SqNO{K_DE>plar7d3uKoC4lwTGg#0 zjpPhzAhDsbJKw+9f#(}2pJPkkrB&Ap!Wi`#zlEx{=L+%{&mH(%F%HtSmX}jfYKpr` z5^11i%hKGu<0MC3?3``1Wc-pC^&R?Hb>06+1BpVD9RAH|Ywl_v1YwMpjNd{PmW`%0 zG5wvARos;v`(Q~mX!DJ2`qPou+@0~Re*Q5!wVfcQX2>ffCdIsACk{Jsw~_M6%R45e z_7cRT3GnLnpd>DF`_xK;m?H?Z+=#o(%D2kJYmT>#;f&`KXKmFW)k=yd zKb0X3B>LPt&g_%yc$Eus40k5DwVxQblaveus$?x08=ajW`zmKFOY@yzOOAxn37zhy z;tU(-=V4-Y->Ch2J)*gs*KYI4&KG5GE3PyReE{h9F|KWXIQzBsyyxE`bn)ZmX=uq@ zvJS7~n#<~~!(Y<0qCM^S{AI1FecQk^v>@>`DVRUrV#mCe%eJKW*O%;YkFKaKEn&IF^EK;0S#`4oElBiiSBsN!nON*KnMS93k63AQcN$;hydM&%QuFG^iYqKz zYA-r?e0~dBc0M=rX0h+|;0_)Xb6vEeZ4Qaull#%JK6L}pg2dHh{`_6wJ$-s**;0qs z-@q#889=A(DVl}^s?eJtz8f@O!-^doK=Y8f+tGr=5#eEJz3-}Cd!9^Vi`x`NPDImu z`A=6v0#)d95T~;DNn&HJMA1~g^fa^}v897A-}U^w9(Px!v9xh0>sVzFJ#wj#2?hrdu*)^w|xIJRIp-w+%FHU(W}W=ciEGv{*t=8oGd$@45cqx zAGMtFcH${bx9J1N*m_P$NLnS%6+UPAcxosOD)YjG1gf5g6y!;rQ}x>YWb2b{shfWE z_)wZ9vXccZNT5eY)21X$(jSKmrMJ#4HX(tkLJy1a#C*H;H%W^N$Z`K$}y~aOE zLkkjWUXiHd`kAyu>inJhA%Utf!k2YN__F$!k!f7s`cwD)nLwM~FTNcuNMPBBoxeWc zBWL}4Sj)rk@A_wPr^dDPaz7cL%62+_(02`%ZOP7{TjWmXo^)(~xju8bY}@bc zJ3?j+?MpW|{<<42NT82gtdDARl+dnyX+B6RFe4%$(m^c>6CR2sYswI z&3u&I5+3>!XJi_?+fO9bD#y?|J(K&}Z??wv}=(E-|;?$m8$vT+k_&IAk5~$jk?>cjg*{}DoSlg>5 zHAu(pL+HdW6a3JE#6Oj9vS|eo+8V&v8m>7Ssq1dYM}kZVw9(qi zCL~Z5*!C$qukY49yyY7;d|aG)dg4%8sQhRPdd%G|UzmU0RDE;*q7?n&V!V54vbk61 zp>&z&$ZBXoVjE3o9fiNWT_c&ss8M&!(E}3c!nJHW5~#vE6miJY4x7c=0b0~op>%27MH4=`oQoJOH9nI_ zbqZOS7A2Ff$MciZX6!->5;))0wE8WJkxiH4`Jv0>1CT(~<}UZy{;JOW z=MMQsy{pig+^#X0kMSM53oS^L7G9Ba!YdLX%0|=Her-iong{a*j;sC9f&|W~#kbUa z(Ijw69Dg(>M^z+HCEG;j zUgJn4kKxUS&#!?NB+&CB&L2Fwf;{OQ$uo7Gyc-Erz3R<`L8qwqYv5owFESz7SdNKtGRJGfqvzsS#^2YOJ8bRkQWca)OT)rRZhcm9D z%eyN+IZgXB?jU(su^+!V^Hv)EE)qGDwllxZcKkzx>}z-Q+Cw}{{rRcAt<%ubbkAFIV-&^??VOuVxT2~??1 z?mXuJYtp%&^~r-BW3u*xWONc%$Wir`8Pf;vI#*?M{^< zwBvjqzO?$jCV;z{a&kFu6YqJ|l`OJJB#&O3H4O<=p{H2%QQgkz)&w@5XtC0Lr-OO)h=-#Br* zg|hX@@rJO`!-w$b>ZxgHK|=NQ&3jjvxxb9(@!f6&B7v%!%iMX+!Y+Jn9@)0%nd`u= zOiAE_j(S?qf&}^&MJ=iEMgQ)a$WN~-yd4QtUH|2?{9IP15qax~ULqxtcfPpIgr3b) zM|1NBPPzGt0Yxd&VkSH>S>J9ql=o~sIt?vI9CCN#ll!{xn94GZM(nZPzf~enU6yA% z5~xz|YRRoY{Y1)8?!Ui_1@8*|qL`kDj&5B+pMStMWfm&Dio6$1K?+ox~3 zl&BD>l4<<@KDhF)@w?XV_@M77VIvF+5_1B@+VCB@Sy|DJ$)^xrmNKI)tv?R6reP4M z!f%CEU|5ZkQ%R(Fa`f-YJ2AX<^4cLPE4Mv)M0%y2EqhKQ=c4~h7^=kUW)s z8&o;v=f8Q}KC^sswBYZ`YvUWM^{%uBd5)MzANnt0sPG%B*ahn445E+kPkXiL{wo7E_T9z$EDoa+#rOWXk5B3LFN#zAs*f=N;!8%A4S{F= z8NfpJ#wi4L65O#Eu0~ zc}vivH@~pS6A$ZdpQR_&e=0HE%snmb#h0Oq1qn5cF@D!fGfVlGDxasBn2MW4B?INi2i&PAABYNAZzY{~&s*(v+Tm>vBT3ley@;-tTgnam}7hSJ+r zPm;RgcMr8q(NA<1@$}+a?!A;Vtr#u4;|puQeutj2MEdlnd;BnMz1)(P9pRu@kO+ml z72c@s-%Z{$o@%GdifGl}Q7@Pt&KX1$QbG~)L%%rMVQefx3li#GRq&W&Zn!&^rtgVS z2vp$=Nt|kB*=$ap8%4WJo=VVy#Dja!*s2JNKCioc^4?D`m=Ao3q0jz^RR~n!oJ!Mf z@A+Vk{yT=&pA|#Ug2c+EPuVpuU7ylUrcvPTdvoOpF|^oSl|Yp`S1VMgD4EnQn$B<$ zV{4edB2lr#O;)At0lh;enMTENMTmXHXsTC zyf&{i*KVdR}%H>$PIAEf5X#iZw*{uC`p;QJ^}SiLdTd?&pC z8$K#tAy9>Jonq{BdzyKheF1iALc9_qiUhXWnzp8lg-n0bgMNPyL-0!jmQCqIo%Ja9 zRDb9#%Om}ng~avjNxv=ZPtbw{=DLXNpSy)@8da7qYv4tZKvl`BI$JsJwLU1fERR{c zlgZp6<>-~4Whh#Zz;e>Gb-4zU+zV%tAvgOe1ghv<#`+ZdtiK&5(-`<=2#GS!A`ga$ zRSIB10?SD}N2L^Vslr9s&bvbt0#$PUVMOT)A98Z4dH9dQY~zz5)_Ig+K|(D-IcM44 zA)d~7u8v;u3nq?B#h1}@)%*?$BIsFJWlW7k!6XO1|JPVscsXC<-H{4Q9$4-=-5LZE89NJH)+CTC${J~%%6*7RQlT9Ck5nDALPURd?^a8Ket zDV`#Ms!t+~^1o(%Vh4fMfBGg4^Ca~IffgjxnOEhNZ+-Kw-A9%k>ZcH>nj^lFe-<;n z8P>6A1nHYvVa+~rMi6L0;;EQl8FNGN4RTA?)O^)_=+SCaAyD;Aq*374%u??4vM9w% z5IY5d79>KI+1=*!L%!yBE$OCd4hn&)|J1}`RRpm|5NJW-50S?2x;v}-Ikv~A3;kR% zhG0yI|5r1AR{f*CYfNEU;j%w3dHaE0zN2gtXSf%%EKYApM^9Dn3e)?;$B8%JmZ~q> zC3}PYe(sj|;i0rxWAR3T1qpn+#0mEArdV3c-$zC9|S zps>i@y&`wff&}KerakuUp0;Y!l(f%3)Y^`@Fs7vTlJdOK<>UG}5pAeOC!7ze&DNhANUQrt5wsvtp`R!J=h8lXYhGD`@0{$| z3C9@vWN)lOpb8@+#J)I9v$FizqiKCMil7CF!B2~Ew?vD+w3|$$(cH^=6X64xZ;4R| zRAIb^h+F!Wq^EC)rDvYR60{(pwJFGh4(`yKFP3RMn4P2_-y2I`iPPVZKo!QFi0Fie zH!KsH#?d?DV~Jvc-^DsD`oX_%SUg+CQM<}2fhvrj5nh9VjrHdqaWwH&3_%ML>ie;F zM*&N|c4Du)M`aZPRoEwrdR3?c)9XdjiSMG7T7r>ISpFhf{rE_B?@BnG&E^zr4J23^ueS;sz3ix;s4`}@*bIU)&KkiZBr(Q}qq&$`y_ zNj)8>Dg>(3_G&|}tt_8QZ*k^bG(igz80n^ISMHx-#eBNbCYSpv1gfyD6kiks|ZH5kQ$!W%S_do5_bN5z6=qYdH3gq9#TrS)6ijAv0S=C_N_d=vqB8sP>vtdO0exf|YqNA?1AEOU<7)J$Xh8yN zsEA^{(3QuO}1O#66S9 z+pj8ts<@73Uhs2fHt>e5?H6Ji>nD%fvtsoUlvxqh$_!(;cbC$hB-pbx^AnUY91>VV zHLbh-<+Qe=?OD$Z1gdcLsn|p4(lkr6oDS^Nqy%MMDiT;j#XRcOG|Pxe4lH7#N}vkY zs0t5@kES0O>B#nm3If)c0o%N`y5~#wpwqgXZ{)qmfUkUbL#1M)W zB-Fb5A=eSz{bxxwBT6Mugh6Tq@~8=M1?>VMyH4#r|n(6do?=}S1O*O1qt>2h@JI- zJ-*SNrdADCyg2v<<9JTf#{GECg08itrEZ54v><`GF8n1&udrILi&Il_X^I4@uoo3y z`wm@Xo`uWNGo?HzT9CkU(zNkSlh}v1<48oIz6yaVY`er7lWwzEE$^M=%g(M8El6NF z2|rxFgZf`xO0s$*hbRQ9)Hcz+?R9G`a6t?R*! zeU%<>sl!jN$ZdV^WMrMO50hAnJkf=@dUhmSoH3hGWze{rfQWAUzSOdC$x+g?c3+AX z`MU-ouZPzl}{wIID0#K^h6zs7W`eTJz@;E zFP7zeNML;v9>=~jh0EBe3a_&A>~CCntaay>ZAsrv8+wNF zl>sLST99}u=$$2U^UEU2O4H`g%Wdx5X&?KsrXQUpzNJ(Y`wYl9vI!!lY-?T@K1+E1 zJ>F*JGmE(Jx69i z9v!EwkVXRUR@3s|dTxHRD~9(e6hn&dOJ^fLI`aoDiqX?IzOpBy#2yC|i&0$VAy#20 zjWXXlAIr->j3sD60!vopZs}3x!jEJ5G7))(1gdcDi74~bHRfAMvAkfb7=jig)LPQe z>!ayG&3L}*SXqTYm9cKd7Wew>)-!Xt`7wM??KtJGaJ>oUh^FPs;XrbIkLE3s)Vx9h zSCWX61mb*1&ihf^_kNU;yQspIBqC1cYY#HSc>o{Oc^JX@po1beRPSAqH$dx+t8kCc>!*bld>gOi1=tEE5ZtEC=79?=(iP!^ssZOHP zd+>_gBNYNw>e`G>uF2+dNoKxwu8-0tV%=5StHkMp%{6|QdB}AirS(Aq-!4u2qu>y8 zz!fv!l(novpeo_bS9UVlng0_jTe!FEmbvH&6K}cDhoS`uwagQJZ<~+LHSw9}R036f zZl|-WrJVT(D$~dlRh*ppP=ik_<3rJc1lBPTjk~ir`8vG@e?CPeQ1v4IJ_~ep;&1+u zy}^ckZAqNi-)eb+H$@8)Sl`53>(Y+6wW-dlJNqaEs&;j`#15@=;77%NTVhw0uj5I} zv%Wler58mD5?J5FJgV3Pl2*u*?1MHzM}$PvdEL7 z1qrO7;yX^CRix;J@;vtlFNHvr-xr;A-C)NbZkF%Ia=+2$tj?R+Y!L~FJqy-8wU6r8 zwu*WGgw1SvK!nmqA%V3=yn_p>m`^s|%!Z3I$MCmMT%Vc>=dW#q6G=8J;FPfW4LKSRtG|-ssyTV z-xm?Fe-tf1qrM@!mC#Mq3L}GN76D}-!h$9=-*}U~)9#Z= zMdK-2kWlMY&nIimmOUQiZGM$Nm5grty)TZ8^6K6pp1Z#*OK=?&jtz&2sIcGjkE=&Q zQu+vD*W0oLElA)fQ_~V_XsKUDhVtIcPAUYdVniCo49OOGc0dsA|2#=hg|njn5}|Ke z^5~fk6fH=U5os7RG7-7FzGCWbL42LzK+%GPI>)K~E-W?1&xhCWrwW0p`y$56n1u;X z>h@x3{_D&0m#!vd?1S?tm5|RKv&^2aof<;Xf&|XnYM*o`W2_M;xW`4~QJy}OVpalt>>1kS<1FKWl{WCeR zi-^)g0#(hXIQ%=awBFUQx%H<6%D6tXAfe9g1T!o;GMbDYAEywgswQ^j8Y5F|S1n66(%h z{|ukc9P0Js58NUNuG__R!XpY+;XNwY^CuB<>~n5y(yp+|Y2 zEPv4?R%xk`z*V$jpQ6Uq^)H3vx&K5c2Ckrt6>hd%0=#>DWq z>thI7kiZq$;>&0^T`yBBmbZHls}QJC?<%-kNj>(Z6FJZzf#NQUxJM(2bLUPM9eJsR z@*O;Sw}jrNu`|)@CQ!5>ar03LUTUKQUs^^IJuBSRI|Q$1rDlgK1gf6Tap%XrIq~$0 zk~lu%j(#<59m}>goT3GZ$F3#$;XV@CHHrC#wNmt)M}Jxp z4m*;uy%Q)}kia|?BfdV#`m!7wS&OG4vIgE9RAH?Ydpg-C>jC#SuoLOw6fH<#9*VDh zLq6+mnwfa(***$^Dy(nfE7`M8`p`fVUzzMf(Sii#p;)PRBn$gVVz_G-wI-qp-vSX^ zo70OWe2e0h?4y#CCB8_t` z^)vHxlOy&C%AT@FV7nsP#A{>NniAn$+Zsb~Ooe5mj<2S;k7Xa*h4X96BMDlNz+Bff z-XoE)OGOhvyRI0TzW&O0eG4s?5uO z8PjHlDFl{gzm&>6re;pQ`iM+pUqwIm>iaU57Agp^Ac5tiX}MdB(9`>Z4RT7uWhu4Y@yhVmMF2NK*v2FJb^M+ETvPwcqo-_oupdv*f&}Ke@R5Zju@Qcix$7q{iUg{nIt1{Oh3t5aC^@Fidn<{3*;Scu z`OAx<1qm!C(I!6mi_N>Zfc3v2A_3vIP_@q~fcMaH@U?ek8s_8{Y**?+)@x&biWVd= z*Tr4ko1;&u??#q)k5>sO8{FMPe4`&WS6{NBAaU#yuk8DQzpIvD%D9cJ$BY)747f|K zJ`dv0Dre&|@@VVLAkLk#aT!OnHLect*(ACD`YFaqEd?{orIVV^1e_x1MZu>$7zZKKxs#3+ImBrq4mPK9|! zGRJ9Qyxx?N3V|wlS4OUD+Lz7S*zHZNcxTgDr93hcMrjJ)>+rd(WiAuHDWbx#W}Mm) z#7k_-%4H-N(jpRY(h}A$t^^M~TUD_jfjKR9%qrJ|oqJoBA3LTJs8Y-PUT_GT8>8`2 z*Fvo2Vbq3tXd9#AQ(wN{E#L#Ov;lG zo5S8*2;_hC@u1Cj6TYBS4nA1CsfQ*KzHmr(o^-4*Rf%lfc8Hz5`|t_})tZQVY+)S} zI|$gNvN!3ydApAtl$HSrOj~|G-@r~CXu+3dXiHFqwMXnvy>1S>>1X13FRAqk3H3Q> zaBe+n)Co(=eM6O9hp;p+o5g-)6SDCUjbyu9cgk(u=ZiOUxjUGm1qm!C;cp*jVqTpt zGRM{36arP4)0);kpC2o->NFcUvxia!NMOl|h?MyWta+Fdw|8u)5U5h0yyU6Udff$% zBzKDhrESN(m#|+E=e{Q0*B?96z#2UhmHq<>%n`9RV_Y4!qV!_sS1U{*P=&pn`0hMw zAiL1w1nZsLRp|$jQ1dEu{9N{SN+o_|m)h5&3VUtQbFNs<%zFa(yi6WSe~tv!7_qnE zt_>`yRv%vXk4Rad$_ z{qbIppDSzow_caY)ruu)>1U-VT9Cjs{K7{azKxU}FqNEJ(p@1?HRIcEmb>{6{gHzl zS*DL)L5hDENsa~gp=dz@*YIoFq(ODa%eyXY@3c6DK-J!lY3z0XEX?kQe2!dwT}j?j z)!CJzgD6^%P*?Z&IPi|-Z`zhRcWXs(?`SNW`H|b%?1&Hgf_pMLdj7n3mXp{m zbmte+DsDXa)UJg>plbB-?W|(U%uFvS^J>hYXT&i*j2xitC|Z!fauU5-^AxhRmmOQ^ z)n6e{bz#>IcC~wUwyvy9LKsSa(DuXd^?=w-P&IvP=$A^X-k@9 zrl}u7=;s5q2<~EzHRk8V6jrn6XWh4ltR-hxXQF$4hR~CC^$A*#z`7t-PL6e>r|O7v zcNb@)NT4d`>J-+i?N8m#(^^Z8xzcwv+^9!!M~W6Cu=a@F*)c!;*n2$5nG&QBsA`ir zmHmv!!j>+QX*4KiPx-q+OSxl=Oto9C> z#x&Oxr0@MAtX-p;{Y5MN zosHh^*^<`y5pm_19Jyav><`yB+ecP zvZH<5%+tGEZ>12Zl6iQ&ksX`lE7Q0?|0M|vdZMpf*x98j)VNDBd+L>)^=%=EE`NH{69EP2 z=_SvV^1z&)Q8Jlr7c1NjThB3ZoRyoduG5q*AMdKv5-fk2#?3Ao`=^SmCGA!_)7ev- z(78`d3V|y59Qg)**MEe|Q$w3QE=vD;7)%d@ zV1| z7kf`7e_ipUXh8yVM65+F?oTJ*nn8B%Ev^u#D(<$0rPs>Jmi3XjJGgo<-8p&$IrcO^ zMGF#`BjRk1r}b&i{_}|MtXv9#s?^&XSYrE}EbB2@6YuS7LvKVzk~eK$6SN?q=GC7^ z+SBICCXv^6R}=zOsebF&j-k$MN?w_}O~!gtOK1T)e%v#qWyqLszu)u2>-}ieGA?xI z*~>)cs9`|@b42V9cgT+xD(6C9^ic^^$$b0$o)?^6mpZ-ALhr`yCTKwdb3}}m{;o?S z_hq3QOQb0Ts${RCK0qCq2|?S(vD{1*NJ2AX(|CZDs%d^ixYde zses7cVZP02Y?_nUY3hp^EwZ*}y6C{x)G1(n3x40#;2eL^LS-DOXLuGR4J6*q*ub3b z=U~o_WC=FtA4CgRFG;h7oj2oiph~`vzuT*_qrQ;VL7fDv4Kqdn^7I+wT8;*=Jr-wS zzp|%SJA}|_-c!=hg6*S0%U=?4OYg*2LjSt-Y>}ZBv>>70Rl7F!^yDtFez4@9CL~aW zC!33SxK{qO{Nl>gQZthUEl6N4h`3jCd0Kj~iE6Jyt0RFbJlR})=RDS##@>HLDjhy# z#xp?i+)tJ0c}%PcC)tUNO)<_HZP7h9HLm3z`gbm^VuxOMuoOpEkypz$455WdATfQm zx1a?HOk2~AL=L3&+b$wI9>(uP0#$9+tY)*H6<{Tu@`*HDa~AH>}&8Qh)#U+&9Z+|DOx;6 zd{Y%?`gR#mh)P;s%RWPv=I=f#t-MCx`!-;U&a|@DQDamjYm710N)z7J8Yk^p`vfV`TP6-$Jm*`+f=oGe5-4gvB;D}#tQekN8Ee% zQZii1Jc}|brOaH@F%+4uG*Loy-AXAlhqIStDAJ@NGDRaQim32^p1t>T?r)uQZ}0zp z-dF2$p69!tHSM*hwbpN(v%S*|_SLXFtdHu&|k z?TuQ*Z;IMo2p*~Ye&j-)3GNPmvVS{2 zL2|BGSH`TXzHKf9i{A2nBtPxHi3hH6+THQgI{VFh8zLprhZqFY;)V4_Gw9|o zu~UAkv-MQUaH9p0Xu4y)ORsIfG0xw9(4ODry-4A_W}BlI)|+L``)Y?h|E zJAJ&n$MVrE?>}C*SB{wBbe=uPC`T-j{j^<$YIjt*4Ck5S!wrIuD_&f0QtOtrifVTo zDe=8U1X^MVc^^P~{C+Y)%?jtWOAV;rNJbnUuW(#B_x=iJZt5*gw|+ccU3qD=8fy=+ zhfVoBh!!Mp#GtnZ6r;m}>W#Wn9QL~XrAkhbO*clzM2?3?qW1W#k81GE_o**kI%6B7 z!O1M=&dhSon@vh9ysM#gELR>^TRy69N1o5L(Q*w4^LqZ}uD&Yy$)D{pliy3l@d~fh zW;wpk9HLg=wA^m;Qym*ENSHDD&mO7@{#nwl^UVT-Krgf8(?<n$v9qXh{p z6YXeyX_UHqa(HGI$u6>ESPyL%h}N=kN%_SP3on&SlvZzSli z=@|%*L^{=l=!@u+UxlCVnH1Fr=XT~8gN|Nv9{KvFm>7$84p;pfoQRw`{H%@9k@)L} zEN6V0rSEOd`p)lBjNf}EIfqleYJ_>`emw5|OAg1wBhi=YZI7tV$2K~9ou)RH1M~jW zoR!Y}U$56S&-4A&dmSHB!-5N(xueF~XhFh^QQ_F5s!e~}NiDw4Akd3rA4wC9r*(G+Q`Jjf-=W`} zd&5RN7Sh;bEbHN$I;lLzZ_qm$9om8xB+MA^?C!4q{xw0rm4DscNT3(C4b2eheZoHR zZGX*oWMfOLbvDe-uiMNkr%V=s-^~(*{rD9!SnM|VYuQk;Dus;Jq9H4EyNukf|@m+&X{Pv`pRr=J*TqXmhE-NR17Lk0AiUQFD5 z;;;p1Mx8ukG{q*3dUix>cbCiL58XPJtT==#D`q zMx|}EH%*=H{LrYsL7-RVPq#YHrsdb2e`n&4tE=qNhn{mn=lUtMAo1zduv7ACKK-w| zimu7>&i0*ilI;HXj4}xH%Cj-zIJ9d0$X6Vr-|>6wzpfRvr++p^p#_PDe%Rt%_#v-; zaxoKoJM6R*$M(}77k<*l)uh-qxXzEXO!WtL$J702m!2WUx>O{v)@derz7OoigKFr) zovJB37JA_dF47p89kIJ6*48JB-LBAr1h$i9ee%ll_QKk;opF&z4FbJzZ4S+#%bacB zf8ix(XXQr~T9CkYqPMkY3fZsbt7l(|j5P@K;=8EqH9yzpoC%(4T-1L4BX37*u^@r% zL|>{~((@+$Jva1D;~9tVqj_}Z=N)sTPWX2m6QMb8)Hlv;ygS2dqGhS@1ohC%H*Yyz zv4D*hB+NU2+uIFMJ?y@XCjA>W2=u~hiDeZWIZRD@x538s?O(Uif&|`i(44#Z-PQJf zM;gp;npYu#US`R=KKQV@_tSsElQS;bXh8z+25H4eq5D*c4S5?Ke66Zci|A!Ou{8Me zpk1n1v4)dR3{-e`|C&SJpr}2nT&>_fGsrU)?OeYvK^?nLBwXg(?uG@4$lvd}bpF}= zcJS#vHQW~beoSMx&83|&CnnLaYaMm=^sV6zPc>3#K?0w`=*?Zd5-M|GhelTpv^NO! zGM`vR4!RiRo_M;7se{EmoO3A8YVu4)vx@&X8npWDY#2(P=stgl1&L4dhFyBpNgk;m zeSV2O^7@R;+z3z#VIx($n+lWkonfhgKETk8@vjZvLW?LJJb7Ut8xiES+BuKETAW{N>cY z9dFZLy>-b(0=>8#HEZS9y&vShJ0Mg}ZCPGf4}9RVjTR(0-t8ad*OPAI7=O*rr}R4= z^%q@I3mP5f(1NXLwqT8p^;Oq#)LM^MGzj$SG)HmP!xs3#Rac-|WkXJ7~$M=cT z$_LbM%}VO>Gd{P`f&{h`?YW#(P31Wk)Qx)AHVE{>yG(j2x}%~>&1$Zv-hVlW79_Bp z=&E+hJ?fW_%QzpcuVRe5*f#iFLi>fcu+@alW48`Zu5CQAAc5^e5%I_7obSq;6+kzw!SZPbQ+ z|2RYIEjOMZk-&B$?Xw@7smzzl>j{Ue8w7gcs6_iryxc%7Y*|;QZaZX*S4dzx(YK=E zXY7l=_S9cmjcwGH#j|Mr`Ss2utAKv4FQ2v3hWu>*vb~qyGECWMK?2W5%W5^JsB&gj z)ivMCr;tFeSu_R@Y>{6VrXEG_+m9Ad|2|w(S9md>LJJZ&uFyNO`-`e-|1NTR?rUlg z==E&L4bIP9^66Pw9Aoi`ysFpP_nd>Hnk%#*!SS-k-Lr+y*ymcU4DPPc#~{$F;ins% zyR0w8^yCx5bkpIzBrJ@H}Vy2SS)hS9p45o zy^v{leCtW0u8`o8i%Kc2W4U*J@cNw@_KAd%27z8!Zt-`3c;13&`roN4!qgtDqx@knZeY7ZC$dg0vw&9nUEdbPLI-@z~M z?q;+g66T#{&kZN-cN(nQ{X1bg&-Kllg{Xo)45<|hk&^5DM^r$YP=vF3xnIW?05_J-aKwWQ^DPifo*Jih_*&>{Ml{vXnu6YQ_jf^sB| z=MwynOQ3~mA*7c?3G(K@kVXQ%Fo&M2`>#((jUpj!9*yAvIS|rIu%>-yFO*wyjDdut z+0|=rP93QKQR)*VOS$I!%fTYk}DT72#8_O zNO%+tBDVJd;l}fPg^-f77srskguTZ*cuoX*VZG%@xcNmwdS$d6 zjD_fb3Xg?eSR-x>|DTYSymKx3b>+6RlrOG!U4na}5YqD{c07R=$q9Q&4*#1#uiSHm z79=<==YO>1Tvs}l5HG9|mtgN`Pn3QoF{J&a79@sAU}>2U8cXh-hZr66F27@&n}i%! z$|1BzjGmYoe7)u*HQ=>5;a5@$2TN=Zs5k#;uR3f>41PE_puXPJUKQ?kYjFCCfcor_ z_Eg>-L@XzwzLgPv{HJ7l-OePn=(;v)>n%xYYV|g1%dZ{m9W|5G^7Ph3ob-wQ zzh;C}67mOc+Z9kZ{qcZ$C2vBo?(Nmyz76e$>yp&GvhCF5-y7J6C|;GZ?TC1DYG!aT5oN0t3G=bmd>l|OKiOWj z^3x9ui!Dd%Ntwadh-h^4yzu^!U4rSo0_ys~ZB-vTD_Ctuvij}qwkqkF_Q9F`0;=qN zZ74=-zpjpLm>Wh55^MHk1;=hrRv9~(_&`dYIVZewLt=2!oPerZv9&sVQ`6wKkpY$b zSZmen`0C)rtYmfmX)gJGpIBZ#Ba9X#FgDFw@^kgf=w}TAz0#Mg47S^ptomH#7`=U> z#&sECv>;)Y<1;^3ckG{Qv^lmj=9c!q@`(dQ=Nh>}g8N(MwtyOT;sMIl0iW1Z!z9oP z>yTE4`QP!RFMLCa;Zc^Y-bP!By1ewFk@(W3NVHONIQw{<{O}`|r57 zH=ULle1ZGb4Kob_z3{xDopj#F3jSGTlKS$j6CPfvaBvTm@Chp6AE!zNZ{FzjB`gzt z^P=9KNil9+HP<}{rA`c@%dNpjGrb;TS>64f{GP|jy08k}xu-?chPttrr!>Z%asY8jPdcfkyUKrcL-=^G1` zJd23Kj(MIV!RgKvWBme-G0rb}sUuzt85z(EM+ura@I+>C55?G{XB+K-BN5g#eRZ9Z z8C*!j)BQ8TXhFgpuOgE(gRc-#y@pAkSMAF;1ouU}F@}@`XuNunhz~nvgwcWoj$<@3 zjL!_dLBztd@q~?TU-H)%ycovuwaK|; z``%qiDzdnpJGM)$)7uaKtiAhBvjve@d~ids(xPN_tvR1j=Y8Uzo4tM|$3idjj7sRX0meC(IJc%hjFfnIopqwlr;`7twXUKlM%lq>gE@Y2>~ z)pRP?Ze5?Kwb&%kt8ba6!6T#O%K3s{^69T-gwcWoUQ1{OgkO$Yz2+JOdR;%WeXve{ zY4f^%UEOqVMi?zf;MI;a4iD{(JQJR%`3{B8oRLr0b+4~{MwOge*FEnfy=qejDtU(; zdn2C_;mjz$At!>pxc5Xd>iSpb`OeLdH1@z zvqX}6-KB3V7xzZ$__^Y|iv}Z8`(s}i*KcEz!=w-H=-#<;~Mv@MgqOe+I_{3!7V7n?G+zTlIGEwN9~E!vOLby*QKxaMqZ{E z1campq?`#ZITDgS;@;_F$?;g|h4p5}kkZaB*D+e7 z(>HdA=8AJ`5)y+gQqxRGjPsRwg!BHq_CNx?B!^rJCLy)RqYU>-u2CKn<@fm7MGF#= z_RbHA5|VzE6Tx1RTds98S7^cGKJ{V;H-}x5VtXPI=ylVBX^P7fjS zXHlbeLuip0{jRi+mi+&hD<-5CDvgZoiC7Nwl3E|PEQSc7McSNuA|A;ohlLg-q`!Gr z&fMw>y`=ZVmmDof$Vjv@g|E&S0}1rP^WU;or~K{CRl9WKL{+BX68p8L)zsOn_uX{L zG1^^#(iI2nwmJRtBikrOZUlO9nvdiWb?+JJzI)D?J;ptjSdb_d{?(0<=SqZP21ipx>B!4`^<8-ZS&<`^Dvb<>w_j1z|kDYPIlsM0NN zjNKR4Q;ggQ^x`zf@QAgkSG>BK*h`@WiGNb=c4LHRtfCmX5$MHfj^PodOP3&yc6a=x zy+R8Todz^_V?5sOP4dl+Krc>n43D_=xm(>BCmwFD(1HY?H{2c%Pk)1ab0g4;(;UMi z{O(Tw2^oEtdp>)`_Ty}SA*6>R!D;!O^ynY39Oh>HGeJ+9yV&icx4aiooaPvuZgOs? zo8C2aE0rTR0=+oRF+8GRp>b}EGIhsjv>?%R!WlQl?|H%$BR2xQIL$FU;;WArxiN~b z9j?)W#Kpts+!zl(x0zz(MxYm`Ifh55C1E$l(7r=7T96oa@dmdA=a1y`BR2xQIL$FU zqS@?k+!!Y!12tNZxV_O$Zj4Iruca8d5$MHfj^PpSHo4%&=(O=+jTR)XhCA*Ys!t$IxUN0YH5-E{0nUITm_xT3VL<%(~)Q9H?%v*{i_YcSO^1wHsoVy~GkrFkNzY9Wz&< zoCx;f-=$^w$Y!p@A~A%JwuurUPT{dQEnb}dy6la)w1-$?3G5|&bp8uzz6wiSaXPlH zxDGvE@86K-lT**V6J+{c%$!R&aIW1#wdms^nAgP*pf-sDau`>h&UkdU<8WpJGMHb*bKJ2P{I79^y%$Hg%2 zMbS%+gm;!+uF!&nq>b}~`))J_9}B(kZrLbD2rWq9n-`Y|NnIg?GfhI1Gf zBZLHc$?wsUM`K9+um!y&&2`9S;6JY%XpuD27|-+fiD<6)Sm-76652V~AfheE79=Ds z_q)+tMPnerUQ+9EF+ym;<4R3OV}zvSNT8Se9<8f5f-N}_@$G@fk~DiI_4_T_kIlM5 zOHM>~jJDIptJ+;_7&(b8x!gs0F^~`o5}cObC0E{f!ljjaQBLDshWs8SC=qhoSuC-H z&@K@oZ_O#b;;@CUMLcRtnsa3k!666nQaFcaSUb|Bn)QK?;QL2M__ zUvh;OBqWXRcjMa}z2r#pPKM){1Y3~6H_$ofO71_oO#C*R@8>w}y}9!kF9urhxcDaB zjDZAt@%W=8IApxYM-j7yl<&KVF@7?Bsk5#d*5p}{GP|X52!x>LHA3pSdjRml1H2x!QX3( z1_P?t#?hO$>`78+K?1)h(;nD818$7#-ZBaF;xxzRFUm9@?wMXLao0^(Y_uS;`!A2U z`Y#i|JvLhP`E=x_ZwE}Z(Sihi^QN_3V@A6%HWW1p^x`zes=&)S3D3ZC%j#ih~v;c2avV{iQnt;u*ho`xKjM5a`86 zV#15DD%I;H7519tkbcFrfHgv2cuTqGhxNtOQAS-MA?J-ZTO>CEy*SOe@`#3gdZuz+ zCHy@}^S6JV{m1iRWF7#g3b4z=LQ8~u-X|^_&Krb#w!SrN*{uP!SEwKdmU9aSm*PTk?x*B+Ol12jS zr^%Rt!Mi9%MR$%@^Y2oe+12-Nel%;GMhg-$XM*RH(JpDbr#WvtH!G!CaI`_7*I)H6 zrcR%ftiC(IM5o7!=h@JtO|#i zxch3l-Z3vL<(|=L4qA|qIbPmewVmxpYi^GYwWk>bdU5)XX~{}vw|VzgOra%~DE)M@ zl6hn<5fVZyu>|)Lk9d}P2YX-MdoYE)VhQ#dy}}Gg5BZ?`j~=P~0YB;aU^|)7}~rp9l#dt52Aa)h`y_b}#A{Z% z*6>?xv>;*D?o*8>sTzO2u=Qx~mxE|Q0@rEKT1#3-#_f08_N)jJ=!L5z=&5VuV3+vl z&kr56Ac5;mawpIW*Hh5WMjLK(V;ou5RHFq6TsM)0=>*p zGQe!?uJ+xUWUPrn0@p|8PM{aAP@$dc zi_LM{d}*0c?y6{6?ScfZoX(v(%o`zQ`tIEHv}TINr9F>)isi;pB}FUC7mPc?Tpci+Q_1&_;VzKY5$3(_*l zg%B@}A!%BFK6aFPFl|ZXQF_;hYxvgI>loa-vVnS*R(;}{Kia>2Xnl3dPXi)<(3?B7 zAW>L13yzI6P$S*d{cjUtof;5vVhHrYwTraV)UDI(S2i!(`W?NwLkklBJXAl}@2dtX zopuw*oj@;KgGm}Ag{Cg14QOa_lKM%_)3-Z7Syq3G_18zSel8 zzW%BHNFcINbFx)Eci&m-74!*Ue)**5o3thA48xQt{Q_PPR~juyw7OO~nD0yjb!af}IY2!zM*_WY z^*U*D+&axE6IqsenBH!q1&I#5>Ichz*+6|+fn!ilbf_nCn;QgrnXBSIEjZ0?@#|Xd zyBaM>yb@^^d~mCj!zwh*-f?d2)PDvx0fjDB@yZ+4qA{HSFu~LbY_F>ew8DEUO2|kUXwKXJke}P zgnEfF`XGVh3K9Ma>EwBH!`N!rOKQ`|ps5AD-hPHwFE6Dv?qiZ^jXPM7zI+e_880R8OjVUp>o6$=!G>x`wouF z48BD~_r#1aj+|JdX0BfK_XBt+WY!fD*fy3W#4kUa1bShOkm8izf*JWT!dQzqCYrg* zPdjY9OXaBbwiyEn9JOf&On=3CEP-BFBec!7E@0PPJx0~u-NKpveMh@r;Urb7XlvEx zYzKQFtytdj?*lPA&=jjR!!G(mP5ZX8!;LrF{4PV@O<&vE!TzRaq8i(Z-ww`gTVKs7 zSJuAvdOi0m0DJMxnyU1S34p`GLg37n*Gg?y7sy5-85Q|FyFWTvtxvM=45HR z%4?I|clz?~9^dIt8qn3g(lk+>bk``ht2|PDShS>_(LCg!1&NBgyVyn35>>ZToU6=- z`>XL;+wFw2j~WDe)ydn{PMegdzHnolEz(6Ts{g0GqvtdSEl3Rfv$MT_6RoMw&*Sdw zo7<>8!5h^4U2O~ky)uS$vC}ssst?>4Lk3k>4-5>dd0$m_(1OGxZ9ChmFC?nfF7f7j zJ=C_*mF)pl|8}sn_{9WsNMDpTB&%u-s@o+VsiVgFr9L zAt@;np+3HBcOn8UNK{$T$)2JU)gx=TJsS6)ZQuFXNHw}rw+QZqv-#Ujb|_zxdWTB; z?8}|(UHOw#-BhmKmJ6@hy^i)!;rD-upaluDt|FED**_f`r4~d=8s`Vb!y}QlQ;iI} z`@B^9*M>ul^8?QbEE7GkQFDEwG9%c9%5>^lI~S z2Yct0L{;Jd6QOIRRo|Ois2#eEgSCjQY1UPVhtAoZ{%WCiZQJLd1qsZpW%cTQ&VKw- z3ze|lB+v`TG1`ZIe1@I(8R`i&^J=spVV2{Wqs{CWG9FfG`;QxKj$SxElJZG`398HB z^7cA)*Jl25DBorAE8^_~yV~=bC92KtdgrIC398XO73?;7rfx`d# zPjsaB=U)05H+0=>BR?52H2rn@nk zPOGW9f2CCUQeDDmi6yc}xM$Z`s`LFl)%o&c3<7&)&m*1e$uu%dbz`(%W~n`$da8YI zr-#vk1dbAxRd~~EyK2=@>Ys<6G6?iCcW65B!fZQV%~9&;m1m5d*kTFU9g5!8W@ZI% ztCgEa}GWiOg)yS@^q=7(Spatk%;bnijEA{tX^I%DALLx&};AOg@RQo z22_Pz9Ao(NBZAdemQ(KyZl%$J1dfk%54W#L@c1Jq?5@-M8w7ea8C@v&?ZsqOYc0pP zm+nLs#`r(3Dc_L=sH>b{5hJLmQfdMKw>W&6FemyNkNILl@=-NRj=d$`W$ zI9D?-j8Fq+l(4IYC);R20!MJms#1N1J-KErdqL^p?o0>y!pHZYlEY$=4))CtC8`!P zIalTCXV_!Ur`ki3XwLz#AYqo{#rtR4N7f{$iyPV)1bY2OSLbqj5>@vm9HU9=nfA)H z392>`XhC8n-7W3dmZ)y4!o(f-^|rfpYOU^CRm33B3)_jFaoW{aN6+7E7h6%!Xam0M zBaV79_CNX%C?mRn_7{m+j3X%NPWDVGijDl8Cy8FWWtd zKnoHn7dqRgHYci^KH)acyfQ+iY%gtFmnPZRws_q|nlvYe_gA}~*={eo{ZXTrAc5CM zI-`=hsK>th!|wd=RD(b-Ggq5yw^7UJPJhk|t!=a*fmc*|8#Sf6`l^3W1@FDpAkYi1 zkF*bcu(!ReV{7%(yG0bXE!G>Jk2D|d)pPccVri;H*?l%zkigv1v%%tXc7x(+>Vq3i z0=;m=AU*opWmMBrEmZrGt&On+39}qaHea(Bo$8^s7XQ&0uh0v}F1il3Xr|k>NV5n3 zRMwos0`pb|PCb=+HE%%uGJ~&bXA5No_ti{SW4E+$np`Us+)vlkYIIG-eJAl6Y*}|E zR|-C{>xBK|Y;$Z+DOV_1`mbb_kFEfCU9qgUr`(|rKk~hOtzT*5`hmpM<%NP)?|`~^ znXeyjo_-}bu6equ@`iZ_fY)}+EuDkKmjtV=>8FY;{>~@|5_k=^tcC@e>3`M~R*nC9 z-5}7*%vI*-DZ%Rowp4d~UtXgH3A}34j&k#c2g}qfuYRVhGZN@!)>WU+zep{+E?vFw z%mWVY7K!b#{JZOdrB~B_eN(vw2QFKe`tZN$YTuw14qA{f>uSr{Wsw1$+N-xi#WfP> zwfp|7sdo(ysFz5^g2vr{)w9e|c z0|yKOz4BK%n|fkcKs~yWYxnOKYn;SCx~LaBeeR$I39NPc!rQXAp4E&-(XJIW66l4s zKu_C4itBgUmQXiND67$e1lBq|(f@p>p1H4!{oJ`EgFr8{cJIA1#QF9>J$v}s5ymV% zB+M2ZT4R#)#lB8<)0>AG1bX2tMEYWK=345oRZZ>1Ma}t%1_AevbdBnnk~;O?7Iv*d zCV_XE=AC7@kmXc)k)CZE^pD_fs@P-xO1zM|H5^b+yL-@my5ef&_tz$<=br2pK?@St zd+1%?nmoEyiEgU@{z?uK=+)rEA5y=jJ)U27V=O6{M}M%QoBDG>c?T^>U|*oUKMS|g z@2xGaR@5J45a>0!z>(Bp1p;c58)HY0miqKvB~{;3eH^qPfxU-jw_O>k^A2rk4?8u@ zAkd3v1!m7^{N(6R{bJ3I_Mhh_J7_@yXH$}f+r-nU=`S>~zrS;wF%t~uk>MRD?a(yf zY-;(+&Fyb3lR&Sj)Juk4N>(r3#giQ4L{8HqQ^g45S;x+2la2bs6q=8c)vnlcmG%r{H#Vt)$N}f3tS&DN~o6G`dn;(VfBd>3EBMa6>1xaC%?tv)%-wWbq*_kl zeg-E`NuF$xcBtH->0qiWx`S{N-z;8{R#KXM_^i_^~+q#b+R7|HX} zb(>$>*+&uvZ$=9ecoxvkUql=@-OeuZwMn2Cr)8EdX=UuWNssH_(f)gN3u8_y&Ni(+ z{Br8A7L8ZGaxY1y7A#IJIIvc?M!4@e?(4iU=|bu;YL7cc@YBRDYQcllg3rG^b2D0y zz;?2%MbsYcs0BCds+58RdNu#(ht$i|9$Q9ojB72f*UO0b{ik{TIpjHd>ItTBolWAFOolsn%6x{`{3epjXzHS5q?{ z3#j{6bBveiKJm&2oz;-)U)yLw0^7;5HdQO44^JKky7wn+k>t4*bIwOI#PH!f9R&ug_Evmwc+8P9U;oXO2-Supuv*`DN>LXfH zhZZETo#=2&enN`u4CfBaHhiB=B0obJe1A=-pi- zc!n9T?&p>FoaTK7WEH;b2VfGiGeu4W?o!~zLNDGgAvQ*o2(drsPNK5~iP+s1+_~o= zW@5dhOgRz^82d8_&7~DWO71$-KcQ$&*ur~G#KwpcA&>D0sVgL8#|j~`%Mt6vF?jcb z90@lJT7*U-d+!84R~o&fp%Hg&kmm`*t{w6WZ-Y$8U7+l)_CSqeCA$8>zn#egvc&OtQW`N-uK^xw7JkoNZ*Z?L!p<{RgQ#|!zDNddm$kukH#RvTW2CM zxP(GrT3V2E+jABs?l7g1z|n*!|(M39;aDIW50iman^{S$Bz_$#>RF(yWTc z>kU3%o1|HfgVzPL*^;DL5hJRvrt6cw8d`X6{`#Fsnw2l`NTliQ&1lrD&V?2vcrCzR zS;^W{8S~Y-G^=wVfnI#4wqjdAd+J=i%9s|FF*z2msA|6{S+lYj&pe&gFQ7fOG+$** zv&tA+kl>Y1>D!aFrRMx7q48X+drT^RjWCkHlRLPdQRA1MWtDnidQ=wrn89k0J%>e zu9c)&Gcc-mr)T{z*VS;Fu_B;Z%aEV8*M1z(tPRMs@g1rwFUF<$%Yx_XPSQ=sByK?q z68^gr%_@WRW_wg-a5L5J{)wK}mK+PccsBkg5$U`6skf8ro8J62%_;^95}cm5H=sRL zL|>iUqFSD0i zqH>Vxn_du^XS4^l0k4U>by2eR6u^9SN6qSv*lN6%tkJq8&FYRw(^D$-64GkaqWUIn ziv+J2>#{mYdnGS4is7x{mGfK_@{kZO z9Oo^oq~F_n6rU5u9`3Jd)T~}+_I6F}@iLWs&WHuBo|l{lNSL*I#4q{1bLJWZdht4) zqocgDfcARviAuN3aaG2|f`r)~r~NkHNQ$0#EcD`4Hy_OnXjTxVU2dr4q#CNH7M$(s ztBC~(9{Eac4`|jOrMCtYgOo`%E0f}}(2G~y$k`m#YSg0DC>A96ox_0L0qvXD#bbM)lPw<*f}bHMOpmHRqh> z{>uG$)YEm{o*z{*Q>WYl%XT|Pggd{HGcB}!&uL4rr{rx(?A zM{t@!=c#k4+N;~RYH32Cm*mPT`5K=X{pXXeBAe8SLD1;)&9Ov(^zl{Sl&HQ5!M$C) zu+~Xu)Q`a}$mjDUYAL>NlhVo>RnD!q^4`}zQ=)wqORyK;+a0BP^X~e5MK+^7WbHiX zklTQ-!Fh`(`FBgcBAXILHnH&i)d$xnxp!nzSKeBEU&%~~k{KVDElBV^(YD_b{rkk3 ze#t)_I@wiA69T=Y7QB)#_K8Ldhq;PuQYT38eW^oj?rFIBs&7hE--JLfv#z)u3lfq;*^MMVS4^On)QC4;xy68|RH+lJX(7C`774T<@&9WN^pYdR=L#)I zNLqFy$u4D?i+!tiusO;LsW1*M)9$#{_AR%elX(~Pj9}B%Chu$tw zzN%G-b+EX0mo=@Xd3RGzryi^1rg`U3PRA=}A%R|;<|7&ETp`x;LJJbSb127%R{%o- zy*SM=43)7^2I-Qa1qt3clw-sznIVB*oaPvYT3U$p)zE?j?;Of8;uYDDKrc>n3`6xT z#5!?kL4tP<E7`Rul+vDA{Q!MDk=S_AD@(r;+{l_K5f&|8ks#=9u2aEUeWrFwL z3HQVB+!e~d?Z7iE5v$UXhDMa%;gyI3SdZ}7pFOfp)wX?T{5&F!F%R% zjCdt8B+!e~9K%pc3$eZ$T9Dv9b2&!5A{!Fu#c7UVsJ?|*Ck`!0@GiR?BVJh!3H0JL z$1v3ELacX(79@DbUXBs3kcR|%ahhWoDtsZaX-99AHi_;tfcmH;K zyQ>W-$Kt)bB^^hE*q^V3XhDM07{mR_5Mn0Qi(|+h=y3!CE+H17k>IrJ=>HRP_d1v3 z$~l-L5%Lg^;27+Mgq)iaBm28rtQW_Vb6$?bM>h$v2#o}%T_RcnByw@-@TzhQlmcghoPC7fgb4CD(HawYfFoGZNd zrCpkHA*$D_p?}TmslHuaP*Yb}+&6mnVZ`7NZpkG&$3Q}2vtM>kWG^Jdi+_(Rd5BrG za2koYaxmZ$V}CBKSwW5o@#6G>vNuMb?#$X1ODrMv#z)Sb5HF^mC|OF2UXe+Ng}soF z{uUnt3GtE`Irl^+*uq{&VBdAGwIM!F*o!UFU!}M6)meV$T*;rOuO=3W!88*>vv>A6 zh2L7__Y%IFU@z_&l9t|+Gr@f{mN5F2`|QElV=t*)Ny|4#tgC1_Ttf28 zgye+N(ktV0C6-ts$6Ogt!c2&l#E@s4Xs)6JTVe_6`8nrG2=QWC&YO5b+MK zS0QH65=%(0%sGa%fp{@3?G#UlMPl%%&1pHiqC|*Ocr5hdw4DF(gjiw;tSgstuOSjc z${{(7J!_*x2rWX3j;7G;o&6*%S2DT2a!=$m)6y$lf+4rZqXn<$@;lzQn*>{skTl-O zAxfAGx z&pRf879{YwJ$C}V@Oj51(1HX$x93iv7e4Qp1X_^DyRo5fsDI6bBNQ?8A3w1b2-I=grwzum*coSF&cx9guKnoK1Cd`b11bXop%rOk@Gxt6b zYnNM)z4)px^~UYw#t3nHa|$g;NLrrH**ABBz4%^><3(dc3AEsGxwkVB7sJ&um1Cio z9Lcy(bjyJjBqVLzCo&O@!N)=`d=ti{=0CUOu3jqVDwZ(cA+x*G6&?${@QofHpZ~lV zXh8zsqm97EEUb@Hb?>h#LhsYj=Ix@789JuUkbahkQr%5`$!7#<6~_;)6} z7_6_xbjuEKgaE`!3fBdYN^VgD#mng9h7%XG6#g zD9ef^#DWC2Q&h<;z`A63EcD{}8ZwhBs$`bL1X_^b`7DLfliis-wD(SohMOD^ zH-{yb;JT6-LULT0GvjHW6(fx*?pME(Iv3AK_;XsaJ2ygRC-6K8nVsM%fE{l)TG#70 zX-n<9rWpi!@y-;ZrzUGp0c<~MRQ29?S4vk>8AA&aIKzYXHeA(G4}S6G`k(cwU=ZlV zt7YGtoUA=1vvks^s&qLm`7KgQLkkizzsQ^E6lq;vzx&9%l;)FL83cOyJGW?0k*yJF zxMe;!YYS_*p#=%vhoug+V75-&*y{TmicXwZkTBZ=wdn9z=!NaiZRfr7;S{!7POT|3 zQoJW^B-j#5lzBQ?dqfM;yJPRcS<#(BG|$YETya{;C=xjG+YyX-!Ybtj_7O`js+C$x}1#Hwg6NzL1}KqNilG zmwMuNMcdWiM`~$kK|*?^Hy7vYrD^(s#&c3KwpKI<^zv6>>q@R78*8`~n>J%hb<%J{ z3lhAJo@+N-C+?rO_BRxrII$ohE$g)hYSH1b(2LXAE$EL7uJ)OXK0GH)#t%+oYg!hn zrSTXg*HljPxFTw4oc89b#j2%=MaD<=!Xwd2Z%-|4J*%am1qsY8?ax3&y^7o82=wA| zkm{S;-=d?aTXM9-5}aF^ZJ2#VNlrvFjIRt_4*p%r$7hB~u!ZMr3XN%RO+zdp>lm1j z)fGbLOmI$QMszIUt<8vyfdr?eOp@FGT@EC?Hm4YLjrRVeM)``vX+Ex``PyY@pM{ta z0<_Pf1k*BWGCl?p(vLZYN5rag$to(Gr;qDG;+3;xP~ zm9xZx1kR4noj@;6XRrCGwt2idUGQXT$1gp#G?}fAHI1vpOzktY#1h$S8gi>$T+@K{ zW?7Y*dHQN^R(UyyF>tk;IqM#E;?RNwu5h%h+z9l-8Th8&9a@mUwTrnE=!G-zX+@Q% zeHLQvGi1XWtl@?hB+Qbd>KhX1h4p4CfZ@sqT*Hg2 zfpaI&%Um~s+Gl7%!d$PG8-ZT9BF0o?LkkkzvT|L?oj@7wu!m#4nc8P) zK?2Ve@49h)^U*qq-Y@Z+6dv_?b~L|}!L-aA`ENqJ_(+oW2vD-^X_?{i z--LK^3`u(gmBFF1xG}`SF)%IPhyR-pFODJUsQM6VR5`dFn6+f8uWX=M)d*K-TUI|( zI4bTbXKAz`!Rk6aw>Hq8epF2&>U!#227z9QjEd>PW;vPrc3{ z&HS5r^Fl`*j(f&DnDOQuE1ObGPC zv&*u+qm|yT(0b=@ip>jS{a|~TxoS8zGq{?Fw?FZ8$s`66*kdd!53O-0eKox@hCnZ@ zk*HdlX0t%@b+GW=G`D3;#Mo?My4_*c&H1XhFh!L+`7l zIjok(Z$J2*w|qC?G{5C$osL62DOavqny(+_uznO;uuNt-eEleg^`nqLFV-8m_vu7! z=tpVRk3tI)tdBHRCu&b?%h!+6tRIC0da-WGjt>*Hp&zALKME~Ku$s%RD~a0EkMecm z9M*}$R>QWz97c7?9M&a63li8)w66iFjP?EavhxzDj3I$um_vFSMMRl>mz`=vpalum ztNL;i?JVGGxcQoTnl<&XkFq|_AX;ypt< zAthbqEIB_go*CnBQa)LFT^VOxm5{5D$GwlgZLu2E)uxG>Rq?P)QN25d_3qGu1gllF zoRp{yy*r2X?vOw)v#xx-J3XKD?$Ck+>pYFykf;s4JI#7`NT3(%Lae!vs6D+qUjaeO-7>-Z}GfA5baWW=DoMV4m; zPnJv9JxOH@dj{_gBRh2A*hRZ?y`2>-UMpR{NlIpDL4p-ZUdRe)Ps!}3F-wDmXZF*d zkjfYm=!Iu9J*7UgH2Bxbe!Az1?;Nxs;VYDAPsyy?r_TjD9!t}CNo5QP^ulWwy&Wv@ zeDJf>mimq(<&CQv60B*m_2Gc_l*~3x9uaK3vYcK=Dr0yo^ujADsR`aPGPvw^`f_<`8X_vI!BUJb0rJXgeO?Kzv$Qgw* zYs~Y!`<)}zH%&`83#*1~v>?G6RTt@A)KfC+Gort;rf+vnR(aGQ(90aJe2prHHLB2p z1ZyyTzd2ER%2~cfm1d19B+$zocYTd2%^Fo`LBhNm_!@2wYq())v28GiQI#==RmRYQ z1hx~6SELzs`{B#ZBGL>)0=+PYG{=jG(4ouDR3gxV1Z!gL+?J?4eKlWGPqU^T_EEgP zvJTd1+I5Px_AJX+wbG($B^D&ix*FWQpWXhKQM&vG#f|d=N)*#TUKRr#9y_TrEUgg^LRmL={jA1Qe zYnpY{V9`0dc=0q{_U3)AE}66k5@tDeFFa?zMuZbXpqHzW(0UT{8(uSBFh#i=fZ zY5H&X=FZxi#%W(aNV9rb?Cg~6k$UB8w5wwvT{nEy(#kW=1yVBG{cbcaYyf|;UB z>R#!QU=^)Ay#w0QSL;>jTI%yz&72w6dD@v$LcB&{jab$M>y}`(Pfj>r&+2d16yit6QcLQzjGP4bHb-VKo2CMmLw7}Qd?I_W90 z34vZ_UEQ`X(tNJDuB(TR=)*I^G)FX$}^~vj6xyo`vpqIIm=foe6 zrq2E&U5|aDg{xjCJHaA>JwK{g=&)iT&Y;7YZmbM-EpI@3iiJ+NhMu4Gs#AAG9aoo3 zEJ&Cw_`qEyb?IF<=!>_NHwg4%g{$v|1+=HgcCAiPeK@^@Uh!yoS6@vmNSG~Huflp~ z!K%*s+45hy8g4?M7b|s@*c8y7vfQ4@tDHtRb=7D8*zfAZi3JI>1z-K<*~q8!$Lr03 z(guNExXY?#&FVZOGHuy-owc{Lt9K{6v?5`);C)?(=}AsYCvWX3<{U_v_sBXn!wUqo zry2Ie#G!h4N=K*PJDviVSgOpg%X+T%l}N+o6ZF(~`nt+;vga-mW($5!+Gpcl zXyUN;8Q$IFd@sC5p)WuE&!)amsk!qTX`i75iK#Sd55JVGJ?*nHm6`;zN*{NAI@I4F z&y-yK%G_L}sDjj#~nHK{3`>Ykg!yu-f5r`txS345B=E;a!bo zUFxB627z99|3LQ)Ri6(& z@r%7u|d)jBdTAF5kHMAgMp69s{=*4N$4AY*5o3Hw&StkxH zNSNn&ZUlO9nzYZfr$y)M-RV=LUWXPW%=0`q0=+oBhV~BkcK`mAG{XYFv~$|~nqe|i z7TbpPs$Qhp^_0wZ5%K()c23CGB@+u0SnHN`FKM4Oc=bko+Sfi40=-yw>u;)EPm!%5 z5iN-5>+7qD1qrNm`bJNxZ+&<6(5rs-G~9$hFV+t`PPOYP%jGBHEh3ig^mO9Hf&|vO zW#w;dIe*bkR+F+kEjl64%iMFB+auq<6ZEaM));#(BVo43=$Tg|gL7%G^yMP@u@2jvciP#;{C1qVj`cU3-uJ)N+w~@dy(HyUf z&qQ8&YP^1INLd@tB5V)r`Lv2IaaJVr-SPVDwi`v`&^_0Xz&fOv18d%O8u#g}_wM<| zAkYhYKFz0|{;ty`p{t(s@P1e0P|h_ZuuRl~Nk#Rp-Z$vcRVyhx7J6ZyChg3AMfLFq zOX#ONo4p+gY#VwKo>p6bxU-A%W}|>{exMhwJ)ynTzwPZ*ESKnvUOmz{2a&-0Im;?l zb(j-4*U33@dYD0=7v5!hGXcGSLyC7M;CYX-cY>s4#{%4Kffj!p#_3ghm4QXK-_+(M!tozX>h}dm$kuml)aQi1p%<^FAXv5^g!rA~X`w z9Zy_usa-iP@0THIIa1C9mxC=x$Zi`#MAtO9d!)#5h2YZWN*MdF^ zPq{TMF>)rPJ&=(7QiRAZN30i@iF;qJMBF|sv4r&9XgNf;%RR1?31j3;$oYYUlw64H za>ROZu6SRRT#0CV@UetO0(Vv6vShahTcjucZ-UDaOGrMDCbGHi1xx%6G>)6v$`oDwf7t+ctslX9@Hx2g&)LUT?eb~IOU1fOd{bFOey;^Xt5 z8AD1dZ7xK7475lL&U;+0LVgTm+(j=rlAKZ5xk3vPl8zE_G1!7$l0zANvSXkH390EQ z!7=FB-rV7j=eNr~fIM4W_6lS_{xb>QV+RRIXYak^Q<{&(yDG?jmXekj{JZCigye*e zD}=-l!fS7)s!eUC*{f!9z~=Oc^n_?yX!eUI_*k(7)6p1iJu#d2uL2P{7NIzCJP$2#Rytyl7);CWQgS}J zS6^sBLefHH*RD^vZ6Gwn$gbUJ$%Wu!^j7P-wK8(R>&sPY{3CECrjJ?P84dq0jSMIq&3lh>Rja*Tj zkcuU+79{QE$Iq3PymP(#b>+6Rln>j3nUG6xPZWZW%V~)nPoRZk2qES8Zvwq?&lOsb z;Iy3o(UOO_9I=FWVU4&1dq;bs)S|@THo!7T43ppzA|Yukxpy97bj-W_j%{udY(YZO zNO0~#`tJeP>6BxY)ZMEhiqo$(t>&hOwVof5-=!QLftFZ8Xj+fssf?*nUFU>9Zjh!+ zY!4_`<7`_q{o&kzVuiFnzi+OmuLvmCCA6&jW@H9u)|{k%zds{<@3=I5+pd6OO~zU) z({#x_0mWK<%eJQJjJ*NnX#+O!l;u>o^t^D55%=lzUIE1#nVYT;>S{ZZ6>Bw~-+rH- z*)O0xea?n{u9|L~8%7Hfcb!kwW49+OPoMJxB1pqcv36!T%KM}_0mT}b)n0C@w~Y)a zR@)r^Zi>E`m8=Y%QS}XJfT9Hnj7>Xb`?*@&;#q@0uNOzB>UNuw6>E-KR(GG+aCb%+ zEl8N<*y5LC!lk+4M~7C`>vkq7)}ngj_bR&emL$cBTwniILGP%Uq*$xfvaXQkBxyCO ze8=a6*>b2>l45Pi`SYvjhU=0PD;DCmvP=$O%7%SM^~Ao3f%HRcy7Zqy@yK3x~PFj3w`rOuZLrqyne+kI9<6PKpj^=^A=Rh$yf{Lj+!G%QFHBAD&&KFM8`y$@RXIbkg#`8q%?wAoq3ley4T2?o|u3oqpPskZugZfy6 z`k1E_`>|hFi%2gOEqGi!3oNUuUyk4JdNGV+M*SzMYFaz5Sj!gMiPn<&Bg2>9n=OdM zu;MAY(xPPLDXgCLiTU-tekHvDz05OemfsVP$wk9i29eBB4j-GF47zBD1rK``8QF7(n z>=T7XWQ5Uz1YY4RYax}K%TcS>T!TQbQ*`C5(_h-Wl3!O<2WEuPf&^ZJEo<2Ey^&Gj ziJI>k_{tAuMdw*}_ z5D~p@nx4$1U0NW?t;M#5f^=t@q<9As&f(4yN$%Z%Wqp$Om!Q;XhDMe*ui6oe&6*KB=wcdAJ-#+ zUS?gr=4npq^KJBcv>?If%2SK#x@VVV?IYrS%GHp2-!cgFGHch@0CihXV({)clIGEw zN9~E!vOLaPR>yDlMrKnCYVwejgKJUJyaNs2mn0NV^6#&zeXuvOpNOyOty_;4B=`tl4j`W&I2!FMu}Lr<%5jNcx;lWtyv79{wdC_;7R>2to| z*Y39doi-qWUYJ9gdFB(JY&;TeK`t#4d?%xSOZ4v(x9;5=*+k_?jx>q(5+=~gEIHSz zJbxT~AWhSIF~vK_aZWhR^t51GH!TVk#Q0AvE&gfgT6pKU)EB)pYxw0(paqHhuX(Wz zl}c)T%R&OZFt_Z-f8JA(5WLTX5WH)d#PfC+LqbaHp4&8*aLIXOkl(o$Jb#IS7H&-; zB<=MQ&eDGo>?OI4uU)j@aZlx~=*Ba2M&s%Vz4%#;a~KyRv}}8M_gK8<=aaKunpZ>! zVW=XyG0=j6yv;|TPU9Li3f*>xorE};;-T2^AmmBW3jCM85da%d>Ua;`#n zEcBA!|9>Ut<4PUM{-WGdyq<{1LN7^sJFBw4PlTl8Tqn}z+!OIgo_|g;kdPkgT|Yb~ zK3C`^{Vl%aXhA~GLD^R=S`G^d^uqJeEC-&QGOq9*eRw33KnoHd-_pwMiLx7F&bdM_ zIZ}MTLJJa-Hgrbg&O!8&9D2KKN=djCxo!C^2k(x}@g&W^^ZOFqHQOr-T9Dv$Hu2-F z<0I_9dFmwH>~-&*4DXuFX^z3^#ZP(ZJKl{@?sFs1i_;v#Bf55)=*E~infAW|3ljK7 zhwff;A<&D{Iln0y((j&V-mx6~I}=={?7F4e)o4KiYs9Nnp9@J0-a}o|eBA$|>`dT% zs{a3fl{O(;_Nd5Sm@zY$`P?hA%#baVEKz7d_I>+UvKKA1DLZ`;*_ko-R3s@%R3uAE zi6pY*EBxQ@bME^yuk-oL^!xtj(Q+R5{eIr}+3q>_bMLw5C1;Yo)y>t!6k4()Vshp2 z6EAK9jKOJn5+*T%JW($}i^LF`OD=?dY8NIhEHU^woTM=ZALsLDJ)xHvIT4WnF(kjy@uYmQ2Vigw)}`6XM16tt+Zg->sfan~R0LkjS|`kPt74 zA@3mVx?+MY?1coUh2XOAUs&<@Di%&h)3Jn{mo3qR(B|Aa1O*W{;U#TjYx3 zw2Ta#j)}pj&XriA35m^qb_^uMi)kreEFl*5LL#Od8f7oJia0G^oR;x15`z=E9Ab$k zI9}vBm-f)Li-dSFE!RqH46(2m5^~-AJ0V^YL*6dg{fc9-g}soF9?CKJ&rou0;~OlV zGooW;5oi$_37K&;!J|qT?=0}XglX;zcz5W)mmHU?HY-EGJ}2}#SH zOeBW>Jt*~#Uf35*mZSxT_sFaJE3X79Sn;aQeHYW#S{&|I&V?`D&|Yleyi0GFZX%ixS_m`a;O{;mc*NmcF=359idpR~>s+A)2}xVCL5>7_NnORpKntFiX9mt~Yz!pO zOOD632U?Jjv^8_;a%4xa7q*jW58h9f^`n@OyCtqSOv`=OzZ2rcXOgrbNYzTQ4i;KC zhInyW?jQf15HCKHqzy5R_7MJ?c0EN4o|n`16_pbqUVJ7=(_R*Zrt*rl@TKvCy`O{U z(frI(p1tx@U_S2tT+=hpcLTx^LM%vdnva`j$g8h99+&2wyF2OgiUo8&N zjb0hGDT6es(1L_K>or1q z<2K#hbG(ZdBSX|SfU9YsSS~^ zEtgjyZq1esZ*^2$qfGEqd9G*Nu6PlM{hnoaS5^q6X+k@l$zzJI!yZz}z~HOXbLXf2LN>!gHY) zm*ckK3Hsfn<6z0r5>0U5H6=&gB_yo+X_KlRpcqEmY1@y<{UA+XGgHt$HAGhw4H9fao=Xv zc0!B9U_xraC{EQU{iwGmPEM|HaH>V1*W|7dU0R4nOe{&XFWpdT!X_IwYHHu7g~^zUTGA-68KF*SN#4|MmTw|%3~KFcbtIWF)^~nBbs2E=UQ_o(}y&wKK^xeLUx3B z$w*}0z78W|bhAC0KntGNE(eTok(DldF7)Cvao;sDq6x7e!D&7&?`yNJD6A_Psks*9 zxU6T0CD;;8$XYCJJDZR>1J5h8S(zCSVP?^i9bwj4W*39cB{X|+I&1Z3G$EE~LRM*V zUb60%um!OVcLL~VwvxgQW>~-M*;Y1VYh3m2$=k0Gt>KM=Tz1u|#5_auQtUJa_ z{$tjbAG*F3LJJbOj?i(A(>iC}j_a3ZB7t7Gde3o&4eF_h)8}^hXh8zkL*`7N7q0iS zb;;0z1g`7MnLsaG6-ayIzTQ@UT{O7!aD^5maD8gd1bX4BKvEJgI#>?tVBzXN^ul$v zv4pJIMFQi|@4#_0^=#0G^rJ8ao)=dF=S-lNy*}~Kq9nz=q$25Hp#=$h&2~-%dg01b zQi^@k-23b-HqJ*25{pck&7wAH!Lf&_khk~4u`xPp?t$gHz$3%B|AXUABhD0<H*SKPm-M6fNs7Gx;O8)ymiM2UaB?EVi_au!6QdR>rmqd2Es2F=U|Qa*nix3| z;>9r}ZDNRGI$Ah}cyXF%xU6+#IT7N;XOcAS4@cTHV;juP{GRFy*MC3v-b3p1@@?n1*UtW|C+0igF^*3)j6n&ScUO`eVa_E&J%H8d{K; zu(*-x_Dzy!^okago#3wjc)^ylQH13M>-Qa}Dk&UQzO**wA`!T-8*uHXuE1)KKBi9j#>`p|Kxmw41mGFc%H zEl8|v|Bx!WI4P@NWlNwJjxjlpK1krW;y5dVZ)Iw{`BFNz8upS`s09_Zpy};9g0Gz} z7M_ug79_AAJB|=Ty1!%*=!I983L?PWBp)zU~I=JV)UcD`A6*-NMMhl>w}1Q z>6@Qu0==+C=)P*?;?Oc8+9uCP$B`3j)XvqKTE5p>1!9(62fm69cN;d$?nEumE9y#oWkeP_*C_we@d$Zo#H&B zIQ3P_THe(HCER+8Yw9QT@{Apy&~NWiT5WGd#2|hGIcvjpx9l@D+_(l zOKUrQd1njn`3CvCgX>yY1bQ92qqG{nA;MT?%R=zY^YBLXc*{4=(+8mHnsqZyXoZMys5SA)E^W!h(AA8j|Vvj%g z+nC(UBGAjOtB-3=a%&YS?1kDiQfNV9=K0cU>y9|j=&N-q)62c%?*?8a(pN(Qz2eT6 zR-asr^NhY)B~qN)QoM=R*>B-vEn;ihb@c@4V7+*$iFfj&T|Qcnz}Tep*M^A8O}v_< zgM|co;W$RxnImSnk56e%-y+|n(1L_rj&;8@a?8Ec#q+*9YPC6f;rQq{okzK#2Y?bz}u2oEgdaL;HX49V3O8Wkxb8Pbu85)(2IM|r}T}g(erv}Vr6gk zUeCL`;G^kii6*i}xH_vGuSxSx-rZ$}S_JmW2WXTSOCy8PC1cI7oozdL*DDTBM+*`- zN;uBTo2I)3%MbPzCBI-1=w*K!-jcM>N>(21{dRSV^{sw1Av+7uS2c}JrHpRTz->>O zNI1XpGj@4XiK7Im>Q+6S(&*bp?p)GDLJJZF9!ga|Tuktc?oyQ#^+Wyl9C6Q*wi6QQ zg`)($``^_dbkB1?x=ki^S7sCy913ZTxTgGya<&+e|_cHiCJ<2x@N;dliN-;r^e*T$@*d$`|Q$9YE8 zs^78p-osn(aSv2+tTimSI^_+zzq&y8S4MH_6;hD=X?j6-$)>R`T9Cle)p6dcIN7aQ zp^E!HsdM3bF3e#)x)&|}M4V^Txx%$(xa;K9X6NG9<2<8RG^BMcFX2pax7*^HR;%$n9Je5^ zJi;70&ghR4yp*mL-C7;0TNWg+ooMd_Qnm6AUUo;2sui9Ky)cK4Gn0rGKU{Xp5P=pX z66p^4=go1R(G2@>->q)F&xU$=4>WSIk5;2!ENf`L1lDlNOTT0m<&F1P+l`b@3O07z zZSLY7xcjJ!79{Mt8rij*`}oPhUeS#OT)aLo9-fJw4qhGT)%l{R+xqMn7yBsA?N}yy z$~m~Zw|C6P?z8tkXZ3a@a1M5yr{f;=;(z|jb+3)L2=ub+Dqocr-b3~BdDCBQ?xF<= zoV6Y2(zuFVGX0vkMEYt-pcl@;boaV=hMTaqxp(o0+#c2lWI;mQr z1qqBzPu1Qz>)ux&)qA9Ha1-y-JDXcAh=g5^xV6{aj9)re@|-o>A1fr|#0wqm_qyd(xZuGm}%* zUK;gTiwgHevPbIHdCP`w`}9Zm(Dd#K=htJYsjBFu1dmm;a89IG0K==Pi35+j4?kB_ zp#_O%G&?(86Fs9*6}n+g=;6l0y&g-O_!u4M56rFOw5vEbbZT`s@9%exS>-?iXE@qn zykH}B=s&l6B~C7~2=uaZ_4(X!p%;3jc}fnIT!Ahk(pY9ouKrgHj z$9ey&uT#pb8}8MZ^01G)8DV=oo=G*mn)Z{?+D=;+tV?*yxxW0^Z z$u7K@xnaaeuj!N$KJJExHGOZHG*w_zqGyzv?k_webLf(h-VeKr_-H`_>(FsVPF>@F zklM~Ww*NbeK(Aio($tUr6Fs9i_1`9I{J6g!^=7x-W(@aZxQHa*Y29D&-;7#*L1s{ z9%!x7L&9#syDEA`&<%kq&RC4St}ZMAMU4SS8n5;KReb(3lcbA(Q3){OG9JhhkIv86AABka1S!Pb8?(N zGnaX<0Ski(KEVB>2J;pC2r{ErH(vi5$J{Y5~O9iY+k7P{%&3w z(sn`%5_i*YwHC7zJ)#)VfyV+*BuX+=s~_a*3sch01Pb^mLjGJVp#`lL~X79@Jn zZ_a0)O!SNn*0vo3LyHcS^a?gC=srT4VQ4`jFFgb3|966CbjjvbJ(cp` zSqX)<|mA|cncRugnbhIFWSF_{fM4%U^|E68* zj1HFDx23v1w}@AvM}>5>ScG+*=SYATU;nS&MmyutT3*NLL7HLz`K6Wnsnc^aT5y!W ztJ!f{5mDnrEBD+Un?Ns4%lc%;xnag|b%ux!i|$Ou80dwojp;2wpO$JDmAq2P1<6*) zA@8**O}b>BQO;UJ?Xi^FW6e+Hld(OJu1mE`Dr26}!TOQf`~JNuzHBt$pb*L5cs)LgX zdXFUBWfACg^gQh&+$+&D>O;ShF4?^&Te<%sT{3JzY&9&C;~aUupDJ)mQ`cEB*+mNy zxcb|1+Ro{#=H_YRp1Eb3MW7d!iL`4-KkBJpQr#Vir98ACfvdmiZTRyQR8rS>+(Go! z2@>dqwct3NzPMA}^h_J~(+`?>Xh8y3e>={ZkpunW&(w0q4IO9^=w**r4`1o*FMq17 z+r2owS%i@cM>vd4dzgCl{TGTIcTZSMJ3ZiAzl+n#OXRV4*5v>;*E z)#xInGJCD*?v<|dql*N3;XR7u)Fp+y!ZZ(F++LtA&T3e1xO=nXEPDM~<{fiKdDAX+ z4WR`ItP#iAxamsfh9#rCcjJ3l1bX2f&-C8ln-?>mnKRN`U8Sgt79_BIj?+3kA@kei zBfV8CYy!Q~hvDAQ8P~R@bUrcMJDQ&Aq6G=Nt~M1ppR(opaIa^v#ukBIc$dj*2eZBf z;BU@X&>BJh#$D3plgzU+X9f9BKn^@?@y9RJPj1eKi?9aKA=xjkEdd~s9 zPCv{{w3n1ATY>>ia5*prmsSWVxpt=igd;g&3-7!T9V0@74PywYD zcn^SV2^|J4LL-s2gFuiggjBb3kj(!iIG)~XfG}Y?~#!$p)-aSp^?BH zHW?R>ZRym@*I0pB=eD15G{=zKM#>S1Azm1R z(?Z0?KnvzD$6SSxKrcBSn=7;+A?X+*5`!)1CFP5)U9=z}Wr`4CzBahRcpba!TE#2W zB`wFTophMcyAH7zTab`666_yVd@kHEOVScU_Sn*UsznIN37=O8i4h?<0R0&~mIVzf zDBh=p_b*8~QdXyVe-1fre9eEu3N6uu(2f)6G$__-;HOcaRE}4y^TFSL>{%PHc>iwx zPNPLeyy6|S9Vbu>QLGq(7XDUZ{U`B?cgn^yMYK5-t9hUW3H~Vv)-6#P&6hwch4gDl-vBH~@Rw-A zKTc3a^JS)4BdkW;KGP!5i`OBK=$xonZ-&;YnceYKXVSDlFaG+h;_)Y(eP$8e>$KJQXw0f<$ny9jJi+Hh6JpW92bw_aw>{oD02p z#sBV1sjG{WD^l}No4zFt96xD=Dx>ogs9-2o!H6cri&y-YpmLZtuR6(ss3}&Z;BUze(lx;fH{3%HR*6@vg5x+} z2fc)Kez0HhdiswBB`Q${k{(KH?gE0fgs_Jr!7Kj5FD5G17@}uOL7R(qjhqX;?CT>? za8aV*B3BL){N+N=#U_XJoT1smP=o4Y)c(Go)x~q6SMXL&vEB?RLYsBrs#N_MqI{w) zNZ9T1>XgNyNz@*14VY;W=*91*%56_ntoh_PUy_#4%S8AmjT)3#kg!|uT+pxLSIx9q z5L=DEQM`Ljf-;IBfx?kug(GZd{a&*;6)TRBdN!4u^t{yB<M`BuO1_!>%f4d68QSMJAyC)UtCpL&T= zKJi%jgxh)H#W>wFxW~-DHD1q4{B?GpLh;J%YY^zMc&x{Q79@Cv+g>nU&xsK|7M&|3 z&`XY+Z}kI}7*AAUB)@zG`!j0jk(#d$DPKhS#1rKcu^_=?{=_*o^q5b($Qd;cum9!` zwN{D{=q0%_C0`H_Z|^>(^*^Lekl=oN;7D9B`UEO5o~XnKfnHea^aW24gIkcV=P}e$ zeBUOem2ZYQw`LEBKr6))t(0hjz4+elFx8v6>kAZItoD$-3^<3}27HHeQ-S#4ZYfZ3 z@kGHzEPQ{p^~QL8M<#V;_D%?tPdrgR;q$Tu37#K6JQEk(C%zGsymaZ4k=kVfy`&aQ z$rlC0`Ks-;f{WA%5`16kQ=1#jmp~=P6O|Yt(95nXZinFahr=bL-+;Ot{FIy1yqgi< z>2q3k1@58G5m0Yzv0?2jF+9gsWvAIGE z68zSh%P0GIalXtohy;4c@z~l$3lfr+oxfsZ@VU@Sa%gttGIgaXT|#~?!aI+0y-Av5 z^V5&Wj-+8jnO$hbf&{1KctrUm%vve9ESIP<#epN3KHnWX^vqjxP)2r1uaPM zuBRNs?30R`FG!#lr#S}htg7ou>&nQvc>h&N#}HCinvioL!D%_J&&^}0rlP$#2Ja)A zEy1YPW07+SjRfvO%l=_~E;+9}{mPaIv%e4=gT0X8v>ex-`fB1-v=_${rInlsu?UTX z>^y9qICHk7$MMd*l8)}jI#*n~`j5SCTTzY5QC$<9=I4}ryjFZUCC?KhG4xYTu?UTX zJmu6xn1iqv?LeYf+lAAY->9ra^Mz|c_7S#Yh$Whkv69amA#}+xSE9EqIh38b?Ob8W zk>Io_2}EM(azqpC#W6TnGA7!DSlCO>%jxe*6wzb8RSq44OOCCEt(kpYaW4@sthboD z3Uf4$j)ZveaoXcIhxQN)dm$m^i!DbqA$J_Zek-b2F({T0i^LED>xwDWHDd{>ANG>o&S|*{VhL$;_TskT_UE*; zX7&WPc{Cv{YY}1glKe`VuWe4tbrVZSe%VWM!f7d=ML1}QCbG>{3?W`}rpOf)8AZ{; zX(Xh-S-H|B7Yh^EnpWSJ$l;}L?P$i0Z%iy|RuA*vHZe$##S=Xiv2YAb%U!>TkrN?a97ED32JV0<7LI{w`~E5?LcBPJ zq#b9)1;^VobzRD#LPjga`?;o)Js>#EdqCiGKicgLluyvYyG9_vY4bc0v^iWPI4xfG z^TcXzcJyYQ+?+CgYp%%iZ+_B<1n(fhw9!gInAfy2|DiLu-q=idc9zGfuMx zi?ow@o3ZP9C*6Wo{=R0#h$fgeL^gUX+QR1*FDw&%IY~-1Zx0_)o0VwLf&}+`rdh|v zaaiAn+k*6dECRjwOiY-%%0??izg@z%;kOR*7SM5`39%r7?G#a0Nz6?OE_g2V;x{Ss z{xhPkvX%+7Ai;0U@(fSVZx?NK6(rD0-qx6RMW8*PWANPsTab{qaz>Bkj_bn}*X|#r z7{X8G&re9u?+4@wJ-;iEC-g=!{b;Kps%Ez_8C4&cU=irWU&{^|pP-B?NkvjV>AmiO zB^jVd0GbR%Af@a)|;tLEtsWUbE?AL zI-*@879{NUKz$rM7kXi9a@(2T1)RcG%dR!$t&F+XMS?BSM6rnp$`GHBVhDTpUphj* z^HTioS8~N^DU(qpdE>#6{)=i{#_m!>EdssxyRx0(1Z7l7YLfEFqTgyHzf8&}XhA|+ z)4bbW{d);D<8p!ZU0-Tu5$MIeBismgU< zOb%tHN(}4DyfJZdMkUgfK?@T6Eg{!#mUhj>8}`)^?HaKlAuVg#1NCw6 zTE%Oc~WsJY0Q zXx~Aj;If_xjDZB^mXsZcIMHlR41r!;4*I5A_t3~Fs>^|vXoAZm>lw1HC@CSYPLNzl znhALu9!uc*DB0@;xg;%Xin3NTM(0W_ z(S)o#-uu4U0m0P_2xKb8yU@)|CD^N2}c+fnK-@&DP*S3lg}NJ7)sDa1~laT_wzVEZAz%YX`Gh5EWdo zZIR$K>9hnZ8Ut05FzcAel`12HT*0`C*;YP50=?|@qJg?fnDtoDf&{L!rZ0;@!37EQ z!d03Pm6$N=%Af@ayX2@ug9LhEz1gZHxcU#jW5F+CawgErUOR|-ENDT(UbCGOfnK;O z)K-Z>3liM2StE7ASfh5cXV*9v3G|Y_VCE0hW5K$@9**@!PXs~11uaP6wZd}%UAc{i zsCat5#7|Oq)aMmK{7eSZ^6vKE3Gw1HN!k#9XhE>Xh(ZeztSZoH zOOi6W8G#l=41r$wO^f3M3Kc2elL`h}kYF8x()*H>(ap$-Krj5JMQgtJf#!?W&5*BX zkYIg-TYi^vkmidYXuenkdf_)M5seYnuF+~9@)ZpdtP8RJs;TLm3G~8mT4)bCQa(v) zF*lR7QqY0~D@i<;yS6e46{NwV0u3IEKrj4mie?;Aa2ZV69IW|*79?0(q5ZWa#R@*O zb0iTLjGBij&Gz&ei&1i$fpK_c-$cJr;?91ojxm;qRmP+a=Ls z5dyuiMj|RPidAB8#kX~FsipWYI$Si6Gvh#z}%ykboY`@6e9 zE5&E66ns{U&yZPF;?q`f%BZUZ`X4^)f8eued=}1{9e1S0DWiPS?vH_9?X*Jv9qD6z zv>?Gx>-jmgd2bM?#Q3ZdgHM4mhrHYT_njzLP5D`Ppqt^dZU$PAu*(tXX85d|fdqQ- zZu9jg#wklTL$PiKT99B}i18{;8I6%ZH$$;*1`_DSyUlOg5vMHO48^(`XhDMaj^BPY zP8r>dKp)3veH?5xY#YpBM32R1Jr=Yef$c=k^edP5?%j3SUpl9lMW7evkbc(^G3m3* z{+V}+Y5fnW6C_xtW8WtFx=w4?1X@ChwS=&b^1k=a(05m?CBzCG-EWUqtT9A8W*Mao zB}yA&LBg)9K#xVS9t&O{7|)KejCPf8QLvc5^`5X+29iF?Dj3%q#wk_@*k z*7-pT61;HPSt^MeF>*>x4@{3zD>K?@SBZ!uy+oU(L&6zlvTfnK~<^_mND z%IN$A$|v;w`Au5iKzbauvt3tl9nQMD{%)dPRlBtEiL?h27~63^eeA63UTUJo?XU^- z!geA}J);t%SS1E6NZ92FRC|=D_Q;rsUN}A)ZH@xv2dko2jM9dDy^Ott_wpV`qpQ*X z2(&rWz7(V8Ar>U;7_2eUxOpel^j@PFA_RJI4tLPkr$)zwHAX&f+euBYU{p!O5=~^a zU^;1~6wdV2PnX(h9TOq2*|7k}F2||4Vri&&mEkHkX>*_j3Enk**3v{} z^glKXofn!rrJI^S8Y4)cmpvx#o-!|VX?Zu*X~{9IN+Q=e62Y$N%IKJM{PNXMnxX9VIpUuu?HW86df}ac;~YKQAhi1V zAN^7jjoOXee;~noRUf*Tpo~7w1Lsesv}xJEf08tK@LcGHcQ}qyf8^woZl0u#LEhVM8yEebBDTgNG*;1X!Q_^kQDY93-i0%JQ) z;->?>g!ha3CFYIQDj0G_;mR8OI)D5AL0-YMg8uXOgk7{C!MYh2>0Z>R#H=CRjC`X$ z_E+EioJF9QJzfR689wV~palumg*d)BP8p4nKsQ6NZUz$QWskdoZiZsr474C&&jx`$ zj?elySXyiw%wa^2#b-Shv><`)gM&LJ5mNFWwKm#Pv8*Q|8(Ylur~ZpI|Lw zYua^{M0zX*3Z$wMq{o65B~ah%+t^*Xsf&6tOSQ+0iBMV`A04OGeZ^GMVr~3C*EF_Pz2JJ5KpjCD6^y5D zPfp3zp|QXE&JilmG*GOl61_SlYouQM<$}<}#Nq1UIZd=yip=`B(-6+Pjx&$cRn|2c zu4=Ds;-du#R`%FOcL1yfLwCret}=a9H#L3fF^fPioOkKzdG1CkeZ%c)=|78nv>?IC z9=W+b|IoD*@4ZI;%o|21oQrUdvTDTn^Sir3YWI)+u4&z^xefr+TYWjvgGY7TwTPtKA5JUiSW1X}=s!neo?f zRliRYt*9gWUm<}#Kcb@Kvx*X~pu;tAtX6UTrbJ~_ly1$aq!Jdtmq7L}gTBrc}?bJ{(a{B|le6YrcpD3A+W~DZSo*dSyHH z-%|Uuu8a`q#p)piHzg{gcH@m*>3erRrkb7KtF>#yf`r|I)Aqldx%ZWk>gB|u7J**& z?qUyin4CFg!AMo<^P*aVM|O@w!fwHSkM&pQ)6@KtRmWLtAhB(DxA_6LCMu(2vT}4k zH7vP}|LjVmN+K2{>=t~T}pmJE71snUbuH3>BLpOn)%?uQR;;iPieIq*#{5_y9G~eSQ=Vgf4F*<)KzdN zF1+{Q{jd}NlcMBT}7w>4^a(1FJ z>MD8W%nQ}n&`mWa1sAj+VbAAF%fA*%?31P%k-CaSzMqTBJvJFDziXHVoBLx?6BSz z8~bNST?GmB!u5W1e>M74O1W7L{NG5y1uaP6Z^MYjh+p@so||z!C8uSjw0)fi8YBLw z8*Bo-I8FK=%IKH`$|tG!@kaQBG8M| zq%oq5u1ug^qkbnP8nhr`U*|ay=*8(Zw4do)TJz-`sd*GX*~(u>dMwfFUS+K-Yj(`0 z+BNDbmxwrhqLrUX`X6Y)*2G$OoD-zrQhII?HIEcrkU%fiZ1^wLuF+!|Ps9NtI+MBz zT9Ck6Clx+YkC?r!gZh~?Un~Mzjgu+utJ43;TlOfJ&;QS0NhDAG^;>8JTlJ);sM1bShgCWVSCc~$S`ANze;xz_r2T)B=kjaQ^Allyq8 zKO)eTk?2U^nsm}Kz0y~GbMX=XtNxQ+JQsS|xyrcZx0Ij;%xsHqgaUs3G~7_IHE+O zScwKLNMM<0_1xc6GUvT8Qr+3RgjOYyT|u!uu;)9@XYtcA=dBv4s((~OG+*?!hJ@W7 zi&n4l-+!{58vNM-i$E{z`Lw2J(kj1y?#EQoE_+?HAc19aoGWqpRh=jEsRrfCYHcUE zI?)SzsN+1*Ex$V6v7kzCXH=A=w8IQkp+6|@GDzp&@;&pFLs z$ji6r^5uQj_XcRmj=(SPO)UPRKRO1V7r*p3D;mvz!wM}DLvqMpP2Gh7p1?Nis z!kUowK!Ve9oV~NIbBV#dLDCpQdP!C}BzjJSlsuBFNP8f`X~~tuunEp@G=Z@r-rOd7 zuNN6hq+dx4Ic^hDKQiLTD1ld3_Jp)E6I@z}hb?I83oQ~)YFB7Gh7i%`m0V%%npQ-M z(3}%&O*;k>=q1OoJxn>!f`p|1H{xI0BXUJ?d*FGc-Xbx=Jc4qGcvZUWdByA7B`wFZ z_DG2)*n)(lk>ChsM>*bAfp@K9FG))b+|4SBkenbPF%0qUPh0huto{qV)S&0)dkY%g ztdzW`tpGCz9HTn(@W>7My_o>T99~n_grrr5rd8{q!`Po#0Mx>l_yN_ z(Sk&=59aDz-C6w*5#@J}(z)98#Z4B0UYvfGVi;m$K(x-d$wdni4JlW>i71qOdx-St zDOZIkSH&hwaM6N<rr0=+mrhhiAwmY{aW?kVM=1&PAcg3Sk( z_wU`FLNT}nUt6VH&_fFn(wc=jHz(p2(@UJ5MVeX!dT~1UU@EyLl72UR_u}|o9$Jt% z>MihU4=eAdKi8gOaNnJ{TK8QKEl5b;Em^%25qB)SNnalmz8qx{=*8(8qs#k-xPjV% zd*TUNLys0DY93jndx!diiuIIe)psG5G&zLE@HjOLPp=f;kcB#px1rq|FP> zG$k+p74=~l0k|A($CdZ_+Lkhz>m16V(1HZ#@Z!tCxZ>nQpqG?Mk3_n}LCF~p3`n5Y%r{MY znCpDRo>4kR($hEjXo)7uEs~MpNB$;*rh<6tUr2CTyd<`1^U>62ca2_@@$A%_T(lrD zjLI=?etAEx29G7vChC%hKRmM4BG8M^l+{bV|E`oSN2L-?bx)k%@Me#DHMd7b$(k;w zpP#+h8{4F&yK^Ux44+e<{q^;#$^3uz5(2$A1|K)&sC{ZHUs2(z6MAVv&WrSiw=ME6 zU9I7s)7SZN`qn3HP}SrQsLs%W1oujgVXoSv@7|=Z+ND%yNT3&|E1$378sfxUbA7x^ z1X_^znMNPZ)iIr`k7)EML%CW{xk3vPJQ7Kb(Ebvq%m`PON{$42aawAGw1kf6xz@>7 zxTzi!#e&4GG*Z7z?eXz8ZjV1`q&`FKv6R{aElBXFoz)&a%9^=$^3e#aAu&U9=#<^A*Q1*GEnSdU1MKkvP{7M}im)X?8{n5)#i`=Q$DR#c5}8oNI_; zHznwDd`WeN79^zJ%y^X(fnJ=xlt11zL_NBaxUMqj%8I@wq(<%QBN!QU?V^R#Lhv=8 zRaZF?=*8)*_Mp1bx#HSI3lbbJtFCe)&`WY_Y8OXpv>?G(a8_OAM4*>k^QLyM9@S%s zlQyxJo(;H!Y(ZiUjU}h6#=GzOe82lMjV0U0R7+k({R_{9UUCJSd9Wmnx7>p5Xy!yq zG_fNg-ZjJ#8W{)(|4uQG;Iw#Qk0C|2IXC%>i!V?9n(i0Tg2V+HeNJ&XPI5UG{i4T` zaGBsvUrLT%c2DFon7^>-!1&mlQf^V#^Y(4;Nv!d79?U~go7AiB+yHaM}9{M;h+TxNgr*IPq#Mb%={A0 zj$kjzVI)R`KntE%j$;fH=V0=N$_T?rO0uM2%|-4&I!hg z5W2r$t|ZNEfaS9Zv>?$b^pLI*s|7hm7zy-}<0%g>%j&y2g%%_vz5V0&{s)4+ZcBYo z=c>hy_oE23;Ca`qNY+HsSIhr}K(Akhm(xVo4>m**XhC9Tsp6Wbc+77fibw(hdu5YTQ3yX&z7!yf7;#kMP8qKI3JfMNOFB- z5n@4t(?1T+9nt0x%EUlIyg0XVT)a&TwBUL9`WHGvgt;6@pqGrIk*k)x`OoC);|s+- zwqQBVpX=qxapP?8g$cAc12{Bv-l|NTAo~ z8~fQY0xayI1qm!)BnBm738^1Gll011LM(XRAe~iLVZ)giQH1uwer(4;3!azL(%=4_ z5HD^`Ni(5m<}jxu2G7Eh=4+eNd~M3?Z02$y#F8B$BZD1-dxpe_?j_mB;Qo^nAu%{V z{AYd-a<2IPgMYC|n)?{vw@2rN`TZG7hy@8w z%W+MFgBUvR9G!nbNUk_7<%s=_gO+H5Yr!HYPS{Jk+S22<$owmg)0`7d^Dh8NoBT+w zML$^q~fnM2@lhvIo8@n|p_4fw9K3N}c zzNv2zt^=av*`0Xo7o;A-1+#;*Ovvofi*3W5qxkTa(_`0)ZAJW)+^Q zd(7s#oU5)=2Dn%0>3qpyRTL8Fg{?_DM@}B#eoe$vM4$zU!rz%befZY_6ysQrzpUfA>L3+cvdLZlX=X3rj`TTreEB%YfvMPDmdigPa^A~PUdJQsS|J@J!< zYch{hjGeC!bJ2pt$2CnkN~G~M`0~U7wBJC2`fOMg>*_==yb5&f`a$h_XhFiephpJU z;f2SNRqdAeo#~yy_lKXc2=v0M*(T6}M2RD2v`ZYpF{mf<({qRVt{yXFj6#|TJ|0V; zC7R%?zz`o$Ihxbks~@Nw>?JXfwy!88(1JuzCg0T6cT)!VOXw|JZ)y)D&4)8=)km#}Wl%|R~_0=;mIA?<-Cx?g$ii9iby+{bu?Gky0r z>g{xWc)td{UB*82;wz0~^H}LP@6i>-x!OhqT9Dvtg$Z*F9-lP8<&swou39-4df|xb zI4{u1aExlVR@TU%M`t90Yu-0w$tN`W^rW{xf75t{=Rz+W?HmUQv>?G_SJs$_^Evkn z>2cSVn)KX8y*=zP_I!>OBsk46n6~HhXhOWO$2d-2nm>N6{y^f5bY-Ch&pYvx$*SXw z`u??39OE+08#_DaP3jdzpcnQS$2m;I{)W!Rn-f;}XhEV@(JAVw{AvEKReYCmJLT%x z)aDy+r5H${7xtJ)UFo|ev_unMe9-9>oGC};aopRR67hVa@*C#UJp&Txg*}GyL&W(vzfWjFG0=iU^9ECOd;Hyy@B03t za=d;z?*_hGLIS50jIuID>4v>@?q7t?niJr#Xti3ED_aqiRR4gl{((Sii0naGME z_lePjcm?Hi%~gAWO8)i(UnGpnD!I1cdAUrTX4H30T@|LtJeQcxk3vPe9d!vn6ab~5eL`zSpQQLfnGRP2G@DechQ0bj*nbR z@)uT{`+u%BmwCZGzH)oY?NxV1(tLbVnHPLMF5diqLx=?lPRnt}8Ps-({~paB)s8&l z;mCRTUGw`ab#^ZgM?0H93lcrHOwrf*d&xZR4xTi?zmev_dUOYX1bX3UXA@{aqDa1} zdfXjyo$s$kH(HbV2hGkU=?(x1^x_^P)ivv3C#Ow^LoYL0u^%&But{fnGS;(fmQgej@S^ffgjzKRQj%=ed%3+^rn^R=bI=6SnX;$QB&o{+-}i zKbpYU^efer!!HozO2%4@hohb2G&be%uhZQUT9Du}@pW$MY8BNkwTCJn)UJ%k=!K)5 z}a{n~L9rjxfm(#zu zdc#fqbcjyp`EH?`a-@ZR?qOCS2_cs3hz);@`acM!*^BAQ9argid}cca=cM|jirR~F zcx_+p>~j^)E>}qG`eOS3P!93J8j0j85~JYf8zVX4yh{$HMj`|!bnS{oN{hrtJMXdU zD$HI;aGJgNxYURhLlaVq?8P~h)|4|@L`<%bX!2wF|4>)rCGogzVq?&GeaQ*s(1(8I z=h&~bh0hyJlv=O55kLfnS zKnx*XLUWC@0D9jRvBcs4YC>TjW@pP760r{a2fjdz-KhkJT?3x1oTs@H7b|M?ZqYO9`X zt!kcV;}-nl7H@mH@mklXmzQswNndE)%j3#cNl0pj-c<)Q)*x4;Kf{4CR1bSV_HBJ3hBh6p>3Ezdc z*uN!n&o}+OuWx_bM+*{o4^K~>17cqkfnFzGnX1;GZ{}}*lz&Zp@XsxHTI{g!ORtgro2RPxD{ig{>30)JCEPKlSl_FEFM zr?O3;*UYb{=r&(+FaNqb+3uSE0JUIR-!>jvkifer+L^n{HNP(rgL>NpdhK3kdS&jB z+!N2;e483|sJuI*Q5*HZ8>aV7YfWzyr5XdWa?|@dOdagCd)K6gbsp?p89hypyT@1ZnE3iH zHB|51XG34SnyAo%1omkfeLgCxdVO2iZS-nWtG8qC!!yzDNsG#?jpxST3^ZkPLV6oFo?D^FAJS7_?TeaSuXhPUddQp@ssMc>`$qXh}F! zGOrhY$0pFL#k#3#K!N7|NsoJC>vOHuXYc3r#@EZ|qXh}V^OAa+~$v6G96TcE8F`#MeX=9%vKjWzV(Wyf#SX{j8|#W(;=G zf&|XHj+6F5Uv+=!yWJ`0-?9kw!g=0t-fiDOy?wZC=(iSjPsE<_&(vvZEbX4xe;@b6 zh5MgS#|sy78}>i#qXh|US;y)1-4n_$UC13X$R^M$6gN%v+1Jz`^b_}zcJrTB_r1~B zZS>toK3b5#mUWz&i=I}uJ>A$HvCk&ZE7#_!s_22{{)`mvB|psTt3o{*yDi4g@X>+< zwk(a*MErMLWA~j=Hi2H-sh4m${xgevN!qhR)vfsoxph8k?4tzp2|Wk>Q;h?YVsKlF+z!iqyHW(in?CFP=I183*4DQhQW8mB}~N z!<&!RGpAUh34Wqyh<7U;^qE-R@o9^|8JWjKJ`>OLjx+w)9KYe0+v>csYJfF6<9u!t z^S{lbIL7uOkLpoW&J|5?u1t($vs-Io!;FF!ful2z`FtiG^BreIxj0p;MB%#Mf1jjh z1F;~12-yv~zN5*dKAI zss3#sUie%LpO;Y#+G}|)5e*L81bW#qZeH_;|A|{&RUdqZ6&(qD?&mlwh*(L)El~t| z4X!d()oz;RR{W8#+U6G)`sq*gQM=lfa?yeWKEEW@xBo8mPdwR2RcUP#=yl&)Q`PN- zA9mkr&7;pBkCpNtqZnUYT${m`jo;#c7_D<(sGIvsv`euJkRikj9Otc_@Ela8-2i$S$#d<# z?w9;t@i(ZXK8Xq~NMOs-o&M98{IhX4sN>Ju1bS7Yv7N_~Ul(yNY2W@k|Lu9Me{0L9 z6k3q5+x)vnzVnyQcm2lH_DGwlQ} zchE%(5;$u+&Z~6K!zHJCAd5gRPV=1%-wn_XZ*(Wd1l^fgPY02}dq&4;MR$9XUMW&% zNbV(>Xh8z+J{+gZgJ$2THq-9(kw7o|UR0jDa?bea@_)`Rb>BVntA3^*AHUYE^uS*_ z-Eqdp?x0uqXFZ{3KoeqNI-2;j>81aJV4A&{e&N&}9gokP^|V&b`_bQ-+KY48Ea|iC za}{Qm3CtA|^o0I@D2I6QnWRSe%vn!_*;1g&p-4_R?~+4_9U(XoldEW=+`-LuU4^5| z!RKW!KF&4G@vIn{kXn=+N^Aaax#BVjv9j@x|3h7gm&D_?v2vwL{^6CnZlSxb>%9N- zb~D#${HIaioGz#lZiw9{+X|6 zqPBaVJ7=3i*I;zN5)0EvynSi3|6}R5vSKi*WBk3NozMAY;>z32d?|;zQrGA5v0tR` z>T+PNuuKxqB6JL~a1113O3r8uAzn<^Thh~idd`b>t~4PfWUn2QM*CH3FZlncDFIK5nVxfLw3~ekiiN$9kUkb$ z4kW~jX{rU6>n)ZL3wt3Utr;OWq1)q*Du;Zz?&u2kVchj|9Cx*aV?+}U#EKE-{7NlynsX?v`M>1~34V+Gf48}KNjx*|mVA0w zMk`tswyfb0@8R^lYQRTtxNi?Lt3_m;1QR^NnYZD!cUH^TGHj@KtoLBQ_e1+sxn0xU zik(`zw-4Hb8QQX}{t$1~*a<$LODxfZte>GbCKb!nU9)D4 zcju8tA&g)! z39%p%e{Qe3zHFv@sbwO?cTFU$IxsxV+4r zm%lva>W0u=nP;Ax;6GS=h((|m*GN_`8MLcNa>eE){n3R-X+kVWv|qSaoqB1ZyYO>f zz0>0Ro*9qT9p~11&BPD_y|CV>my~^B<2QxxQ|~QnV3nM6B4w)n^Ip~P<@N3(ed8#` z#`d>m9zI!1{dTgJhZZC_%`17#nu#yo>X`U^vDT`0<3cfncon2x@&FNCbuUT1;q-=W zBl@Twr`Ne?!SgP!v`>}ko$k*5q!H!ndlS1aJ71fRkO1lJXN9T>V#b*FUu6TEuoo}FEi{JhQ7 zQ*V@1Xui3bi2rixwm}&F##ushH(|@LMcw@~{f5O5;`Qd6`&8LK7rPri=9Pd`3w*q#7maQe5{4)~ z7mq$%!eQjqxcGc`M?7!J8i}wDtW=HbGG#RrIw;N*&|ek zb#$9A_wGpi=kxjQ`#<)#2=u~wqkD|*yD}Ql%()_%Ip_br(wCW&`jxfv%*>n@KdYAU z5zU;Ff|>K|(R5#C&g3?me3?0Ar5mk7rkQgU&76~hnNuuW(@608J5#&SGpEGh`iamq zKNeT%zL_~+qnYz@nmIcLGpAUP;55fDW8yoE3tZQ!GgEoLKb6jehnsrx566=PG*UoJQ*fW#$|>?@eE3 zPFWS`IQ^Pl&p6%tBR}^|X66(N&zwT=3^#Gz9N)~GU!>SGrx57HwM*BgUPnkVzKoeU zwFL>D6RVV6r)cJk&zdM7?=1W&7AdvnG*@|;`#B{V>5g+bMC(W&4x`hb1n*IPO;#5dA7S)??vCtoV8xb zo4J@~&RxOGDHbF+E$bm2C)e7Jdgi<_m^qOUFPKOM2$~GMG8Vg6HM= zasP%FeKT_|qM7p}nmHc}W=^pnAvw%`=0rkPfAajeit5VDoaH|6lJp+UoMVESQ!IF1 zo*%Ebf7LfL=R(h(ImLnmr@8&j%sF;wGi&BVLcDl<{G13gbC$lLgf(-D1<%X#Ji(qh#exK<`T8(3XPKy(6AAI+IqG8OeBaERgJ|aLN~2rFVCLk}M`q4lvzGWU za|SW8nK`wEX8<91PP{pit7mEETx-vqnm{i*R~JU-TK^EuoNrbzGpCH_JP%f&kyB<) z9>+{CslIJrVq=;)j|4NPSdicuZdLKse)cn`5a`9VD>V{3bBYBCZu3N{Lo;)JOf%;x znmIoRW=BY|F=<`@ye=Uj0N zv>-9~*CkL6%2l=mdT~0d98_Zc-hfMv79^TgeJ@hex{k6X(2LX19`qFwmxEgnElBK} zZ(^8Tvw4q+>{0- zy`gWIb+7nheFo$?1$2m~3n!mDdVRgsuW>yR&FrMSgpHjk~ z{`ozAm+yxuEFq^KTzbT<_{&XEbv69_(9C*0Z&O!$KWfz#5_XIkm3pb-%MWEPS)b|O z^6A&Q7Wvx@Y_<0<>`|%Zj<}0YY@m|YBbDS=XEygMO}SH{1qrNm+HtRTn);+bs{hQ! zA{K#Oea`MtkKb{`ZTQoAiqU0sd9`O#hTr%9F?JU4RUF;lU$n)G6$uo#1S=#+atLaWbOZOnnlifDFkXwE^?k7+<94lw2o>pXwd^xdzyg_Sx|$a1PQgy zsgL*d^JNeC4fa@ypFi(SY$bhSqS&Jrar)gXi?|IWP=W-7RiexD@~p%`8*?Y5R^d-k z?DOnseME|z~O{>X2*OZ z7)p?cYH*fq$Zv7^7QnxppqAXbL^P#J(k^B3A3H+{67D;yB&8Cll|1Jb zV-Yg9NKhE}V2RrbIh34`TK_xeXhRaXn@i?_{%e($Bv1=W!6JAK>QsYRx>#=17K)TP zVOp(Z|GRyWzU!Lny|!AdL`smL@PwDA&AX4@@U}~T!Buh_X@<2F^-*AGoO!hOLR(~X z6q8|<$P+)xF?D5m(ELCCm}pq@5jW3*}Y!MTerM{Y0lt?|C2)uW_@`bxQ%=S=EF zs*UBv-};7byrciadlX8Lpnj95$|=+8Q3r2dJ}@X@p5B-DC?rrzEi20TieMEIX}bTZF$^V0P+7?`)U@ws+suczis|dyj#dcNqA=OEJWKcY^V?(cF!Hv^ zD}Gb1F)Ctt0FvaAm54X2%DM5nX zqsd0f@8^<0Eeg}`iEmzv#$Ne;E+t4vdx>v%DH5n9^O5)lDF}M!LV(F$xpqA|Ci8Uw)`F>6|NP+~tM<=x_J|~kRfm#%ntta{Wxs)Iw?OCmza_w64 zqxn4v=ckJoHDbJfHyq37ig2ravy4Y;MkaKl5?J z<_Hu7g%un2{rBbxN!`-B42-wL%vs|18;2v^2$Ucp?NOc-8yXU*^{)LSVdKidLv930 zkVuvfJGaFDZ)Z}Aa_9=P)N)R#vonk<1wzoINq^SK@~&EAltWi-GOA5UD>)ZALJ1PC za$`yjCL>VGRZooS$x4zdRhlawBE8Zc<=j<wXrQEnRZ)Ay)!3-|ffpm-@f*uS6%uUt4>goBN|JZ3r>uja1S)o$`rlyKJu z?ygV?I(_e0R^MumIe`)+)O{0lieRM`;Sno1fqNQo@4@9EGuW(+bMywc#_&|p$=tK6 zm^R zLf0PNFRuD%!Ba(LHN?LlqjJZU_E?5|*1(ORT5~6G&AxR`>Xh(S5d&N{kf41NwEGZi zmhVgDHr_Szu9k+MxQO+EC9T%rb50D(vA}03w}BEQ)_$D9G9KQfKmJ?XL(A*qo9}+C zTHlR8Ej8!Vc8jl`zPp)QK9G2xdoH`xF0)~;Hj}p!BJ#&Q@ut>}aiJFW0!^cqSan6X z54A+BDJliID_U(OR90^qdGDdJLJ1O7B1!w5sjNbBEQp}8LISlYPZgRQLwcbPh93@ELu4b!U1%$Wqk?l&h zUDU#MY}E&jK19gT=es`NiZI$vtij!~2Bi(EHAzry-fowfCDnPc)ziIYE0F|hVTn+B zG<&NNqxDtoMjNPwHon<53v3V~36vmlwR%`$3Q3=zIQ{i=J?v^X1BoNyQxoeMZL0)I zkVu}7j;?%QyF#t^S*Fq`>Kft5iX>2i1lqGw#s9U_lMM-1Sf`N_Z6^{0DUuWjL0beb zU6bmAQX1t+ExjaAVKvcX*E?i%Agjt z68Q{P36vm#_AG)*mWS+gYsbWYiWziY3Ek`=!}9mU`*BE_2n{7jyy-SW&?~%V3q7m8 ziI};_l8g@9Wn}l8B(&x~J765!6ehwYobGo{q6CTb$3_bxt$EPR1`?=s`;2Ad6u(QF z(n5b$K2U;0{xaQ#jee_>Zi-D#pjNV+C)z*>5}WUL5H`l}TY^NAQY26dOFfZbgxy-R zTzFms0^1vJCan_ToAGrGe0C{>h7u$^3T+hhf~MX{sUjN+fm-_lb_(Lt>{2RWr?xA7 z!y=Uyity!KGyjjNLc)1&iJ-SM9HH7!QiWPrB1+EfnBMZCP7!b2po0I$R3Wh;_bEa5 z8BYGL^=IwF!qP>ppQ@h`gykW-2*KXFGl;KSC~wfa{=NBuBE0f>TD?u@AQ4WyOUN$U zZYQ7lY)c_eBlhRqI+g1 z+Ou-uN|jy4>$N@9kSQE>+@5->6dOo*&9w5DEFTJiT9T#`QBtKD$HGKjLQ1=&|97g87&_3(Um{_btpwvjElE>}$W&RQ zHTqH5j;ZZRpD2;w0lR?`cS621SVZlB5Vo<|4d=xBQEZ&I7n?I}p?{aEQGBkaJS$Ks z!9O7vUvuXQ^WDp7H$?WY6T)I2J$9mG)bLoAkjsn351s3eG4U_F-P`+p-EkBvaA&-U z5+p8Hjb$G^JlTuy`tz?D!!EzDr4Jj*!qcx&2-G@S{46Wnw=5f4x*R8JdB#=uUilka z-Q%!{5+nj1@bv+lm|K~M^YvQpJ(a#QJ9Y1iLZB9XJt@?s470wm{OA?zzx!ZabJ?~r zY{0X#EVO$;*1XbU-(thgGOq#!nBUH;HFMvLV&$3@W^JmC<#YP?KCkm%-RK8%(Sk7y zB}mNkI?D!(&(B7-FISVF1NpMQe~VFd%)HlB0=3qik78*HeWy_!wo--_Bq z`uckeuEp-wE29voRrqrhi_2e}c|L2!32K64+vjJ?4>V;cLBb~>+KpHia?R|PrH?|O z7M3AD)p0~2N3oy_W|kp+mC{9`-Gy_^{&iut;qq_1KAIn2;`jB2f#$3iqZI zfKj8&EHf$_Q~s*R>ee{Ve!q9Y%%cXyrvC%{c5+#bqvT6;kngz#p z;Hg^nVIa%XB%A(e&?bdIt>C&bEb48%xp_blPSmPAka^s`;s1SsT_#G9c-kVCZT|PX z88K!YC*DjM$b7QJ`R^?Kr$V4s)j=_A{;4Q4*VP|5QJve^+%(L8V%N|1QjK9;pL zqRgqUCvn2R)~C?{O!NIU7hJ!hD|!LL@zb# zdxjDuu+;f(*$-veSLNsH0V7ocwHhxy&(?H0Z7!*kljl6RMp<^eNPRtYurEUi5?Jbd zCHdsCEayH$&$Lb@P^;V8^XyILlV(hgeB4H#Z_2P<_O1TM|N4QU1PQf1%7m3+`FF4P z-_~CxP|Ih>c~OH^)_liplzb9kZr@qN_$rUC^jfSNb=3=dH`KiTI*0M^iAG`_nOyaP z1eQ8)?Mp|RH|k|Jt_^Ia5U7PKU^MM`(68o}->&HAK6eo-&k|SDKs{rr^Ysi{Mw*M7 zoY$+*@1_u_g==PbD``5!d@+2cK5WuJu~tp4xj_O;ozD{O7-rV5Fj?={V30zfmbw-v z^UL2%$DP;yPfPJVIk2J$3AH{dtsZRp&Uxgo6;KJ(!ZlNTm4)w6`ub|m>=-RpQ_1yL zsD*SQp}7;NMPZ7`Y9((Amt|yQM~+$yB}iZ!(=->Mxf7^GVX|S3CFQaX6gJ}9J4}=y zfg=&WkHsQ1cLKF2Og5|$Zhid$W~ZS=S*{T}yT$#IUPmtI@mJQ{aLpyIrsQjcbCqLV zzPe{#NMDc{*<)Czve)$R+V^cpQ_D}cJ65-zYJGDIV%-~+HtT-B#{A<>40~Daj(#d* zDSxDCv z9c})!A_vR2tdT;X7WK#XC!%$06#cJXU-S8?XfvWhcQJ}e2@<%*lb@8HX_OgOu&@sG3lPou;rDkVs$YamMo4mR6`ymmf(Hc}x_3wwd4je6(Fs(pEA zF6;5F(n_$_)H)B%R*oI`a@2f%sw6`R5^8Y^$ZEnWvmM3#7 zLm4(Q#{zTv!zv6VNT~JE`gK`W^ykH9@$Qus0=4J~S7=w1Zh0~T3zlW;YyV(w{^H9} zf`nQhm%_@j9TD}+i z*jXh|3&$9K=GoXm%)3%qvqiR*O0UJbAuscGo$I>gA!j)=kWHGL-7M(6*+dBvSnB+Y z_}qio{gXLO$I}f8fm-Bcnw78WmiHQxYasL7a>?2E$K57Mkib&cwEnXOvW!ixIluJX zsSv0|US^f}^Sb4|_9!)wJy|r>`FiU<6D3Gssq^<*ekS1hL$jRwkL*eybS-6%7lQe`%+n7U3M$98pP zzvqZiX5;FWS(SX17)p@9ah~r#pZd&9Kg@%T`?{n;pcd{b(6sW|z1ZZQpUfj0vMc)y zkiaJce|PrrV%2hgG=IpJLm^NLcSmqfrbrvspy_t=`(w9Flpuk7Hu!ARjX|tZ314&e zfkh@tkich`rk#E|h$S@eHm~Jgq7bM>^C+|z$eQ=r`?S@$f9=kwAd z8wJ-a^)iZOt69w0e8$5@b27Hw1q^FWhNeH>&k8Yee|_2c{%Wk4EA|gQRfeRr10cYS|;Bx^^-=!Zd~wBz8WGVKsV{ zHLmEMoQMt_U>jMdzj0{)NfQawQd2ed>xqumI|dp5uH9v#1c}!pVp)8BFQaggdECaI z54~++KLi^3`#K7NT38~y&hN$fzg)Xk|L}CMQXd7rI?wiP|IV2IaHb#D4b_IGg_V7* zPrlWip#+JB8KVbRr?0_LTFFI98p9bJjSi zcUm3CrjFR4S1ELguQTizR>9Gs&M4#CaTCN@L6Sf%*Dh?`I%z7uEnAJ3^L>pI^(z?| zFKJ0SJY76nKX<2o`-91Cj9C}vxcJ%IIM4r&5+o?h&&6_`RM>KIhCRaPmuk?}5Pkh^%Ikxb<;cNK` z7$`x4!u(V&ah4)~DX8?u=VWvZ{~w&8$q1>{uxvbAnMfR9nfB_j&CC}2#~3KVcwc@S z&jRJ7juG33o9w-7&N|sM86ma2cv+=+ z9IY>ZFV2B1(rVx8wq;oSfm#MiFy64JI96!g75(7YqdZmpu4Q*RA9%B454;VOAVFby z&ZVa5pWD`Ga;`O7bv#EhLTbI<9LFk^PtZU3(m9a53Vz;~e&AqsH-5X05{&o$4{@yP z>6`k2;<21K*t3%JTGmnQP|pcEN|2ziJa>}U;MMsxDtrlH9zhZQ?u69p^*L4$kqhYz z)AHxE{d?a9u}hf?n<&9}ACHM;k1pKM``@@lshZc(ne(5KY;CIvCQ6WyDYQJ(#^4K^Rk-o_5LS(SMejhGM>sx z5~zh`$UVyz7n~C-R5b^$7$XQ-x=6Gu%AcYMXLRoguX#SEj454n?c)n(;r4wM0=2ND z`7F-rsm|}0c^eg$StlFO$Vsh%O83#{Eus!6RW#aB&1%|)?OyxWSN1TzTHILJkP;+v z@cJ)TX_p@BMMS%xKWkiUcUzBM(Musv3rpSgRBJohXfk=U@|;-C`vjdKCC_V=VT-u+ zX^hc*O+#_QpOheBw2oyDYOL4a4f>m>YWc(R&N10X8D=l*Oh8GX7Uf))h^8&da(M5~ z-o1=mweAQTQi8-{-ajtC+@SkBq5cswv007jVU3KiX;#~n1ZrWqS^1di=&WD89>B)u zk4`*!lv09cjV7Hh8u*~I)2~4xBS(WqqIBgMui@dm^>Xa} zjSF=Xgp?qW#W$MWD^Sh+JDbM8@W%A(?|lD5McwB@phBP)rq;^GgteoLK7Wlhr*Dc$ zJR4Q?+P{7_sc%!BY{j&q(iaUX-qsAWY-+5jnqMg^B+}fEX3JMJF{2y5<2JJ1K3pShU=`#3 z#OexxT3BvY&aHp#q6YCySs6}VR!CqyO9JcP(!IHA6q_GE)*M1T_2AEX?GaCODrtFQ zD-klRX$dQW4$R%!m9_5kS|L#DR!lT2{HBrK!+6hg?w{tgt@?%@?0LLZx-u>z%F%uFG0Y&y<5&;zW;{ z&idmzoA%`a3?&#Zg=M)}Wp!tWr+H*RP%=VlQGLj;MI4D3#n&s0HJ>(#XN8)N&`8zv*}wzYYp!trvWwqXgs4 zyC$Axo*SzF;Jb{cs?_J79BXcevJ=a%IZ%QGg=KrQT1i;uP_{VFPNzE|wXo$|g!Ql8 zptgkPcgrxgF`;WmLbfGJi6kg2f46i?E)O)am^Ra8J@LeEo+=SeSQ^i^4+}M`9$vw7 zzPR6Sj=r}-je|?BIZ)!tZ6Ynt5!bXiC%*DC)`l9#?QQ+t38|HCLp+N)A7YL>w3yp? z`6Pd2)ZyQZhY^Q#l#mTcY}yjfj{A=>`&60FiQaAf90d;aHS*Vp*HMB5h2;tAns(%2 z?%i3xZDsUtn9Fb{q!zW%p4CR1!$jN7*yhg8vD2#=c>=47wkstVZ?{lhVLd_6*zQh9t-JiWQnT3z zGx**vS3bxFJwH%_@nSDXKEonUE~lB0vHaX~Im1$EQ-YcD42vXahDBkuiQ66)`nqes# zG`{*vKEqPRHNzq$7%$DEENyetOnHVyN|2y1eg0W>^@XVL8fY zSWMRpi#sAd85Y0!9i7?u49g+c42zT?Aya70uzcLsXJ0Em!%}FeHN%1gl@)2xT*l;=8%%44 zrO?gC`(N?dm1nLQ7OH1C!?L@=E>q61NLte>ys&0iZo6h!q=er4CENuZXRsuX5e67Oc9UP~#YH~M)E&zdREut*8bmu#7L)Pxxp5tF8snQ*px z#iz;)i;y5eGa-9sTK7U|+D}!I&9DdpwWvO18ERSppJ5r!XIO@~W>};I37R{ZS!8=QH%Jvoq(h zHpZOT><+vO0&jW9nwcnVo0qZBJI@HU=Lz*tUrLMx9afbd(^0cQ){o*qYX5fA0FCH@kXTAyBJf zTpTmD&eaosFTrh8ZP0{G?ss1gDSAdn2@>j!2<0F9u(z96>0e$HHIP89cH86F;JhpJ zu_N#IYKlTlCjH1-Xq2 z#p|)@;kTSWt}bGr7TyJ+620d9$adbEVg6GvkAV^-@U{v~%W}LL`!3x{v-Gbjfm*>g zW;LV>XCP&{2W}-YUUQ;6Lll za<(nT%I03D5U5qPL_BL<&D0}%={!|?b9k|B&XVjyDW;=pvo&(+Ys>ZGW%aqb!Ak7N z$FdJxq7bNsw`1^CFRlF9FK-I5;?-v zwsLH3GwR!F3V~WZ*2c4}0c-V8`*@y@{Zo8cXokY(xr&t;N|2y4u#@hz_?@r9W$WVi z-x%Yi5UACQ+bD0W(f0`(-Y5N-PsD4-$LIQj%S}+&eO+#4&T1PQ#~g0J%4jssGM|r1d`92BU_nFUqpN1~qM@o<&A0_E-4jcD0&m(Nf92ZvrKaWk zT;{&d6z=={;PQQBTzH#@N(|(_&v@?pJaYLyGA<Wv{UxbO2V_kD`Gd>=`m7WpfOMol#>-{%hZeb#f|C)nlt zNC^_^jUmmr@8iRLpA9bGM-r$-{=>szQ%uYE>CC;1-?^93cy1MOJD0p;1n(753G`%8 zf`ocwNFVMkRpQ>#Tkb6(fm-xDAG~CWNxl|;yW<|&6z-8dcMBX!6_jP8O^rok2rMVB6m-}%4avu&QNT~Oi`0+Q$ldd;NBv6Zd zpOKvw@V#WA+=jciB=0eyC#SrjL?zt4B^ehI>OCgz-jXCxi+rL?K5NXBy(K9@g1nlf zdrZh%8n`~mTapB7k%#kO;94`uTiVRMrB5zzNlK8w8%mOUOOik>@^B(P>@ZXImgJo% z-vf&|`a!gqReZ|NELmg>5^B}t$b`9wR-1E%FIHRaw?1MV#ic6m!uf&|{p z!uKd{^JT-2=P`yo+b6swNuU~=z5)nRX zxXwsP%m+%4K--jY`m^$Z1Zo{xx?I@!xU;>Lszd@MNF>XLutIj|oT5Xo^Ba_QI(HDm zbowU!?ot;2v5VZwGmr3;BRpp&IU!G=K>}@Ckz1T)0|}WbvZ18Pj)at8ysonplky=6 z*0cRGo#MT?=AcozeItJQbbcPU6_&qSvGad9WoM)%B}iO*(;<--1lOiNl|U^D%a|-( z>tBoTu3927B{EgLuBUg(-&F!7m@3R)>I7^%V|0&yWBZL;w^t&A4)Kp1{ z%SIwWHY6buWanj;EVon#q~#i~L|ACM{;@_lEFVeG*d@cM6R3sHlH`PZE+Ii-dHUl2 zCZrbGkYP@IJH(ipaM`<__ZI!Yxc(x&-(JqHoG7TCJIGHxrKgC!IVbSk!4zoMDS|FS z142lUpfJ@F*|t(OF5&WSN)?_Kh+247pg5h<2q@muyAdZay?DYS+Ovq#2kv<{bjvvs zYU%PbOet-eJAqnQH9AD3LS~SPH2V zsD)2Bl|Ts+GAy4TM2URZv7UF&pC)p9$9HG)I+uio^??K{w@A=;SJJ*a>o0i?q8664 zN}vRZ%~>}H8*`4*%4M{H1Zt@@xcNm_G48T{uXJob6sCSBTRw%UrhX zsA+!$R1!8a_4YMTf&`Tt(Nxljgyv457M8T8`Nh-TEzN%LK_3GpNKmGh2&+0aiNw>A^N*kK2U;0 zveHe=ITEOaC8FjWOA*_yEb0GUA4p*DQf**dsD&k>5-33eM~T!4)WVuo3D*g#j7|l0 zom?x^|XUZ}jLP|U4PbE--gzL1}|4%+pOVW7$F4?j(I>ma@KgAfGbxo&O%P{>; z=e^|Z2zbkC4 zxYm=Q1c~myOb|BK^l)$+sS&6}VX|Qno0eA*^;n^2b%qioT2-GeY)sx6!F5w3P>aH3 z!y*Ph?jvke{_B#75+oMp3llbS_1?;LQzKA|!eqlD&hNKQMJ|%(j1whDyvjOT*vJsK zhTBMuKrITB4U4EeK1k%F;;^zhN|0!=FN3HBc8%^5;$qm`ScXFPOf(mnmd77c%r?g z-F_b`@-g>X7Y9m^pi}e7hIImeY6NQGIs1Hl$r)>&;c=;rCQ6W?)Bni^o&KLXfm(Q9 z0QbT#*An^Y?^A}M1PQt$fNapM0;veXG(!mz`T5-gWW&09ATkOT6jN zF7v@3Uc&m&vvc%n_jieKu1;HZS%%iFp^z#&N|2D{X59e_goZYd{@CV(u-Cj$OED%8 zW91wrNYIUyR91=kNRdFTz&ci)|1|oN7!#6gpacoJc{AnuKmxVsJTf8@&m*(Te4qr0 z)LSA-kdP^)Hb!}%KdY>eKrLBr*1eXbE(xr)9&4<=@_qGvda5;OM+p*}sx1~d|DgiS zEujr0P)qikWbH~r2@+xXX9^o7(_7!*lJbEBY9(v!lrZsRLkSX@mW>xSy0M;aEfERS zQu|=09uu9E{VT&ml~dBF{^dz^*cSL&&S7)SUr&zTf41oeh9{%pnRj$AGM$V^_gC}1 z`aK7ld$;}>+4Rk5akI6QAfei5GB3ugd3k|A;TgY!ULfEpmo%uaMJDBTu~AlNtWc` zx4kd;#gD?5PW&Zqd7!X7w_350jF9)nBb}VUc#$YDG|oKQd!ZP2)l?xNwaCVVm#59U zkKQB^cCtniS-KRKxuvkIr{t-U5_dwDNFrgU5XMDesYT&OE#maMSr(;`Dk*U%QZHR3 zq!!WB;!o>$^Su=|`1^B}+(zbMEtPvSNDE6>rjXwizi47)k7AjPT~n+Z>{HUBmY8%a zd+3wae$&=9*9-7lVo>6q4_VSwLi}ulKTGOIHU}jmq!z^_!XoyW!N@?O*-5NV&%Zwa7-& z{Wve)h;i56Y+RtohfFV}o$igMu@-N(=Of&b(vE6($M{bl8=C9}dr8nZPhrcG>9i}x zoU?MFGyROd3V~WQ29s^;8P%grAUzH2J-kLU)S|GwMMot%PnhnEzq!ZO{g+VjjFNF7 zf%oz7cjr!Dn|g~-o3SHUAy5nN{Na21{%c|WbT*%D`QkAQC3yRcnyQT5H<{}nZt>k8 zK18vB1m0uA-<|n0>RQ1%k)QZ83gbd8Y(4z6(AW9c#rHS-Mx|@UP=W;BuA^y}+SOxu za&)S(^kOlEKrL)z)Yj=wj9GT_mZ)y!Tam1DddrYuOJ9z?ryW)v}1Zt7DOtzKxC_!L)r47ml`N1Mj{C!7F6-tnh z`BUC;gbgH6i@asBLH@OB10_h1?@L6YPt7swse=+EWX&o*wHQy3KrQlp$ws12Ep6Db ztmrL_wCMdzmbCKbC321uB;wE3oKSP9#Us|8_$DC(3tlTcVw8_9c@tdI2_4|db7K*&QqTFkN0_@qXdb*CuR%!%l&q@b^;}`gc*Q>1%sP(S>B$1CR2M=)~`eJ@zBfL{n z!(EF~MOrFRxy@aZ`flIbJrxOQN#aSFKoOo=`Z%|-=iEK>Uad2cQ^u+UYS|otB30Jf z+UxVynGa88@$=J%8Yn@c`1d1(jX_=~xD5}F4I)+Fe;lF^sO5^uwSM=l{h)dI_DyHN z^!^5E)xYIwP+V0{juYXnF-K(n46Cei_0vRIWgXQ?k+>5SlSQo0Us@1DqiQPzm6gxw!bnZKK`(f9gG(b|QCw`x~AHmHSDd!yg2 zmN?>CTh?{S5@(N185Ic2lsr75sj>5(e|5Mxs z5-4#eh_(pJ`>}jD`tC$ui{%$A8CJg{BY_h71|zkU%Y5;i1^DqXY@e6A_|h?G(WBkzrYz zNo!bS$r4LiQj!uuG+)m!vk3D(U6-8?cDk(0D&e8l|m z`yhMxu&-8mvs@l!9VnskQ4;6}YubQiRoSpKKCFRfgi=pFR}`eB>& zUNh&3v>$Bzr}1YkYu$=t+CIfo)3mKEzGb;*=`8J))jIlc==EVtnpUx5Sr*MpcjmK+ ziVY;tFXiVt@2kwh{Jh!z{hkVeT3CjfwqrwO_Ind=)_#|#juIr$zvg3NL2uTF>ipgu zeQxETO8rAEoj=IG_}pmpS)SQK^2u&f&`Ai{L9bVM&|ZW z2J2m+xI&;-p50?aJ=LFijJL!>HGeffz4K-TfA%s^f&}`EbPM=AbLBN}7SXqqLZH^T z;Bmr6=UPX&jS@MJm}O6{mJxs8weCG-0D~ zg2`4FAc5XFpH&OU$o~G>oBh=7m5u~zVLRq))k^O%f4bO_HOjS5 zM+p+-ol!n4AMXCS?5xTSZ+7nab%j7J>;?SPY-=nrbUv2Qm_chMXv{#Lfkq|z-5Rg9 z^6@I+P-$baYrK*YB+#qTG#eiiJx|v)Zu2n_<3cSOF(@W~K34Mc$gGjU80s1sqy!1{ zwfI|Vun&7U-P_3jW^g3Ng<8~aC?*=mc-tLQj+MP)7_9E*MdVY_2&WP|c^@2@ zj=$Nt`k;&p3G_HME&ImG>_QW7WAP@dpGyL@X!N1qX&lqE4|^-KeSY3XzQdk6YN1c9 z60Y&ekmHq%3ke##C{NbAbEa4MSl9`F?(wY@(i`pCgP9v(O?OaoY-5ld>c)Z%8 zys_Y0ib}Xzq9I$Nj0*|%{p0JsSIlAAS{fZ3$3)we1Zq*gq2H}OIBe@NXWi!B#&G^r zLm!TwYNSO^H5$7p=a!$ia?>&Al3;Hm=f$du1PK}wiKgdc;+SaAn22$q7L8qG!}51s zW1>N0B1({;k&kRxW8%cP<>sc&d5rGg)lvx5!Z%ia>gknvX5XvcMs&YY%G)mzG>(xC zYfSupXN1}5vA1z~YaxX|EgHKhAIg|$(3pr4B-HwFjfn=0iAbQ9`UY9+^%t{yl(+FF zMiX-xqK)!*WF)Zu$q%DHv1Y$oyV4qnDB9R%Bay)V zvGJnSSJJH*uJjdGHe5Xl`vel<>n*zF+>vTNG$c?9Q>fZN2@)0NTlvVnYNDGBBv30^ z&bcA0&Se{=aS2DY@fm$Z>3+Gl$IS*xkjT`qmLQs+p#28cpJf9H)JnCLXedGA-k1`? zMzRz>M zbld5A)^ber4?7a5g-<)x29BcGVsLy^36vm#ttWK?wI;+^Epd1;cTWZ-NZ=Tw+CT!e z3U9SMvKa~6-0A}*NZ=Tw+CXnfhSAqb^fEYRjaSmAA_)@c;V3rjNT3#-4wRzrV@C-R z=o1MWc9|+9P)q*aiTjL7sx*`!A;ZZD%q{NVz!a)BP=W;RP)VIYEqvcm36vm_`pAF; zYT^5iY6B%m;7Ftr1@l__plJ33XF_n#mr9@n37q3doj@(z^Q96fK?3JE6vB=KYT@%y zAvBaAq0W9-jMbx%KrMWV^0OwVSv&Ox%;>3O>0-H2nD#DN`|kd75vynR6nlHV-eSEk z5lvyL8}+ToosjQQNT6+gKDC<-Bq%IxP^zqVH6l(Wto2#pN|lsgylOsV`BGoUlu#>? z`9L~JUlKAUNMIY|r%kWwEWUZQyBVOgS0r#wj(Z=A+dx8UkqvqBADM^LA3T0A$<*$AW=TlDQwgYD#&f5 zMxYjj$%aK#Io3efc>PtNff6J(A^ckL)+enQ-Eeewji^#pEuGo*Wc~_``5+vvZ zRO*Al2H8lBKrITB4U3?@u{6Dp(IkTpdw(^S(OBXie8_+5-?1Xz=O%_VOS2^v5ePDlvuR2mk@V8Y1+1?y%^=??YcV(fm#$3rOL9g@}#v3 zyJ&Q2C#9Em%Tao1Wv1LYM`5{Fir<$S8){6y@vVRUgeH+FDfKdnWvf}t*nGyrhB5KG z2lj>Acv+C&>;%n33D%98D*wKLymj$AO$*dAQQ}S{)nNKx2MS_C@BxJ&T593` zNKHcmCGG^#)?Uk=pKA*n?QfQ1NKja6(Mn*d8*7y}5-4#eh_;9kwbKe4kGgeaNKja6 z;Z8(NLjoo41ktodRnx*MHRb>Enmjv(AwglOh5Hp%0wwMQ(bk&nR^Mh2<5h{cV1@*R zr55g2+Nml- zg2GY@doW+)1q4dm38Jml(Ks?7L1C$-jtuj=i#>7n91}N-v4pf}%%By<6sCPFI4bd7 zLKdM(LVA`+P?&zVb{x9zKhLzKJR=E>a1@sN&uKk%%7m0CgtBHEM>ra<j$B^I0pt&udP29rm%OCCW@0{-g zjF}tEeY-Ao6eFC>ITBr}QdyN}1u7-*oNwJ1WR%QY-gkG05(E)AR89p>gRSE z8IYi`)S^C5Hk7eM5GZjch_(pVcx9&%4hafNEgHMXhB77!0wwMQ(H4OtH4+q-S~Lce zjg-fBDRC!=wg~s{2W#`}2)zs-Z^y!f|tx6_3p zA#Byx`5f_%H%|15(Z9y~+%)as*mcT9>QFvJW1f?8SHexsAfpIPo}>?YGX^ zOq3uI@F0c_;bZ&U$~3k=nH0?Gtj}u8us55D5+u|epizfI*zhc^9c!u_ccKId^~R}h z=7z9$Yw|iiH@~P5sHNT?)uLDktClu*WY0`*oge$eik;V`&du!e)$W>S(#=A16vm6pv-q8eBCC zj_u%PBP58otGZVl+ruv^Hjr48Eta+KaNSHhr6ITRG*bw>S9IHfXWD0lKrJjoO}pAF zm<3eKu&?i`oMK0=+Tu zvD;pRu>B8u)Mzwjze1pvdY{)Ij}Uev?7RKN7rb+#1PSUlv_qcyji!wc4`F*N@= z`ER*bPLyE0*qiyf*I^+nv*WyNJzu?T-T|uQ6DrbU)8DCQi&wp6#Lu!VAgPO zfFs}1EGCu@-j|Dc;-`3g6T(I}U*vnK`$sYQ$Wlat@|Sc+?)lsytnjAvei=hPC1ud>D!-P51O53lBB3_53k!gRuh zb>_gt@L*Q{+&7L**|VCjN5r!D`d&uiBJ=!_re2VANACT?A@K_KhDk+0=2Nc@lkYVFiTVYV`RP$Un@Ds+*Vy5%UFz;5#h6m+h|`nlpT*KW6O4X zqZ1`a&}f%**YD<&!R-C0jE?u;WHgaLE%Z_NTT$CkmTq2s+s3l9ohU(qMmu>^u%>y3 zg|a+b=Gp?xo(h3ls_)bM#YncyWAW}fuP5oQd+znw!=C7i3&yg`FE{9PyZDfeG3?R7 zpY_@!o^b!_O8(I-C`X#e0V9JH2@-Tq`GXqkb?g4~Vi`xWsy%!99hfvzAy8}jrWp4A z#LxPjUSy+UL;(A={YvD!Dcy9GAVK%7XTG>bA2E;47Qg2g#5_lzb!^I8LGQFWj!hl0 zL9bHil>W3yJS)_EgnsJpUAjv6ntUv2{I%_BpRW`N64QT*V-ueB(hIharku|RV80jG z6B+Y!PlZ4&Os%F(XdcWeMl^L~4a}{iD(4?@too}Bdd?arl@#)MxNE`8c4S**xv$eJ z5+uUY#k2Kucj~u4m^@W)e-2@{y>dp@h<)IXX-BQ^v&6GARd(s0-#IyP;J;v&HRPV} zv1$MLdvQsc$I<%o_f9=5DvlLecSS!q_NacBmmAHU1mD}miPcj=SXkGw2j<+k;*W6+ zD-+KOpJIBYkNcI>YFdxKLfGb_!Ta0nI;o@ziH2q4*~+j(dWoz1xsCI&A#BRO>382c zeOMt-OHI|KIU#IEq4PBzl`i?C1c{g5#qGwTvv6kqyQi4P;-aoe0zokbm zr2f%S8^i7$p6u7^r;ZANT93!XvPTzg=>2cp;>7!YquJ3dZ3oi*XIVZ zBG)R|dUx5UNRYVoF`A{Db4Wkl_${~5en~%8a?zeh&tIbz0<~U$iDp@+GyQNWBJKF>5 z$QQ#h=4@e}fBTvf<@$_Z6E9}-{qE!(9VJLm3*B8|mua=#ma~Vkf#c)$S6I7TAy6yL z{b;s)MH4f+@jGtgt$ip9PP^^Eoh)m0lpvwzFBn4`V)hX5ULQmMan@sO9gOdC0W-$ALA!u@g1=M|Nm&SRqhLt-+~>eq(q38yng9 zz#*kRkf0W`W!_QK>QR#x3}WvVb#yrWck3vjwluHdS(940YQt`_%jOQLM?g*Q)(@rA-Z@Ft9zoTqr&UT;;AMj zNRX#iX;Xqpo|>i&tq{yktltv(cv?Q;ElCOaK4W=q$y-uwOgkFP=9K>~GXLp}iUbMr zgL2J?H7#$+r(p=|^!@Y$SHk}l9)L_0YLSQY_@8Lg@|N0$gs>i=UmrMiIYIb7QbL~0 z(l$p;@_p1)?cE!~E;gvPe{|#-#Rd}OqvQ`eWLmz@Y3}<_D;XDcSRqi0Y}9Nv!n8`a z2!F>}IkBei+~VB9b z?BJr&en(Gz5PqVRke|3LV6!RxL}{Bp&%=UQ(9Ht2U`JL_CQ^a~`9V`(Y%s}l(zLM& z!R)VtfB4n8noc25i~Q^H&w80IFFY`aEv)^1|H|U!bkri>r)}%CCizqMCS;1IvmPs|4fHJ<&jzQ5UL*-Rbp zUe~nsk3w0`f6_XNh97gF1c^{i$L{H4);>9d+bGOWvwA#kwQXSex}rYho$#ndWteok zJi8srRs;k^?%4gpff6LLa2r=HcQ7{|o6c=~z7om~?5KY9O6C`;JU-Vw2*m;)t9 zWZM?c`uGnu@9zrZHnwxZqilLdnx|WEmOo)b0<~~%fS+ry zEtK6~yw>)^8eipY8;Krk<5|{#wR)(1Jh$=Z-B7l;-^UuExgXe2LigO4H`eHM&%J6R zk}A}4^Xd3(i}H0|QMP&RJ(U|YJMANZmKiI*}m`~Jy-7q+{UZtp={H}+>Y37 ziS z?`7m&ugf*5tRg<_FsY4F?~*F1>m?Qe2lwiC#^6^ktmCNJt&aoq zL2WEw$K58ia7-beTjI};h&6V{#?vuk^pUwmg34;AdBCK8qiG$u2M}1GTx4(V0bpFH zrGBH|#Gh)N>g3;>b4eQ~N|2zo(Dt3ve7=&t>KBUVU*b;9sIjlhVTC{~{C2Nti>8FK zA4+$1WQ!QAtQ|1ugJL3Y$(qZ+*$@?ksP%B0r*`-Cw{4l(C%dpJcYlnnAP_}L<<5U53AvSATN{)rbh=7;w+P=ds` zRy&1_o#CaqjnoL#qA=O8i0tP*M6WGbq_Ke#Br@dNC~WLuwCX-J0<|biHY{S?&c?#V zgl{|ylpxW+_bOo{SL=G*Mrs6VQJ8F4MEgh94uxea{?t)|#G$3jg^iCp+jASK5vWCB zvSAT_Pq21cq&w6~M+p-5&My%*jvBO^BQ*lGC`>ji;zXdeW2CO#&{2X!alR{sTKgrj z^CdL`wJ1zBEMmrLYd=m?*M1y|OYS9;CvhRozqoT^e%B^@nsEXpv>!(jwDX0|_pwg+ z+vKv*#En2LHC66}OfM1?=DTiEv4MotB7%OmQbj%1`m^pblsTszPBM&n61sLIWNwk5 zu>4)!OGbOG=sY{xGe%+3qOeN1_IcT9FB!&5`^P9%w3atTLX(8Fjs%6}*?rbtGQKk` zf_8>sT&RVqwesxBIm5Gx<*C`U%9rj4ptU&GieDFF=L_k?ofcApM6$D^xi3er52?s zSy_pEpacmk45e$gEZJFd!qOrlnGH_a+1Nv;jl6r`h_=-B#Azcm$_fu3a?+R_byWOr z#V&221PKbaz567E`lugq%IIjG6Ou^_4j4lZ4;1lc{CvuIaV{rn~Jc|i|{ zv3E(oWTl`Im|G-zFWO^7FK?1UK9E4IC7E^@vsd~g5q55g|KH9qy>GjZFm6owSEum< z^QWc?B}mj7IMR51FG0|$6R1Tor957t1c_cd0#fONNTAmFgX7fx!E;T2c0R|n#yH_q zRiw8==xXE6GO9^I<0fB}lw@ywrF#pq!ws$i=^I1ZuUpv>>tNt3-6# za3jE|A>x{!F3jjvrb{=3-6wlvp za*iT7iR3JI#JlY#=bS-uMgb+rNs0%Asjk_3*M0VHQsKv0q(2nZ5YB=~mq zZ0&t}_wN7mz2{N-*{aV}cXg-xH2%SUW7|Lp5=)1Frk=i0JQ43Afm+z! zY#S&ECE88&T4j*%hqhg!SqodGA+$FA`CV)cKX!;!e=nPE@{X;?(Uz z{fb0Njs$8QtUOv3?6W0-(ATFwzl)N6f4`w-?)pCITp0pwAhGY<8>(!4Vv*A#Knq6< zlbyi-yg37pOL*OwXCu^#TIUnWktl&$8+VUT-*>u{K=?hx?_Rh$T)nXRPa~O-cW7`N z+@5oUYMcoA9&$ zeaob2Hc4sxhP)6+poH$Wkf1bubzX@3DJ#2Fbp5Y&EuvYAzZFm4rnd={gc3vti25|N5L+FYH#v^!xL*+2p%p#<3o5_%od^BEG{ zN=R#Ly}8ClFjqkWC80z@IjB7a+Len0rCF=pAd@Cgf`p9PZ`<$(YS51a zYH=&s*lk)!u26ym+uMDWcB|{ZpbaEYi+`t9X$XQ$4Wa}I_DIbVaY^Kgu7z6M-ZJi| zz2{_rOOEY|&bi~ZbmyzNCY_^HGu;QhzwjP~IsEKvukCjDvtvlEP=Z8QuCy7?1`?>X z`NueutB=Yo46%U{BqIClHbl6ukU*{5SJoQh?;&4@*gy#qZAN@+h+v%u%Yg)HWsO;3 zh!_6;Cd3BzBJP6}Ws>euC_#ezzZW^N29ZE5j-vE*z|-eef|A4tFP@_fBsfi4xZ-Wu z5GX+c=MOf45}e84m23hfNZ?${BK%08R?=fTN|0cCUaa-3c&!}?)Z+4akrN0%J`==e zkoXq9RStm?B=DK1A^hA2kw7hc3*WYZxk4JBE?R^iB}m|j1r{NYKrMW_XcIW9_37?K z(c=%kkV*H!hvz>uy>rcll1kiJY|@2xR}YW1+K^X+Xak9NhAuGl`BZi69;LrMkucVx zR?_1xo&kVo4&aUgyW}WA0#8Lqnm{ew=U@{kK_cl^f&^;eK5N?sN|3--X%pBQu$AER zVT9&gmYE8-S#i+3Pl^-QY z@Rh=%njhzhSXzz@VdIrR2@>cx%e#IgP>Ul&*i7G#5+v{x7t4k~0=1GHcLhq2z|&}K z8%UrQj`?<-qXY>&RmZl01Zv@ZiA~@=PN|_I%@|cI=86yRUTgv-NEA&s*3ip(Muf~{ zkU%YL$F>cWAn|hVDaOWcC8meiKmxUJoHsW7+y{AXNOxX%FM@s3&J{|K=(XFMi%w`x zZ##K^UNk@gwJ^6fff6KElv`y=zHVdg|08~&mKD3S5${}FvW90zQ#vBzMf0r;{++%B zLVDo@NkR#t>H8-Cn;t{#_JSZ(+> z|3ngj5+tY>5bd3xc&>=CVakI9YEhccLZfofpI3uOaGLUtx%Kn|gdZhH@Y&exs{|WJ zpcbdSQ?moBYGz%L#w)$vrf42bX(}zHX^f%YgKK0CS%H;1BMBvl_K3jhpjjovYf+lD zXkJP-f@@^1v5~L>X(XWp(E%c1CDp-eQJS@AwoEpxl~l8?h>}o(=rBSeL21@v+kq9Y zgk158up&t)L3DtCb!xm8=Zdu0hh7{6?^=>jf^2vM)VW2lcS(!eLU4_Y>)eur5@aJt zP~WBXU5nsWLRu7qsXl_a3KA#@B@)UJSbL>aXX{!-vliX4l8vBuX`C|zNDOzoyvk`LM6(v%Qzx`5Bv2Ac5FNJm>L5XB*5ceIxgu=(K`23Vut%8@o>~iDi*rR< z?Db%;4H75`CCEl_WS|-}BLfobUDD!q<=xT4YORZsP=aiD1YKWOpvf712a6;$_R)-k z(zL32I`Tj?rM(dj36vm_*zO(A#^;4UG}p~uNWZ;ad7erCm2QohUy}`MUDV`?R_jPI zPOmi5x*w-$g^kjCaOKVrC_#eOvWT!&2g3-|qBS`pYT?SAA!wa}B((Ozy_V~PfA>7a z-sOIm6cJt@NN}38@O*M(!_PK2Co}@!c!g2a&J{|Kz!5cR0=3X1Hh~f(*q+y;JjQD! zNT3#%&+8vZU|U*$dYY-Vw{y%1Z&w=fY|tEzYKmGM5;1Lb8g?Klyv6f;6o-l8h z10_6)62YUL7Y8XzoGV((pq$WK%Ct&BX?hc$Rw*d$oq*|CG3D@Isjs34 zCcUiedP#TT=1Tbd!}tm%bWcuNG)Cc->~f$43A!&KIym|S%Yg)H-8t;p`@^L-U%WrB zK2U-L-CvOn>q&zt2NI~2bPb{eiLg4uKLRuooD@&$&VZweTwsHh~f(u;19Z!v6gD{$kTI)@}1v zQmK^$qqD|5U*X7rMA6G$ocEp9YqEjAa00dRy|l{ME43ExoefK?Lu8%K@};#tO4FIU z_+1Fw2CX!b7QJyqtLK!aH=OY62sVKu1C9o?CQG#UZn$RrTym5kL941ncqiR@R=koU zfm-(4Ysxi-3C_y60R^mqjwRp7Ks#kHXTnUsQG3Y>?qTFUvuu?=V(T@ab@o0BjuTt4I zP=dsT>fX3Jwo72=fS>CF3Dn}zE?ABrff6Ke?rY}?3Dn}5b9jBA1PPp-8ylP}fxQz) z9PG_juKXxLg2&+Sc#Z^W(ONInpm)N!XT@t*C_#dwL~xy&%i%`?wP>xEY?RF zqS`i4f<%&IyB`VEq9>SCgWlQdo)xc^pacp0f{&FeKN6^g@ya3uN|3-W5hYEa7WOnI z=wH8D^X3PVzJ)#1chLH>IsHy=1Jdu|1WWK+=#=K)J%Uz==s*1GFn;w9ZQBG&kU)Ee z@ar1QMu4-_#@`_(kX-u~0V?l4S3!7wqZUY=gdvND^AXrZr?v^Y5eecOpIgP=X{#aN7Fjq$vkl$6V33 zQ^}t91$)nm=PQ&T(W^tOAwKH8JtS91pcZ}OkZgEgen%Vh1yYjG_qNfa^d)WMg(2`Q zQ!0laB}ic1*uFvnwdkA7WP`q0ZWAa$V%dmy3=tag^9MlS?m&v1ZvT@jES(m?`#N^AVJ?qCW5}IZ08CI)S~bH z5@CI(+Sot|67&^kBCPLJhY_enU%4iNzKd<=s?Z5~gQKjwtHKg>s6kJY-t)t!=Ihys z=E{#_AC8IiJy;?d%-n0+@S_BYi`9o4B69amn-EB#7Ja3bY|M(@Zxeo$AVFW)B_cfH zAc0yGcZpcC_<(IgpahAeqZ$&ZMKc4ku{g{IN{~o84kCeC^z@Z%ghx)6&}d0tHYP1f z^Y2L$Bte4H|BWCm%&pxLQG(a~GVXojt1ugWBv9+SZ%!Ga$ou<3Y7iwzbSb&n5WiFn znV0yHK&?s7(kk-Xyuu-bz+Q_zieneWN4w;&&dzAAHL=omRebhKCcXKa^(y(kD3kuE z`{ob=qcBG2`JZ~xxz(JJAp}a0DE(!uv61h{l>dW3t#b1`;<*n)#}f2Up%IUaN4HmT zRg%8)qXY@`i0vyRQ0w>4@|kjUE9lzg@S_BYq`ixEz_SdR$s|pn1c{{U90}A~(zCTG zN8`Eh9d}pzz>g9nu#JWI3PyeUf<3j@z4fOgJ+@nI7m1v&Of>ZKpM|y(Z0)FpamCIR zN|5-z?j&Pl<>#R`kU%YLm9`C(ATck!*LDjx3AKR)YK6D<3Hm!*{q)@(-YMceAdX5x z?8vY*f}Vu){UFr=jrvGnl%R5WciNPo@jNo(#o&DurD+`Gah~V9LBi~f;_;kmB*I2f zL1Qgnm(!;|+M#HCAF-0U43;;`RI3x@S}ujB50Ig+9CuJsKvkU z-Sv5huTX*nr)lg;+y-3>wbrkWGP$aH{L2smB}mX%N#&q;W!pdkwcg8@+YlvEg+?`$ zAc3vNwt)m{-P@GS*vLEUn~+?g1PN?!K^umpSrP3Kq`Kua@1Wz~ZGzVKSb_xgN8D{l zl$qXu~TDu5418_e0W^I8B=L ztcd=+U6ZuZNIPgyD{NiV12lmWB&c^;HWDRJi>`!(x5hviNsb)OD5=glJv8S_CVgpi zO4Ald&n8%s7(sNRgv&NG?XnGR+u^aqw!spz5lV#Hc%ju8HRWbcx0!ybOX-6j^>nl6 znrzaeEA@0+&hqAPK^uP3au;@Yv-X@~w60X{?pAoqOVgDOyWTgggM?rkB%w4Cb)Ix} zJ8t)4ZPEm55gj|Si~GgN#E7qR^l;VH7-OSF-Jb5_W}{3xre`M_f@6t`lFsEPseZ+p2J41B!q=yNZ5v34;S<%?daV*{1TdRGt*O~3sF{1)ClG!Q z@w+I=@S0zB8r<>!BUeZa+A&t;`1a)l8;Rx$waACu-h?QWa*)d0=1b?Ty$zi2&&8@4 z4_ll5eB!L$^O3rZN#E7?gHJEFb}JtorTfR{@0Bd!T-T>mqEAqZe&-QG`)WcDSuQGtdm^^2Ay|UM z6aQPP;O%bi*U`js=E1#<+BLXA{#u~>96pu+A4QV@8N!1^Fs$Ep#+az`kSmPj>{Xb^l?W=HZTNB zkigm$qIrn}a?89|+&Kf6#gh#tP>X)&5krV%{l=)(SJub3ZC}Q!bFAkfqrA4TAv2BC zyZvp|3oDw$H>;4@MF|qezn-ji`#kB_c)Q!nh?6`wlOUk(ze^&qon7@GFx|3;li|wW}g6GO1@%CdEJcp{NbJsYP@+r9nU61i-Jvwioi;Vw#$cz(GzK5pDeG3up)_2ld2^29Gl zGsZ;;5;#^0vFX-j-*am+Zhx)cTNZ&@I0g$5^?Vi8_DWfI($WS_-!2nX;lnSRo{D|` zbd`x}#M>_idhOh;dDIKHd~R=Nk%JN>u#M@{zo(>DFGUu2C+^PZB7s`J9-5#AAL|^b z^LO7%t!7p$?hf0O(M1Uo*t_(%evfaI^*Ud0E?#J35vX;#%mg+0n@)imJo(2)sRmte zrvA{zMF|o(O6aqeGym(WGpc}-^3G_BKrI~Sg{a^1Uti;y1)K`EN4qFN0!KR`M$fCS zrmxQ9P95IB!Oq&@dbqdPMKR<|Hopp>wpcY1L{e89O1!an#9>mwz1WJ&=deUDj z`1)1#e(p6+TODgLzG4)$V{PPx?&^B_OU^OT+Cd2t=yf5w&6jG@Jl7dAE0c=^Y7H+Q zs}4?V9jK2?yQEsJi5FXEa#4Z=){_uD`}`{_D8F-cKwFDItySG7saAJe@d$VQU%9ZQ z-^ni9x+p;c>q&o`V|#?`?b{gdOF70OEG=tBHn2gY{Bz*O_{mT8$<`o20_#bSB{4(Q zXWveD7U|aBcI{*pr<$4Z3gf^Ha;|u4=>>`0$7^!tM_^Gu@p7DPCfd`pflpuliB*Zs2GODG6SH{1ztF1+# z7RFs6Vlre>13IjX-?6%_ixMQz>w0FHvc9}^9s8*AZ(cJt zkl-|F;p{`lK_F0)7~$D?;f=;>^XmLA)j1NJCM}$!2!RAj5+ghtzkFO>{Z+4`v4I4q zNekztLLh;X#0byEg`T-piA~Ln4J0^CT6l*f1QIAojPPt^+;u>fYxJtIfdr>X%f9nM z0wswNo{it1D#j zFa%3NiG;PKoge#s@{1JCw65b6&z)&4jB#Pb_oDyGS zVG7ksKbxg>swcX%<)Xaw%XsVMj`(%qitpyz? ztKaf83*_qhiNUJEx~Wb&?OoKu$Y~Q_92lXTnwgx&+G{ zT4M>0A81>*-R2SM=Gde03xA2U`Z*FEhQzAb>zf8fpK${tRKdGP<9qM13DiO#>Mvnd zDX)4}YT%SS6RA*w#BZNYQok2#9k5ZcR(X}GPXnjLA)7!gY&}AJ(xHf2d3mLCXF#Mv z2@=N(PgL2ecMRBgdu$O^s_92gwu&}^TG(%NA8e9Eo!xxSS#my7p#+I7eJ7~+{G9_f zmNw3!;&z>Ln*L-HsAZ1~6DIyDn{CPD&R!j%P=bUV2lr0>RbJko$vymmO`sNzmHICA zgZVOV$ztyQZIKEkNYIGNaaV|qDQgY&7Eu9W}JrX5IpciyhD_KgG+S}3@nZ_nii`PrM=TY7NX(h)EE8m(I)k$VfWDx{e1Zts2=zPXtPkp#DMg zu5cSjSXxlC0SlfPGn?dV5y3M{>^DKeCod(Y@ERqn3Rw)E0`CDIGG!8-@^eS)f0 zaI~>8s!~t2w*ozb3?(Qh{KP#pSBXEPr~D>HB%LcHSc}S6`$<=|>HEa?0kDL$kYF!_ zmxH}X#K@lA)P>cacbN_+SQ1K9)t>IA_h|gz1ZxrfRgNAihkhF(oL~uQt zG}{g*SQ1J!uiH~q8K2lb03=w8X#Lz!{j-+tKSJ9T5!_0+W&HPCAu;t-5B0~F^t3Ou zU16?Ri)?V47NXCz5$d!bTj#59Qnxfi#)X3y;MA0c~ONNFf ztxbH=S{D6ei`;T$fJ@iHR>Cc#Z#TUMtZ)~#PWKfdN*ymFyVZ$}uHAmDOCu+>@aUV~ z4hU}fgO*NGsoFO%ZCZ#|tDclmZ@=gpJ9&V6=R&MH|5XEXExP9C zntkSLHz*Sj2m!S_AcE*eRg5D6H2fa5j+yd>-uY(?cY#!&g}HL_oiC} zYT4~-N|}-BNvrL?*ZamgC_w`2$!oh?9%YvWblXJ&wXjVK(PQ!Js#u=BvT3G9 zk?qv;Up6s=Ds(JwGP<$@V8;| z-y^4dwR|zICGqAW=DIUiO;E2KZyT_2;@L3yOODgNTQzI~wT2ym`b^Bj_h>YCQ!?2)1q;SimFVV3bI0Mq}AGy!0}Q0 z>RAOP50{tkZm?; ze(q0sYF~R*@Z*UNN|3PU3?tj!mGfe|sY<`)wg}XsG|y^jE^7Y#G$+OJobH5amVtLK ze2~Qa>%$_nG4GC^ts}v; z`F|6r#U&3XP{O_QW z^UT?M1{po0wR&~Z8JT;{PKgpEhUopG7KLv-ZARhsds#17nZRI)Z+QPXX9j- zZF0oj%)Z(6hA7%KN!RMMXNtNQxQ{xgpZ4*X=soAmvL%HombtO7Q}LHA2@D#yV4mwls0SBOs5_bscv^2k6Q#oP*!s^e05 zt$A8CtVv^2w|Ga-YXBV2y>k3|w~zc_-F{hTL?49`sx>Ak&8rl8_fEh2a?zk3s>tMp zK9brsm&N{D8H(!3rZ#A~ntiwO3i5I1v;RQrbR@+}+~ zYqcxBr=rqgn-*e_UNyL-R}J)?m(|*l;QK4jS6wu*QQxcSbq0$-EspJ8$>Cm2q67)P zBlB#)y_!X!7SB;U8*r~CQH$@-=(;xH6z-)`wAe3eMtM&Z>AsJyg#_PUdAW)$+Dnyb zxL+PBV-u*wvokMOetqXvM&Eh$8XPN8f&|YcJR2?b-CbLKcenIan?Nm|KX^8}F0Y{+ ze-YKI)Fg=#B(U`eaingP>US!Ks?lY$)e@25`HGh-n3q@tYGJ?8yKyINm(lV0)UBu9 z4hU|e*n{m{4Ub8u-YE2kEcs)E)!LEZS-3Ycl&YIf<;nDi9GEK7B2WuGqD$U7zw&>- zSth?9sZfFh&%!+$Pg>+xIZtnv(;wIbYGKXlCnnz(Q+Kz_k(qZ#DwH6>v+%$Ox3QS| zZs#2N-7%X$ExYX|D_2qd_)mHHY@+uJlG`p4JPY@1jQXd7nwPVJoV(s8Pz(E}5Lr@2 zr~+kA``%1ZS)l|8JL0U-^Y+|&roSVEKrMUp+5Lll?%ee=-{;RFt#JtnJK_xby0vFtSg{Cg;LOQe%b4Y@Wmr)S3G{;AHL2G!Uh&p4 zECRKxnUffvc7m*0((k)dReu*Cur5N;5(%tLA?miAAPeO2`_`7X2}>(5TlQu${)@w8 z#(z%vO8A1$?##>*32c=@98EV|w!3-CccO+(pcc;5g!uGMA35n_DtWR_j6w+#*t_)o z`ColxZaH_^~!lnwcNN#N-u;M`_L;^<%Ar35UEbpDGAV1G+6R3qV zKz;ArKEM3*^Y-$p_7zHypjewQ%UHAEknd{h60%OCF&2SZl;$TXLagXDUUmL)ra3vB zXLr1dmF85ma?A5aN+(Xxh>SE7-bjr$P?8wo*;u>lEp@T+0h22vI89nO8xR5slq5!Y zHb$2mr_z_qE$Q9`2~Lw1&Ia@wBS4@eF~YMkCjBUNugG9y0|`!(7S0TGodbcA#0byE z<&{HKm0VvK8%S`Pv~d0)1QIAojPPuHnC%s{zr!(O0|`!(7S11pKmsL+5uS~)|8!A* z%VfHR={>N4)n#fwoF*-t4d@+>K%gWs!n4tLU_&*rVIgA!2~Lw1&L8xXA0SYY7~$F2 zle(Omx;om}K!VexWzS2HKuKbRXX8n>2Xbusp2h|eoF*;m=X{r;*DQfRNn(U&W6WD` zxXmBttbDZ0Y1&+=M8RtJHiQzWMRb>UR~mb|e|WjtM7bJ!udd0-jd=~!JIU*t z9A+xlBqUdUO;DR!8K-N5qsPDT2zxTIdlkS8W5nqU-j~yh>6|D2J4H${~8h z^OY`nn6HqyHmk1jRiV1|6TBPdE7U@d1aoD4gC+#5<)lAdN0&T6P{I%_NsL&sxcdJf zh$bzf`}O%tAmMcH8q{Wg@Vr#)Y|DhbL#dLVP`o8E~RpHNz`n>BJiqd0p+?GXJN1C+G zf{qTM;}vPKBr#(0&6g6|E)_$B5=4_0{l4pAT1ECqFJWZh>)wC4jnSeU9y#3f|07pO z{8{qnM0^#RE7qdl*(2e(`Ykq#;+#<4IfqoH|Lv<#;@w^C?2`LKb4AxBE%b<$D?_js zNsDsGwHcNxKe3@UkeGZk+kYqrYq34@2wgcL4wB@0Y!-bgy4SA0eVEpTcI77NDI2n3W+HA zJLgb~|AUQCBFT1T`HI^WdxY{5?1QFVu@@=tltZq~uw40xB`ubO61sOe|J%E)#Wc4o zx;p*&-ER&aRa*;AmN`$qxc#}#CxU7EeM`Z~4*l-wdjIzbmLNfC{@v*Mx%6~5!TWb{ zkMNWe6U^_|`+K`4iSqn~=YHV%98A~IXZ{!)L4sBa$Of-WP@3*i=2rB6|2gf%5CSDk z6R|a=_a<73bD=gcziU468+%!zy}g`VK08-fawKk5^=Qg%(gbSpmGDWm$)6v6h5o_Q zR%{#SQ9R28X`4U^61=NCELQ>v)M6hd?Ol=}kz~mQUJJF@)8TcF5+u;mcFD0dU@O7$ z*#t_Epr@qNO1!goJjQEbNT62IHAs6B>00zwBfcNSZJJu8ohy_e!8!ES;V@T7pcbct zZP(Aemdin_oLqyHW*>(4bCe)~?>E@xKncD9idQm3Fjpu+!hWCAv*OhU5~zh9v2x`{ z2@?4Js6_}QPz!4|NVt@u)=ulK}1Xq}s2u8`m|QJ+WKlzaN~%7GFjxExkL4=V?1@s-GLo`p~wBte2k z2J%9%wTI=32-IRa+`H%#+@*ycv2%qIByhi1(gbSZu5yd;Q-9_XQmdpid6a+m*7`ig zs}GbQLH&m4;MneG?;?R(xPRNql|Ts+=n+E%Z6JYKxPRLwP=Z8~zA~qHu&=mGG;*>R z!s{F*NZ_6sJ6E{V1$Uva7pzg#w04vr!TmA3wIhLA?1gXw^NUX^v3#Z+`hQ+4K?xH0 z%rj{MwJ^6fff6Ke?@!VMYN6MK=u~}%lQ%Y2rh8$q+bxB+g5B)xde&;~{eBJ1%5CnS zXzjIIvu4hp`ULZG3(L7E!PQ!Ol`|;#$M78*3Xo8ZU_dO@ER7gA#8!C_#c& zYk5^QX#%xAxzWfFrMk56Z1@5;BubFLwO(T*Q3ACZc57nRlXKN;>-kCse5Fu=1g=IK z?H^OKEWore*qMXiU3V7sEWON4_GB&Z!zuIRZ)ut1POfJBE))4WR8t>o)#W#5vYY@j6OM16V!H- zg^WH(;J6~ho{Y1dhI#6%9BHztaq_5o+Hi&(eto};YT~8uBtIaVwLPkOzcWMj-nL&q zr5!kCrc=CWBlYtenG|XvJ)+bhwPVI0Sti>rnn)Hi(pnxIzi>tq zrMv&)ymC8_%+dj#u()y5w)JE9^dd+bcOskO+9e@#-T+d$&>%;qKJl#cQD!d41BLzK&NP zpXwT{cy7CMS=S&+kO;H|C!v*8{j9IkJ)xBt2@>Q(_K4RKTiwp%Z$?+44A0&AqYpKOu3`SJTs&lR=w zDEiLyTE6Nc#(mH=)*?`guEbBwgm^HlQH{x$8@ip=7F2j$w0HaIV)gBqmCiS>(=LYo z>z_r>xE<;0{}f7)pfo=P)cZ@Oq>Rh*RW4UnYaT|h)?XhlQB%MD)R}p{hPLtX!mLqW zta6;33kEBc;B{luEmdhced&C3kDl-jOZ#JVxi@2-Un|BalpsNA{Y1z-?bWA1&54cb zwkMC%I`_CRg0=oGzf|Qvyw3SFp)zr^(+qIVvSQ zsrH@^R#!KcL}LE?6WrRwj`I9HoeH2!AAh)=e!yf@w=P|MC$t?Dmr zXPqT zJuABX$SP{^#0Z6wAA2uRYQ%PD`=}`EN_uQByR@3GLV6YB?_f!gII(Dn%6(&-^YUY= z^IO+)Z5`PAwER&Hun5#bzX`G7;*uKY^bA>_x8zXCL!X(`^SUb==d0$ucR8i*(=*{2 z4L+;RQ{iLJM&}e8QXj%Ax=e2+FCJUyc&4m!+5lT#7{LBs?GYT zzW+OV+SmMPn;O69TqW0c6iA>J){_v?AAIfG(R++4cd?8ixCW7+9{laf-GP3t?j5go ze8mtouFqDBKrO6IAsW>wFQ4?Nr1XC-S?8zsyMLUgUimA|$=TiB+aSb}s=_z^t?J5E z6%E0A7?9Y$e7)Z*;hTh`kSwCvood! zso&9a;11*Fsg6T7IH{jBGxfo_6=HJbJaN5KeJb~s9%hvTiTZoyspP+Ib1H45=W5ND z?ycVOuhgp4v`!X*T399_Rz^jsB2J`pWMxT1@Xm_pdGl1PZOA?Hd=)=`R9u>_ zC!8xE473Q;!ZLYx+hfPP$51;)68b2Tt^&JrY!q+g)g zZ~DNw<22B@I`YRSzM~^Yx^;4R{hSHZLXYUZwVONDn0B?Vd$sx{V}pH#MB&ZzRjCWh zoE5ieWVrj!^=%h>G;)(=DQI~Ywa{<+Jb;ks%sUb&iZ*GpOLBD9y;geB`Np(bz6c$i zU+CtI3`_)itg;1aRhWa818 zC3szm!JpmUBomL$EJ1?Oy5E>RGvU!03D%-GIA_e)GV$olJ9a2$e82Mx3DG%VBa!HA zBuG%)-MpN0l}L0p1Zvs23XRUZ=Y~e-6TdE#9GyA0;nA5TNKgzOF>bj`JUX+4V(n|+ ze=IpV^OeG*GfR-5xVxb1r!w*A%miwo-@>D_?zO@FKD=*dmMJ_s^KLVWOQq9)BOyAQ+zN4f>WQeIbaY;o5S@(#35vU0KKUv@G>DCe z8)`>qBS9@JQ+RZy(V6C-6f+j?btFe;&TV*fW(g7$cR%@kn@l`9Gl5!ICNDaV)X{m} z8ZSC?ETUM;QHEMOr#%9rGfR-5DB5Yxx6+HwU)}k{w?{|k*8=At@yuMS7 zUOGBYs^LXvmLNfKck+N;GV$ol1Ztt*glL$3V)Q>fN4S;hEs|#{Em3u!&#I395oPX| zd+*PtC?eB78Q#66PmQQi-B&bqjN757K3Nqc)N7I8-CIJO+>p+<^G2kr|1;O(ePsQz zzOSC<&ZP3ZUp2(W%UM%wJ$j;3NaReTI56ah!A_1WQ;qv z_^2}^>J>w<1c`-XK2WV1rc)2}8-w~BmUiW$GUj-}9rt&Ai$E>(o3^pBU)9VnuJ+~0 zZI_&K!ex4I!7}w!{3FYkrET;Non3SDeEm%X-oYq>+PXC$U}LB zY*28F`lm&1i4tmwHD3GKL>au25O1pL)oO1VrgofMY1u%+|IrfF_TfdD`WI?fsnQMK z!m9>&E!3jlxlBT&J$S??bGA_5G|FM>gC$6ef4D?_a`BR^^8(q(*v+@~$jFK+W@L4X zKrP!>qdOgsO0S=*J<+GCaIRoqpQL?#3n$N2Q5kQ`*`3;G8#$`nkS~_Vt7=Rv;i6>o zA9Gdq#@FQO6D^Hx-q9*Vxk|Bd$+|RBu{jD_Hjt>ld!9aJ;G%qg3*8k>>T@%yp?)(n zn_g$YT%i{I&b28-wdM`wms19-?Tc3$f+a|#cyGSy@Z_AFIhO97lb!x*+nI02szUXO zSOjWeTM#1ss$r_xna_P!r+;7wYT>jeaa!bDwdUO?vhSMEeXsqul~I!)b&(Z6_Pk3q zNFGJvT9>(M+|qk8dL%u&Te0l&wk4e}%H#$58DBAhTIhAX-7KCG%7A*_mj^2O#>_fwXjUOocgc-#PROhk>kw0Ge;SUwH#$A zx19Ef%Voy6rS8=;bVAnOp+VKOPIS`%AZfyPJCvthzi*|H25+o>!X1Mdv@uG7<9i8Xv z=zKOIIvWDDsLt6VLcFyoW86L+oredaGfR-5xZCBmTaFi<|Ls&RDwmGVBLdNx3DiQr z>H9&S9i6%4loQ>uO%5prPy9Ez>qX~2IyxWF(fPYTbY=+>l;*we;n5ih)}n}0`CeMr zi_Xt4$rQCyN9Vr+(HVE$^WJkBcgN}7>RxodrK58_9i6ka^rACMs3rE5Nf?OEd?g{S zy%ZalNk``qf#}Qt|Xa73hdlM@QP2cvd9i0t?2qt3wsH8KKB{NVHgV;?ylPzwwR&sfz}1;fk()&9m|a&M z?~uxUbi1uuy633+^XyFL>wWv=z~sl&%PnR(tLyKx$|S_1BPZnFRjxa;S~pf$S|p+h z9aGg>&2qj^w@=$>P${D-xOb=XQCejYsD&QU&mcelPFA>=+#OP|mPO27a#Y<*F~j+* z&jE?K6{7IakK@OVFYAs?7j2aT3EV}X=k0^1I`3wx?=I;3oJF7(?m-aZi=P{-hXY$W z??pUk)kodyhg9Av1Dw2vFUfzMLu&B!SDfpeXot}LbNVY|y;?e-SF#DzLLcg{S{=9` zC$-P)7JU+Fl^ltKZyr)#CLiRyG@NYg+;>4X?U326973QLdO^=c|I8ZS@b%j6)cVC0 zN|3<)Ec$yznrNVjw?hcjLca;|!Hr2y^EZ1s?asVzcJJ`c6Wo!K=Pz$Z%Hbbq_s-!w z^_`zu=>Ab)ghB}tY4pCFdU^Uf4eruTrwkRpiYqNzIB7PIwg}Xkmhq6;^-}jF*{Gab z$vwBKI^*@3H7G%1N)?YdzLAIvy;jN=WvV&LdJIu0LE_-ZLuzJ&KF)%rl&g|E&dE=5 zWOiCS>unLJ^|Xs;vKuw?o32bBfyOs}J`D)p#PQwwjXtEs1nyhZcl1dRsD=CQ zgm_<%qW#|NDckB%G|&glE>9%To<5Z;Z++)#i$U_L9z~HrE$W-~^_lzDC@Ogr<-DV> zY$7mYb~g-M#X+r;Tb>D9jHAIiS>Dq1y&M1dVgRi^dt$ovCn-|O9u7i9hWnbes< zl`R6bu)PWK^n*R|_XpQgPjb9q?LEhqziY}-_3aBYR*#nyS13Wk zw$Z6aE_q>Eq#8BpC5u3XS@CmIP7SSBHU{ObGovyE#j z-@Kx{f7k4;r@0~Rz^8q|m|G#%=sT9It=dF=s_$6n&g9_LnUd~I0(UHu?rQ>fMW!w2 zy&w9nXu^`czG?|~MMi=I-68eKHA~VxmA*F^-CU)uEaZl3!CAN=Pz&3FKEM5PHMM&0 zAnCuTXUNd{kfucDsQ>2@<*VonGb^vt*|R zbg$O!^h{avN;)OiH?auRvRg^!JB{U)^UteT)yQfkNG!j4R23>dOHP|WHqxg#<;zv0 zu$uf+J&QmsyOpdiwPE|JxAoft6{D=Si$vOuM^*LJGiA|RWMgN_QqDVBE2~p~SFi}w zvfuwGCGwa#+%(lp-D+@5@BS>U#=N&zlCLODb%1`;>+O@Xs-tU5RlnJ+jY0|5AYMs7 z6TVVO&3&@sn`worS~iftHm096yxCGUJUXRXv3WTx0=1~$P!7F2`cuEOR*zbruQLCI zYzievU|-RDQit_1CGVf@n(2dlE!4uk>E(*%KAfwDmrA?jE7GDg<%H4+>kNfs`lu8u z^KTpX%jcbqz z)S`N#-@P6cHKVvXxvTHiRj<@GHOLYq?3IaoJ(HVRc#{@gECRIxZ6UDwL4MNl(@=Oi zNMh%V?DrR_#jb}ngqRqx(I=Hn zpcY-}r{$@XXM?_nOu4$D-w334j_E85I$MC==Uv<2C70eHr!@WUy-j{3U?Z=#ff6L> zjboy{^8k_}P>a%J!y}IU-NX2*aGM7XN|5-cu4m)*@^qd|Je|(`<-WMq`bh&4s6}sm zlMU|#fj@70-^rWs!fQ^b7Ui9^Y(o3U^d|BdN+`_)=g@oqJV1z00<}1|9ua6Ie)<K-MOW`a)JptRSck|I!x z(g}SK2nQudusv^NNQyu$&aFq#cx%d`|3wKBT!Y>SmlT0o>~)W5SZlp$C6^z+=As0N z4&Qn0YUMbJnFn>-UDMFNy|{|82-M;>?Va@!bHX(}>iUJZtdTmDp!)C#=(QHXy*6~5 z*Q=Z`w$q5iCy)e226LVWr4!B;K^rJRB4AI2=L!kbqBPmCO77>9vjmBN7gU0GziH@? zChy|4P>bp&p&VF)p<3FbrsOseXeBgKn;PV61?t=ofi`ANaq%KQw?w=aYEhc5WVLp` z_OgQ#Bm#XUa4rt^4OrRFmre}jh@(xxDOJ+ectmGj0_fmTHOBwL}2vMJ<42*>jR0vJScEt7HI~0ltrKx zk7L2M>k&Gtp#+J*d@iAXBubzbr75@JGfR{p5twnRgxPD+FZV^!>=g;r;@l=aLniAa z2_>jDJtC>Gol8zy>}fBmk!QU>zuS0Q3VoOIFh0Y?t%}k|4j(q@6lc-~e`js_*YBbv zlwewje@D)gh4fh#$zn3OH^e?QD|;EMYsw-&b0yY6%AvvGRq7DXrUx9k(U;gBX!f&`vrqjv%ZPRHLK zLZB91>D!07UC#!cz`y9qrAo&&fm(R7jZIKFM$~N;aXw&!uZ0AjOr!UgXd-3I?DcL4 zfm&UCbxp4REJ>#n(8={VXVr+HQ~ptc1fERe5sy~96tOOZKrK9H#>>^R+AuWCE519xq-Zk`NflM z&?9=SPumzbG;PGkAtgt`KC=c}30@1e&?BCW;(sjP@I}A|`w9s>Ny{t8;dd)Wo(&;T z3;m`~zxcJhsyZ{TTHN6~ht@A{buO)1cP-+h^uv;6)xpC}eY7$`Yk&<<*Q)C^{nVA!tv_?h!)aeKD=aKQ0#`zW zXpy$EN|!vBoSxbyPzzUEgea(URaIq`cly}5!km!3S8`-fuN2J_EyUpVRaD)@8D-mQ z6-_xL^2Q?WCe_~}Zd8g{dYTsXnA z!4kYKrSsG)q~`DaS`)pFMye)}F>-#l(#8f7tVK2kmMEz@S16+EqfMh?YV?c6)ytWV zIwawmqI8-^rPRvK)lF@3%?k1Bdo@(y?q_BCqUlV1umlO)#^84ORLcpQW&2Cs8W|Ft z6Dr4T{ha5Gbie6xR6gBUb^pgFv+d7eY_J5cYnS|7vmEM+8xiVepYP?5-yJorFXP_b z5?9P|{aV-Hx--(z#J=R&&DtxKoYrxXz$*!n#=S3>>^L0fFVxd|9)(WDwMmfaFRZ=XR$EN`>r=1x0Tm=pAZ zemnEy=Tw0dRksZ-(uz-kGX6p0Qkw0?S3jh9r0aZ7nZhcrUCZc_YZ_PtYN6k})=u-p z!@9L&yTT_i_7jseY5$PfCZvk~t4FX$nP(}u!xXQizj4_7t~@#B_o!U^dRjJ+u=k5* zpLJih%5yAgb6J}}EqnLpcY0)q80<#XPZ$}@*;IHQm7Oc9!8SkSsm3+PJqigt3oF=4 zHghXs0=2Mr>DHdLtIF0qV~uusk|}(nAKy~<_Ez&(V&dv|RjEGS9d%=?Fa)3JgQw2m zPHBC@MxUO_Kk-D3W4rE2lpulU*9dX-S|1gC?E7uM_2AYGL_wo9+FoI@YLI zmG$)wNIcU8-)qOyX!Lw{!4UOD%)8$#Uc6PJ1PRQcUh9h)tlZY0)VN*CwFuNAn$P;t zHU_<_HXIukwJq-fi4r8xheG80sJrTVe$uv>a*rgQ?}DcW;3+OTs!iyvnlGEM^{t&Z zBubF5&w45Ib0@XB)xoWEUrVj9#bHZC+j`ez)1K<_(#O@#=D%;{3JE-ULGME@&{sWL z{8#nN1Fu*FYGDqA==gM?8c`$DmWCUSSv82K^slSu3lDB@y8m8! ztDmE%@w5#gwxnvKIxo*t<;?A@3MEL;+f@lCS}$((s8d1t*B6f1itC7$M*i!)SOb& zww;^(l0~2voRaCxD+igF$BtqeP ziTGBdeWG06ay8YFw_c1ITey_MGkx%68{0E~~cpZ-ciev( z)LY$s;H%L*>rIJuV4Y=Qy&Il&d3V+5QuS>aq8~}DDJ1ah484l;>C39dlXY<$#-vb4 zpqBkMdE=itsaI#eu{GJy)Cwg?Q19Z?J@ozH-PUSeWU}fzGGwy|)S@26Cl=_PnY!0f zAN*POT9kwmd`gKBZNH~?rQi9f zS6jXJ-1E`RHWarA)WQ=BgsAj$4fWYaN1~UUE3Z(3gk9(N+tpDm4n4p9(C}jB1WZ0- z3(wWEiO%(Eso~$Ph|6-JghB}t_8D76cPKSEO_8{#OG{YmJKBAlfULq(RX!6mv33MBDY1L7Pb6@I5;qWV>NPU>KZu;c|D3HNZ4mnwVc$Se`Ypb(2PE;A6t+=UkKH&`sJO@_4C3L)&8u$B#%`dAG7J*vSt`g3B z{a031t)E}I^~krCO#k5gVma_Fe7)EC&C05O-yCth-itKn?eH7@NZ93goUWQ`e0$Hf z_4m9JdYC{hY{z6ZMW#v#(~| zUafz5i$E>=1cCn5>#O$nuSLZ_dBMy}_!I{us2wMqTU%&Q2eq`p_tEoD>SM}4>Cd5Wi9HDeBQ4no;Fq=4qg;>|DSvcB}mvOQ*61}NY(0EH>zyc z0v3T&{mpaz9Ej#VgSvYo zH4}7Q*2=YbiOJQ*f9SlWV>=qF2az|o&1{@sp#%x48$Jt7pHq}0O6~libkriZyhWfE zja_8hn^TvqTwDFLHf8+5`NgeyI}%iz2`8BKuc=g*<%_r9&0E?cPz&!e^gUYCX!S56 zv#&_?b`sArc;cU9X7}{m(LUE8|BK_*fwKp3{p!&l&FQFpRjTy})qQ1! zXlMT-i3Dm1F$k#~=Ee~u>=l0800L61IjhEO^D zDc5W@%iG5zizJg=b{WYIPXYEl@q6Dvt{YHpvMaQd3zx*3@_u{8MEG^mNbG0ysLY&_) zR;B#VzkP7p7bQxNAdm2wUV08UY_$3@XPWpYEfHAI58`*5AVb+)_o8qNKk(y+Uw^z^vLkNI21i!j|@nl7M4$l&z?oAE%ysWzxsJub05WL z1>w0kIG@u`crVpdF*{F1U#nQsy2n8R&*9N)8G78!RDVQuSC6}RE!3hBoa)~j+bf@J zq@q?-+d6r40W(sw1PL1F`2-?6e&DrGi_&x@FRJCa*V^>+{`!s{B}mw(+`|1SlC6=CqFU>xWcd6HpL5~!Hho6C_ms>}PsvacN>ID|N{|hYsP`M4Q7Qa=^Ho(yP@1){_2_jtAW#xY5beeD9TTb=8}-Lm zvRWe1tc9nD>eF=BS5-}S_1XGGQ}3>b&lg3)UbzcA+ji;MHa)}svt(J9pN3Oy@|$Rs z_TF6zJU@5o`8mFKg>O;em2@1`U(z98Md+PdNYFESx^B~|(?j0c3J`(`erpQ}N|P6e z*6Ti=4N*|rz%vr?WE=Z^&P)Mfqb5*-g#9jAQUq#In%^Z2mONMvmLOr5Bh*(+pcc_o za__ynZGZPs6)t71`s|-8)_c_WMz;O-GJVEC>o-&mycTNVsTjINC480LPyXpx^ac0fxZBZ` zK3O!6JGsdhCe3XuoIovp?~3R!f>41HN+Xf*Mit~Lj9@LI6WVTo2-;u?X(7Qophz*{ zy*s=XrCE#8yw@n4;1ZG+rD@L3RwzF2ls2dqW=md3=EahEi&riqt-uB;00OX)V6 zci-%wV+mfD(rizkkuoyk|1owJ&{^bMA0OO(aagQKaVZpNp9wCDySqDuwn**4wYXbx zEAG-s7Kh@txG%Q26^HL;r2J=q_k5i5?wiy5|IJM@nM{(&&BOeP<`H#wF8hhFRMLm+ z^X2|KMLCtL6l?2|N5pBcLMJQ>URS2A7NaO@Gn8iWYNzEny^S4oR#c-@S`(f3nk zacJ}?+OZWKU5Z`bmX`MzUQ#c)WkEuwt!I-?rU)&=%Ga;RuRkpO6Je>O53c1F0T0iU zkE%0^vy$$L{MJ*$hh@R*%CyxM=+uaJ<=M8q!+CzM+`11WES2J=Z9{ zo{r2w3tm^It=6L`)fSPD`^$L02U&h1ER`gz`!8F&_0KJ=xKtS@IxEYG*qBi(a#sG` zQp^8$3$!31b8AJM{+>XUGg{W73?EjED-tqowFO=6rvK9aekLrH6*+4whfbgcuPe)B z(R6kF`uhLrb!FuWRal2V6IOID5?F5*VMP9#kq>&T6~c9*NG;h z4Bun40dg#+|1*3bfvVM)3?g2HznxI9gjKH@rR}iUkHtGNMlau<C zo};RmMb?BsKPSY z2y1+$*AEhSpMFoE3Tq*j5He-%)Xu3 zMgTt%sKN+&qZHBBa*vW2u}(%#j3o6m~#v!$&OPMvFzu7;cQtmTLLW=zXNciqDpWm6lhM zX`2tdL})?6N?YYHt}h*#_0FuE;Qg@t{m79;SQd+xcg;-yxF50i5zB!pnYJR?Z9WvV zI0@NGWNsy4tYgRoMi5&uwep*=l{Vs?rP8{CUAEQLTVJKio0xBS13jI~a}`V8tb?Ae zacNa-35nwB-X5Japk6zQ*j*UE-xpJe$qGf4cZ%?E9$TDfC!v_+m zD(jtACkDOQXD8ffL1IeQOgfQ2!45m2Ac3m>@k;AN?wscRuxi(h79_T;^U(?KGm#D- zNT3SuldY~4v>+kxxopRW_pi45a3g^#yqmfYx7A9}f`pYec0d^UGWwHW5mIISJ>ka)djl1}`TD+LKudF?iQv`E_7o+||{NOW!zuKOqw-SdAC zsLFZWtrM-HhB*kdAaUDgv`%cPgJ?lw=@ft6$7!#*j$9#uDt!Ls{WE$6 znX1z9q<*Txs(fx$re)l|m6qo=T&~+#MhO3ckQOH)X@j6|kV0Z5KK{#{DtTS$1JCEs zzjMYCXu%xHze`%4qwzB#y-N%F!;?3DCg^k!{Y;Ku5c;VhbV{>Xj{iRV%kf&6Lp;&L zPN2m}Sf`ZG_mA)K^pbaK-bz0y#3~2+o4<3Pes4~^-%TY?+C~u#*Zt{pGNg?_3ljFT zMbgDnbRTK9w6RVj(Mu=^t41a9M%bJM~<-`6a3=lTe%ls$^Q$xzACZRY9RLQjTVGxyf7u9|EW$_VcLE`Shg}RTA`!g|$05u53 zNuWxmr4NJnb7@)K$BV`#1X_^T+HHpJW6UcV=VcO#lR%YBOCJVt^;J#X$B`!41zM1p z(R{M*qvZ3lQJnAH7m-1y%Cz@`?I2VOfws ze~OYJBb_Qn|2%I`SJ4Mvx4_4ly6=X&q=LDsG@LPi2DPD0YQF|}S_c!H6nEtQqFjZ1XG zeAfy&b~Z;yLXN`Ck(!XB^Vm}BDYTexWFg1ucqN^1Qw9Iz0}1opE^H%!p9oZ$qYq&l z$wpH_;PY<+S+jI66f-^2CYG%}t2 z#?;ufRdOR|=KWw&CDXDWlxbW|&q=3sn{^ zYsAP^zLZVakY_2xp!6qVPxX^KwyYEW<>Rbq#C9i0Ezp95 zOk1bG89p|oEXoS)_W6mhRPstz+8}bzyRY6p(^)4h3tm^It#jl4H({xy4=ZgDQ?|}m zbKf4Q`>-r{U75Dd)uTA!=uuHuYXqw|(hmNKuvF5Ab=sfd!%yw1-t`-z6P5+9E7R8B z4Wiq-8tU8xK|c|eO8WS*6L3Sw&T>ua)=*!jFbKS}X9A)MPcx%a1j`>%uP-RT zt_;p=J68>fH17}UwNR_tbt=c&r3clApH+6baxxo%Dm?#;ey#cHId%SfFSfl*I))Y` z;xFH;`>6IMhI~AjbXQHKlxB&_rmzvH!YCL;`L|6f7UL6_rR|bmkFJrmE8}jE*j#e0 z?&D@#dBWYaU0&?-aCVH`?g^2(Q5*Q^$zdm!Z z2us$_i(U0@s3L)?b5E!1KH9XErzWIJSd&dknx1XE)=WhU5*WKizfqMj361dnVlR%( zuo0+=w{n*5<8ouUmf;?hf}QVIojqDITSW^JGB!)rp%Ldbtw$ynXGTG`_{M!3fvQtk z=jlEs<}Xh^l3z&4?!NJ2-T6dEwNxo9EKJoFjk79 z=-Rwg^U<#lZ|{-FMxe^xc8wm(SV8yvW{ir8&NRmD)(8n(sG+C(C}heU8;FDSzBAv* zqQZ|6fC$FXk|f;bn^U*^im;6UbRS4qX{j>b^SVD03wCCaoh(*H7Ow_5tX zm&iFkE0g`Xw8-}a#@gZ8mh{_zyS>=Z{a#}CqmC}wb6T@hysqr+ zp88hpq-;#JzeGaU3>$$ejBus%`mUv5Gj>!H$KTDh#l9jT`(x?D=&1ucWM(Hr@`;!X zFKh&=FjALJ9$uE3ow@5Jj_0|mq6G=rA4?xbPhFv1d^YNVm*`pRy^TPX?Cs?JFd{&G zmL_Cn=?lP{Enif$AR+r>>BH!$Pp$i?c53e}yvBXE5vY>=qx4}!vff+qMNJ#0w0O2I zjxCZE3E3Y@AIAIK?01Fickx=NlKrmqVMOGbV+LW387vDDa{M5D7~_)5Ew`wAbbaw5 z_?e2=LKU9m|I(rL&#!iv&J5^uV?{q!yxIZ}B{k(MF)kezIz%6o=Fb z3-XFOV+z>Ldqu+j49+x0mcklY%96{tO?+zQs8;^n81I^+S7D7_EejHITq^6z81I@R zWW7(sYoW^eyK%PquLx@tZe7=+jmR*oca#08oHh9Dis5n=C(~98j!aw8TvBKBhZcb< zq<_o}oP=d@`U^W5qZ%{F|3z3TNn7)spL1p9SE{U-FZA~_fq6&bM`W0pE4Nj0BrKKm zK{H`tD@QD0&5@YFWm%krH5dKggr$-+)|H}k`&gGZ-)YS5tUD-M2Bxh# zlsSSsnmN*hGk^W*s4iGlhI(y~Y&n6_&Ae-oBU`moXl;niO7{eFFPAC^V>z_fL5 z{x@N%qz@}?5GC^z6Sa1h*L_$P=>yYN)TW}WX))iomUm{cE>WGI2ume>{AeYeCeMnx zdbG2M8hf9kMf$J^nU+tm_0&?%QZ^A=X-&pSSSq@kWV!>j7^uMQ=G z1X_@gF#^(u5pVE20##;Ifk{vu>8(W809ufc@dna|5oP*20##;&f=N&v={{r)palsT z~U`fw*7Sye>~5;87C`Y<9!OhR!Is4^o-Ok&d2F1n99J@2S! zK?37P=~pm_czbL57D=E52^sk$b7jO}nLd=;4gytXtdvQtk6T^O)wx8utavWnf`p8l zl0J;MRFhDg1ggwPE0d^s^Qvr#?n-^TF|;5dBdw$lBL>SP6eocyGd9a4@?QIgz8)y< zma{?`T9Cj+k-N0}?5r|w;4n6|yegQ!-W>;$T8@v4g1Q!BEk zMhg-$Epz+x+W;*{$ajg%mGO?k_XiTFGT%fdfp0amAR*t0(ueV`{T+cS^IdBa&JlpT zmK;r(qX9jQv@rtMb^1n0IRZcn680!l%ZD5RAb~1-u5cuS*Oh52hjJVw)5iGfcLb`; zQItvGhzu=A$nl)?VT==hN1)0a4VnawEYX659G6NT#(4L41ggwYtx4br87)Z2@wN0} zjN5-lpvoMbn}j*icT){m<96MGgq$ZxAIAIx=LUE!RGG63lQ3s2ZmI!m{-Iltknsl6Jtz}5USef`8Ay+0W zmAOh`63&$g=|f%%3AyGVX=7#LcLb`;RSJ`Eu1rWD@>)p9H3#X#Sef`8fhu#A!X%t4 z6Vivg77}u0Li#Y)8Gc8g%3Rkl33=z}pIhF0v>;*KS;L2}*Z&i{;-z29N&Lu_K^Uvs z!?O6%2=WV;r&gUyWTX?MjPSjGuV3un6(wS3Nmja>x2SV2zb_KEo(yEU*2VlpD@yt| zMOoZ?!~Yteh2}#yPBWHzYymO+_;jtFpFeBkj^QOc_Hb33 z?9c9xi{bxG2y@|;6eZ!vGHiR%QsR1e5e={PI=w#|H6w;sTJ7N=8np0cH>#8r9d7w* zcr7I27xHJN!(;fg)uky{ciNO?oAQ=UU(Bnt`2MG&HfN^Uf1+jc)oYsvu)4GV){sEe96Cq7<)IkfYG-aD?$++8KIt)7 ztj}{)LkkkS=Z3J=TVnXiJ&cGu?c=D|dxx-0Er#0&RPFENX33AnaF2FPiKsT+OHDR% zs5m>g#R!$YikTYo3axTPgmDc-5Cb6J^txA5~zBUZY1+O7Q?%Y3MC?&oA!9M zY$rO;oXgRIL_p1vEZepizB!Ydh$Q#(vl0K@;WZAgBIyHT96q0Xbc-hKK_oHM8uj_1=)i&h15}Al$&iAi>hjWSPnLm`WRnND^%V4!Y|N^W zHUd@lTn*ftUd_?Hm0+*GaI_$?FaA7Mf_%KlwoUqYn^nC$aVg(3ub)5yRahewb=KyT zZ``;&#a!>x9P0;FNB0`_=9^>}`M9t`@vYo-h*)>8D@O|w-)b#q)hJgV3QD5&t4Vve zYzk%z(|FhjRJ}O7ians(-Bo2L5nb5wsDytH5u0DPgr-wG9YvZhPUHW%s5(*sPSSa%Sb*7O;|!i_|*&A$%#YRtMa97 z1ga8D*uzGVj{~u{sm~H#=a1&1rq4|~ z0jeFB_cDL-v8>Q+BF5LvD}u`ncU3xGNuULzO43aNSK&#yqty> zBuaKZz=l$;{@pczh_A`wi=YT^k?HCSjs&Vkbw9ua^@%UeOQP!eV&WnZ4~M+el219# z0_lC1Io}@F_Zi38%LDYzD7nX#C-686I!JHMv4`l*Ikn#cUOVeRk#f)^8-c1deWF<} zdaGsgNI*U^U1-D?r60-;=WVT_1&P$>kFh~VVz`(1gNQecsqJ1IDwdX;Xd_V7e9cid zklt#~6BQ<6(dAP7N`)Zyt?WV#El9kqbcEfaH|Mnxm5Hd;!I$r&d*15(J{y6m^mPui zv{bvp_tz()L*IrXY~TVlI7JLc3lgg~A7b^XcALdCC!+KFCfvPZkQmL=+6YwPy`kNh zqYm<|c{_@2k>fa8kjS?50NX)6+70VZK2Ap`7hyNNMKjk`8-XhOJ)cygxR}1!Tg*Cf z#dZfbtUAuJ(fuzsag*)-E6R)$9Ym^#r|QIFQ5v=kB-+L~!3wUA;a6V;P%DX-Jq@4O zErb>K&mM&Ys^qtOYZnRqs&1{3ymg&H;v5%y(Sk&HsuOJW(ilGK{#`l``R@KU;^d0& zJbLs5UnEd9l!%Ws7kQWbG!X+YW)wHS*AbE1ulk||i2?79vsE?G5lzQV=7G}# z*vp0~Tu7j**z@CT@gyQT6d|J9us>O?E-q2-$Y{PS(>T^}YF~XO^x(;O_T-OFJb#w> zK3=Owu);+q^0mGEh)5b3qb8fdIfBGfE7rF}PK8iB0X&5W)J5fv4c}o++P;IX-&Z(#zej)7Y`6t?wQ7bjHAc6BM`h}wbAvD%~s7)`rP8)DPkcHhn z&xdSZ;=-8_&X8!F_$8Pn$`F@FjM<=lsXB;-yt~9-6+L8|b0SUUP=Z;*ELpf$;l0}N zxr5mK_c!?0Pxo9nE5i8|#WWll!s4{9#%oPIt97|Phz*{7pL_a$ap4>XX+=5wxio8Y z@2O9_q+S9?tT;k0M`y&<`u36++94xGLYq`!G5H7bt`V68T9CjoJpIDa-b(D)_qjZz zaylDhoy~3sKIJ2hY$6|x0*{2o@`MG|Ll0B%FE5AK2vlL2=#-n5 zxz#4&dH99CLj+ooz%jg{EUY+H9Z~s1)QwgFHUd@ly1K9`xmeM^F26Lrp1=_jj^X~< zw~ck^^ptzdmLtnSBOdar8B=N%JUa`tAc3PyMfvn$3GaSc;di(7w-Knqd!s0SuU^Be z{!^A$NY_W81qmE2D@vX$ZFsK|*|bWBhS&&H;hj~K|7s)=9!)-JZBI0@aAbianaA^vvoP%$Fa2pXjbyg23>NFQ zx6wKd%gWJ$1dg0(rKnAyc>VaSHua9%Mxd&}{iAH=Oj`5z&rY>_dQ+hI<79TedSW|{ z79?=wOuu;_5h{W^oYV4@ZyR-e_;L1a@V`7so!KrN$zb^uWyF;bakJTbP0V*`3BN|O z*QYP&@9pMCkF)0YpX=!*(a|i)t<(IELEn57CCkGQQKA1w?aaRH8d{K8djB|!_uvih z`DYv&$plmyBI=B2%~N~Mb)gTWt8b5Ht@&wl%rL2IKXEqI7XIksI2T%w@b7Yj?$dN!*{>Y|7RcbSTl~_UvYwR)h~Z7@lU+0;zGdymyH0`s%HCGrp9AU zAHy>j6x~WQk@nh2U$o$L*?>JPNw>Cq-i2h;5*rOKDk4hyh`ddYMInKzELo%2&Urmd zAFsM47lp<&5w)lIxzK_{*Eu`b*@d-DV#?DOd{;~dG4@qD4J}BtT(g;F3M|Lh-Y!PD zTG#9(KVG}1_%Q5G7ZRwNmt+&0vbePAqnOV^ZOF6$v9II=UgFkr7CF&_r)^u;6&hzX zJGnU@@7S=u>%7M@Ry@>$XDQZ(d>s1{sg-j-jmq#fRG@$ zbz%KLQS|Tm90^q2W=mPwAs&2B&lW^v>^ayqadxnnIWh}J3laf6m$3MOMs5`)*MGCr zk-hyz^+q{dbxuXF;R8K*!0lze88=0+9+XaB?1nGWijwMBZZ+wqVDWH4WE5JEs7hDr zLv&gndCwyQ{&S5_7%JNDsHCAKBHv=RfK(0d<#pke6s2JJ9#>fHP|-Wx6b&s%q}#ff z)%Ew_xexo2kL^3>y6VOa6*t-(w-Knam;BVW-L7%128;cTx~kH0e~<@XmAa45>u2-X z+diJgeXg*Sxq?0Tq6_`Y)2hLaU9Li_2Z?DlY1IKNNVE!D%I=M!H8lM+j$o0zFatt-m(=AE?F zcZZ6g>6KL^P-U;H+Mm~I$(n?Uv^N%M_zX%PnHL!C3ZE`Td9B^l+Eok{EoKzb(1OGe zD&O!W9=v36*>_&aR`s<16k6m|)UQ6kV z1gdaFM^P?62xi;7lJU{+=4iMsg6k!?#z8Z$LBVW6<#haR@zu7~4U)P=zZmwBDXKh%L`omd{Bw!-W zF4PxeqL7#YDqPW{b%uw9*s@VB(dTL$4J}CIDl?L0tucWQ3mQ#6&JeMhh&K)bRoLDX z<#_+bEYLTlxcZ@?h884>)(T*>wI-cUn z1ltpZM6-}Uwl3x@FZd{sd~_iqgovIF0#*3@)B4r=5Z0o~buC|_6}FxM3ET}qs|K?| zSho5%v|W|f*$7nGR|h|B9Ly@-?&iw$r5DF<|K*boX8-o0S<#Aws(m$T*SH>RQJmEL z(Z_=vEl31pbF*}%@A4y!YSHYj8|%udbzG>mYjE90pbA&Q6y=^;gB1*ZtzDRz&9dkE z_(TjMqKtz;6|R0MO5wN1)iU`i@QIhZ2(%y(R&O@j?mo)Dzh6y0iW1>N!~_R{DqKOL zFF#v7)k94i@%c9cZ7W4cG|IPxRjzS}Crq}He5@tnED`e@1gh+7WQ)o#(A4xTdD1ra z6)z+@XN_cjB@c1&Fp_*MCc^a#0#&#kq$tf2u{0 z4@p$}1%WDD*HV<6?!@AGP(}Vdb0gbI5fb^6Xe>>YQ+#JN`3+JMPkuq53RjIN7J!!( zT0kB?s()dD79^g%Jir3({KFd!Y)3wJ5#dLK+d-fTS9gfW-&Qnsz1LQsq@7c+PK5-n zqbSOHBBrSCwI~OHDqN+aQ)qqsM1|H{wF|vg*w(L*u&>EX7}8&qx)$G6`{V{2fht_f zqH~J;LdEe@i?mO#B5bQsxXy&DJBqUROn^8sGYhXUy+20_5|~3p;Y181qNamD)wf+o zS+Zegc*lY%=zdJ~X(QTB9?C}Ol zz?QElLy5@w3j$T+D{NzF|6R#PUz|)ncDonS8pc2T%Yv2yElA)KOlJrYQQ#K@s&Hx_6?0^bZjh<6SG zRi|%)q z<_FBH9N~W+?kq!J99e@WA%f z5>@yGlX{;7}Gh7_0M^Lf34#| zb+w3yi$t7u5U9dBq_1Sl{$l0AxA1p^6oD2b=586qigk(P+mhEKAK#b$#Yz$J*+HNR z+k&DjyYweZ{rDO8+nvkSN|2Z^Ae?n6Hiy61AluanBK{zvkApxJwrM(jZ|r&XOmGU3 zxu(6fBat(B7IQBf&)?-5PCmL4af*oS4gyv9Y|?MSDHi z@(5n&*eLQb$0S}j2vlJoL;Et857b)B%qf)UYPQ}7iO}+E+5UDTc<@YFj!`BN$3dV9 z`$|RmTxSk%kRzMeoZQ#eiz2am|5oPCFrL@$=SMz164CG%1gfylr(Z4T55m;3hdAz%Na+1*GY8W0ic zAW(&43EE9{$6u6K-kuMgQ^hvQK;lum<7~y?>%3?AAo9_k2wx%s9R#XyOhmB&--FnW ziQBaMMYD0-e}TI?uwS9tUDk`WZ#0(g3Yx~zf<)=Vp{()YoxHhsBC6d0BDxc?#6h46 z`xQlrv$!@(vFSFCQ{)^+3leVnwVtaD=JQe4@{*5)M5H6)-@YHRGMGBuk1X_@oa&soj zouNBF*XA$safOJtL?m$#sKS0lQ8xS5P@kNyEJkI?F3^HRr$rI0UiN0ZXzIG;W6N&{ zRAIkD-*I}C*H)zaORUk2wN*r{bP%Y*ennAMwV28$ z238ThJktrZAkoERD~o%uEB~vaH~EMpVmuMO9R#YdUs05o!{dl)HA;!LPZWU`B--!W z%a)fP!PTsPl8;wJO#KCcD(qJjrO>64Vpw2Cku$+5+O7AaCqrWWgZ=FCv$;Hd`Ooy! zmLOsf5uOeLRoJi4PT5T@#QIG4`Q~Hc94$zU%zu=n$-RTG>A8`7gcC83h&>JhRoJi4 zj+7+>MMSf3p5|Z@jus@Il{(I1JpbVXW|WuZAfg`;^&AAMuqRTKG!en9>Z+sK>ICsQ z?ia&dXxOjN+0p6yuy=_T@+8mNbF?6FIaMf2_s1sg*Xuat>JSlch$!qJP=)=9qO^%y zkEQ4yM`X-8kD~>N_WMS%!@Z{PQD>i$kLD&(!a<-4`xQm;i1c8M`xF*oefMy*Ao05T zM3#7VAHMos9BPSqO(N7mpbGmH`eM@gjyf?z9kFvR?InPo42iU!GuhDrHTm>)vZwB9 z5*r)@s<2;ClFW5a$M8=4e4;#*Ibnc?$WMPQ*AOwmAq?VZWj%-{Owro^?8ku&M_+T98Q4 zcMF^MsXFg5^by_j&qNd?BE&(U3i}mBx!vP4_Z?AJv~IncqXmiFIrp*;zPMkxOLIxETfAty8(SpR*PW#!mTa)=f;`Uo3QVFNEXy9xOyPed9bf*b^@uwPLWmTQ2>b$TiP&u_Gb79=Xi zInFBFJIgPYyG`G`yoqQ|L^20~D(s19uR*FHkzh#$o~dU`+pZuSA>l4&TK(_}6Y-lz zP<%%9D6}A9@8PCo2p0eJ&c#zro$W#bRrcM{NzaE0_rLqK=g&QT(Sn4%95u>>iLcS& zTC%knG$c@E--VR7bf{>eJ<=jl$9JIx39L6dZF+f#NOJXqRyKEljX)LdNK%ySf&Ins zX&d=}S-pJGf&|`8ihU(wEfLJaPM`|+7tx3;ys^msS4!c|UO+<&64)x~i6SB=5k3wA zRk*)MQT|C@SUmFZ6*uba*3g0kK3%lxOvGIxGS;;dsKVVsin9FmYkp*FTaj{c5{?!m zu$Q2jut}tG5U9d0{Ittra2UUu)L+zZTa=>(3GD3@2e=G~;MN0^dHgd&eXuI|x+a7ff35 zI`LQ?Ua*a*IkW{w3ljJirFa9AsO2C~g;IH{DMiVYMcAAj?LEaYCh>X zT9Cle8LiwA(TRx04gyv91(VkFJwn*&TbHy)vo2|9LBbxPFmOQ#yVB&E)@J!S8-XhP z=1Cx?>&YuZuk0=rtbwklkEyCE_7JjZc`8{+W zNLX<`*dNok?Qy}(-7KHlzV?V`&^ZNu1-YQ20%o}Q>7fhv4U(3m=pAA9g1 zQeE_*)1K><16f?JE9&^%i*foe1 zc~(f@pSU+m303Y-{5#2V_Wo;e^)>AmZ2x){o0GVdIy6O1BK|60pPgB8TOBazfZAo# z5H{xIA-#4F<_u=-D(zDL^3Usg=I`Mw{nxqr-^s@!e-Zs8Kz&-W7=K;kI7`1XM!hoh zoU091^OIi{RfKMY>1w#=mIKKyb_S2KRmSn)cS)#1;_Q(awuT3&R?cG&efUlD;8 zBo1yqsMCuVb|#|pVV9`3?5(RrI!_ycs$SC%vYT0Msr&P^A;N!26Y=lOv#t(vlM1vT z@!0pU?xVm=xz;zPN(ZrbLo&7Y*GC))RN3$ObNa2{T!-jG^0!+YElA91bj+yf)H%q9 z;u|22YvWz*4otEUsKWL}E09w@y22NxQ}1;N5~*{|WrvQQS107!pvwJ%@(%7Rzf0YD zYbiVAdsa;~XAAkLefXu8YhD)hLlt@#f(3~?r`PH9e{*E~dDW2TTFS1O)!-I(0#z-S zu4AJ-&#JrMtS5q%oyv>0%&0C4A0W_zME|FobRXgCWc+#Cnp^nCB&F4VBYW8hRAK8; zl$!2n{-nwu>Y`%ZZS4w)RPlG{K2}D{SpA0clZhJ_ld8}6HL?+?!Zt>yidWpBwv8^N zR%zZ#B#oKOKCZf~emJ{WEz@RZY~HcfX}8GeY3ktqDb#Fx2iWch5^HMB)#>HEWbKX( zd*_<{B)yuhz5NcN3h#}gy#Kc&3;&u#<(KdBB-@6tBUfIjmHe`*Jh@xHu57Pmx(#Df zb3am>wQEa0(q65?(rjPlQ)YD@ffgjv#T%>BD>BP3ql+>y_Auox*RtaUYy_%K-XFsz zPrIc~?j!dad`Om;jlFiwb@uOy0xd|?DKSp>A)k3#Vd*?~D8o5rU3Se_qJXgn8kZ}_e%LK9`UgOpKzAgKoI%&@9`sG94=AXYkZ zif`pTGnjU>nwodQIM<~Ti1r_GUh0wZnmy!_5nlK(xp%KqNVZW zS!{=YC0&JAqO)FFY*c6V@6Qf<9kTgAA~Iq+Yk9Sn=_5tMcWTA0?OEJeiG1){sKW9o z%7#lZYU1qe**S`8K?@Q&w@zRK4)isB{98Xg6A$aKzz&aW1gfy!=-YO(^sZrJ2eZp- z2k7x1o^Ok*GM40Dwp1U(-K8-c)*H-P7%r`rM{-21qm7JV2uW8)w$O~SN3C} z>{@ky4K0Z&-e78t66*egz78MbHtll_rl)GHS3H{!BxEE(iIF8#8QDQ+t3UEoM>Y#) zE#p7;#ay8Z?=0=h7&<}iQ!tQq?~znP3lcKkWXK;SRT-f|@4=8bY6qVXb}r`}Tl+zk zq?HvVRU--_`SZQ5ertnSSe-;FT4XJ}PgzQpu^{N1_5qw<;#yN&qxDD&tNq{%qVKE~Y#6ne=x7;_Gh;$Q ze*J17JNvw$Emtzq!nz0OkK$OWROU^~4rT8;?{T382^o9vBx=ebRb_g^T>aN&9s5~#A5yhgi*V)&{wtZ8dS zoA>=N`?tXcb!|X7-%Dc;#Lk^2b>GJ}R-B|(&9<1@ZuzN&#fkwXSxA|oDq4^jJ!=p2 zC6g=V7sYE%zRRW-6IF(hgx4w;u6D3ldm|v<^q3y||^)scTMt zcHz8l*nVT?B}W{YM@O@nH_oXSM$D&p&iSD=MVZZ+)Q06VGqfP#?{_SA_Da77#d?eP zJJ+jYca-NypbGC3?b55zUEG;@T0Pz6z6&i#Tsw1^b*Q<)>f0|j5h2x+vKE!j+6YwP z-Bgs5T??`@A5=Cs<;Ezlj1yV%J-yV;Vzw*kixI4E^=WE)cE$J0k&&!V!YS&N=S!$| z{kt_}@pGhM{TFr7(1L`04PY=4-~LR)f+Oq%s&@4cWe&ra5Y*#1w zZPn0%1db&Pq6iW79R#Wt`VV4C!Ha5-0x}la{VIqZYMNZl)BAyj79{MWjEBvFnD>}u zYW*&WI1;E*%Npa7faUASNACV~UWPWp)hR+zarBC#%=aAw*sZZo%{y2y3GLH=^~AN> zH`;|3Byjvl&&TQ@=CL}JI`-l#8-c2deFNFM2RBR~)!q+f?Glw!a|SGRp#=#XaVpB6 z0|Qx}nxoY2-m`54s&K7__A_J)WOo*iQ(Kf9;6e)$IO0^4o?rU2ZDO6eW#h!XNT3SW zfPSn-HK5ffv><^khQ84cXvwbRiOZ(1HX$n=~sL_eveUxdS^?rME8(_NHF-Rf zwLjfR{roBw%?F3ozo%ArwPWkQG~{SO0?S1EcZsM_e78YJpF32lk|n z9&E|KzAW#<#vCn3U_WLMONq$sAW$`J(J1CQe}-DLL_+cr?_wR6WI`&oe9B)OEl6NL zM*EhCNJ+$42Z5^Q3&U84h^=Zwy4Tc~D8ap0#ok-hdVXFUEl6OmWDuo^7~&vM)iKpz z_TQO*)Mpb;k&h$ChqAm^ld1CpGjOyZVejE~o*c@CKTD?GDQ+iFHL0i3CuYvOi+o)F z7%YZ-Ug?Uw6`$iOC$3-O$}N3kc^@dwK1{71Y1N6N1&PaXj@HlL=3-? zT3yh?PM`|c0BNV}%XVVx<4)?6HrH)yeMl@)4>G^Whg8q3a@YMzA`<-9N!{ZhP=za# zw9_etuSmInhMMw2HrpyE68)xYY{cPR>Wqg$cN!D$j1yK7XE@j z6|S(-n*Pf8s@9mR6&m-lt-T^qE^-d*Qgf5aM#?CmdPM9bqN0O9m3;-$H++}cXYP9S ziGN$$3M3M}CQWA9{dTL_Kge}Bm55%yAW&srhf7*3Eqi%yn(A}DifvU5i8j;5u-5$# ztF!(XMm|yy@$eS}s&Lg%Q3j;1z}B;N>e&N1Y^#Gv94b7FO&If!>U&%6^6pKbM+*|y1`S~W#~!I$KBXfct%(>yL~;j#DqNGLUzU3mz$$(T zb~Qgd-nLqcM2|T1HH%gU{% z;HV$JI???|-dCKhwnx3+w4LpH6cRWCFo@$sJZWYpP?dJx5teSzW;Jd^bt*^r!v^By z__S=RYk?11kia<{t%VbDfr!r~>;$S-R@%?zKAxslEjxpJOxf!x+SX#M?)I`8T9Ck5 zAH_!z(T0e84gyu9Xs1(^asKL>(|?nX7q4FMIgi`38YiPPv><`AJ~|7Dh`B^`bP%Yz zv|tPS;MGuV68|Cj$eJmXCs`Q4vS&%c(Sn4123dxP#6*0`Y$s5KYbW&WF3|?f`&;Jybe>09zs0*%?eDczyXV_A6{R8*vE7N2 zaI_$St%qh4CK2HvP&GOE0XC-WBDGP+59FgBoev+Gxdc=DcH?M40$UH2!z9u>2vqIJ z9L4&T8>@aTBX|7vT>F(bE?1v@&a!}`1qp0Dw7=aX9yth9#q8M1&Ykj8{|YWgJ{~8U z#3y#@#MTYn%h7@awjMgk(N%$)i%fEbqXh|^0Z`vgL;)f;ItWxfi8Gt! zb`4bh$4ejiwp>(?uB*%D&$`Ibf&|V0==>`pqKTN}AW+pe(g}Se?th0kT9CjQ0QGQ0Od+D4gFuyUm(gt4-U#)kTaGh;X~N)tMS!z`^#~(AYq>yEK4|)mHC)b_0FE(Mxg4zDq}V=WcC5_ zaqC`)`1DLslQ-S(i+eG!@50>|^bGbMD8}ubt_ErMHMAgsy%L?IL&O#$X79BVsG7O# zC~JS|kUC_ve18;Z(^8!6|440pWduhH64)!zo^2wci3oNOs2a2T01F$mQB^bLr#m?H zu$O4MBO{yN=`cqN64)y#%48y%5V6uhpsMJLC{|+lLiN07Bl2-dBzm zB(PVa8Kg-hbr7gpzIq!grA$?u^$j2&6S~dkkZ1T9CkAiDE{HSVP2Y2Z5@G z?IPKuHRII=F*1s-bmFO6{hT$})A@f2v><`K68-Qy5sip==payaap4lS`}%lw(mJ_M zCgy>s+K+w%WLEcF0xd{juSCDiL4+R>GaUq~s=uDi_RgHD_MIV5p=~q%n3^eh33fDb zR)H2IuvenJI7Fl);<$rARrHfd?7ZJ1b>ZAF@{uAaGdq4NJzI7-8SSe2VL<|WCHk&L zL^Ki09R#X+r5eNfZr!A+8#<7WjT5S}dmHYlf1Ib?J77TqdnGz6jEGxAWN;9uN_N)G zdeu3i9?v1)oIZ8CvN*LTsXO|v<7hzwdnNk*LBtXCT}Tlo66>QN;z`KVuN zFzc4-xvOe)YmOEq?EO{xXY}1JLnifb|FSj$RRjJrdbl2!$Yp^(+yF$ zmkawYTnV8V#n1q8rgM09ZwsKS*HT9awGl3%@(p0&@b3bY`Bz0&UqRN+bp zMKwOuw3S~nv(TKi1X_^5UWrb+eV}Q}h#2M|P=zZY)QfujL2Gd7+0t3H1zM26UWp>y zh&V>X5(j}QTnVAGcNPkDQu)LzQ?E(_El6OmL_7P5nEVR@Rk#wOD6Sgm*_&|>)Tqow z1X^qa^h(q-5b>3WJq`l{RiMs((}pffgjNSE9E85qpRTbP%Y*l@R*! zQ?E1o_Nk?sCBq4h79_A&qW#oF{PDS^n!!P!3RglDW!s5B*6`gvS5UD~jus^B{Z+SZ zfviEw3Tm;%m23p6aP5TFsr7%xuchJ6Ra_m$bzh3$2_6`=`$L%cTboiI=e0NjTwK@K znVlkBuHtlWd?@PE(=hSu)}wN0K>~YM+P^!axbR9;mgT&&$%S8a@%u3D{-zU}%9R$q zHkD!zi!5=W1qsY8y`4i+iB)GBiCZaB+Xz(Q9&tL;DKw4d`X`Ld+tOA4We01&ITBbt zqiX4Er~d1USi4xG_LA3S1^C&}V6iHyi|vhrgx$xMa>Yd1Pu^_u_fHyHkg)HRJ&>=k zSbo-L%R!I#lNZ`&~+R4%K58ilJu$cU2 ztc^g`?TUwWAMw`9UB%x9L}>TJLs^Hd(>2_C`tk&gylI#J3(;4_J<0Ti*ZVC`SHFQ+ zk#Pk_3ler8Wjmx7U7vX~?+g2E1gdaPvZ5p|lT+}O-mKZ~1sp9%V43I)p<8v-D!07Z z^-%={?x(EWYNlR}w);1zxTBR$PpV(uH)Kkf*jllth884N=Uk%GX>-V5YT9?Qn(x9L zp)A*w<2C|S_MNhiDoylV{?41l`&2?ddDz+!?IdJPKW!j=9H3t~O48Ds4en$oQQ^7SJM(jX)Ldd#2O(lE%|sw+<5vSGhH`An|Yc zJ-UyiXXVL84KCHy=06E#>uxTv5vam8O>?!O7x~Hu-Ymo9lmabCB+RDiK3bQM-zH-A zDxy;xZ`OI|dyWLEu;nYtRiDXf!~t*it~Bj+hJD(&;}_c)y>Uj>^?m+4Ogz6bKME~K z;0|NzsUtV3AJ>#&Wiw|JNT6y-k#SItrneuci#~X>{38 z@)sH9(`Ed+W95}6UGYbRvV-|^=)cuyS&*>5&)+93$^yT6vo9g(IbI7@_FQ#~D9WZN zW!bF#NjO@N!0`h`lXox8N)0W+HuXqoBT$7kLan`LHx_jIgqm%A7F%86+7i|qty8mh zObLFaMr}&K(Sihi=cbjSTFqIzQwiA9M2|HjP=&jN=vPU68?oq0DcRMcXEe0nUT3@# z&Aj3@U~PFC_TA%<%?A>=x0=r0$yk?V$(4Z(xx2$gpbFa?MGurL!79!!%W8G~>Wll9 zYLp$Iw?5|%d|EHbABi7Bc9D7RTi;y zioc#d?KPLQCZRY9RLQg~xj~Fs++6qZv`1ow79{Fs9H9GHUuZsQ=f^Z*fAvopHFaEa z8-c3i%{u5lYFv`P(EWW<6X`>#S11K@s$@B&%1$iwD5K{piY^$s1s?z06M1&{(Q};2fb4`X8Cn5bAME`9`b>d>dW;R07 zma2ce(z=h_Id_wG=ZoYlrd~YlOL!BVuv9)9%j?8|fjgOHDc_qWg zorMo+9H6+5*6nN~d4T7#HP_%bb4jRzlo@x z>a6skoZZ-ip+(ZthrBLcNl|j-{aeq~mzsTS79?5?PNLIWb{!xe?;r11t4!GBQ*l>s z8-c2id6VnqC{;=lqS$Ex+V)&CpF(1OI(C3jVs!?IJ35OKJr-1|Z!ngMnKRpyn1 z;p1krhibzw)hI3_wswWAceAuYmVCNbHdfbE>2dsj?G;qV?xPX?U`R%_3D6ajIk^J>4aZdahE= z8aKs6-Et$+kC|^DA>T`O;!I=@c?aD^a-CJt;v}eVH+?wYAC`AXTPn;gtvcV*--8Of zy5*-_Nm}L#{n_8OXpw1)kZ)?4mT&Ff6R0xZ^Ct1|Typ)1sy{V^tslHlf1dqZ(Rx~5 zSEffayrloVqt8+D@m?fXE9E^~<^vIEk+em;s&YwB=kk?A_7%OHQKC;RBQCwY!kM zMbftk>P6cZ-?G<5y(nG_RoHjY?|J3aduk;?t=OJg@70`y%%SoAShx6`Uh-v4df56w zd0k6o?-T#nlv2pH8+T%3aez)I^(vJ|l&`av$#hJC!g@O2)Dn7n$IdNO4wF!v1gd0O zUdbTJhCb%fN7DBA%xCxI%NmOc!EE-$1H`9J49m#W+KQmAm>>6?Az{_7R9S5y`O)3v0|~S^3F#x2AWm^pyJARKtwgH4Iv>>UM{KTQ3A8wg zALXEu({rV`WnCd5)0V1{{{h`cZ0*JpXmJvfj=h6AA@3j(GHt0wXES`nwvt!^Elxtx zHbQT^NXWFMvV6z3cIiVW(BdQ{9s5M-gnR~(uyQ3;RvpGZwXpM}(uYC(q9qF1mL#2IU12?KwrNp8e?E{vi<6MFLHy#0(k+s< zROYiO4(iW25@>M}k~Rpd_ko^4w@BJjnSG21w)I!g`{))YA!!@omVF{#OQtQAmD|{M zCFlm~1X`Sgq+{EaPRMqJgq16)vTA*o{{Argb~n5YgtRyb>BAt*ca-c)toMg*v1(VU z%+@2GS?!9;a==?nw>SyuBbIQsMBQSw5~(uV^p9M{5@>M}KgvNRcRo@2wIpq+%xCjQ z?Zy&laT1b_y@NU-?>Q1OZK=#Y=0_`uCD7s|BputXbV9a7BxKrBS-xXidn|z#Cn4$B zCrT$|-;RWpE2*+-J@%=MCD7s|q>tF1!McOi`$M-_wJTLtyRyC2WDjS()$|_6Nk|_C zvFm%7kbPoR{|Y|;*VviI>0EYy{2oMFL}4at*(WoonX%2x_d?o~WwiN4L_Cxw%F;8I z?lPj3vSe3HiI|W)H4JlqLmJDFRF(>D51t=cijk-AyFS--pWEk}MZfuDUgz~a=Y5@X zooo3n_xav;hx1)besJZL@@krq>u&F(a2(gW_KK`9AsQwi<2Y#j*48s^^xNC|S8pyp zr&z;8?1fhi(c}#f!=7%FJiA`g79d!|#MF6HO@zL==iE1u>WM=H$wZm9l^Z94qsb+T9KKjhJdL%{;`pA27QnG)3WfjF5 zCMuo%%+UAV`Mo9{`f{&#>S7cBbbO3MuvMSW)*9c>cRHhq&DZbn>ipHxFa5)HiZx7> zS-95txbv?9O{8CY+FO4(-tV)!fTRv9 znkOat{U$AQ2(~);;dJApa%@LUeDH8>bu^Ud-*fT80-?NGSp*d+DYnZ6newy*|+ruFK=$E82Dkb_m7WGSI zf~|OU>2GxK6V;nJiGI%J$5UCugu4c#kKC*#>N9iIBbnaVs=H0R|LQr(E7xteiDc&d zNgl6FT~nlqI86-J1Z$Y!^%w}W(>wG+O<)HStF8I>rHTw6;`_Jr59rTpnP5$E1foUD zf#5uSXLO(TBUbRi^r$NNrcXF-h=35RVWPSI)Tg#7sMTl8Ig-PDWv`x;MfEC_vhTMnZ7`8j`S_Q-Xg z*59>`HB7K?{odWGG?Uq1cVF+#nl)k#=sZzi-8bbzjv#m&*iOxjld5*-?JggVCw6%bpLhhKaf( zx2e&e6@=~{Z?z4kouZsS=V!$E5l@%DtU3zhay-9!yLauu=JX zG*5i>wD!^Bkq-W(lZTSO$gklLY{hdy*YA#;8p4HZuodS}zh65i z%8zgKMe=FgRn{FR&`R9CCiH3>IYb~8p9u-?34n34x z@8Tb=Kk7BkA=rv@7zli}>%h7-N7GX0Ow~0%lwBrHe7;y6(h;t1kEoviq(kV&Jw00o zPNX{oTk*&S0`tqx_jctbrtW_2nIb)xKCPWGUCq%xhF+>-u=jR*Ux__XY`p9K#)KA70> zcu-xVcj|h*9@0H{p-!5*$6ufFN5&04x5ZYRb-ly2>!hyzW_-%f8PQI5nfU#N3>B-# zqu+#a+DC_K$)@Ln)--Vlw&Ky$Z#!lD(-2qwx3AN4&eh5l!_}sNXG5n_@m)wSX<}nu z?y5LVu!afLupra6h6P0b+spr}K_P;zc9k2ZuK@lET~XmJT}L({9Mv4jw+!L z!B&u^hD}$CoVC{_SC$U03tw3%T#G=46=a-I&oqit_G;-r{y2Zlktxa5{@7x!eMG|q zS2PC#pVl4a517>;xAx)j=3FZTTX98mAn-()!Df~`HF~{MLC5|0zIo8}yiBzR^i2F^ z$Y8aoam?DWgMEi!E3Ws`-{bXDTNR&BBYD^@4Sm)y@zI`1#>dN*r)eKQX17&$mu{2% zR(F?RE3S0Z@2gEOrJ9~eT$^)i51%zmv`U&`e4H)6O#67b;a^_AS1%<0y0xc6uoc&M z>Rf&NkQaC1_}T#-)1B&1CQxCFSz;@fy;XNUoCfeefBdHB4~5a3Ij?wY?#4>)>@`PWAU$!vv~-5tXefzWb3Q#>e4WeI0_WxL#O4 zXL#yHAN}~}vHN`1Fv0c0`nqIvGk^3iudK`O+sbDR6R0XiRH(q$l}_m`jgMnvZ*>T^ za_f+PukwH)9_V$Q&l)DUo?c&tcj@Do`ewnp-)fu)v4#n(T0~{vP)K}gfbr3N+HQwn zD|el@|9Z3`Vxn7ySi=PFso=xjdA)LAoF6}{P3pvfi=1~F*vj3nFc$jmPT_u#HB8_> zQFbNRUm{q;1nvzlMHRkFRT>PkMr65TjMJK!ay`cv66N@w9Gh z*=dG|sf8yKSp!?Bn*+D0^alM?S;GXLIe@m$GS<{-tlq8NLgn}C;yDCaZC^Fr_*h;Y zPgo|FYN`%3O;7_C-tV!7+r_gJ_^{7p?ti?NTDL+!YY2Ye5NtL3*_p=2=#%ZVkM|qh ztm-eiO`STj++z(Bcm@O?_SsU$hp$uj-QQfD*tpjr*y_*U=NKO=a`23-=G;oEd{%;r zoBf@~8Yb{83qI^KvNo}$)#3`x)eGqb4#8ISeztpi>K;7nYk&0>>h@^~s(SW0k2Or- znH+rBXMJUx|LMgYO;TCWQHlw+s($NI(~sEYG1|wjZ!UOu4@yv7^Ghk#Fo9=_@L``> z=Jh`0T{Ewx`uO{@4#8G~wyZTiDk(gBef`ce-jXKqs>-d`Db_H7XQc39pS`{@E#Dh7 zy_IUQ$R*h7U@KdxFs28dA)m?n*1PhTcy+HIqgcZPp7p|qeTKZe(n|epSt)9DOcjS< zD|baz_%+*W-?zEi(%C-QmbJzNuTA~CmiFm+HlDZhD#BAdS&w)QkEom{^oC#!6L?w= zy6C3>Ot2MX_^^b0(okQ2Ho;bR>CYq3ZhvJzrzn{a4HJ-Y95i-a`wk=|RH29laza8~ zV-SVsWY7t zRoQvHJl3ERPzbKs*WX_fj91+*CaOw1IynSemAh!?mHkwv*}=TjhhIokr}Gn3$4$FE z#M^gXo{Ij*0wd3zv&E?p)OXu2R8?PQwNiimBis8a3UBJfsWD&AHI?g#3iX@g?#?jB zuYPW#9>GU`j#WL9>Zo^SZSz=zN=YG5K?&K`a{h1i>s8#*JJhv{Uv&t!;vDMtoe$Pk zEA}U9{Jk~J575Ms_@mf|_O=~n${ZsNCf~`2~`jduo z(Q5ex{YgMpo--ay@H+zfeYN--)dqdFbo*Ks<~d@8}3kjj$Nlt|9PY7 zVT<;Oi$|OSXA0{-Cq_O%;b= zE6%#kZf=(MONDz?mzt#%Ynb3S3G^?MzIf1Eq`#&5p@9_~f~|OL0)bISGQ9aqlp4{f zhPtI~uOj=Zb&*xxvEsz09MDYFme! z9D=PlZ~9y7M&+fpU6-g{nvvkFPOi-5)vSM&{hbEhC>_<3#?72{&IDJ`>ifZ;n|nQ9 zxkq)lA=)9>iZh~XgqL;q9z2++>MzviQpyz*{3d~Z+v$giUUXEFO5fhlA=rxZrhip8 zBQJH}x_4yP9a2;40?G zF6v_!#cl}#yCv6CV?V}mdv*@*)V}Q0qG5vTxAimR&Nrz;A1MFJ**(opEd*P=IefD5 zk&!S=_am4YtMUU${)1=6c&uT9>)v&CC)8E*^Ar7tJI!|pwz?%N!}zGa{YCAg!=B2@ zySu$V=F!O>YnZ@}ikf7*Q@{UsLlrz(&%ZHdn?tZw?Jw~hF3#W36mJjQQ8QXq^jrCr zVm@}N?zytxC5|_|Q61Bt_C0g{Q;#)F@S6ns_c=47)zeW){*(rvI|N&8yQ{Z}YSY*H zR}uo5ZELAnSH=0m*X{IJ!vuCz^xVE_acSwDC`TuAhHMpaO(VS?Wt(Z2@u*hk*}#vT0m?V=oltxDx3 zo2cIHg`K+Z!p&aqlZk$<&#RhuOwdETyTb3ZxJ0clS9^0y>+gYBQeClz34S+6?}-;@ zd+qk$V-6YDbC9!h4jTEsdU(UFB!aCVqa{m>9>3i9 z$jln*vxbQlO>Qt})IPa6+DAzQTS0~oON{vWXX9gl*Ux7S6Nl348Xvts#B48#U@OS* zVTn}_l=hLUqoM9TYnUjne;)*S>%4iH_E8eSR*>Pt5@mMB7$3)acJx`pgxqD=dz_L8 zwt@^Fme|$(gHX%OPk2lAKjHuOaV7H(Mztx~Din9XykpS(M6N2m?@IF?)73Am(fxSu z!}Z8+aPql9enH+9>a`7La!1t3F; z1vFBa9GaA!zPcCNSz8T{jf~_E<-iOv+bVr zIX@VGWEbPlb3wlWI$^&d2Il|6nI%lTUOmRp4X?n8Dv4k#$aq7=66^P0Fg|*h>*=$G ziH|-=Ha=SH%+fweBG?Ktd|2ZBnU#Iy>gdQWK5LkGG_}3)@%e`LwU3erwt@^FmN?wR z?r^7ahMIY`;Y^Ie9L1V|j5Psydw#xIH~RB}f3G$3s$1P5X12?U;#Jfkr?gos4PM5I zI;4GcnpCd!3GIV5Ozj{KGqja?S=3Lhm0&!!sN*eAu(W`6J6h_3!GJ+w~EQ*x}%# z_&rewwhHf$VWRN479)r~5#s?Fy+>1T_>9dB3lGh*;Y~`*feW7H|I5_JdCy2eEQHl~7PY@(m_StJ; z0@+30VI^bm_k^^|1mviF4LrmWi7Lo#i4RyomS`QKNI#@qA;iZeN;KSaSiL@Ul=0DZ z^#K#rC4x0VgE;-$AVU=O(Z0`iquJZ(0Z-(`4T9dALpPb@zto;p$OmhfxUn=YkJ`NK^~Ngy>>97g2u29jFtMjv zwxNTeJ#JJ1CfI8D=gSQ7b(QUf2-Yw$a8#BdVz-{Z48c|<_nb9M{Ip7Z& zf~_EOg!@P$=82MRU(iLl% z;Pt4VA(ud~6=e9Z>-;KRGYcOpJ3ppa!vyaVfj~(FTS0~oyI*~=w7Cx-ExRWu)-b`l zoqje}0>M_0;R8FW{>|cveTxQRdQ6aYH>yu8LJliG5k5_TH}K?Oz_&YF-cTRuoZS~_`p8z z60Bi@*QQJGisG4%eN6J^60Bi@=XA*gTk&YR1Z$Y!IbAZrRy>+6fgKq=#MK1%30EID z9=Vdyn4Kl8VFFh*AaG6O`e1^sa1~WN!BOG-0V|wk*q`IWTrFRD(C5UBmSJIg3|8wJv*gJgk68G zpDJ{br~<5E;_FP?zX%bOo-@H#LL(z4stEB*lXpzKh(uyXgxr$T4=1YPh-ytA#WlY9 zvon#~5*b#U5top5F=`SaVi!8nbBz`C!918X2*j&_2xiKo);YudJX! z?2si_ke#SNn0Y0d;s_^K#s_*RgvhW$M#NtvSH_35i(E;Bk}GM+AxzIj!vtoG950z* zE1@H~LZ?kXkVUkGNF;VygMaU%IKo+jCFTlNoDsJl(k@0#B1G(x=^`WORzgSCpyVp}RwyeZyJ&;)cj|WSIYW*|_Cz59tYJcAA?(^f4n%_;8M2%ik{CY-4JFk;3-Ys__2*q^yV3e)D=&O`$u2#Ga?3EdB$qq;O6&`_=- zJ}ysCZyj2E*fox*!aa{zNuT7nLj;)+A51_N0=9M((Uw?A7Nk$b5;99nTTF<|KCB24yW~%jiX-f2Md3Ud z6jo9XB?M}ti}CNhpkdLCI(LO@fPaH1;Wg9$_>EjizMYQ}>#;zI~0yG5cxTS6dLB8!hp_k+;j zZd5WVvK)uM$h=aJSc8lTA+iv577BriScwV*%kT}m%M;QMv}C_4tT+N1iBJgmD>*7A zB)cFYK1^(g4?Ps`(py-G9Px2k0#?$JjE6gSC0E?8$dO#ZN06gJTWlq=__#FYZ#8&Z zW!_QNT#Jr)GSkSos=@otI9}vRCdiuNh@#h`Oo$AtTMsUb_(Sygvpco4iz_{e5Z60G z7l|ss8YZGYe5?3=I0Rb>UG!SCT-`;cEkq)*BSQ9VdlBx3!3J-t%Q!`Dkuc9 zh_(=k#4c;l@ge5JN2dAZVwkC}JsgVkLrL z<0WFRZSW6K5G>rc*>{;-l1t&i!H}8XzI`*hm+jof+G;qP&utY_E9uQlJ{|to6H$0d zmE!g89p0s>rn6c|RSl8~*tkg_M4ZRbOSpJ=Mda9!>G$g?)cA>R%O}O+S2_3s_H6&rGntGMc zvxwr=nV4`M6TLF=Dd*8ZU{}b1Mr^x_mCR&KuNnxy25I)KCBah?>aVUEB0A<~SN8Pz33H~E+I>z%hYqXG*wq1g1?TLKbdIl&x%0sUtFRJdrK*p~ z=t5s8zF62d8qC0xjCpT@306Uau~O^V`RK{`WW3U~XEd0BhKzNm&3OwZSOpEnO5J>4 zK%-0zOpV`K8EZZJWe6fzWqnv;*f~S5%IuY>f)9Qr&^P;U5Ja#F8jO{SB#$w3mosMu Ry^?YLegqM$f(B!y{s2yMGW!4k literal 0 HcmV?d00001 diff --git a/GEMstack/knowledge/vehicle/model/meshes/e4/front_lidar_link.STL b/GEMstack/knowledge/vehicle/model/meshes/e4/front_lidar_link.STL new file mode 100644 index 0000000000000000000000000000000000000000..d49aea2e76d6034125cfbf0a71807e198794b928 GIT binary patch literal 684 zcmXTU&&f^eX)Saj?KiZ6wk-e6xgty&$ZYA>1{F#EvbFgqajAnQP~1EvG)T9}T8{VF2r=zexR$C166@+N45jT28)ACg1M&wMF)}{FdZnaVqgH7 z4~iEoE`jL)*?AVe+Yko;sUAz?n9Uh LfvRBf4^1TiZNkKO literal 0 HcmV?d00001 diff --git a/GEMstack/knowledge/vehicle/model/meshes/e4/front_rack_link.STL b/GEMstack/knowledge/vehicle/model/meshes/e4/front_rack_link.STL new file mode 100755 index 0000000000000000000000000000000000000000..6484d4245cd1d9b21b50a59ef899c5b43a162a0e GIT binary patch literal 12684 zcmb`NZHQh+701UUC@xAuX#2sHU@`3@RFWoGsiDt(VjH!M3k~&4kXB07MtmXG+6GKw z-c6`V5-N>Y8;S0^Y1D+4eh6guJ^?M%+ASEdNfl~!X#}e-zCf!@ThD*y{^$A6oqM0; zgMq-|p7Wb?=A1KkX701j{eS;m@WXBI-~Z6&$B%Lrp%B|dcKN>-^M`+WaYZ_!M)i0nmAp^H4&q_&lG7YLq~?x7H(S)QWk_>!BJY(8tX_YDBcMXrr8E*K3enS|Ouar<72Q z5|r~?H4(6~e)GP=ZlE<+jgH$sb0yS@a=znOuKYSj-XSBSl=aQ9J??5GaE_`IgL<4R zcKde~=3}v!9LtDI4mDRoePHH7$7r2vA~2Q`m^tZoLai8KV^ltNXp}J7KMyC%T2x9z zE6s@YfSi!wU1|_%J`a7>L_njlQ|5Ws_ph&sX$s^7^Pp8F$ND3xlo%FO$d%PPsX6yM z-8m`e#AV0#`hD=n5C7uSct6PNKlB97*KvOwM8v*=53E#Vl>XWY)hN*(l@e-Y&kOoX zqf(6$Cig((Ge^I29!m2$?o_D{)hKas9~eumDCa(~7a^)@$MJHtp3(w!eR6$JEW&2KmIF zw@$sVEyxF+-f8z*?RM2DLEqs%*hZ+;uZ{#CmcyD4)hIzZui#^Q!wi3Nbotp&BLTT@#2rDkap)R)_fD8c#V-L8aMSv|aue4VRC3Eh3td3^JW zVJuW_&-a6jYR-)XIj@Iml(2sDQROvPLal7Acp|T$YLuXyua738S}QF+w10G5&0Cr) zCDe*?m^tpV*vs*43A-B4YLI!Fq#XL{Vg#%}=-oN>L5+?J8J*wkLkU`u2%T7+mO40@ zsYdr#Jm*OMcolDWs!;;65`%fr3a1HLQAUJ}Dkq?+6N!&L_9=YdH7ozUq#Df-edZijBXmv)Mg<>6mqNs7n+Zgs1Uiv)JE2xXqwtw2yg4a{ce}n5p}}`*d{-w;ncuH-AJo(dM3sNprVo52C&38U zzGGg|92GTn0&|K)thrhFZm4GKt5*5&&)W%TKr?p8^zCP!_<&WFpZIHr(#-@Tkxa+m zMJ`TMc}t@5yC?g~$BzEN$%&nzCmi@l31qQOfaY`O?iqh>V)S#r>#lj=>wWCb7O;p;E1ZLwk&Gyyfp^X5 zrBzS~%bOnwnNEG^SZalvesff~FGKTDkX-l!5EcVX-3lQYHf`uFrBHA>)pMY^3(D_v>M_0F&8 z{AaS06f-TH%Dl`K3D!>QUeO&`WrZ-_=83=^mvT%TGeX z$HfU+A=*|SQ3D?&P!G!4Jd}u5@WJ`z1T{J?WIp$u==buGWjiN17IuBgm@SF$w+1{_ zf>2Ep5pty!#J3FT3_o*prB$N#g>mzEE(2NY~fgO~QAd8d{73UYS%X)xNO%o9+xPIjE>AgSyOlS6O+xnVa z&1iat`}?llC93$Bk8a8cp4-xS9Jp|zT=~@Hoqyi_W!yhXwStT{LrOfda%um_^{-zw zvtdnNHIPZ9U%X&x!~{qs)GDn9qOqtZ5uIw3Kn~$AoZDZzc1!=NhsTUqo)BsUnZ4kg z61(@x*Qdf(#${EyOvkplXyz&+W*O z<*I`WD4|w*PjK$p4QqOTxcpn)^EbY?Uq2fnSNLYBCqSR8-Vc{v(H(#7IL=f)UYwmF zlR)P~4qxsp8Y3RMVf?ja387YyG4pUPvGvjY(s!Qk9(-_Xa{s{YTvZUiv3LUKVCUA4 ztSok3cDDP}qhIT*rcQtk-(JtWY47Q>oz6?Xj*AToSWTzuDJEDPj=^y-JRsB zPJqUDUtjayO$R2si*LCpAuukjG;h8heb%G?4H@}CruFM^=v~%BHF~DT`WR#v-NAY& zp;la7p@Mi{u^u>6A@=(1PQOO`dX%h(YV<^=XFKPt9wqCcgj#7vd_79mLp5~*GY{u> ztU=a83COh4yruQP>0YX483^^T3i{_*D``Dc1DS+%yO%?^Ydw@uE6DJj*TXv8Yful! z@PQMub)|nEy4}`CtcPmq1n97$v>r-8rj=$St%qvr1n9gTN_k?Si@xViWU5g@Z%ASPSiXF+^T_KP za9WD-s#SYbwr|HsAfww6mF@Fhj%S7f*~N)Q3AKWZIR!#Z#Qy+eq)|u! literal 0 HcmV?d00001 diff --git a/GEMstack/knowledge/vehicle/model/meshes/e4/front_radar_link.STL b/GEMstack/knowledge/vehicle/model/meshes/e4/front_radar_link.STL new file mode 100644 index 0000000000000000000000000000000000000000..fa78394177b644eddc00f00b2713be394fa1e413 GIT binary patch literal 30884 zcmb`QU8rx@RmC?+Y@t$2QyYZ7^d&h~3sPv1;QilIv{a=gkO#$&Jmw$KKA@ceTiRz&=2F>Ugq5ezEU2pUQWLgW0+J;%Od?X~v4_kxAM z;LbVbSf6u!>~;Qq_*Xyn(Ffo0@dqA!;N$Q3|M=fSH%-$gp8TzoX?pbH6Hor{*_&SY z|=lh5sI;Z7zSZN$0($k@l|K2j( zVj3{oQf2(mIWdi+Vb_RKMa>t6X>2hLS*j<9PkUKOoZ)RX*L-1EdDjfpJQ#CdP_k)4 zZPu z&$#We_a1)j-G6-!1HDhZ{cDL|fAD?B`(As?pdPZU8EAj(hrW5att$&&&ba6Ie(LapZ+q*2QGI)WLCtUf>6;Trs~;I}eLb8ZFWB@`Fb+LK>UjO_ z-~7zs{MX;Awql+SG`t?pxaTeRZPddV@KSRDAusea3wnl+jGPl6`0gbb z>i?c03trCn`MYCAJ@@TP`wV$4?7LqXFf=>yD#i_D24_?W2lHHQvXtZl-%Sm*dS4G& z){JVy@n~OqP+qWWrVSXCYqJj`mmHOSn1hi;2W=$_ah(y7j;s=WJ)9vgl`3-ZK%;VP zmdY6#3%!OjAyVh>*1q>yo*=0 zbgqv*!`JX{zWht%-5bb>&iKOgk;4-)DtisjKJubeKmOrhJooJZgS^Blj2HPz>v`cp z>&mibkRRC@?3c>fr9IH7T$}4s)hRLT7`umFLl#QqjLN$MhR@pY%C)cRv@t)_ig;z~ z#y-LH1~aPbk7Cf9<9&%U)6@&aot^o&*Zp`VkjnbtF8 zA#UJ>QFCQb4`;{=w&r86Aq!pu#z4avg|i;)IIev5tAnjOlDEGmrIhg%X{dA37;*6T} zgHkCL8u9|yzmIbwJK@Z=&Zum+t&t3Qp`kI>x2{H9_;M~rHU3ks_fAU$5_MF=Nk;>opNnq zjrJ^I-@2@1><6iB)cmNkbKyY`%Ccrq+VL9Y40*w>nh(aVdu7e9uAI3K?(3mg#C1lD ztK)bl;|zH%?BQ-Hc9vN~ykcLvw3Ws}Un*JF4ECkty9{T@3%15suMzuNMn?8?oLI89 z#n{;U_$VQZvI4-+i0L(C!OIzpV`jlVLte%{?-@Q4SxaokkuBXbe7rhC_1kC2i&B;L zcB!&;ol$xNhW7{iAoibVFnZX-_oZ^L8dupLHQolTi@M@cc5YSB*v=)gsJ3FzhMPGt zvkVM*ft8i|dMNkd75gj3RkoYPbkC4wgE44bXB18ivTN+f25lt^8Uw~a!x@F=dTfq% zAK?SWK*Je@Q=?|rfKe+zdQ~4Bsgv?p-@3Bk<&5gh!ANw5ykOTD8#4~t0n}+bMcBsywITkS?7BO{j61= zex~f#Un*yiiQ-0QpyBgeUT7#|^riBhMXiIEuD?{ysC9QR2fbACGL2(jDj$i?sGY&K zM$QR&p}{yF-$uoF&HHG)YV0Ok`M58YENcc?o9`|A40*xcUJZPgQTZzSBiEJTmj+pg z>x|05gSK*pykKkp(AUGgD$i%Bwi&Vz*BQ+J@y&!Y=!`wR0NO+!^wM zt#!B8sP#N+TfL@PdmZ`88P)&eS-WI7c~Pnwl>*)v<&4Nmhs_MP zluBNdDl*(*oZ)1_D@J0*1;=c@j<#|}jJK>)-ye!aTzP@jPd!7HH6uo4w&6ZQUa)I~ z4#t%%csWDkt=Djdyq0=wea$$=x5gZa&Zvwrm+Ex>PCq^BU#boJ*YG)Ci81+i=M6@T z#Ls{9OLx5MQ(r!Q{tb`hH+uCsr!4P5;b}Vj*zer=UynWh?0>xflgW_98DRD1K0{vK zo740USDwG~_aAui+2?M4C^h8ealz`FeTKZeH>c_Kdu}~>=^M9Qy!Ms*QbS%I7p%V7 zXUGc;;b}Vk*LR=1ddpoG@n34l;&H)|8R}c=9z$Me2v5@&Z@>5CzrS+d#kan3TWZMS zalw&^>b_);Aulw9r|Ac7dGO@#Zhq+EgAcrT*)1Ly9Ah`XDDN}mMI_;A`sbS;KKal0 zfAZp`#~x1&Sv)Q{=0D#*Vt(u~{=2uxfE;wd$eYMUT6qU)1SoH{kIsquf;rci^l~srswaRdklFINqCy>jX8MJ_uO^y za?C@wcw8`ZbKc49G2}%g;c2?<-dj&zjXHcQ>f#oU3ns^KqqonH7mEXzU?~0uG zV$4Igcw8{Ka{dai$B-A1gquvA8nSp?Fgbs|DYDg|W5^2);c5DfU;fe^G5?OtL$`Qb zFe}k~2e8MG7mUE|}ff+#k_a zn+$moNqCw*cjfsj8KWi^m1WIhwa>kxL@C zZ!+YChH$P?XE8TUnTKxixZt=CxVjE*GUP=h;YK6ZT3I~qqL=G=tb@|%7+LoEVj`S7 zfV0>$oNCV?i^m1ihJ1V3XUI$aF*B?OFT2I#f*B?A-RmAhUPKa}roW1@`{o$Ce_ney zSv)S7F+IPz+hfQJ4dL92p0N+rUQ`y33ubQ4cYU!J-DJoM4dH3}m&hg5fx5WG8am zlOc=81=sF1G;A;0G314YaI>dQhAbWzT)XhluswChkQW-l&DkJxqAVU4TxW*Ru(LtO zkQW-l%^4>dvUpr@or*%k&Nv-IUT6q6XSG~$WbwG*I^Bhaoz*&qywDJC7)Q5w+(j?H zRGUV}$P(7~Vd3T^{OnT0@bb7|+Hn4AX=mq-Aul2cH$9jPSv)S7u`u7BTc39fd7&ZP z++|$2#p8k*)3FZ5jhEeJbPRbBNw~R_Nro&Q7tGv@bucvSPNrkX3k~7srYIS*cw8_! zhPS-?40)j;+}wDjhAbWzOs<^&-oS3vI)=Q^5N81h0xxLIpcLl%#ldh_l1tf95GW7JBWb5l5L-kt7f6ORk7y~NyB zn+$nT58-AflckcyKO7uL%7+)B|{dE3$9&XXxJXEW5^2);bt$I3|Txb zxb~=_VSCYzAulw9n>}?hWbwG*+G~e~?WsG4ywDIHp9jf(9v56Ei_oyMLFPooaxXNl zG9pv!jFSvmoB^)0PpnaU40)j;+?>^NRLkOV!F7h4*Fl}tI)=Q^5N zAv9v_ZZhPBhH!tnlf~nLV{X<9)Af1K8S+9yICIHK+>2hsy=c}$7LN;#?8D2Ns7K_I zO@_SC5YC)<68A9|+{?Jdjt-Bm1)3uYyXd(qJ7&V$B~7aGFD^I*pE zxT&}NO|{*+_&9 zaYwev zkQb4J`_r8)9v2+9gZY;v`wV%ZA>5qRa*dM3(X$ywDKNFD7U4PUbY;$z(lb@wi}e z%)D=pZ!DV(d7&YkUw*E{JDJPzP9`;E@wi}e<$NBDZ$+C7d7&YktD0`^QbQJx3y!<4TikX5N`H9sUeHU1=nsVG;HtFG314YaI=R?hAbWzT)V!|usvMI zkQW-l&0aJavUpr@?KnfjzD;xtd7&ZP?5UF>i^m1mE<7}BPu(%(g@*9>bjRBWj|;Ao zMQGUBU^zjGAulw9n=?)_WbwG*I>}txXUGc;;pVKCqgob^3$7DcXxO*Ajv+5Jgd4`u zEgpB#8@?A+EcaUKp%+5Ud(o^%y%%*%8;;+Lj=a#g%CH{Hy^k!E$}yv4elNPmkQW-l z&CSGxThNdfm@z%S7qz>Ljv+512{(5#$&kh4f|;A+_oB{_7aGFNO;Kvd;&H*`nE73w z-7R$td7&Ykx1751N`@>R7fi04-zVCwTE~zV8p2I(PlhZW7fjCQ1?4_NUT6q6YgB5; z;&H*XUWJC;S#}J0p&{I?waJjhdQ4Ou)cxOU;8VSDP1Aulw9$LB$EpT`B)nISanY>-)0vD^!d zs|@>sl?+*&0j`rwXzVfMg@$l*R?9U?7LNe^|7qz>kjv+5J zgqu6EWXR%i!Q@K*?sA_YFEoUk+@2b;cw8{60Vkw=hP==aZtg5oLl%z3LK;4VD|y}H^Xt-UNP{}SL8TZ zI4dWI}(M(oacGcnL`hP+_M?wl78En~tGd(o^R zIQG80vs?Axx*p5}^_nwccg{<|$P9Z7d8t%$-Ze&+Dpnj?F~7LSnn7D7CcDlzcgDyb ztbCQTsPf8cMy(l9kDP1S3UgjbMzkRrBS!lkLtfQ}^{r^lh)hkJWZWowzQ%+h?R^br z#7b1}Mb{dNMO=A-X}9^S<(g5eaF(i8xWv1Rj8z)>1p{2G-Jq=$%e}xV?KNwjUt(a? zYB$hOEcXIyEc6=Hq6d{ko=L~kQW+czIkV9 zjHOh}XO)VZ{~Ifn7?n}ahppR`O1Y%+@qkfnm2;xPrRG{+ol*I5Ja#h{ zwUrmR^6`Kn3tr@Ta+KQY+NE+v#F8UspPfj*Ez|m1lBrwC?fRqum+NZgtvTmrAjSD=%=ZID?VM z7}XA$+@%+k+Aa6}Aq#PxL4KUSb6Tmg=FX5;)jUUNufd4Zs_zW4_WZrpG`i6)uc~=w zqDDjgvFu)}ggM5f-7q>0XVmN(tWkc zN!>uM8P#i9lIrus%9VYoWFf9IqNVHW(ptkA@`4@hR^N)&49crBCpl63#KMFAkcGI; zAV0ES>FW{sgYurkD4aDXi+1Pp99Q0h-Zxd+L8)Xx!x`XlW>_;c=T*O^9yvdh^;Hkf z{jS$AvL0R%YA#0P;JUM1_lGm&g+|O~&R6Yrt5)+S5z^^gTGRs-E@C{oXmWzAqEn!hgDD9N^RhP+_MzcUgCrK&lY zy;h?=an1j>2U9~9;;tBs`T?WzZqA9?g(s$;#<^V-ST z&cTY*_lGQNM(sGx_ZjknJzS%*b!EZJ8MUGgG@KzX*tI^kj0uac=d4jWO=@lL>mdtl zXRxYu`6}z-40##59VJ;R?LY9UokjMC>erV_mNi55+h@oNc4@bz%6iCxmov8aK4Ia6 zm9r=q%lTY6zb}<6rLi!gr8z+kO63fB!Pc3f(a6^Id0uN`W;@N`hLJUwg}Ba8j%gUu z$p3c@81gDMbFj@m$*9#bOX7@SzDh>zigRStE+bo-9Ne9@vmUZg5@%%n*7rWC;S71f zW@YF`dopCf%Nfy68#gSak!3G-;vpk7WU-PsV?0Vy9Y(Qdz0s_l>rs{s#z4d8cHz{h zEYUJjgMQX2rOt-u=+z17ydPJx;N^^pG|+H{ykKkeG#Zb(1?&t){`kwNV!@CXSYxc$ YkY&w?5yL%0TaPT2Gvrko%$Z>PAMTzVp8x;= literal 0 HcmV?d00001 diff --git a/GEMstack/knowledge/vehicle/model/meshes/e4/gps_antenna_aux_link.STL b/GEMstack/knowledge/vehicle/model/meshes/e4/gps_antenna_aux_link.STL new file mode 100755 index 0000000000000000000000000000000000000000..9a0c069b0de86a4162da067ea0dbfcb2b709b41a GIT binary patch literal 50684 zcmb__d)!u2`u<7^9i$>DlTs?As3hLK*OJ4Ch$LeulN`pOk%VzpC>bRc^^$ZDIo6Cr z4)3$~ikc!B$_!%UJQ&F_2GQ?Y_jB+4UQgS6rtjzT>koF__qEsF>$%pw?sd4 z$(~pFbL+P(AlR$&sXiJy%vUx0To9cSrd^UQQ&wmhukU@L|2S$S z2(~cd_=}n*!-l`7b#+3U{{E_0b}k^;>&K{RvT>L9w2Z$u@9V#KbT>h;g%Q_vZ=5vV zuuc*FN9&KfY%f8ug%QU-^nK~28QTb3jX80fUcOD8o&^MZz5o5j(hE)NCuQzF{CsP_ zZHIn>7&H6%(xv@d$-TbW{hy_EuQwMjMjP{i@92lvLj=JVM$8}keQDYC+h`fT?$p(v zJh!TVV6V!j+G_Q8>1}m~3L@F@*3yg@I%|7;vb6u~-Q>Rfw8s2%`)&PS*PK*%k97lT z5p|DzzOoYRZ&H(&g($6cFsiHDb)ZkFQMM zzvo;*u!Rw$>fc%#mUPxK`lf5sy~mtYK(H6rn=z3&Jsm#hGC}a0^E+*-Z%R$Z?yqI6 zp0{_pbm*0WU<)G#+&HS{**_nkb+zP*kCOU>uPz|i%Xb`A)9A_rw2WQZh^{ym_3xIa?Tk_p7RS^Ei8RMzB}qQ+0cMrOjA^-#NmYjTo!%U!U#m4 zD2u_yAX2+5QnQ5-h{sWFZ-7YcvPjJc_CgGfDk8PZA~jnWfk++I_8&j@>h1Plx}UIw zEsQ{a71#Eh?H_h->0kCNAlM7NU0mA_qIY&#?~EQf&N3GC)N$5_GujyR&Mxbn*}@3) z!Er_J?6TgO5$sj@RLEppmdPL&iL;CanM|BzNXT&FEE_cDlBs`iw?CO?nM`hB1ahr7 z%g&7HH}h<_|B8PU5bVV@VhplAmt}oyVFYrbILihlTXI>p#0d7{dNT$YnaeUVesg|X zWMpxc`$~rFvJ9Cmj6fb7XZf{c$S%u}8Npu2edCG@*<~3rTNr^1Ij+syk?FfE(`O4K zFan6P5r8pE{&tNUo3@c2ixKRVU6=DKMc^JXnvi=1OXd~+UGG#?M(9%sf-Q{DC#(u+ zV=y*w=hSa$!!;w=OKU{S!1yE7t{~XL2(9&~{8Sj@gkMk)Y+;1{nivshDPc*{8Ac&>Xb(;#vg)U3nMh|(x<{0$6}0AK(LqQb6UnL zcCwjMYMBSwOH?-)luDNMHqkl5+aNsvNFQRLd(EYg-ky~qSfmR!4CIo?&8sPT$n_C^af#;ORmvNgjqH1oiR4> z7#j$JEsQ{a73Qz>sWATV7=IKH?8P-=jLt?0f-Q_dzY^xJv<#i`Dj?X4>rKWVVRldu z{O0^l=+(jur1pbh1~SVs*un^824S{V>k3(h&$0|guov=&Fz>5n=!~#r8Ejz$vWzf0 ztO$%hJjNe_U<)IVYlRtaeJYG`JjOT$1bZP<3v4b#kQvI@ARsgv)UF#a z0@-=EQ*EXnRvHQj_Tn0mOy6gjK3f=pd_Jrj)Mol&rJ+!}?8Ws~ewXrpN4t-%ZWvFp zTbEv3xiZ@7jP2uX_840eu3^6?)Pi2;pwWTxxrGsX4sL??{9g$6Qgl_ZjOG(RkJ{fn zQ=aOQT}@nP!DzYWvhzp6Mded5;_XHCr6=GK*KF1r%J7Dntjcv5sz|Ns1tr(!Rzk;*b&IJI6)vo=lSNpM}2U31x$2(~cd zgigz=?&#V$d#4;!Sy$}EHIlpIVzk5Cma_VRS1GGEF1r%J7Dk}Fnk{;&+>2|ZvJ5bz zlyM0)TFN-aWmh8D!U+5}r7ijeb1$xu$}-T3lC0fncO%pvpGLUR)!&J1#~$<*VFFf9LGJTToYw zP+n!|yqLK!#2dg|;q*n+2Gg!XV5IxnX3sn|<<(O-BEw4#u`$i2Y6kkw@O-GZlLgk}R7 z`oBCCdvT5A?owBX86ne?7=@M^GQjM^TvsC4i|4EvHQHme6;`TbEQ2vlSZUI6&3`L{@5=~`OTzk2hR%x_?HR#d|NW^j zYY^6DWt_mXgM6pF09;g-!3du5{O<_%;u@($@LUhB^O-4l{g>Z^EsVhYOjsqC_p2;} z5$we^Qi-^z88COjZ`AkQVRd72)X7vRU+8J2z|mVO5~u*_Q76UBe^>+ zMtiMAWM9T;?aDR&x&?K`2>ms)cM3O@Kb23#UR)!YcliHkuZ)u?Q6~N$o{AC5{0yBJ zQ~6Zv#Wj+<%TvKC-$#Nn@*OZRZb4l!LZih0cq;bd8mW9L)M&m70lx?Blh~4{Vg%lt z_I}isQdw8*#WhmvAAUiwFJJWrck?{~TUJ+$088?n5tU`|z1WLu#F!ZmUFO!TKfz9X zwL0cCVP5U+d2;u7*^YZg@3o$Yp6%)37q~GGJZSqbt&VxUmRDjAh`Yp>J$tz#8r$Ex zJDS&bE8eS)d2N$d_-3}>CAK4&8rE+fm!E3d zzAxATJJ?FxjXia>X_Guc$H-N?4PSTUE5O; zcaFIsKI^Hg-GzUxj(J^$S7nYKyI0lRAA2ccP`763m-DZ5V?Po^*u^HZ%e;DmGHPne z*i^GVz5Bk?+&$mPd*tf_JjY(I-xH-9N^P`^ZF}tKZ+h!k*Y1_-m}ljAZW?t}s;#Tp z!@K&BQQ}BV4?#Py)rT1_ol5@%FtG;2r$usiC&qQ?@0p_ z^WA1(Vgx2C0!(yZqE{y7d$}~0WWQjDCHf13i4IImm5KR|Esby)uR?@V#PFx5#|OUC zxHRI(Yn+aXWd2*nIHfQjFn;9Danm~|))>D6F|po$E$oVazEWzj$5oCkj5v14j`5fG zHY$}7$27amc52-%Y5u@P6$tivy+PY}QDt_-1cc?~T>T#Fwfn5bX6(_pb4V_vY5T^v%O4 zYkp-MTNp9@_ub;tkL*|~BOW~OJolGFnx&5puCa_@ue5Qmcx2TBHRX2x)eaZ9^>uzO%`yscGO9TNv@|u8re9vz}7K#>p++ z$jMwpSbD5Mn3S0 zEsVHk&cCY~4(h0ghi7-QPo2=&2VOCPz253^WYlEq&Ph4?Jo{E#yZgQe_zT)&dj5Ih*ykYuevYxk6!t6m!uqho;o15J#IM3hj_&nMqF^-4^`)l z+fNZS3(mI#?mf$gc*O|zdgRx~M@y!6)1LF#9gnlawi@9>ykZL@G~ZRknrB-kyGi+uS)nx%$^gCelTBAthwWp(x|PMDodjKze%3xut<2t7W9KT0{vB~wjZ2#!SM9URR;;L z7{Ol0to^q1&>k;ouV#8oPv4n#itvgpj6i>t)b@idj(I*keb!9j6(iWI%dk4hjCO0X zUhT0@(#xmaC%j?{BhX(Zwf*4vUAFUWfB1*=gN$IWCMVZVT3q_B_G;h#x}|URpEsl* zWD6tEUnRBu;Ek_!^fjyMNW5YMdo|d(LDC}qNPD$`JN5LBcdsM7VhbbCUnRBu;0GNe zfBqiLgjbAUuQum2N}ApMsrG7*zWHlE@BHn3=m*)th{~}V^7aIId!%`LSQE}xGs2p1 zq>5W1$ldpKz^MdZ;$f4Jw@IgYu=tC*bCWtg1o&d&)ZYv?Xl+V zxrGtPuM_0$QJ%M_$lGJh+j9haAv;fyw^!wPyGPz0Yu=t)7=ipcLEawadAmp69&6s7 zBiIYsd4jyXD$mJw@JbHE+)? zjL^8E2;}W4@^-6vdyZf)w+pY>!U&Bkia_4(k+)mT z+w*&|7qasNd3#jm74mkEyxnTvo?94EIY)-Py@b47c*QI0yyA{ryM(+w&hz#JdArrT zJ-09d`E?EQc10j>Pms3@ulQcB<+f(H2R`d4! zUhIWjyM(+w&hz#JdArlRJ-09d`E?EQc10j>Pm#Af&D(PXdm+~@A#acKygfzU?lf=D zEsQ{ZU4y(`5y;z9wB2ISfi@^)nj^7a^cyTmKD zFar5?guGqj74mkAyj^(32=+p*9U*U5mLPAp$lHZiY+(fQ>j-(fB9OOR-6C%nUa^G{$gd;h z?TSF&ZjrY;&D-;Pu@`df2zk4*1bMqf-Y&di3nP$UN66b1fxO)!Zx>!Mg1vOMR(XZI z-63xmUa^G{$lGa+1$ldnyj^(3drEXRO8P#wR(ho9%y^w3i$lJA7L*DL?w@W|B7Dk}I3iDTrK;G_m+u6di^*j%6%WtfDzaH|ZQpm3u!Cs$z z7o&Wy%(t_J5j+oXOv^X+ap!!vtQ7h|MzGf*!@5Zs<$iE!{VF$W z-=Rt92id|1o`*MPuRa6ava7x?g?^9`>^0`lo>E4+AAESzVAt>PaY^V0*}@2(RS$~g z^W7saG)Y1~$O!hT*DvVdI(I7fgZoKCEeZV~TNuIf@W#yk;!1b#?AA%wjV&t> z?3L{=3+s5sd^+}Ock$er$$dXn$82GQYOQO^h>M0?>g=V5rlAa;?dR1cMjLbe*ejfW zq-(lqeRa$hM(9esmhsGXSGnB}+9o~Z#YzNwRX&xj(aXxHuFK0hm#){#wXV_YX#4uB zM!KQN^z@J4w6ttt1iv44F>E^9-SF|Pvi`vc_PX?pJ>xMmFDaE-a?x#Px;E8Um)BUx z!U$eH!Fd3C4|LtC$CcM{2*F;r{H;Sg;)@ZbGTU1(>F0*`J}o^O++_#%f`C*r4_WliBWgdT7Dn(Y zsWInGm=q8E>E!}~SIoF7Z#gDBmyg7Su9U9YT;RCkO z&Mni>8?c2D7@yO++S{Ezvo|(yGCRl!_F^s=bM7DNx>I`&FR+9WycTB6KjL<7*d5mv zn8;qtX=ASZW-mA5usdXSkS&bhwJ>AquQ}AM>O8B^qS&jlo%dLOq-*=cqC%@>1h0kR zM4)+t9oAk8k%7H9#uzhv`KhkCSs|-rY+(eio*}lMa<1!mjF(8w2=?MwY0RD@&UUZv z{z`g3dIPpFLeFQAhzbShLnpb#Z*Aqfp*P?)I^LbYXk#XJKh=FU?8mgpSJg3F7@>Qn zvNFCL=1QwSNk3jziD0kFr|LB2a5wb9cK(s)s$)HqLGGoeEy%UzaM~N}^!bsl>D-on z?&mGT+-u0;#KH)EKVt@7(Z`LLzmu#2FoL}_f7ITf<$wCPodz}VVTOe*jL@7>5z%?w z+`X4<<3pCg2=>xESbKxt9ni%M?6E;sc-g`T&3zS7Z_8S~8}+=jLAEeLb9hBuH~s@V@y3PH&Kbd8Ixf-PV29Gn*4;f-dIPpFLdPPC`0S=z z?Y>V8lX%4l_R{f{_6C!lyTtDOS(h|q$ZTPRj;R!(qdSSaj9@PvCu(mn{g7+ocJFse zLZ;6aM(Eg35jy59AXLX7UR<^@m;Upu__5PP6---M8@O z?8S9x%<9v|*^aM{Dby|_W^{Zj`r-Hg*56}e*VM*uKOnsU-;2GN3 B<8Su&9&}td+@Y&x*m$#{#l=H-Px9{st`S)&x$iQA4 zV~lxfWmh+=)!v2Z!-&d#WUH^Oau05|mqcp57khE6H0Hu%d%3lbboZe*U<)I7-u$RtECFLx9!_f`h$6M_tEMW^H`1d#F z*8c14p!rRGh`WqnFP&ja%2{}u$sgLQp4>`S+}Xki=CLvRfAF|H{@S;tMKOZCbfz#V zXW?U-+;1O#!Asm_3nREa8nbETaC^X{TO=|tg1vOcQ=`wt2lusS?{k_&AGR=pX<;#&_oRiY?c7{T$;nBP88*DYLdvfuXQFcPla@u{aA z33qkYQ1<~0eW!uDcFsWm=x1THUAr%o5zJ6yKA*jnTlivs;VvWCOXo6`yO(dM?^d30 zn5-hRg%Qk9WcpiwW=9=WCER5Md+98$a<|pW&+R>}y9#&N!U$%lF<-s^oPBIq8y`lH zj9@RFTUPEaz5lOv;+{>i-6CNITP%!Vh8nYI(H(aGUwtjy<$JN0&XFs3OZQH;ZQHJv z9)~TAV1^nqVeXN3)xep;T}H5%&h_hlpWC15Vw-++iEx)Kj9`Wuqbm)uHW=x;VxSk!JIZmwE(gMTlfD9UsV?%*Qy0j?q0CZn|5)RGkm}ATUxd-f*ESe zpvzvd-%TDY++_rNbz6CJblTWGl)LYbS!+Lf@OX*4Y+(d56g}r>-u8d)2;nXx*z30S ze~S7yXs6u$)#AU}Icp9Q?y`ju%ur)qeP*tG=KIdVT}H6ipclqQ&+gP(xw~tNyY0^p z>>}J{3nQ4J#`Jpsa@+ffIxH{)VFWYOn0-DNAD?vOwz6xI5$vU^U)ghM zjIP89ciF-S<}}nb^}dR3JZwS%!TUP7Y-3)YcU(N{*d~RiVg&ElH0GTFYvbMxClubC zy|@mI8FKh{agP)KT&P_}@QzJm9vy#>ZQ6K!;TL2t=7KRJzlrRUHrp0h!U*26iI_O! zN;|UU?gb{Y7jxQ}n_j=j{_TkUB;REVBY4LqW^1>(-TEC4FSIE3;nag4#)hJU}y&O7<{lJByG5xmFKm|0^M+0Lzp`!G+< z2=?MwY0Q@+?y;M$9Vz)PTNt5d=}APzTt=M}?KNlrQF3bDNy-`%MjP|5winow+Ft4( z`Mf%23nNsUrDe1pdXqhP`o(_Lib@1~RX&xfwnQtVN-epUD!AlYRa@E{3~BQBcv9&K zf8$pzEn67D?`O=aAwFJk{wVo97{OkvAMI3i{)Qgf8+7=#j=gm2;qsfag%P|n7aEi0 z3*ukjJXm2g#~scZAlzjOBY1}~W>SaW79W1sLDCyAg1vrf z`>U#DcXrm^pwCT<)eYujoI46 zjwlTpS5;v9W{8^F7Bywlr0A*N4lJ}N+&A~)wuxWx>&r?jZXZ%;wVNSoY9qteZ_S9t z?{|J7GT^?s7snW^$~3;Ebl@!)NiNEk%@Cvpyy9Q8qBomgCA|S7aGiT`tTg7K4`-Bq zjINR1fGwLL=&K8=eHFzaD;f2yQHi^Vc0v1E8+Vf|?y`juT%IvITvRu0b^3)8cNxK6 zx=%{u?t|AaN`Bnq50Ztmg%MnD#=Q92x}@E`r^qkJ2=>zbUK)27kDr~)9C^I3ge{EV z-yd^*|5}#x`0zlP{a^%p>Ap3MyS=WxHtE}aABnqcVFdHom;>uhPo}-Ly|gGsu$S(? z)42PubydmCX+KNcWeX#?JsR`PJ}&v{_;TE31bgW|LXEpqK3`p$uyZ;3u!RvES0wJ1 zvbf6#_R{^38g~&zYqBWH7DjM<#LV5$o6;=H&@*L)uX-Y_Tq9ozd-0UJN6tP!oxkZ~ z|KR$TL0ywu7{LrR=IGr8dH7ODQT0Z zPZaJlg1vOtq;hxFh5M!7{<*&o>*s7?1Tz#XajgzaM=#!Aq9`NSOLu=NcdO&3={@cC zl1R-KMleJ1rHz4&)8iL56z(#Dy>zdta<|dMSCSR&e-Q4ng%Qk9V;(e*C+qt?F1;Ef z*h_cNDtG_U@uFn?O;e@kWD6shq1bD%pi$VrE4?!#*h_Z;*X9hREN5T~Bbd|1=&oYP z85p7Gk;#3zY#Bi&*$9#?jKG+)R6BM)erb|iS7%b;&Do3V(3rP>teYObYC)lP8G$ip zsdf%vcKi0}PyN4=oPqDfUd#n!UW<-NFT1;bfhCNa?NDGMdoibR zHci`c>9mgBWCY0;Mqp%Fs-2U$^jG84#U1)eZ@>ul;3cwu_Nug@q%A4XuDNT(E>`PAKMw{at6bjSB%FOHSi zz2l!q-`(eY$r;$f2tE}7v*+d0FXYStJ@GB!8L0t} ze&F%+-uJDyW(DN#+r1$WE*KwY+(e}TSzB-=nbXxo-fu&i(&+OVdbw>yK`XBxLIkF zmCL0?v4s&>Zy~*NpBbalgCCnHEs7EBg_XZj?GA_semp3>_t@dmqS(R+thbPE8*7kB zwg$-v_QHx{eugpP)yQ5+wvNLVMqnL>PCCY_WsUy!|+3&u3Q`S0n_ zTc0hkgb~;+LdxP<_kNcicG@>-n1|zgu@`gNn6WoD@Ta`KQFa2dg%Q{jLdxPB=e6+T zj@_})qS%YurZI25)!y$~wNs(hG6K6rl3Hc)Uq9K?A7wg8Cd2n)FOD(DWPa%B+uYni zG8wio0y{iNS=@epPd}~yeiEq}!Co9Ijp?!}@;BYNw`4MGVT69ILU-xa{CJF?(5AVR zfgNq(WGvZ1$0toO+L+!+Kfl-NUHqais$;e=LeJjPGWM8qxIazz^)Z6IDxd0vFNgVT z@1TC!LGGpBg^+9PLJZnP-3hqw8H0V@y5FbkzGxXvBgrj{;P*3Te4`Wn9!uAyA-`e- zd#MIf_w~(ty`PWfe4Cw-610|LVFY&Uk(&HBZ}subUVT+|nDV{YOO>IzZ|U>rdir{M zyqTT#67;8HVFY&Ukt*J9Xz!P|TO|9!`Cja$YFXWXb^il9`u!F>Ci}10!U*ixBX$34 zkNlXfKW>7wb4IWicK-&YuI?l27{8HzimZ$@ykcPlcI?q91t+hYo8G*sm&7Z+7kjCC zS$CwoeCX(OX6rT*6WPKD?AW8z7F6#ntNM&!FYLz7&yF_+I{}kyCm>rGp=xQ}2cRl! z8P_rbyUO#^*tu-k7oKMO!r8(I>?BWWcf|LZIzD~kzXBBOgj1Ti>Km zyNtl@@1%BT|HB7q+EMWw8k|(tag#$Xa@y~v7OM!{( z#hf7tR(&@EL^0=xK;@1|6Sgs9&OyxC<3bI1N$bF7!A))8nv( z5nLYDwr@SpUvS@bqQ_wbd+8Ym8h3lI80I^DJ6UR%EsWrLGv=ss2Kj&Y86m$QBiKvN zYS6elpzD!->KkK3J-`-5@b3@x*`Ip)&OQ1`++_rN>6sH6cMrXK58vX76NT+;VFdFS z^Kf$;_zmChDlLi;>;)A}IFm!;?!nEzPItMnjkH>}FoN47=Je-0n(p@6i=xM21bgWj zAR2ey-ELC)o8Ki8eb~YXjw_*;g+@8|X|D@Mq|2xcgDCwy|Uzw5>ZWmO6x*h^15(US`Qa>}uO*bN;d!m))B z%ur~T4mi+n_rs@2*a^r8_R^DE^u)!Xx9{cKb=_9D%N9m3LybAE&-VU`W=~{iG=`H~ z5=SgAJ$O=n0s| zPM(@xa^fiAE?XGE43#r8!`VC8nVI>$*sJn8CeV^4nU;(#j9^YW~POtI@j{3fI!e(q|1oXpFMtNU&kDB9s!-K~qbRv+nHTJ4(=UF=KM>%4t??VT3YN&%c5yK7}eiQdPW^5wxM~#f&iqs`wPD_()apf(RUCgmPNX zzk(`0g(^N$ReX+MFJ_D}P{n(w;^j0ewlG53URCBURPi3F_()apQbw?_7c<5fsNy|T z@v*An1ra#P2xYsTe+5;%hblf&ReX+MFJ=sO>1`V9p^A@H6)%XuQAQ|3_53TS;yqOH zv8v*81bZ=K@U8gwM|r5?V^zfqB5;%u%1}N33aWSyReY?f_#DArl}v;x-a{21t14a) zfuoF2PFLlscn?*)RaJa`%D3je(dKAT#e1mYt*YYlQ@I$S`Gb}b@)D@xt*YX41bbCJ z6;$!zyl^?WUh{K#63waQT65p1+|D%%x2lQ{qXw}sLNg9UKo#$yikH*H_+IR#xo?!K z;yqOHR!%T0kAB3$2+cSY0ad(*D&7WO@x9nfbKfXe#e1mYt*YX~C{8Sl(2PS7P{n(w z;;pLUa|C;7?i-ccAXM=ls(2gPAX^xr8HXaEiuX{(+t5cbg1t2NjdE3d3RS!fnG9PP zp&5rFpo&kSikH*(7{Oke`$oAcK7}ei4l$7}jL?ij5m3d4EIbaUaxsFvG^dVoReZ=~ z__3L7@>0<`W{flr%=Tg-kiO-4n-B8LKSaS6(43f zq}~~!^CkLwKoy@t6>mdt!1rP==7Ol=Jyh`pmM}u+OO#ho#e1mY3ru9M%Juv|2{!9EY}ZsNy|T@rB61UL0eP?=C;p zLlrM)(6NOPI>({$3aWSyRlG!MMz9yhN>RmosN$`v;`49%GD2rXB%+Ec-a{4dR283p zB|>Mm#f#CRiuX{(TUEv9XX!CQXP~n($}`(mRq;83y(*sys(24oyi-+t{%vZVJ(v6H zth&|}RPi3Fc&DoPu%aLqM(CWiBA|-*P{q5@JM+EROV=s%H-{?TLly5-6(3ec#KH)j zvsMID@gAypr>giI!Ct!FqTGcl-a{2{Lngx(M(CWiBA|-*P{mtS#fLQ^v9On}8)+Ma zD&9jCFKv)5jLt7m6po&kSikIGiEsW4PYehg6pF$Nc@rn`b zrR#Va6QPPvp^CSviVrJ?Vqt{NSt~-%Dwep*_hK(ykJQ+%bK$Y7;=>nD#li@k3s;1m zpj<%cDyevJ+4;(7;i(v*E2jD$P{pTE#TVY3y|@lV6`w*CU#MM1=vu1&9#F-nP{m7c z!1rP==7Ol=Q>fw#EMbJMe=4t_iuX{(7nsOi+zLb$@1cs96aLu32wgGN_5oGAhbrD} z-lEv6vYkT}@1cq>v|2{!`e&T0;yqOHg~-5O9AiWk@1cq>L?1@z`e$6uccF^+P{m86 z=6kW1t|)5Ug(}`d74K9PpGQ$f=!$7v9veUvAHJv~-*(cSE@ILBC33C%K=i4?jufck zovPyVFBvg{%M(?+hbrEwDn3WBm+k}6+J!3KLlrNz%N9m(y@@K`LlrN-AS2jI_kqN@ zD&9jCFDzjTBl!0hReTCnyi-+t*sCJd+DA+7GL6E>!U; zRPn-HwlIP@Evonws(7cW_^{Ve?!{iZ3sJcXReTCnyl|H-j9`X}Dn5lOUbxE$_R>9t z%3Y}9Q>fyl$6*U2n4zMIPoatz?lOYCbWdSi9zjACpF$Nc++_S9enhciF-S=Cr8d!*|K#3wgThR`{wrW#w9Tv?_O@iVu5hovPx)USP2>f*C5R z_!O#m;V$2cy>v&bau=%j6smZMyKG?uGgMUZDOB;oT}H5%?r2r+LKUAv6))Un3nQ4* zqKZ$UiWlxOg1vM{t8y2r_!O#m;VxSk!3-5ud(3$q`LU@zU#s@#PtK7}e?xXTts zFhfNZpF$Nc++_rN>5f+AE>!U;RPn-HwlIPjn(wW(GW$_h3CO+JOLxk~<=GGYu8eS( zEsS7J=euzW2-P>pefeo~O+(?S7@=AReRHVd6R6?~Z_Zv^hoXv4po%ZlE+bUApuZqg z@hMdCg0(x6`w*CUtl78F{ecppF$Nc`7T=+p~?kqQBcLF zP{kKo6nk;o6jgi*ReYh{a#f2vwpf0;>1~s(6W4j9@R-L~2ZgDn5ZKUSc9!7@lzVK9=A;Nh8`W{flm!OI- zygBZhdvP6#D!vM;_(JV&h6v{x=)eZDrKsW~ zsN$tJV9RERs-3s$t&v*4!z*8e)>BThxEsF7E7yp2^wnuSjYQ%uTM&111eYhOcnej$ z#9c>6(2(tFD;4@?1g9-zEY{J7OMCd zs(6XJY+(eqM^VMcP{m7RU<7+1+J&!eYV?6BK7uM7inmb3J5|N! z7Dg~bMHO$MiWlzkz1R!+T=;gTau=$23st;C2DUJQ87iuH3st;uml5oRyfl0RRJjXP zyoD;>sVY9VFoGG1mAF<1TBzbBit@eK3;A{UmZ@?Vs(1@kyhLiYFoGE>s(1@kyl|Hh z?1gbc_$I4z7pnLes(9fpTNuF%6;*r;RlIPQ5$uKWPWZO0au=%j7^-;TE?XGE3>8&; z_!_Nnml5oRaa(liiQCoY4B;dl;VxSk!JHOVeE3Fg0fF&nv|w&sxi6QUpQ~1QDn?+; z8BUbbH-{=dhAO`B=Iq6FD5`i1ReYg#8G$ipI2liWL8#&_RPmBC@V(fJxge@|3sro9 zC5*tBGo0|JOoS@lLKR>y|`_P zD&9gBUudi-{|b=K1y74M*mm-d16i2Q3}dLH&Ka2Kk0 z2UWaNRea7wMqu?M+R(6-whuk4SXO12?d+vz7%Kv*c-Q&tgWNSss$;B9MlUq2FBYsQ zM$4|>My|2)7eN)TEh?PM4OP6XL9&Gr{C=W}cTmMki(&+OVdXEJd#>>cs(1%gytF8` zFaql>^wl@0;vH1+(xMo_URe1H=eO%hHB|8qs(6XJY+(e}Tj=X`P{muQ;-y6~g1xZv z7tW#A6?drOEmZN+qS(R+thdlt_@IinP{m7&Vg!3(xE!geu-b6)!D{EsVf=3w;$)Pv(|&97eDgRurR)C%#;} zjuTEdmKMbpMqnK$+GXR1wX2rlEbjtBzo#HxTz39Ngu+uX0=q@%yM0i_Td3j-Z_Zv^ zhoXwNP{kK&ml4?ELEr6zD&9gBU-$*ti@6}Gcnej0fhCN#Xi@CNZBtb74yyPKWIh4;w4uy-(S(`%tzV}D{?`>kK7;vH1+R#ox2 zg%SLIqKbD=#amUy=Lq(~F3q_1o5fJYJE-EbFA(PzMqtMteX9|wcn4Ly>@ekfu@`om z#p)6msr9UMqtMteFGG#cnej$#4ARy7j`knwcqrH zD&9gBFENoVjKGdP`j#nF@s_>%JITX$;*Q$1haz4yt(B7tZ%$ zugZ7@RlI{LKKnL#9(@>r-QRJhZ^3Snv(9o*#amUy=Lq)VSShM_2UWc63ug->^ebu_ zsiBH@FEtovr>v`v_3M{nfx0F>yypnHh6*NzDqisKm8kHZ#5aCxGNcTmNP9)}U^ z1r`Z=#BKP{qqH$O!g=3MQ`ed^=?cRPhd~cu^0qg%SMw ziz?nh6)$m@5$pvOOnml>t(EOi#XG3th3#x%1oK!_@eZnZX;F+|FQ{O`Hz&2#LKSbJ zikDW)7DjM;6ji*1Dqi$Bj9@RQVB#F>NBX!;yb%ND7rML&tlv6E4hX~E`};zb$3w3JE-EV zs^W7CBbcG0ig!@OOU}UeVlU|YVyNO(KL}O4gDSqP7$FNIn4zMIcTmNbRVjpEFX$EH z4e!lW9VAro4yt&GaBN`&GgMUZ4yyQARq^?~*bBPL7)o~4b3zsGpo$mnvV{@MP*KG@ zsNzL4$_Vy?el&)XU3IBY#apQ2V^ziH7Dg~bMHO$MiWlzkz1Ryn*chsK)z?B5Z=s48 z?y`ju%urFqTd3ki!^;Tvf}S^ql3f(Q`4?7&yKG?ua~flVr>DmUzSFpX;BRkp*`h2C z-`g%c6(gWHjw@907OHqr7W2K>i|bHS@fNChQ5Lg>5zrz_8M!LnLKPneEg2)&i@6}G zcn4K{q^kIwag2cCSjs5xr-mxtK@}f|{nUIf_Tp9`s(1%ge59)Qob8N&7Fo*3Rq+n0 z_*hl(IfA_^+c{M6ZuPPzqAX?$BcMf=GICYCgDPH>#f)GtjxnN&cTmNPvY0K5fEHQG k$W`$Us`yw{@p*(}FOHR>ig!@O$Eu3YqbMWzJKVSI=|r@m|k*)>_ZKwlV*I|NKpEYqvkhhQ&$ZpPG@+&_7tn@RjT;5+AgI(*Y^QTs{D^&D@tJ0qi3zeWcIoZM9-(Y6q0j0$+3>Rv`^vg$@|Oi zH-7I@s6DTfzK>s5+#NR=Fia3^VZ^d+CKcYd`{-3onzSHZwsuGk!Cw4CjM@K*74gUS zUML8*Fk)EE+X@4twt9{p@tU~Z$n$at_TuMeOkmEA2hF-d5Pau+Pn&9*LcLK3>N!@; zX%{aUaJ3-V!ie5C5373aUkB;4T71>#QO$nW<`C?av>sMf=jwy>9J~L$G763zAqciG z;)5&NRqeV>H%0X9G@~%{$0C9)jKJ@T(p4R~_QRmz=UYT%UN}-k=^VIoo8CF@Hb~ik zrx2vir~Dka^Dw=0wlD(sS5bE7VS49`V6XD4>iEP8o3aG&IY`+6mINvLz@8v&X~y(8 z_i20o%)#<>*}@3$I7pdqOx5xkc4F5e+Zn-L{6wTh*|bHmg%RLekhU~oqD`5|2=?OV zhWm)u*p%&j=X`}=dyvKzV-S688hzNp2t=PCjg=C8TpE2C!Cr_fL0R;1Y4l+WBM^Op zGzJ@kNbS-{%@#%=9tWk~0Fm0Ik(v?gg%})^MQWEuYPK)}kvb^#AAfZ1<_=tPfUtxu zj6i=CmU_;Xk2tsF(S33V_CjwLmij^T&Mxhp(Ibax#)6(YO#5&~8-w22rM)v-7=b=G zEbE{C9W9Q*oNfWEMss*9z0@ z%$T0j&vyqd|4$CVUi?IiLDuKetdA{>Ku#2<*`Q=gF3px0!Cw5_j6p``(u|DnobMJH zS(xU&k|Db^LuLyjkOzlpek~cYOEY9fuorUQuq;D%X@<-eMj%5DOL;poeV1nXY+(dO z0AV@;FlO<;N4QaOGwHDy!CvX_Vt%Cv979GEax8C2z5M^{kt&J^y(&Slg%Ns%6&`I2 z#s=7#sNBIfq~`?X~qB@9em}&j19$7Di}hpor?lEJF}%VT5KJ zdR3aqC5t)ULt69IEx4m+-S{+B;)x zkYH>e2(~Z+{gt1;(yPMwBfpYr3z?dqL)LTX?71M2P5L=@$!n2i`q^{w zVzgwIenwajY+(fQM?Z(G=g?W_9D=>duL^m4LYaOx+m9?f^5X%`;pMl_3}tNK5gH9j z>jsQKcJ7Z<%Jlt8Lk_`S{6r+vPtr`EEsQ`u@7E1VnZ93X$UR;5;^$Vpm*U^oxzDey z9Zs;@7G7SlBG~4f9mDPR9#!Rk7wv7^lzyiOwlHF!e)VvlTSKsyqAT*}XgL1cpye&o z<*J77Zo+Ewu9M$DbU0r?`y|#8$ zjM%5&gkWs1|8C`~*o&V?`BlAiMvbZl&FaaO;CDs(`_Ek!BTjC!tm4iNb?Kgp$GA>n zZ^}6K;wMsmRk+(i`h4J3NT1uEyDCQDd{uwysxmKrBIQ>FW)xB`;fWSfj{Ui-Vg%kz z;ZME6%!{8$`BkA6MQOVO`wD4${Bu{u2=KV@r`Vo(@e?V(D#VN^jZtW+Q5w7c+*L6G zZ9e)_ks3gQ*ZtYnyLU~2#EnO9R@e?V(Ds9`LMo}LnXnhg+oOIO8S{6xyH3NgcHdJ?11Qhf$U$KBdhF+wvZLT~A+*o&V? z*;OT5nE#eqoT68;M(2Mc*o)_^%MloD`IRckZ!yO4D@~f~dcQ55gOAGyj7$9b4xx*l z*CmW#um62jm^JY0vNBHK*+D*1@%NU_!3du5{ND)n;wMs$;JF_B&Ss{HUR!%sjKKVi zUnQ6OD?bMxi@o@Xlp}bSgJ)a#NaYB&FoI`|{x^cX_=%Jwc)ZLbdOmkKf-Q{T8H@jo zU@v|m<%o1->i?HVlSQwsy+KCsD7^d}d@T0jCsK}3OTquIBIGw8sT{!;M(7n%lqhtf^6aNoa#Rz3S zq0@5||1I7jd+`$~zbbfTbtE`PRsq9DDo3z|5gH}7a#ifbPo(@Dc%oSq0^SGJNqE0M z@dh&l?wo2rN@pp5gY3mmq~veRbqUy)t$KsISxrFEYin1<2(Topj3_?`AB(;Ci5N5O z;Vazgbtl{LZ&Zf7Cd{k7T~6y1F5P*b;G?GF(X%}>=wdhW!G~i;8G^=zKTs| zmwELB=cp>3V^h_-_@4XEa`*ls_mQm+@Em)Mo=+BTDm2q`Y~Ok3WbAt50njFpL5 z^{~$A3Ia@wz(hrWi3ymPC=;{lXuS_X=zS;xOiaMUM46b?x9Zc4{8j1GjWQ<2U}B<7 z%qlQ-?M4t_VgXE41eh3uiHR~Xt1wlT2trw+2rw}M6BA`(RvoEpkb(dctH4A>fQc4N zOq7XPRiUyyJ%?wzBEUooCML?ntacDg%&O+V!~jfG1eoZ+#6+2x)xBw}m2+sTRRoym zz{EtEnAN0#iCMK7m>7VGiU1QGn3yONvsx~VCFvXVu|(e>nCQU7SeckrY-xl`dF3OV zA_hG(H9Yu(x`iRfjBq+ClKF2P;}raSz?h-ChV}0nUuBZzh>0~0Xk?ea`&yyV-q$#` zFye&%JBQ!jSEo=!9N*w}+ooy9sNsW`mLb^dty;~)q4(Wh^~?MvILFU-KWSgP>7UWm zzYKP4VZ@pjcMs3IXXio@F@O0+TXWkxqC-~nFGH}`#An-t-@bcS)fL}7gL6dJ)pg@K zuZ~W;vyWp7BZi*ZDm?$?riCJ6$WQHDjki}t<6o&LL$KGwojQc;Kbl?j%1@8r9Cz&1 z&CR=U$GDH};Ml^58u#xTR(r8Up@>-e^@;AfhSlPp19vJzu-E0aJBJ-Fnp<_%pu2I7 zlWzH|o7`)kc=aB}v4s&+|JE@)`d&8K}HrpZcywVY`a7jn>@_Tak?ZY$Q9iuF{uHm+} z?e&$B=M`HR@$<4jf-5J@RYbqa8|^hs>&2c|j9{<5{-_r|HS1Po$>PUm+Rl&K*z<}l zjCgoP&G3*$k1FE&;UCx@uU;B^UNM5bR;_Ck9((6hWy#z9f3eZZ$+71ZTNv@&?sdcN zGoDt&#)*yH(6)19&nrf-*SKeP5APf_U0Krpt>*62uNDcf*usb(ZfX$zkt|Zg+8zhH zLASglykZ1%EbxjgjL>XJ5g)qw!H<8LB)rm@w8+OOok^45kAB@D zxVL_Ts2F{Io>wPaa_-Kt=M`HR@#L$oRb1A#ks_XbVOltA+(h9OBiQS(x4Q*z_G=Oq zqt9&%?+H7cv`~1(7Dh~b^ZklO^P4GRU$c$<@Q7dHgTX6CuvgQ?-GeJ%ZV?ruPmOQ? z8`hs+C-J;u3nNC%`l_OK-`0wFWM)VE^vP`#&nrf-*L$6h3F>XzHY!G+=iX~>_uBuU z#K$YPFrwO=A1m5C)m{D-PahQ8&NrQ!_;|$@ zMqGT+Zxt7fK0pyw^9I}A_nnvcc*O|zT5!}!!Q!bMwdXux=M(L~ZH6R1Ua^G{n(r!N z^>dA*(LHYzUg_Ml#3-Gcmfyp#s4V=q_O{BB?e3ZzUHir#60g|8h`vo07LJ|vlg6u$ zdNhkyA9$VciV^I!xW%l(U&hu}mc%>uj@Ny3r|^m`j5u!SqQW_@nj(%o^rpD`FKm**Wg%K;Be6i5#%Iy@f^W9IyuMKM`ykZ1<9X4=& zVf&AFRhB%~^R@VipPLA;*usd#!&er*eWZ>e4tnl`__4a3lViavMzGh&!yhkvx%=+Q zk|*o`7SGw#Rd~e~Mm%@yn}v;2cT&Xadw!4G&p$?Z#R&G&@rSZxR_j{HUhf^gielS~6th)2d!mw?ZC`*C|eu|!KwNQA)7W9J|0{vB?)DO~c<)!VS2LZb#ve>MU3kS7MxeinO8sD?<6n%=o-ti`#R&Fl zKd@Rft;OoJS9|=+_{u5w3$NJ12=rG`sUIBNeut#_Z~u{gkP+-v@3fjxqsu?kUhS8o z8YfNu`?mChY+(fYtEkiu-u!0kq-td~iC2tZuUfm-iWR4moCW@ovI11*un_( zS5c`S{G@e|4Boqe@QM-a)$D>gQGWK0 zYr^SjhF=p7G;fcPw^w9&dyKq2(7ZjfAaBnQ$gd;h?Ln5e$H?15&D%2sdm%fIkhfQ4 zd3%h!J=DBCvoHerb%eY<$ny3Wd3&gNdxl^yWakm`_KGZTPms5Vnzv^bMj*eAkhcd} z-kufPk5bTBQJVM@Hk>%|P@^-6vduCw-^6LnBdywVr3G#NUd3%OnFXY-0^7e`> zZ%>f7Tg}@u3nP$UN66cQEN@Scw_DBIGX#4fJCBgJS7dp6g1p^o-kw<)Q9d()ygfqR z9%|n1DygfnQF1%t3BQ&lk0(pCayj^(32=+p*9U*U5mLP9Wkhcr3*un^n zD~dqgo*-|xnzv`iVlQOp5%Tt+$SdUS3G#NUd3$DIMEM*U^7aDqcHtGTtn-RHa_s{0 z_AtxaBjoK?^Y+Zb2;|pQ$lDcxygfqRF1+Gnu@`df0`m4S%iAO5?ZPXzFar5?74mjP zAa9S6w_DBIvtzLra_s{0_AtxaBjoK)^Y+Zb2;|pQ$lDcxygf$V?lf=D5bT9qyMVks z%<}dadArlRJ+m+Z`E?cYc10j>kCC@K&D%2sdm+~@Aa4(|ygf$V?lf=DEQ~;YU4^_| z5y;zPB<+b!~T;T0p;3%PcHyj@v>yxk&i z7hbW25y-CtAw+pY>!U*(Ne*Q`k$lD$AcIgKh!CuI7kA7)DP>*d^=ls zww~wVjahc*6noewbqhYfVg!3FZqY){QS1lLJ?|NN!tpB$KEGlMBX}O(m};Xp*&qA= zv*7b9MzGg6pZbcPwrz_2;DQD9T*sMhWxky)jNo~AV;aA`pS$4Gr3K#)GJ?Gh8`x3K zQS1ko)U0qb_8$=WevmDU;CXms_U+!sExqQ~g6{_z!CoT|?;__Y_JfaX>gReMIXd$F zAX^y0v+7>4JlHLGsb1v!K}N7wjhncOGFhW=2^&HRcaE;sRknQ5bUM@$lSNT=x8ojKH>bktFbLo1$ z{MI#k9c|xu%}_TWni~J(r^c2ojNto26~m_U-A!NIChH%JV6V&1*(V%1eR!eBl1pzt z*EOrWwz$SZ7Dn*u3HAeM*T;3N99>+;Aq0Ef`tMfZkne^RifnJXxThP`?X37XaF;EN z;8h^3t1ar}R@OT^J_+rE5$x4(A#&ZF{#Gcq+AFKtxHE3;CUY`uVFa&c8S}+CJGh%B z?zU8#~@5YmjVV1g|a{^V@C>>;vmN$UGb)*h}j=3x2l6n5X947T)vK zI9W?&3nO@y)R>FLO$ht^{%Q`vD`tFdV_NP|#|ATo=B|nnycTB6dDX_*MUSt^-8p;l zGc>0A{0D8FT^q-~H((1RFg~YswfEb6V{fkIWOk4d?8RI#=EA>McV~1Nlw%1acrDDB z|AZ~vz&o$cF_FEP)5cu=)4p!V5qHY$AX^y0YhlLJTz$A(*>*;*MX^_TJMX;i7}xyC zg}GMC2wn@rjzDwzIjp_rA_IGIj4@`=vNK#mvs_lm*un^2Jwt3i{X*CJ_(UQ#BiM^$ zr7`;qIp4jp*K6?u=ndGy2;HASA}SQ151;B5y|+!$5xoJg(Q$PGqm3Eg=?wSHzzuP| zA1Xt(FhXml(sO)2&=ppF8Go^~9Kl}YSJh_Hk#4|4Es_N|eP~sIM*h|M(+8a!GVYqGgP5anq$ZTPRj;R!(qdSSaj9@PvCu(mn z^{^3Pi;vqxKGSClBXn%22px0g5UOJkFFv<1m%sa7`1pw{b63TPrAMp`R=x6`-bd|P zXW9MF?~%K6_Tpz~%&N0S+tzQ4%spL3Ol$pK@Y~H@$oannS2n9274yUvckJ&@ z|7y=%WMD6jF~&T-qJx{!q+KrhFrvJUY}NG@?x7v_l}OFUVlR%B#$0kjSGQ(Cr^NRL zY+(e~tr??LtWrD3HE>$dx`leU0~YS>Zavi{PyO83>fDR0vND3tXUwmQc5|18HaQcc zB1W*6&gkgVUH-=IuG%S`<>|785&Yax`97?+>vBYUd4r5#FP)i+idp#j<7&Gvw%Joy z!WKsG`#0vcUTbaNx%CqtcNxK6I>Qzfv+!mUKeg99wT-N}vxO1NV`C2d_HQ5mB_#d_R<+ojXswh+QXi|-&qoU z*un^oE5^*Owi`CPP|ICEt55RSH-5BTstaWVGt`)GXKv%>zuZf>%Lw+;xlHBm zmFsJ|6(=7dtH^9&1Tz$w{ zY+(d5)R?|kyk>uy*iX322=?l@;+Ej7QF|+QKOVWpe*Vx&5_j3c2xcgH&TkUi>xH9* zyNqD3+t>Xw=vAwQa(9nK&)Zq64-xLNg%Qk9W8Qdnwte>3w!&RTuvg!gMg`C9(p0&- zd!u{o9}n&(++_NdZEXNpwmwcmAjXZz1X&x{-JP}EsS7> z8dE23X`lOLu5gzT>~-11p+TE!b(Fggt=-XXoO7damo1E7h8nZqCu71>kJ(YNk987I`sT@@p^V$+xpdant) z)gG6-bN1qAXiWbje+fIE@~_;}Wdv7j8uQqgLu~!J>vC_9y_gHe4E-svi<@nqV+kX; zViPfO+SPVw&N3nRE<6SKA3-C>iRj?A?v_Tsi_%*FOr zJ8DwzT&raSS8N({eWQo%L;IW|y&4~jy*S2TZ^PH`wsTJVo8-G}VFcHB8Z%?$Lff|K zpv2EpGlIQ1RvPpDkbCW>>xW9d%N9oHUV0KyF_%&86g%Sle@ITvm87gOVYD%yHNV)N z+Whil!MBwmTNt6*EImil0b}it7=PogZ}ki z4<{6^N^bt4v1JP*`2LJp**^*A4IU=%gAwet>ajKzgV%S~-k{ab)$HZl4w84y7DjMo zE;J^~=7mSy(ocBB2=N-=kvbU2U~D=stE)c<8b1lW|y&Vhba+#kVm#e$+Jl`HiO~UNM5bMy{?~G3cPi+8fO3(IITx=yr*T zY+(dft{c;8&iJ6+mAgvZWdwWa&J@}kJka&z;F*i3NNi^dBe(+Jn5BE%QZfI!${a#> z@sQ*4xmELdedF9!ZHA~S-TAnQwSw`}rsVD%$IZO>85%Qp?^~+Qdh40o)7=bFReFOr zv^zSeSGh@g13nghXI{(&W6qvYt8hyFopLPM3{h2L;`Guv>-_aF0wr_^0Dz&Idn5%`^XajZ1v;ZLU( zHUuN2H(<+V2>R-RYF|Zh$Vx`tYgFPcqMg^imf~)d#$C2Bg3o8nPM21Xo1A@##9c

SaTigvDvhFSVFbrV%-jta8>d-@?kOvL)g5W&H}VxKT@X6E2{?xxF< zht@Ur>YB{L2xh1;$L%>ReskR*;VvWCOREi)yZx8+h=+W7zC;GLFoGFsOy%9D$Mv2$ zMYzid_R^|JYUO!0Az{g@Q=7KSA2FJ%&+*32h5=LOmSt!kA9Dewjag8Oda!h0|<}~)E zX+Aoh(z>IJAlbqQj4TVKIho7%7!xmQ)kAs%Mz9yRO{~$cy*s|^vtGGY%Lt4U3#GZG zhnL+EPrLRk>DBmH?8Pw#t#;A;_~fI`$wePVV4O(16rB6?J#oj;Lu7Qv$6_yzm8jlH zo{T@-Z?NPHY+(fNih$Yk;_er+=YZ~bA+c8Xz?R>bFY~)!lxFVYbmopNjNtPbv*^~3 z<9|YH=~qk`!CsgzBNg2XjbDzN*ZzydUA8cSpPMn)eEf3!!BI!Z8)O7~VZMyifX6-f zM10@JR^l#O7{Tw~m<=C268GxRTH-Dv*bDPzq-r#K-5zgjw}-HuEsS6u8*^{RQE`p2 zo6=e5>{#rD`7%;xuJ3tT+^6&B(rVel2yTyH`@DAXxxd~kk%1BHh50g4nI87ZA5rx& zV2;6!O3SdZ}gtq4bX zrx50wF(dY^lkC>NZ!!y&fNWue?&u=SmsOc0U6o-3dvUu#4PAo-W z8!LZ)uNQ4mSc6O^=o%zj7{T{v%=G)3CtnWhCM}8)?1h!TLTQEfq5-=kn<@{M7R44u zV7-NOsZEB|Pd>D5q(w1;y|D6ED6Ld)d;Ye`nwMHh++_k|Tv?#VP0_!cL+r}DXl&(QC zg1xY!nC)SVcr~_TM~~dxPx7Trj5YEw9G|ZhJ1r z5=Nj}gp|cI?)xP^;;f%yKM%*pVlU>jF{5s-m7M<8MyUj33nNeyLdxQs=QK)2pRjYT zMX?vRO=I4BuVu1(#V)y4%Lr79L?vbM^Iz_h9BbN0Cd0>KFOD(DWPa10+&2g1tCa8qnon$g>VT69ILaX$uHXNUfYt~TCfr>W2 zGnQ1)@lI2WHl|zDGue05Zpp&$Dnqs~LigU%bL>6o$mA@o>th6am0#7#-w#aE+ClxY zgB(l03n9Nzh3K`5S_!!SIsKCA)qjoGe%ILVMv_?=!S`p(m^!BeyMiq~3-g%POOBQ^P7-s_$;c;gMJFy&*hmnuWGZt2?>x+FFBeka}Q z#p_SS!U$CCkt*Ju~6#5`B?0wYFVwndf>sGlLO{GF7;PzVFW7nNZtSDf(`My z6URwAX9Rnp`qwLUwT`TH_;&m?vNF=}iiHuV*rQzvPFp)WzGYKaiC26q_EPn-R;0Xo z_;vC0rp+WKvV{?-*rVMRRPQXS`ix*NRAXm*#~Xu6z$mQ*WD6ryEv zp6$lY=a#zgIIRn33nNfT9+fKMyH6eyzjebOQWwq$_Tp!VS%aYu$B(b8mwUR5K=pT2 zs_cK{;4k8;&-&)xAbT+vjJdy6jU?>ZFUJx_pprZ)DHINB-7IblJiPes0DbdqLmitL{VO4Kjkgbgu@DyS+Oc zlT3blq^Jkj!U%ryXU@zTsLgVh?*Y2G(y6O~RJ6jmRJjOiS>{`kC zUw4-l#R&F-3dZlrp>g-n20zBT-P}xCEn67D?GbbOvmT50eDh_|<1m7~bPo`XyC3c_ zA^yvmkwhQ1FoNTX=yBpykHZM|(!ESHib7ozrRo~CFoNSFz7w~@HAxFqpXnEeM3<)D z5|ZE0vH5*8bZ5LXFS;W6{qgp34a|kJg%Qk9V>-?nnq1eivE&SlU@z$W{O%sQ!{3Z& zE=c}1yIWB)LKa3aLs6aZLc4U( z!O0H4eI5BqKt`~a?%bj~E)KY3-=sx{?S;E+VFWYOm=nA2m|WH1$#joKzjKQmi@kIQ z8r?baq*=ekw(j!C@6W&%MleH-8FJ23@g+N5lI}I>cc77Du@`i(e)k*Q0rP~3ljGs1 z3={6Mg%Qk9*)!Acy_4>lnH`J0%D-a*Em@Rm$=JdO<}}6z#T|jtojjxTD>3}76uw%l z{2U66mnw_d!U*VxqmmYR&2CfT`;T5J%3?;a7e95>6y5(!eB@vMDavBDFar8vIY+S$ z`NfHdmrq@?7@uJkM)vm-dkFr9f5=;jDUVv&QYwV{^(p}0Idh4J9%cj zVlU=2zQ}fVMRM@4UkfL1#&$+PKP=}c)`fSjIw`4r=;(-c1d_JKUgholhhhDbRZHuM zvY0K5fPPrcQB)7C8Tt3*&IPxNvX~L<#W4o;?H62{JT<+kD2v&`2q=!_97Qein$xdN zzMnZg@;L(|*o$K&Rz@3*NS4grGxF*IwlE^yhrXyRhAKXqe%125R2460_nJy&zU*wp zjLEnwyIHY?5z0{A{|c)37^?U{Rq=8TuMK4{W{fdV#m7*^2dat}gy$$Dl+(KZ6;$yt zRPlkT;xhz$F=LE@Dn5ZKUUsu$3nP^66-Dks6`w#AAE+u`&fzWW#f&iqs`vz|_)t~x zg76$=gtA@tzk(`0fhs;wReXkEFJ=s?^fvWNpo$Mw6)y_G?pxDke3%9C@_oD`}FhVm9ML-pwKou{$i}A78OLN~KQ^hAx z#ar3ItT_4+3nMh+Py|%*2~_dc^NNqfUYh#`nJPYkD&DFp-jCwM!U)Yc6aiIy0#&?K zReXkEFU@^}VjF}iK7lIU`ZmZGMrg*N2&m!{sN${fqZq+nn)?QsDn5oP-ug_2EsW5N zLlIEL$56$~?t6@2FU@^}OcftP6(9PT$QDLu#-RwP;(Zn#`dzsg!CsnE2bn6~XEL%= zAzK)snT#SdZ_gogCPcjW+}Z3$?y4A}a~ygfP{qek#pmvvz4#f5Dn5oP-l{6z&vM9f zXN1m|==*>wK87mZ`rd$##a_$>QN<@v#phVU2%RrcUO^R~Koy^3B72p$52)f3sN!Ys z9kwt+XGOGqKoy@r6`yNS?8R-<7^vbCsN!?2mJvF~q3s;1_ynr>Tx4J`jxor0mz|M7 z6)$_xv4s&j$D#2Gs`vz|c!|`EU@wl9qKZ$TinpqY&%Wu)2%Qy?h$^c11gdzas`%_H z5jwLiUW^u1d;(RxRaJbpmmVW@20A@Qac0}9Dn3K7SNT;z6`w#A?^G3^eVbZm&*iu} ztFF%qs`vz|c&Dm(zoH-(M(CWiBA|*-po(|CcjjZUm#$OjJBKPhfhyjqD&DV*h=mb4 zXRQdR;uEOiovPw91bgXvi*gsL_ynqW>oXa)Fhb|76#-Rz0#&?KRlHvl5(|6jx{%W2oY#oil>Hbp1uNyaAUbuK(qRlNV=saP1HbK#26 z9h7qjT_qJSK6kbW@iA2KIhHU&*FTk4P{k)u#pjsFUfc>q6`w#AFFX9Pg%P@9s_g@+_ynqW zw|R?Vukv;dReS32wndSi}@~8@d;G% z5~=xE?4>J;8h4?JPoRo-s*2B|C?j;mG%St{po;fj)RAvHX{C!;w7x`sYaNJQm9I#F zD&DCoKKqgpBlvuxicg@5cdCld5bULOAo_Hnicg@5m#51XM(}eJReS zgqbQnfht~D!WKsG`xjMw3{|{SRlKiNkz=u!)`5h@EF7x%7^-;Zvv9UBf_W^e_!z2q zX;F+|FRcR!GgW*HRlLMqwlIR*qp0FzsNy9uFoM0b4n(65RPixX@e+O5!U&ElqKfww zDH7or!CqQlqES@qOC*Z2g%KPdv-&His`$czGxrp}YW!UeRPjz#@!5B~ z7*Wo4sNxf-;)T0>EcVixLgg-0@d;G%t~hHTm5X9w1T$1r@iA2K!d*TVdudIfau=%j z7^-;TE?XGEoEBAl3{|{SRlKitlw+}%Rv{{Pp^A^8iWly(g%Qk9QN_nl#S3>C!CqQZ zsN97rK87k@dK|Vef*C5R_!z2q;VvWCOKS?l;s_F|_!z2q;VxSk!3-5uy#H>7aF-G6 zrB#T^U9F}P?y`ju%xO`@`|py;7xJ{~R`{xwvhrIiT9vy{#rxV?r>b~g3oI5!FhfNZ zA43%{+~s4jmsYeYccF@pp^BHd%N9m3Lq!!ILlrOFWdwU^MXPcbs`wbHc;PNv7{Qzt zReTIpyl|Hh?4=d0%3Y}9W2oYVyKG?uGgMUZF;wx+&wen1y|kiLxeHZ%3{|{vmo1E7 zhKedahALjT%Lw+;idN+=RPixX@xooUFoGGH)z(^>{V1vgvRebKw*^8f{sNy52;&V@z5vp9!HwaaH z3{`yY4YC(=K~(WERPi~MFhW%j%0#H*W2oYDOk^+Sw5Z}^sNyBxWeX!zxu7iys`wbH z_*{!(FK(NnijSd+&$U`csB%Fg161)bRPoZQ@v+#8V~nWcW2oXK-(?FURJouL4yyPV zs(7cW_$BoD#m7*^J5|MJ zJH9hQb!B=E)vGyG#b*fiD!(fIf~0)QRKFT2$5O4O{8mk*J}ao=y*ksWD&Ffv#li@_ zKT*X;P{qsp;A63uY9jTWLlqxG6)*3cEsRhlnj)ZzkD!VdUNM5bR1>M(g(^ORDqgtD z7DlKNO%YJVM^ME}Z@>ulQca|`L8#&*sN$Wf;=TS@ER0Yknj)ZzkD!W|cFxCQFV#e9 zEP*OMf+}9JaJDc)m1v59Dn5cLUg8xa*h@8$8WW+4kD!W|n8+4Js1i*PP{n(7ro>%F zu$O8rwKsq&-YeWBwzGv1s&G?;>N#@=peq_Qt0!K3?o1V*yQ<9)em?-c52)e`P{rr& z9LLSP_!){Sz5=TF+|%6*;rBJr_W@OW0jhZE4ft62op~`AL=_)E6`y0tW(dDOgYpWh z_ySb%(i`xx@H_KjPKzo&fGR%6_RSD}p9yUrP{kLZiqEwu95?ggwkfLk0IK+0tKAIY z_sh_B4pn>ss`y-Fz;QD#jxnN&51@*dT$C-FAu7^1W(-vE1*qbsH(&&QXI>mDMHL@F z6)(L3TQ);f?7B@ijnw)bUil)l?sAgGUH?s9`Hg5tU!B(7NF?sE1#ve+@cBd)Z=s5p zxXTFkLbUT=6V#^*ReT6lyky~QVFW)nQN@Q)#mgIH1bZRc`L7}>OQ4Dmp^6ulu!Rx) z{zVlZLKQEwABGA4L`K_ui2#1KC7y_vHPBugEfjgkO z!U$%lsNyYD@xom`7JDI|^WV-??m`uBp^BHtz!pX@Lq!#Dp^6voGJ?I3m-=sjDtDoZ zw@}49RmEo(MleIM64&Hl3st;CQ9c%XA;0$DGF9$E6>p)6mq^VPMleG~6>p)67w$5G zy)aJj-(*$pLKPoE6))Un3nQ4JqKXfpiWlxOg1s=_@!ytJ?m`tGLKQFEWeX#ip`wcS zU!xW7GJ?G@ZVS#hWrtGE;CIpy?y`ju%xO`@`)}mt5Ey?3^JZ6<smk|15X!FWFwKV!=FIFfeK>zcF7H zKozfJHQmorX71R+2tJ>v;w@D1>8x{hEcU{D8GWM)s(1@kyu@9$FoK_(sNyYD@$v>4 z!Csgz%f63=-r&I}EL8ClciF-Se*dD1w@}4P++_rNVZO}oxTrk$p`}_ru--ccF@R zP{lh{#b-=p1XfRi^|hO5`_R3LWmSgR&R)8Qu_B;~cWuu<#En>78De!Zc&UC(v0z0p zSbF1j@*69E0aWqYqWsR>P{qp{BwHB4_a~}&2UWbZC`PasR{s3H=Nhk|ig!@OON(L) zBe32=Uwwlr-a!>FEs7EBg_S?Qf4iWafd42LKQD9iY<)5dJBDp52|LDUF_)h@YLj)mI6uvypn@*DMuVd-1HP{li_;;pLUGYcd5 z{zMh;po+Juiq8=2g(}Uk^vzTT6#tzf(iHj=Ue;-F;J6jmR-%f=J?S?TSeVaTx7OKj_ zWzCO}-hi)G>caik(xf+F3nNfT?!ObK{UB8F7OHru3ugp-@iP=vyoD-0_jDP7>TmzO zJAH#t#apQ2b8nEnm zdU5~#LCvqAig!@O=UNndaoZGCyn`w}*J>GoN^<`lMXmUSD&9dAFLmL3EcPmoS5U<} zsN&OalV{O~5vcwSQ+*4nMb10VK^1RR6`vv4i({pz;vH1+QWwq^M(9`6G*Uwq?_Q}j z+D=+q8S2+B#R7Frcx0C$@*66c5UO~sr`E4jiXMk8jNtQ$D&9dAFM1qCuoqM?;n~Nu z)~5?qyn`xUo-SJ$!Ou-p@eZnZd4r5#FQ{O`YA?1>mOvHnpo$mu09zQr?_X5$4yt&G zyNqBjs9?hLUv8>whbrDd6)$XO3nQ4vqKbD=#Y>A~1baaRs(1%gd{LD`2=;p)6551O*5$wfW5LLW`Dn3wE ze8xCNKyfVRDArR$74M*m4}Co~AB(-X6^JU{K@}gUDn4U7BcMf=b7ZP`2UUEis`w1S zUghl^s(80*X+2REvxO1RBFi~4RlI{LUX;a*U@wj_qKbD=#f!3-EsTH`SM(}sIjro5q2`NSZ literal 0 HcmV?d00001 diff --git a/GEMstack/knowledge/vehicle/model/meshes/e4/headlight_fl_link.STL b/GEMstack/knowledge/vehicle/model/meshes/e4/headlight_fl_link.STL new file mode 100755 index 0000000000000000000000000000000000000000..bc49454cd9d15568068343798ea26bf654c7efc1 GIT binary patch literal 61484 zcmb`w2ecMd(lvZll8SCfMNn?)DaAb zI_4aBy4#F7q4SDaQ7~f8>D&99s(VkJJ1l zMt;0ETR)s{@b1J+NAG^%g$aN6exg#HebfcXYX7%krD>PO)s+vQ;r_j*=A&IE6s=GD zyF;|y;-TvG|2*4yU6@X(E}b~tp#7*H^vH^5C!OjL;kb%mj5fzts(<#lKw^w)(yqw6 zpWXnWUJYke+v>|=>4?KJTF%|6S)Tp(R5z=YZmY>BbeQbMy>mjd{KoF5NsQmFe!ckq zyQ5qTwGgcc{$8;DDVvn#uciT`!+zR7iV?S1$*WP zJi4PGnr*a8dF#{bxwAXC*>QP~S30;XY5&_1`L$d3a9)aLyqcPW(*EU#Wmkt#3&&Li zf1mflkbHJ4oz?!=)|NYU+q3~fy&BGH)+!^)m0$TWWxS?4pOtsnZ%Kt-(|7-S-u=K9 zZdN*5`qb1sv1oYt)|$;49ET!^UU>Dmywi*ha^zPZGqn8Sz?KaV>P3VelaH}MdU84T zi76>9pFVtE-tnUI-K-AY=iGeBgt--Zb@}y9|F{Q0@r?l{y!v?BQX zwrkJIA6tL1AQpT+uDs-uyBZ)uFFhlER*SD6Rc?0ga}CawA{gVxMXwkDk^o#Gz z$X^(h*ZLSu4xCs%cIr}>eIY`<7~`dTXXKqbDxxxYQrTh5zZ@d8gosuhFU+4kc&fy> z`rAq6E?dlTS1q(CBAC^DKdaVDCzS&}f4|D;{{t~U_;*3bkr%|v(K@soQ?+3XIr2QT z1ZUKt<@h9q9C-tTdNrICv!wUE&lR-Db#~)Qmbh6-Ub){jH8);8wj6ZCgYG!gLbM|I zTk=>C7xz7}od3+628hs0&j^pTrbZam;9Mz!F@$LnLo%@eLcNFx&vZ?VWV<5p^eaI;erNY`!&|ck2=(Hu zq}vHXx^u~~q$B6_l1}Zs6iuI+8tKjsp_UNA-_nC6hIHo!2=!_>D_P072(^Uc^0%x8 zC5Eh)8X(k*i119;)X0j=966(h$0REUYePD^-9=#L3@FA@Wt zGs7OoAwr8Hh(;Gpu=f!Jx^srTK?8((aaQQs33d~LzzQIHbIoQB5n4h7Rt5=nFM_}- zBU|N_A9a;cXHf)ag%wAFy^pMYu#(BJZf}54FU|^Uy96tJL15LFVQ-*opE^s3zdQ;|KzKoD6%M1_<@ytgxO-utO3AR>;}Hxjoz(4lC~j zdjPkN#=0%R4#IgUn(=CCuU*G z1qC5jumM87IFei&LC6(!h|m%uB(DU4{YUoDGjkjwv?zkJk~|g!_Ba{#I1Lc$#aRgp z1R<ZSm7EV)Qbo`CLcq(K}L(zb2lsLA8uUf5)uP@gA98E7eg&X zD}ukJUkL*Hj|}^d28hs0&xoHD_BdH^H;Nt7%}NoBAstm>NXKz8bga;ezxBNN7}C|u zk<$_$lXNwSA*&3B2rY^rT2>i?kX1$lgnDsSvVIVRtTG%Tw1fy*`v?O2j}-e4hX^f- z;H+e=B?#Sql9ieuWM%2juB;~A^^jGj^HMb9x%~%MmJXp7j;jd%mi42= zkdKCdNIB}5wO2yrSD>>B}DMItn_78*ne=P-vAMM=^5dO$REGb zcL=qF>v zZv1bH;J?uFzYzGhoYv(dXr-5+YZ|LV_N-%S%rv`x{Rn^ z{C)fX5ra|nIMj=?(lbJYO7-MM zzgCH}G59Y!EA?VLJtMSQ#2?>v$S?oC*3IO}|6(XIGS0A>y_DHpp+fVzFEM*du3DJy+_*7RdT~~I zMjFmaSd`F9vd{h2ks2b@5+fv!S1>E}B3jQ#!x&Pd+)RY2e_>W3LOAa-a{1>cv^<8EH5x)QkjG)KyOT?J6ogS6r_`1S(O2D!Sr&<-9m6 zJtK@{`5{MJ4ZPfMdaig@GOk0&tX5pxIjit2{11d=h8tJT=wFysh>&Yj<>5mt>#&P0tmds}LdCzJgh)7vt#}VI(^%sW@&X!qmSos}Lca&l|?z zzv#JAFV0HO2(6P#{&)Bvy?c(eFW<#+<9fTS8J3F(y=3L=XJrtw+j17!Eq)aK_ljl}BEq{yHijS1%*xgC@QheQxL*!; z^x;Sr5n4io-hZHd`H0XfJR=Pex|h}6q>s!0UeUP<5xNT}u3-!vEA$G_h(*9s_f8rR z?rl1b>;JQ&S%nD9(7mxoq>T}d6?*aC^^8~q&Z2uaiXJ$-!8=#{mle$_MBr-Hy+>wa za3mco^a{_2MIhtq-k?Fg25%nKk7N-pgv>WYAoJZ@Rz^)h1wn>x@kvPn%?I|Gu9?gwHnh2_F$t&+d>s^ZOVe zCVw#|Y4qj>S=XlqI7IkNP@h2(adrExlNbB!55yC_#wH8TADE>#cXEjE$*4a0BjVB1 z4o|XmHvwYqhhvh7CymOQ9rJ9#x$E;Y{?_MTMC`cW%%u0c_mRh6HyfKYoAQtBx@@pR zgin<8xe5^jcQ`*8@#X*^#(g{{*<+k-ZPTZCr?4PPy5^0 zWUpnXW$jOF<(^Flf~$Ldc2fyrRBCFT|7uKf?VBfMM_w@9A@qp}5&A5Ii1EjtlRR-a z_aF26j!mxr@X+jrHNJF+@acly$0y=HcT7n7j9D|Osd?o0G0Due_sk}YXp?c=@Xo*9 z|0Y7tE)Yk4G$vX5-`i$mXK(5ddS9LBy8G=w{NLt#BuD&X2OxH9F*fRO|Rr zf*%e6esEUY1J=F8NCfzigC9T$KT7b!A;1qFxkG>-d=J^xMDQaAKk_<$l;B6nalsG1 zZ|pcPXV)R*>;fVDD8Ubhkn7-lpW5C4h;2-8zTQB}34=qH8i1%OKr20Vbt$=u{ z<0;w6xa8*F=GDGqDX*>lN0g@+dX9vM61_DBU&e$ZTs^4haNcuh}T{_Jo|IuE%^t>zF&lv7}5Bp zJ*u7i@XeZ;zwMp1{PL#!UrSdjLj-@T*SNM#lh>xcKfh(~TN&&3}J!ut5;5Ue7=GT;;<*f0^HCYre5H^Tp;_ zmnj<-_b=M33@tHY)NZF#Pd@D|AjYh-B>l%h&5ON%JJcYER%xa@`_%g_=dE?79Z`q|>Mfw-;prRn%@)+w3{KEWV}RxehDbq6-8-aLW# z9IhHYI-NHzE4DfwZ?^@O7-9J_sPXRk;U9icVTR-G5V&!j`;B``d~Q@>RvvZm`uTai z9z;zfKdv18WIo}HGn3Flbck5{+&1}k-QNa+{Mh>DLB-4)e>4c9)r(m?Vol$KQ5XR&2WZEQ26gy_l7)cNvl&zVI8wAU}RR?zdv$ zA2+9=B}Ux!WdHoAmDWNG@*}ywP5Iqv4;ci}>cy=5>gYrA1AeOkg8W$Rj`rn$UVS+Y zEivMm&v(zCYQ8QI7KVQEoj~x8yHfghR((YfUp(RFK zvS4`r`C%IXF&6xI>5A>kIVXK<5JamNv+|0?$LCkxusRUrNBeKKFMB@JC<`qyV&rNg z@<*TP3dF78$LG`bD4)7&WrHAEy~qOTgFyTn{J3f2Zsp$}Yo3Lc7*W5Uy_l8gAGPQoKuG^c&_A-!5+l$VD(D|TNdHLCKMaCs^BgsGxrUA^jsk|1b!m)r(n){!xqm0fh9A6#XL$EinR}p@RMag!GRT{lg%L zRxf5H`bP!*0|@CKDf)-YcD2L^bcPE02N2RfQuGgl;JE4~U7~{i0fh9A6#c{T1D(ZL zVnqG^gZx1MNYFpH{$&3EPp)&n_1Ofo68$4V|ESjWj|BZA4=vI^_>8T}e@ACX&_95X z{*j`87)0pBtVI7v&_95X{*j`86rm+Xpfe=sA3#X|NYOtGf@t+(R-%6-=pR5x|47k4 z-1`bUcXVGtZwy_l8g9|`&gVo3i;(LajN5+l$V67&zmkp7XOe;5SO z>cy-?|47h3fRO%?p??&iB}Sk#B zh6Mcs2zC64n!U!F&2Y0e3mge?PC+HbAg{bo}P6 z`R}*=!dS?U5K+HlAwO>V?ydP>+;yzmf9P1ucJ*Rb^50v&vm0WNAG4aztq$Dv5|{02 zi4pZX7V_iPYxb*td-O8~!Ex1#S;>)Z8_0L)$&a_cZ=65%$%ii6)ecP#85_jQ<4 z9Y40Y+kYs61_}k zSG|~(9O;1HbpLU6HX>hd#x`y@p_Uj?zhfakk|p0(&scjmgW$O8#jNB=pRdoAKKU{2 z^E2|pdhP9Y6KaVO^*a{!kM>Je&0C&xxIu7S^P3EVq&{P2AO`!#(fu#aj~kBfaRN(>sNb<%n=VU! zdb2}*eJgxd6d?Fpy^#4XhJVJ|bi1+1HLYgneV+GUA~8BGF+$#r#H_ACj5b^ESZsM3 z?jd7b-TiRf@UDTz18cjFO|HFX)8eWZ@Fh|-lR5;@a<>gJW`8#(S${~=;?lkFwNr#p zFUG5%Rd659-OG@BZ>$WeGvJO%?!zI*^evVpLq`0oIB4bxE{0lSgdU%-SGO(vXK{b+ z7>fwb0(y)3enrPwYZ(N`RWH`AN7`Rez2VNGh%pN_ap*^FiZ>=Tbv02fF+%Up z__}*YkJXBq@4w;dt|BH{aSwiVUM}mu9g^~_nCbEnDo|d z`Pkp58wAHyFZPnl_c^_K-O8IH27A;AyN=KQ`|wEDqtp^3^nRJ|gEO{mmd}{7*!4k0 za9s65<|lYZL*A5SuN`^90o9lOag^(?YKakg7teR+ArD-SE^da^%Cex-CDY(*fqlIj(xy>%s1P&+W_dr9VzJXE#Rd z{PY9WoqyszOJ2c0Ds78%-kWa_99O+;Ua>nLwPvN5dg#k0OJc-IeV?iBy4TK#!AzX@ z;*g^84lA2XpL3+$5k)O zbFN;e?|6C9?~?9@wJ~DV8B41ho^vE(urh4^?<!k+4an;M#D|Y7=!|y06kM}p# zCq}G0>znFBXY#%%yYqsnw-kMzA8HUBSG{cAWp}=|<)g(K&G#`?G)DBe_m}FGm!E2`vUH|lzPnR5`?pXoGt$QK>bp3OKKYK1q%5J|D z%?>%p%}OntNr=!H`Xj&V(wg$iVS8IdFe{#g8&7SYw> z-*;<+2(yG)`QsyN*NL3_tqwZsTzuNf*9Nz zwEk*Zal*78T)k3DjL=Ht`{0pB9$Wmg`4a{aRv%WoDcgNeUG^ux$Ym8h@4wp@UoX7V zRZ+FX2(75T5AHH|?PB8rrx`?8MOn4aJL}o%!}oFT%sx0`>AU%qv-fb_KrJysJA?0o z`NT1K|68AT9Y+yiH(>X{JD2X;6W`U^o%33C=4HcNS5r%j&<!u`GSu}$|t46a2#UC^jp zY0GULqtp^3l$)M|8{fBbxnR@o1`%?bncwY|E_tWf0}z88oV5P3qQ}PF9HZ0{Bb1w- zgKhU)Ts%LtwLyg3X6C=Sc8C14RklS8a`2RspDjLEt%YNhT4IE9({u3aLmw(mS>+pd zr$`YYx0(5KUuc=Py0j-^a0Srw`fH0LHvh;mN-Z%$x#>Chz=G+;scYP45Fxjj`ITXf z@=o{s4Kc{UCNCdT+<(aRj!|lf5z0-^!P`FFyy&+1F$NKGo0&hd#j@(dZ>)hBzucygQrZdvyB)v*MBWdA38*rsHPj z$la{O%U%zzMc03Nm*TDOhnTY)Bia^g=lk!(v&$>kc(1dIA8xzMAULji*}URfbl6XG zijM!9YqBIpy!FEOMcod8DelP+WY2>$|LUVV-Oryy;!xiOZYoQE%w;7{Pv5@ zO*e=U_3xK(ExOslP0As|Dh9!E)r;Lndsj_OW2{BTeYQop+Ub35SBnt(K8tw^$sy|A zjlsBeZ@>Uu|DH^nzRQw}`)yZlKMuMdfrT>(5jsQMjl(^%gPz{LJooet77@&fXF;A| z;_R{yHlEk7{Au_G?(C{1Jo50o`L*b|PxdXho!{CZLN8uTc@isGGJ2z)Ws3{fae1Yd z7@^nS_rbll>ROKeM-zhxvxHeGPm~dZeQ>Lz)-6xjys67}wZsU`eBTFaE^Aq4gFban z8Wa&`JJ}^q#u0<8o&5_|l_xHBJXcGMPzL)x_&|>@ig(X=*dRjIvP#Gke#Bt)dE;*j ziyO{(&{ZF`#0afKz7KZ(^UmUnk1sNau==pt$(stO)U2YdKKf^I;dlNXfLdaNR#e{y z+blV(==a_>uI?%#tfH*i^2UX9gI{`WRt$fzgX;!ri4pbvgB|C*W%uT{-S{upaTF1D z19l&I4@COlKCAZ158KW^^H58S&<kqh=9S&e0e(o*PIpZ$_)mWKfSz~ zW0YD#&J&^B^c=kVj-AR+oBUdYV})MKe0j?PF}NRWa#E!nHDe{mD7C~0<)-K0Zg*}~ z_Bj7TeM-hRHu8|$%zSxU1To0LMQd~~```PqKD*<4Bn=SCw3?c(=xUw&{H>g|{sMyt zxy{U%w_b3~c^7B$)RtwFbb(`(T4IE9v!>>9bm!XdYs#N*zRn;*ZZq@c?H$A*2d~{` zY0;;c;~1ru7@^$s9K7$UM~ZIeOfZO$+su4<3kfmE!2!q4D_(l_NXIC(#0X`Y=ir%N zPbk_A>}U`nx0(6!HWgxUMfUQh+ZU_#ZR$9vmKdQ-^J`Ig|H^St5h1t9L3xu4F?e5e z_RDF$d5bmO%2F*cLb++)t#xmh%KNl@s?Yb({oAJCio9Ek80&3|XA`}TD4*^7RzXgv zB}OPW{eJL=c_YfNy8oX=1l(rk-%~p||89G}2f#i!_Wj{y@#=?;QEFj49XDi}-w&?* z+0b(67S9?)=tZu~==S$~+jahn806p<+YBxzUGbV@lv-kha?^A0f$DbU4$U7lh>+XN z{CV$=&Y#-@z&HGiY$-UbnJn;gXV zwNBTr3J`{xT!s2T*v#ka^#JHs9ayYmJ;-_4&H-`UJ6My!0~ z=6QD9FgfzwH$I^Fu<30E!Ex2gUJvdEKRNuo;@wV<=Ak7F_?+tKV7+eX`5XQg5#=}f9Z;EOv9g5#=J z*d_da@TfV*mOGw*jp+t4qW&w0>#!f(vDcWg*ADj^1jkh`b|39s{@KLJ&m3RgG~;^P z)glDGN}_5yjwASD#3AG>5!VOnzS96&z8C>wLic6K!Rww}ZhzA_H!HPpCLuy+==ZVz3XkKI)+IjV?#HEKy60(2VhYu=D$SmbVP;YY<_UFe{HHfmF=CLl3*YNr z9#!4Uu~scHLK*D);1xaAE|2fEia~^|WtEuv=0W+ee{?_$-WT2W`=({*HP&?1M=dcz zE0OPm!`r`CbUoq8JRB>mKCE^}<%9FT|FI@wun!*p=3~Y2U0!f?S1mC@>!a_3x3|5p zxOw_yg9xiAtM>4N`sUN;)F1}?V3P$Si{@XQ=(>SgVuW@E-v>W#yELEO=1up`rXs>_ z!0sb@Lim1=YtgSh8kxU2{v6lU)Dk1K! zI<0KG$!qQn8nuvvAws$7Ik@?flgo~4J!%mFx0(5!j-8(G^Z6NwK@R@1?1Zvr|Hh6{ zY9R-8Tq2a4o`cIiIHo-Ai~HUCf{F;enE6L6nU+62`c%Xq2S?60tZaYD&u)LFmKdSj z^c+kd9aaw6{6>Qaxy{U<`1s`f=@3BoedA~~y zf@t+(=Jy+QLVoMgLlJ`<{P@jY<)6Dhl82TUq1^NwT=l26{^PPGk207S!uVadr&T8g3sFoO^ zO!FL^yZEzw%q0gp4k{w#HaRFdUWh>sZaQ#O{$r(!Ge*2yWshUk5 z==<<@tvwE|Me~VY;EqF0O=t;b5+Z8-kF|S$ zWjP4M;1!%Y;hEx(;hh>>54oDPHm|rAT{7vT;{L{O7)vmd@ZS-GnRxxF&C7c~+O-;v z75uIZS>UsM|NGjNPaoN-5?YpnKnyaf-RZr{2eR?i5E1;Y4cY8jd(fKOmWzMhwGvvE zgFppGTFacR8;TT9$)A3|8v?-A^hnT<@xChzNeyvTAFW@ZDh5)lMmAeKyN| z%dVE?AP|GkCeGTS5?@T)Uq4|V#t^G{IWPD zqV9|3`mW}VL%L6;re=!t!8V(`mT+9P5G{Q$JaWX~vx)m(oKVi}-y}7N`t#$ihjcZ> z;5R1Ew;Eq=bz3#z`B6)F9N~HMeQ@XpN0)QX`OP3gFJ4XQYKSooS@O)>k>wkmZ%;x? zjFA3_6Y^^cKl%U@<+V-O*0StX>aAqK0@?4_%h zwQCJYLQ9O0{)iZ?a3e2RT>RAcID-hQPtbi3gH^P}El(FeoZKb}EipnXs;|_$jK8>O z^wru15mr%FZRu)=!9Lh>$*5w~Q*+(-r)r52((P~@>^RZ~4I=CY>^{=ffM6e#u10p& zSz?6rM<7JYg5T;p4$4l^F<5qYu42gU4#%PU!R>Au=NP3Haxg?FH$4ZxNsli-`r%}Y z2pG)Fmwhy1aJPNP?c>VTR^KBHEg^&X@5)X8Y+{Y;N0u+nIL07CFJ`{%?hu2Oy5mKM zlwaSzT^d?qL_KTS4fg4{N4a?QVFp38dNK25cZV3{V5{o~l?R>DGYu^t_%|s~0n0c6W%u`=TdY*Q4y%v~?ObF9T4Q;E}tD)Z1icGgq9eg+%)?^$3Y#7X!Rn~WOs)c z!CI6osbz1Kj>X^VW%G(zGJfKJiyKC6n1+@ZA@|`CgPFL_ zdX38|8*gP0M5|ZG0^f12oVRAVXwd#9+hc@0Pe2TIwJ-a0Ef-Y}H3*KYULl)(=ln>p#J3z$rOX&xat*FCESxi^%;86z;gT%mz(MnBjouGVz9!U zdeZRnj?1y432GmIt5;ZE{YvJxp$C))y?&#qqA^0AQy~V|qTSa#x?Jy+*#^OJ)r(bI zyM(_l`p2lF%Of_v+jN5%QLl2twdlc@9ao+)b*@2hT=hcctF{bg#V@M5jvZTGu*w6r zt3?P^)iDY*4k6Fz6OJp-2VEbOr*esTKImqpmKdQk^sDeuCmdL|`(&v_1he8=heD3Nu3?lU6)s&}wI1XmX-^c7;9{bkgE=$xB zBQ#_DT6F9lN%_g0PZ~s+CCtitMF(d4lEK@QFO0v#WxHBpgl4|KFWUOmjmjYp-C_`7 zwv%1*v=7&utX=usj^*^bE_19^ON>wk`^xa&{hF3nPP@P$Le{cM$kRT=VD+hd_j}Rf z;p1HOQA>=_O61p~TVMEW(SMy`1`$>tRy%pxhZwA)7k9tEnDc5+S4GtlBebIWK6vAR zGmFs=G%<*}ytA6)H@y^FqwFL2#JEipnngYP)Ge?DjsVK-p+k*9r#!9FNY z`&?I3ON`JC=l7h;=IvF^d$UEx3|GwxGAdNeQl{0^yt?t&Wb3Q7eHL26^TvOdw|9WxeTGN3*}Obq z___uWdXbOvJ{%CN3?FyjqWt5~7FlSC5%Ts95ZtA{vC9VK>qDCx1kvh6KFa%WK(I2L z@olGa;mn#Ww8RK`dj|;aQolX9c{#J)cdjz%SVXHA`6%zh0l~^J=YwWt`N*4&=W2-& z^7al8Tp{oK_>$tv4WBXyj;mheqr49X1S`Wv`@LE0eAn%c=W2-&^7al8T>Jca)vZPI z4K6bXj;mheqr49X1S`XmU1k?Q%sb8TTrDv|-rfNRxrTe|#Dj}_dS(W}an*}_l=tDJ zGTixPzhc48t7OM@o$z(~4kS`YygPHi;$xjp;{=C2-IIenG zelXjg{ptDQtV`cF*&ZY0dkVxLqqaTzhoW5L7lYuq>J_rt_w!D7|57}7_Ns>GF+#p1 zK@3)geqXmJe;nA#AULjig;mK{pDv%aD6d_&qp3bILcWMW3|6=;_guexy4{8b!Ex0q ztggO_zPnz>^04=MnJOA1$o#tAYQ>Tb9qw7;F*2taujW`zSfPv-Vl1y#M~~-Pu)3 zc;w-E^DE@5-e^`Hyk=$)p%<^Fd>MMcwYZ4DyKcCt&pk3tNxw)=f}H}SO9 zvd|JEl)=6a_CEZs;L-nQqo zqG_jx3?i&PtakE!6k@Osc767gqTiS~u8OK9MrcL#eQ>XXdls{Xj4_C?in40U_fd$! zZqRt^R>ibG`uT3)zjt(ZLUi1)&ijrdUsU;yBZ$z8-ABHULJY2u<@+et)zlIrw8I&F zQO7~~=Gbviz7uvFl<$NQBlxn|F-k4uV2Ds|dJf+9`B%lRjrO+)a8SLN`SL|JVsMw* z_dmZE$Go+dW0YFR!4RR`^i{Omq{YP-^L8@`j;mhGeECioG5F@dmXCg3ymj*qj!|lf z5z0-^!LPf#Sgg{l)*wP|GxOy;VZJJ7L5i2e)o|Nim?) zSB_C?i4n?8&%whlKcu*I{8I)Ia+_R{?}QP99GtSw(4zaITO6a*5+jtGo`X-$Yf+s0 z&?JKhxy{U%?}QP99DIAykNK1L4{{t-ON^*zt$#-EzASbeR0PLWFLF@66GjYjP`+w( z98^n;P;PpJe2Z)l99Q%?Ol)5nL}9~NVua{{$dSL(Z$aMep}ozKb5`nQuLswn3x9n- zpS91~=Iq7@Q9_X`*!Jx1#XZaJHwccaUN*0|7TtGx?_&QpubM205u(q67|g^ChK(xD zKk-k4;JE5#`N8id+CF!5aaEr+Ot!}eQKmr*GOB5lONw9SbTSBzt6rAp+(C9ZJuYGDF`vR7Jcl& zyg0D!o(92j)yvjh?&weNb5}9#jx#jH&ZF$j*UUaZ>MC44t{ z<(6vE^z0)|H;57S+UmSpd)Ya!6jz>bltFM@^`X2r80x>1P1K6qHO z%ZiQ1ALGuhTEZg_&ztXqMdQPZ>-$fAVSu%N{Av9V(=~2e~#@{%)hCzQ*TvE zjL=Ht`(UTqU-FkMY0D$1%YicpBbKG(ISz^roa12K-)sO^M1u}7PTY7|GJ0~aB0cvXj!|kM2SbE%({u3bY3ml% zweZ&?g0c8py_or;-G>UCSG}0|qCtol zT#IhIFs^aYwbxLC2)WJ77cE7^AP0v`=~V2x=gy8%YKalb zO@D{wmD*48^`G9_AVO|4^FCh{nUr^E(`tYRS_Y# znfan^i5Oe~3^??y{JUpXbsSVnj8LX|4({~(#rdOGeBd~!h>+XNe9`Dc407aY6+`>Wi8jD z@>dre2Ne-|k%RSrHIy6_wKvB>wZsVJrf04EEeM0)xO`8Q|7(wfvl1;5xxzY+PMpEflJj;mgl=WZ?f&bQU^Uud|x6X+p34l)M079&u>MS-6jgdTDQddQB0iV$u) zuQ2m{$AKPl0zG8MC?d$U7=cby>lOIf)u4x5fgZ9!2)CVAnE8J73O(cmddQAZj6tr& z2=ri4;3o&6hg^XkvOx&9omZIoegyzMBl zQQ#Ln8JFO;(mpobJ$AmsbAl!M`LRddMmCkQ*S>i}C7b75v>k zcO2NiR^GjDnj5$7@1UWsV9&|F+lLskOHHAN>|&^e~Y&_hNH)?Mf!r_e)o*IX?;yE-lrSo_LfU0`j89&!pjWP=F3m}A&;R-lKB7`&GO zJ>(R6$S!x)5+kremcJgs9tAz*6ne-8!Ex1#T*02R0zG8JAP1p`oI(%TaZoKW0xM+s zD;Vsx&_hn4hiniWSG~x2>^UpYLq-hN66hhP&_i~$L@hA_D`fd=9((R6$Ogf2 z)r++Yd(H~^S%va7p_;JE6=8jL+>1$xMc z!P*Wz`~A|PN0YEdX!pX z1oooxS7Nvp#V$309on0%EYd_Tbn=+*;rx(?k!iKhb%`9J>&#>$mYm7EA_J1gJ&0d$O-h2&Do6+ zxT{`)9(R6$cD8s0?%G5&_hNH zRtD%Hr_e(-2#%{>wqCLNKo2>E9zb&nnPEMhsSJ=pm=jLpBJGt6r?y+9iB9fF5!RJ!I1jVg&B*%HQW?=Y$?| z3O!_l;JE6=?xVfS->ronatb|U+tnfj?(Zh}dxtm<(L?56qjd{WK*&?e6ne;RR(Oi&ESyP*&>8w8haPeUJ!FdrX2r9Br;7>nkmc+`4>^S% zvOBwK36DHHZ+?9RJ>(R6$OaL5@oM53WCA^8#9)>{4>^S%vda>+#0bq8zfOc6atb|U zg9x*PS&3(m3G|Q=gV_!}

_yF5A@-BQ*2==HGXA9K?G)$;a0n;5dkPagw#aIMi_v@8a<9J0pg?y^}!?*)d8j^M#vPFP{>cz~*TTcn}kP(CX59lFh&_i~NQVTg4B9xo{ZY}hXGw2~31jkh`W^M#vSXB5VuW(ja}avS8T611BIGtRAMfHM&_hNHau9mRDfEyXqtp^3 zl$)M|&_hn4hinibx0(5P7bk%pGGdT}&_hn4hwK=omKdSj^c;j9atb|U_x6q=LT)qj z@h(mRJ!Hh-3IKY@DfEyXqtp^3l$)M|&_hn4hinibx0(5PXC{FjGGdT}&_hn4hwK=o zmKdSj^c;j9atb|Ug9y3J%*R`r73d)&1~~{l

_yj)Q865y~{rLAO5zE1)@WP{+iP>ZZ|dgnd&7OTegv%*`f z3G|T7tYQS-drhE+j9Kx>p@*D857`{Ko0WLk>%p}s^pI2NA)B)sBia^gC(uKdD+oR0 z6ne-8!Ex2g<`vhX&_hn4hitMWM&PaK1bWDb!EOLO

_y2ElRF%kqP3QRpG3&_g!a z9wYGfcLF_R#2}-fhnzwW*)WRZs+Z+C*P_rv&Y*{ESQ{hoPI>}8WW*3X?AsYn8RWDn2xfX>Uat1wQQ$=G0zBfpq zhm06pi$V`MgC4R$a9s6b)z&Uir-z(D57~5s7=ia*^M#vPA^5;#t7A8T`9_m=*gV^pG>?A-l7ymhi~K^XAv0 z&_m9khinj`7q2G1y5Qd*lq`WBat1wQmnCY65t=c+4?+()gC4R$gjvF@#8(&mJBo~1^*r-Vvx1aL(ZUw?0Bx07@-XI zeei)EU!>4OHi(e5tP=R@f`8W%F<5<|hnzwW*;OC4#0afKz7IkVIfWjwL4?(Z)ec`> z@b7b?QnL?24>^S%va6zMi4j^+eIJA#atb|Ug9xiAt2Vy6;NKaQZU8;x6ne<68>l5l z)b|hGlYt&`0zG8caTF1D19l&Lo58&W+c!Ea5TV@kYf^M#vVLpn#^Si@#mvVSmHexrh{63J^pG>? zAv;E?B}OPWJqMwOoIwv+zqNE@h1_Q5^S%vSXB5VuW(ja}avSDfEyHBIGtRA751Ruj(QOIS4)E6ne;xQEG`1%1zHf=pm=j zLpF$z+su4?QOUm!j2K*zK@T~F9^P{1klW-SzNiFeu0ss2 zMe#*d0zG8MLAAsPx% z`aTFf_yj!|lf5z0-^LFgf;&_gzeklW0Be7&4N z4;eAYLFgf;&_i~NQcH|bZh8(v4>^S%vO$F0X6EDT^S%vSXB5VuUhH z?#a}?nm`ZPAVO}FgZO$mnfde?h(Qj@-wk))JF6u|C^tO^M#vZ+2X0?I}S^pFvQ`$6a-XV6172#%{>w(fF22tDKs zddQ}V#t0}hCD21g3|4CBA!pD-HVBTZUaZ>MCH#I6ddL~{kWDv;5l{+Ao;aM9LG+L_ z=ph>f$5k(OAMIWK*#z{EGw31Pt`;Gna+N?288Ji;IlC?!>=4kPONMnD==vbktdfow zo$vY})U1*bZw>%L^sh4LA-h?rg)<2eIz!(Fp@*D757{DuS@A4D%_@N&GGcHo3O(cu zddTkVswF(~@Vxmx2tDKsddLP5dhu#Prz(LSGGed~LJv8E9hnztV z*&xC!VOBz?DuEs{Vu&7c20dh#?P`e;n)!Y$3O(cuddLP5W;@vhovH+S$cRDKLJv8E z9(2}$gcXRB}Ql^@_i6`$SL%Y zRfEor6;>ZsJE&PD&_hNH_Ce?&r_e)obyqDhLhGaNgU~}xp@(b`VHIW7hE7!iJ!HgS zAA}xq3O!`k4b&1Nv@`gQ13lyfddRL9DI)9!>^@MlN^ZJhv1rgi%_@N&vg>MUi4of2 z>hzGae_npJ+XF&5GI{pksZL)Ks*XwLj=8EjCZ|uHf*7KQoIwxSKRN6@!&%6|5TV@k z9E2Wn20dhp00-5JnGX%)1bWDbK@LI>IfEXuW0YFR!4RR`^c;j9at1wQ_db*&IIemz z^P%dPKo1!)$U*2KXV61-Z)vF|MkqHu2cd_YK@Zs=LT)qjq3W1G4;e8;4>^M#vU}T1 zEipp5>F>!v4>^M#vO$F0X68fHF@YX3VvvK-L(ZUw?B1GFON>x%dJaMlIfEXuL4@39 z=0nvnfgUnqa0LK8(2}$ZkETV+H8>>^|DN{8|)x$QksI ztD$8%2*eOQ;~NjF~%WFpog464>=DlF+%zy zVsKXkJ>(2}$OaK+Nzi=|gV_!}=DlF+%zyVz9zN4>^S%vO$E^ zC+I$i!72(p

_yd1#3dT2Xzah8}VXJ!FFjt7y=D5QBXXddMmCkgK63Mo72Aaj@e^ zA2f)t8zA#_EeZth$w*ftJL@blLb@FgqKBM857}{0c8ZRJvb%GcFS|P&hwcZVhwK=o z7IH8|C^tO^p@*D757{CD1~c^M#vOy57Ud(*i-2p)kLJv8E9&!;{VuY+kfe=09 z40^~0L9}`?^JRAj1n-MN4>^M#auHf$gseq@AP1p`oIwxSAc$5kX1?t1fFK8=*Lr$TGY!D%X znfbE21A-ic9&!pjvIl8T611g5#=JSe1PB zfgW-OJ!DgTVuU>3K@3(n=pkp&LpBJGt6pJs^(z_ZA!pD-HdQo6$a5;h;93-V$QksI z4T9sU7pt~*34dP{ddL~{kWDv;5ppLLF}N0m9&!dfWP{+i>V?dw9y0H80wH?H8T62C zSBnsGCl!c!ea9x(e|Tti!x~>Yggm3qIj%hIbA3>r%H`(ypqrIiVua4n-;;qJat1wQ ziwI`Lvmj6V5QBXXddL~{kloo;OL*krdGl8gddL~{kPRaA;?(2}$OaK+3A0k3_8|td9eT(a^pIV)t0hKg=KDSfJ!EJ!++q-6wv%1* zv=3L1tc4zO20diQTD8OoWw5Ud&_m9khinibYgr}aX&+*+`almkg&wl2K5B^(T8aEx z6ne-h^pFiAtUj!E^0W^zSVf_SoI(%TRZ+FX2(75T4?+()g&wj&gjJMPTb}kI2KylN zkW=U(yKbPC7@?iPcO2*;^ZB4bgx!GMN1pZ}2K%5q?Q>mCEipnnT%8_r20i4G87^<3 zI1b8tYi`%4OsmsF&Y*|v5NaU@>k#-Y@5~?*MGrZH9&!VOdJ(PsuhT=$#?Icfq($DX zbF-57;oPj`eK^Eu(|1{Nalh@bV(RK*sDf(dtD$%KLCYurfdoIfEW@8Cqh5yuAYicd5`r&Y*|vDua$iw0e<`@;)38tPIdY z&Y*|vc&?ThA#d*h!4)#}kW=U(8wAHyFY-~|hXaC@0eZ+O^pG9T)e^S%vg5g0VuZZC0}gTx2R-BzddLRBan*}_l=tDJGC&VG zg&uMdT4IE}y#oYS$nplAs|-38(dvcF*EhbUGRWIIWKo?ZM#$Scf{=Ia41#ER58bVh zHMXCXyh(0m6(i)`bDUk)MCc)>&_gyy&RMCKy&gQf&_hn4hiuMnjF30}yH0Jq2Qr zQP4w9p@(b`99O+UHv4`KJ>(R6$cE=JLcSzH3|0o{A!pD-HVBTZUSU=8)dzaW8T61% z^@$PkMGRuF!a)x?gC4R$a9s5YtE;b~&_m9khis~7jF2yT5QCK(ddL~{kPU+4su!!a zb_w4Npog4657~5s7$NVTBZlZ9XV6172#%{>$o#tA^M#vh8XSLf$<`jNMv{ zO@40ED!cgZy&OWmYIJ>2zK?Q!P`+aVBKV@p%}OntNr=!H`Xh%Pat1wQiwI`LvmjqS z$=QV-at1wQcXrhh9(j1){0bR*$QksI4I=d7)s*j}5QA9)J>(2}$SzCN5+gKYd?rE< zIfWjwL4;Yttd#Gg5QEtcJ>(R6$S&K}5+gM8eIJA#atb|Ug9x*o?2_-J5QD6R9&!pj z=_O62<>^pI2NAsa+k zeOT?}`zXXu zqq`HLEa5TV@k9E2Wn3O!_t00-5JnJ-^tBL;V=&_hn4hwK=o7IH8| zC^vl-g&uMWJ!FI6xa!5sm+yoTgKrK%4>^S%vSXB5VuW(ja}avSDfEyHBIGtRU%nGY z3~~^9$SL%Y9i!9|Bb1w-gU~}xp@(b`A-9?N@|`eZkb}@ePN9eFIH;Bwp-l4}gdTDV zJ!FFj8O+R=?}QP99E2Wn3O!`UD7C~0<)-H#^pI2NAsa-n=&d?t@^pI2NAzMT+E1m_>jY16eLFgf;&_i}-S1sX@hv&`rLFgf;&_gze(2G}7 z6rm8qtwq;AKZPE$%M!K32+bJZ2cd_YLJ!#>!YpA{iXs$ZFx#ProI(%TWxHBpgl4|) zgU~}xp@(b`VYZW9q6mc;WG(cNQ|KW()~Y2&D1&_;gdTDVJ!FFjS<5ORicpBbw^*Tv zoI($|3@tH2E0OPm&_hn3hwSQ=juloPRy$FILJamn=piT2Lv~eEEipnXs_%o)Lr$QF zY!G1;Wz`l%D8yhNgdTDNJ!IDn)Dk1KGx&}pN>i@mC?f0z>^`C!g&6FE&_kwflpy8C==pm=jLw1Z(3pp4fl$(A(2tDK!ddLRBan*~NFG_`o!L=y#kW=U(J4UG`MkqHu z2cd_YLJ!#>LT)qjMR5@^$U*2Kr_e)oj8aRCP;UA=EYL$vpoeS_A-9?Nq8y1BZZq>m0TVH}0)QTJ0zG8MLAAsPWt!(8^pF$iAv+E# zB4jW#Uz9u%gB*k&asoYM$0)VL2<4{dAoP$E=ph?K$Zcl6D3T%uIS4)E1bWDhgKCKp z$~4bG=pk2HFaE@FP!S=w$wARfMGSHfddO6Ja~xDlj8JZR1oV(=uNXAiAUH1HQ^o(9 z*nU&}Xkj;^ER_bN12iKy|L#{v%*__=NK{Pa45rbC{ddLa% zkPU+4s+Y|xu0^4TT!9|4$&wgBG&EWfgP90DkJfgZ9!a9s65=BtJ&5Tb{iKo8k=wFp5p I)LVi0f0HM^Gynhq literal 0 HcmV?d00001 diff --git a/GEMstack/knowledge/vehicle/model/meshes/e4/headlight_fr_link.STL b/GEMstack/knowledge/vehicle/model/meshes/e4/headlight_fr_link.STL new file mode 100755 index 0000000000000000000000000000000000000000..bc49454cd9d15568068343798ea26bf654c7efc1 GIT binary patch literal 61484 zcmb`w2ecMd(lvZll8SCfMNn?)DaAb zI_4aBy4#F7q4SDaQ7~f8>D&99s(VkJJ1l zMt;0ETR)s{@b1J+NAG^%g$aN6exg#HebfcXYX7%krD>PO)s+vQ;r_j*=A&IE6s=GD zyF;|y;-TvG|2*4yU6@X(E}b~tp#7*H^vH^5C!OjL;kb%mj5fzts(<#lKw^w)(yqw6 zpWXnWUJYke+v>|=>4?KJTF%|6S)Tp(R5z=YZmY>BbeQbMy>mjd{KoF5NsQmFe!ckq zyQ5qTwGgcc{$8;DDVvn#uciT`!+zR7iV?S1$*WP zJi4PGnr*a8dF#{bxwAXC*>QP~S30;XY5&_1`L$d3a9)aLyqcPW(*EU#Wmkt#3&&Li zf1mflkbHJ4oz?!=)|NYU+q3~fy&BGH)+!^)m0$TWWxS?4pOtsnZ%Kt-(|7-S-u=K9 zZdN*5`qb1sv1oYt)|$;49ET!^UU>Dmywi*ha^zPZGqn8Sz?KaV>P3VelaH}MdU84T zi76>9pFVtE-tnUI-K-AY=iGeBgt--Zb@}y9|F{Q0@r?l{y!v?BQX zwrkJIA6tL1AQpT+uDs-uyBZ)uFFhlER*SD6Rc?0ga}CawA{gVxMXwkDk^o#Gz z$X^(h*ZLSu4xCs%cIr}>eIY`<7~`dTXXKqbDxxxYQrTh5zZ@d8gosuhFU+4kc&fy> z`rAq6E?dlTS1q(CBAC^DKdaVDCzS&}f4|D;{{t~U_;*3bkr%|v(K@soQ?+3XIr2QT z1ZUKt<@h9q9C-tTdNrICv!wUE&lR-Db#~)Qmbh6-Ub){jH8);8wj6ZCgYG!gLbM|I zTk=>C7xz7}od3+628hs0&j^pTrbZam;9Mz!F@$LnLo%@eLcNFx&vZ?VWV<5p^eaI;erNY`!&|ck2=(Hu zq}vHXx^u~~q$B6_l1}Zs6iuI+8tKjsp_UNA-_nC6hIHo!2=!_>D_P072(^Uc^0%x8 zC5Eh)8X(k*i119;)X0j=966(h$0REUYePD^-9=#L3@FA@Wt zGs7OoAwr8Hh(;Gpu=f!Jx^srTK?8((aaQQs33d~LzzQIHbIoQB5n4h7Rt5=nFM_}- zBU|N_A9a;cXHf)ag%wAFy^pMYu#(BJZf}54FU|^Uy96tJL15LFVQ-*opE^s3zdQ;|KzKoD6%M1_<@ytgxO-utO3AR>;}Hxjoz(4lC~j zdjPkN#=0%R4#IgUn(=CCuU*G z1qC5jumM87IFei&LC6(!h|m%uB(DU4{YUoDGjkjwv?zkJk~|g!_Ba{#I1Lc$#aRgp z1R<ZSm7EV)Qbo`CLcq(K}L(zb2lsLA8uUf5)uP@gA98E7eg&X zD}ukJUkL*Hj|}^d28hs0&xoHD_BdH^H;Nt7%}NoBAstm>NXKz8bga;ezxBNN7}C|u zk<$_$lXNwSA*&3B2rY^rT2>i?kX1$lgnDsSvVIVRtTG%Tw1fy*`v?O2j}-e4hX^f- z;H+e=B?#Sql9ieuWM%2juB;~A^^jGj^HMb9x%~%MmJXp7j;jd%mi42= zkdKCdNIB}5wO2yrSD>>B}DMItn_78*ne=P-vAMM=^5dO$REGb zcL=qF>v zZv1bH;J?uFzYzGhoYv(dXr-5+YZ|LV_N-%S%rv`x{Rn^ z{C)fX5ra|nIMj=?(lbJYO7-MM zzgCH}G59Y!EA?VLJtMSQ#2?>v$S?oC*3IO}|6(XIGS0A>y_DHpp+fVzFEM*du3DJy+_*7RdT~~I zMjFmaSd`F9vd{h2ks2b@5+fv!S1>E}B3jQ#!x&Pd+)RY2e_>W3LOAa-a{1>cv^<8EH5x)QkjG)KyOT?J6ogS6r_`1S(O2D!Sr&<-9m6 zJtK@{`5{MJ4ZPfMdaig@GOk0&tX5pxIjit2{11d=h8tJT=wFysh>&Yj<>5mt>#&P0tmds}LdCzJgh)7vt#}VI(^%sW@&X!qmSos}Lca&l|?z zzv#JAFV0HO2(6P#{&)Bvy?c(eFW<#+<9fTS8J3F(y=3L=XJrtw+j17!Eq)aK_ljl}BEq{yHijS1%*xgC@QheQxL*!; z^x;Sr5n4io-hZHd`H0XfJR=Pex|h}6q>s!0UeUP<5xNT}u3-!vEA$G_h(*9s_f8rR z?rl1b>;JQ&S%nD9(7mxoq>T}d6?*aC^^8~q&Z2uaiXJ$-!8=#{mle$_MBr-Hy+>wa za3mco^a{_2MIhtq-k?Fg25%nKk7N-pgv>WYAoJZ@Rz^)h1wn>x@kvPn%?I|Gu9?gwHnh2_F$t&+d>s^ZOVe zCVw#|Y4qj>S=XlqI7IkNP@h2(adrExlNbB!55yC_#wH8TADE>#cXEjE$*4a0BjVB1 z4o|XmHvwYqhhvh7CymOQ9rJ9#x$E;Y{?_MTMC`cW%%u0c_mRh6HyfKYoAQtBx@@pR zgin<8xe5^jcQ`*8@#X*^#(g{{*<+k-ZPTZCr?4PPy5^0 zWUpnXW$jOF<(^Flf~$Ldc2fyrRBCFT|7uKf?VBfMM_w@9A@qp}5&A5Ii1EjtlRR-a z_aF26j!mxr@X+jrHNJF+@acly$0y=HcT7n7j9D|Osd?o0G0Due_sk}YXp?c=@Xo*9 z|0Y7tE)Yk4G$vX5-`i$mXK(5ddS9LBy8G=w{NLt#BuD&X2OxH9F*fRO|Rr zf*%e6esEUY1J=F8NCfzigC9T$KT7b!A;1qFxkG>-d=J^xMDQaAKk_<$l;B6nalsG1 zZ|pcPXV)R*>;fVDD8Ubhkn7-lpW5C4h;2-8zTQB}34=qH8i1%OKr20Vbt$=u{ z<0;w6xa8*F=GDGqDX*>lN0g@+dX9vM61_DBU&e$ZTs^4haNcuh}T{_Jo|IuE%^t>zF&lv7}5Bp zJ*u7i@XeZ;zwMp1{PL#!UrSdjLj-@T*SNM#lh>xcKfh(~TN&&3}J!ut5;5Ue7=GT;;<*f0^HCYre5H^Tp;_ zmnj<-_b=M33@tHY)NZF#Pd@D|AjYh-B>l%h&5ON%JJcYER%xa@`_%g_=dE?79Z`q|>Mfw-;prRn%@)+w3{KEWV}RxehDbq6-8-aLW# z9IhHYI-NHzE4DfwZ?^@O7-9J_sPXRk;U9icVTR-G5V&!j`;B``d~Q@>RvvZm`uTai z9z;zfKdv18WIo}HGn3Flbck5{+&1}k-QNa+{Mh>DLB-4)e>4c9)r(m?Vol$KQ5XR&2WZEQ26gy_l7)cNvl&zVI8wAU}RR?zdv$ zA2+9=B}Ux!WdHoAmDWNG@*}ywP5Iqv4;ci}>cy=5>gYrA1AeOkg8W$Rj`rn$UVS+Y zEivMm&v(zCYQ8QI7KVQEoj~x8yHfghR((YfUp(RFK zvS4`r`C%IXF&6xI>5A>kIVXK<5JamNv+|0?$LCkxusRUrNBeKKFMB@JC<`qyV&rNg z@<*TP3dF78$LG`bD4)7&WrHAEy~qOTgFyTn{J3f2Zsp$}Yo3Lc7*W5Uy_l8gAGPQoKuG^c&_A-!5+l$VD(D|TNdHLCKMaCs^BgsGxrUA^jsk|1b!m)r(n){!xqm0fh9A6#XL$EinR}p@RMag!GRT{lg%L zRxf5H`bP!*0|@CKDf)-YcD2L^bcPE02N2RfQuGgl;JE4~U7~{i0fh9A6#c{T1D(ZL zVnqG^gZx1MNYFpH{$&3EPp)&n_1Ofo68$4V|ESjWj|BZA4=vI^_>8T}e@ACX&_95X z{*j`87)0pBtVI7v&_95X{*j`86rm+Xpfe=sA3#X|NYOtGf@t+(R-%6-=pR5x|47k4 z-1`bUcXVGtZwy_l8g9|`&gVo3i;(LajN5+l$V67&zmkp7XOe;5SO z>cy-?|47h3fRO%?p??&iB}Sk#B zh6Mcs2zC64n!U!F&2Y0e3mge?PC+HbAg{bo}P6 z`R}*=!dS?U5K+HlAwO>V?ydP>+;yzmf9P1ucJ*Rb^50v&vm0WNAG4aztq$Dv5|{02 zi4pZX7V_iPYxb*td-O8~!Ex1#S;>)Z8_0L)$&a_cZ=65%$%ii6)ecP#85_jQ<4 z9Y40Y+kYs61_}k zSG|~(9O;1HbpLU6HX>hd#x`y@p_Uj?zhfakk|p0(&scjmgW$O8#jNB=pRdoAKKU{2 z^E2|pdhP9Y6KaVO^*a{!kM>Je&0C&xxIu7S^P3EVq&{P2AO`!#(fu#aj~kBfaRN(>sNb<%n=VU! zdb2}*eJgxd6d?Fpy^#4XhJVJ|bi1+1HLYgneV+GUA~8BGF+$#r#H_ACj5b^ESZsM3 z?jd7b-TiRf@UDTz18cjFO|HFX)8eWZ@Fh|-lR5;@a<>gJW`8#(S${~=;?lkFwNr#p zFUG5%Rd659-OG@BZ>$WeGvJO%?!zI*^evVpLq`0oIB4bxE{0lSgdU%-SGO(vXK{b+ z7>fwb0(y)3enrPwYZ(N`RWH`AN7`Rez2VNGh%pN_ap*^FiZ>=Tbv02fF+%Up z__}*YkJXBq@4w;dt|BH{aSwiVUM}mu9g^~_nCbEnDo|d z`Pkp58wAHyFZPnl_c^_K-O8IH27A;AyN=KQ`|wEDqtp^3^nRJ|gEO{mmd}{7*!4k0 za9s65<|lYZL*A5SuN`^90o9lOag^(?YKakg7teR+ArD-SE^da^%Cex-CDY(*fqlIj(xy>%s1P&+W_dr9VzJXE#Rd z{PY9WoqyszOJ2c0Ds78%-kWa_99O+;Ua>nLwPvN5dg#k0OJc-IeV?iBy4TK#!AzX@ z;*g^84lA2XpL3+$5k)O zbFN;e?|6C9?~?9@wJ~DV8B41ho^vE(urh4^?<!k+4an;M#D|Y7=!|y06kM}p# zCq}G0>znFBXY#%%yYqsnw-kMzA8HUBSG{cAWp}=|<)g(K&G#`?G)DBe_m}FGm!E2`vUH|lzPnR5`?pXoGt$QK>bp3OKKYK1q%5J|D z%?>%p%}OntNr=!H`Xj&V(wg$iVS8IdFe{#g8&7SYw> z-*;<+2(yG)`QsyN*NL3_tqwZsTzuNf*9Nz zwEk*Zal*78T)k3DjL=Ht`{0pB9$Wmg`4a{aRv%WoDcgNeUG^ux$Ym8h@4wp@UoX7V zRZ+FX2(75T5AHH|?PB8rrx`?8MOn4aJL}o%!}oFT%sx0`>AU%qv-fb_KrJysJA?0o z`NT1K|68AT9Y+yiH(>X{JD2X;6W`U^o%33C=4HcNS5r%j&<!u`GSu}$|t46a2#UC^jp zY0GULqtp^3l$)M|8{fBbxnR@o1`%?bncwY|E_tWf0}z88oV5P3qQ}PF9HZ0{Bb1w- zgKhU)Ts%LtwLyg3X6C=Sc8C14RklS8a`2RspDjLEt%YNhT4IE9({u3aLmw(mS>+pd zr$`YYx0(5KUuc=Py0j-^a0Srw`fH0LHvh;mN-Z%$x#>Chz=G+;scYP45Fxjj`ITXf z@=o{s4Kc{UCNCdT+<(aRj!|lf5z0-^!P`FFyy&+1F$NKGo0&hd#j@(dZ>)hBzucygQrZdvyB)v*MBWdA38*rsHPj z$la{O%U%zzMc03Nm*TDOhnTY)Bia^g=lk!(v&$>kc(1dIA8xzMAULji*}URfbl6XG zijM!9YqBIpy!FEOMcod8DelP+WY2>$|LUVV-Oryy;!xiOZYoQE%w;7{Pv5@ zO*e=U_3xK(ExOslP0As|Dh9!E)r;Lndsj_OW2{BTeYQop+Ub35SBnt(K8tw^$sy|A zjlsBeZ@>Uu|DH^nzRQw}`)yZlKMuMdfrT>(5jsQMjl(^%gPz{LJooet77@&fXF;A| z;_R{yHlEk7{Au_G?(C{1Jo50o`L*b|PxdXho!{CZLN8uTc@isGGJ2z)Ws3{fae1Yd z7@^nS_rbll>ROKeM-zhxvxHeGPm~dZeQ>Lz)-6xjys67}wZsU`eBTFaE^Aq4gFban z8Wa&`JJ}^q#u0<8o&5_|l_xHBJXcGMPzL)x_&|>@ig(X=*dRjIvP#Gke#Bt)dE;*j ziyO{(&{ZF`#0afKz7KZ(^UmUnk1sNau==pt$(stO)U2YdKKf^I;dlNXfLdaNR#e{y z+blV(==a_>uI?%#tfH*i^2UX9gI{`WRt$fzgX;!ri4pbvgB|C*W%uT{-S{upaTF1D z19l&I4@COlKCAZ158KW^^H58S&<kqh=9S&e0e(o*PIpZ$_)mWKfSz~ zW0YD#&J&^B^c=kVj-AR+oBUdYV})MKe0j?PF}NRWa#E!nHDe{mD7C~0<)-K0Zg*}~ z_Bj7TeM-hRHu8|$%zSxU1To0LMQd~~```PqKD*<4Bn=SCw3?c(=xUw&{H>g|{sMyt zxy{U%w_b3~c^7B$)RtwFbb(`(T4IE9v!>>9bm!XdYs#N*zRn;*ZZq@c?H$A*2d~{` zY0;;c;~1ru7@^$s9K7$UM~ZIeOfZO$+su4<3kfmE!2!q4D_(l_NXIC(#0X`Y=ir%N zPbk_A>}U`nx0(6!HWgxUMfUQh+ZU_#ZR$9vmKdQ-^J`Ig|H^St5h1t9L3xu4F?e5e z_RDF$d5bmO%2F*cLb++)t#xmh%KNl@s?Yb({oAJCio9Ek80&3|XA`}TD4*^7RzXgv zB}OPW{eJL=c_YfNy8oX=1l(rk-%~p||89G}2f#i!_Wj{y@#=?;QEFj49XDi}-w&?* z+0b(67S9?)=tZu~==S$~+jahn806p<+YBxzUGbV@lv-kha?^A0f$DbU4$U7lh>+XN z{CV$=&Y#-@z&HGiY$-UbnJn;gXV zwNBTr3J`{xT!s2T*v#ka^#JHs9ayYmJ;-_4&H-`UJ6My!0~ z=6QD9FgfzwH$I^Fu<30E!Ex2gUJvdEKRNuo;@wV<=Ak7F_?+tKV7+eX`5XQg5#=}f9Z;EOv9g5#=J z*d_da@TfV*mOGw*jp+t4qW&w0>#!f(vDcWg*ADj^1jkh`b|39s{@KLJ&m3RgG~;^P z)glDGN}_5yjwASD#3AG>5!VOnzS96&z8C>wLic6K!Rww}ZhzA_H!HPpCLuy+==ZVz3XkKI)+IjV?#HEKy60(2VhYu=D$SmbVP;YY<_UFe{HHfmF=CLl3*YNr z9#!4Uu~scHLK*D);1xaAE|2fEia~^|WtEuv=0W+ee{?_$-WT2W`=({*HP&?1M=dcz zE0OPm!`r`CbUoq8JRB>mKCE^}<%9FT|FI@wun!*p=3~Y2U0!f?S1mC@>!a_3x3|5p zxOw_yg9xiAtM>4N`sUN;)F1}?V3P$Si{@XQ=(>SgVuW@E-v>W#yELEO=1up`rXs>_ z!0sb@Lim1=YtgSh8kxU2{v6lU)Dk1K! zI<0KG$!qQn8nuvvAws$7Ik@?flgo~4J!%mFx0(5!j-8(G^Z6NwK@R@1?1Zvr|Hh6{ zY9R-8Tq2a4o`cIiIHo-Ai~HUCf{F;enE6L6nU+62`c%Xq2S?60tZaYD&u)LFmKdSj z^c+kd9aaw6{6>Qaxy{U<`1s`f=@3BoedA~~y zf@t+(=Jy+QLVoMgLlJ`<{P@jY<)6Dhl82TUq1^NwT=l26{^PPGk207S!uVadr&T8g3sFoO^ zO!FL^yZEzw%q0gp4k{w#HaRFdUWh>sZaQ#O{$r(!Ge*2yWshUk5 z==<<@tvwE|Me~VY;EqF0O=t;b5+Z8-kF|S$ zWjP4M;1!%Y;hEx(;hh>>54oDPHm|rAT{7vT;{L{O7)vmd@ZS-GnRxxF&C7c~+O-;v z75uIZS>UsM|NGjNPaoN-5?YpnKnyaf-RZr{2eR?i5E1;Y4cY8jd(fKOmWzMhwGvvE zgFppGTFacR8;TT9$)A3|8v?-A^hnT<@xChzNeyvTAFW@ZDh5)lMmAeKyN| z%dVE?AP|GkCeGTS5?@T)Uq4|V#t^G{IWPD zqV9|3`mW}VL%L6;re=!t!8V(`mT+9P5G{Q$JaWX~vx)m(oKVi}-y}7N`t#$ihjcZ> z;5R1Ew;Eq=bz3#z`B6)F9N~HMeQ@XpN0)QX`OP3gFJ4XQYKSooS@O)>k>wkmZ%;x? zjFA3_6Y^^cKl%U@<+V-O*0StX>aAqK0@?4_%h zwQCJYLQ9O0{)iZ?a3e2RT>RAcID-hQPtbi3gH^P}El(FeoZKb}EipnXs;|_$jK8>O z^wru15mr%FZRu)=!9Lh>$*5w~Q*+(-r)r52((P~@>^RZ~4I=CY>^{=ffM6e#u10p& zSz?6rM<7JYg5T;p4$4l^F<5qYu42gU4#%PU!R>Au=NP3Haxg?FH$4ZxNsli-`r%}Y z2pG)Fmwhy1aJPNP?c>VTR^KBHEg^&X@5)X8Y+{Y;N0u+nIL07CFJ`{%?hu2Oy5mKM zlwaSzT^d?qL_KTS4fg4{N4a?QVFp38dNK25cZV3{V5{o~l?R>DGYu^t_%|s~0n0c6W%u`=TdY*Q4y%v~?ObF9T4Q;E}tD)Z1icGgq9eg+%)?^$3Y#7X!Rn~WOs)c z!CI6osbz1Kj>X^VW%G(zGJfKJiyKC6n1+@ZA@|`CgPFL_ zdX38|8*gP0M5|ZG0^f12oVRAVXwd#9+hc@0Pe2TIwJ-a0Ef-Y}H3*KYULl)(=ln>p#J3z$rOX&xat*FCESxi^%;86z;gT%mz(MnBjouGVz9!U zdeZRnj?1y432GmIt5;ZE{YvJxp$C))y?&#qqA^0AQy~V|qTSa#x?Jy+*#^OJ)r(bI zyM(_l`p2lF%Of_v+jN5%QLl2twdlc@9ao+)b*@2hT=hcctF{bg#V@M5jvZTGu*w6r zt3?P^)iDY*4k6Fz6OJp-2VEbOr*esTKImqpmKdQk^sDeuCmdL|`(&v_1he8=heD3Nu3?lU6)s&}wI1XmX-^c7;9{bkgE=$xB zBQ#_DT6F9lN%_g0PZ~s+CCtitMF(d4lEK@QFO0v#WxHBpgl4|KFWUOmjmjYp-C_`7 zwv%1*v=7&utX=usj^*^bE_19^ON>wk`^xa&{hF3nPP@P$Le{cM$kRT=VD+hd_j}Rf z;p1HOQA>=_O61p~TVMEW(SMy`1`$>tRy%pxhZwA)7k9tEnDc5+S4GtlBebIWK6vAR zGmFs=G%<*}ytA6)H@y^FqwFL2#JEipnngYP)Ge?DjsVK-p+k*9r#!9FNY z`&?I3ON`JC=l7h;=IvF^d$UEx3|GwxGAdNeQl{0^yt?t&Wb3Q7eHL26^TvOdw|9WxeTGN3*}Obq z___uWdXbOvJ{%CN3?FyjqWt5~7FlSC5%Ts95ZtA{vC9VK>qDCx1kvh6KFa%WK(I2L z@olGa;mn#Ww8RK`dj|;aQolX9c{#J)cdjz%SVXHA`6%zh0l~^J=YwWt`N*4&=W2-& z^7al8Tp{oK_>$tv4WBXyj;mheqr49X1S`Wv`@LE0eAn%c=W2-&^7al8T>Jca)vZPI z4K6bXj;mheqr49X1S`XmU1k?Q%sb8TTrDv|-rfNRxrTe|#Dj}_dS(W}an*}_l=tDJ zGTixPzhc48t7OM@o$z(~4kS`YygPHi;$xjp;{=C2-IIenG zelXjg{ptDQtV`cF*&ZY0dkVxLqqaTzhoW5L7lYuq>J_rt_w!D7|57}7_Ns>GF+#p1 zK@3)geqXmJe;nA#AULjig;mK{pDv%aD6d_&qp3bILcWMW3|6=;_guexy4{8b!Ex0q ztggO_zPnz>^04=MnJOA1$o#tAYQ>Tb9qw7;F*2taujW`zSfPv-Vl1y#M~~-Pu)3 zc;w-E^DE@5-e^`Hyk=$)p%<^Fd>MMcwYZ4DyKcCt&pk3tNxw)=f}H}SO9 zvd|JEl)=6a_CEZs;L-nQqo zqG_jx3?i&PtakE!6k@Osc767gqTiS~u8OK9MrcL#eQ>XXdls{Xj4_C?in40U_fd$! zZqRt^R>ibG`uT3)zjt(ZLUi1)&ijrdUsU;yBZ$z8-ABHULJY2u<@+et)zlIrw8I&F zQO7~~=Gbviz7uvFl<$NQBlxn|F-k4uV2Ds|dJf+9`B%lRjrO+)a8SLN`SL|JVsMw* z_dmZE$Go+dW0YFR!4RR`^i{Omq{YP-^L8@`j;mhGeECioG5F@dmXCg3ymj*qj!|lf z5z0-^!LPf#Sgg{l)*wP|GxOy;VZJJ7L5i2e)o|Nim?) zSB_C?i4n?8&%whlKcu*I{8I)Ia+_R{?}QP99GtSw(4zaITO6a*5+jtGo`X-$Yf+s0 z&?JKhxy{U%?}QP99DIAykNK1L4{{t-ON^*zt$#-EzASbeR0PLWFLF@66GjYjP`+w( z98^n;P;PpJe2Z)l99Q%?Ol)5nL}9~NVua{{$dSL(Z$aMep}ozKb5`nQuLswn3x9n- zpS91~=Iq7@Q9_X`*!Jx1#XZaJHwccaUN*0|7TtGx?_&QpubM205u(q67|g^ChK(xD zKk-k4;JE5#`N8id+CF!5aaEr+Ot!}eQKmr*GOB5lONw9SbTSBzt6rAp+(C9ZJuYGDF`vR7Jcl& zyg0D!o(92j)yvjh?&weNb5}9#jx#jH&ZF$j*UUaZ>MC44t{ z<(6vE^z0)|H;57S+UmSpd)Ya!6jz>bltFM@^`X2r80x>1P1K6qHO z%ZiQ1ALGuhTEZg_&ztXqMdQPZ>-$fAVSu%N{Av9V(=~2e~#@{%)hCzQ*TvE zjL=Ht`(UTqU-FkMY0D$1%YicpBbKG(ISz^roa12K-)sO^M1u}7PTY7|GJ0~aB0cvXj!|kM2SbE%({u3bY3ml% zweZ&?g0c8py_or;-G>UCSG}0|qCtol zT#IhIFs^aYwbxLC2)WJ77cE7^AP0v`=~V2x=gy8%YKalb zO@D{wmD*48^`G9_AVO|4^FCh{nUr^E(`tYRS_Y# znfan^i5Oe~3^??y{JUpXbsSVnj8LX|4({~(#rdOGeBd~!h>+XNe9`Dc407aY6+`>Wi8jD z@>dre2Ne-|k%RSrHIy6_wKvB>wZsVJrf04EEeM0)xO`8Q|7(wfvl1;5xxzY+PMpEflJj;mgl=WZ?f&bQU^Uud|x6X+p34l)M079&u>MS-6jgdTDQddQB0iV$u) zuQ2m{$AKPl0zG8MC?d$U7=cby>lOIf)u4x5fgZ9!2)CVAnE8J73O(cmddQAZj6tr& z2=ri4;3o&6hg^XkvOx&9omZIoegyzMBl zQQ#Ln8JFO;(mpobJ$AmsbAl!M`LRddMmCkQ*S>i}C7b75v>k zcO2NiR^GjDnj5$7@1UWsV9&|F+lLskOHHAN>|&^e~Y&_hNH)?Mf!r_e)o*IX?;yE-lrSo_LfU0`j89&!pjWP=F3m}A&;R-lKB7`&GO zJ>(R6$S!x)5+kremcJgs9tAz*6ne-8!Ex1#T*02R0zG8JAP1p`oI(%TaZoKW0xM+s zD;Vsx&_hn4hiniWSG~x2>^UpYLq-hN66hhP&_i~$L@hA_D`fd=9((R6$Ogf2 z)r++Yd(H~^S%va7p_;JE6=8jL+>1$xMc z!P*Wz`~A|PN0YEdX!pX z1oooxS7Nvp#V$309on0%EYd_Tbn=+*;rx(?k!iKhb%`9J>&#>$mYm7EA_J1gJ&0d$O-h2&Do6+ zxT{`)9(R6$cD8s0?%G5&_hNH zRtD%Hr_e(-2#%{>wqCLNKo2>E9zb&nnPEMhsSJ=pm=jLpBJGt6r?y+9iB9fF5!RJ!I1jVg&B*%HQW?=Y$?| z3O!_l;JE6=?xVfS->ronatb|U+tnfj?(Zh}dxtm<(L?56qjd{WK*&?e6ne;RR(Oi&ESyP*&>8w8haPeUJ!FdrX2r9Br;7>nkmc+`4>^S% zvOBwK36DHHZ+?9RJ>(R6$OaL5@oM53WCA^8#9)>{4>^S%vda>+#0bq8zfOc6atb|U zg9x*PS&3(m3G|Q=gV_!}

_yF5A@-BQ*2==HGXA9K?G)$;a0n;5dkPagw#aIMi_v@8a<9J0pg?y^}!?*)d8j^M#vPFP{>cz~*TTcn}kP(CX59lFh&_i~NQVTg4B9xo{ZY}hXGw2~31jkh`W^M#vSXB5VuW(ja}avS8T611BIGtRAMfHM&_hNHau9mRDfEyXqtp^3 zl$)M|&_hn4hinibx0(5P7bk%pGGdT}&_hn4hwK=omKdSj^c;j9atb|U_x6q=LT)qj z@h(mRJ!Hh-3IKY@DfEyXqtp^3l$)M|&_hn4hinibx0(5PXC{FjGGdT}&_hn4hwK=o zmKdSj^c;j9atb|Ug9y3J%*R`r73d)&1~~{l

_yj)Q865y~{rLAO5zE1)@WP{+iP>ZZ|dgnd&7OTegv%*`f z3G|T7tYQS-drhE+j9Kx>p@*D857`{Ko0WLk>%p}s^pI2NA)B)sBia^gC(uKdD+oR0 z6ne-8!Ex2g<`vhX&_hn4hitMWM&PaK1bWDb!EOLO

_y2ElRF%kqP3QRpG3&_g!a z9wYGfcLF_R#2}-fhnzwW*)WRZs+Z+C*P_rv&Y*{ESQ{hoPI>}8WW*3X?AsYn8RWDn2xfX>Uat1wQQ$=G0zBfpq zhm06pi$V`MgC4R$a9s6b)z&Uir-z(D57~5s7=ia*^M#vPA^5;#t7A8T`9_m=*gV^pG>?A-l7ymhi~K^XAv0 z&_m9khinj`7q2G1y5Qd*lq`WBat1wQmnCY65t=c+4?+()gC4R$gjvF@#8(&mJBo~1^*r-Vvx1aL(ZUw?0Bx07@-XI zeei)EU!>4OHi(e5tP=R@f`8W%F<5<|hnzwW*;OC4#0afKz7IkVIfWjwL4?(Z)ec`> z@b7b?QnL?24>^S%va6zMi4j^+eIJA#atb|Ug9xiAt2Vy6;NKaQZU8;x6ne<68>l5l z)b|hGlYt&`0zG8caTF1D19l&Lo58&W+c!Ea5TV@kYf^M#vVLpn#^Si@#mvVSmHexrh{63J^pG>? zAv;E?B}OPWJqMwOoIwv+zqNE@h1_Q5^S%vSXB5VuW(ja}avSDfEyHBIGtRA751Ruj(QOIS4)E6ne;xQEG`1%1zHf=pm=j zLpF$z+su4?QOUm!j2K*zK@T~F9^P{1klW-SzNiFeu0ss2 zMe#*d0zG8MLAAsPx% z`aTFf_yj!|lf5z0-^LFgf;&_gzeklW0Be7&4N z4;eAYLFgf;&_i~NQcH|bZh8(v4>^S%vO$F0X6EDT^S%vSXB5VuUhH z?#a}?nm`ZPAVO}FgZO$mnfde?h(Qj@-wk))JF6u|C^tO^M#vZ+2X0?I}S^pFvQ`$6a-XV6172#%{>w(fF22tDKs zddQ}V#t0}hCD21g3|4CBA!pD-HVBTZUaZ>MCH#I6ddL~{kWDv;5l{+Ao;aM9LG+L_ z=ph>f$5k(OAMIWK*#z{EGw31Pt`;Gna+N?288Ji;IlC?!>=4kPONMnD==vbktdfow zo$vY})U1*bZw>%L^sh4LA-h?rg)<2eIz!(Fp@*D757{DuS@A4D%_@N&GGcHo3O(cu zddTkVswF(~@Vxmx2tDKsddLP5dhu#Prz(LSGGed~LJv8E9hnztV z*&xC!VOBz?DuEs{Vu&7c20dh#?P`e;n)!Y$3O(cuddLP5W;@vhovH+S$cRDKLJv8E z9(2}$gcXRB}Ql^@_i6`$SL%Y zRfEor6;>ZsJE&PD&_hNH_Ce?&r_e)obyqDhLhGaNgU~}xp@(b`VHIW7hE7!iJ!HgS zAA}xq3O!`k4b&1Nv@`gQ13lyfddRL9DI)9!>^@MlN^ZJhv1rgi%_@N&vg>MUi4of2 z>hzGae_npJ+XF&5GI{pksZL)Ks*XwLj=8EjCZ|uHf*7KQoIwxSKRN6@!&%6|5TV@k z9E2Wn20dhp00-5JnGX%)1bWDbK@LI>IfEXuW0YFR!4RR`^c;j9at1wQ_db*&IIemz z^P%dPKo1!)$U*2KXV61-Z)vF|MkqHu2cd_YK@Zs=LT)qjq3W1G4;e8;4>^M#vU}T1 zEipp5>F>!v4>^M#vO$F0X68fHF@YX3VvvK-L(ZUw?B1GFON>x%dJaMlIfEXuL4@39 z=0nvnfgUnqa0LK8(2}$ZkETV+H8>>^|DN{8|)x$QksI ztD$8%2*eOQ;~NjF~%WFpog464>=DlF+%zy zVsKXkJ>(2}$OaK+Nzi=|gV_!}=DlF+%zyVz9zN4>^S%vO$E^ zC+I$i!72(p

_yd1#3dT2Xzah8}VXJ!FFjt7y=D5QBXXddMmCkgK63Mo72Aaj@e^ zA2f)t8zA#_EeZth$w*ftJL@blLb@FgqKBM857}{0c8ZRJvb%GcFS|P&hwcZVhwK=o z7IH8|C^tO^p@*D757{CD1~c^M#vOy57Ud(*i-2p)kLJv8E9&!;{VuY+kfe=09 z40^~0L9}`?^JRAj1n-MN4>^M#auHf$gseq@AP1p`oIwxSAc$5kX1?t1fFK8=*Lr$TGY!D%X znfbE21A-ic9&!pjvIl8T611g5#=JSe1PB zfgW-OJ!DgTVuU>3K@3(n=pkp&LpBJGt6pJs^(z_ZA!pD-HdQo6$a5;h;93-V$QksI z4T9sU7pt~*34dP{ddL~{kWDv;5ppLLF}N0m9&!dfWP{+i>V?dw9y0H80wH?H8T62C zSBnsGCl!c!ea9x(e|Tti!x~>Yggm3qIj%hIbA3>r%H`(ypqrIiVua4n-;;qJat1wQ ziwI`Lvmj6V5QBXXddL~{kloo;OL*krdGl8gddL~{kPRaA;?(2}$OaK+3A0k3_8|td9eT(a^pIV)t0hKg=KDSfJ!EJ!++q-6wv%1* zv=3L1tc4zO20diQTD8OoWw5Ud&_m9khinibYgr}aX&+*+`almkg&wl2K5B^(T8aEx z6ne-h^pFiAtUj!E^0W^zSVf_SoI(%TRZ+FX2(75T4?+()g&wj&gjJMPTb}kI2KylN zkW=U(yKbPC7@?iPcO2*;^ZB4bgx!GMN1pZ}2K%5q?Q>mCEipnnT%8_r20i4G87^<3 zI1b8tYi`%4OsmsF&Y*|v5NaU@>k#-Y@5~?*MGrZH9&!VOdJ(PsuhT=$#?Icfq($DX zbF-57;oPj`eK^Eu(|1{Nalh@bV(RK*sDf(dtD$%KLCYurfdoIfEW@8Cqh5yuAYicd5`r&Y*|vDua$iw0e<`@;)38tPIdY z&Y*|vc&?ThA#d*h!4)#}kW=U(8wAHyFY-~|hXaC@0eZ+O^pG9T)e^S%vg5g0VuZZC0}gTx2R-BzddLRBan*}_l=tDJGC&VG zg&uMdT4IE}y#oYS$nplAs|-38(dvcF*EhbUGRWIIWKo?ZM#$Scf{=Ia41#ER58bVh zHMXCXyh(0m6(i)`bDUk)MCc)>&_gyy&RMCKy&gQf&_hn4hiuMnjF30}yH0Jq2Qr zQP4w9p@(b`99O+UHv4`KJ>(R6$cE=JLcSzH3|0o{A!pD-HVBTZUSU=8)dzaW8T61% z^@$PkMGRuF!a)x?gC4R$a9s5YtE;b~&_m9khis~7jF2yT5QCK(ddL~{kPU+4su!!a zb_w4Npog4657~5s7$NVTBZlZ9XV6172#%{>$o#tA^M#vh8XSLf$<`jNMv{ zO@40ED!cgZy&OWmYIJ>2zK?Q!P`+aVBKV@p%}OntNr=!H`Xh%Pat1wQiwI`LvmjqS z$=QV-at1wQcXrhh9(j1){0bR*$QksI4I=d7)s*j}5QA9)J>(2}$SzCN5+gKYd?rE< zIfWjwL4;Yttd#Gg5QEtcJ>(R6$S&K}5+gM8eIJA#atb|Ug9x*o?2_-J5QD6R9&!pj z=_O62<>^pI2NAsa+k zeOT?}`zXXu zqq`HLEa5TV@k9E2Wn3O!_t00-5JnJ-^tBL;V=&_hn4hwK=o7IH8| zC^vl-g&uMWJ!FI6xa!5sm+yoTgKrK%4>^S%vSXB5VuW(ja}avSDfEyHBIGtRU%nGY z3~~^9$SL%Y9i!9|Bb1w-gU~}xp@(b`A-9?N@|`eZkb}@ePN9eFIH;Bwp-l4}gdTDV zJ!FFj8O+R=?}QP99E2Wn3O!`UD7C~0<)-H#^pI2NAsa-n=&d?t@^pI2NAzMT+E1m_>jY16eLFgf;&_i}-S1sX@hv&`rLFgf;&_gze(2G}7 z6rm8qtwq;AKZPE$%M!K32+bJZ2cd_YLJ!#>!YpA{iXs$ZFx#ProI(%TWxHBpgl4|) zgU~}xp@(b`VYZW9q6mc;WG(cNQ|KW()~Y2&D1&_;gdTDVJ!FFjS<5ORicpBbw^*Tv zoI($|3@tH2E0OPm&_hn3hwSQ=juloPRy$FILJamn=piT2Lv~eEEipnXs_%o)Lr$QF zY!G1;Wz`l%D8yhNgdTDNJ!IDn)Dk1KGx&}pN>i@mC?f0z>^`C!g&6FE&_kwflpy8C==pm=jLw1Z(3pp4fl$(A(2tDK!ddLRBan*~NFG_`o!L=y#kW=U(J4UG`MkqHu z2cd_YLJ!#>LT)qjMR5@^$U*2Kr_e)oj8aRCP;UA=EYL$vpoeS_A-9?Nq8y1BZZq>m0TVH}0)QTJ0zG8MLAAsPWt!(8^pF$iAv+E# zB4jW#Uz9u%gB*k&asoYM$0)VL2<4{dAoP$E=ph?K$Zcl6D3T%uIS4)E1bWDhgKCKp z$~4bG=pk2HFaE@FP!S=w$wARfMGSHfddO6Ja~xDlj8JZR1oV(=uNXAiAUH1HQ^o(9 z*nU&}Xkj;^ER_bN12iKy|L#{v%*__=NK{Pa45rbC{ddLa% zkPU+4s+Y|xu0^4TT!9|4$&wgBG&EWfgP90DkJfgZ9!a9s65=BtJ&5Tb{iKo8k=wFp5p I)LVi0f0HM^Gynhq literal 0 HcmV?d00001 diff --git a/GEMstack/knowledge/vehicle/model/meshes/e4/i_logo_link.STL b/GEMstack/knowledge/vehicle/model/meshes/e4/i_logo_link.STL new file mode 100755 index 0000000000000000000000000000000000000000..e0769efe778ebe005cc7db9fdfbac6e5a0e5b7d9 GIT binary patch literal 2284 zcmb`Iy-fr$5QQ%$rT`>#8KMG~lSmL<5I_|qTLXpA!Ep^7F)^LsZ|vuNws$209N_VI zKELOmTXwtuZ8x#pe4=}Lf7yRL{v0p9ukYS2Z|@agTkCj&Mqt2KHL})Zb{GY-vJ1ciS#3O+^1ShJvob;qT zJuUx6P-oN=rXBOEM0|aiDR&-~#N=qLM(>1Epo%;_EfYTD4!2!7;Z>IJT=`5#MCG`T U4I*w3@2mF_J7dN);*~7KFMt%h=Kufz literal 0 HcmV?d00001 diff --git a/GEMstack/knowledge/vehicle/model/meshes/e4/imu_link.STL b/GEMstack/knowledge/vehicle/model/meshes/e4/imu_link.STL new file mode 100644 index 0000000000000000000000000000000000000000..97d552e728c8f86e0d5877e4bfc037724f3da5fe GIT binary patch literal 684 zcmb`EF$w}P5JjgJ!7D6?>;-It9>8O0v7m^^YGJdL?RMTka*D8Et+m&2ell5SV@d;o z&xDu%KXcq~t94QB>f%3VOhl*K#S%3gOKKmrc|BKd^qv~lPH8`%Uk|f9ftQ5vG|%t& zxmm!6Zz&!|JhUIQ2_88@JW|310)K;&9&pzlQTusFl_T(yN%&3Gf#Pd3ZM6qdh2}qm zc<6+~RCcpGPtYYvq6rgs6ZVl1PHk|I3Ug1COtkFLNe?vao3rk>8G4{~LimO;p%6Y5 GG|>lKeHQ2d literal 0 HcmV?d00001 diff --git a/GEMstack/knowledge/vehicle/model/meshes/e4/lightbar_link.STL b/GEMstack/knowledge/vehicle/model/meshes/e4/lightbar_link.STL new file mode 100755 index 0000000000000000000000000000000000000000..04a9d2f1e75af3bc334538f464eebf912731626b GIT binary patch literal 13484 zcmb_iYm8Ra6+P96j;SwvVM382pp8@p0z#Pi&gCKC`%!#HQd_Oos({v3Z7UGV55QK9 zRYY5&jm%)IibGH_^Ub{qt+9%lRz<3|Hnm1=t2Hgq7nQEH?>?7xnUBODoy26z-fOS( z*k|8+*8M{G|NedUGa>wD{qnxKCoRb4Y*^Csm$N43x2^wH=f1BW)tT%Np6+_T*^z(Y zp1Jn#AuN9DlKl5~-k1&VI(?0L6tUO#m>+P}?9LDtc7<^8k-hmPC(i*#+gL?tRI0J z$lt}`T`!GMk0R!uGBcl4T-brV?G9n+1J@Nl*}N=bRPBn;sAQKM-NSAw-dI0~9PR2! zHuE0x=*%2z)?FfC6=P?Q8oBPuRW*+y-0m$$Pq z#Hd(Te$F|nF`7%Gl3k8!)TqDWlq|G)s3+OX3p=7?_^5V4RGwA{pz()MHPC%*RGKT< zjKOFly3fv;M|7Vw^U9+LtXo9);mq-e)s5&rwz`^2qmo_D96K1%eXL5%<8q!St7iyfUu_;>&iTe@EXIY7GkYfyXZa{&N=&4 zh0v&EmmGdRfM^@5o@6txpBo<)x)0A_dIR7YG>;I)%!{ayC5o0D@6JHcnZ%yc4_iFaN5-Pt5*-|<@?V?w@tNrrA;(PL^}jU zT(makmktU|dcL%wGrxGn!De$*tr6Khlj1eKMm1YlqFLMA*OA5uU3b;@Vl0yal2)N0rO-T9mIy3xw8>@3U3@ryG?b ze5DOtUtP_mQF_wq2w%}oIZR|5k5ll@qM=% zZ9hciQ3UvS69$@hgI(rPAv6l3;w=>j-cl9eW7nCR?en0GXQm?5<7=gePOk0l5xPG9 z9^~(d%AuYX2!DrDgwGc23%TdjDgZ6_b49491p;&0b*&WPwnbsIa@$r8^|U~6=Geho z&RE+ zMQC>ofqTI{A%`L~>h_H%!BLp_Sn=X_ba(-vND9E#8=uj$Tmt$02b z-Q5+&%3g9tdzW!2LZiILI0yR`_T4zt zqX_Sh{zm3K(Kr;LQQm`{+0rLi<<< z$2`6?AJ93$I255#uda^ys>QSX`Ekhn`|^?7_csppC_?)f6tibH=cC3SWgLpos6jVO z$v?Plf^+-M^<4}Y~{ptB>`NppfbdG87>{YyT zZ8PU{P(6y!J{H1;>yIh&eV)sEupf%hsBbTwo*<LNA}YAUd}yNghrim|BU?df1l|bn{WPnvGj^feVm7S6rp`Agu{=UR?Hc;xQ`r) z(5UZxGQ;j4voTI6Qaz+Jc`iH z7Xs@R^&7b#noFa64V{B^d+7Z8j6*$&&^{Kz7g4vUU*k}OMtLoCmh)iUZW#JzWbLX) z5!%N>VBK!rzF#JFWw|uUYuY(jx2WHYYo#7VXderq4|R+BH4a5+l%GxK_%-Sl^_y`X z>QRLDu@KHh-J*Uo?zti~%6p7+EJ59(er+D=QAE8b&O_azevLyB8bzB=n{q$i+BPu% z=XEz0kN%^*_J*w84jLf8C^q@#9K!0iZ^^HF{cHA4tsX^a9}8jmgHPmd54f`U88{T7 zQRz-qa(uYzqdZ%5rg5l85!%N>n1Akm#rl`eEFK1jA~XsLYrgX|E&aQ}Wv6|)7%;gf=N(5qiqJk5LT}H!V%xN3`6J*^ghu)O$~o3vb#<}sje$Am zp&mtO9}D5-i@#eOxM)QmITWE$`fV}<-qU_?#^MI&p&mtO9}9tX``c{;BRLeIQR$vo z?g#4@^&82d9z|#$3xRce&x21Ghaxn}*U-K|guuE*{ThdQ6rr6j1lBF;HF8@sz# zj2&LQc)2MPm4_TDiZ=2$@&D-5FHgCr8_@+&d_%4wQWXC^*&+P+(o4EAq5>o1)1dNb zUfNXj%9-DE;plGMR)84Y50RpnDcK>Mwd!83mE8@Pi+Q+`j8dC(DA(%G4=v_eMPI8L zB1JJ%vP1Z=eH_;+^R=ox)NzD<<@11k)xi6xy)$SO?KE?| zKSbzPzPjM-jgN&cV7(nx*E_D6a+QfPNK47iC?UM-g7fO?DvDuVT_(HJ3(tO*hN6V%>_q z%kyC#MfiDi4nKoAYgcn=l%I3w;5pyAQ>W&sHIE{^uQ&&LNz%eKmqvMyaSrw?(c9Ut z%%ceJkIn)8iapWhp}925d!=(gziL1Su)7*P>B*wquHM_BUq$Eu={{I>eMQuJBJcmu z0n&Z2LTD7;wIcK@e||u}ibrqXKiz99k0P{>nSK?a1EhOxh0rLxGe+oF&H?=@LI*Gn zKs}1kK4$t=1|1;X&#PP-g?HZw{mMCb|NrB)P17>eqX_L|re9^nKF^t!p$Lt_JA8zG z<$4M4|In{&9_mp)7epThtDBMLN^egA!{eSTln@n3$k0P{>nSPZ)2QY0( z5gLU%6?$dpF5i9lzQFHZu3uFiMQ9&0{VJpW>iSiM&?x8bEjd`X)L&h{;tb8B2<>C0 zUuD!^$)UM4%2(YvpkHOsuZ%-IiqJl0`c?KG^jB(2iqI&pg=RSq)-Cia(_Yo12<>C0 zUuD!^IS)l>l%E3UfPNLJzq)?KYB!G}w2zs76{){+9-2#|{G2-n^s7ky)%7c$TJtDE z`>KB3`K)=eMUm1sb6rp|0^s5Z|m1zKq&?u-0{N1b1gZF>v0Hy(`M-kfj zOux#Y14Q1>6`@g3MXFzHhQRy(-jjQhUQ&4!p?%Ess|@;;X)>BiqoCFBm$I(O@cs`S zAi924c@$CaiM;z4Yf>sK6=c@&|2%=D{_`YZQCb7_>Xp>wcqKZ5?swNj5Fw2zs7l~I4ChO7vU z@>+1!0Qyx1{VM6A_DgH7l_Io{nSPZ)zcTGrb7_>K^;hn>dK963%=D`W{idKwd??YKstjP(ZLq;GH)7Uy_?dtj%M`fBT^uq`pue_qt z*p;5wq#iY?M-x7%-IzCtw)nn6>c#|XKwAxFkKnt>i;du#M~zglsK>k>1h?r zIj7^wqB@cFL)y}K(c9zCntat=j~x8%Ig>~4eo%HC&Xs7?J2XP53_|*+^782$GlDft zbngcfY~|lW$os(>CNQQa<{ z2w}0(OjteUNj+vhx?>O&_7I7^?W;a&WAcdsm#yYZcvSF#o_i$zy*mL76X?0osCktS z5Ny>mDvdoSgf9BDTjqJ@gNbOx8PVOjBlXZTHM~Vq}hE>=FL zyAy1+>*N+CUYgUgbvH(J!&0m5A5N_wT`=3^{eM|I`ocPsw>`Z!~cm4C;IQB6R@ME6{ATWlpOk@f>CQR;&=OmrVtGBVm2 zqZmsv##F`_6I$hRu2{o_j5j69BasQVk}N1ut{~2ah^jb$s*E`=vrFajtYr<(rJzCh zii+8s=86fnlKI%h2Wyz{{>jXnmHJ?Ut)w36qdd=9!vya>sgG~nX>Fluo4;o=s(Ese z$>n;mh6x#O8dbUGOt6*A6(!0QWDOH8m*+_QMTPyGd+r2w`kY97#IvYa>3d1huD+MJY(#%eeUu1!xrr|< zPFPgaggE^39W9AW-vBr#9#sfWCK0BDM+F~37jGm(1O6TUstIVAz(}-y1Ua{JRNNL@ zd4!cdv{KM8A#yPimr6Y{A526m&PaL+M^wlnd~k$_%D#I0{(yX^1R zWgo7|2}D(X*>)dzC3nIjT=>pOjq0delN0DuBw{_pN~>1%R;yO{(C^&|Xh3`HkllAW z65XoEPy98*zsH^@QE|JJ>G-=ywGWS-GEGtOZh(`Fj|QBaT;>x_y5q2h3CPHiDDLwGQnqw5+R;-K7)v|_-MGlGT|B~ zAp7_9l;M@~3c?DR##syU`mu%bD;eLsn80cWEBwwS-_-|NDiKk`1lD$^Q-U=vBP!et ztE0kM9hw(fi^g!$hrF@5DE?Mtzr=ArI1(ms%c%Cj1Y7xc8}00abHy2TqIXnG;N z$3b@Uy$@pv-|@S;jVs>OSR=VgX!tlk;Z}&YtBK*6!ufI}5ygo8qM!Qbf-x}b=hf^{L)>IJ|6;}{%88kAq=NOez&31LoStC9o z!KaUOlt@%<>PM9E-N$j6a1DGgJu$AhAKVs4g*Tb5^CN1Q;EYVv1HU_aBt@NLRNgtG{%^%uaqbM6U2=$tOU~Rr9ecF0Bur*@rWg#*4EvWG684A=}HHL?guZxx;6! zN(i=sjGo)MMCM2Ri{Ck3f8fEj$^8Snb5TM3#-aqy!I)9kG&Wpvtp3y!U+b_YCqUcV z>(RIDZ`?KSNPX3{%M${$TX9B07+?Kd<5Pb>TtB(@jwDw(0UGbVTJz?O+eYfsZ@w`h z(5_o?-n1SauSfodjQk+e{5ou7*XzL=K2u|UOk@|M!|TBWTlws=3SzzTdf-fj*kwi~ zw>y4~)_SzP9<1RL8K3P!kb1Pe9!#(mXGH7K_Ij`;C(v^{w_^@^J(z&(R-CuA9yr}o z)g%K}52>Jj$6QJ4!5YX;$Y@vDMmyJo3ATa^-{pG92v-g20U17ULY7gf-)*$Z{D}2n zO-_Ke8O8Nr0%jzMx8l4>J;tXrZo2=u`gNaO(~+?hdkfh|CI21? zVpHSP%SY?|zquzN*ebn$Oy2uuW96K&`tP^i)?p13{EKM_gKzdVKlXti*7qE}IU(4J z?`xry!Zq~b6IFYf23BDoO{_*OmdTZw!%MyaEx<@7Z zc8mlvMmwUCeO~2wW@udY{#pws8Yb8ZGWui$=ZZB<$azJ5#IsMV2NP@s89w6qD%PAe zOvt%Qec+^~XSg`7m|!c&@L@#$O9M1`_rb}6{(f5tdyUG7sL2VZC+-H9Uq7gK1J^iF U+!OSkXg>UIP!Lg5Mc8fPe~5gy=>Px# literal 0 HcmV?d00001 diff --git a/GEMstack/knowledge/vehicle/model/meshes/e4/stoplight_rl_link.STL b/GEMstack/knowledge/vehicle/model/meshes/e4/stoplight_rl_link.STL new file mode 100755 index 0000000000000000000000000000000000000000..9e30a0a210b42cbeb0dec03551717ce2229901ce GIT binary patch literal 45484 zcmb__3;0&U_WxUv3Z)ym)9p>kQKFOYyZ0{TQX&zR2qEbrMM^36dv4{LOPy|SVznn# zmn#U$cxz;{(%lD+2l}}?XSDsKUBjfx;Zw^H!sXU#Xoqw1g>GLYeTSVHkRRC`Ii>Glk75bgldOSh!zBY@7;7!Y4Dce zL~JVLpX{ycdUjQd*UznQ!+d3n$A3Ssw^ASmOB$@i9qtQ`Rv3u@KP zuf1bt(x>HwGK6puA^n!iZSOxRzwY5*lJkl~otE3JC8GImyTpSB90M8OuedfpxLK`q z%Z&pSBBR*-GpFs?dG+JFCiMcM@24~J?@wu%zP_ek8A7-yqx)I)<7KUg=&)>7{^c>v z($*V$D?~=g$|d6QZO!7rJqth_)@nh1agBEAp)GqTL`KOFY*WjyQ+z?#9*EIucCtVLKqY@0{j0 z3_UEZGOMjZWRwh%%dKp?xJRG(#(Q@K;_=6y&-d%lJ3Zlq<{l#BqKrfLJv`pFsvZz? zKYA~}?(tJojBeNWXmuQ(~~@YJpfA<}IG ze}A&Icl^Y;tkn|({+6Hd^>Jy%*Y(Q~!sXU#>9}w6kNtH*`orh9grv0pc2xYuW7nx# zO&vQbK4{x?RjZk`N5}7{*Wvg1M}3_SFB+fDI(mM{`U-_;L8y`*JR=^u+xeOs(L}WevWA2Ci_@gGJ)2_YPX}RB~wEFn?KaaPEj1AxZn7{dmDd~f6_EdXsR;yRej%Odeq(m-b ziQuwjytL_ue6Is9POqImQX%Ye1wr(!m!BUGKZUh=2|B+RIv@2`&oYE?xwWc4V^jW! z+ef71zI|IEjK!&18QWF0lG^5Sw|?|le%8-p(uqq-W$h3IWsDnjcKm4dB|xWrzsk3| zXk6NU&xgto!sYftTX=>XJVVWI>ca!gY5Vo5VO;&ZCQ3KPN5$+bsV%Hz-P(LKb5L6K z(i%Wy6qYLp{>~7u-t|Gg-KE3Qt7d;))^gz@LfVwe^?|4E4o|(|r2|#1>TPQocl)8M zs+IA5=zNznf5sVyrFHLWTh5>h-%McmYoVL;mdl;AZdyJmR!Qr}r#LOA4(v9Wl@nxySdlfs zifq8JGZiAEWC)^HFIrh@y!S95M!$D#zVYNW$-trKmLY_Twfgsfm8I{VJOhaBpBC~> zyRA&N96m-NGD=o15oWCg#KHHs%D*^eVKRTu@d}YqG6dJY&-55oI^%)!fT;Us&HU<$ z>B&D2zQ{vlT$ItU#i-Kg%ZWG*E95J%LOvpyq!1a!MVK`l5IeV8-nQ$oLNe|zQxqbj zWC+%(ZI=gDO#kshAo|~POWW$r>m{e3F|`aKT&$H@x9eIhM6E)rRt46VT##45x*c3f zUO~5f@6FFGY&PVm@Yvm_z)CWTjW9AQur~nuI7e?26)=r5O+Au_JYoeU7q9586X z!0qb`LqF9Bv&T^_7X)SGa-F#M0pjkx2eoDC0-WDy7t(I3JP%FhnM5e*|Z`LfXshA#$CBm+h27TSYrVH4ypdGOG;tNw2 zhL*J(N~TS$aXAJHdJJMj6)~bh8BtkT85e7Xkyg-SaMXLp78^}o6UwN~C@uoyzkppB zY87=j2Qt10Eze*m8G^NfUkS7q9k^~<5#A>f?~|34aj{nL#{vDZ^3+9m>d5lchTA+L z>~Vm=tX9OV7U@~7JLlR!=34mL0DBH_*)rg%i}2Ku_S6}LimH{=R?VD6%$$*)Io);$f-*3R z270c=>|Dg`9Mw~^vx^WeyG^-VgBhEON8Uan(yOH$*KmQX;jm5!u!F#QC#!8PhgC)q ztBgpmGBOIw6$F1v`_xLNh?PvFS28X_xQLK8sg-3BE6Yf)EOT6?23)0*3+u!HyCPL9 zsjXU(6|o|V^oq=FhaiZ?>MYP}IIQ}LSoKAE)#oCFiwJ2`E{9ck5v%aXT7?H(pOXu# z{y?vmb6n}Gzvpr-r|&4{zMU4;ul+Q1n^9~8e`8G@V2^_~o!DV}vDyt&qx+ZFA!ii3T>i#tIWTMLO+OT|3Xk+E+(if%5z=pJ$5OquYlWy`pyP?hd^)4JVM@d3ZzcknQCx(XwILf(&LX0mkrn0SOs{H{ z)ucNk!UY`>{<;68;(HJO5=taBD=Xt-tq@x-Ft(h_A?jR2)H$@G&W7S5%z6cgnj4QT zzH#ZAaQ9QsjaXJj$q?*mM2ZWHs^@YaHa)a>;puT0y*s81AzUoUtki&b`m?VVB0?YP z2)&Bq7bK2vR{G$wWh|^!xA^uQGeaG9&L}Kb5d4h@bV0|dPrt8K@$1P8Lmk<65yIux zs&Uo(+FYG9kDq=0Qq>MQQ6QIDQ=?Xu>vsGGVgV2V5jMp}@VD7n0D;qtg*eR!{L>7V zE9;S5?%6wMEZo$tVQ8H+RQ8pWOEgX$3i@mUrx^=znh{#38I=g(B0~BNJ}q}ybkUtZ z=lQGFx_O1-7lqQyBag)XV_xB(U6K`jM;@(y=W++N!`@_3IYKDqh|cZ)_FCWgw-LFV z<}&CC$}2~7YVc8MPLmF*CRNrhEA6=xqb>8GoByR&Hsaj9rkA#k@BUw8NLegbxcFOo zq`X!`j%Xb}aQ6>bU(G8F_^Cns)(yM;fm+#!JLXr5U-`J{@6<}TC{KE%yjEf7Uh#jv z8>wowZMQ-cuq-tfXPyLqml_P}0a&3gMyk3-F?H>wu~yO}<+Xyn2JoWF!lCB?Ui1&t%0|Fq0(jBi zsg-cCR?;KowSvzG;6+ufFeUq^MgFqZ)F{i2X6sdW6^)dc;9w@eGHir>zv#CRaucQLlF@E()=cU2ZExSbbUE4(=?2}44=Op5aq*HLtV|gHYw_Y0DGh(FCaA?S7L z4?s{Kk8f%pH8>_vaZ!o4Q-;LFiKtn>S+Jl}MWFT3@4h{v#&wTZ2#JMTy&Di=dKU=l zqyD1J;hKXhZ%3;*H4zelCcSL#F zCnPH`yI3LYd)h##d*KFA(g^Bf-M@B9$K5+vA?!Qbuo87!*|Z~ul|TmdF?;);(|_Ie zCxwvvyKD!nMBUjX0#*{kN`Rm~+V>xvj+(f$LfCg*jkhZh0e!?;A0_DH!(kVvFPwRz z=)CgYtGQvQ5Fal*KVGw9KWLESW9p&P(syS6C16eDW~S1Ixs6E~u&Y?x74^~Rk!k6N z%LZT%pe#|{z?9!SueA`^c~Kud&b=rdckz|V+U*;LuteU*EfE20kF~W^AAKJV(rc%* zPg$;gqs{b{@(iZ0Vm&^N`272%_m0yP!oJ-GE8!h_g@Bcm^f>>=E|*5{&G^1F@0enI z;ckB^tQ$D9)aBehYF~r>hl&E5{fCMt=W;}xQkY+QG5D+E!oH?57A^>u)cWxwN+;dj zAGK=H?2@SG=SRn1AK5;!DJ<7Ui0oYMi~G-y9_af-JZJ492VvLntPOV;c3$1D)be27 zNMWt+Jh@G2zjq#0wKDM?r-nq2+5M#z?|*xusnthc{#ZI}w?8QvLSe0>O?GW{t)3oq zbUfz!haH5?#abPB=$k8^UUeE|tgbyG+H~@q_~`L#6Pw~AvUb#YyMOfhYmdZB|Gh_Q zBkb1BdH2RbvnKDYc=CV|rscDy@5m3TwN$m1J7JzEupQD1l*coKWy1%WmZzt*Da{z) zNwq^LK0ADPgxw2lIsbn0v*$v_o1J?__k7tszB|`CwJAO#>#HYAt)my~eq0*)R!;|E z_bArYN=E7M^G)xE1;zDvFPgKFsCVyB+?~J-9Njdsh&))=V!{XuD$Xo>cwg z!X8KK-bF7eijTAspo@MQC>qQMG)(Sda&_A^) zK7ul|J{qL&hE*od2xfOV$3fUyqZiFqOQXX_!ox0|5&!VcSV63ybi=iRYbySxj9#bm zej*Vs?DOa3*1bljq+o{ReCHr2?~?hamR7tA#6Cz)DB zuP;fiUVD;~Arv3cYRLRj_!38L9q428bq^=4YDW%&Va#YgnqJi9dHA$n@s)u?x`Nj~_cp@U$#!bKaaa>y&CzWsZ%RHW33_|e{s~XKJ6(2hR2zs9lxdW41E`DBlA3?BO;o?}SHfU98z*L@da{f5$#t0DEC zOJ3Xe?+$|H3K#qBw!`*}7uP!o29`yS>imXNo22t@9H?|I6d!Tyx2MI|?|BUn9Otj!dr109+nXH(%M~v6bj9pb z;%iP!fS_;h+Tnu_Jq!#2?nLb$BPbvXyKyH_d4VB_@tSu zfS{*7dh(fRa>{*)P4N-gn%dHNK&=^_V>dakASb+*&I?-S6W29QzPNFAU{id=zi&7+ zUN(Fk5Y&0=vmZ!Wd|E%W5&SJ&md=5o&YM+VnM_-JL}*idMC(R9<0VIa1O#>d(LFn* zO{Y(G5JU@?rE?&t^Zu*rrXA|s9oiHhv0+@F_~d6l1A;nlU9D3(w9z65L9}pLnq{q^ z^FGVErJqlDCbTI&;@=I9i%W-Z0fOWF;$i*My3<~C5JU@?rCA`T^QX5BNMCtiV`x)+ zM7AHae7n-Q@$Kq2&Wdio#(|1Wu9+dmxy z%M~v6wDHG4Q0Fa9U6~v*Z0E?P_=t-x%*AIN+Y<=-_P4*>lAL=}V+TRBaIvS22M1yg z=={uuKP1l<+DA6UN91el6wghL0)jeUGpKg@NRzG(f@tBQW{n32f;u1AYPWRJr9C5? z;v*0*F>wa!-0W+Wp3Oc}{WiNhrE|0AgbZt!sx&AR>fA<{eJv2w`LVOt$Af-c;2@|$ z;bKpl6$cR1`Cl7;9Us2#4W&V$_z1Hf1cExBoE)5lV|R`0viMuL*wbd^1O#>d@~#IZ zLki8628H4y%*ql7j`I%&k4qjo?@$N9a)paMZB~G+6?8s#)3D^b*Ly1s3dKj5bubXr z`IN(NPAXQO;viVAa8a{nB?|=S^KJ7lPcEN#j?%eMe1ut@13{gey_(XqIjF(x6a`&MOhnW&yDbAgFW100P7S9E8!J;$lym{S^?@Ibr|-VgO3# zLh%vMW&yDbAgFW100P7Sl+FcVG^n`P(`J7K1a)56XIn62+P+GILh%vMW&yhiAgJ@T zRlW``S<=Hn7!4{e_Vg;fR|A6cId&`|b}UMRLh%vMW&yh*AgFWfibCv)9E8!J;-b#Y zUJVGd^9r%^QaTrkkH}({)cFN(+#FPyH$drGZiSfHS=|<4Pj`QD|KPhhImn>S7hm2W zJaq80$^!_+M_{H7viZDgcuUyy?4y*<1;KKKi#`47<6VN**H(uN>iqqhPlop%cCOO7 zP<#Yt>L8oXhwk-l_+yQtgJ8MB#hy+suL!o^#rFWH^X4mSML%5gsG6OH;v+Cq2ibgn z>(Tp0<8J)GL9krmVowiyx_eM}N*&1HIRAT{PSJVif2d|>q4)^Q)Im0%cdH*ocTK3K zbS?;%D_qq1+^W5T`@XCT8Pxd?#~mHby)LJ8E)*Y;#oMX#&rWm?zY>JP-E-cV{wWpx-m9wKLc(0X%AX>OA%|Zspd6kw&NBgwsr*>Y(8cIF_ zyRbm-)u{8~$*^cvgPsn8}lh{A%i-v@%XmzABU_{8Wf6;K(r;$F&U2Y znd|qC_CI8+gJ8MB#hy0)7&55y%X>GEdYoS~wJAOV(Uw5RWVk>U2m`H%=)-2p3DrqRxN9Ip>T;8%pE8nWhjzvCHM}EPLJD14!f^0M7pT z&K1T=_Lc!0`EN`_E;g!G}-VBxSC$=hwub`UIAxTsBu4(r+A z@=GQr(KV+jD-nv1kQlkP#Hu?@OAdeWNC&}kg^N}x(P2HS&2DvEQsaw4YEyhf7Cq;P zx})n6NsYfXbr3`g7e|*whqaYF^WN&@zHz$c5^rZ;*=MQJhq+wO05>4!yqrANW2Dnp zHiEyiH!i;1duhiZibz5>k(_^Q{g_gF^8Uasr{f=)uq61i8)b4ua(h7jDv*^nvIlf6qhb^x+XRn7 zsToHoJ|a7t;Oh0}^szYjrjdhSxx&R6&P1jlgEQyuZ?uT}HlD3!PNDb++$y$C^+zr4 z8Ru8t?jTsMoQ1gUV69Ay%&C=+kaH2;@^OogO73iPi-Taf!sY6NbM2fCS0)qJFLrv@ zN65K|)?ka#4<_f0`o=-9T;X!dd&PB8rt$SDX6bG;lg5?UAJI*=R{<#IcAUmDDPv`zZc#vWw|;UXfd z)kO`K20w*;((_MgqS}F6ZNB8Eyr|r=VVkfQjj>BbJ8mm<4)B~_ezHo|yNco?{wK-e1thS!aj;EM>HxyG|Fi?Yb9K+KIlaejY<%W za(dTCm~$h@pav0*N)U~55G+@?T)UzdMKmf!G|I6OA7RdoAcK~OXjF=5l!IWo!sU(+ z6OBp{jZ%9~86Q5voEt#~M--w_DWXwj<3qUIac-hfDWXx%sAWxTggIS;jH}?`TEEpV z9lfNsgJ8MBMK2*fMtjjeJvK1?u3int`}m0LE;r}%DhJMr2i5AV>`H8jRwAd?wl=k0 znNv$;S7I4HLe8VLT{Zjkp5&_++bFvd1j`jJTbp{+?iln;GJRyAtVArsN5~1bwyQQ{ zs-z1(zurNxT;Z~{sl8A0It|hm&2LdwB9`GJ z)%u@@rW-qc;UHM9aM7+ZE8*T|>5!oA!oSo0P>Advyf6rAitC^mw><)uozREW8D^x{$J`CFbTLkJfUS*vm6HsnSr5 zL815vxjCZ8dAIM^B*lTT#4J@=ELXTV<`E;05pRbK&QZz6MM<*o|0I&CC_VyFRdY{< zy9q>V6DwM)5G+@?=(`a2HSZeGC*FR`Lvg+CuSrB$QGA5l%h9tl&JALm8#oA-i&Fr; zys*M;hdDP$aBd*cWmPL5ffIok=LRcu%W-ay;M~AzIm;C;S09|6ac+>{+`#EwAAu8r z80Q9%K@H;EAjP?XgJ8MB<=PczXPg_PI5&uGijTmFK#X$($l&aZbAuG;1`dK~;c~}^ zIX6ggZlLZV%E<8%I1z|(ZU7ndqBu85ac88S>(N@``LsP~&$F1eVY zVxcSWo+V;39qV3_Ubn|kb?4udi!Am3ihvBZe9@)nrw1oDsN4lXSmmy;dI2)%ud07^ zPWr*}St`bEdQ|dbn8#ovAcO0xBk$>-ZkaZ$V3%e6USVkyGU%^XZSI+#_V5krtiV`C z#jhYBgO<4KnAT~hz4s~DWm&&hSXK!cwD#h?_0p409agd_zk+}aj;J;Vyqny!WI=_E zuzss?ZpI^I&|j@6ElK88+eeLaq5KL0GIUI)Q&My4qx)JTwZi%>?+>UKU9|V9h#!lO zpS!@J{0agxzCd*FhR>&@i@s{E@>nEyMcJ!)RoogMg?9Wmig@W;8q2c@Q#aS0A=qlC)^DwLm=!#Yc#} zX}kL9#sfLyI0(y1)LRy29)t|egT}5LijOce9NJ-W;!??pGb_CUtwg>NK>eF_5M=P& zV9Ze$rdLidxpk3iaF~x~uXj6PdW{I>boLZ(h zwR8|f3m3I%)Cm$}qDX=L%LhMc3m04do2%?3Hs~WRf zf(+V~SuMdbGK!CIEzzvV90bvF&(^N3u9dk@?bOOgnEj_|`8%I3NRB`3eFwpEh0E0k zd-t0juOu(Vdxti~N0|Mm(cq`sYo%WtQQ;tn7B1U*wD-BJ*eLzK!6O|j@eyYK2^sWo zi)VC8pISb}L9krmvPXgTqL-vS)AOp|=~%muF#Au);E0+ueMnmE+B+Ns%M~tnoHP2d z8}>NQFM8M+wLZe^`XIyFK{^PQD_ryv;$!ss>csEIr2oErnVQvv;v>v{5HhTtu##c+ z&dOie8K5E$wi_)CE_>vx^n+(VQV5~2CW7E^f|A-M+{VPeP*f@l+Ic4X^X;noWy+YZG?m?*btIc~iqxb@<+ zoV5}zS08GQ+A=S}trw?veT0eD8x7*tOM+W34ua(hmupwF65M)8aO=gf5+7ks9Uz02 zh+8iyZoN1NmMdKD_@K4p)=P?8FOg005$5y+GR&=)6t`X+1ku7}k7ga~!>yMTw_co4 z>m$r55M0EL!XeIU= z5Mn+0o=l^Od#5*!?dw>Hjo|O>i*wuw?>KdzwAA;AGK6puAvRt4UPdDCWtbZ~%G%|X z3fh>t&jM>_OlEQIACnq2PEj(1!g6hdv`>%oj{o{J*=PLm4ua(h7j4YkXMqe_`?l^| zlI~|8p=?(uK0>l!^z2-3(yPhMy>+gPAXu(&(Z>bK>h2kS5D@j{>ucap>b+0Tr2$m~c zv@vs^1u{50Z#}zfGW)IDmF)_}M@V*+wsvz*#zC-L;i9#hTQ88o+1cEBQPwULA0atk z8ewkMI0%+2IYw?fxMpbZ`t-QbA+4NR`3T83(k<^htA5gZ;sXwXTYnbeM&lm^6a)pb!S=DwU-%fxGdeN0lx+FcWI#cOfC_X~+%Cr}4u%KEpW|w{r zg5?SqZ47x+d{qT9=tcK$(1!7j4v4Uwi@SB7Rwbbj(Oy<@s%6Mpcj3t?oILE z4_T~yiBNomLb50|!o1ewAXu(>RYmP& zq_(VsYsud0;rs*2OQK7u#1@ydsuJT>6$im`h07i19JRwQX&mn|Nc$2Q=RSgHys82j^l)3c-5*ameoEOm z7cP1U@iE$qKDf0-{KML5j`v|rY()0$30h)}zpJ;9lwFA}8GBVPjN96*v@5>WqpUoaSwtcf7ZoM^sEV&>YAbFE(!%$$nLj1N;Q-jlho z=|dssb5byG^V@)Gc9z%vSQ1tSdI6JqP*EoFOqTSUP z6pD|?^0qmDocUueY%%0@HO>XWa)pay9&7jl-q?c-&dziCJ`v!ZJLOA+;v=&BbM7Ya zmR^9j^c)1s6)yTN>_yDC2h8kTz*i#qq{uN}<67l|3c*{KpI|!C5T<-Xw zwd0Mg5N~Wb*6t&)(=Xs1FUVj7vis{x!mHMvkku>@Rt$iItZ34T(*zVv-7|Y)`V9aGQ#mbJ_36mej5}r%xj^MycUY+kouk% z%at#35slah-;@Qy#AL#nCMF{kA0ai={tCHEA##^gI|O0ZioJl?NuXaNF}X`2a+g%^ z3dKiAPwU+Ta+gBnE;$Ihcd1RpP6GX^3atdWOCfTXl$8j@M~KDf-2`%%LgX$v2-`|% zm57}bve#jdyA&dKNm;v4e1urOUY8(uDMap)8c~9&bd2E=3n6Zo36Q&_ypK?Pgm@x&Q5_wO7#*Z#APT6yUdP|^ zvM#lW2&8#`m-l44ytij`$&TL2N`&Gg#Co({A-g6*c8!Cu?UmX@{5rs!XRuw)gUH~C zkiny@L?}K&>`mL%{rHCBimGiLgl(_XCZf>+-fn{o+7&X9!c(7ap{ztGK0@qG+ZD2% zLS#ER2-{w%O~kJQyg>&UY91W@V2F$=WhFxK5n?^su8_4AB5TV**!D_oB7PmrtJ#ZXMy!XlPb%$SK1Zg*XCik1}Q<2)l`3GOLMmx-jNhBvGLh%t|Z~DXpuhvC)wNBZUAZ&Z3 zHgW#JENsZ2UEyWC2ruI)D-nv15PQ>hh1d5YyuRlkY$@v_3m9QI&D&2 zWhFxK5n^xJuJDRrh*t#FiHRU=d!;sU{=uwx$e>-}rNR&|6)GzcijNR`({_c|5JS9% z=pbx+r8aT?!R&s>pj|yWeMI=-wO1&+5{i!yd((D>6O#b1Iywm3UTIh6H37(=UE$@( z053->yAq0z5PQ=IoUsJRD{>Gl*Sv9{?tV#ab*;?125RLc6d!@}X!FVqTRw9B72)-L zN0hZgxLkd3eRX}WVu&0pr+3*78)05TFd9UjSBN|>2f=cM%e5=6uaHX?BA3ju5+8vZ z1?H6-Mn90R7Cj$UaV(ML3YR-RxV}P8T!frB$J%`aZbq0_ZaAWlcNZb=&OxwT;c~}0 z*H_5xi;&yrj9MQdZ`qjW$KQkK`*m#`1j`jJdI|9{dVN(IdqlLn(>`ie6N-<>zB9`; z+&d?n7|lAax{`q#BI<>DmWx|2*h6nsw=_i_zOjybGJ7>15OuzHcZCp&jo@$j&TKAc zZoNdj_2Sn=xQNJVWp36)yjeqv`R28{y(4eyvn1Tn3Gk{T_UXJQ^GnNN(erCQkh?gF zLbQ#L_UYLf*)dYZr=-zzrDlLKDXavYjGiJ2?oJD_k5axP=zr zwNS{Q7ez)@gp4XR28H4ya0AA?G{td_tgR4PTMmNd3Kz#bZqo&L^%OGbOOP2Be*Iz_ z&;A67Rwbb`YzlGRNsu#J`ovi0W#c_PZWxez&#oBojCek zyxtn%^;QSLa?Sfb%8N>EwHL*0!w|2xDlaM&AAx(8d=bdB9Iv;Ac)itWIcp_cu0Ghi zc)c~m>#a`j`Uu<#<%>W@gLu6)!t1RLg5?UAYge=qyxtn&^;XA9e1v)H2Qp}hc)c~k z>#Yug#Y%9Z*{EQN0_&MAcOlTyxtn&^;QSLa)rws=k%g@y*0w?tk*NB zJp#Ax)py)gx#mmkMB}crdCkh)j*jGZv`~D6)KIVbkbM>*`%JY%5O%HD3%JE>Uga{` zXA!c`RPPGKM@UcWRUfj?B4nRA2)lQwP26HOuZx-Nvk2K|%1VUdBgA6#st?&`5wg!5 zgl#3XO5AleucXmmA^R*s_L;JFq4)@~e7)*J_F0JRGr4uI%CfDUqYJl~1O3_?{S~s$ zLS&z*aV``eAtP9O2J=>!gRn;}y@Yvn3|2z#gS*ZFvd`3AXQB8A@kH8oAOC!EH0S7N zRIC^|80s4}v=U?q1^8l!%FPj5$mM$BJ(&qdPK`R=_O)blD2uZZ{Ee@b1aIB*C2sbc zjFE^LBesp&TvT~PL+ZC0$OOchkq$t0FK&?#fQiR+k z$#zl*)=+wZHfG+6gA9|q6d`v>az6OhoMcg{ezOpe!PyzPOA&IHB-=?LY%bcEdGii3 zOzu*I+$G6G;+uJr6Q$m^vk;I$zl+?Z2)Rp=?W7Pk7j4YE-3J-8cH}Na$XzPflwUzW z2ImjtE``Wlk~}EB7HI#L93#F|2pP0?$^RM~+E=+$D$dD+tK25U{1nR~FT8Gge9#8ZuZbWWMl?Mu%dJJN0)n znoGLn$gT;SHQDMQSgvqcy#N{PU1act$l!@>ijOc}2{NcbWC=yc5^@kk3zwx$$e@)p ztlla@CX&jW6pQl_#=AlWXJ=$PMb)pI=^$9Ha9MT?8MJm}R7J?BifxLIFtY??aJ@Tt zi4L7z zGqEW?!py-&#?ZYkjC%euMb*m8sU@P#9Ikwf$U{4DPiFq|Nzop|&rk@V*a-f{_n3m= zr}TmhlYbsD|J<*Ma1oK!%H+65W0B)dirM3+TFF<CVsa13tVUMoUAPGVDh zgjq9C2FCf894I>;VeiK_#YdPm0}%9AW;fv=h!!sT zF0+#X!df%HGBS#fFlz>bFngTXM)0@U2`SH)wZqzZIkoZ;W*25!j;|Gj_*y|?x17I) z%kFjEyUnVv4Dq!Br+0mX*-b(QHHfbjMEF{PgJ8MBWm}K-qWD@tgs&AiR^lVft{5_C ziTGMUgs&Ai2$m~c_9!r3bXm6uUn_8|-A9<+J!Ei1;cEpEzEmy8*0y5}D&%myz*-`H~2$m~cwvW+X^oB>zh<3i}E64lz2onQ>3|gYuZ7aJH zTcVYi2&A$r(Z9BK^J=!TE1~!Z6Df@Kh-w($9@coItFkLW&`N~M)~2>AWblN@;89j0 zmf<5zY!NbOS9fjL7XEaI{yvT%Sgvr{+SGQ1Or!{zNXkmYGJJ%IEkXwE>Tk8%M#y$@ z5G+@?Y;9`0LPk}Dj4EX%Vi`Wd#1O+SDBUYp3KP8kB>Ix_egDuk1(-5BV&t>aw-|-Gy^tP8QD}T z1CgiSld18ao>A5PTPcK4Yy^MfjkO@^*aR|oPi9-#CmM^l+x(gc7ZF*lc<&YO!$sTh zJ{&3Ld{EU&zEaAP%&81y+=_cL5ANI{`o2pyB||7g+X!i&)(0|QB4oZe2$m~c)Qvfn zfeh*#nJ*DCUs9XmBh2{@5RAzn^Cd#&i-RCqxM*YMR0aszE;3&tWWJ;}#YdRa8X&lO zMdnM0%okeWq{xqMCMC~%ojCkh2kU3`3?}AosszxBJ;&Tuw3Edm^Y^~ zKyY^M&}d?a%opWLgyJL2xd;%P2hBN-gJ8MBMc-vkWq_bhG^aAkCkn+!nDZTjFeg6_ zg5{c1MCB``wz^j4)Y7Syk1*$)rsepqOo;EwI0)8CxLkd(ckx}B5Z{$?de=vo^IFKD z2Ju~)5Z{$?5G+@?Z0pfhg73_-vuQ zW9>e|oS#DmM-;v*6XClu4ua(hmpjfmJL9`D5xy(qj9MRI?g2msy=e1m8b`-;Jkmk1 zT;Z~PjGmom4Qmkf8QIVAK0dPqh2CW^rOCfTXl(h@RM~LNX ze}&wo5V=bZ!nSsfE_3SzGU%_6yA&dKNsU^e_y`%n+B2AYG7iEXwe%9^)(d3NUm@T+GM>jhnL7V^AzVJ^9Aza!A=*ZW z^=P|7c1?)v8V6z9E468Eg+c~LEi!mQWbh~}5sHrxd((C`==#~=n|P1aE{nf~i`q1| zLLq~8b$Oe4Au^Gal?cU0h`njMLbg+gY$pd{+bgwc?s!55?Ft!HAu_5`o8lwH-n3mI zYb!+7ma;1;i)i7ZHqC8H$e>*vGpl~sXW|3ON`&Gg#NM=BnVXpo!nRl1mAMrP8MG^8 zxbgm#vMZtZ2(dSPPX=%Hhw^5>x!`D-}y;7UzzA$9auJFaF5MP{9Rw5K1A@-*23SYGf@l`7aVcQtBY3>U{2JLFY z;Bn!S^A1&3A`~AX_NMLX#a#~y@pUc-VcRRUY3>U{2JH%801NR2FlARl@eyJ@+OF`G zu>fBgQ+6c?+bXF|b6*%TXjlDauMhAgGi4=0@eyKg+OEt!WCvl}EA7hMDuxW&mAO@{ z>`Ev;LhMZ=kXOW;%MOC&ns0ll^_A3C*UEg)%c+%*FnJoL<&W0ADR}RY#SVhC5-wLC zTwfsvD?kpG)4M*xWOEn|BF`&8o|mIRmMdJYU2zqTT(SVUWR8{i2$RhL8C+j=Y||(_ zsAG2r!E%Mm9UqJ#BPT9IPMl-yK4O*5=70>2DCFIR$h&h8ELXVPac*+^Lge;2qt-{5 zya~wQ`pRTlI0%+2T=Wv+WAys!%-YSv<=;(FvzkzRgvsWB4DJm~MlRwdmHEKRmf$(n z7lDmcmT*rW2#ycjR!?wSU0DgnfufL05N51cUm!*ouXb1fjzWNs9t8dCmOje^hb%5_u|X z?^LT>FIP{Ak@MpqY%cybnLUufvpeMc#K`$kRw5J|LEV@<9Ux3DS%6$J2VryB+SFEJ sa(kQKFOYyZ0{TQX&zR2qEbrMM^36dv4{LOPy|SVznn# zmn#U$cxz;{(%lD+2l}}?XSDsKUBjfx;Zw^H!sXU#Xoqw1g>GLYeTSVHkRRC`Ii>Glk75bgldOSh!zBY@7;7!Y4Dce zL~JVLpX{ycdUjQd*UznQ!+d3n$A3Ssw^ASmOB$@i9qtQ`Rv3u@KP zuf1bt(x>HwGK6puA^n!iZSOxRzwY5*lJkl~otE3JC8GImyTpSB90M8OuedfpxLK`q z%Z&pSBBR*-GpFs?dG+JFCiMcM@24~J?@wu%zP_ek8A7-yqx)I)<7KUg=&)>7{^c>v z($*V$D?~=g$|d6QZO!7rJqth_)@nh1agBEAp)GqTL`KOFY*WjyQ+z?#9*EIucCtVLKqY@0{j0 z3_UEZGOMjZWRwh%%dKp?xJRG(#(Q@K;_=6y&-d%lJ3Zlq<{l#BqKrfLJv`pFsvZz? zKYA~}?(tJojBeNWXmuQ(~~@YJpfA<}IG ze}A&Icl^Y;tkn|({+6Hd^>Jy%*Y(Q~!sXU#>9}w6kNtH*`orh9grv0pc2xYuW7nx# zO&vQbK4{x?RjZk`N5}7{*Wvg1M}3_SFB+fDI(mM{`U-_;L8y`*JR=^u+xeOs(L}WevWA2Ci_@gGJ)2_YPX}RB~wEFn?KaaPEj1AxZn7{dmDd~f6_EdXsR;yRej%Odeq(m-b ziQuwjytL_ue6Is9POqImQX%Ye1wr(!m!BUGKZUh=2|B+RIv@2`&oYE?xwWc4V^jW! z+ef71zI|IEjK!&18QWF0lG^5Sw|?|le%8-p(uqq-W$h3IWsDnjcKm4dB|xWrzsk3| zXk6NU&xgto!sYftTX=>XJVVWI>ca!gY5Vo5VO;&ZCQ3KPN5$+bsV%Hz-P(LKb5L6K z(i%Wy6qYLp{>~7u-t|Gg-KE3Qt7d;))^gz@LfVwe^?|4E4o|(|r2|#1>TPQocl)8M zs+IA5=zNznf5sVyrFHLWTh5>h-%McmYoVL;mdl;AZdyJmR!Qr}r#LOA4(v9Wl@nxySdlfs zifq8JGZiAEWC)^HFIrh@y!S95M!$D#zVYNW$-trKmLY_Twfgsfm8I{VJOhaBpBC~> zyRA&N96m-NGD=o15oWCg#KHHs%D*^eVKRTu@d}YqG6dJY&-55oI^%)!fT;Us&HU<$ z>B&D2zQ{vlT$ItU#i-Kg%ZWG*E95J%LOvpyq!1a!MVK`l5IeV8-nQ$oLNe|zQxqbj zWC+%(ZI=gDO#kshAo|~POWW$r>m{e3F|`aKT&$H@x9eIhM6E)rRt46VT##45x*c3f zUO~5f@6FFGY&PVm@Yvm_z)CWTjW9AQur~nuI7e?26)=r5O+Au_JYoeU7q9586X z!0qb`LqF9Bv&T^_7X)SGa-F#M0pjkx2eoDC0-WDy7t(I3JP%FhnM5e*|Z`LfXshA#$CBm+h27TSYrVH4ypdGOG;tNw2 zhL*J(N~TS$aXAJHdJJMj6)~bh8BtkT85e7Xkyg-SaMXLp78^}o6UwN~C@uoyzkppB zY87=j2Qt10Eze*m8G^NfUkS7q9k^~<5#A>f?~|34aj{nL#{vDZ^3+9m>d5lchTA+L z>~Vm=tX9OV7U@~7JLlR!=34mL0DBH_*)rg%i}2Ku_S6}LimH{=R?VD6%$$*)Io);$f-*3R z270c=>|Dg`9Mw~^vx^WeyG^-VgBhEON8Uan(yOH$*KmQX;jm5!u!F#QC#!8PhgC)q ztBgpmGBOIw6$F1v`_xLNh?PvFS28X_xQLK8sg-3BE6Yf)EOT6?23)0*3+u!HyCPL9 zsjXU(6|o|V^oq=FhaiZ?>MYP}IIQ}LSoKAE)#oCFiwJ2`E{9ck5v%aXT7?H(pOXu# z{y?vmb6n}Gzvpr-r|&4{zMU4;ul+Q1n^9~8e`8G@V2^_~o!DV}vDyt&qx+ZFA!ii3T>i#tIWTMLO+OT|3Xk+E+(if%5z=pJ$5OquYlWy`pyP?hd^)4JVM@d3ZzcknQCx(XwILf(&LX0mkrn0SOs{H{ z)ucNk!UY`>{<;68;(HJO5=taBD=Xt-tq@x-Ft(h_A?jR2)H$@G&W7S5%z6cgnj4QT zzH#ZAaQ9QsjaXJj$q?*mM2ZWHs^@YaHa)a>;puT0y*s81AzUoUtki&b`m?VVB0?YP z2)&Bq7bK2vR{G$wWh|^!xA^uQGeaG9&L}Kb5d4h@bV0|dPrt8K@$1P8Lmk<65yIux zs&Uo(+FYG9kDq=0Qq>MQQ6QIDQ=?Xu>vsGGVgV2V5jMp}@VD7n0D;qtg*eR!{L>7V zE9;S5?%6wMEZo$tVQ8H+RQ8pWOEgX$3i@mUrx^=znh{#38I=g(B0~BNJ}q}ybkUtZ z=lQGFx_O1-7lqQyBag)XV_xB(U6K`jM;@(y=W++N!`@_3IYKDqh|cZ)_FCWgw-LFV z<}&CC$}2~7YVc8MPLmF*CRNrhEA6=xqb>8GoByR&Hsaj9rkA#k@BUw8NLegbxcFOo zq`X!`j%Xb}aQ6>bU(G8F_^Cns)(yM;fm+#!JLXr5U-`J{@6<}TC{KE%yjEf7Uh#jv z8>wowZMQ-cuq-tfXPyLqml_P}0a&3gMyk3-F?H>wu~yO}<+Xyn2JoWF!lCB?Ui1&t%0|Fq0(jBi zsg-cCR?;KowSvzG;6+ufFeUq^MgFqZ)F{i2X6sdW6^)dc;9w@eGHir>zv#CRaucQLlF@E()=cU2ZExSbbUE4(=?2}44=Op5aq*HLtV|gHYw_Y0DGh(FCaA?S7L z4?s{Kk8f%pH8>_vaZ!o4Q-;LFiKtn>S+Jl}MWFT3@4h{v#&wTZ2#JMTy&Di=dKU=l zqyD1J;hKXhZ%3;*H4zelCcSL#F zCnPH`yI3LYd)h##d*KFA(g^Bf-M@B9$K5+vA?!Qbuo87!*|Z~ul|TmdF?;);(|_Ie zCxwvvyKD!nMBUjX0#*{kN`Rm~+V>xvj+(f$LfCg*jkhZh0e!?;A0_DH!(kVvFPwRz z=)CgYtGQvQ5Fal*KVGw9KWLESW9p&P(syS6C16eDW~S1Ixs6E~u&Y?x74^~Rk!k6N z%LZT%pe#|{z?9!SueA`^c~Kud&b=rdckz|V+U*;LuteU*EfE20kF~W^AAKJV(rc%* zPg$;gqs{b{@(iZ0Vm&^N`272%_m0yP!oJ-GE8!h_g@Bcm^f>>=E|*5{&G^1F@0enI z;ckB^tQ$D9)aBehYF~r>hl&E5{fCMt=W;}xQkY+QG5D+E!oH?57A^>u)cWxwN+;dj zAGK=H?2@SG=SRn1AK5;!DJ<7Ui0oYMi~G-y9_af-JZJ492VvLntPOV;c3$1D)be27 zNMWt+Jh@G2zjq#0wKDM?r-nq2+5M#z?|*xusnthc{#ZI}w?8QvLSe0>O?GW{t)3oq zbUfz!haH5?#abPB=$k8^UUeE|tgbyG+H~@q_~`L#6Pw~AvUb#YyMOfhYmdZB|Gh_Q zBkb1BdH2RbvnKDYc=CV|rscDy@5m3TwN$m1J7JzEupQD1l*coKWy1%WmZzt*Da{z) zNwq^LK0ADPgxw2lIsbn0v*$v_o1J?__k7tszB|`CwJAO#>#HYAt)my~eq0*)R!;|E z_bArYN=E7M^G)xE1;zDvFPgKFsCVyB+?~J-9Njdsh&))=V!{XuD$Xo>cwg z!X8KK-bF7eijTAspo@MQC>qQMG)(Sda&_A^) zK7ul|J{qL&hE*od2xfOV$3fUyqZiFqOQXX_!ox0|5&!VcSV63ybi=iRYbySxj9#bm zej*Vs?DOa3*1bljq+o{ReCHr2?~?hamR7tA#6Cz)DB zuP;fiUVD;~Arv3cYRLRj_!38L9q428bq^=4YDW%&Va#YgnqJi9dHA$n@s)u?x`Nj~_cp@U$#!bKaaa>y&CzWsZ%RHW33_|e{s~XKJ6(2hR2zs9lxdW41E`DBlA3?BO;o?}SHfU98z*L@da{f5$#t0DEC zOJ3Xe?+$|H3K#qBw!`*}7uP!o29`yS>imXNo22t@9H?|I6d!Tyx2MI|?|BUn9Otj!dr109+nXH(%M~v6bj9pb z;%iP!fS_;h+Tnu_Jq!#2?nLb$BPbvXyKyH_d4VB_@tSu zfS{*7dh(fRa>{*)P4N-gn%dHNK&=^_V>dakASb+*&I?-S6W29QzPNFAU{id=zi&7+ zUN(Fk5Y&0=vmZ!Wd|E%W5&SJ&md=5o&YM+VnM_-JL}*idMC(R9<0VIa1O#>d(LFn* zO{Y(G5JU@?rE?&t^Zu*rrXA|s9oiHhv0+@F_~d6l1A;nlU9D3(w9z65L9}pLnq{q^ z^FGVErJqlDCbTI&;@=I9i%W-Z0fOWF;$i*My3<~C5JU@?rCA`T^QX5BNMCtiV`x)+ zM7AHae7n-Q@$Kq2&Wdio#(|1Wu9+dmxy z%M~v6wDHG4Q0Fa9U6~v*Z0E?P_=t-x%*AIN+Y<=-_P4*>lAL=}V+TRBaIvS22M1yg z=={uuKP1l<+DA6UN91el6wghL0)jeUGpKg@NRzG(f@tBQW{n32f;u1AYPWRJr9C5? z;v*0*F>wa!-0W+Wp3Oc}{WiNhrE|0AgbZt!sx&AR>fA<{eJv2w`LVOt$Af-c;2@|$ z;bKpl6$cR1`Cl7;9Us2#4W&V$_z1Hf1cExBoE)5lV|R`0viMuL*wbd^1O#>d@~#IZ zLki8628H4y%*ql7j`I%&k4qjo?@$N9a)paMZB~G+6?8s#)3D^b*Ly1s3dKj5bubXr z`IN(NPAXQO;viVAa8a{nB?|=S^KJ7lPcEN#j?%eMe1ut@13{gey_(XqIjF(x6a`&MOhnW&yDbAgFW100P7S9E8!J;$lym{S^?@Ibr|-VgO3# zLh%vMW&yDbAgFW100P7Sl+FcVG^n`P(`J7K1a)56XIn62+P+GILh%vMW&yhiAgJ@T zRlW``S<=Hn7!4{e_Vg;fR|A6cId&`|b}UMRLh%vMW&yh*AgFWfibCv)9E8!J;-b#Y zUJVGd^9r%^QaTrkkH}({)cFN(+#FPyH$drGZiSfHS=|<4Pj`QD|KPhhImn>S7hm2W zJaq80$^!_+M_{H7viZDgcuUyy?4y*<1;KKKi#`47<6VN**H(uN>iqqhPlop%cCOO7 zP<#Yt>L8oXhwk-l_+yQtgJ8MB#hy+suL!o^#rFWH^X4mSML%5gsG6OH;v+Cq2ibgn z>(Tp0<8J)GL9krmVowiyx_eM}N*&1HIRAT{PSJVif2d|>q4)^Q)Im0%cdH*ocTK3K zbS?;%D_qq1+^W5T`@XCT8Pxd?#~mHby)LJ8E)*Y;#oMX#&rWm?zY>JP-E-cV{wWpx-m9wKLc(0X%AX>OA%|Zspd6kw&NBgwsr*>Y(8cIF_ zyRbm-)u{8~$*^cvgPsn8}lh{A%i-v@%XmzABU_{8Wf6;K(r;$F&U2Y znd|qC_CI8+gJ8MB#hy0)7&55y%X>GEdYoS~wJAOV(Uw5RWVk>U2m`H%=)-2p3DrqRxN9Ip>T;8%pE8nWhjzvCHM}EPLJD14!f^0M7pT z&K1T=_Lc!0`EN`_E;g!G}-VBxSC$=hwub`UIAxTsBu4(r+A z@=GQr(KV+jD-nv1kQlkP#Hu?@OAdeWNC&}kg^N}x(P2HS&2DvEQsaw4YEyhf7Cq;P zx})n6NsYfXbr3`g7e|*whqaYF^WN&@zHz$c5^rZ;*=MQJhq+wO05>4!yqrANW2Dnp zHiEyiH!i;1duhiZibz5>k(_^Q{g_gF^8Uasr{f=)uq61i8)b4ua(h7jDv*^nvIlf6qhb^x+XRn7 zsToHoJ|a7t;Oh0}^szYjrjdhSxx&R6&P1jlgEQyuZ?uT}HlD3!PNDb++$y$C^+zr4 z8Ru8t?jTsMoQ1gUV69Ay%&C=+kaH2;@^OogO73iPi-Taf!sY6NbM2fCS0)qJFLrv@ zN65K|)?ka#4<_f0`o=-9T;X!dd&PB8rt$SDX6bG;lg5?UAJI*=R{<#IcAUmDDPv`zZc#vWw|;UXfd z)kO`K20w*;((_MgqS}F6ZNB8Eyr|r=VVkfQjj>BbJ8mm<4)B~_ezHo|yNco?{wK-e1thS!aj;EM>HxyG|Fi?Yb9K+KIlaejY<%W za(dTCm~$h@pav0*N)U~55G+@?T)UzdMKmf!G|I6OA7RdoAcK~OXjF=5l!IWo!sU(+ z6OBp{jZ%9~86Q5voEt#~M--w_DWXwj<3qUIac-hfDWXx%sAWxTggIS;jH}?`TEEpV z9lfNsgJ8MBMK2*fMtjjeJvK1?u3int`}m0LE;r}%DhJMr2i5AV>`H8jRwAd?wl=k0 znNv$;S7I4HLe8VLT{Zjkp5&_++bFvd1j`jJTbp{+?iln;GJRyAtVArsN5~1bwyQQ{ zs-z1(zurNxT;Z~{sl8A0It|hm&2LdwB9`GJ z)%u@@rW-qc;UHM9aM7+ZE8*T|>5!oA!oSo0P>Advyf6rAitC^mw><)uozREW8D^x{$J`CFbTLkJfUS*vm6HsnSr5 zL815vxjCZ8dAIM^B*lTT#4J@=ELXTV<`E;05pRbK&QZz6MM<*o|0I&CC_VyFRdY{< zy9q>V6DwM)5G+@?=(`a2HSZeGC*FR`Lvg+CuSrB$QGA5l%h9tl&JALm8#oA-i&Fr; zys*M;hdDP$aBd*cWmPL5ffIok=LRcu%W-ay;M~AzIm;C;S09|6ac+>{+`#EwAAu8r z80Q9%K@H;EAjP?XgJ8MB<=PczXPg_PI5&uGijTmFK#X$($l&aZbAuG;1`dK~;c~}^ zIX6ggZlLZV%E<8%I1z|(ZU7ndqBu85ac88S>(N@``LsP~&$F1eVY zVxcSWo+V;39qV3_Ubn|kb?4udi!Am3ihvBZe9@)nrw1oDsN4lXSmmy;dI2)%ud07^ zPWr*}St`bEdQ|dbn8#ovAcO0xBk$>-ZkaZ$V3%e6USVkyGU%^XZSI+#_V5krtiV`C z#jhYBgO<4KnAT~hz4s~DWm&&hSXK!cwD#h?_0p409agd_zk+}aj;J;Vyqny!WI=_E zuzss?ZpI^I&|j@6ElK88+eeLaq5KL0GIUI)Q&My4qx)JTwZi%>?+>UKU9|V9h#!lO zpS!@J{0agxzCd*FhR>&@i@s{E@>nEyMcJ!)RoogMg?9Wmig@W;8q2c@Q#aS0A=qlC)^DwLm=!#Yc#} zX}kL9#sfLyI0(y1)LRy29)t|egT}5LijOce9NJ-W;!??pGb_CUtwg>NK>eF_5M=P& zV9Ze$rdLidxpk3iaF~x~uXj6PdW{I>boLZ(h zwR8|f3m3I%)Cm$}qDX=L%LhMc3m04do2%?3Hs~WRf zf(+V~SuMdbGK!CIEzzvV90bvF&(^N3u9dk@?bOOgnEj_|`8%I3NRB`3eFwpEh0E0k zd-t0juOu(Vdxti~N0|Mm(cq`sYo%WtQQ;tn7B1U*wD-BJ*eLzK!6O|j@eyYK2^sWo zi)VC8pISb}L9krmvPXgTqL-vS)AOp|=~%muF#Au);E0+ueMnmE+B+Ns%M~tnoHP2d z8}>NQFM8M+wLZe^`XIyFK{^PQD_ryv;$!ss>csEIr2oErnVQvv;v>v{5HhTtu##c+ z&dOie8K5E$wi_)CE_>vx^n+(VQV5~2CW7E^f|A-M+{VPeP*f@l+Ic4X^X;noWy+YZG?m?*btIc~iqxb@<+ zoV5}zS08GQ+A=S}trw?veT0eD8x7*tOM+W34ua(hmupwF65M)8aO=gf5+7ks9Uz02 zh+8iyZoN1NmMdKD_@K4p)=P?8FOg005$5y+GR&=)6t`X+1ku7}k7ga~!>yMTw_co4 z>m$r55M0EL!XeIU= z5Mn+0o=l^Od#5*!?dw>Hjo|O>i*wuw?>KdzwAA;AGK6puAvRt4UPdDCWtbZ~%G%|X z3fh>t&jM>_OlEQIACnq2PEj(1!g6hdv`>%oj{o{J*=PLm4ua(h7j4YkXMqe_`?l^| zlI~|8p=?(uK0>l!^z2-3(yPhMy>+gPAXu(&(Z>bK>h2kS5D@j{>ucap>b+0Tr2$m~c zv@vs^1u{50Z#}zfGW)IDmF)_}M@V*+wsvz*#zC-L;i9#hTQ88o+1cEBQPwULA0atk z8ewkMI0%+2IYw?fxMpbZ`t-QbA+4NR`3T83(k<^htA5gZ;sXwXTYnbeM&lm^6a)pb!S=DwU-%fxGdeN0lx+FcWI#cOfC_X~+%Cr}4u%KEpW|w{r zg5?SqZ47x+d{qT9=tcK$(1!7j4v4Uwi@SB7Rwbbj(Oy<@s%6Mpcj3t?oILE z4_T~yiBNomLb50|!o1ewAXu(>RYmP& zq_(VsYsud0;rs*2OQK7u#1@ydsuJT>6$im`h07i19JRwQX&mn|Nc$2Q=RSgHys82j^l)3c-5*ameoEOm z7cP1U@iE$qKDf0-{KML5j`v|rY()0$30h)}zpJ;9lwFA}8GBVPjN96*v@5>WqpUoaSwtcf7ZoM^sEV&>YAbFE(!%$$nLj1N;Q-jlho z=|dssb5byG^V@)Gc9z%vSQ1tSdI6JqP*EoFOqTSUP z6pD|?^0qmDocUueY%%0@HO>XWa)pay9&7jl-q?c-&dziCJ`v!ZJLOA+;v=&BbM7Ya zmR^9j^c)1s6)yTN>_yDC2h8kTz*i#qq{uN}<67l|3c*{KpI|!C5T<-Xw zwd0Mg5N~Wb*6t&)(=Xs1FUVj7vis{x!mHMvkku>@Rt$iItZ34T(*zVv-7|Y)`V9aGQ#mbJ_36mej5}r%xj^MycUY+kouk% z%at#35slah-;@Qy#AL#nCMF{kA0ai={tCHEA##^gI|O0ZioJl?NuXaNF}X`2a+g%^ z3dKiAPwU+Ta+gBnE;$Ihcd1RpP6GX^3atdWOCfTXl$8j@M~KDf-2`%%LgX$v2-`|% zm57}bve#jdyA&dKNm;v4e1urOUY8(uDMap)8c~9&bd2E=3n6Zo36Q&_ypK?Pgm@x&Q5_wO7#*Z#APT6yUdP|^ zvM#lW2&8#`m-l44ytij`$&TL2N`&Gg#Co({A-g6*c8!Cu?UmX@{5rs!XRuw)gUH~C zkiny@L?}K&>`mL%{rHCBimGiLgl(_XCZf>+-fn{o+7&X9!c(7ap{ztGK0@qG+ZD2% zLS#ER2-{w%O~kJQyg>&UY91W@V2F$=WhFxK5n?^su8_4AB5TV**!D_oB7PmrtJ#ZXMy!XlPb%$SK1Zg*XCik1}Q<2)l`3GOLMmx-jNhBvGLh%t|Z~DXpuhvC)wNBZUAZ&Z3 zHgW#JENsZ2UEyWC2ruI)D-nv15PQ>hh1d5YyuRlkY$@v_3m9QI&D&2 zWhFxK5n^xJuJDRrh*t#FiHRU=d!;sU{=uwx$e>-}rNR&|6)GzcijNR`({_c|5JS9% z=pbx+r8aT?!R&s>pj|yWeMI=-wO1&+5{i!yd((D>6O#b1Iywm3UTIh6H37(=UE$@( z053->yAq0z5PQ=IoUsJRD{>Gl*Sv9{?tV#ab*;?125RLc6d!@}X!FVqTRw9B72)-L zN0hZgxLkd3eRX}WVu&0pr+3*78)05TFd9UjSBN|>2f=cM%e5=6uaHX?BA3ju5+8vZ z1?H6-Mn90R7Cj$UaV(ML3YR-RxV}P8T!frB$J%`aZbq0_ZaAWlcNZb=&OxwT;c~}0 z*H_5xi;&yrj9MQdZ`qjW$KQkK`*m#`1j`jJdI|9{dVN(IdqlLn(>`ie6N-<>zB9`; z+&d?n7|lAax{`q#BI<>DmWx|2*h6nsw=_i_zOjybGJ7>15OuzHcZCp&jo@$j&TKAc zZoNdj_2Sn=xQNJVWp36)yjeqv`R28{y(4eyvn1Tn3Gk{T_UXJQ^GnNN(erCQkh?gF zLbQ#L_UYLf*)dYZr=-zzrDlLKDXavYjGiJ2?oJD_k5axP=zr zwNS{Q7ez)@gp4XR28H4ya0AA?G{td_tgR4PTMmNd3Kz#bZqo&L^%OGbOOP2Be*Iz_ z&;A67Rwbb`YzlGRNsu#J`ovi0W#c_PZWxez&#oBojCek zyxtn%^;QSLa?Sfb%8N>EwHL*0!w|2xDlaM&AAx(8d=bdB9Iv;Ac)itWIcp_cu0Ghi zc)c~m>#a`j`Uu<#<%>W@gLu6)!t1RLg5?UAYge=qyxtn&^;XA9e1v)H2Qp}hc)c~k z>#Yug#Y%9Z*{EQN0_&MAcOlTyxtn&^;QSLa)rws=k%g@y*0w?tk*NB zJp#Ax)py)gx#mmkMB}crdCkh)j*jGZv`~D6)KIVbkbM>*`%JY%5O%HD3%JE>Uga{` zXA!c`RPPGKM@UcWRUfj?B4nRA2)lQwP26HOuZx-Nvk2K|%1VUdBgA6#st?&`5wg!5 zgl#3XO5AleucXmmA^R*s_L;JFq4)@~e7)*J_F0JRGr4uI%CfDUqYJl~1O3_?{S~s$ zLS&z*aV``eAtP9O2J=>!gRn;}y@Yvn3|2z#gS*ZFvd`3AXQB8A@kH8oAOC!EH0S7N zRIC^|80s4}v=U?q1^8l!%FPj5$mM$BJ(&qdPK`R=_O)blD2uZZ{Ee@b1aIB*C2sbc zjFE^LBesp&TvT~PL+ZC0$OOchkq$t0FK&?#fQiR+k z$#zl*)=+wZHfG+6gA9|q6d`v>az6OhoMcg{ezOpe!PyzPOA&IHB-=?LY%bcEdGii3 zOzu*I+$G6G;+uJr6Q$m^vk;I$zl+?Z2)Rp=?W7Pk7j4YE-3J-8cH}Na$XzPflwUzW z2ImjtE``Wlk~}EB7HI#L93#F|2pP0?$^RM~+E=+$D$dD+tK25U{1nR~FT8Gge9#8ZuZbWWMl?Mu%dJJN0)n znoGLn$gT;SHQDMQSgvqcy#N{PU1act$l!@>ijOc}2{NcbWC=yc5^@kk3zwx$$e@)p ztlla@CX&jW6pQl_#=AlWXJ=$PMb)pI=^$9Ha9MT?8MJm}R7J?BifxLIFtY??aJ@Tt zi4L7z zGqEW?!py-&#?ZYkjC%euMb*m8sU@P#9Ikwf$U{4DPiFq|Nzop|&rk@V*a-f{_n3m= zr}TmhlYbsD|J<*Ma1oK!%H+65W0B)dirM3+TFF<CVsa13tVUMoUAPGVDh zgjq9C2FCf894I>;VeiK_#YdPm0}%9AW;fv=h!!sT zF0+#X!df%HGBS#fFlz>bFngTXM)0@U2`SH)wZqzZIkoZ;W*25!j;|Gj_*y|?x17I) z%kFjEyUnVv4Dq!Br+0mX*-b(QHHfbjMEF{PgJ8MBWm}K-qWD@tgs&AiR^lVft{5_C ziTGMUgs&Ai2$m~c_9!r3bXm6uUn_8|-A9<+J!Ei1;cEpEzEmy8*0y5}D&%myz*-`H~2$m~cwvW+X^oB>zh<3i}E64lz2onQ>3|gYuZ7aJH zTcVYi2&A$r(Z9BK^J=!TE1~!Z6Df@Kh-w($9@coItFkLW&`N~M)~2>AWblN@;89j0 zmf<5zY!NbOS9fjL7XEaI{yvT%Sgvr{+SGQ1Or!{zNXkmYGJJ%IEkXwE>Tk8%M#y$@ z5G+@?Y;9`0LPk}Dj4EX%Vi`Wd#1O+SDBUYp3KP8kB>Ix_egDuk1(-5BV&t>aw-|-Gy^tP8QD}T z1CgiSld18ao>A5PTPcK4Yy^MfjkO@^*aR|oPi9-#CmM^l+x(gc7ZF*lc<&YO!$sTh zJ{&3Ld{EU&zEaAP%&81y+=_cL5ANI{`o2pyB||7g+X!i&)(0|QB4oZe2$m~c)Qvfn zfeh*#nJ*DCUs9XmBh2{@5RAzn^Cd#&i-RCqxM*YMR0aszE;3&tWWJ;}#YdRa8X&lO zMdnM0%okeWq{xqMCMC~%ojCkh2kU3`3?}AosszxBJ;&Tuw3Edm^Y^~ zKyY^M&}d?a%opWLgyJL2xd;%P2hBN-gJ8MBMc-vkWq_bhG^aAkCkn+!nDZTjFeg6_ zg5{c1MCB``wz^j4)Y7Syk1*$)rsepqOo;EwI0)8CxLkd(ckx}B5Z{$?de=vo^IFKD z2Ju~)5Z{$?5G+@?Z0pfhg73_-vuQ zW9>e|oS#DmM-;v*6XClu4ua(hmpjfmJL9`D5xy(qj9MRI?g2msy=e1m8b`-;Jkmk1 zT;Z~PjGmom4Qmkf8QIVAK0dPqh2CW^rOCfTXl(h@RM~LNX ze}&wo5V=bZ!nSsfE_3SzGU%_6yA&dKNsU^e_y`%n+B2AYG7iEXwe%9^)(d3NUm@T+GM>jhnL7V^AzVJ^9Aza!A=*ZW z^=P|7c1?)v8V6z9E468Eg+c~LEi!mQWbh~}5sHrxd((C`==#~=n|P1aE{nf~i`q1| zLLq~8b$Oe4Au^Gal?cU0h`njMLbg+gY$pd{+bgwc?s!55?Ft!HAu_5`o8lwH-n3mI zYb!+7ma;1;i)i7ZHqC8H$e>*vGpl~sXW|3ON`&Gg#NM=BnVXpo!nRl1mAMrP8MG^8 zxbgm#vMZtZ2(dSPPX=%Hhw^5>x!`D-}y;7UzzA$9auJFaF5MP{9Rw5K1A@-*23SYGf@l`7aVcQtBY3>U{2JLFY z;Bn!S^A1&3A`~AX_NMLX#a#~y@pUc-VcRRUY3>U{2JH%801NR2FlARl@eyJ@+OF`G zu>fBgQ+6c?+bXF|b6*%TXjlDauMhAgGi4=0@eyKg+OEt!WCvl}EA7hMDuxW&mAO@{ z>`Ev;LhMZ=kXOW;%MOC&ns0ll^_A3C*UEg)%c+%*FnJoL<&W0ADR}RY#SVhC5-wLC zTwfsvD?kpG)4M*xWOEn|BF`&8o|mIRmMdJYU2zqTT(SVUWR8{i2$RhL8C+j=Y||(_ zsAG2r!E%Mm9UqJ#BPT9IPMl-yK4O*5=70>2DCFIR$h&h8ELXVPac*+^Lge;2qt-{5 zya~wQ`pRTlI0%+2T=Wv+WAys!%-YSv<=;(FvzkzRgvsWB4DJm~MlRwdmHEKRmf$(n z7lDmcmT*rW2#ycjR!?wSU0DgnfufL05N51cUm!*ouXb1fjzWNs9t8dCmOje^hb%5_u|X z?^LT>FIP{Ak@MpqY%cybnLUufvpeMc#K`$kRw5J|LEV@<9Ux3DS%6$J2VryB+SFEJ sa(*wq+oi(PQ_`8!;+12r8DsElm5PbT=uqEGz7M_s%zS?vBs*{%HSjKj(bk`Oe%o zbMHC(GMWGPXG4^3-{H>e{GXe`<~_@{*G_-9?nr)e0E}?=%qc;iZ$=b|twa53zo0d|L1rK8D@zDP3!@1rhqhLhm1zz%Lzo7S(N6gcb$$UM_3tyN%Hl-j79>msT z=+5b3|2~6^f)Sk;xMo9j&^WIz@yzb7i z!AJR3k;k{A9t;ni{34|w3z>+m$J8H}gxznyVHAw$yuf#?ofy2{Ffj6{$v+XcUA;1; zAPXME)?@gj6=A;ZQlnr*=LLRe%#@&|>6bREs6N;j?yA~t-e;{K3m(K)G4fPXxNt~) zR!4MR;KP4S3I+x{>a1eSqNebo z;)D8zaBFaXNmsT z_kerC&Qr&Yf)Sk;_{JTBf|(1yj64opGbjA+=y|@*rCGS{Dym+)HC*t_5Tjs3D}dJ> zJ2!ZL?&-*5;=!B3#&M%l3bNoqZ11D)z_@VJ-?c`;h|UW&6=cDK z*m}qg=W~Z+MCS#Tz0yneUD-u_?xI>j7CeZphwRk;=4hv8MCS#TJ>N^t4>=8do(5V$ z7CeZphnzS*PaH;cUSK)ZyyP5|Q_X)eI@Pp-EO-!G4>>t~o}7&6yuflgd&zk&r?bz~ zSu4nb2eI{#4#3|TbpVX$yui{Kcu8L(U53vtLo3LF2eI{#PR4JKIvGZEUSR2oyrjR9 zZpml2q!nbrgV=gVN9MC5V?^f#maflB`b6pae0F_WK^8oSt%r1$K08ZBbY5WTQN5(! zmG0H=7j>^%K^8oSt%r2TK09PabY5WTwX;dzE?v0KE?g_ff(NnnkWSxcr_YGa3oJ83 zHkm)(t*!DoO=tyK@F2DxGO^_TjV2aGbY5VYeX_|MRnvMX$Eipw$btv4^^nOc$H|Kk zoflYUxNI^H%5<0Gbf*<$!GqX($OM_=1j&fb3(N`GDr8E{aZ1$+vfx2%75fg?dzgfE zMCZkIFfn=Kce9Uw@dFlqBcc_&p2>`FH9SWlcW&lau%tpWFP~k39LUvE!6_WkbX8Q4 zMUOMzhdjGxQUpt$F*BJ`apwDgD?PMAo}PGiE?pH_@ZgFdpR17F$IN74$u41Lz{;!A z3VHwIDb@9WEAN9WcyL7!bro`cnCS;B+2_r)Re4ofAv<_H54s+3WmROsgDZlltB?-B z%o$+GNp0qu%B#`}IfLWL%k_XOt0D^?ToFWFh4gTyqX$cREi*w>UX@lz7ZuMqt_NIM z6wzn*iY!#c6+zTh=#ETxfMAxdN-Nl-Lg#wm3acUuRdGcSbrrhz(Y+R!<*U*Pc7xEl z9=O7)$U;?I5ky^u?lN>&17`WEw1RyXbgl=kuqv`p6;}jNSE0{y-9La?zACL?hXbAK zfh(+vEL6o6LDW_76b4J5)L@pcN-Nk)K<9ek3acUueq0emn?wAIAAQnC-9Y@eaLb5x z21miXP_QayitocwFjr3nR|N5NRmc@pWxf%hM|_?;9{dcz;wMN&`Kq+y>}$oU$btt~ zBz+%zUcutiUU^ko;XGH)o$J*l3m#mNbX9z}!Q#$Pc~x5Byn`jHA`2c|k#tqu2f^Yl zT6tAk;p|r>t0D^?T#-NH&MDOvf#lLNmnKNhnX6{lHJG5 zAC*_774n|P-!7G|iY$0=MbcHtUTY>Suwp%|S0t194+#EOWdHyG literal 0 HcmV?d00001 diff --git a/GEMstack/knowledge/vehicle/model/meshes/e4/taillight_rr_link.STL b/GEMstack/knowledge/vehicle/model/meshes/e4/taillight_rr_link.STL new file mode 100755 index 0000000000000000000000000000000000000000..afc66745f5c7befbcadd078a0e65fa8cb672c990 GIT binary patch literal 8084 zcmb_hZHQG>6n)qSsiBrr5^6K~Nol6#sLj0lZh?gaiIy1nGAWI+EHbs4%$d>37>uaM z5Vi6HZOTA2qhaRVcg3jGAgCA$r!ehD=}b~+SytFy=iK$~esj9x{n7jw7H_Y$*S_c7 zbI#r~nauzDvnfh<;Als7{!a~I{=DAB4|cCG9*k%O@EwcC7xw>tedN(O-!ERZ zV!5Lr3m(L_s$Y7oE%xnPY7~sYUsftP&JFX%n;7~U57`D&IIzBqlXqaX_& z#8xqM_w=xTpFu{!h|UXKy{R(jn%NS0oPBO~c;BABj)E+B5L=JC{RQFnLq8UEMCS!w zf7jUH!>JLl8uD3QA1tU5y@SW=>2Cvr*j6AAao(x;B zS?MUqf(Nnn7&d7|*wT8rQ81$O0>3?GO3>8sbE{QU9Dz`7d$(}C>YTS z;PofY58j)5Hu9Kw_~x*F+-OHZ7CeaUbJQLh7jF5h#wZxkd4WeS`>wEf&Opy9hOHS9 z?if1NQIG`>VyhUiu3uQSah6dqqVodppRuFRzj}D&G3ZpUaLpfiM?n@mh^mt;wT>5xtzSN26pZM+z_m?XZQq}$ zjyyiSaZYj7l}|egvfx2%Jvz2^1ZSVGHws2{USMJ3c8)wcw&jC8n;RSjS@0mHN8Y1? z5uG>ktBs#Ss`6NsR!D`06+MSi$dl*zb~wLW*PR*(e`V(TF%gU^$J5uF!U&KNH~ujKUcdHQGtS@0mX9&*C@ zJmDD8d4c7u^x|_@PEntys8)~#4`S;fC$+ydI;k1ad4c83_u~6QZUdjUfmVmr|Zcd*!CnGv9u-wjGe4oqh?DKZk3bNoq zY(1m{@OMWY03$jtuyh7q+?Pm~;j_!o3bNoqY(1ot@!O(Kh7p|?Sb8Ea?ysa<^4TqE z1zGSQwjR=v`RvFT(RqQT>+|A1QMx{#U7uEv1rK8DA)Teq&XN(G7g%~!FYb4xd-eN8 z-K$oR1rK8DAsw>M4w(_17g&1jY}~g?7w)qQ*9x-WL2Nyw)A!lwGoteX%gm6C=Z|-4 zDtt~8T0s^(h^>cAEV+N8iG>lJ7g%PWY&=I*Hy_DyD$)wF;6ZFXWb(>!@?u2i1(q2u z8_$C>-Q_slX$4vEAhsSdLFPC?GNSVWb3(QXnNo9{Qni9Cco18~fung3ldz8Hy!c$0 zrD?m-x4KLQEJn0~pJy`To53wt$djA-6)dUH%*#D1;DKD-6`aCd53L}J9{3A_tB`ls zOp0L1J7y+RD*pR9w1-y6+f$mI%b#2;$btt~#H~tBA2XAIC8va$0n=Bd6|(PR!GkN}R;Bwy-Iv1e+YneG6Y$yG3dyjsB?wPyuc zP;*6Gh3$~1%g|j7yngr4?m+FtIAK;K3DftKvBb z7EjUiRcS@pd6ifdS@7VBxK;6H0gE?I`l_^|>}*f0iY$0=Mck@*zp@hi?Tz@{drdoZyovY_CKxK&B*regt1p4{|4>8sL;vYsKaDzc*Ii2ITp%|SH!J~ cb0%1vYtvVy6>@)+{==JG6n+a literal 0 HcmV?d00001 diff --git a/GEMstack/knowledge/vehicle/model/meshes/e4/top_lidar_link.STL b/GEMstack/knowledge/vehicle/model/meshes/e4/top_lidar_link.STL new file mode 100644 index 0000000000000000000000000000000000000000..b52b8f475237ba9931347dcec48edadf3bb96010 GIT binary patch literal 42684 zcmbt-3AkNFvGoo!+?#=U5JCtl1YbY~1(I`igUnzUW0)mG2r`Bt3BzMJ2qJ<>E($-> zQ)KY{Kp=<+hTL;@%OFOO$EctJVMakzAV`?xUsYYT@7g)%MBewm?^EmEs@1EycXxGF z?S1o3nR49GM~s*{<;27AzlWbZ;{W&m#xI@G|25)}(Ob0Ey=cel<(JzH*}OI3ifhJ_ zL7P}bu-ef5{5z2w@$K)7Xnp60S2g9QqegGs`uq{csw_Wu`oBix-!kH)J4d%pynJ{Y zx{6?{?p|H>!G}%xk8s^RuBSC))92d8Wk0GMjF|K68m(}ewx;$&PSX{1p#R%-qy6pZXBiM>pgi(!XnwtF9 z5Gu13%T=!!VIH={`6_~~a5l;nsdCsVswcL({|m1eVNbISUG<8sctxsS*^aBrZ*9M- z%vLN{IT&F(|KE7UR=grr4m+LdiJk5Lg;$KQDA9(l&V#LZMXFv|B-62w30x=7nk^QW zs~n85h}wp(BG`&ogn1fKB7r<>`K?3O9zrSA<7x zM8uCWo5cD{-qtp56~R9-0?%G@#x``-E4ISUk&M$2uU>IZ{N$!1b*=f9cMn&3YQvh# z$%mdvXU4lP_(Co}vBqUVxQ8NVSvLe*xtus|{nxa3RBMKEu*PK>*XNWtx*^!g<-{@R zyyN0Bf4@&TSmUyc>uZ%bx*^!g<-~Erkcn~Wo8MCo*0?O=`W{Oh-4JZ$a^mLb2WwoGaecQZj&2CHayfBe{0NkCu*PK> z*P}$@=!Re`mlFrpDPs1@!5WukT#qY>qZ@*)TuvN#-UXhbaB8E0+@o z_HBXPs2r?uS;qA^pE$Z9*vjR^f%8}3R4E5*T$XYDW=I^}5Nzdg;y@fJ5FM0*H7?7z ze&ZyLZV0w=IdLGmwGic$gEcP8xPDV7j&2CHa=GNFI|plAws}YuRxdd^BH&eN<#M@J zxvv##T$XXMZW4QqL!xvi1Y5bBI3(u!GiQy6vDY}dA=t|0#33=)_bzK(77pxV ziM__r4Z&6}Ck~0Zeg;|NvT)!$O6)a`ZV0w=IdMqL^;p6hmxTjyMPjdUbVIO}%ZWo` zuE#{yxGWrqkNO{xv#c9}tz1qVGQObXC)T(uz&TDdI0*X&i+st}nqF3Y&KZq3AD zYbA(=TM3%2T$bNwnLR<}V2#T%u04O_AVkBhWF)q7S$>~owiA_uH7*N>?PKF0M8mCQ zB(`!{exGG_qLhO*E(?d9N8=zw!>wc_wsKj1pJf&qqR6aqSvV}N7zZI5ZY5~8a#?7(QqpniLG3g-)EWKoXWu(mxaUbUE?4`!>wc_wsKj1pJkQ-CqV|08g3;cv6aj6dqqf2tsJaz+2*0|MM{p22=J9w zE+-C&xrn4b5494FTgkXsktU+wz*==gu$9Y+15Z$D9Dg1$2yNWm}z{hc|Y)KRZq&F+$5~_$e{S8ReHl`{`p$%$KScJDTq0n zJYPHL{-3Fgov-g$)6C&j3tmO@svlmp%&UHQr838P^(w-v!n|t2D;*bJwcwS?yeqS8 z{R#WUuUtE{_~0KsfuHlz_xH3;*y@vh;p1nMWxw2Ozj)l~s~3G&^aR#0;#Xsav_5Ig zQgoJW-n(-=XyqG<55d9g>=p0hEbIMX$N280w-jf*v{GQJw|8H*_1Crb(|J@8d(7W8 z-aO~B;^%Z=i?1+_AwL=$XHI%V=fN6AaJ0*^v(MW+uD;$sig7FT21c+Ic4*UgXqJ6(qs?NN zxu{rke2?tiQo{(2+F6F(9%;9i2)4q`Z~D&9vX_?|8CTe~H?Fu$Z(t20E?nxd<_A07 zZ!>>=jS=zEVMF8g$M*!*FoN%^Ec^X}wd0ZNtsbYW-djPi)w8V!oAMvo`B^r6yJ2zq zcZSDnKk5mrVZ@00?rOgA#xsWa&c{RIm4ima`jtI_HH_e!I?E=nxqR%~`}6UFHG3-v zwvu&{RY_i*@Z6%}m5VlwYb@*utYO46*IwCtYxTDc@zExWiuwzi#x zI5;IrOh#_|zfQ)n&xXTW;QbbN>~L zlpvUg<2mbkC=o!`9wEKKYZCx`O*(4*Sc3m(u zpLF|v@qtM_fi=v5C##uXnmKk!?z@B$Y=x&ec3_vhyXq17i&yO#xA~+eu!a$Mnzeyv zK4bRr`N(|Fc=m-ofi;Z4UeKI3d4*k)`z~PwTVa>f`~+v&3p-zzZ$EkGIP|@qz#2y2 zJk|zI?cSqq$k!jWbNt|!J%Kfhz-iWOKY4|7p8Gjx1Y1ciHxPXg;c|~~tYHMAomMT0 z0}(Fw2*(JvLaeL}MA6mOT9m*3#HLZQB}8YfvScj8dC3(u)-pQFKKkdPeE5HD8fQPz z6IjCt#QfU8ZGhOGdu(R}TUEXK=kM1K$3Hbhy~6!kW~uO~%wBQBY2BG-K7abi@aG$Q z<7p#$M{bic5UE3$L$>acIL6zidQT> zxKhIiA{-Al?b-7y2LpC^}*P%+ixBzemkzmD;Cu-0y(2p zELK5UjpNmX)HsS@E1V6fcZ_5H9y^AeKbl?aze2C%?WKkh$jIxS!=sv*ymL70kQ<6g z2cb3~4I_}9>o=Zh=E(GeXZnm_E5wny+&XD>7mgSg-Z=8K;%9?;18W$8jJ!UOx9`5o zo?)H4jxU}(y(h4S5vUFH%gp2zGX3D0J|ox)F}E%^Y4U34mG=u{$E{wx_I^)b4I@xT z)d%XRW4^UtI3x}&hTYN=Si=b1Px`fK^6H{rjt~1xdZ_g-GD}9VmDIPAfh4bR&jz_~ zC1+p_BXG~w7k)f-!^9zoCp#e63U_&Z?(m&9tZ>wYgEfpWKC91-qYc4U=Iz+Tfx0#z zE6at$)~6=^+DfYxqqVLLsB3epYs&-7agAsNo8UmGYKqVZk5|;b5jl=Fo^UChpV3lx*U@N;5jRTc%KqVZk5|&$7 zHH@%3(GaMF11jNQm9X5YZ3w$j>nWDlT^pB^<00maIrMjIf-@ys~U5SS4H{*vhgca$go9PWWxv&`mktQ4ae`ICQvK*yjIc_^=7CB$MF%IdO)5eq+Fs9)fx6NO5+iAp#~CCmu6vMSs-PzkqC2?wi$r9M{;Bfuwb8f~qt zPwn0F62VrIVaQ#W=7CDMKqVZk5-v52z|)jYh#^o37pR1TRl=o)5qPrlZqmH6eu?f9 z9*eCc82KqVZk5-v52z|)lOhapf27pR1TRl=o)5!hEvxzp40uzrc|5*~}K zBy*LUG>-DuE*h(rQkCj=5O1O~9$SPrZXR2f229RE;M^xfKC0w8q z4ps@58b(<6(;~HXIW@MkCu~*qO6pCiJH;#9ee#x7?^JjvZ$njvcTKsc(psSsj;Mr# zRl=plde&;iBb9w>y`5RZ2;9HYr#23$&80?P+$*+%cjX#tB^*%+2djij4I`|7Z5-C8 z*4vrKVk=(hEJMv1QFG=}b7Hs2TUK2kd$XbAVu$G8o1~qHx;CP&&84no4I{8anx3g; zne<9fJ8Ra*2)5#9qxE@2eV$8w&KgG8TMnDKz0J@ZjuC8CedefZBkI~*>RO!s7S5i| z99g)$!P0SgMY0UFb42Z&OYO`WM&SI(dpz?B^|`$5(|3@JU@Km?EJIxzQP<{D*CJBN z+hX+!S-8Bl(s9{aeBCl)Ttw}hOYO`WMj%$ndo}aQ-o$zRQO=yLcurY{Ix13?TE02N zebMsD6t@k%cg7tUz2;;MBcy*UZ-CPo6ol8cj9@G29}6PwMB~t!lQoPmKC1_fqYc4U z#%*=2&D<+UnW1VJfof7##5m9ci0A?2(gWbJ*ovQQmZ8rO(Pzk|&%hc+;0~0xy~bg0 zExlGNcL`hZ^Utz1zVv1ho|_cEJNe0NM;$V&dGVf$nhQT3ul*m{jq(iaUTMkiv+S-_ zo+;M++)?`N2W#vusUXr5yz98fi$e}Sx((rIvAS=>H=1*}7 zwjmrXRdHJuP?9vA;{n_{1b{<96?Xt5f<(Xacj+H|mS+%|FT;+A#Kim%t}`>_>{I&qX5Mu4w;>x3@O&8OCF9t|Fgtz0hGs%~r5V2#V-JJzjyPnBhO9(8{n zZY5)}6`s@B$}`XDnU@+y;Q7-#FYK$__Em$&Vk?)^Jg|3j+q(_cxGeLK=qB+iJrA6Z z+|P$w$yjWKb5pCF!JN)usbK`pBfTZVInV8!H+U?zayiWdu_U)x(qN6t;=A0la+9Wc zAYSDjuiQ$;Vk^Y4S|ujt6cbAgBM=|yy&B?fZgIE4W3iRXX}xyAMdYg`uJC5!Q! zLGO>;?+>?$aXS2)6QfQ)wQ%9JN8%{mz}$E7o*E zB#ytFKPo)>WN1S;TC5Jf_x{?n8IRgLF4+A)!tn>xMdEmD%$LGa zk8BkW{@$=Lj9@E&^Oxqa)>B)D!#3JNy<$x#MB=z}N(e*V8`Xwzv{?Q5`ajhk`|4bq z$GD5O4|DrAivI|Q%wr8Br1q3LCvgnx-z|J_^?Gr=Prf*Y5o~2WWaAhzXOA#=_0OnR ztm%YE9JkNdHw^mW%54Zoi`A+#{$AT~<`11?$oTN#F+=01MQhDt4I`w|#$L90e6q{I z;ZN%<6JMMc#xR1d{EcFI9(&$!NO<9~LFyH2Iw8_Lrd&QLgdP4SU$HhA;j&mwUpK1{ zn$xg(EcpI6!ZK&QUi|Xc_ub7JMj(!8rkObYa?R0UhY61r&&;olVFX**yAb2J#h3j`csrc(X_swMuBc!8-d$B)p-1h2!hPTiCa`A`z2aRC_TiF}4 z{=tZ`B;n630Cw&JG`K^PW_14Mw;uR!bc*q`v&;zHJJu*=JlE!-2)43S zFb-QQ^@=r}5NRH__SM<`?g?MSkO)Uf(6EVT3(@n}_Y) zeAf2|-_2vOmF-I7u)V8Zv8EFu&0{3a;G)Tww;>!YR(3Xx<2IbZrw_a|-}5Ki`KeV6 zBkVlZY^_o($v-^w8jlQ$U@MCf#$mBUy<$x#MB;c8F>&V!kF_BjEmjsQjpJg(#BEM~ zI6rsVH$94~h7lGYZ63!Xw%2#~Ti$!w;CVb2TUpdLj^`2Emp$us^@=r}5NRGu?|N`} zcAaH{>?=mNELL`R8OJWTqn>?iP}t|=bNyCR4I}KnvU%KsyY}P%S~>hr?NGlt6~R_^ ziyFtuxNAQ?W~h3_nofu`k5!Q~e0=qKZ3st;mE{t~u{?5y6;}UDxc4XD^(;d*jIjK{ z=Yia3x%Wne=XSWpGZ{s&m1Q-?u@7>eX5U8Y6>B;n(mb9(4!86pTeTq^EmoG>8OJKf z;SStri}1VA7kk#H8b(+?XY=?Ya?$u?2>adhv}cxzU@OZqjbkQq(dh@&)hpI?LZo>} zPQB8hyR{)4EmoFm8^`v@sdu<@=kT*DE*QfaMp%Ar^Ee2#!53fNH*Eji!TpS2E6e(g z<7U(b2cDAt9TwJfLZo?Ejid8mgv(-OwU2R}f*R+)rydaYXq`HSt*pjT->V3#yaH8T zIu;|W3aclt&>fWOE?9R^syIckl~sN9bQ@R&sqCq&|~Dzy#aXtA>D)i}@{lu9^Q zcTg%})iA=UVw;Cm+rhenC4#N23O5d`=+!IMbV8(gSl6Hp;b^h4Zi3I_%NI&#B3O4& zIuoj4gmo!w9@hN`)*UPnY-L>$U9`f{70I~c4xSR&ZUx`qQB(t&i2e&=8W_{ul&+8vZGr_O`NVk?)^8MIES z&s@h6ja$jgv2NwNd+iQNw^pBrTM2@#tcz>&u#T`l^L~HkjKK3R-}Yyjb)D5K9*eD9 zPV=zNwjx;LvdjbfxP056W!62{^Wj!97F$_Y-R7}U>d^ZcZ2B2w1kPjmeE|OUF}(#) zuXrrBayiYz-ZUtJH7?6Mq?f8E z4z?j2Emp|-n&=K12fBk1-N9hp!BWErWM}j}1G<9|-N9hp!4kn%$Qk9Y0gVIQ!HDjl zdc~Sfh%^s$2P3+JZ3st;6|(Rqx`W1n?qHmY4B5JarG^oB7UdTnS%&UlM0YS)cd$gT z6>@m_`$*$JcQB$ms9v$A6C%w6-NA_NU>m~GVuh-xiSD3t3>hEM9SqhTEH#Y4*`Tj1 z&>f8E4hHKEmI$^&O(lP?Y8>beMsx?&E7o*EqVBP#Vd3NBf5iLJC~YHh{S>JU_^JY z4dLU86}kp3bO&u7sOTfQgSmAFOAR9s*Xb(@bO$54gSmAFO9We?=b&G8q-I8OGJ0D4dH09Lg%H0?x4*B9hQjhU~b*PQo{&zTj*N@bO$54gSmAFO9We? z2c%y>q-JpS44Nv`&Z>yjutC)!dmDK4s^UCx`TD=4wf25p!+3X zr&u=%-NA_NVBNZdC4#Nclamf*mga%(U_^J&dwr#*6C%w6-NA_Npjz@+F4H{v6NmiU z3Fr>CtUD-PsfH28XWd#`tCn>KO9WflDi{a4gR)lY6>B;n(mc=|jOY#)vKEYRS*&bd zHPbxM9gOG>7Sn}*xoIyJ6Iyv%66r3*xpsISknoS=7H{DM0c^wGYtx_y0tUFjD*vg`Waab%-uUOLwkvPyDjOY%wAsj7M z7I%#U-NA_NU}4=siK41ugvCdj2fBk1-NC}TgC&BkENUAEx`PqjLG_9?oe*gr=nh77 z2czsOMz}0ib`Kf{x`Pqj!D!t&)Ri0)t;!qH-7d7^QkI~dU&jMg2LtWPzJuzb$uf$m^LcQ9Iautczx zWtql-?qEcBP`zSJCq$Zu4bO+Td)^tLod036phH$i4Ssi5@=nh772cvWcS;GjccWfS3dHHu4 zQb*}nY-LqgD|vO_O1aL&-(7!)6j+&npaMZxjOo$C$Jqd5zH!04~ z`-XS&r| z7ablpzx3Xs0gg-FUAsQ*a}$+g_R*`<2Mzmy%JwG3p2zx!PYf3f{!Q`v)iVp$Anxkl z)XKO#QkMPn@*~3&$ImGqoLc2z1ixL*vitTrHf-_A_lk2D^NOu_MY8O3zda_bcIYL= zz8lY~tQ8}0!|C7GrkOu-;tAomCmmbdFul6EY{l!AWwV#tDQq@pm3SV!;wNQqNpyW) zeQ|~QM#Fw?Pw?6W+lMnwTQi>1m{G75Vxs)jUI)ZQ+3um|j-L3!34H~R#R&c~BFp|Z zcYHYh+INd{;1wg-il1hdEq}|tVf61mF0L6evtSJ)aQo=rTBo&I`x^&_i!Xb**z)AQ z3WBY8FJ#%iV>S)9JU%*}{nq#7M3uXp*Nwlp$+B@bZxNoIwXv=)YZ$TqbI;ccuKU%?2r!r9cnqfhgQD+~{3O{m2)emYZ5ZK+`dPHk=A)Z&~6I_D*V zt?W&TosS2`_Jm1a+dZB)v9DkaBM`gvUqVP;&BtH&uQGXDJov$x1#1|w(o@&hS}zT@ zSn`*t|H{K^`^Fni?5iNy%HEimS3kb&rF_)Q2gdxMzJfK3KwnG0xl3NXb;C3HakCGO zZ!MZxu!a$r{^s1;11GLwUX6eLH+lZ*Vetp2^i>dS#b57b*#U>$ns5B*k#XDo`U=)C z0$oG>qA_{3_xd;Ha~DpITh?Y3tYO5J?~bkgYvH=))y?~VKVSRgW8$OJ`YH&v;%_6f zZ0m4z{=$_f#Bc3^6GdNOG6FqW{a!SA^~Noe@?xDSah*$N6|7;zO;^1%_IC$vU|!v^ z|K|CqzLVnar}kA4Y{g%mX4zkF{&W4rS5Jv6?$B4Th7ss^>({u+tAB3%a((wfQ{#-R zuV4)$CLFic*wy+rG_Q`l>iGJ?&rOSiPOBo=ioffXEEoS;^0m{VL?6~L0&@QV#}W{w zmAxHkrFndN#LKN67M&8m4G#F;@2hCNceSc=eBsVNw>Ew2l(^&jvkKNQ!rl%T2WH;# znKOc|s$QMG?2W~?k4=te!z(=JrtdiH#HODK>qZ;LKWiLR2fWBF>f&SDFJ6?wXT(;u=5MJ>K-|84^Xy zT-38Z*%?&?Vq)Pjku{9q{1JcMf5tP#8;ygbWEqTLD}I_;HtkO@74Q7@z&P=1GYi%* z!rl(pS|KJD9upbCR=gMRFWSB}GT!@*ZQ?rH&ZuOTyl&Ns<*1j|iyw`u`OR6@AB?~a z*BrPxw_Y$h&Odc@yy%;HbCw9U@_Hwo!O#3|ix}o^9KSkyrf0}{voHcTwPeV4J6lfe z`L1-y6~R{33i2aVcL#iV%{cKJeUdGe^&lg>noM2|-D;=!!6U20-_4s@u!a%HiCP00 z8S<;>`4uDBs#>4#IceW`;8`CR(+}+{Si=af)st6~UKt|5t=>B+u65HU#XY~CRj`H; zsIOWBmDg7uJ|*ru`ps5>`TW0y zQ-P3p#R#^Nt||iK25BCG07qRAtYL)ljZGZl6*%hR6(iWH+NVa9iZ?%-e}+HjO~22vR$d@@_gi0*OnZNuv1_hsB0tY+T7~e62Vrs$BYAY zZA4w0TU}eOE+gy|7>AvY-0IpA!B)J|TGvL@wZZDzvddvHSjV;4WnQ7Kji_sb)wL3- z)yg7j2ZY7lV0EoTWF3nU7F}%~sB0tY+T7~e62VsdG_|gcsB3epYbCxa2O})H8i&Q* z-0IpA!B*8>g1R=Mt_@b#mhXP;#!)`Ios9!^ZA4wGtIHZj*ezb2)42u&Nxul7N~23)wSg}ER3)m-Vms33)Hp2>RSCuN4#Q$ z<@4s1)ds=p+7iK5mcttd>e>QzZLqqw{6dHkmcttYb!~yVHdtM&-$031jIav8yt3LL zSY2Bp*ve`H<3L^8LR}lIt}Va6VuV#;hCp50LR}lIt}VX`V}#Xk=9N`o!I}mfG1kmVhX&tU@*p)U|cgwZZCI=?>^vSfBDc!YT*q+B)jmV0CRd zE+eecHx8@lb>=)4TUEV6U7Mq>4OZ7mCq=!&PLy7c%GmAYm#6r*qrZJ?j=DBjU0Z6b zKck*t$CM*!T`N5q-Mg$|1om$ERcMx>uFX-`2CHk!vDgaFzg$DDYjf1K!Rp#l!wBou z*jianM)xj{#a6u1TGs~DwL!8a#1HAv>G~kTNe@wF>j7H4LR}kB*9NO=YyO=TBByi& z)rv>TGVAqeOk@os5EE+yU!I|^%~96|t7}WI*ovQ~*0nk6+F*5U`J5SHJwRJ4>-A|& z~3L7);2QVFw$5%xa8yt21T`UZ;;Y{lz_|1V>&j1Q<%bE#61N6FhB^$NL< z{yT@_6?>aysDuM5;anqD)t$0pZhAK6nO3kH8MSfoQ8V5PG zyiroG*jxOIK-V1;PzmQ!3A2U~$l>b)-(T5VGOs4enX?toDa%k51*$pAw|c0A>i(4t zswH|qi0Up#1u5~0HH<*jhxeQQg%B#pAXTcw5=O8Us!2tZRjP1k&B+=@7@t*l;+0gX zDT)q^#a6~`RjSS0>p_{JY8ZjqP*%h^c6#rmfQmksik`<}D}J(BhOR+C*C3a!0c#k6 zI;uYK<(a)v^vbK;C2YmdAA1*HQ$4tG`ddq>$z|PT72%;)#e2`Vyp+@G9Mn6~L$H<0iQ^A<92!6Rc&6I;RF3Y%H=_QVC2)1%Laoj!Qv+4%WDA99qdFjwK*UE1=8T zC(Gbf-RHp?mt|bcNh^SI9vu;E<#PEva(^DIaaqR2v(dUFao~A$M6i|1i37VN_kG10 zmt|b+G0n~sM>hmpxtut#+jBo3tZ`Y!#aYpsA#rp=u$9Y+1E)6lIcJT_GA_=%R!E7X z8-lG|P8^6n!Q&NcT$XVWyR@1}9NiFX<#OUc6b&ACS>v*dix{kxOycNkg85eiE zX0?f<8-lG|P8`TGg6AcyaaqPij-q*2;^>B8E0+@ovZdhp6>D6UaXo)b9NiFX<#OVX ze__M3KGwJ_<4WfIhr541GI4Z6u$9Xd4$UZ8<1)>ozrrDihFi&4=9OBxTv@9^A~tJW zmT_&}nu){KN)QdVlCjvz<-}o6P&ruRvW#ob-#7@-a4Q*$tz1qVwiA_uH7*N>?PKF0 zM8mCQEVgnvaoCAc4%WCV9CjX!gAfh3lCjvz<-}o;A+Kv z92Vh}gEcM-hs8(ZAVkBhWGuFFIdNE|Ru0yt;KxRs2>RxT$F%Vd;;H7*N>hmpxtut#+oe`h z4%WCVM3QgbQ?Yh0Fbahmmuw8YU3!B#FO4n!ZRot1+%F3Y%x zO8Wg(;^>B8E0+@oqNwx$l!G-c%eaWH(q|ZmyB!g1<#OV{Z6Li2{%javx^Zf*Jc!Z^Ai z*vjR^fhHs#mtJR8IPT=M^Jt$5hZVO4Td2;uTT8hWsWR>SH@lPS~0@z-3q$hE4Jblsd|Okmi--AQ9mi!E!itZfN!jPQLtnL zTk(oiy~55YJ1JOE>fC%9uNZ-6L%pQ|mbNEYTJeeu*vm7=DJpvw*nQL^`7~ZJ0{fV{ zI0GzIuh@!LWWZj$Ld?+jQL^qhsnm`5G+r?RXP){c11wdq*os$Vz+Swvahu|md1!aW zr}2srh>z5n7+|S-#a6r`1NP#TJp=X1d{^16mb`ZvVXII<%P3W^*os%g`4YnRYfISe zIakJAvR90-9aBNKd&O3~B2};KY^zsxCRBE-C40pPJA)N;yH{+*E8=_!VR2B$viMOM zcgbEc!Xi-x-R>1z@rqQv!feaR1XffDCA%ei#R%|~Ralk7f0D7-idV#K@sk6|YFuE1aS-+s5vr?Eceu#R%+Usy_x;s%Ma`ctr;6Wvvi1 e%DfgQmGbCM;}s)t<|)%3V5xe=R=grv_WuBrWLd!g literal 0 HcmV?d00001 diff --git a/GEMstack/knowledge/vehicle/model/meshes/e4/top_rack_link.STL b/GEMstack/knowledge/vehicle/model/meshes/e4/top_rack_link.STL new file mode 100644 index 0000000000000000000000000000000000000000..a55bd5397ee322aa4e0b121bf82dd2788cf173a3 GIT binary patch literal 13284 zcmbuFJ;-HO6^5^3F${vBmDr5hXb4(N3N7xvXk*YRCegwoBEb+4h4@#9h3rBLwXhMw zq_7cGQV8M{BHZtQfk^$A0N)&c=!H0=UzHoy!f+} zAAkJiCO>uM?FZTEQwdvz=FD;sXAl4U`$?<4+MA$;1Y+NXpp`v+^Uv=b7BS9L$1}HI zQ6`oTFMaKMDc^kZ4}FY6%?7bu`N5f}e~{sfpoWCys3S+A^=?@sWaaixzWCZK#y`J) z-%*vn{+|1fmX+1FK6D}5CHH+rjb+6!El)i`4GE9tqK+L2S}iIs^I0NaBrIRN__tXd z^hK-fzJjLB-SFGwh~3Yt!WduNe>>;Wz4sM~@YLw--lf$$-v6n=Bij?yka+sm!$~a1 zg9NS6-dDbZ-@&r_3N_6LYDjpc#oRsX>tH63hwZGWA>nw75!{iW6=vwH4r)lSzP=6; zvbcm-Y8{r9$aV)T|MrdjeL2Wo2Sd%Q~o8BUp!Gl^g>}imo+CdA_$xS8}9m zg&yrjQ+j_&ciqNrmwhEGR<3`SPD4WSf+(&-;~`%fb6Y7x%lh`GuY&}3qBb7&ew4mw zrJk1Gu8yLts3DY-fU$jDd#>&-{5;Y_s zSHf8_M&5-fU(Yeg+~Km0AnIC^hJM{HTBJYa$omrBi+KDQL)5gFNJB!hEIOiyPz-Ar z&pXkQpoYYDRwQWUmDa_GWa`ymysG6IbcUkct~P%Pt@2bPP5A9jNVcxyj@;P`ZPymv zh!CcoK^kPTBueF`oncO(7gl13Hes3BruUM6BP(j?7vtZ@IO1+8cF}ec${lr#H&pLq zjJ8rEs~OSO=0p^Ypkmk;<9T0^rxqg#YDjo}bVQ)jHL7MctuA?5oh5l4w1$2qyS-(l z80?eig;s6KidP5Pd$Q6RcZ*y~9M8YEHU-c|04tjb6f60|~ldY1P^ z42?mn7IG!lVvuOP5E;&5pz@ADPv3>06?$PtP(vc>Xmd$8}<%Boq}lV)YLH^J+m zWmT&kT$T%>P(woZb|RL2MS@mnPf~QPgBlW$?~Pbq2U`s1uC-0SZr7~b?f&)h<>9Y) z-Zm&VKNr#ScFTHF@RtXFwEx7NUmc#mc4@!c{U?Z5gLv%Mw;rH|#8X$U?4Q4O?Qs9Q zz7fQmZeAY#IL07BE6X*;8*g4dzA_Tme{tW*(ck;XTTb#TE4TmTBacRmH9{H^mTOi~ z$MLm@ar?;|56~B_{9GfR=)@|EzB=9-v!Z5=s83k_5!SCqf2nsJW1f3t*=pMDNKj*1 zHMw1K8^N3})wBG$hJkPHNfC$vM0;bRIuJYRKvn}a@Y^a^k7yL~Q(_$+ANlStbB-!^$@}v+ z4w9MSXkVctHFLsroh7lNay%GA`}sH?2e;SRu6Z>lq#dXt|phW853jXjfkMT;=D!itlcm(F^;m zBUda5`2yYb^pbEd&WWy$F2(cy=ywYGe*{ub5|N><#_WE zY($|3G{?NgDC2doXuY{lu!8q)kDdA?|N7KXq=tlL)l|(*aK5@)d4Z>?^6W2aNH|8l zeki4R9n#Rso)%fL@-1Sca`}SaHrrba_f?LEXTt_Di-BsJ-ylz@X+}_ko<2F=as)}x z%I#6dMhs~-h<%Q^E8o!<)%3OM_4g-u2oZ&(7$xoM*{JZnD$+sGkld%9hP<7mB*e?zIuBPx;^*NyTVN( z-)Bp!3_)jKt;QhHveK_Q)?-LRzngXB$%}PJ*7X(ic3-t>O^B{{GGkvA_)$2>bb%1WfdW1XL#CBHgU8-^y{pv#> z(CnFFC`87v2JuMrF-lmqdtA$!yOQNmvcB`$Q6#|XXj!8MVmTi6wII}2afjSzr8*Xb ztk6DXrSwQ-?)K{p>s|O*$K8lC6U$YLeW}|&&|b63`W1v4$!gPFf*b_yUfYUNbY2ZS z^XsYwk?TX%N<+eO-KjtN+_Psd)YHVkD}b${?S%7ZWcuMCu8#yYB%D?4D-hi;nqZaZ z16@(;9l*z?td7X4yKhIlxPCv&?y&IJuqOXQH-En_y&j9p1z;y%>bzBPKwa3P4#ivyL-ovs+6KC~0g87``r?+0X zN(~9$an!q|jb|C{zC>2`R7Y@)kcNIOR|3x&iYt`HvcCHmB&b;<)VAAwJl4l=>MY@} zP`duXc*F?CEYUjGOl*6t_CCjxU&iZVbUP=k+LMX;6bCWda|UThAYP1ld`kX}dmvk> zuWZGhuDx5W^|!S1d1&?+gZBJN?P*`~FV5%EV7A8dl zRb{IywY;?P$oJ=?X5bqoyko0%Bqx@d4PurR-?Br_Uk)gCnw;8HQc5MWc zP>VEc#G>*7UxQ`UVR~5yHEV?E%qss%^4n1PvMejV!E7-)LgW^)9V0aD?Q75}%ahvm zJ*^K%-y%f!gx-01q%12Fz6)CtYEd0)gy<#V8D~P7IL5LLYSswXp*Z@Kb`PiBC$6vg zY{9b6SJk%uT@tp!9+P{bsp%IGbHCbAP1{=EJwYq(!5yJH0O#J$%MnlKD4!s67d4f? zfM^=uO^QGrl_-_z30fh;Sqy6Cg!VDTn=+Dwd~-Z_^_llo-5n5PiQmDN`e~DBqGLt0hUs0#Q*>R literal 0 HcmV?d00001 diff --git a/GEMstack/knowledge/vehicle/model/meshes/e4/turnlight_fl_link.STL b/GEMstack/knowledge/vehicle/model/meshes/e4/turnlight_fl_link.STL new file mode 100755 index 0000000000000000000000000000000000000000..50888317f44b58a6d4bbc2c11b260186daa377d5 GIT binary patch literal 66884 zcmb`wdHh$?_CNkkgGeMpGNm#lvrN6uU`iCOA#b73B}8Q`QxOp^*HF||NyH^H8GFB8 z=Y&w^AsMcjD`Qy6$_5}Yfj4{#iYu{pReY6)uhe1%3Xunx_0|5nN)ePT^ot<->GjE zOTItB#ZU{;is0YFHaVtp?UMF_c>BtyiU%ePZiEQE^p5x|e{ZMhMc*4wa|pGB?egz* zYM;vfudORFemP=%G3=2u8zIz-2)%DU#++Sh%I4$xn=7X!yr#|CJXHDYM^k;j{t$g3Bi6BP4-mdJk;Q@^h>cw8&{_~v5Q|%S;pBWv>d28(B5TPYR zESmaS<*a7EB#c*6bKp5!l;tm(LxdJZ(C7CxzpY%b@I66n*rZ!ox8hEX5bDKVjp@6v z(&7CN1<`Wj-sL@W*K>FGFI`ru*6lhYq1T9$n^t?@^OW;aG~?CO^w0JvKP@+P2(^R= z{@v>9|5Q4?puIZcmfCXf&9-iYP_M?ly1wZ#W9n$vtLi7Mt1G`b z&GkxqOP`vWr{C^dzPoD6M%SST#@J?I%j&gXJt$W`b5DU3`i$GK`tYqAxnBMD{rc4#mejg-|MB{U)tf)sNMfve%o*iRFHCXQp%$VQ!M~q5 zb?xePb1xLcvtOT5jvf18BSh$>cf|MVliN-zw|)49M)yh)jB)p`YgNA=H(FwJz3}*Q zpW^*S2=yXD@0*V?_~vuUq~=(2<+Oy?^v2;GtJ5cbQtJ`3j~P+Ec57FM2rY`B*W8|+ zt8LEhD~J~T&M%)jZ-L8EAws>_tA*=yuAbIO5lOEL%Jql*!y!UTh*qv~L zi!Ug9Z-0~f)k2FRf?n18>sVvK1!a$~KdLbL|3K6S|1Jo*@`8A|T8EZva$XWo5OU?! zFgn{+L~!MTkSlM5kh}0ddc{$)&BHGgY)gJ;*DDz%6~>lv<^Hazxnt_ka-V^ZyX#O3 z(Td>TGL8jt?M`Qu_0QeZ2oZYe9bvqh8evqUd!-1*5T;2C8HtS$>P3X!Hy=YrySZ{& z!fTSzE-@tgI7Dbs1ksXx1R>d{Wb_cBUi^2-D}s>h;}D@GL`V)6gk)-m2rY_WuOuG} zLNawDgnF@8l7j^ync5*jONfyAA&4DkZ&&`d(=HAXS`@)vNxgETwWenF16|6__vDQb z>cw73wUZc9olCYQ6&Y2ab0U@6wX10Q)YM3Ib_lhE2>vZKSb8PZxe-FW8uvP19&r)z3tMrN*@(Zg$!8JWb88L~r!7DW&(^I$>947m|Pz1S<6 z`wBv4$PN)&LWIoQ1tBwihX^f-V6XTe#1h0M#fH_VUb>(WLcQ24{hR+=Qv*b*2>$( zLIi%N1gjT8;1|rW#&L+yq6l6ae$51HA3Pi>=?emk%CI(Yh|m%u zz?B5+4?$r4kzxJe5TQj8>=js$V2vXPtZ_1|aT+1ii@gH760DE}u^?F`$J)U01Gyx@ z8bGs8f)#}GQZ(b$)I7IKP2Ox=e`S=5&UV2fhv45}SArFp!~knEtkoJJ)T?o?j=ZHd z@3Gm|?mCdE6U??)&@D&1}=tL*sdb@H}YZWZ zXoLv8^p5x|M;6Vo#&HO>gzfTgWYh$!BDr#8>KyB+MhNvHLhqZ8fvT2c{b8=0mhhTT zA5*MeExtg&9YRwT~b$lgTk}Z-h`U_6l>m6f=E6VAhvoZJ=|X zWtI?u`CN+ihaj;2$j6O+&>=#LBG@a;;Zm$|1c5b9jx|mrgnF@8n9rqHAqfIAVKpXv%idRyyzg|$K6^Xrci{y(*Zh~RITw`2X0_uBp@*T?^X za9(;xd<^N8V~bkCcKJ7E{p_v8z-l6Y;=Bco5b8yQ-ZvjZ5Ey~W+HzMI_D~S+-!X^t zzhD-$We{vvenEG4mi>Z_5bDL2d+(E37|qtUnqdLNC1|J_gn}dGIuf71G@+MKFd`REZ%K z$HmaLLNETU_sz$Us%Ea7mhhUSs>zkhEW;r}iz0}YS%x5FmeB~IUhI|39|R$@42K9U zAwuRpg24JC!}`M^LW?5UE17Ev0&AQMYn(<1^U z{lS@~L#T!ADuRE@{83`a%(4+ey&CsQX8P_r^l3l67$5&D?S_BLOy9*&uMok%Wu`A^ ztUox@Z-fZF^p3E_ni`quJA_)ocKNr==Ou>B^cx}6iwM1Mj4*0hZ?1lF2`m%phY!A~ z!oLsNVjaBmxW)ZV&zhQRHsgO=1pkGW|Ao-G&+-w((o4`-``l9Dzgfg)ZMxyv{bkOp zNt-qBHe>9c=v9aqw#kR}*Dkr?f5c!^y$Jk6t;1-jT+=l9AzhC3n>Qtt~Z1sD*tG5%Sx(yS)5f zsTa|DM;gZv7P+3t==&4B3K24n|Dadu#a`(hY1}KxQLZPFyZ%J4LWFSs4|=6u?3Lb; z#=SzjwaB8bC+H!w+MnoEjL`RA%l`%01A4JndPf@f3cmrKMqK8+(04rX82cxB6(VpK zYLP|%_+B|L_Db(a<6dFBCdi_$C-|N5EaR9z(W?-F5rbzL=lwyi)Qi2+JJPsU;C6y6 z>X-^nB*>zFqE{gT>~gcs#xeLWT5;5iz0x~EtNqQ9GZJJ`mpSEcmr?2Yf6AgnI|TAo zf-L&S`O0~*S9(Vn$@WUFwi0;N^KW|oaj&FZhmc+X z=O6bfM96PbAd*~f$+$+gAt|!9O zKhdiYA(`P1dZk|MmEIB8tCIg6{s;4qD*r#`zTAuB{`Pj6i!K)tddbY$p+^~nthSs* z);Rx%7&?AJgse;cM~tv1q1W8uR=ul)X2v0?U`OB z{I~FqSVXv94p;PHOBNAYLWDklpnds>&?~$njS*l}%C>Yh$-n)7{^(wX2wjB}**J#Y z_s}c6BNhS6vOQ@)xZQNpCH&7H^(sW5hi=E-|97uKFM8@7vAx1wbbF)dfx8>*x#GY4 zQLjP-e$8e3$ZQO@q-}*>;T^FEjJRbxXfR%boktBVS%eEA{S6Tq`EHjL?aN1mUf~_F z2=Q`!mKg5uFt$a6mJlJ==Vt)R%?zPect>muxuY&4%kS|gdKDt%${pIq2(Kgb3h#(T z$mnyulCkUl4qLK_&=MkKlsNSA5usPZ9l5J#UE1x?L$lploLgf2>ocS(|JJv?kG4N7 zDZ8zmbU$rF#8`dnx-|Xzu59{Kr#ghbuO&j?#1hec_EE{VEAV~o{JwSR;k{erO)o#( zA;Nc?`i75)f!{xvY~70QRcpJ|rJsM^G5_q%9u5({6V!K*L^L_{)#TH&f5Pw4erR1f zWlGO{`Xe12B78HdZ~ln*>*N*EZ_a)ahDE(!Jk1=+qZ&R1zoor?k_Ec0incbX_`sg^~IEF>T$u2|>8`QTiq(h*4Wpv)#^h>9|G1@*5^z z;Sl=9gx8_(LWsES*Y(nYFLqCAYStNEmu|9jKt61fMGg_ZUC`(FM09S}I(>WIEkL}x zM_u~$CI{v-hOC*h-SEl3KK~{{?k*4uad*4l)jeN)_tp-f&((?6=j}v%_2Jja6X$&Z z#Poyf(up0~=ChwZ$RWb_2Kro_2pJ`5P0gd*)uppKeVOgi<5-8#C)1fqUil z8#4y@;dT-e0e)1#58PehM+ts71bz>kG;0F-Gj}rXQQQ~%z5&?d= zovTEEA64)J2;oNwe&|SCwo?{k*XzDi2+6lKT7b!A;1szicd7j5ANTsFb4Qh1wSgw_)&r%4gr4f z${hmy0F$RV1o%+}KY$Q^l;B6ncEJzsH+BfQyAC0D7YN};34S<){2mSgesG_*Lx3L@ z@B;|pM+ts7g#6|%ugEB=@;YRcRG0Ci06!c8{NT892=Ig70yqTtQ2{@I5PlTkheLoL z9J>x7qun9E4~}*q4*%x`d6zGqsqg)GpDI^z^3+LJknSDAmc`;^!ymV)KXKa%uH(HM z&d*O8eO=|@YhJ5{7NW6&T!y&#*?a33^?MA6HiOU2_kUt(rMBh*Z_o8-N1 zde(o@>-!pK9;_DWhm!Ty_JYCbIa^o7T&MTkZHLu_Q z^Xiz7Y7K&D^=iKBgURSyF0VguyETCLA?uhww4`0pYs)>$&=MnhJk+wX^A6mxm0jN| zuU^r#=-Z}`K@hE8d+t9uIpu?^>pQ*YW*MDo@?mqk6vtn3co|w^#K6y1tsGcc8!?`^ z^p))A8LJgNRy@HVh*qy#uDm!|`Lyfmmy{gsgCBY{TQGFzV%O0pm7yg@v^#Z;%EOne z2SoqJFV4mvv`%r=erFm4(dtFkj_E$3{@0m&u5n?PL$kW8b}O!YY*-muVua=3uyc2< zHs5l7LKcP3@$vkM@1_!t{1$89S{ZP5ns^S5oc3UK)Bm27h8Chj#E73KR3`8HS0Kp2 zm%i>+bm{SdK@hE89Qnsp9OYT^Z4q^x} ziu<14-5`ioFOK}94|u6EXP2Qskb}kQcNZ@_G$;!#G2$<4m6h?kUj+m?_~Y|$6&=T4 zY7j)L7f1eny*{e+XnPS5Z-IkdyMI=!^~U5Zw8V&;?|h~5VBbkVkb}=3)3TiR!<_~} zw0d#mkJ{zC%G9^60OCk+@XDiGm*@UCD+?_#qQ&7KR`zdxI}qgHbxk{#LpFcTAc$5k zj{J^?)l}zicO4Mq;7?sPE}uU7!z{GKh-uYtDlh+fKM>^LyASMGzA@lagCJVHIP!Pi zyhU}NFD3#p9~|80tDVX=d;Xk-mKf3c;vXwVH+>w4C&9t17xXBv{_l?lL9}{tY#gXL%!7OYm^y0`z9jrwi1VZXyiaO{RrIr|h3RjCd2!zzZ6m`%b*sgkUR^gGXb@~yy*Tnw2WwFW(`9uqMIFpTON>B;t3@3| z45@=D>YzaotzI1YsDrhrgNPw@Fhd>8LraW6g-cKefsi_wq7E7a(dxyKk2+Y3ItYZ+ z!3=dU4=phQ6)r&?1VZXyhB{~vM5`A^KI&jC>L3v0AnIU-I+%x+7=a3xpbi2dbudF6 zGzg;Aiz6R(uoiU?2&sb^>Y!tkT4Dq$T!K0Xgw(+dbY$s8swGCC!X>DKKu8_T zPzMcy?Wz|?KI&kCItYZ+!3=e<2rV%J6)r&?1VZXyhB{~vM5`A^KI&kCItYZ+!3=e< z2rV%J6)r&?1VZXyhB{~vM5`A^KI&kCItYZ+!3=e<2rV%J6)r&?1VZXyjyh-%M5`A^ zKI&kCItYZ+!5nq42rV%J6)r&?1VZXyjyh-%M5`A^KI&kKItYZ+!5nq42rV%J6)r&? z1VZXyjyh-%M5`A^KI&kKItYZ+!5nq42rV%J6)r&?1VZXyjyh-%M5`A^KI&kKItYZ+ z!5nq43@tGN6)r^`1VZXyjyh-%M5~unJ3jXTLh4|SI_T!2@Kg6*moM?PDc zv&%xnxCnF6btivUIsUYl9i!9|BN|qa{fSbi4hGeNOEwS?`KvHetRQ>V7uzYkTJe*fxMcW>cVcWQ|d z4J$};@YE$AR{ru!Y7lH!y*TpO(){h#L=19p+V-baFWhr)x4KhHjA&Rvl7o9ZR#Uz0 z^g4rJyXwV}&zAQ2g5MR9gZJ)!X?4KQ{oLwKEis~D1xXIB`+V!_>eB`p1lv_Fj(oOs z(>#73#X5NU^<%5s?l#mhN-Z&>VFgJJo^f=$>cG{{G6=S-UgRKKdV3zf3?m2M>pijh z>22pY4yq+aG^`*m9yvd~XXg#7ElxP!Af&#!bta!uu_gR3VqA89UD{)ZDb?RT@?W2+ zB}T}8SRfc<($Kw%n_u?5($y&24WAS>^lICa>e5{v-n#halk;4!)Dj~2w>)7*jGMaG zr5z7nu^4^)$VLeDBBG&J!LwKQ{7Rm;y60E=EQ{A9&t4H@%IWjd`m6s@T=4JHT@1Cb z-4LPIhj(Q7JyyNbt3t6uzVlIcfOR@siv8T#Qj|F!?c#gbk9C{as{(B}a) zH78?SHNW!O;@FADx>2GCwyRzoV@EDLq;ki#d~(OJ`(V>^i#vJ`aAQ|3F+!hf)YQBI zer){un4*7&LkxoLsu#J^tmswwe0OGs92{)YX<+g3%Lh0PswGC~^BK?c>DQcA9DiDB z5Nuby$ob9(=auURHAM{Ol0}ny6$hj{yIi7{7@^OZe7<`BZ+|Jeuh-ci*sgjpcRl*u zc9ouIeqZtPk~cT#TAa1TdM+obB}VA;GM{%x4%xi8WOg%yV7uzY9K6c+ohpmp;nP~? z_Uhmji=)OZb-7(FF+!jF`TDWXF+W#}Bc3q`wyR#OCAUA+wzA^oa}k5{#GU8Qs@^~6 zepjQ^5+n5arLTkMKXYUC=G#UX1lv_F*2KjVn^bme#V_1gYwz8qU-h)Z_II^bEipo$ z!}@yOrPq?mGxJ_>^;{8bSG`!U2w=djY2WJ`Y9o?l`f5>dps~B;{>RVLSIcU0E`R1)|tUh&h4|C;gSH0}- z!CA(nqu#8}dG<7OcVomy7w%Ts_>NM3!7X2DS$y&9bc0~K>Sf0jXBk%x+@jc^teR00 zBi?-d(8_Ng%|i^1#Jiu&i_KQ~#vs_PdRcyOroY>_#}(t3{_5uK%8wZF-Kas8x6b|? zF*wV(x#{V}$W7O3#1HkdJm)N9&VQ~f-urny!&>$vL~POeyvk1B@(nLD!`v;dE*{-* zTZ3S`>Sgm4XBl@bo>olXbVrkYV#K%2E~$(h+6>u;vy6*gzPUK_DL*gK499lW%jR9q zGM-=fNO8*h`P2VYU#xj?UxQ$~>SgN(XBm&2_;hi@jfb0R z5F;KKesyK&yj2l{vy5-&%q(tRc$`77UG=hc@FG;T0nJ`67X5atscJEz;aw4D0BuIj zDq77r*&x`ida;UX4feB)H%Gr-j4V$y)j3A!yD7}!{LTTs8FdJK&&782Z5GiD@4O}t znV)_&;^(5-9sOOe)Dk1KhrXUS>Di=gacZ4GguUWjSoev9a4dI&~j*>P0{!#Itm-cg`L@hBwM~t8E zZhY;h#jPKw1`&=Dj>`V;-%{D(<{!W)j`la+d#U)MMdJ9OmKdQU-`DdK7rao+J#hc8?Y(PTAD4RxL3?8SLx%_TBC;E-Km@M95lZiQ^YvRk@+> z+me0ezB;k!vSDkNebf>oG_Ux2zT?(c7hitA&}BG9gxQDL?!E;VRa&)t7BOZZix#7X z75g6eq06Fbi4mGn{WF=?`yX12$2ZksTVWPu*8b;1Cs$@|!|%^o&&MCRO>y&QQ(ZMs zON`LU;OqIdEmkc4ee1CX5mp0MpRH>Tth~D46vSXX@Ab~yYUlN9T~$*{jL-__>v@k? z4y~@x^>J4@6%kf7R#EIpcHd_C>U>2ytFr!axvS1QbJ@e--iGUYZn8`E zGvGR&KY4!o?x^Hkd(BFrCT*U6hcTRE@p8^o9eo^Siyisci1GRIoA z#0cfTpSQQaYQ^%LL$@)AFn>69jV>ykSNQ}n$n)Pj{8S7nw|1=kRxB|>`R{o?XRXD> zl71T)M3_Iwu7PuARI0o42@9)p&%eD}?ET)ljA&N808d}h&WtEP_UYKalbX3z8WzMo$F{^+}o=ZXmP2idjfMmJPe9r*}i zaJF>X(s9MVu6V_sjDl>OCM!fO+q{_uxjgwz+>6>R3KOJ_NL9ku*vg3+R=-Vy1rueSQ^=6dBh{yN7 zr?TI<(-4CrvFDa|6{j!pGkqP2Y*)Q3KR9o{dB~H+_vb%rMth97c9&}9;7ho=BcuLX z|7J1vYhMRLeyEq_Ip^(NJ1;6aeEYq7-mW}nPeR1Ir#@eKauL@!%nTEo{9e>FYu$+F z>Sgm4=k5Fdx^j8=wyT=#!=8kQAFhA1vdX~c5rY}-?Ivx?pVsYQ5NubyY~JP5kHdaj zw>)6bh9--~h=Y&(sIp`-*HN62Reo5%{AbUt41(>dm#rUsiqmWB&B`0=w=mTpM)V#1 zd1XNVe<21d&Yr8`gqv-4HVC$>UbYT$-u_y)P1)wH?M+pS5e@suIB$QYb=R`zwTVHn zUG-uW)f!w=b2*+4e)Y@tG3HH!2wBT4Av<6YgW2bhrr#AO?>W!qE49Q3%`3j1ue$eJ z#a`p?Gl($zFx$ya9>ic4y=e7W#h@4OaCuiPF+ww{e-78X_szvW4;gI`VHRc9mK{lm z!Fs;s;LD5JlTUZmKrJysD}%4+uT}ReKCj=*Ai`?E>LWX=5QA0ixi>Z}u0No)t7>YA z5nADVJwN%mY1J1_x!hGwMTAw2RaEwSA%=T@K4-n^-aoZ<)mbeuLMt`SxXbF&CQXhk zKmNF>`RTRq^eIQ(+sd(4Eipp*@8|8S&pxDle^PUU2=fQo zB|C(09enz+-n`!Bj*DA4)~Y2&DE~dr`>fKdTw$}{i?A*JtzKl8>~unmr%(-Ud~mn& zn-iNk)~Y2&DF6NXeC5My%d?*UTHo+;*Hk6UA7q#8*g_2Q{LojoEl=KQvA%caUam$6 zWwYn`jFy|18%>&L5MllxyJY7XVz4@IKYso4gDIZ1YKalbe?M>kY7r)kkord)Yt<4Xl>eURv$p%HsP??xAj14XcF9ga#30XK?f+Ww zOTTL!Yt<4Xl>eUR?a#QcIBv+%1`*~DvP*U}A_jRr<(l!u-X9$3SgV#8q5SteKV{xg z#r^YEHHa{OkX^Df6EVp1VOwlneE8a8Ki~CxHY+hg+3a~PdpQjv%pc^r>+=rh zA67mv`Xz%1IZr-*pRQV+J7gGQaMri`>;uYi`@Z8?tCkp{{P*?z{MUPyGae`nBFrCT zS10VHo;LR+#30WHRMYaz(Q_PY)e<8bG6QGGozor4+Rg4Zh%kSUU5}htQ=NQuf5afq z^H!Ue+rIRGW35_Zg!13l^Ov)A%OeI{XAoijAiJ8qzp%3Q8V4W-c|LfTRm)dqj(4n8 zON>zdd!FyK=;z|Kg{K)rm_Nv_9jotD?s+&t4Dx*bs~;89zC6XTRxL3?`R{ptVQqa; zv-OS!5#|rF>%(tmSKj`#3u2JxuiSNW(QVY0jLxdmZf6-e1kBzPfu`)2kS9-$f5s-tPA{zQ^H} zHy_`lxc95c2ElgKE4+vP?r#6oImNJT?lX5cMob*`V&#dImm&s#!2>4TSuB3Ox%maz zu6o&V#rJBDoj1GacV0^~N@B#Eoj$GXbz4griEHk%uz2jzJI{pAM1cGb(~s~?elR&Ab?M;(2k$v!cn^^dKq&#tfqVlcz~eVu*E zgV&v85NubyY~JPie6xuMmHXFRW3p(B*yDsXtA{_j9b#}s)^_D1%E_4Nhi&n1^|JMY z@6|qS{?~HIT9ZsQh!GEN(7w86znu|-73cFw$Cqy&_MkzqUG)m9onNKSe1C9x?qRo> zsum*}zCPpnyxGVh<%shhH3+t=UaX>8gZ=vak@rt4Z<%nLsm?J%zjiZU>N$jbo#(!y z)9>SmZup9B@JaL2n+Bg%9=7xp*DJNKCm}+6=<9jA2hJ>;pWnwI!d~$%G&x~|>N73h z2WxqEKRN!C@}JwB-RQ@@b2>0eBr8fst4`xCSq`}^D6!S zTAttbBsWUb5+iiP_<8$QSM)8Pd@M1DaFlRVp8M_U)%)Ln5ivO0o0NYk&)D`bH`>(_ zBXs2Zd3&2Z_9%D0uZuy1qn+%ke{7}dLp`2E4A%3#n(b0Pze4UW;lKO z&B~|GX=@N6Yndemu2WMz=YfY1gV|@`?Dfi}ojbYgqm~$noMVYl%+UfO5 ziyyB;3|51kyFF0+e9cT(KhzQ=`L&dJkm=B>7A=hw7;htce)p`RYr~EI&D{g=4K+VubSF@3UO*l_BN&Q)X7fw)nStkzL#V zbKUAY8?-?T&fEJhTa-)hyVM|vRxh$^(c4X`Uo`!0rsw&vlRK2tPkz9$RxL3?`R{qY-}sfw z@1H)(AVSWQU6Wq@rn3D_?;!@?pWom8*W!uq|L$0;mKdS@_dLJr>z9fjAKBa>Le7(2 zd#*RXvd@@j5raIRe)7Xbzm^9$)~Y2&DE~drN8UKP*k!f%+zML}Vg4Yy4%)O@8NS#3 zh(Vs;cf`TPZnaAtYt<4Xl+B*!U5}bqT|91Yg9!5nc`oNbA_jTB+E)ixH+gDJ$8)vB z2<5*=?D6uU)id&*dKwx}+0^sl+=-j^Iyi6d@yZ+6X;M=YT7sT*5B|Nozw*Ca*r!Nd zn(fvAdgY;){XO_zt!JN$i{JL@SsPlGgFp=af-7$GXz}g!Z5sU^^4oN` z^1a%>`kq_vIBh}_T9$)A49?rvz2f|G=;=4PlN+>h255JRi`HPjAMX1bE+}sqabv>z zs+Q#-5FR6=c(!jx6_o^&5i-M+rxz)LkGr+M7)|w0xuH)-<%l2$=x@!Fryx?opmT zWu8HVqn+%Mx(fvB`GDQhveU)aq@g872%CZ6ihkgxhE5=tz2HT-#CK^vk$YKRA5 zWhGf{C&-Bn>vP9iwUFl_Liz9K?PD)Iy-Wt2V-O+d$u3!KBL?5AeRJ1odNig^)m>f z)r;(s)iz>~=RZGpP`UnX-LlXUBN{RTpSSnCWw-Lmb$S>C(dtEZ$!Z%h$n&qTb6}O* zJ7l3HMl@swuFpSzYm@T&-MbhB(dtEZ$!Z%h$n%!RZBVXTZIOkR7}1a!$n$4^ZBdTi zb0vcyTD{0FS#2W*d4A41KNr8P{Dxz#T4F>)W^i99+%dO!;??I3BFqwGm#nsh=a26@ zqxj~y368aDi4ihy2ZA%p+7m_v2zj4?UyvED=J|b# z882R95bTwD+24bAcgf9X6(c{HY3^=}koO{p!Aw2o-g}C(rhZ`%Y*)SPxMDTfV8D~b z4=b;kg_am0?{{P*-nGkj#eMI0HVC5CD`bJMYP+qoLU~Q|o@TVi2zgJ17-ZD>C#_Q+ z{^bD%!FJUvWHV-#VC|l-bSRJ8XqaJbjF9(jh{4RT^p_pV13x*_AlR;Yg;~iz9XxsR zuI21WSDEY+BjmjyVlcz~vmWU^?CkoTX6!A$*d z&;I4y-^LpR+f^@HKUfXM{`aWz$=P?AY7isjJuYH!-hT5>gUT6i-DD7KSG`z$wA%US z?O#nDRA!q!WU5+>XgIZw^Y*L%eQNp1tXmC&?Wz~6sMcWry#3QrL(5+69y8TBM(8Pd z=0rJ%kbN?)p3B>CSI^}=H?CaYpZ`AkUDqqMuqPoxd+6)=nG^b#+id-XL4>{HU68lo zh{1Y($OcE3$F+OI-CecB2))z({rN^09a2so@V-HWcbC7WybVVTuI?5zJEYv{h`DZ* zs3k_|i1E+iF5YpkvbOz81`&=Dj>?9UjX2uZeth@x_J2O+M!Q;KgpPdAs9)CDw!Erp z5#eYjyX0*+u7hvMzPO`n`RNJM9Bb7QBb32@-hSkicICcrPBDm(wagOoHXJdSeR>U8 zy}V_Uzq#zAmKdR#$Y;2_KU`WI(CR{i2(u5foxBZ44A%4g+Ab)rt~t_WQMJSf&8Yr4 z+^n-7E5>ZOn?ZzGlv!Keb0Y?;!74LvD{eS^{VcS^2(1jho_AgUx`!(DY&ON`J;js0-Q zB`YmFs61_@HaS@&yVxAh!&5eu%{4U-52{O_opETn`GKoAgj&dRMeuLgO@}MLxM9y- zBZPVpp*hB!HJQ^Q`*dBe^c+z3R`%8+Mz9;##ZU{;AwsXuXP-^#lk(*&H#UgyE|BxG zw-zy&+b_Cww{qG>>*b*(M#%mYiip( zw8RM6r3VC86LUA)tjsT2-5`ioFLGY?)&jxoGiArk%B@GY$U{qvkX?E}a5ZtuifflQ zj#$AUh*mFhUiQ`k!8yZg+pbx*-)f=DC2ENgvP%yLJ~jBu&P~c2M}BA!Y*)R=dD&YF z1hdb9ZGI^>K6kFmC2ENgvP%yLt|q1qf35iPf=3L3?Wz|!FMDf&;9G$96P_)`&%ep# z61Bt#*`)^r=ZUKvc4P7DN|zY~+f^@eUiQ`k!R)h5?bXG%V~=y$M=dczcIg4Z`EG~m zKE=8hZfOu~SG~x2*;@+)v(LY(n-&8O&Xn^D~V&BF%4cGb)BgQNYNcj}98AAHe__81}G&>#jG^}$ac72oag zZ-ZdF>ScM()x_|dJ}bul^k2i;7$INXAOW!@>SgO7pM|$MV)L@a z;k%lu79$$Y+2(5E%>B17$Ijf*AlR;Yg*Di}1!(tr*K$nn)Kupfq33#=lb{_!&j@F` zdJ;I%^6hJCzLs^pQcH}`9{PH|*@LT>W2f~th_F|@3-awNV({+%}qBAyLWM;L@hBwM~okdo!d1juiT`Y zL4>1(qf)+omC-)(UYwA2dKWj^)e<9g z&awbM^z@6Scl39xRZEOe{(GL!==@#LajPQ@BFrCTmz-rGJm2c^-;3X-9O783mKdS@ z_nCUst_zA6IvivWVg4Yy9@t&ZTE4kRZEOe{`;o}mra^q?EdBM1`*~D z$1Z=?3u3UUZJ)khd@z1z$67h%!o4fhc5PLnpNz!a4Uldy~r*(%L2bSdH#N@ zr;E-LIyu&=B}OR!JRkmqMMy}f95!%BH*i4n?w&-3k% zxU^V!&SJ-NZHs92BD>@)3&bGLANu&>;`HI~IM%8qMkxP1&xhaEtN7_QKfh8$m_Nua zIm-eu$n&$YoAKKLlO1c-5+juVp69>b+@$#ViQ^3-%pYWzoMnL+-e&Kkoh%kSU=W><>Vvy(ZRlMW5T4IFq-y`I_41-|1!~7{(Zr-l3eXry+ zE7PkOA!l#Nm49^ejOyR--_2Y(d!=6X_u#y}^`hsi+vR7PyBj0q)G_%5FFCP&am%28 z8U))_FFUR{Z=cYQAvr8gGO zeY2%OuwC`C`HD{s9%?qBnEfA{uVRFpS%nxpuWzOGA1p4-{b|#h;n=Qv*}TiAAFp@3 zqnNhZ{w9mY2svF)GWFFTJW(9@R3C$2yXs}@2cP29toLv+r(=Ip4Pu0xd59RCS-$(P z7m67z2N(p~RWDW_t#-buy*jyCEGSPfRV_v|Xz*~}zSeWE71z(Q2)3(UtfE?j{k(n9 zsZSJ_-Zt1&=NO@yKSo`}Ayhwz?aEn`uAa*&lDP7l8cwHl*P)gep*{5PKQ6pvOmXzK zrx`@pE8Yb;MN;l=pIs*uN1Sl7ySr+M5qhV6J-_(!QN_-i9&Zrg-Q}+-r${0O=k2F- zxw=>~?kG1()Dk0f#Q1vNe)iB}-BS)Vh;Wo}RLUumh{4gm=h)FjzSn-PI;$l{=*ai; z_Rq%E6(fh|1`&>SvP({pL=3X_+!2F{r@ratSgV#8p$zuV;d*VbYq4a`#s(3xmRUkh zkwo_CgY45~oxO{zH)-#(k6L1cW+GqD-(Ig>ab%ko1`%c-W;;1W5;0iMkAG`}V*6bd zyDX}f7@--}KZkqc#gD7UZaBvv!YsZ&D&K!jO>yVa51h%ty;+Q5TX3{ zJpXBz^@?};pJfniSG~wCIa3%h__pt|wezCYgwq{s)e<9=|DNaVhp$gY1$sw-JN0jH!G7Qr+*}4IFFL5+juVp65?bzpvW-3P00VM3_IwE;&0~ zcs^zFoa(H~&yKZfi4n?w&-31gU0m&W_=^S+<`1$<&OjHQAHUMI)%qJ}IM%8qMkxP1 z&#$_sYxVW<%T!6~saF!_53)W%v;zh{oyoU=%B7tA+bl z$DF#6LHMimUY6&4OEzWUhn1C^bv3Mw5sZP;@g*~y)b+ILUq`0~!FJWl<|{rmxbmTz z>Y;bzsaI8f@qwMj~L9< z`;Q%4U2*L}2ElgK%hnHmEjz1UyXv8{hni{-BZ$W7_=v%ZQ|vpj`q}xz4T9~em#u?* z-rjAe4XR7Gw{EfQ#2IMx!uaT_C$k88aelxSKc(6lfJ$sf)uWS4)615Jwr znih_=j6puf2-Fo(gCftNX^}wF!XPAnIIoahzN$gfB88@fV=ZHl&oKhkPSl`SIiYEh zK-0n?*sgko?DEwanieTEEgWkZgM5w=sPm!*#TfuJEfQ#27=+{x=M}Qc&oZECkwVkL zv6eB&=NN(cil{-6=g_oBp=n_dl0TeR$S%Jsf~G|ZO$*0b#vq?#1m<0$21TAj(;|hY zg+WOEa9$z1mT6j~(6n%@WeoB;MqvIZYEa}kG%ZqSS{Q`n59bxK%g}8~NTF$A5RyNf7kSQ>JZnYMB88@f+^+_6l?O+IQ-xY9*Q$88j^#A=HbAhF%4F z+wMB>JR!MuNqg5TJT*w5&+2-GX8_dOMhwxk$e?NAVyK1fh6uer|GWg678x`x41)Jc zz4+VU89)L}3&h|v8E9H$(6n&BxmscbRuiHC#^*lJw8)@oVGwLry*S433?PA~1!8dQ zLenCHriB~3YKak8O^A{ipI<@KB7>%dL9ku*B3JMXAc3X@Vu+?i22BgcLAAsPtR_T} zjnCnrX^}zG!XVhLdXe*Z29QA00x_6NplOjo)57HvwZsUlCPZ0|s|jdYWYDxQ2)3(U z%w2c}kU-M{qn*0(;|hYg{x6&i4j;$ zh+-ky05m-%#@*;Qd;Hg0ZO$%4g z6~T7Zi?tok0BWyYasy&;&VbcK0!<4yXHZLwz-q!NJuZ9BkU-PIAlNS6AtZMV8tZDi z#`d!eyah<1X<>R5Bk_PJ~Ev<#XSCi}z)JnK)OX@Ts+Sq3yMGH6;D1lv_Fn|DRiB7>%d z$)Yg=Z)Fo`T1cjbrbPx#3xi<0>SgPPXj){@v@q2mM&Rvo0!<6V;4A~078x`x41(>d z7psp}JIr3Ont-N7w&=HGO;w8#cyEwE{~R$m%Yddu22BftV7uzYDylWuuO^^rkwMeK zROc9h_Xc2aTf`7eiyWF34uRb}$!8z8)VKNx6xv-q$2sHhmmACpCG%Z}O)WV)% zAHXt%_R!aJXjFCKOKaoMFvd^g9z^~ ze@(ngPqrG;1Tk38p=psp)547swZsS=F@C-aO^Xbg76uWH5{^pj(Mh0b0Y-7OL(?LI zriB~rYKaj#^8LIWnid%}Ees+Y?PM3;(I?Qf5Y|G|B7>%dW35_ZgfbYjC1eI@T4d0) zFo=+~%o2F}oG_S_|( zp3Q0?nie@UEgWmrLY{{R<-g}SG%a#yS{MXbt6pRm_S_}Vv_K5b+o5TZL({^sRxL3? z`R{oSO^Y0w76uXK53&n;?hVubSF^BkHM88j^nBFrCT7xvsG(6m4dR%d8hWYDy5tW`^l zQ2zV3ebBVXplM+cVg4Yyu;(s;rUhbfmH|zR44M{>=W2-&%74#uXj){@v~WCEM3_Iw zF6_BWplN{^oGn4qB7>%dW35_Zg!13>9GVsxG%XAw%pYVI_S_}Vv_K5<9GVsxG%Xx! z)e<9=|DNa2w8)@oVGv>dAiJ>VE`g>6Vvy(1v`C?8;dri=7@=(TJjX7*6q*)}=ZXmP z2YHS?ci`rEh(VrX_f7&$3&(S{#0cfTM_^xH3QY@xV7u6}pLBTt7&mX%*uGcTb)Q1h z!t^ReV4r>hO$)hlXj){@v@loBUa6P;JveWNrbPx#3v+j41oqY^(6o?W5SkVlG%XB* z?W&g@S9}WqO^Xbg7G{*h2z=#{K+^&-I1-_0kwMeKAlR;YS$=Td4o!;;nigiX#|V6_ zl0ee}F~}%rT4d0)FbKA*UY6&q&d{{TplRWD-7C*y1irdSplN{^%nZ=9$e?M_i0A5M z^A+dq(6q>*X<@PtdlDk>T~Pu}3&dcCgQi6eO$&oyyXs~0E}wot(;|nag~_5Z0^dg^ z(6m4d&d8u?kweqMAlR;Y+4{k!IMB4np=n{NL5#q6UI{cU5Q7y5nie@UEewL~su!z| zRy#j$ho(giO$$@iVg$ZQOP)B7PbN5Tho(giO$&oyyXwU%sx^3-rbP}-3saqA1iqC6 zgFi%!_CxE^DN}mp(;w;J5coPT?S0Qv`W0Q$>4o>)H@x^JF8${0CxMW!=yGUUxL&D+ zJ;7IW%MjW_|6CNB7CAI63?l3m?*hJdqo%jqU1(b5(6n%OS1mC@@3h}_4^4|4nid8T z-d+Bh_}Y!yv5U+AO^Y0w z76uWrmRSN{yHWEVF_?XzX^}zG!et+|#0bqqzMezVB7>%dL4?_d*$!X3CF6I$3Ne^P zp=psp)52v@wZsU`sQx_;G%Ye{S{Ou_MVYnnwOcZx?I^@xJ%^@622BfB4b&1Nv@-a5 z4o!;;nid8TRs&WaeC?J@-uJJF!Fmo&iwv3;uBxdeMreiel@njlrO>o+l~WO6Rbv&! zH*rbtd-g;O)^mIlmqOFRRcE!t2(8r1G%a#yS~#BLJ6f#Gr#YVE``Yx{uO8HI_0zZK z-GUgRX^}(I!m$?L@Hz{59wLwQ7kG%74#uXj){@v@nP;e~?}HB0m{$c8VC}IW#RYXj=IBu2^D(vf1+- znilD%|2@ed!u&y=dAiHqFMhZ;}#9%##rbP}-3&&cu z#0cfTujkOT$f0Rr5MllxyKurr3QY^dAkU#`kweqMu~scHq9HSIh73)M9GVse5#|rF z3ny%((6m4d@*J8LIW#RCYt<4Xl>fe-L(?LMriDR-`Gf4j2^$GCEf9k|ho(giO$*0b zwZsVJzvnqLEi!0Y7(|#q$S$0)kwDV|G01ahT4d0)aI95Jj8Oi2oczFjue^}1`*~D@*F2@B-hPtf*7uzpSx??e9QTc=W2-&HZ$N9j})2~ z2Elf5c2{!4lKNVE9qbj(*h-;kVR{uKa3WX&O$#|)44M`hG%XB*?W&jkJ-9xHrbPx# z3v+j41kOTBplN{^`~{(DkwMeK{DN#(z3jN+do^fUWYDxQqa;S)Ot%D@7BUi{X^}zG z!XVhLdRcyOeGW~F9GVtpw8sdXT9-i60x`%aXj*c~yrK8L174owS#V7uzYDylVjnWjY! zO$$?AUK8L174owS#2wBT4fwL`BXj&i!vkx>aa%ft(?4y<#p_$0nb7)%R(6rFA zaa~(s_F=Ze3782qEf9nC9GVsxG%Z{fRZEP}jOyz-G%Ye{TIkuhuB|YOGHc@m%mkVi zh{0+AO^Xbg7OsA%B}Qmv@bw&;78x`x3?i%stUfr~GJ&QAVz8b=(;|bWg{x|6i4j`i z{Jb4!W~R`zaL>FI5mq%;QJjF8OrLlxVz8d$1k4ng7Opz0B}QnaUZ!c0PndeCduNVQ zv(vi4>o}f6p&~u4Q(ryHJMA>09b$;4MGj31_r?upT{{bT9wL<-bSZ z)a(?R7Vgw+MFj26wAaCTJ2Wk@(`1>Zg}cJ#AZGe2ho(gaO$)aM&?^txooRm$&fB4B zkwMdMB8R4hDpa`2vK$0ru;M_|B8R4h zs$e)o&~81ek5)TmAMA&NrbP}-i%Mu&4gxVaZ-=Hu4owR;chV*X;BR=F+%D*5Ta?3L({?_Le>UV6bNP?Xjp3(nGH6;LRQ-@E6HlRV%F!5wQ3>HLxl3*&)cDCkweqM zAVSWQU9#Fn48B)`rbP}-3&&cu#0cfTf8GvFiyWF31`%?e?2^?sVvy(1w8)`pQG}Kl zA@g?JUGf~77CAI641#F&BD-X@jTq!PG%a#yS`?urMl@swK5vJnMGj31gCJVH$SzrJ zBL;a6O^Y0w7DZ@@5i)Pbb#Mj%O^Y0w76w7IdXZhS+C~iW9GVt6G%bqI5+h{Zju_-Q zG%a#yS{MY;>P2?RY8x@gb7)#*(6n%@RZEO$$PDfag*)bE(6lg!FiVhKvf4(k$a82~ zWYDy5tW`^lka;^0oLNHCB7>%dL4;X?e3aET5ac;DEi!0YR6|RQka;^0zddxWg$4T5NST5n?eUdi)za~&~4-Y4J}%dL9kcq zWq%LeU1(Zl(6lgjH%7=?4#eOu2u+I&nidAZcGb&{D^>$&T4d0)C_+n&koP+>5}|34 zLDRw@h*qzV1%9+c(;|nag&FNJLf%s$1{noSiyWF32ElgKD`c~0Ei^51Xj&N7#t3=e zh8WBY(6q>*X<-m-SG~fliKLf#u91~VKqEpljD7zEo@uQ0p%EDBAF z9GVs;i^d3f|A`pP)X=oZp=n_dY*)Q({osB$XjW)L(?LMriDR- zz2aSvx8aDvdJavC9GVvH?y4n5=$-cU9GVt6G%XAwyu180P6iyWF31`&>SvP<5E zBZg>N%dL4;Y9SzF$QBL=GhG%Ye{ zS`?urMrdX5^&FZO88j_i{m{0;YQX9vZ^IFTRSlXJ88j_iRZ~lh&B#UH!n&Y|bfsJ@Bnie@UEgT}`xgyAU*&Bym ziKYej+%-a|7ZI9cmT6k#i|^jLq(%1Wx?aiNTGuPtTZ z3@tH2cIg4Z)dVyxa%fr@1kvh6&dc6fAeeoiX^}(Iq6{rDLU!o^!PNvbEpljD7zEMk zMb69KS|B)QfTl$bO$(Px)Dk0PmmUzJX^}(I!XVhLdXe+8w-yLyA81-+(6n&5L@hBw zcIg4Z)dVyxGH6;D1lv_Fa$fe<0>QTc(6q>)Y2k8-T4IFk(gT9?L}*%M(6lfJwyR#` zyzH$7g4qX}78x`xT=r2*jF4S=KybbbO^Xbg76!p~)r*{$y|q9v`#{qogQi6hT4IFk z(gT943E7S7vX8b!w0bf7$lh8Yn0;iIp36RJi4n3(PY|+yw;Hy^zvbH;x0=w{zE|>f zjp)X<{kvGH6I#;F_;;kX^}(Iq72*O-|7`+rDd8HIW#Ry_K6Yl zl^|j;!$H#`ho*%=uwC^Ev#Zad(6q>*X<@QxjF7J#5rdf;nie@UEewL~s#jPgq#8WF zQ4UQDQw?H-e6@)ftT@oL$f0Rr5NubySbenG`PBq8EpljDn5q^d%;A#Sz7CAI6 z41(>dS6GAnTL5TUB|$%68@3SNE)6zG|(S zuVr1Y)Dk1KhrXUe(;|nag+YY9;$4t$UlD_M7n&A1G%eiSRZEP}JMG^BK+__JriDR- zcbC7WeEW(RTysLxB8R4h8zpLq5jtZ0NQ9;p}U44M`$`=}*GXeRRY9GVsxG%XAw%s$L^^6e{Pa5Vu5h{0+AO^Xbg7LK)Qi4n?w|I`4Q78x`x3?j@Q zj$Qt&7sMdXp=psp)55V@)3;gEfIW#RYXj(Yd zswGA!|2@y4X^}zG!XU!@L3YVm7KlNfL(?LIrbQWAVubSF^BkHM88j^%&$TV0)r;(s zvn&vUJcp)522BgcTD8Oo<-g}SG%Ye{S{Ou_KgcdQ%K|aTb7)#*(6n%@RZEOe{(GK7 z(;|bWg+YY*gY1&CED(b{ho(geO$*0!wZsTzv*)>-e&Kkoh%kSU=W><>Vvy(ZRlMW5 zT4IFq-y`I_41-|1!~7{(Zr-l3eXry+E7PkOA?IJol|$1ag{FnMa`sBS?C-&OJ2Wj) zXj+)N8zbb@G5H0dX^}zG!XVhLdf9Qsc{?;MGH678x`x3_oIooN|R2WE3EVuYNMh!~t%LenCHriDSUUG-x1(Q4FC*K=rEWYDxQi16<6*OXHv5rgw~Xj){@v~Z(DEipnzjIZa=w8)@o zVG!Xc;i!~TBoRY2Ei!0YxY4eb7@;HI&)cDCkwMeKAi~j3cF8G{h(Xpu(;|bWg=4K+ zVuUi-KZk>+MFvd^g9us6EFq^zBKwG@MFvd^mwnU{BQz8FdJavC44M`O5oRA|J2^!X zF<8%`X^}zG!evpl#0br({y7{pEmCM&7(|#wnYHBUiRXH6mo>p3(n zc-Ew=&T5GfTB(<5TJYRj$8$NK*701) zY2jF_mKdS@_v>?LT4d0)Fo-aJkX>>TG-7bx4o!;;nih_=YKalbf6sGhTBOjlFo-aJ zkX>@3HDZwG(6q>)Y2jF_mKdS@M~%V^p#I+ZDKsq%BFrCTmz=qc7@TE5(;|hYg=4K+ zVubSF^BkHMDKsq%BFrCTmz*#zJcp)53QY^gTD8Oo<-g}SG%ZqSS{Ou_KgcdQDP4FD zO^Xzo7LK)Qi4n?w&vR&6q|mf5h%kSUU2>MY@En>JDKsq{&(#tml+B*!(6mS%zUDQ@ zb47&tgFKfr>4oQV3a#V0T4IFq-)9DBTGaM_ypKV!U4Mf1G&gV8*uGcLwBT9yrdKh7 zXqxdK+__HriDSUUG=j0icbxoX^}$H!epNqK{U?5 zM+{~-Xj-Juv@i&^t6nzmil#*hO$(DnV+7GS10OM%siA3+Les(^*sgln`XQPYDKsri zHHZ;J;|zSnV8wx^MG8#|gJ8Sr#pPTBOjlFjXx^5REhN5rgw~Xj-Juv@i&^ bt6r?4T7&((9hw#?G%ZYZjuAuyi5UM6of@=) literal 0 HcmV?d00001 diff --git a/GEMstack/knowledge/vehicle/model/meshes/e4/turnlight_fr_link.STL b/GEMstack/knowledge/vehicle/model/meshes/e4/turnlight_fr_link.STL new file mode 100755 index 0000000000000000000000000000000000000000..a4488df1f1383ff543f3b9d57e15d096d56fd94e GIT binary patch literal 66884 zcmb__dE8gi7XF(Ckw}JQYA`0VOuc8wkPxmRuc^=_L`5i55fLue6uByixXMh%-tYIE z5XwAMhHK`^SeKOP;`cmzuhqNPes4cNpU?09aqoLu>)C6c^WD!{d!Mt4WogZGGi8H%j^U?8=+P3X!Hy>m6E;VKIvHi@I(-L0OW^Ep>eD-lmiSc=|O8HjT zI)?}?iXi&4J?2!t-?xb%M!wOm?6ctkjS%X^Ufucg?8?*a74e_x9m=_D?ClVtB}6Qm z{CefAX1^qiS5tG~Ia`$FFPTGx7DdqK_cgz*T(IyxL2THhTUoc_PK^-i#a@j$d|{=- z`yUFT<;K0sd*`g@?(Sc@tW>Srb$UXt5vMe*_P+ON=cQ=ItEuUi?OuLbZt4(f2@(9e z)z|;2bbe8Lb>wZeN))s~H}LlKOz&BB(|YrlF(u6**qL&~Ln+cZL`S9nc6MyKqoa>z3m zXSDPgyJ7W_+dH~m{r3I()ti>ox_1BZ#)j2fKk6tk);;!&@~0Okx$961(Td>T&z`n+ z_4+v%3gWr1Pc5&z?x9AA&`a-#@6{)FoLp}E$cv5cl_D79o?q9hem{1!#OQkA3FY3! z`;8FlMTFirA7jw1=afm!apuZt39o715uK{j#(z@l5wngRQNDhASBD5KilEn=UK>^0 zoO`$+TJ$}?eEPfvE=Pq3^bgk&Fw2rVH(a`B)H= zsT(2Gi@lN@EC|We4iQ>Hgwzi~>^N(?^0%FKafr~O2=+?ql^d-!HM1Vp_UNAzoiCCucSIRLa0~cUdc?xU5Cs? zT(4yANd>@uC<$cCd?~7PhMh{w;GYLG1YayrTEbCpAKZUV2CTmCLNpA=DDK z%fDqdC^2NV)Ci$oM1*&`rbcFD=E@m8ye65ENer1GJ49$v1ko}N7KF@@8zIz-y^^`F zAY_K@5TPYR$h=(;GShd6(4q+TivK|@L0nR7Sbh5C3mPHRi@nmn`M)(aK%|P`|8Ho^ z|4js9*J3r%(5n>d4~-F68qnxrE!HA}7}#Q+3~Pf%2=!tN+>u(WCIo@In_>Oo5TPYR z;CD)}dJzPE!3=90hX^f-;I-k`OtAJ51V%}Qd3z&-da+mFO@f)eAi$^$YXgS}Eg=G2 zNwEG91lAuJ)*lWLS`@)vfdvWHID)_$C&L=25kkG#E3hlU3P}(Pl2vl74IDp^OA@RB zH2Wl2K{zi(GhR*2^SjjK&BpdqM!D#07c6oJ{tb2|SdmE#ur|Y5tr0@K8u#j`+iLTk zn{Dl`1DQI(Y}?gy&- z2@#mjrC5Im0_%@_>~#-0L}*b2dxbe%iZzZPu*S);#%Y95FZK%axfClTL12cQzj1q4 zH;2PaIK>*k%~&ySOR<7*b6iC;UQG>VeL2=2I_q=M*{&k^H)en-R%8+bGs_%nwMGc_ zYTPT#sqA{4Mi#tUvO7x4*^p@qZwk zm);Q{Lwe=dqL#2-{*75bdn+-pn#i9#Z$Tr3dJ&=b&BqV~M&Pox+!cmB6omVC%;Eem zm<4Sa1lyHg(A}M7zhEPTda)(>Z3H2|phJX~5Fz7A5LkcYGoHW2Awr8H*ee;wg1{Ol z#~P;*LcQ24VSylowHezIrY7_fZaXhU)2F6JSnCjK2@(8TSSvAvwT%$!)woxZ;c~{4 ztmb+p+0M1Ay`@i0jbu27Pz&2t1pk&iCcTmj*9f6rM1*&trbenkPK)GoH^!uXxOSyV zq`p^J8{}9UxEN|7S`qwP>Xq~g>yI4kk4A{lOYew}fi+GZJdI+7boWXTj3E_OVo1et zF|@7Fi+}5V^D(5VnJcFyye6q?a^*71aEQ>N2%=?{AqbgeG(xBsdnNM+LC7q_Awo-t zkhzZ_u>Q!f{&0xUq6qd%=30Wl8YjaVrx8NE*ejW-2|{L;?(WKL(v1?CWjZfKGoD+2 zaAxTcYGJ#I;NLQTlo&FzY=ls+#=Vl6zPk>6+D|XW$Nx&Z;omaTcQMo}MDTB!=?fa` z56<)(Awn;`BW$szMrQgBp_Z^+{w?!)i6JxnMhNvHLhlHJ2i;QP z-v@264&Hg(=KiK3#1Wt|wy-AA)D>$Nq_4 zg@{Fy55`-7^ZuY$>cw8^9ckRF-@cz%xoJs#J-wbiZCvI0IZggVuR=uilfQF?@dv$9 zFUHe5(zsV^UNfaqH|QVT=_P;9;NSH8<8c)t<{fcsW!m`T+}y|h9@-Y$RWJUncZ7C} zkgH7suiF3jUP-$SA@SUt$j0~|y>bY>BaM3{Bg6Gd?x_1)TWX9@3;P}-#!Gay^mJ_a}N4B4ix@L9f({z0y0xXgK>?|9;I-Jj@Hh`?Q_ zMHcquR;Vy44!42_XoXFFZN3BNaJ3C+X=F$ zV=6e2AdCKqUWEv-%gr_$$Kbzc#ZfQzO794*_BTh)NRUNc=9Ir(My2QfQx+xKA&{>U zWYIs)SI&#Q(mTRPwpVhsmB6c>f7A1idnN5Ug!JlW$qawcEA?Wp^p3b*mHhAEKO1BIQRV-~+?RWC+~3|VbJ67@LNA#)JM<`nkkyv6 z$QtL5W1wjtJw(X50sEBy^hclBEl!0%SVJ>;T^FEeLBQg z`ee$-<$o{d_gH2L5%PS-j}r5H`1X8Tp;vfEY_IfL29f%-#ka!${-a)ni14YAjp5rf zy-N6R;T^GvaJ?L^=);yQBD91Eef~iE@)4m|ct;u|z^IgM>1vXH`~UpWy$TV!3MaC0 z488B6S9nJ(0+wZa(tvQg>7+~epFiqVh(HhBj=leTuRK(DY!d-NGqv(OV8|=B_ zzx+|JLIi%zW&6l%47Q|gg)+Qta4BlHUI zh(*ZgbG?$W>;4W~vWU?a)KB9xcu-G5+-#Qk8$}+uq08 zAC{Ee)=s()-4HQW-?}bMzrH)0_Vj5Eq3>&n&^NI}bf0x}^6d(IUpxQsy7Y+NE%K(9 zAK?(;yG?z=N5p{dA4;}v#rLYU-RjcMKkt-(_GV9q2;T|nJ4hm$9Qs=F>DfQw_h>() zE}b-~S3d304h|8%8Pzv`MErH)3h6gzKLtd-WnDVwvXk=>=e$s`@B03Xf9v}%A|4vO zR=UcsqkvenUtRjmKhDj&?7Oc+gm0Aey$TUmAJsAaWrvS3cBgGqm+rOp1^JDWFLie` zd=n#Ym+FZ)_^Qrn=Mn9IIQy8obp8q>^Z8@ix_1+TaPOn^O-vA@wx(vgo$J!Ei-zSl zjlaSn^oDQYam`@+PX3loQC;$5Vn+UnPKrF=F?S6OneDOV7JA^)0Ct9Dk6YdgdU92;Up%b8#YMl%zE^k8M|%&g}eUwtLUx973OLGlo91CZfmY z*CqeCXmud2I-xH8vdfrk!2`n`B76$0&q9fi(GG<0qX0h~0#8rf-fYGI!tL@FL{5lgxp;qgdZjN;SlnBI0X2?ecBEI zepJ8@AcP+!_~8)po4dRsqom5~kWo@y#*YI0a0u{&x(9(Waq&0C$C|M$Zqt3$VW#2|=P zuT~2_Np{Tp)eoNdH4vk}9+=;E-NfoWyZn{;PiBiwl5wcuv3kyV2vT-_823 zK@hE8o1HyBX*XeLeTVJ1Pv-6C>++sG->9zlRLe57#E1`nTvR`()31neNZVfd{;xb; z-E*xD20^rX&3NXSM~TG4aG6AglB^}6lKi<6ayUSGeYuyDto*x(l(dxyKe|+VM%4TQR0YMH9KIy1pT+21H&=Mp5z2ZHU5p7vNHUkIe zUpk?<|C!wkf@t;P$Uo+Qmn*Y(83F`3Sgd|e@#4b+v(OSF{<2nC8MoV2K#+q!zVKGj zY22j-L9}{t|?Mf*icQX{U1V=Fb}h z(dxyK-|4WL>iq4l2Z9{@smsRYGsk?Gg_amGrTR_fm0uqKf*gGJ!5zza{XaDbqScEd zf9K6xRQLX3JP`B2!M(rQscf^y&sk`R5v?!&v2sk)CxCbg9K3o#&+_X3{%8M=sorjhf(J)(*I#`Q3m`WX7_O?ggd2r;T4%VU$B8Jq#1a;6cN-a_c-FqV< zP~mD(2Z4|}n4k`3VOyaWM?UIcE$Sc;QU_DiLB}Yy#0XTlTGT-xqz;gx1S(uD z>L6lB9ZXRN4T5O(;>brGtVJC}45@<|>R=vPVgxE&f;tF<)WH;W&>)CbFOGcF!CKTo zAfygvsDpWEi4mx93F;saQU^2CL4zP#y*Tnw2WwFWfglG_2Q$>cJha3JRJa6n5D2M* z8S0=x5UpMu`KW`nsDnUA9n4S%9i!9|BT(TI)IlJm4rZu>2ElgKOR8Nh>L3tO2Q$<` z$3av`XNeIFYc+BZbudL8bn{PrUn5nGZx<^Z`KW^l>R@GA9ZXRN-CR^HF#;7XK^+7_ z>R^UCXb@~yy*Tnw2NTpmAfygvsDnjli4mx93F;saQU^2CL4zP#y*Tnw2NTpmAfygv zsDnjli4mx93F;saQU^2CL4zP#y*Tnw2NTpmAfygvsDnjli4mx93F;saQU`O?L4zP# zy*Tnw2NTpmAfyiFsDnjli4mx93F;saQU`O?L4zP#y*Tnw2UFBRAfyiFsDnjli4mx9 z3F;saQU`O?L4zP#y*Tnw2UFBRAfyiFsDnjli4mx93F;saQU`O?L4zP#y*Tnw2UFBR zAfyiFsDou_i4mx9De52)QU`O?L4zP#y`vH?ZIP&@L{m-rf!8*9^m(SMUea1Y;D78oxU502_L6U<@zk0U* zwNZWCdQcH;SG_p$`R^Dxh(QjH`DtwBg{BufMyVx6G^`+52e-Rm&&s!*A2SHHt6m)W zY-#o`3lZZY%thCo_+90Mp|3bbsU=1e+UMs^{QA zQ#YyRpRMdxcWQ|d4J$};aGURER1SW-qd~A;_2S59OOxMfg&3@Z+kL-(^{acfaH~7D z#E6C!BsqB6k`F6?`6V?7wyRzo`D|(ac55OAIXGqeq16lb*vqZ%)Dj~aR*>Z2?vK}0 z?>N2AAlR;Yapbe5y}#ghMdaXpyIorC|8rlrx>HMxXjnm#gX_M~y1M$5fd;{L)r%va zE!{Gg-$$_yo_@o1)optWag0(+jA&Rvl7nX))2=#T^|K6u?Wz|!$d=xo%P+&o!S{NP zuYP*RIgW#Bi4hGe$csnLPw(A%gKCQt&o>CEuWp^mr&MeS|BD!xonM#s++kAnw~zeS zXKINNvL6-*#+Wc<&*Iise6Msh%67viMGd{$_T;*Bmq)fPzWL-l*DJMz2>vZkSP|ov z?saLWBUUU%pD?l!LcNG+=vDCS)jhwG=dJGfl|IYjHOaGA#F%vY{Ive+e-sz|`*asW zEo?VL==I?p8Gesd@B2q_+1W!3g6*mof1705k(E`p<8y|-_|1RqcX6>~S3gSB5+n3^ zKuygl7+1}&ytX)Q{BdrSD1z;(7suF93lFJGy_QezICdXudTuebcYil_)e&)*feqQqC23?D@wph>QM76{SeO~7C?#RKL7njUxW)N&wy_kbn`Mz^y@jHB4 z%iLZav|@4e*rhJFt0hM0b3b1{_CEIKYH{SV2ElgKi?!s=huccyJ4czlz}j;;8G8*A--yY#INJ#2qhYt<4X z^f|1r=Uw()Qh9dni>{t4g6*moYdiM-$PR4I8Q!|4XQkr_2f8_fT4IDg9rm+~v7@f5 zjM!}-gJ8SZN96W}+w0&gtXukLBCob9TY z{XIC#m~ix))!EMtHFq~gd~{)t%EnVm`31LpwPo?euhR^I?W&g@SDa;BIbe%ogR*Ky zNsM^&jYBKHeKZ#_I1=x9Dlax$2@^?8+@zU3QUW`;RiTwOf2 z;kE|BcGb(~E6y_RUOc6kw&{*0`^1QEn_W^FIiwk~4`&${y>e@D=F@&&q8X0us+Y~X zoMpVQ@X_Mb_xCYbG)DYol`ASMpUUU$%+!m{exO+M;=>Js?W&ipADm@8deSq+O*bE5 zszHo+aQM}gA#+zn49+sXojs$tb>Z;_!FJWl*1?NV)%rJkrC9Xaai*%ph=zAXoB^~M zIkRXr{S<>>yXwU%sx{cpGTt2hMlrHH$yDbUq3@fpQUa2KUXb*ioZ_=wt+2XW1g9v-YyRh!m`zwcC-dyf(k9!vuGyitD zySr+M5qhV6J^%TprNycD?`II<-Q};@rpH~Ctp@YW4@b!wfB&fX&&&I{QKFU@p(Do6 zcQ?NF)8h7zQ-cUc2}fnW_iwB0aO)3X6i55K_g*f(XpuO6s3k_|$oKX9qy;Y)b57dA zAi~j3c3t}5O_d+-{X$qfyxn8PNs~5ptW`^lPzL*YzJ0d`ii?W21`)EBS>lAnS5(gJ>PNbtBWtcU+6NNBEsy$Y-`Tc#^Ialu&pqQGHd_y;ZrIzx8e8atmos7+NQYmv&pU+ zs3k^dW$^X<+7>Go|Gxb=g9xhutIyW82UcF&ZxUj#p6~n4oa#pF*Se~vmKdQG&e!vv zuO3=mq3aW_aw;OMYOJEzlkC3D^40l@bY^A!<8xP?)e}SAryl~3=^xaYI%Ny43?O3Z8@;pQ+|2@z5+^>CE{M^$Z!u&yY4LIke%4Z*Np2&Io zl)G0ecieR!$6B?-2<5-$`BUB7mec;57(|#q$gWd1eXep|-8YCa6FlGc`4!72`(%!_ zYKalbe?M<;f7OcRIfrgz5Mlms>>6EEHd^Hq#30Xq@9pIq|B}OR!{jsTDo~tEBD4RXc*ZY22@%v-%I-V;c%pYXe9vyG0tUB^h z#Ncdc=+d#pzpi-Iu~scHLiz7`zW%`@i?@Hd-5^5FlU+(wT-nSzLdA{({Ly7}$ zyTP$mEipp*?|FXg-#Qjw3_jQ(!u&yYwYdI_%0(Mrix}kj9pj#ZQM_W)N&wz3jN+6Z&>bt|`9ja)TKqG2)56 z?yc;1?i9q}NbI%c-Nork{7hd*BHL9j%MZ@mZyo$p@%{PFnb962uHB_tIrtK;?#QVB z*1uU?_qDHsAwSg1@|^Sbt{W{XI(+-Rd)}@*XHP=JyQjTSd1?{YILr*=oBUqXG;7_6 z=jvti73b~y|GIK{#I~!N?8Bafh#zivv$D#77Z8IP?(HUR%AeNlU=VCqy=>m)(~rY` zTem!5;D#oP#)yND`lzyGBG*xzkyU}=!o(4yh+`bzFzDxIWs5Oy8bruiW(nB=gBZ*{hcx}JIAxEyE?=o7MrdB~^?cR6 z-YWJSd%r=1*@xLqcJd$wv*<;u&nyPMG}Yx@wZsU`sQx)z@7}i-|2$;0L4;Y9SzC4_ zAqMODmV+)YYEL=cRRgue2(1jhp1)q*ulT%vGlK}L0jrPftU?S{wddz;Sln#DO_VuV&|oN<@crA?X~ zRet<&Q^#}N9ZS~g9$2!gVW({Cf%DUA-|171y04XEty*G)^54(fSD$rA`Tm6F1`*~D zvP*Ud;X3&AW4*b(%N-ZDa;#NLj8Oi2p7&X0-*Sb`elNnd__unIU9!^&F`h;>xcQ+T zLzi z#a0RP2iYY%=n#WEKl!3&<>2~99c$GRBb5K1=QFqas;Kt5!63r?L3YVbK*S)=U+edJ z@k`%p9c$GRBb5K1=k3q9zc_yIF$NLl53);kG$IChKIxiq#a4Dx*L z^Ifa0p8s9<$#A9Z_Qq(tHZug@0=OOVvj5+$&vkb^*(KisAjWCu%uoM*?tt>Q(eDR3Te|k4Bg-N8edbuJmKdS@_v`Zx z=O0!+IQnIS2suwaexI&doilhCVsO^C+pGi1vHQH^SgV#8q5Svt{QNh1mD3+A4I<1R zWLIbGrJge9WW*rP`&ZNQ%+a$QYt<4X8ZrZC$Qz|Ql(n1PV-R8fAiEwtsir#d>VAkp zp69JLFSmX9LC0FP#0cfTujj91>y}6Mzuq9i{6Tg#dw*eN?KKWS4Dx)?E~}QW&KT!d ztCkp{{P#THY0=Nc>kEe(M3_Iwt{toIRPKEwK@9SI{%aowz)vr-Dy_Ih5)NJC3yK>4+y}b_hYOk+mS6|z$t?5;axc{O@DsT6F8{gyb z%A1etS={&4M1x?v>J{EYe|NWk`kZ3eHusym8zaUKd#Uo|%1aT0zu*Bk-c>Aqp}F}5 z*{*uoamDv)kDoWI=zCsEGfHB_?43TX?0H8^8HsD|vaopk-CYfW?W&jM2iNC6O=((A zY`K#e?J?r{oqnq9xXW6IK}M~y0p^uxCJw|d$7 z!S`yPHvelmc&!Ph8pMc)HfUd6v+vG`!HVUJ@oaw-GgVA&Cl;+5Mi%)7n+>7LG{^| z?}N3xyPuqJYWdG?&T@BGEippxw4b+cb-}>$vh{l#M0j`kYrc5ZI@N=AcoQ+W*LjtG ze=W~%d$JoPYKaj#V*I>)t1AvKpL#qoh;Wo}RG$0o>eUC{e+e--+MASrDbLvUFgM!O z5+iiv`+0kt-FGi{zQ2n>grlA8s(*Z?>cc&sLJZdPJ)7-PzOX{>SgV#8p$x{|MP@jC z`_0N{&S`59A#0f>2CP$4J?FuP5rf%hz^wJkr5km2*+(rgLNk%C=M!4CEKfLmQ8jEU z%s$L^`;7mxGVZK95QFu6@_-+TBYQV-SyU}CLNltb=Z~%NLUGoI)2m@yVHRc9UTLQ{ zDlLAz9x+%AcJB6I@$)q^T>Vf>jL^#9E6yq%E-XH2c9KDa)qvG!a3O+ zp_STvU+eb3$v3r*=lbO=*(KlCBE~1D&QHs2N0xm?%yVCQs)alc5z2qh^TWEGQ-1l* zQw9;{53*~()g7v*J-8-fkmsu}IkWuauojNBYKalbf4|Riy;ld9>ra|d4cp@1>P2>K z`_FZ&?`+TpF*tAUJNd-&t>U+8Xo(TZf6w#Fuj*TF@Z7xyL9}|2U3Y%FMs?TsS3(T( zJR8@i96RRAYG{cO%Kw@gR?fe_-?JPub)rEKtzKl;suNpP|I>a2#30ZAb6`@=z3kO$ zXo(TZf6w!}gSIG_-hZh<5UpNh*P^$ZRKIBY-3-t3VW)H`r=9YkW35_Zg!13>e7|uk zm)}2gv_XWNC%Y!R_DyB`Ti!zqzCVAU`>(~5-~ZjQRxL3?`R{pt_t!5MKR&v-L4=$q zyY^Uber4}5&mjhRKJAo8ioPumaI95Jj8Oi2o{zkFbg|27@3|GWBEtMZb{({7wK9Cq z2M~iizyHXCiypO09c$GRBb3da=UtDUTU|VMFM|m42YD{%Kq3ZtzS>s@S2uZjO~-S! z#0cfTN9_K}q17|;UV0iDPubM-;oOOv_BuFk@A>LH>@=yV2`xcSx(EN>-Cy}%F6>hz zFVAvo0KM|i%l;mGuhy&2#l>%X_Nomn%RwLpf58>Ed93*MhBl3U5BY7n+i}Ht`))tI zQr!90tlH2L#0wFK!HUy%%J0S7-D@i$BKW(z9S?CPI>)Q#&`-mrL75?YpnKn!N; z=bs!{cAaped$OrHJV4imIp0@<$`?b*yINh9gqGzX5Q7zG=N--})3a}O->zuI3DC8+ z4)VR)zYagQ+;Pf{NoZLP0x>vmU-ydh%OR)V;!bYR${C>DDK1)r{eHObZ@QqoZN$w9 z>#JIpgFuYn^oxuLJyj#9&h9#-Is@^k)bm3}%uCs>T4F@Q2^;+0;NEr5E^l9R#VkaG zz2aSvx+{10n)buXZ_g{z&=Mo$t^>jMYP-)KRF1m7CJPba-Q}+-br%TE+kbfCr1IP| zr>CJMM#$&^f-A_Tw;WaO|JpYO5sng$N~ya*aI`m@bZ9xR=JqtS#0Z%I0Ks~mweDG- zK54E&grlA8lDZ27>v{hkY1#SWYtqmXBZSRBa7900N|*As?H)CVkhRPbQk{Wd_IWVr zSYE&6^fa`@2&wbPSMJHgYAcr)?KjpS!tBFrC)F7-m_>(;`>p7-FiS&AjF38y7~BEz z_Kq(Xi*G!_Ai^vfR8hoWHRyi!qs67&Tcn{SMrdX5^?Y%U(M5-zD;h*t4Oo4oIwJ<_ zc|QA)V)*&jC!r-qNVUUtuyRU0H;AyR1@m^qU_F=WTpL-JSm#nrCgFHXu%HzvyyPjESi4hH%fjmF@{z~}9~ZtGEAxlT`mAX>f1E?I3O26_G!b`Gp^ zXNN4b#E6E>!1ej(Z*5ZEuv-^{AX>f1E?I3O26^7{_zlW+t1Yt75+fQi19|@3uPw^a zd#q#-M5`CsC97@3AkWWP=jYBTq4-{@GYmKY)Pb|5&jtUYm5@oL9W1`%cnvP)Lm!t*BEA6Rs2w`CeyVnjn`AkSre z?s%?k5v^Wiv#hp-=Q3|kLQ9O0dAlHFMQ;#9%hP%j+h-qn-fpfVM#%dF{DRDIH81Q_ zOn>PTgJ7@J%l;m`yGw38s~Gvo40Cs5guE9)3})&v_uX5ZHTesJV7uyN#}%u=2K}EZ zepq?UEVRT3dA}ng@$Ox|EAD@PBZDAXy+RiFs@7wj70PRx_cEhBM#y_A#2};2KY5+< zh%XN?2)3(UA)7I?1Z($rwL^J)$6bnujk zyOy&iTxGIPjF9(+h`|i^&ra9@G3ajw!FJUv%&va6H1e$j%71Tii^-xfLf(HO1~c^| zz511Nej8^HY*)Q({a`h??!QNuPtCg9RD&2H?{N`>^Y&YR8dy$$>lTAxyXwX2qt(to zZ~toYz%twHVN=y&M8m0doVQ>7@6*apX5MZPY*)QlMYRU|=k1@48dC1t?r~F{V}zcP zXHJxJ2-zp&>bblPclBJ}bK}bO{rT^s-*vrG3wshGw1>W)pLt`ya+|HcFo>{MybJO+ z95GnW582?D^7wZ1+}%}6jL(_BXs0@M*XtJw&hh- ziwH+M*(GnoaUFb1_Qlk$<)g8>l{LN(_wZsU`L_Wja^WoCsfL0e8M3{Y;?c{AZVz8d?*LFd1bf6?Xh!wV z;bxxwcrj+n9tII+QD$v<&y5(Y2CK}tqqyma^|R0tBeXL3dfs*YQ;Mz~7Q6bPZH3i< z)kofjBL=J5fN4F7u`{Q;s-~70p%uhP&#lmKdRx8vEgp zOIBKVP&ss^HaS@&yVxAh!&5eu%{4WT46I9^n|^4y`GKoAgj&dRMeuLgO@}MLxM9y- zBZPVpp*hB!HJQ^Q`*dBe^c+z3R`%8+Mz9;##ZU{;AwsXuXP-^#lk$}-H#UgyE|BxG zw-zy&+b_DbM>(bAdUfsj#GK7GEAvZMHwdEDi=3CewLmcYOxkg?a_iA8^3W0^WS1TgTut1z;@aiS zBUUg7qScF>m%X(>aL(}hwriH{w_50OiCSWW?9u~*PYwREbCdGskslfa+f^@eUiQ`k z!R&Kjn_r5J&z<9PiCSWW?9u~*tBJ|OUoXDA;8BBMyXr;G%idZb_!gl3jn5V1=HKFS ziCSWW?9u~*^TbsSySeyvrOOP0?Wz|!FMDf&VD{Oj_Uhu>>yCHXM=dczcIg4Z`EG~m z-o?5XZfOu~SG~x2*;@+)v(LY(n-&8;ZkmOb7$LjqfZ%FEcH_G2qiqqbUd%qSw-$(C zm!8W$YKakgUZY10^ZR$xur2;A-{!d0gvR#0lCNt_uVRFJ3nW)Qb^o=CTaQ@VTseEC zUiSCk-F^GW9g2as?{4mHjF7LO5QD$qUB8VgPT$y{TBpAt+f^?+uDIsBV$gJ8Sr71m(?7NFf5UCS}OQ&XK|gr4hdPJ(s_JtLg$ z>Pg^4%eSwo`C8WXN-Z%$d+6)=W)H1iUN@z;L4>{HU65~I5rcR4AJ?=iryjnC`#sbW zBlJ%Dw*WKOYgN9v&+Y~h-d+Bh^6e{PaLxJe<5nxX-?NJwC2ENgI%51t+^AiX^2$xR z8ALcrI4b4aR~hXi@52dcr+0CqT`e&}N4~G;r_NbW+;nXxg9t}E*(Kk;A_iI8?yN70 zn_I8#SgV#8p$x{|MP~T-gU=NoG;3uLA#0f>x%V?k2a|@h_D*4`pCDhh{1Zk{=B9|-`ShG zs-~70p%u z&awbM^z@6SQ~NpAswGA!|2@yAZ}eT!X{)0QBFrCTmz-rGJm2bx-;3WS9pYH4mKdS@ z_nCUst_zA6I~-&XVg4Yy9@t&ZTEJpRZEOe{`;o}mra;o?Dpku1`*~D z$1Z=?3u3UUZJ)khd@ycj$67h%!o4fhc5P}x*xRpVKUSyY?Wr5$EJb%B{ zGsQ+Xc6O{)ON>zdd!GN^=AXsAcdum-Vg4Yyrj_#05+juVp6A;i zd1PjswRON>zdd!GM#Ym?&VCr>blFn^F;a+U>RkmrYP{z3J@CEXm) z)e<9=&7S9S`i0}UBEtMZp37Mlh(VsqSMiSLYKalbe~*y!G7N(44)dpExp}+B_PvtR ztW2+Bgq*!4SN_qh)2n}fpoh6~_Da3%@4qReAx698ocQ;1JsblgBUUE|V;OJlyQYV%C3bzKRiYW)))ayuOvzf2g=L_oq#3hGV`eXZwTFK(D=5o}kzSVgr4`+57o z)1E9YyT|JjmByr`pG@MT9u0t&`LVM`ne_VLUnBtgi zhZ;oKE8Yb;MN;l=pIvV(jy&-ccX!niBlJ%DdVcZcql%q3J;5NtyUSlwPLV_m&f8Dz za&@s}?9pzNs3k_|i1GEj{j4Fyx~Cp$5aB4{sFYJA5rda3O+p(EeV z+dmsySBxB<8$>wT$u2oX5;4fyb4Ls;p8lqrW35_ZgfiGahue39U5h2NH#UfnwagN7 ziX^g6A7q~{>+Drry-9nQebf>oG!yxH{`Pw9ilf@JFo-bwFx$x~l8C{2e!^QD6x;8z z*kw_*#0br({yE&dmp-l@x8ZDq2(u`&wwxk~7_8^t5C5dvZM*wiHBd{8(8?gs;oiEo z`sR@H4I-=ttUhvzBx10hUwQ8()jqH8@1*5mq%;Q8{Z8F<8&# ztVvg$)eHLxl3* z^Zch>)+^rWca}l0UG*ZnKYY#Nqt=5ABFrCT zmz<4^7@W5sz2c5V>%R_gtW`^lQ2zV%`L`>rT-@{3kp>aw53)zdd!Da(>W|f<2kdDOVg4Yy_E(Q_i53)zdd!9ct?fz=>EBs7f5n=uyyX5R} z;rXPAv#T>JKRec{B}OR!J&fKomAv+%Ec&?Thp=|a%7nL!`b47&tgFF|# zGU2(LLhE?0mKdS@_nASo&kTa?`V+LLxOuzA_Pvs`?oF>^1kpGhU#|T8AI4T@%sIqd zIeVpE_V?ht{h{;rtZcOX#pd^j5kzww_)Pu9xbG^bO?=cK*sglnamBYXCmnfBWyy=L zm{AfVh{oyoXoVH$?J1j7_k8a+gJ8SrW%R1K4LIa z?|I1KjY*Yu;i&a!>u%EYg*t$dY!ZR;0)tNmB z5&RoS#NZ5I#!q*4hNgw%xwlMlZ{?6BoX%6ou4O#0g{Fn$IT7TuWSnIPWCl@#;!Fmb z7PZi{a6DH8+f}cST|SFK(;|VUg<~xd9Jet7`MB1rL5ZeC0!<5pko@7iLU#G5IMB36 zplRV)%NXQyj6huxH7N2NnidH(Eet~Phw}>A<*OPrEmCM&IMy--`5Yrq?L-ZVl@pp4 z2{bJXg6*nT$Sz- z9BUbae2x*AuZS8Hc@9mB6q*(WA^F33h3xXHB4}Eq(6n%@WeoB;Mqu70YEa}kG%ZqS zS{Q`n59bxKYni4+3QY^gTE-xsV+7`pq6S5tL(?LKriDRB{%~F)yZr1GnieTEEgWkZ zgM5w=m=#YC@FdxSD{bMFvd^gJ8Sr z#oUEw00}fLFzT5Tp=psp)57IMwZsUlCPX2R^DAgtWYDxQ2)3(U%)xjDkU-M{F__z{ zgI3I-Y2k9aT4DrN6QcCT=ey9fNTF$A5NubySWEB>Ac3X@V(_T}G%ZqSTDTgemKcH6 zgeVqrz6(u@6q*(W!FJV)H4)DM5@=c=25T)eEmCM&xLT{07=hJ{kv zGH6=3cV5bm7=d?T2{bJbgN%ZvMFvfaM*L7O%X6|8nid%}EevbflMsQofC)4$5QCWk znid%}EewL~s+Y}I%szK7o{~Y+!epNqfoJ^*G%b*QILm;hMFvd^gJ8SrW%I6RT4d0) zFj+K4;H_)|O$*7?(6q>)X<-m-SG{cg5KW5=nii%S#0b1yPM~Rl7@TE5(;|bWg+Z`g z^;qVa&>s4F4o!<3nid8T_KJ4_@8}a~TFBjnrbPx#3wL+b5+n3Z`=^7@w8)@oVG!Zn z<*$i%>B&}un;-`3IW#RYXj-^YqLvt;BgW5np=psp)50LaQNmG)Jvs?AEx;&_c4%5; z(6n%)T`e&}N4}r8L(?LIriDR-qn+%+JNg8g7Q$L+T4d0)aI95Jj8Fz+wuH<8O^Xbg z76uWrmRSOC-xFwBNcMrIMFvd^mwnU{BQ&r0brdu$GH6=p?j6@wn0=V-@Qyx#rUhc~ zT`Dv!GH6=3EUK0mp&8Xb9fYPu22Bft2(u`&Hr~-E(6m4d)^liDWYDy5)j%yVLMww` z*Fw`GgQkT+gw=r62k+<;Xj&i!>p3(nQfOMZs-~70p%uq?7q{ykyY!N$+c$AM$DX_7 z)3aF(MAIUNriEjzTFCPdq5Steho(giO$&n{Yt@VF!k)VXnihz`c{?;Ma%fsO)~Y2& zDE~drp=psr)50La{6ThM&s_pd3&apjiyWF3jzdd!9qnB7>%dL4^5(?82VA1ez9z!Ric6iwv3;j=QT4d0)aI95Jj8Oi2o=MLOF4>8Dd?A}SBY2kRTmKdS@_XzCkOQC6D5NsEF_LC0pAM57r8r$~@yY5qH zT9{tN2<+2OplKmj4o!;;nil5D*(>$3zX#{-(6q>)X<_bejKJRd1ezA|3qsQ(gQkT+ zuwC`CI%!g`eA=TO90FhGrM>TcTEC)8I=}dy`-T_a#HHVy{S*-L6k;Qtmn|Q$e?NAs)1T!gjNP$ z&!K6NLDRw@!fL?kgRk9^iTnH&F<8%`X^}zG!c{f3#0af$zH;I#x)hogu5v0OtZJ;H z_$DsteeWKK!FrBw;!bthW{6Ti%i~JPI6^KEeL(?LMriFg1?<_Gw+3a}^O^Y0w76uXK53&nizd`*}MwEpljD7(|#q$S!=5pY&|Y85wyFO^Y0w7LK)Qi4n?w&vR&6 zWYDxQh%kSUUHBqDnZ3&p#30Y1X^}zG!m(B@F+%z8c@9mB44M`O5#|rF3*Xn{B*Qwy zAkU#`kwMeKu~scHLiz7`4o!;;nid8T<`1$9U*sqK&rT78Jcp)522Be;-xW)YP&Rv> zL(?MN^uH$?M3_Iwb9|BScS{ZT_6gPR>W1^MX5*1E+PQ z*U!1op>V=R`u*6^j^{XGBVFZJ=0rJ@BZsDiJ7GgDP2?p zgpCxM7Kp*w5;QGxXj(YdswGA!|NZ(Lnie@UEes;eA7mF!*hryiff%gk(6q>*Y2jF_ zmKdS@_w^i_7CAI63?j@QWEW1@NTF$g800xLEpljDIM%8qMl@sw&XA#LkweqMAj14X zcHxAL6q*)@L7qd?B8R4hW35_Zg!13lb7)%R(6lg!Fn^F;IAJ4!rUhb<=g_psp=se* ztCkp{{P#SErbPx#3xf#r2ib)aHWFxBAO?93O^Xbg7LK)Qi4n?w&vR&6WYDxQh%kSU zT{vMQfu;pwkmt~}$e?NASgV#8q5Steho(gaO$&D>ha$rKL3ZJUjRcw&h(Vr1(;|bW zg=4K+Vnjn`;CnTk$&o_S!XU!@L7wA;jpX_{O%TJ?^K*Ain{PSa@mwu2!e$1X;*mnr z!XVf#&hAQXT2fzYuY) zX<_bejKEoF2{bJbgTEj&Ei!0Ym|u|Xs+S#Ce6I#giwv3;W|YJToavT8(?UifG%Ye{ zS{MY|RWHjAuFs)qkweqMjP@9TQ|l6FS|A1)1x=x7CAI6Of`rRIJ+^0rUhcK;y}|P zho*%=uwC_H_0ekQSEGyRAoQ<1K8~=$ra~CIIrjOj-(baRDfSLZX z!^dEhoSB(J)57&iE$m5%&>s4F4o!<3nid8T_KJ4_Ct#+~v_K5rU1(b5(6n%OS1mC@ z@3fz{L(?LMriDR-cbC5=&bCaUX@MC0x(1pSIW#TYC{as{&=KS3?a;Kyp=n_d;V9v# z#Mzc9G%XN=qaB(SIW#TYXje;&(2?)w?a;Kyp=n_d;bU9QD$wNfSEwk z0x?((plOjo)56scwZsUm48ER2(;|bWg+YYXfYk?QTPD!7Kn&J%Xj){@v~X2TEipnX zoS(Pj%*+&;7Veq1BEqW1DvA>@lWF6RLk!k)oPe1^)529}wZsUm)XOw2@*5{#>fV{- z)aHn?lpV@mwu2Liz6z zI5j(kriD8-TM@-=XY2mJLIfxnl%AskILDRym0rbj)c4ye%gY$N1 zT4d0)s1Gg6K_CWyL1v;^@&1Y)q_K+__FrbQAW zg1={2eu$<;4owSHsBp|#4gxXAC}>*b(6mq$42KBXond*->I_Yb9GVuYP~kGbauD@C zGeFZKho*(9U^qn3ZoSP{oVP>MB8R4hDpa^kwj2avFvCI9B8R3$61ElmU2pR)=k3t6 z$f0SW3KcFRF9(4b%+%1d$f0SWDi{tCv|DfM2j}h3w8)`pp$ZkQvMdLI7_2zZw8)`p zp(+>-5wu&+>Z8>T*$4aKplOjq)1neumV-bH&fB4BkweqM&7HNa0PVD-vg=vV>MjtXX^}(IqRMvF64dkX%7G9~iyWF3 zMTiJ{6;x3mcz2;`kweqMDNae1(qf)9f5FG8$w8)`pQ4K9ILh3vaWE3*2G6$OIX2bvZ+G%c#3B}Pb{N4|1TCRSTHho*%= zgxQDLPO39vFpEOdB7>$yHMGPCsq=`z9T3p8$e?Lq5MdS#swiTx8bH$`gQi6_w8RLl z48ER2(;|bWg+YYXAgH2mXOu9%Sy7^u9)??W35`q^AMr@_w#mWTIA5Q zFo=-zWS6YA5rgm5plOjq)55VJ?^JpGBc* zkweqMWYHKQ?>`ZPnHriFIW#Q{g6*o8tsmSE2Th9{nii%S#0Ythix`|)LenCLriDSU zUG-x1(Q4;suh6u>=S~lssum;U2|Z$P-VRNR9GVse!FJV)Ra9&6GEIvdnii%y#|U{s zj~MF=uS+*s+CLw*$s&i4eKM||%iC~Q&*eQg5c>Wcnij5CYGF@8g!a(ab7)%R(6lg! zuvfeb@-`eXSkIwpkweqM-CecB2))z3o%ds~_4{SPfWx%dt7>YA5nADV<&^j51`$>@ zR#AByju@=x@;2O6XSKu#t<=jjEpljDlw^_YPjft%J+KkaMbjdOriDXT=u zXj&LVco)cd*;|Vk%f1dD&YF1hWq`EpljD zl%XX?$Syq~xSD{bMGj31gCJVH$a&dY3k0(dG%a#yT9lzBM#wHbAh?=;p}U44M`$m#8I1 z$Syq~xSD{bMFvd^gJ8SrMb69KS|Ioq0GbvVG%Z{%QA>=FU3x%po(N5g44M`O!FJV) zoR__|Krs72(;|bWh08u_i4n3(4+ze8p=psp)50Lwu6mL4vbPopW*=x;WYDxILQ9O0 zU3x%pH6gokUG~woh*mFVAK6d}D?fWE3|J05mOfXj&LV zcz5}0%D1nG!8Io|EpljDxKW~(7@;G^k3?u%*Y2ik@ zT4IEbd|%I@X^}zG!XU!YPIk$+uZTg`LenCHriEjzT4IDU7)Y2m7YT4ID&24ByiX^}zG!XUzG!0IF4z9I(e zIW#RYXj-_crj{6?70y>q`C8UhPDO-Oja5{>eMJn`bNTkwRcE!t2(8r1G%d2-dmiU_ zF6Ux6p37Mlj^}cg1^A(-UqI8su~seQd5BQ{d!9qnB7>%dL6EiTMRv(q7Q%CAT4d0) zaI95Jj8OjjOg(DX1sOCg3?j@QWS5*}ff%d?(6q>)Y2jF_mKdS@_fHL=X^}zG!XU!@ z;n?NRdO-~G9GVsxG%Xx!<&+Eeu29>xnSpQnplOjo)50J^FS1L{vcPXnou`g+xJRNvogJk5pw>OTsbr?QfOM3D`&6N%l;mmw?oq+ zg{FnMyD>se9g|-Wnid%}EewL~s+S#CoVP>MB7>%d86`17PESJ&&fB4BkwMeKAlR;Y zg)CU6X^}zG!tf(T$SGHdK}JE-B7>%dL9ku*vOH&XhNeXZO$)=?7$K+GA^R{hK+__F zriDSUUG=j0icbxoX^}zG!epNqA*b>ohG<%3(6lfJwyRz?@AByfG%Ye{T9_;vBjj{J z$<)xa$e?Lq5NubyZ2jO<9B5i((6lhsAV$b3iHO0OB{VHEXj&Kq+f^@CAFX!2szK8t zgQkV4YB562zd{Vo+o5TZLDRw@*sgl9ifRq^^LA)jWYDxQ)j3AU`B#W>)d_X!mtDqW z3mzEm5OV6JtLJjoq^sw0iX;%CX~EMeU9Z%_o`eYPp5-~V$ho(gaO$#?l)Dk0f#Q1s+O^Xbg z76uWH5{^naMG`SY(;|bWg&XZ^i4i*T{k$ET78x`x3?dxuWS5*Gi5O%pG%Ye{S~%9K zB}OQN{c|{IT4d0)Fo=+~%o1{nB(jfaT4d0)aM?#KF+wwuujkOT$e?Lq5MlOVwv$sN z5rg#{nid%}EnF5=ON`Kr>Yu|w(;|hYg+YW_lv!I&kwgsEb7)$m(6n&XKrJysD}y|T zd+XX1nid8TRs&WaIYkmNSkIwpkwVkLRW-H52(56wa?0tHu5v0OtZJ;Ha@Hhbu%1KH zf@e*->a3O+p_O`>rUlQfbv&2zX&uky+*-$TIU5(_N;EApXj(Yds)alc5z2qhb7)#* z(6lfJvR1vwE;)G^G5EIcvbFOJnih_=YKalbf6sGhT4d0)Fo-aJkX>?uGGcJv4o!;; znih_=YKalbf4@G5rbPx#3xf#r2iYYjK_dp|?a;KyplRV)tCkp{{P#SErbP-(3xf#r z2iYYjS|bK|4o!;;nih_=YKalbf7B?<0P63XpF-2ZAj14XcFCFBh{0I~G%ZqSS~%9K zB}OR!JXk!xOe zJXb`RKge@AlU{f(r_ef{t0hJ#|9xhFrbTV0EnHriFDKsq%g6*o8tskOkkwVkL zRD&2nG|s?B3|1UyTBOjlFbKA*UaUS^?R-^(rbP-(3sco%1kpGHA2B#@ho(geO$&oy cyXwU%sx{cp+o5TZLes)j=NLgWkcjbr0Qifv$^ZZW literal 0 HcmV?d00001 diff --git a/GEMstack/knowledge/vehicle/model/meshes/e4/wheel_link_fl.STL b/GEMstack/knowledge/vehicle/model/meshes/e4/wheel_link_fl.STL new file mode 100644 index 0000000000000000000000000000000000000000..06fb9b87e8cb9b1f2ec48e2f5ccc5820cf9cfc4c GIT binary patch literal 476284 zcmb@vWpotF_WwOWgA**cyIYV<*Wm6h!R6p?2g_hVW5lq8goNPkWV)skf+cX!;O_43 z|6P>{eCs~^-aU7%yUr~3{`BtZuCChF9h2$*-~ZJtWipj%>SY&4JyUUtk#S0DzH-G1 z{@{IM`;^R+M!KgPM@eE;;ct(TMEl;O6~aMFt;r*HNE;hhRVUr)uTM#0TG`bA?*(?E&iwNOUh>M%uVD>MA#xPBd>TiK8oA6#}&!zgaR->ad3-KD0`0pacnV z=fu3qQE~^__;|CQB+R?s+fnitf+rIl8V`{~SHEit;h?2f;PqP4#>o*8WaGi@p^|Wp zO0uKmF9c5}?8Ycb^t;9t!a+-|tG$`DA)Ww}>D!61l300Ws~shOA$T&ez4jzY^iLnC z5Dr>u-C5c|+W3*9G1*8JJ6RIl2QIXu7eYM2M8L|R5b)G8SYwEQ)u-NHv^cF%|3knER}YT`s}F*d>T~=h$)H_U>2@B}l-2MFi|>3V~X%+YtdfXFZf4 z0lPL4ushd7$zKSu2NMAvfI`52ZUOIu2=FrMq2w=w@HmJ#k8uSWPp zM1Z$c4<&ygcrpPVnL;>dspat07cXsJcC_GcV)R`j%+OpdbxiL{4=;|$YpeI*IU z$bS=#<4P^M3QXAeeRXLxCX?gp{+9fOaNG}@(L)lBJNTP$99L@5-IV|SdzMIo{B|)* zeoOvBIOY}2L`jg}t`H7dYSFBeM@pXULOtFDIQOM?7%g+MLGZ{fESK`XT+$Zr>`sI(y@NYFZO z5jMyRCxUhZNs!;J5UAz&E&O&d=9Nt(L4Lc~4aBje1PR)&qz$pdNxxkZ3){bUXGxIXE_UbN613s?cgKEC9)KjsZ&wJ^B5yz* z>9?053G&;8m+@Qj7sBC}kl!u|^4k@{K}#+2YUGi`6Ck}MNs!+zyrtigzYq@piaat& zkl(Hl4q9rFcP5XN?Ddf^DhcwCg)b^3(*Jb)7GAL?)?4xKD%_-(VK=fvt+y!Wv2hz z;H>c9%_h_GAIU_u-kCKZ%t*j*8u>PRGI1lR7W+Sllq1=MeUr(3dNOga^_&z!O7OUj z-;QVk#-SVwwH&s^k!;F1Qbs5xNWgE}0bv{*kA+$=KC%JhNFmH{b;Y@hXi3~BF=NOE z%qxx(v;nh+2#Rr1=9L`@)PnoZWsH+DuS5hXtM(nVfO(}5s0B|N5%5IW zQSui;M#aigs}L|>Ijk6DgJK*x4vKN?DESK^qk9?SNP=Ph;g_|P>dsOh%63DV5R1;m)MmZ zM_zm``E!#BLX}!10{bUgm*>+ z#W>Oi#W)H99+}7pOWVIQ!jf=ggnvu^LI^LDY*36N36XWiV}WOB2cMb<+n*Rm5L`St z;#j05e~X;8Ebv~C9{o$kc%TxG$D!plGqVyRR~q8h(bsTh7k`QNw1Zp{cJH|mHw+Ky&4a8ZAt1Bf);B_;Z&J|5Qo6EO0u)&|I zSVkNP;dz4V>W<$`{JuCL`QIxCN734@@#M2{OLc;w{jx%8Zy#}!?n^b`BxP_iu499MOBsKFqv+z6L(^kJS*`F zB?|F}rrjBAu>XUwfo&Q`uE^xGa;fE^+(EFBLdd&mGPxa3CUSi(n?gtl5{}=}Gf>Y8 z?=xyS&X#8E|1okYQHbP`3mfEL!N@rt3kWmV)|7E@)N=fm_d_M%TBY1UF>>V&!qp`k z@O&r)YQd}|0-g_!lD`m~o)046`LHA5_${>@PXVLng9vy&>?lD3<}O|N$=j1>d#IaP zAy5luJ`t7mt@??_R>O7kTzyLA{FYH6%lPmg@0j70QO@wKZr50zn_1=W9&x9Mxb?ia zp5dF-sCE2>4GGj5`>nJ*k{%$4VdHn|$H_+D!83J~AhGUUc4_0%g9IW1clqnt-dK$@ zOByQ#YL!h>z|yD9GXBr1<3yaWKhc|Au^MB(hUzFmVtt0(7Pprnd{EINLY_@C`+sF`pBsz|W0=*aWvstai z`>fr0nfW(ak&FR+cJb{jjd#*MfVetxxr*UxrNmjb+RT$2@)UM zePD-f1@fHDDnz`N6QG&#vw3#iYA|X8dkwIrQ>wZ;Ud7agmSo5typjHOgjFvBtgZY24b|S)f zUG78vLe9^>bd(@*C}&2C=YwFr`-mWx4`KYD0K(1f%G=2rm;3z?YYsXo1PJbR3 zy@80ESN*x$6Hnv$opB0*TKN1^B<$+PFMaehqNWc~Rt6;c9=*#j5Jl)Pi&+8Rptj5&?1vyI2+2h#hu_645do~Lm$zn-wTT^5?3`jh z6nmcdEq1z7^AlLde#^Mm@`6Nsp0z=rLHppy0B;@lSKLM4Mx>ED&Y%g8>FOSsP*C6b z)oQ$bkwHfZ68@=j%e~gN>K75a=daOS$i}BW%M=2&=AQZ@ueA8D$@Ddyi++i0_#Jc6 zQG&#kw3(z0@n4fE{jp%(lWgQ{7oiZSCC*>mO>x#HQ^GfAeFxcS)vAz=5+ua=i|Z!r znoMnW`smq&&roucLZFuLO@s|`Ey;%d(I2-KQ* z)XrWLku|p*v`724d(6*G7z!yb$Xs{snxh0*+?N!%jKEQ zE-en`c^{-BqUFcT+<%ePcyg=-M+p)&7U-EhQT8#&Z9Tft#7F>^E z3-Sf?F1=F=qDVe|VzSk!TA@2ftx}0GY*C(IUb1;=i%NW5P?UcjZZ$$z_Twl)qHLCf z?A!JrezcW|Y!uj6lGhwWMBTv(fm-EH9bgZ_gE-$Tp4w7xEAR%ie+s9}MIZBY|9k`br zIv2?It$R;IgJ)(wf?17wZD%S3YCYV!hxvpA@~M7rh?rKa0r#qDH7=E&%~66x==a_2cui7C@nmECWqXdb!U3RhU?*e!$uO~#b@NdsO@>`9Q4;Cl{YLyPz z!F(qM@b44v5z+ZfCw?`T)mUG95l0CU9{YE&@16nN^g$3!rgrD)v(TEDZizymRx`it z>{i(TzU<{KB9gB5C)df_(a zdVMKxI#dv2`wieHzk3?hru%Y~ATe;-R`%U{DKB*4G73K-3=lDE|V^-_)!B-XG^ z?Ces1{$=lfWTVA^aol*|X*387Pzcl-bao?49OKV-*EvbV>@t&i(oIie;POC@5+vG( zZ(wU({CQYu5!b%2_b-2b&C_uDq7taJEouYno5P=fttf~lA=7x=Wlv*Uk06c`B+`9b z&ko=43lnRmZPTxan!2+Wj(t=S_PgTVJeYn$PC{1qNlNaWe`UR5*5y@ zXIans@h^RZjmjBj@_-AT#+0opfm+`ut!GX5`0+Ny4imAinkO%u-lslFPzkhxC#yC$(8Tj&o$5yd-X}x)+ zbfFBr{+H)gv9Ju@d|TyEBI=Fs<$gq*k5viOa=NpM{mkOci}w{ohk?G_N`(JuUyc$a z5+1B#Q?hyU;bR1Gt-CKDNyPTMDuG%Lzpi2#^LTUD1A^Gm(Uk)A znjjjL@#T4l$nCBYs1@8il(|**<{u6TVpe`%o{ESUbWc%&M2^Ox>}W-Ao@2Kl{7k<5 zTCAt>V46yxR-YN6th>dV-dNTn;CqSED6-v*Br!-4MWA)Cy;f^7(M_Y;^As&b}1$;nS;ZV8@=U zX04rk_|6mSi1-!d!v~X%U%tZ;QP- zw+kZvhc~}O#F}R+fm*rf&UuG>^R^L@L_CP~<_C%Ruf|f25+qhRuV$@cyt(h;C?Xav z^5&65L{Cr&)LNH+HOoau&Yxy25tlo8^FShAZC%Pyf<*extJ$x!-hA>gK^!kf)`-}8 zStU@b)|}OB<85#La7Z)}AHFT&i-{Jh+Eg2audtJw^iS55vC^XmDqC44mz*B7b;YT*nunX)I%=VcCi8g3VZ zc+=96Y+8C>{^rR}*3yV%>uUS*M{jqt!5<=7sTRK6lRQk5>B(m=zT}9f5tcfbqXdcf z&!bqCWxjmsPmvexF>^K_c8XTfD#09AWL&8y?~G=}OZ)Nb+3ZAo|2CVq`_I#;=^o5c zg2dqg(dRfJ1^fcZy3Fat4 zA}Vk#>weOguc|LHUPC|5<<%2tg{!9$sHKj4?)rKB$}vwP&@Gsw1c`Yx%a1Si<(a37 zYnA6;FFxR?r!jzbH6&0Aue!;!@%>_clJ2?Z{Q!KrO~eDw3v?&>(xA!KrQEm5v10=H6r)8MTnd z5b>Ha@F+ndeCZnIa@mJ>c_fIng%srFLsiR;cg3fNIdNZx=NrHJ}V|u`E>hbuCHcHel6fcCX2}FMJ$-3S00|lBI*(M z0~hI0BT`vJKJosp>N?d8-r8h7F{WvH4JAkvNHSSO&a!@FNg{eaiIX|YcW>UCkwC4+ zot-Qq<2k2bIU;=dVVM`*92aUv2@)U6UYGe&Dz{SgwTR0unSnglxQsH6&&x7fM7?E3 zhWW~vOr|?^x5=uE^NI=@o;wm-wz*hDh33}4P&zBW`Wt1%QJrOs@M97NCns>Do0=0ITTrHxGvv$jFB1}0} z%Zf?e=sFr|-9D1XBB~@~Vt45(QU3D^Suyc8*VRyh#Eqi)ETXzpDIX^rgT9Bz>e8L! zDuG%~74us}ZOR@JN5tAs0kVSSce0L#5+t5YFJKXsty<%c5z%?Ezs#QJZl@BcWsfUh z5&8BC-p7e3l>L&dD3)66XU3}jfXVe_p3>7^onuFV$yBpxGg-ClllO}|N|0#QqLHMF zP2N8r(P-1m$9(_99hSi(z?1rpjPL(MP;oh*XSEWB!o?owIZ*`N*YR#c=))atViv? z@|uWN`$o!o)PwQm6auyS@DkR z&pk>g1Zu@yD=lkx^;>=+;>Ny?vUb=1WFZYDNIVZOCo8-Uj-}#MiSubH>w~2OTonSf z#yXdm)y0}&sfp-Rqn4~e1~$s7p#%x2*Ao%DqO7btpGioop#%y4TvcRkdq{j%B6fHb zk+toq^*@=BKrMW3D2^(bk&F6yvtn12Cklx(i)zY>d%f8FWMjao&9X-SyzN|tKrMW_ zC{I1BDi@WXnn@Y;A8pE6MCIpR>QoHQkgb_r(IP58Wea9t6w&+F<)ZRay-julh>=APsb23s{RdG`SC~?tPrS$y+*Wou4yAHKdh4T z0hA!IZdGHsCMNg$gg3e-D?ck+kB&hCwcu>&TD{5LURHi~Bn*y02@+tBh8wBRDSq_w=|Bm z;k~%1{J32yuA>Br%d{qn%1^2AH$>d-&_B8Ild+USpq6i*QWjD988=T5Z<7Yf%Fn(E zrFE1bakyhii>Un6ZTgakt&@h!%1^@OvI>D(b1N0Mh{{hRexHbZ9^+-@XGz+MI!chx zmlv~$%FpLkcZs;0+f!D4Y`Ll`1ZuT@U)UllKdvDci3s(dBP%}-+E>?6>&(r<7E$@B z-SMKP5);ZVl$D>2b=`E7An~hYL5ryTyy%`tHnKEZA}c@l{;j1DsMXU}z#=L?g~uKz zVrrPbto-=btD~a?iDo16Sw!W>rJtRM_MZY}<)>_tN}$%pIe9Ij@?&WgLqy`#<+Aeg zu6|t|B}lB_na3h3KP!jqBBH~uRa{hlF1)Ry5U5qHWp0b8{CJcR@0gTZ6)r13S-aNJ zQG!JMGPx|G^0Umco``?bMas%gp%t|i0<|)1%V`mnpV-{dL?n5xm6e~}Q)=lbLE?o= z4vVP#c%)fP#KH9IWaVe*DmNV^NPG`UmR zxa&tm^{1O<nw{!RDN2WT}Z^` zRy${1oXdh>*nHvhtI6Tp5KxttV?TSw!V$RqSjcN+j%&m7lOZrF4`a zapz|Si>UlOs5glS)0KU)@^fotF@->_udmWuMCB(b>p&t{&V#b@lPP;49ktR=N^cRB zp963EXex1Zu}xNf*wH*XN|0#qER97}ek!eNPBs>N*Jb7B!|)smfm&58X)L1hvn8w{ z5w8asvhrivl~G3t5{vq$vWUu0xt`UDc=k`Mto*P?=@bIBIuA}|5tX0Gg9UNcGfq~1 zE{;m2qXY@3-cA-#`5Dl;91&hO;$-FL!f}(1T7^kVRDN0wFQ=(Qfewdc<>&dNA2yUA zv8$kyMO1z|)GR|b_AfgmD?fGiepLw6vU-~=qVhAoQgI^kvjJS!iTm7htgpV&}>glp*^vhs8Hadsjq z%qM~>KR*^cPzcoOJ>-Y1{4D$6LPU?S1X=ls8sl}K;96)t~!{%s2F}-R({&W zIn||SFgih2e)48{s}QI)@Wgdl`Elx7oroEm5@h9PZSH&rQG!IXtJh`a=iZuzM1<~0 zkd>biPa7%(YON@ELsot&9`hoi>YfBy`DwS%;~+|q7?Ashto+oBn@vPXTY{|o#C4dj z5U6!})D2nrN$9hS2=~|oS^0T+aQQ)$AhCSO4O#hFzvd7T-A^RQ%1@TghZF*}%-L_s z%Fm0VY28hx!)Fs@`sEsf5+v%ryeTU`HPnBS^4?2x}kY^&?8y->ASwUd1bqYvhq{8S9R*T|LBw`D?hnf^@zdauDyCo zR(?WbXS=I5GGYYa+|$a3tqto$sj8cAnm%9kiBKW(e~DgALvAVrYJEO(PgZ`ykEA8yxRxj@Kly6BjX?<# z+yA{UD?j@`xe(EqCCaMIoaH7P5~!7!@qw)TyvkmXh}1-g%1@(B&Nh@Fk!SD&S^4p- zQk;mU?#VWKo^VkJ)KX_jeCuZ`<;SDvE^}DNx3cn6JM54->epLY`RN{gT#P*baasAT7KTYD(64B(|5n1_pU^%Z4sC9Vn7g_na#+`^L(c!49{H$Gm(uNWwuH^VED?h`` zA7~s6E+3VZpMWLt3V~Yc$Pc$YCM!RUTia|XL4qy%AS*u}uWynK{q!+e`6=*xheDth zUUienrD&q8{8U_4!-gvk-siek9?QzlytjSG#+9^*vhs6&ULzYykeK@FsjU2*v(F}? z#)AY|`FU5bn?j)0g#piG<)_{i8D?&9~E0_j=TMN8ZTu`+i~%6L^6xr42zzVJomrfVywWwpQcr!Ixaqk3Ek z7yA~ft2EtxR{voA#UGQGxn}Erow`3S#PZBnsME>0s&1?Pg4I0j!)LE)s`=#k#QL7_ z<;&v7XqP|jW?IXIeC>=1bRLT%j_5&@xjUlO;XSiQ$zI@1y9!#Sg@mzsn}hlK(zz_} zGDot0PlEZb&!Usu9QjsXJI87?ZPJIM1c|$uLfD4VL40g~XCf|a57g$)vKm(=Oys+! zUD3V9FW~2MN3!iVBlLZidA!84QEb8Uw(@tzc<~L0s}EYUbJR_BqkS~L@vb|!6d*(`ANH;34XJKQk{MJJsemmO<9uv4& zUZ0zDuJJUNy?D?*KVG=XO}ZZ;KRdJWPd$ykO;@o`wI}jEr@Z;y^|2g|%To;=ByAkg zy@~KWaa?Pi%4+1hzlHToysW>>zL2j@x1OgNa!H>!Z6OaYzJ&*N3f9G01@+uX#NrD{ z+J^g9qvheYTG;v0_M-mF_<#&YI9*}8=(?sW&iT4x^0&uuUm~J>M{D~&Ta9H~JDDG) zDr+y)KZNfdmY3f(TkN8<+byCgXBjm4`^2`vL}Yjn#m^+Vk?~y{O`Q(iYb@lG>XqVs#`I<4 zekAmIpa->SFMm&OlbMKJOLcyQ`r(G$KA_D{_a77YW9^hvdi6?4tjOslyutyYwxjcRCZ37r58r7ojBiZb^RhR-&}?rMxSBtsuF2tDt8E5*G2)R@f%8=i_qB*MJSg>i1xbd(^Wj^p2?`qD<^ zZeJS`sCBzd9ciQJvxQ`1)*elFruR7)dimN=f&^YSiq+Py;hxW^uWx5Pjx$cIa^mTt zRgd8erFoTOEqA47u>V5ptA@FY1U>)E@%+rX*K?volhZ9Yex4hmQnPkp7vUFI+^kh z;m0RhjmtyQa+DyEmNKbF^k9BvrRY!G-MbNQx02o~8uv^`0=0f-$!b~sBbYxPAl{tJ z($35$M_Y|{&Ph5-kf-`b%-zeW((q>IXg64~QXx?LGlo$D?A`)#XnbntM6KrNj4R_q<)x-OG5 zBjD*dv7g9!CH5D}y?*b>Pt&}bZ>(l0K_a9>C%L-zZV*UBZvWhTOmV9*%of5*X?L`D zzFz$6>jiSX73(gozkIK$iX@)yUrogGPF1+}&eKTJq8LiV3Y|g}^sC3F9$mzn4BA9Q zK#qF+ClTeTdlU)OQqRhKt~u{w8&^bBUn9HkJbg;&I6 zT4md>ziDMPqC@F_Kia1q!%!l2 zniOL1QC$+9^r1uqjf>P5QGfg5ce=9I;{JN4?NO~(MIU~C?_DD5>2vjqbO%jNc7_rp zKD1k*iCy$WUz447obWK+muAU@>TwEzT4IkCdoAr@WMgKbMY?{&)7UeaGn62)>vN>G z;~I6KK1xeAX0Hg>2htrZc5jbDpjO1ae5~Bk0N(y}CL(hGw@A;G-fFD)yp5q2dC8ja zmW9`>62S$0^bJkv?V7W}3?)bey{#(!-KzJCk&R=)5qjgcR^v|dr3!&sVpkTsGwsDh z4C(2wm!-YdYxWFU!~aN-5PPiHYiZ9VV!UOPzMQ=9z7v}>lprB|9`T&hUQERK@-BKo z`pU-nl3z5GAW@)IJNY)??)Bp9F!}oA($CU9c>mf-g+Q&CBlDzkcpflE|8~`C zH0kqJ15e*BRx`1x(JEx0c!^6JRVq~^!mVR>z0Cuwk``XEm~?3xDHbHR>#w#!!O9wzeVc zYuO+k7UN7re(&#ke_Bh{uIZ@|sD*cy^3*@y$knIUf!+)yNQfO%?3}dIk&W~2|LJMg zT8;80>L~Y`?+npi+`T9FqWA{K z^CKT)tGfXJ;SJIakmiZ>5p;Fp+rcOf!sNbYxGv5&-AAn#!g7kF2}@fN4p-`I9;MU zKNV;-wwynx5U2&Q0THFwS$Vlp^aX)IM>Lcmk~Fixa-bu@x^ zrD*$2@y4w9hj1B3d2}y}ekt$PJD!O>D(CEJ^nB#H9zow}qxW%AcVQ?2-xobjA}W_$ z$Lr7@mF8Gyg#b@h#QriK6uAJCDO0g9KAIx0y>lBdlpt|-aVi;kHEBz49h$1->c-Dd z_9MPiTK2e_lf@%f5YN(RD=*kCi=}ORFmL~KkIb2fwVg5|L@e#5@%S}Xqv7E@n#iW4 zNRT*acd>{_KYssyBEFBR#1HJE^=ic-g+MLv=ZLuIbXs?zJi~O~F&avcfQXEUM;GH{ z_h;zNW(t8?;3pE%rCmmwi0;lDdtDb|8QyYCT^ZfAjMg~BK17(-d+H@9y4zWEhZ!YE zK!ijDL|zJkS`d*D0nwd?5+u}dKm=(<0<|C(B^#Y~)sTI!cGvx8lpulEjXdNM2ERv{ ziC%X@HC$zI^?_KOo+!&@&MOe%+vou1FO(H-{eR!2cm8Ol=(Aj5jp9?ur*3m{wL+j4 zME5j~cV$=cp0z16F@Cj%TKg+zv55WZWcz|#B_ems;`=F%>d?hULkSXfrWciQ)S=Ri z$wu93?tI*St8s8lQ-wgSe9Nm@=6nd@tXoAQ4h2@^C#j=x{m_;gN|1;RC?(@4j}2{! z2yb~;PeWct`XN8fNT3$ZF`6Zxe#tm$S&Kp%N|1mY2iYj~>!qIh4)u|hETRyog>%eg z%GofIHKg?_p-=}#F}ciHiri(RZ2nwiywbh*;ESl+BlU~L{6pR@WFvRiF!uh1r!jO! zONJ68nr01^bm=a2h-g|hiuEKS`?cB%fm$M#a^$jzXcxGG{ga1w=f;Iamg~0!i9x%3 zdDMXUbXF!J+O+m(wuTx`4YHQ`r!K91c9EN=Tp!0Qcf#`;^56Bj zBBF0Ss)v^Ti`8JGj+#+|gqjQ2oz2=q^4nilh*k*Hx zUqcBJB7PEa6h%!$oUPhOdq6hopPFDs0=3k9d)s60wU-omC2erkP=bVdt-Ae6%Z6X2 zb+>6Yg+MLL^_xttLp!kwQC8#Gp-vh~kidIGTW#HiYy)*0&YoMCjji~MKm6g(Yv)=l zV-QCsjnAH)-7Yf1;X6dWWPtZjww>1YfGnvQN<`F>LI@Avks~7_PihOxN}hhNif1(> zP)o#wj*J%(i8ZsbvXnjF^Tdk@Z%?cxw(;7>m&>@A zasB=+Viy%3@teFfyLev2b0eM~`U)-iZo-GVtzIEC_w_R0ujE?wR1$A zZRM^Is3p8)vHFk?Og1Jj{#sXfmVUQ0m_>a{Todvz?ZTrJbpzV5?U!y&m;Y|9?@mN) z=e6cy3no*< zC$8P3$g4+>y$tJ)q8cailoWOSPYtr+mMxkyIM{B(-YOZ!5VE1 z?X@$ab%jv0?q1MEcJNNRpF|k>wrcfhKkxT%EHi-w3E{Phx&e8fM5NstqNO9hWVo?G zAyDg3-Sj+(1@k;c5xQ1YZ-r@I6|9E;_i%<1B!mYm)-Li-iMaS;mUf2XbFWtO6#})U zJ$9%&`=Le)D0dE=&cZ_wWEm(7j=W{ zfhCE^|8lS<>IR;}+A)+MA^cpiijsdygqM+D6Lo|7PPr5UwQ%Osn-=8fin;;$y&6i8 z5c}VseB$nhd9@!@H<*+EwL+j4&U}-pRy1b}8i@79fMz$Ow{O2(r z-s0N209cd7oXYK{IjFv)LTG9*__jB1c_>Y-B67OFK!Kq7Csq z6auwiA0#5j&xhKRA+*5Pyd-ZUm;Knx*>>| zxTGxeaJCw~*M=&05DBW#$S6b9)am(1G_yEbuhzAWR0z}(QIey^Ld5Rddo(l65>8#~ zR58&V6%$;EL1r9dC3~V z{B^;i7U6M=y^s7i3+4Ky&mb!A^ligYT{Mv?TK%iDsKNi1AR&4|ga<%gArVfUyGaj# zjj5*)s0B|j5t9#mGz%|dMvg~1N|1m(n1~WNoV5hn2aA?Itq`aMD+3Xyt}k;J`+56) zFJoZ$vQYhB?&qSC3A-H;<1KH@#c4l(k$#+x5+qNvn> zPzcll?}KbiiJl|(^VO#qhTX-}hjvsBdX*<0#pkld{U->H~f$&BRUv+Oxbw z#8z96-AxP$(eoqrT2WJ{zvi*E8kv*_xnMhMP2X;7UgesO5+q6#-pfDNSj0PiOd{f^-%jTG+0!WgB1R!l3$h}Dm^h!A zC{}AVGP8`)#JWo{8xt{_*wrWkW4r5hm$BM`(Z7hOdal3B`&4LnS4RmFkoO^CXTjQR zHPt!u1SIGp0uufQT_+}DCP!WzV^NyBk5Uh2l_>HW>uJLHRUt%FC!#xw<%o#yG@tcu zWHl-uFQ5>p#VwiM;T<5z#tccO-=OEj%aknu&Pm!Px=Y z)#|JZPzcn5tPv3xFUGQgw5vT?9F2XUqGI;@xWfAuPcwPVMC9$WkNu!7y;Gin3V~V+ z^19gFKL_x@d1r~JXxYkYk_T|1PNa?!B!u_v$S2da+UOt1KGM88-O@`TP)m5)`t+`+D;`zES5wW2r))G;X zgPuzwGTk_>KYitC49>6{yD=5wLcX)wydI1B>CW*)B+c8Phte#`+-t8wpcZtF5D~j< zqyB`x(dazfhFzWv3Gs|LB32?&=USpaxZ^HCwdOp&YiBkyF63>MrN+sgxs*L<0<-)CB=F7Fvk-uVMEp+6sSen^y zWiL*{*B(TaK7Li!&qFp35Y-sb@|%;R^xcFraDTHfO;Fvl9>yt@vnCB$aoorKrImyIQqqj zcwMn8k0$>refh>ZN{|pSh@%Q1h%0k>v+?vT?`%DElpsMJRTjs42(%kC4G!ZAYg&z4 z4;ShvK?3TWM6^D5fIp<(j|xo|Ck>O1}Ow;K_>^#zJ-; zMK(0gzGfs)YgC~ZOyp$lHgBp^&T^5B=caM|>U-CW5+uML5tA;)@{IHzOX?3*G$c?9 zyL#x2b+f_iUG+3vOHNk$eUQNZB8s-}9_G2}Ylw~6a)m%G@|>8%BcrogUEQ7g9k3c- z&sS0^)#N|OzF?8fgPBj)tKHH*yb}2(C0n*ss^LhGha)?eMZS@~0(EK;uQibV{>Qc1 z3V~WM^XaUHo(to>=o##G&`aq9K%(j3tQOIQ7TiMAQnwsCz&YKIg^d;{1ZrW|g2_}n z`($qJM_%7}7vXvT?qR{+80>~InO+q161YMyKLxt0JnU3L~hD{G;5>~ zsFgPKITNdot^Yc@R);<>=iW4qw@rF7lps-uGInAu`F=yZ`Lbp+{hb(!o&U`>lA#2N zkIfFs_om*L7Zt?)aD>Bmrl1a>6RnmBO;v7*Ra z{)r;UGa<7WN|4C9d7`uteozn2BF zhEoqDN|2zOtXvr=TT4W>)T8(Z8u@nD0EQAIuru3aiYzsp51{)|+i8VDpcZ9onIn%P zY&7l9-_o^OL4T1DB}icBI*pw7;~l7Tps>42pqARp`P1BmM-p+rOc+B664+Z$U-|cG z!2A60H1gkAp%AEreVsIS8wAR?YnJ4E;|`vls3NkIDk5bpn20|p!)B+>%qJD}Gq36I z0{mQ|^wy#lc$`EG>$_2RPo&O)by<~OP9((J4JKrUBoot!`Uet$sAcuF^=QT`iv`-HK^>&P=W+_XG9GB&|2S4 zzEA$pE((EKlvQPpJS-9BYyI^BP>w$seN7@IL0peHQalrxS^o zeo-;hd@O7x~+8&dZNaC zvMU5?L3~Bm$~wG-{*>aVOylDjN{|q~n^r)Fsl z%2FTMy-1~YCw4HglhIyfhipBKwfp#}Kt9K_C zX%_NiDw=Hyfm%>Q5cgwrKP`^Nv3Hss>k+bpIOVv)=MlaS`7K1;+uu~nMQ62hWQ;+xYry*D_lu8yF#d1f94py3y>{0 zv(Rk+uJvPBi-*juUF@-9uce)pY+TGzjZGjgqszJZ3?)cFo|*`2=58#GMqV`CN`*iz zu`7#NLVGb0{*GMu-o{Z3B}m}Az0~hhYy|s4wYzTfBNPI)#6B)&JMG?NBl7DYHj3(l znKniu;5H41@RMRSGl>Bs3C@xKlbaedfe)|o1!onA&W z)WWxnRU+%pp)8zyhT86-3?)cFWt436*gKU4)7&lN@23!`C3b$X5+!>8%|1?NF0@`f z5AqWG`ELml-Wlh}?zTxYW{{0H553q9s@)A}F;^i_s}lWHlmfdK@z1qHe2_)=VJ|6* z^PbISC_zH({Nni#)mf^BpYUU;X_h>jGoGOY3G9cY_flUiV@>E8Y~?&kAy7+w-?`w0 zP*(6ZMRyx|F_a*I9h>xB=dsbO@Ci?&PrQdhpq6+SPQ(VHvP|FP__$sh`oe0w4r!{1 z-PiHHD`udT-Z=W^a(NRwae=zR9{DNnhGS=y+D(;p)-CNC)##t+8=(-W1zB}EtE%&} zuxhlQ=kKspIV-VuJKkhe&XC?|IM{$yr~Q0S%Qs4o7ZT!a6vw-kWFzg*QS8D{dao!x z8^d!)E$m36RdlfzJL^tWnXMI+UNt1d`!ZtHrZ;2AM(I+Rg+MLw&Z5ZN ziK-UugAps46V2U8PF)yEkZ?+Kn!i5h$Nil}pZ*g18xj%p&4GuR`YQx#;q0OBWo+2b z-jPo&qT)2q_sA#bcEV;670aiKY6_*{-))q8b+xm#^wie8HO`C@B);~%%r_le!Ykan zMMSUfF>C`pAEm42(2zhas3%Z#cdt_%+eqW+G^!HTAao?e&hPj(1QD5f+gS)bQ9;Xw zDFkXkrGbd*#pC7I7RrZpSGsYL5Ieski$g@3c?a1{8b_6X#wrAA;WsYGvz)tw4M}4) zhE|`h)D6VW?}%mbNSetsFyJ8TL^hrb7^_q>kPth+*r{ocC!*&Y8%sm?quId83V~X1 zb%~g9&d#RMwTkc3QK`xxA$ER8_JfG9hcWCk#W+V>msbeXf;&rJBl%M45X(n*u-~@F zHk2T-t@~v@h-OLVGq;Gin#azfX&gy6$0-DA;T)sqqhBhv<{Ev!k*>kNOT^F zEGkwVC_c}5OB3(*Jx!NcM+p+p1Iv`&S{o9m1wFS!K>x0e5+tCPmxz=e;TIL6ZAhS& zTD!ab&tdKKWBTIBRZT|;60nMr4fFGMn)ZcyCStDJkU%Z08&a(H$}um zAy8{At-FtD-Hmq^Z{AyWN3eV3GYpy4fujTo@x>O=i$ndrM6}zrnuXKzkvmU+g+MLg zQ9ANIL?qpeVmd`Ekp(=YubCo2LU?<^>m!eih?}0F>^sF#)=K>q0=2+@AR=wGNH*-U zr_ttp7kuYKyovVvxUseN@^1}jZQtC3h$5@Pm@~c2@$tWw3V~Yio(2&w$xjR=Kk=%2 zsM2$Xy>Z~r5wX$XC-$Jf@P!g2z#Ak2{6vL7E%45W$n+@LPn_0bE=LIx$H`BuNPc3u z+6##|ylW9VL2r7O7%)X4P)ohKT}B45lH|k9ST;quR!9gBU+ik+*OQIjua~hFv{JiJ zjtP&2TIwwMc>alYIFh=Gr`J*XODLBi`!~f`9w6SaP)@)62dx5mOC1*1S9(~GpzMe2 zFeUGXh+09etOn(Gy{n8-2-JdjhsKf7ry6TRk=KZr`AYW=62eOodm?!^MEp~%8(U8M z;LmI;6#})?j>fspOSCa#t;T|P^cN(d^9(!Mu!oJlZu}-tvs9-p*1KU!cN-EAh0|G$ zm^@3HU5@$yhDRy{YKgB~i8V&ll4#wXXVs!;97jqWl;6GjE%_7OGs+<7;%OF@A*wFf zhG+vQznlH=AyGa0BLRZ46uKk(L1$HI$Xx9O&60QPxcE}m9|;hU10dqcx>lMGJ%eY> zaSDN2-gnFDMf3XbvzZ+R`&yeViX1ZoN2&5>=PdwwHL5B(8kKa!T{ z(yL36AOTq_BG#_+&})(nQ>1BS`sYnJJ*qyMP1c?1ouBz>>8nFfSw}+j;H1>mX_f>O(cLKK ze3i8r$1@RqH;yiNrTR`){oI}Oy0nVUF!kYhTqHzikfTqZ#!+R+e7y;IGVMI(C&N=ILA>AqbdPz&b*eSxM(YF%Wu*Hvz- zLsnktP-||!walBom$7uf1F}&j zO+D_N+G=FTvz(&@3E>|KKau=8B1$#x!q-t%reldPg+MK+&=4{GbvHho{KR(|qw)Jk z;=Qup#})peBRfdMnj#)tbm>jfS1SZ+L8Xa^&-L5z+vM-M=7{7dK_a?iJ+}4${T1Zv z;;+6{`EKD2$fv&1ceO&G7JTuD2&ndPsPJJOk3o%%h%Qv^8%Nc?FKHKZl#maXQblBi z61>?Fs`hyXts){r>hXL&d9Ow9`6>iz;rJ;2xG<3~qxzr+&3}|2A$&JSww7!x`|uB+ zMC)#y$}1HDwbVQ4&BpK_bO(zCgevy~3CbmPFNAp%AEr^No5r zbJBMPbJ24i+(`Kznee_GIV%SBVX_gCY6Txip3LQ*J@K0r3<>dWiP*bDjgnUCgR6L9 zis*-w_fQDbg8DEKyVI}aE9qKQt1$$>sv+{1zmF^4k#Xc+iKx>qh^L~nYTaKYPzz@d z#RhrlZ--EAqT;&g%Dh6Nr`sl0l4{#7Lzj|`15~Nzv^!_BTNMJeaE_Twm->A$_y2A+ z!Y;ot505^oiSMBXl)R#~xMn*J>?B&d?r`yWow%hPU z+mqW@{(JTtwEdg5-HSEXrnBl>w2>k~qUgLik}hh0PBt#S-zIH%bjYO;sC8-SW@+PB z!B<2a@O^F;Bk#MZmWC1}cB}}KHomRBM#Q(%XQYklFP#+vweZeTtXO#!t_33V~WvN)?b-_v4!^M7+ww z8221|N#!(@ zAn|_cTWO>BPtki`B;La&Y&`exs1T@Cvs@)zjH6p-@eH2zZebJSNV}n=h7u&k&(U-- zj%R~25iw zevurM+R*%A^4!N?`>fsSvPu4Xk>}!F0ABp8JgZfwoD~TYrZER4 zy>Nl}8&%GQv+H7(^r}!oAyBJq8bjJRYchz~Q}d;?k@NItvm$}x)+~2k+VJ>!l8EZ9 zi|XQj)N`3(j<;pz;<`6~R6$!Y2AH zBKt-cX=D24{R)9v{?DIC8`dE47pHu4)sQvqvGR2bag9+x6y0S$P*j*DFkZaJpS{1SX^eRPAI8 z5~u}tmWa4M-KC98KM%&B1PQpCM8Lc{hy-e-{1&rPS+8ucs_8Jpb$D**TEX+7NRWVM zg@{=nf58q__@+@h5NSV7xz=}#XU~N|j)WUge zGR?~wCa-R1mQVQ$4zOG5u)~p!ht`X7=S*~^9l*ror!?GRv}Oe=NS3BcfxIAEy?BAQu&(};4^UWaA+MKJ7J6*$A<~U zXzu>@is-v^fBy0X_$WjiaUCPC)lEwWg+MLv)QIRlu$Z*b_n$I4N{|3wi-_zaGfEq~ zE_YQ3)B=x_hy{fsrJv~btGtd9B*14RVslcR7;&xI{@X(#P^<2(EpB4Jn)o9f5$<=3 z929=ZP;*5cB}jnpOT_iGQ&Rq7h(e$i#3Dpo3Y#w@mj6C>*HMB5L>5H2=ut9a$^50f zjuIpw_95ctv~p(Q$xNQmMIlfNA`2pnO2y4$-*Tfx6?NeSMPz&N{BFtZJOB;>)rqWS@ z1jOw`Kzyzcs0Hyk5s>$>p#%xY)er%B9~}wQg8U2-pT<^@BhTiXPDcq6ke?A}^)Zts z=I)1;$89J<0t`fl^5yn&G5iVR&+L+-SaS#dA0^8(M=gyIA<5R=QF(^R- z>=99~V|i)gO>m+@pcY(po$AgpUF0~Po-biT2@-JK$j0HdiRQZWE^_eAa_Et1@C`x+ zeiz;I3;%^^w{KEjv?F~x^pCHm5IZe}<@Yi|(>7w%=``exw6SPsL4`mq@aM_K{A=5! zjSD|xF*eYUs8yq;v~m4aWwMcPU`9=hV?c*23V~YS&y$Ud6Aw!pF&{QzY@i`gCZd_N zF>Y{PvQfWSere;#(@z*1Xs87d0NE(r`jWI^nIE8|1PT0th{-f(Zy9MLY5!S_4K&n( z*nn)<3q6uHhGrkDqXY@{Ya}^eRhKqc;0BBhG}MB4mu#Ha@lM)UwYN6L$O-{pz$GFq z+AM8sEjA4!Vf;?62GJ`$wXT=HOB>AR3r50bJnoe$Q{?^NyQ`6nGY1<;8{bzHQ3%w6 z=#^~rtLwzX+#OeWmJKCHoZ2%@+BltgG!f@=H<31`ZuG*~*^F9nBzmIS*GeUA4C+@@ ziJg&v-$eLtO|~&E?Iq0O*iZ|u6%p*1mh4H3U1jd)%usepq$pdPN};GwDZkh2^tpPS-(Pw3 zen02Tow@fj_ny~ze%`vn;t}$gLfkiMKpXcs&U@?^-Ni|2m;BB_tbg)v_xniO{q^4zKPJ+NGbov0t*VzgweGuWtgaC?WR>#2S}hvcjz~x^p9s&@TPtjhT~WuXAfm z*!N4I6(!`Jhgf5KwGnQOE8j`?2<_5O-neti$`Wpk9$)_%XhjK`Ac-}`4`}Ar=+vvF zM`)LR^2Q#(`>)1$O}u$on$e09H6LD{f0EMLXOYzO3i zD1SjqkI*jt9F5PlPgf85INrSElxC3Lv@E%k4j#wZyGOe<%3hl85!$7nim`_rc5!RO zUi(SYaI1ve#RqHLUgsUR#`XyfJwm(mQ!&o(o*e1cIR4c>O~XSajyzJ<@OS=EsayCs z9y#FFcxC*R9-&?OsTe0~s?Kw3d{t5TEfR6JMwj2N#2TfBmUU}XJ9wT)XqSG*#fcR2kz1o*;aPgh zB2>bkO!`HWYHp3rEe`1^3vYg@e6qx~z3(dr-5RZi4AW1e9--5GU;e=bGa>lLtc~B>ahWcpOXLKdZYtuF%heffDj_1JR~iE4Rj~J8F7_cFAuR#LTDuaKH1x@0Aa=qJ;d;L40y? z%&n2veqd4w?ULs%h!1xib8FoCR=ZFuO2~5z#CeSyyEXoK>&>JR+9j_+5GxLT>DKt> zo*|)Dl#th;!6(QqHQgGw%-WSyLc8Qzf;IZRzum2obN~9&5BIS;?(2Xwsia zCA3SfiCAMnZqlvsd*;eeD@w?<3v0YptC(A3>W~XOLc8SJjy39BxWKLP)>E59ttcVa zV61WfTgTkB{l@T8kI*jp8wDb>T$WoSbM)R&D@w@U5)iAGY;%d6`V+9iK$LF{YY z!>!S2!jGX=l#suPAf7uk)2-3{o~9n5UGkm*#LR|u+#1bpI~i(433)dFV&KO6-5TFN zYCJ-_(T-X}hBRY9v2CFDILh{qb;=-!KVec;+q z3GI@1&LC#($%*mr$HFhutX7ne_r4&~JCu&`J;U!qTZc+$mwW;MQSV@pfNQ)s`mazc zO2~V75H0V1)U7e($G{`BOFqefxbultZjCoSJg#}IcL#R)ECOQSh~f6-E->$luH#fA zcPB?qSN&(|B(r|t%eF+r{W>`huk$7E^|J%uM{1s9K?tM`)K`QSlpmyO)h&jsJbr(rQHs|5S114_dl4c3pn8M`)K` zQDGd`?BdpVaqzuXD@y1oc4S_?>bf<~F22qqv`eq3*hwAQ%B@kaYA>r5CG-?KGRP0g zxHW1&ceh7qmtIkEwzlq-ZjFJ}hk17kRl+~nzcnal=d{es-~aANkI*jOwK;XCQk+7% zppoqZ*Ye1K~+=J&m|zq{*m>Q1MaB#@fiY`m*>TJvoi!oqzr z^9y7=r=Oj4*0a&O)8hU)kBUL~s)C1hU|*Y-JY3^sh^&z-635!$83G46&~w4-s)#OfD&F0vA`e~Cw) zbKO&Jjn9_d;1SxTt~K_rMz?Zn*lQbkPPG!Ue~C2;?d#~)I6LWnkI*i4#_=ij&U$W* z8b`17+;Ami{}OBb_;k8k;B0b$JnWty=?C*^{1Cj zVK({h=S{(0n2=ZHlTdd410{4O0p9gp*V*jCB${Pi-|z_Sl4Jwl)rtXQbl9`6dcB4%$G2Wx31ZxuNf(MMYl4ypY0$!p3fm`z{*j z&74$1{zidVb6!<*6wlp7yI%GP?b3OdxQgD}(iFp;5Za$V*PDc?gx>8BzVlCKg5$8T zFIY2#^9Ih%%UqdP%D(jV%eMD`9G%*Q@9MoV-vo)rGxO(|zDEA4StVo|7zmj%<`LQ@ zpS(c~zjbX;3->QMPV#o-KRAV;7FFuNGMd;>@W@!LfdrW%@~PkI*i8 z{|KUAa$2yeE$$t?eUj0N67miZM2Qp40=~a$_|-s<&@Oq045HlkwcNYcMagMKD@w>a zSrD@hJn7yc7g{{nBeYB2>4Ug^^xO=-PpnjJhS7==@*W<<;^hO~r-|kZ2782d$tM;N zBPySDpC+E~I9+$PtP=8B1Vn`)G54wH=!StF;dTA@`3l75k4LyqMN>OZHS)K=TO7WH*GG~1xD$_jE&1fd*=_;fk@FglQ(^5s3OoHgAb?04Y1JS0;#&87Y-7R`{u;K1aGjfM-ojD($r8lVi4Ea;d`f*L>skH$ z>Jjo87sQT-*M|G?-lyn8cY1_&$tQXcH@}-^<9P3Lut}y)2I1=?_1W3VCvOl%XBW17 z?*3h+yGLl3>_325mQmO8dG+z(!A2`e$PNOCZ`xhv)|i&t&Lgx-_EA9GpLT;=8m5!xmDK_Kor)x)jPb?BW&D@w?Y4v4J_Zgy+5&aCbc+9ms1 zAQt8!w8PJ8Pu&co6(wY63dG6-L+$L=nfdl$HILA)CuhBC?rJi^_Da+MG4GL?_VC#O z`K9VNHd;{vpC;X&4F4)%0`ZTl>~#D!*oWtrPIJI(!FBN!;7@kw^z~%B6R)UmADtI! zMF~xsFwNuESKK4-{J;|)p$$>sdId6(uzJgGYbn-!;Cxv1d#P?UJ?e{%Yxi|E@8*)2f(Ol#uoC zp1Nd-Y3^}+H29W43GI@fI@V}jW1xE+r6234zbP+qm7g1k_1*e8qQvE+Jwm%=Zy7|J zm8V@|k~5^T?nir>u;iQ|zMs+DC0KRKO^oT+(k@9FLG-Cs)19q7P`jySkf9R(N!df) z+qtu~^$!j42C5H_h^g%g6P_+tL=e1l0LFL z%X=Jyu2^C&D?Y*2dij9&m~hX53+}QzF2FneE~AWo?@FY1Uv54=Il&fx>oC@+lepa$ zse*f11j9W-yXvf4VNTvT(catb7>K?jZ?H#d;m(nRhZ?OYu_A4yY4`9%+dc6!h-KYc z+vjobwyc$dJVLvcZC+*GKRD5zZ1+2e-rvVJ^MJ`QyL;_+_x~##;6#LGn~u7v zRtJt;5okq;NB{oS(Y+f~22t_NA>mf6(I|Y|Bed)7rhDBQ`NN8XIJ>fzjd#O+qsBgL z^!wGvQTNl;=FR;%_NG?~fGGNFb-NDl+n0~*X|$rm@oKr|xnFW@^I8Q#?CWv4t@jva z*SvI}M`%~IJ-H?e_k`Khu@H#NK~?O-&t&G0D0i>XiW0BPO`4mon`BQU&jV5Jz{U2e z-k5p+eJ795t}FK@%_Hq6*}KXX2Jv#w3+;15GxKY2zSU?&i8Ax^%zjK0Tzse)hzd^> zv%inUJAjVYdW3eZSf6JG9Ktlgi}=%h<6uGi;MC0gsSg>W6(v4glV|?;VUjIYk;Fx( z&xT`W;GQ)$-6OPX*7x})?Xt=Cfx;z0Jb%rJu)%AXm-=lZqZK9AFIa1mk59HcN|y$4 zUDI#EnoBeD+g@GEBebjTv9+dGZ%nbzB+K6kFp@P zUXdSOi%Di94qRZgqQnE2uQyGPO|}b*l?T!H^;O}}ZI~H0vWQ1$m%eUrKm9*vgxBMq zXIt|Qd#@-Z9-O|(biH+ot$p4lSmWc-ZNt)-qd0MSwnu1}zPeyq++E(TUxS=;_@*GX z;(~bD2PWIbz1Lbi$~fof;j!5-o0p9@T801Lk9Yb1;=L-iUT$W7hlf82wDNgI>G<}i z@!l(Mt<|rDH44-ja!BxTHs^k8RM{S2qtrEZEzA5&jmp6lW zd_q>(57&~@178pHnxWT{2cG-E{mxI!=4h%-_c%6(|HQPSg#Mn8<8)l=rXqGbm>DRcUHYtq;kJHMIN=0RvN=ryttjFD z&L6GvbGQRjj<0|8RgcgveNJP->VRwPJ#+D%;q6m_KI8P6*x-rc@yfqWvRnVi!z16h zrG=d}6K9>D{3pk8D!0ZMhWe@pnUQ8FCd=ZK;rK{ zaa(svX8zBs3mL5_kLw5wy6Lh<31CfVWp zazQkzcbDDz0*K2h8SScmL!tP{3X^ONXly<)W7>W8H1?_g9DcdciV_=cPK*DwB*)e+ zwHj;8NbhN{c>wP$->L2q+GXE7YYxrIv2{PwcpJ9 zJ15#M6FC#}Q7BhP5;E>)dyP(TWm9 z2mffUFFMhlnztOpspp2-MD@)4{N*jBkdQs?_h_I|7WzKMB4A)m@@+=*v{{gxVgw^dw!|R{A>H% z>Xqp-tr zV9|XZpva$X{+MWw?8Vfc#ETxGU4LG+$#g55Z5PiY zvH0#ByB7Dlzjkt8qZK6z{T+~*#)ObTz%d+dlQJ@I-k(4l4WL^idD1h z)^amId{l0n%>c187;Chm#Pq9YniAErZ0D*Z%4dwT6+pD9yJDu*^b@hsc5ABp#-jkEb6 zwjCK`w4%h{m}%6uZI&G{j>KbMjkCi*)Xw(_?OM8LmU+8tmi^@$6188)?p!`*7PlE~ z@ES91Dvhx>Hk)N%YWTYOquLmISNmCZ+1A(0Ed|EdjfY;CZG zEc0RKEc??JGpxVHv754OGY}Jck1<+N;*;cT)9tw|+o>ieHEryZZ7YK4+0iGoD>Im5 z%4KHRAvcrATaj&l!{caNcZ|`B5;kv+`D;{`{oolAbAHOUyFq;Lca}$J*KM=snygt_ zw%iI5A2u0pSA#gTCd+6=iLvYEnVWO7?DV4iSuJ>OyqybT#7LjeuFB`lH|5r3+1DzQ z`1$Seb|Q#9|I0F3QR0P-^Uc{ES@!%6B;MXL-i`&asg6%**LM#sFpIv-vdspQs8M8s z9R=d|zeXFaDA9Gx0+V|<%RW1c#23vcxHazE;1k;AKTC4%o?s_njY@My8?7jD?T4?K zet2H(|B-9#!?g8RK^%F+C$vkSp=oJNKg+ST)?pR|GWz3(mzlojkG0p;oNK>7vBJF8 ze5}1Gf36*{Y^AAj<5=7C_qkYOW}!)T^m@#XIz7y2MTtKDylWax8Ebz#G7rQj4JX-0 zJ{pjJcmF{~ugH3(-d8%$Tv2nJePP)G5Z7c(vh6+`kbmZ{K}IV|)Guny)>7l_x*jC@ zx0z)B+BzVA^pwFKp$SiF=#^P#$H7>krqP+-LhQcF88LcSs z{@yoD_KRce@AuCJF?Hxf`xuD!1$;ugKE3BH(`@J%TXY188$OGp|B*&3N@RWY zwz=i?F?P$JB=#1{v90jeAfvobXxIJ75O%H~V{3Jq1L7C#isyoOeBKD76(u@;zr>W; zGseyuPvWa5a%>k&shoeQPiU9E3UCfNJI8(sB3LurdwnQT_2@FpqaSOZug%v-?J&nq z{s7bEoBD)y>1zeg_T0(=lb^ap-Zis_4-T39OxRi?@7swZLnc2B9xavk?efMUlb?By zao0Kby7L1jKP^urjaHOsIk$SqSl6(w+wjMtd_oUFYMk9=p_S^<-v%gQYG9!I}oFNaKiPERT6Jtpk8zfvz? z^7B>tVx!-?5(n>}5inr5>L{=<4VDeM<^eaXyO4P4pLnc4_FRz3(zPchkVDj_8naLiZU3rt& zhD?46T*bs>+_n}0lb`vgCK#FaN71ERsHCt^%~e)@H{M`%|Am=aw3v*#LuIQ?kzfXUC~A!Cew zzxp`#4%!|v`5D#eQV^AwGz*yg9DZ@M(TWn|w(ba-{FK;DV&08S113LB%8u{|?b_M< zvyjQpLr1HESo3j{fXUC|>cfmylt|Rr7c%)tG`<`}?^_xNOnydmAM6p@Rqo0CA(NjD zLr4spTR&j(vw3E3qZK9I{rs1Z$I^sy@D+4A!9X{*g5!%)ArawX^KWq2a#2VeVT^ca? z+5gTRMk`7j+E~ys`8hJH4v3l)Dh5n`rjEJJBed(9nT0HqpQnq~1u?PB1p$+v|21i5 zw4y}O$;B<7S1&fL58~s^g##u(YhI~sw4%gAA6#IW{A8EoGqF$0Q!yq#OFLiY5!$7% z8yM@=K94c^X;Zzp(TWm@HI*%spN~gggEfxaHYCR6r^iQcdapt4(pMM$;_NCOGWq#& zU?cNQp@N3V&)>J!$-`rEc?2JA?JC6#lb<<*uEH9PZ@n;N@>4TA-Dssj)k22JPt%Qc z^7Jd={Z)gDLnc4Nvaa{mP@-U~KLaK|M@rVh8r>hgBxLe4aqg`ip<-%{?=i{5;Wezeo68X|M5lwR>J8 z5T<_7_n7>=Hs{s=cL+FF`TqnT-)qy`f|z#8letWOX0_ogiT?=xJJp5nHsBinK8~fE zd*(9vIbPm94ypV{U_JLU{P%IR{rU1Flb=ch_wjL@BeV-YL-+sxz3$eTz9yHCV_TD3 z_|rXCQ9^%DxWnH!Ba%C@#@?E{Jwm(mS&2R5dBc-Tex`Jq8)!ud|94&_{%w-U&#BQR z`5HX;4A(AwPUG`n{PK{=Px;23j6UP^nP?B42$=j7d5G7t3T3C2Gt% z9x(aYpIDUMG-UGg zT-^~yD@q)_YfHf7=WO*VSmT=)n}tk%N?kwNBebjP)0+Y&Kldd0P9{6iB5Z~CK7D3p z8?7i&=Dxgu$i#zd1Kx^0R30#UOrdnI1Cv+0tjK(TWn& z9$FqS`B}KE0*FsfvP(+yw4%h6_`-n6 zPs>_-zkBH`%|j+XFBZY6d-+=0wWj=nfXPp>#e7e_qIa{9$NE(M{9Lkou}5gv%{xW}On&y6QXsDA zbXCaYXV1+`jaHO6ykS_tpQ`Bci6g!KPBQtqr2YFw zD@wG#rdGh@XL%K_(PGt~NhUwisqi9VrS1IttnnEcdlNut-Qhm%Zx1~gb_w4%hbknVU`3Zp&LR`MIhu_bmR~zi79% zKsuA3t7h^4UtH?MdrW@bUf>hjRiInrbS6LdZzVCme5KV)e)_$!*=R+HZ|1a4XYzCX z7bG70vGr;uKQos4gmzuEaacN&pI55v2hnas=haMp8m-)Hw4%f{YX_w>`RP%f#M<^R zuV(U7J?RtLwYlr^bS6LBpCEB;_0-i&elpfiV|sS3uG|)`KSPiIv*6yW%9FqzfWja=dO)2 znEWhUPGZ;Din&aF?)+}E@hb9lubI<2gUL_&F%m1PwaR7kQ|h!&XjiWd!!nrs^gneF zM8#WcC7Jw`tiQ#adbM?o$1CO;<& zY%%(EXRH~N!Q^ND7YD7s#y@$PxlDeFU%16+MTrrO=4LSYDYfxStZ`f8vAIls(kl6c zc8%?_JcG&49l=*1#+I9%%jD;oE4LV}DA9HH`x#7rURXh*-^a^xnf#2d=M&o1_qPKX zOnzz(`WnQQ9XIDP`5E10i_wY_KjasPG5NVZ>l+Z$9y*ZglAm;+(5_kQ3&)uJoL*0& zQj-(8Onx>6TZ~qec=uG97?YnRFMbPR@YJ**Z?^zyW@>BeUUu^T4@5h+@%)H}-y=%dy z7?YoQXHQ^_mG$39GWjV~d6UtK5|5VrCdTBa;dv)P)c*WHlF84mQtORgk@ZUb&gaDf zCO_F@{{r#Js?U>5epWrX-e^UMYd%K0p5m;@3o{B$J;eIMuI&c6C}eEXL&L(;h#8=s*3D zB$J=+cC*on5>KBTA7k>J!@4rSyy#lb@%L90hUuf+0yJKkc5_ zY_y_8@dk5aOnyqtq5md=K+yGJ@&otBBeaXI50f7lJ|O7&F!_P|W3-|KU7!D) zAG$tFe&GIikAtoclOLEo-ebbE9j*_PAGkk8zjr0*`Y`!{ql52?t`CzRxIZ4DU37hz z{J`)5LDz@L58NN46(#8UF!_P61A?v(lOMQ09-&=yeVF{f*8xG-hsh7zAERA#eVF{f ze0jD9U8==w1Efun;p==w1Ef&1eT+C|rg$qx)45OjT*{J{M&T2X?o z50f9bEg%-&+?vF=k7hNAFKQMei(Dh;R1NX;hMG3k-On%_#fS~Kc0Ct#e*av9>*CIMaDABk!2R(E?c(*8Yw%}@HQ@U2alrkdQFX4Og#Mo36~Xmk z@&otBBeYAOm1${oeVF{f{Ry<9g#SCI>%-&+?vF=kmp-TQo&l~8lOMQ0MxSx|Or-0> ze0j8>GO>%-&+jt&UAK1_b#{&<9T(e+{S1H%UdT^}YtaDR+el%VUw ze0j8>GO>%-&+z77bwK1_b#{&<9T(e+{S z17C*(TpuPsaDR+;(e+{S1CuAuC+PYx`GNamw4wxEA0|I=bg%|pA0|I=e>_6F==w1E zf#HLzC|#dcc<%%E$7n?fx;{*P;OKy$>%-&+?vF=k7hNAFKQMei(Dh;R1NX;hMG3k- zOn%_#fS~Kc%-&+?vF=k7hNAF zKQMei(Dh;R1NX;hMG3k-OnzYafS~Kc%-&+?vK%m5_El-{J`n~LDz@L58NM*&@Q?@OnzYafS~Kc%-&+?vK%m5_El-{J_xxLDz@L58NM*&@Q?@OnzYa zfS~Kc%-&+?vK$fx;{*PVDdOS z=s$w450f9bKSsZn5_El-{J_z{8gzY_{J{P32<@Wl!{i5s4+y$GOn%`07_BHl*N4du z>>ChteVF{f{qYFxqU*!t2Zj#_x;{*P;Qkn`C_&eU$q#%T5OjT*{J{M&+C|rg$q!5( zX9xX9(Dh;R1NX=1*HQv!c`cJ4I67E^t`CzRxIZ4DU37hz{J`)5LDz@L58NN46(#8U zF!_O_1A?v(lOMQ09-&=yeVF{f@Bu;Bhsh7zAEOl|==w1E!O3qBbbXlo!2R(E?V{_$ zt0c95LDz@L4;&p3bbXlo!2R(E?V{_$%-&+h7Sn3K1_b#{ur$&LDz@L4;&p3bbXlo z!2R(E?V{_$%-&+h7Sn3K1_b# z{ur$&LD$DQKh7AT>%-&+?vF=k7hNAFKQMf-23;Q}KX8AHR+OOY!{i6{4G6kEOn%`0 zc!YM*^>_(Dh;RgOm8q^j{$|7(Q5ot`CzRxIacKO3?LT@&iW)1YI8{KX89MLc8et zxa8*^n%;DMnEb%~F%-&+?vMBSP=c-xlOI?;Sc9$)lOMQ09-&?OT1iWz z>%-&+?oUY9hsh7zpMb6pa~#+(0bL*FJ1~53#+R-SlOMQ0p;nZj>%-&+jt&UAK1_ao zJ^ou#3GJfm!{i5s4+y$GOn%`0B(e6y?jiE@JzXFEe;7U>==w1Ef%}uI6(#8Ukmfn=v^2Ut zOn%`0B$d!Eo;l|lJZYYmM%RbV58R(nzh8YEbbXlo!0-V<*N4du+#k#Z_^+Y_T^}Yt zaCAV>^?oo9~eF$==w1Ef%_9`MG3k-&iSdqpA}snCO>e0JVLwZ`Y`!{ z;RAxM50f9bKcQBXpzFir2aXO1x;{*P;Qn}ocG2}=@&m&M1YMs8r(&vAR*g_AO3?LT z@&iW)1YI8{KX89MLc5&ngX9N>4+y$GOn%`0gj!L8t`CzR7&iua6kH!BKX89MLc8et zF!_Pu1A?v(lOMQ0p;nZj{le!JT>)5IaDABk!2Joeq6A$ZCO>d=K+yGJ@&orLsf2dv z>js~r;QBE6f&1gVqLiTP!{i5657waTQyR$++#iq7E`4=jpBk z450%$GW;pfb4g31>%-&+?oX~(l%ONS>lNJ=+$#*O50f9bKOUi7bbYu6{&wImCtV*V zCUAdRXhjLSK3wBpg02sfAGkjmN@$mSxAe0 zJVLwlISuy}t`CzRxIckDe0JVLwZ`Y`!{uLFXv50f9bKY@19^d=K+yGJ@&otB zBeaXI50f7lJ|O7&F!_P|6KF*Vx;{*P;OKy$>%-&+?vF=k7hNAFKk#)x(Dh;R1NSG; ziV}2vnEb%F0YTS?$q(EgkI*i!{i6%-&+?oXf%-&+CQs-SbbXlo!2OA7MG3k-On%_#U=6xHOn%`0c!YM* z^Q7==w1Ef&1eT+C|rg$qx)45OjT*{J{N*X+;UT zK1_aa@*4zQA0|I=e>_6F==w1E!AWxvbbXlo!2M}K*N4du+@JS!|AMX$lOH%btMM9y z>%-&+?vF=k7hNBBx3_MMLD2PK@&orLT`Nk^^_6F==w1Ef#Cy! zt`CzRxIgJyQG%`ylOH%bAn5uq`GNc65!yx9hsh5N9}skXnEb%~N!N-JbbXloz|jFg z*N4du+#iq7F1kKUeqi|I;tqdseVF{f{Ylq~5_El-{J`n~LDz@L58R&&CA5pK50jtH zT^oa->%-&+?oWnRl%VUwe0Vsw3&{NVh2 zlCBSvADqNb()Hn_6F==w1Ef#Cy!t`CzRxIYe0JVLwZ`Y`!{;RAxM50f9bKN(t4g02sf zA2>Q7==v~~f%_9vLc8etF!_Pu1A?v(lOMQ0F|8;;*N4du932pJeYghPACJ&3|5-xU zhsh7zpO{vZpzFir2UZW(pzFir2kwtYXqP@iasCRf50f9bKQX#KOn%@tBH0AF zf%_BFiV}2vnEb%e0YTS?$q(EgkI*ijHM`#yapJ>hx2)aJeoF8Wa zr7B8@^8H4^x)B_j9-JG8o zlOMQ0p;nZT^V=Zk`b2YnJVLwVggFShK1_b#{x~-&_5JGOpz9OO`2j)KCz|u)ETB|H z3A#SfoF5Q$eWE!(9-&=yeWE!(An5uq`GNc6ETB|H3A#SfoF5Q$eWE!(9-&=yeWE!( zAn5uq`GNc6ETB|H3A#SfoF5Q$eVF{f{qYFxqU#gQ`2j)K=RqVtaDSWyl&UB}*C(3u z1A?v(lOMQ09-&>%_4#+s4+y$G(VU-uEug5P1YMtK&JPH>KGB>XkI*iX5OjT* z{J{Nj7Er39gjfY2==wx+ew+owXEkSyC_&dJn)3sKu1_@Q$0M{$UpH>fk8^(D{&=q_ zCFuG@bAGS}T^}YtaDO~PyY$tCzqN3EqB%byT_5H(Fm{Z1Oopxx^Bvd_c%9SriRS!- zTA}L`&G|9jHw}ujQeWE!(Sc9%lH0Q@7w2Q7!H0K8dU7u*qPf{ElBZiZq z>%$ZPh6f0`KGB??P_G$!EfFIIKV7;$(VU-9D@usd0)nnjH0Q@7v`fq$d{=aRn3%x* z3ALhxxH(vZt`CzRxIZ4DU1BI<4Z1!|e&GIuT2VqABM@|bqB%bvp9f+!`Ekh)+@DY@O8CEXx<1jIACJ&3eNMYMKQ8%!`xELj zPM?W%eWE!(c;s|_nEb%~3ALgGU7u*q4+y$GOn%`0IBzKRwX}<_50f7lJ|O7&M00+e z1(d2NLDwgm^8ZKOpG(F!_P|<1C<5MG3k-(VQO;bbX>ZKOUi7 zbbX>ZKOpG(M00+eHZKb*}Y1YI8{KX8AXH_6F==wx+en8OmVe$j_$5}wBiV}2vqB%bx==wx+emp|E==wx+ zen8OmiRSz`3n*1lg02sf9~eF$==wx+ew+oAswhF%Cz|sEg02spAGkjrpH0)-en8Om ziRS!xgm%&OiRS!(pz9OO`EeFds-gs4pJ>hx2)aH@e&GIigm%&OiRS!(pz9OO`EeFd zs-gs4pJ>hx2)aJeoF9+SF1kKUe&FkXpz9OO`ElM*>TA*UiRS!pHjfZ=eWE!(&KpX7 zEhXssM00+y23?K1_b#{x}OLRZ)VjPc-KT1YMtK&W}fE7hRud z&JPH>KGB>XX91-uO3?LT@&jK71YMtK&W|&VQmfPTVe$i$hqHNvpz9OO`ElM*>T4-M z*C(3ugEi>-M00*TLc8etM00*X(DjMt{8+6hLDwgm^8%-&+?vHbQqB%cC_b=%BF!_O_1A?wk zH0Q@7w2Q7!H0K8dU7u*qkF$VM6(#8UM00*X(DjMt{CI?R(e;Vu{D7eA6V3T?7Er39 z1YMtK&JPH>KGB>XkI*iX5OjT*{J{Nj7Er391YMtK&JPH>K1_b#{&<9T(e;Vu z{D7eA6V3T?7Er391m^Ml>-@Bx0fMeiH0Q@7w2Q6}lOGs9An5u;bAFr!l&UB}*C(3u z1A?v(lOMQ09-&=yeWE!(An5u;bAFub!{i6&=Q(x5B|kWc&p9nF`GLCug02sfAGklx zG)k?`6Zp}bA5Qa;HR$?8bAFs@lv-U0x;{*P;OJltx<1jIACJ&3x;{*PVEBNb>%-&+ z?vJy8QWYiW`b2YnK+yGx=KOescG2~T=KO%5>l4lSaTZXjq6A%^XwDA^x<1jIACJ&3 zx<1jI9}skXqB%d#0!mespz9OO`2j)Khp7zQACJ&3x;{*PVEBNb>l4lSaTZXjq6A$Z zCO>d=K+yH!8gPF+Lc9ED30lx?qXb=_XwDDTpzFir2kwtYXcuj?)HBr0 z`Ekh)+#l!qM00)&T^}YtuoF1V$0a{-O|S-CpJ>jHvw)Zhv7!WBpJ>hx2)aJeoF8Xj zrmo0(rKal>&G`XA*C(3u<1C<5MG3k-(VQO;bbXlo!2R(E?V{@w&G`XA*N4du+#hEF zr7B9$^@-;EfS~IW&H3>N?eZTvU7u*qkMo~WKNBVB`b2Ynum)Y9XwHvEXqW%{pz9OO z`Ehn(G+B%j$Iktp>H0)-ey|2zpJ>jHvw%_+CFuG@bACY3^@-;Ec!YLgnvY9l4lSv071ru1_@Q2LxT8XwHvEXct|dXwDA^x;{*P;QlxZC{icoURYE z5ZEwrx<1Tz;Ok)DhprEkAGklx0!mespz9OO`2j)KCz|u)5!yx9hxrZ+9}skXqB%d# z0!mes!1;o-XwDBFIbEM<&X4yv==wx+e!R!z=KO?oe&GH%vnlmxm7wbr&H2H1Mc0SP z58NM*&@Q?@%y(e;fS~IW&G~T_P^zK?T_2`3@O41Y^?pT8u&UO==w1E zf&1gUq14x+>%-&+CQsZa==wx+ew;Uy`dUiR^@-;EU=6xHOn%`0c!YM*^jHvw%_+CFuG@bACY3^?oo6u2}X==wx+enPrF+zW@p5SK|Cak@VI z|L}D{(Dh;R1NSG?iV`xj0R&y2XwHvEXqQZt072J>$q(Eg=O(4TUws^OeVFgS@Bu;B zCz|u)ETB|H3A#SfoF5Q$eWE!(9-&=yeVFgS@Bu;Bhsh7zA7=rjDoS7;PY})d0YTR% zn)Blk+C|rg`3?*p5OjT*{J{Nj7Er391YMtK&JPH>K1_b#{&<9T(e+`z1H%UdU7rV$ z{J{Nj7Er391YMtK&JPH>KGB>XkI*jX`XJwd;RAxMPc-M}UkfOzC_&dJn)3sKu1_@Q z$0M|ht`GAa7(O8A`Y`!{`{OL2R7DAy3j%_!Pc-MpSwMVN!#jv8LDwgm^81TUT}I2tMAwJO4{QjmLDwgm^W!X_RE4fjH0LKyYbf=V+?*eGw>P*y-Wp2K^@-;E zU=6xH(VQQT&@Q?@(VQO;bbX>ZKS^8-QnSH$^>KGCgZmSw>%-&+h6f0`KGB??P_G$! zEs>cvAn5u;bACdtC?RufK+yGx=KOes-<4gHzghS?Ae`%i#02gS&LsU;@rk81>HNUa z0YTS?$q(EgkAT&5t_$C7$Ti^WfS~KcXkI*js4Bc0P zuLFXv50f9bKm6&Qt0hx2+a8jnEb%~ z@d)jr>%)8ph7Sn3KGB>XX91-uO3?L*=KO%5>%-&+?vF=k7hNCbJ1~4e(Dh;R1NX;S zK&grnbbXlCz}Epm*C(3u;}P0L*N15hd>s&UeWE!(&KpX7ExJC@oS(Q)(Dh;R1NX;y zL#eN&1YI8{KX7!g23;Q}KX89MLc8etFyDdU1A?v(lOMQ0&H_qRl%VSq&G`XA*C(3u z;}P0L*N6EI3?C45eWE!(&H_qRl%VSq&G`XA*N4du+#iq7F1kLKGB>XkI*i< zKFoJu_<*466V3T?7Er391YMtK&JPH>KGB>XkI*iK1_b#{&<9T(e+`z1H%UdU7u*qkF$VM6(#8UFs*^F1A?wkH0Q@7w2Q6}(;E0X zAn5u;bAFsRl=@n9eWE!(ai5^;6V3T?-cagmDM8mKn)8D-==wx+emp|E==w0!Ag>%;5?_6-QSKGB>XkI*iXRQ}t)pzFir2aXQ@KV6?_&W}fE7pD2FX1)W% z2LxT8XwHw-iV}2vqB%bx==wx+emp|E==w0!Ag>l4lS0YTS?$q(EgkI*iwuu^6V3T? z7Er391YMtK&JPH>KGB>XkI*iZ zKb+ZKOUi7bbXlb!0-V<*N4du+#hEFr7B9$ z^@-;EfS~IW&H3>N?V{_$dN?V{_$dQ7 z==yLCxIZ4DUH-F#t`CzRxIfMnOFe&-pz9OO`N0}=eVF{f{qYFxqK%e%hPpXFv1rbZ zbA7ny4ePXX91-uO3?LT$^p*>1YMtK&X2P%Q&(iY zQq%Qez5~Mt1YMtK&X2QzQWYiW`b2YnK+yGJ@&otBBeaXI5Az)uJ|O7&F!_P|<1C<5 zMG3k-(VQO;bbX>ZKOUi7{v)UB6V3T?{!{8_q6A%^XwDDTpz9OO`SA$t@_!$6eWE!( z&Mr({arF00*N6EI3?HmP*C(3u<1C<5MG3k-(VQO;bbX>ZKOUi7bbX>ZKOpG(M00+e z1(d2NLDwgm^8ZKOUi7 zG~QCL0^Dr@u1_@Q$9sJ!LDwgm^Mf_$`Y`!{`{NPXrLPra^po2qv454o3FahECS#w9 zCza_<80_`%1allGjNQL+vK8;h#+R**xeS?!l|2rGUEVJh&%9-_Iq>5egJ~6U>|Yw3 zZ8w-b5y!r$!FhCiS3K8_UCso~xrbU&f~VK9Q)F-bs#hdKttf$Wy>1Phw+3F5x9WC=`02(_XF&RM%hj&tK6Z~{BTK3sw)u$9m*oW^!* z@W1YqcZj{d1W$QuMG2f2H~bCqzwRWtdmKDTu7q~+`{z%Z--A1?9%9cjvGV0Pp;naO z_s=!Bt~(JQVqY|YX&4@%UH)?yr|v`Sy(TbmBh-o#e0FdR{`_zk!A@<%Y51M@dVH8i zXqUcj($Yo_n-~7JCo^&P>)(Z1QG(BMuEA#~_S+wQHN@^<0_Vd$Lc3@`V8@#_1PIJZ z3E@p7%-!Xk7m=!X1Uw4th0}%rfmtabcFz;=Cp?0-MXC!^Pz-j`4a^7-n3WR3n@GT) zfPML2MF~ujFxWjeI9(3n=O^phAKuDLl)vl;@5-RBdCbj;r(HJLz_P)!1QT^EGL{4^ zn@}rCV7g8mIgWvG1A^uba-0NA9*@v2O!J8&5i+oaK+q0)aB5~^(ZPaND@tHWP#k%b zfjI<%1`_h9M8zkHd4zUhj!_)RmVxyIf|e69uLP_os}&_M?I@01&A@=-8sB%a$kh@s zt2{!xFpnvYgwDX;0zq2~*7weY%~#`?#qxW1=~{VI`-U86@MhCXKF*Pms5bwAC-lOstyQ(Yc~H zIY6tF)7cCXegpf{U}l`bxdVEnSYz`q!|d8>nTZ9XZn0WXLf1}9Yk2l$JK@sIM4?l+ zd4zUhW}Lz41Oty0YutO~K>Jbi%tZ5-5>_ip_>aSG9Eb!lGjV8tOOMbl%#SlTQD9)6 zVvR#B`q@T_%tX;YGOSjV@PE3P!e?HvWWE*5+GiLm>NRx3(inu|ehU|@KF zC_1T;MQ)JTar7CF&@RlIF-RZ`>=Y2RQIJg}dRBPCYDEbeFUUU(Ocne!r~=~!`9}f< zj7Mk}=H?hADYR@r(5gYkl7MC7?3vWp!bBZ|RK~!viTebm_E_XN379-qD@tIRk3qg; z-~nNcFGrTM$chq&x7^_o+JzZI2C0*Qkp$vK7)Z#Y5MKybSCl5Hnyo zA@fSWdh!VEqDh7H%)qPyacp%Vi(D-Mv&uPEsfrSqsAQ1c8CX^zXlo(6OTgap2<^hm zCxaBwzykw8BW%{p%mfTEs}&{uzvr~hkU=IeampjK3zMh}vPlCw4QpUpT8R8S0fW+N zMG1ZXfV)5~ZflYJBuZ}^>^<8t!N(xeG4OqizHYD&ci#;b$xj0AkN1jFg02tp9Rv3V z&t1&_6F zFptL|`7yA1Kw!>~Me>t?`(w4D1g7~IB$77KE7&tm0==vb}Nx=QFT2TVi zd<^m(1NR36=KNSBKMA-$9-&>B&0~<(7+5_ZFz3f2`ANY2v071rt`E{0nmiy%<1{h$ zmJ-)|mSb@bb%RgU2Ind{BfwzSh$o5-PZndJiRXqvV3L5v-ckami`|*yR7DBgHQ!(# z#o&xBh(~a~5}&pcIB)3@xVO5&XL5t{mb~ZsxwVnw;0z}|(I>9W_P;A7a4&a*T?2#j zomd0+h_~1^NZ{P4_c*i*cbhlZe=sx?`;WBPVM*YOt<{PWxVOH+E{?%@TM`9ES?uB@rVRB7 z?Se^QupeY_Ru}~40$A)6C2&@l6G+Zgl%V5){Y0KL27%cF7Q0c2{@+gU2<@T?fn6$^ z5g;%t#bWn70e^z?QO;GA;CXlKe$t-+!E^1{WT?kQm z&S;CB)CA7byR-ADucZXf=VP~)=jyRWcbw11ZfyeR^*utn=m22f*T4w?@!MacEp~(x zZ~~kikg6zwSs(_x&IWz}2zmxw1Kxp0XcwlH80=pgxD6mM$HZc1I{~-BYDEdmG%?sc zH}D)lU{;F7?s)?Kghyx>rmh(5!y7mnAil#sI(Fz2A2%6qwW0)OvlyfR2EGOe%zUv( z0TS>)JVLwZmLN|sa7{qaEkV+dfNSEclT<|s`YT8?47?K%m|bI$W+dRVc!YLg3XVZ8 zLT3g9=Hpl-CJ8t*&V@;REzHL;$XGbFf>UsW_y-;iQkle*;@O(0-F!RYE1vD_k zK+p(7KA31MT} z1SVV=WT^($8wgC!vdB^su<1NPyD)>xAg?tr_CR1dmqlKifU#$_q695KWWoma9*Fp3 zV=Xe_#LhK7pT3S!5OffgqR5^zVYR+PZRIfF9@27W3C z%%Zb6osfW^YPF&S=F%CQfG}`XLDcM!X>kG~(e+4cH z9-&?SyI0Jdv^a&7fQRlJ_SE}YB`|-|;0%+2la4ho*V5voQv$BLM`)M6b9U1TT=H|Q zz+1UIrOcgpp3%mg>)pS3x|k=HnF!&WD%N>`bR7 zslxzQQJhQUehJPghFVdAXCJv=g0qkyaNl#cU-Dba^iV5G;2!94?w8@{gQ?0O+)R%edy!dFTvT=z$b98d$(Wm-R+G-tti1WwcIbk=~=AtZTSIiza%Wz z$Ro6i=XSYYf^)necy5>bB{;_$YDEd$zdz3X5}fG;u^4BAxnF{_!XBYrJb%nx5u8T` z@$;_x-G0fcdNo6>D1kWyaqgGkY%&O*ad!J9#cOzkcJUlF_e*fD8pJ%Dqvn1I&Q*t6 zQ3CT6;>AM{koU!!??ZSQU zAM{koU!!??c$kQ?y%tWEC}3B-|evAjBThDC3vQme~EBn z76k6t>vmXj`n{UusU7aH;QRvb#p`xha8e}36Fl5U!I^`YyJN50VZkXL-q-hBMG2nT z;SLMVvVh<@2JW!nT!Tm89;R-G1?L)gZ_{&YW8Piy&2ER~j^DGr?@9^WGu7>|;2Z_k zz`a=A4hzm_c!YNG%m;T^a0Ubf&wOx)1!q8#T2TV`esw!6I1d8COx^5uShjcR?Gf6A zyVJTI7Mx`Pf&13F9TuErNoqw2+{4!Gu;5$^2;3Xj?Xcjyj7Mk}&){%}1!rB-f%7>aF1&n;+hM6UrHMyq7w-M*_EB&G5d`i@?siykPLcN^KUYzL z=MuRqf)i*U8sYpHcUYdiyjoJbaPMfh!-Df#( z+hM8RadWO#l)ydE-3|-RMS{S+)!h!uOCK-u2<_q-PVS@NOeYAQ;p7g>xN@^|wW0*i ziE>v2=Q}~*9`SC6rCsB(9-&=4@5&t(oJ|FR`_Q``7MxAZ)h^tJ-tDm9Y%1?IFU0RS z@5&vPi*CM~_q0D(QG%y%xx<3RQ@I|YT|DW_eU#2!8-wWd-DbDL^6A-% zxmr;Icl>udEI2m|;=}!$-3|**7kh+u@x(HBSa5_uU;=~NVZo_v5SZ-Xc35!Q+at7# zC&;ZJ!-deEP?XckV{d-Di7iM<29Tv>&XyK-LxE&Up@PAJ$N?@{w zVJ3`c`fKjq>TZVx=Ph|p`*VLSac_0E!-Dgcyyv?79bA9gMz_O)Go4ATD1m#qyB!vs z@5Ge>_lS2pEI2pn5!%JGsN7+}*;Kw~z*$u8u;6TJQY%W}p7d^q1?N;j@VqN`SaAN; zBeaWWYPrLLGqxabKYh2uf-|;Bttf$e>$@EmoVNw>X{q&Yho#Qv2RuT%XjpKE1;z!4 zx-YMDJ1l30A4+OP33?ygVSxt%0yAIS4huYxq*jy&mz;GwEO0_VV6KeYVS#Jn5!!_b zHF55+z-Ix0*)?v51wKnsD@tIFO`JO{a9cpE!u`y+!*b24KRrUbXzp+y1zrva%;0f5 zEJu6&oz#jFw0O9~0!If#^L=aG4$HHf(>TxP+}F}B`b6AefnNk7Z@^l&!*WZnf}vKF zptHms7Pv+rFt5n%u)tyR2<@U5#T^!SQXuF>afhYA^5UUZl)!wXICog!Oo142CUiS2 zaIri>yZm>rnC;|tSm1kwT2TUXp5okLf%}CuFh9!eu)rzv2<_5$&baQ*Z|zRX79L+d zxZv5^?xbwlYH7~>=Sf-I3&3Jlr#mSNf8V+ppzfqB?h6oTg?9@`5%Q@I1ZIG`ld`xk zfJbN-W_7xgvhepoG~IidJ1HBs*%#A_5_GA#Cqsi8YrOoGJ1Lu8ZxiQQrgn!o*D|$h zWHH^-os@;~k2Rh{YtR5)^BqsWye$=9Mg&t{&z*gnMLc4U|59VafP42wt-lHww>-;$A5rHsRhVJTE$AZv8+jN?=B^ zJ1>g+rhpjPeXu((+UJ(W9-&VPPIEPT4hPIKr2dMW_6tBMR6Y+5R-5}9NZTtf&1fl zgm&@1K0Ggq`}~05oq%{=v_iWUfmW2@-G+Ex6n7s2fl1@;yy)0%Eds45fvMwho)^WP zh(J7Fe~LRVy6?(#kI*jOL5b%@aepKbOR7(E=S5F`+9J68vGQ@A7d`&&TbzX+=Xp`w zYl$<<<-2-j)?4npXw$w|aqfJaXB~03EY5U~^SmhT85N$MQZml-qPY7M*4SBOp*t_S zx@MC=D@y3vxbMfD*WG#1*RO5t5!!`G^KqUR#oec{#sjy#>duR1wQU|~MG60L6mB`o zofkEKHS-AV;$5tGUKIDM!Ws`=Ki!=dT{NaepcN(jpYCO4mb>$!xSyBzI3{c@5$Ac) z*~15i`ZL74z9R3s^P<<}R`!0nO7PBQJTHnnnc=(Qoy&M$6n8T72<^ILS6ZCsMRCV5 z5ceEj>&}bfPG&K!D8W0I@w_PRWCjAhmpd7Cws-iz)To#r1UHQ^OLi?by)L@b{rhZ7o?H57+%i+~^nk<_M{~m~tFE%An~XGf zoZJ<>dgt4g#LnDLf<2gB!+)1G0|Pi%2j-a&8RV=>I@?ZNKCsQM8e=XR)YnvPc);eo zGtQj1XP9Zx|0COZ!#HzhKU3s#cg{4w9UYK(xZh1?Bn|(gqs;FYceK}CFvES_njKr% zHl?%Ozl;3V+2YgPKgYxChGZu0eXomIeA{I6XYCv_Gq-5ouO;W2`wmYs%TJfh`+V9= zvp$?;3S<5&uDfLu_MiXb>YU^2TD~@(I<;-vOwOL1+BR<8-s;v?PL(ok(x^)6)OK?A zq_%C_w%%vvm)rZy`&aYnTHmuaX3s1P-upU>V6H;80H+vvXqu?eZH?USQBtUDf3|a> z3~SO%|J}YyFlw$F-+I^a-!INj$7-Mv`C>+$I;7XGoLF2qX2@l!|1Md)815tb^&C;-rmwS} zXJ3)Bbd>ykVy4)YH%!*V6CI2v8s}E{|9e&$;`xXa%kiv=owX{4XO7uCHcb4TafwvV zMLi!pCpmt6su*=ui#Dyno!6YWN%V;Ca`r4U+OF9>MU3anAQ4*UkToS!>KN}YK_Yn4 zS?iwPZzt!AeZw+#6+onTiJjupHYueioRGY@%33=pOAN@^xG`;K<&fgm%f?pHQ(hN z1&G`i=eS$HbvXwn zS#7g~33Xrk{`z}?m{cs0euHsxCU!HyTI%lAQ^3;z5t(?g-S?fZvsKycvc=_0;xYC# zT{1SQ&*S-Dtqr>a#LAQ3MZo(icl>A3jY1P4Tu)}l_@6<66eXbsJ z`=Dotyc=Z@tY!8Lx!CTg|yw^YloJzNpXSG2Rs!G;G;=3#=h%%|IX z*f?u^VVCnv@1^qPk3=$G*--H&TP~kEOAp!a0)xc-QCQ)0@1m`)>TbecxDUr9m$mG< zuk&F3D9I8ginjH)RS#E1U)A0d(=49{zRuzfw?VL0aI;YTW<%O;hK+~gI#~yBAB{%F zNR}`$eo0Nc-07LZT}D0K)yHaD8F5v0`a~N9YniR5`pq=fA>;sj>+Un!6%+pV3fZ|b z%@k*os@46iFKu^3-^XmK@-YTsYW>&7u+R35Io_&gXuRW9G3vn894>a$eeg+9!u*z%q7rWGc3E=mm| zd9@2xU91c{wZ61u2@}tXZP$2U);fZ@*2T6?6NM{I1re|PFKY*Sxc-~x+f_0b zj9EK$j_6$epooe|9iv8{{X2IG>f1rQ-sUY2k7xoJ>2-Y%vhR&;YiuagxkIaTg{1@BwcW~$ES~o^B{S{%hX94b*Gw(;ij`<3!`l|OS;7QH zGwpY&Q3%cKAni_==559Ga_;?@py9_f3)}m(!BK_GI;frULw`Wt18f+#onn^XP zsZj_!c|MF5-=Fz9XLKxL5UfRS*6rbOu-HD49d9t(g(nV{F!8PJ6}bkjr0D(IAd+T` z5zBEO(v!l@6I80BKrXs1R!508Y?J0q)s%tXGlqIka-QhCUgn_)Nn z*2#76W4+nN{V|9dQB_14^jF*JzP0#wnZRhK`ztlNA;!77SoFT_>-=X?6EUFJbNT3J zps1K`y3AJmmQ=pzfR}zU4tmiy=tToPBR~ZALCMok2`r7POq+kgXh}U)8uHtu`)fj(}NR3rO7cws~2-f;g zBusy`pK8G;_E`F@o9GK7>FP+q5+)-0yX5UhGsT^h$3e`@-A8=Iob6VV7aIg?AzPrc z25OW>4&d=!>&;@U&g>(^sIUm>TpKD@7DyL!Vc1T20de`;R;gpipNj!8>xFd=#Mye@ zf+bAA=aI_yQND_YhjV#GQ5GxKYv%875Udp)JY7e^w%tYzN$u<75tlusRSC$R%@ruM0ow}CiQ`_U@uzIeWG&9zTmen_F1cB>j{pL$PF{up>L+TT@P2u@h7-q0Er ziSgrOW98fYkuU-ON5;nLAhz88+bW1WgU5%)$}{>SVFKQhR5=IbM_^{=-p*FrK$mm9 zcTa<0t$kjJkj6m`uX_@)`AZrl`o>a4U;&yEYu1u>T-@8vRJT$ z35wzHKI)ztXH_ZWaz@=>Y7nf2jD;PWvA|V*80WG^;SJ_37p3wf|4IIf8YRYYJ2pxM z@p4rUt0O#s;RpAr5&l035%4bT*w`6Yb)x-5>lsGQcB`Z?Bt%f02qI@lJ!=|zhFW5; zL9kZB3x(|M8E1-So{vBjw0*46=zVJKixw18CoWrAQs=xEDFyK z5{=&^jiG#5jLJf)9u8Sa5IsNEw>Kgl%o5&0=O_P_FrjjoDw;%26U6x=p7xll@JmW~ z>g?vf5+*1U1|t58=I$L|T+WE${Ve`1)}kC4hJS-n6{~AHg$b50fn2OmU#-f`Vt)I#zvUpj!I{P98w6_&Y&l1$+)~i9 zb07{@?JvI~<2816xL^qr$ngr*m#CaC?p)$DM6CbF;XThFSZiU%<)X&J*&^t#hae{3 zo+THj$NQ*NO*|u!Xti^52 z!=pu`ByKf2pE>--3!}16Y%W}?>~Cx?T;6F=N&lVex$=+;&(0)gp29vXt;<;$m38%A zjnWvEeN@Ivji8z5miC$OF-(Y7#XvOKS6rUM4owL&cv&oAf+`Il7MJms0lQqzujh*! z1Z!dB_leDAfM_(kgDj3{B46FQ7E72=S^C&a2#E1RR?A;WT+V94kK1M5L}FWG+0 zs=0WbP#$vWwwJ5{MK|fMc6{wM7V3k~w#x&oY?+Q#xRMPVbP#cuf$U+vMB!)(@?nc=hOczl+av%kM(5_K=`k;y>B z@hoMtgb9^%jg3-a!+WY*X2w-b^}FY0g0;qr?fR-zz60w&vc|}j_&ypR?dWC+6DqH- zdON6NCP$$`J7r&*!@pR8`zb91X?{33G7C$%4fvmM( z)<1^5cY24}EMa1Av9Dt5-~jPD-~*oSlXH9Jle4I$cJ?(0)>3))*vtfob7!W>ityWS zZXa(`do?O?o0|X7JzVWa??EI#6d_&k+uw!y*(~AOovH-H=1xG=kJ=?4;hh()F~uNQ z%e<zis8N6Z@lF4oi68*+%;{MFwuKtE*};9 zJStipM7%xuWOwXs_;=3{dfIx`W7=X~J&VDxdzZMCJ1T zC6J}ieF^d!Aa(>=QbiLd?p(B4!UQUqJ}R0(1rtP?p{-<}2`=Y^kqK0eL8CK>se|XqrHCdn`V24#)@oaR zjmU?QGj-3|Ao3Rsmdnw%2kz`GS;7R3&LDPStd$sRQ^vRqg0*O@1wnoy`-VJHvu_8Y z1^mQ;@Dsl#m~If{0gCKL{l!7}iM}CfkF5`1U9u4R#1YqLOO`MJe?*T4%8x+x_2)nG z3+}varXa}@CdhvT(KA2o>lO?d6FeekpBpx zu)C9N2|saJC6i#SiJ6xRfB1>ByF3JOs6a}Yvy;nN+Hbh5(GY9Wuv+%)^te9vl7@*@ z1wzDt&YnK1MiiSb@xjXb$ouv#L=$N*IwVVIUWSjVNvW6t6(JDVj; z&s7R{dk;hAx_OpLZW_ENaYH2)bVc>Lf#A9=WwQZ|8~7?x|7 z(YG`4a`$(k=Cc&K`4yu<{PD}=$UH7*ob3w@g0;BU##()R=ld<}LK`>27^9fj=b6e! zJ@s}?^Wc39Ofy!NAL(*#`Y^*FSd06450BG%Tgy|yF6X-QQFe#^9mNixN#f{V53O%+ zrik~m{6v21u2r^QAN~J-J=%c#*tBbm^c{d5dn@j@S;EAxxuN3VxXB`E$(tZj-03At zVnuHKj|&WfwZ7&UqHP@i)Ca_jM+;@v*Ql5zsV=$aMAlivW}P`^z@4`(vO+dQROEzL z%zYFSgQg!4iR;f4expW%$bWmWT#Xz+;yWh6THF&Mhn!})%y;n6SkWrOx)~H zUV8wqP<6*1bnlPYgJ5G|`O-EMto0={zqTzYwmTsNpW(gA%6@j={?v#B3 zHttkUZZpAJrYAG0MP(Z&FFK?4405xC35vpCqwng?c8k}Tv32U0L9iD4UD%_s&pG=b zVw{t4R_oYC#W;v{q>61+jDyHU(rh}Z&YV1Dw?b=Q-gYa`vonZ(^-o*3#!MHzdK>`J zXvZo$?HgZb(`nlcg0(nngcxVwQhOTqnVA0G=J|V)3FV0^j~sqBY&h+S_9c8D9&us} zg0(o$gwqNZMcA|O4PGp>SFnT$)fcKh5q%hJjLkmHwlS)08zv2cwaon0_<4)$uBa8| zzP}A~`2NdmF~NB)Jl&Ji>~x9nMSa;|5Uhn-r=|RMRr|!unr?n}XidEHdSR*x`bWZq znIjwRxy+8l4g%MUcN89fPqI`m8n5~wx&4r>|88dYl*#(tvEuCZ6T4PU$DI#w9t2!b4tAcawjTc-_$IssuOPHXM z8br-DFYRi`8vJv$s`mZ={Vmo~9=^&NsJbN975V?LJ7X^A(j{#LOPJs}p75^UM6}cdl%USu_ zY=dAeGpjaoW)<1tr>`^1&3S?)OrV~sM>thqh2QRIA(z4C zgfGf({20NRW+qewtRi9fKxkK6OBS@{dCW+eo5~+L?4`_ZS38o zGV}+XbKO6_VgL4r4ufE=zj}sg8yjYq2eGzmMSB-)l+Jg^VhIzNW1wxQIR}V}gzf$g z8!zXVH3-(?ZyqZYZV$Dy;8~TP{lH=g6Z{2Z?ULMOAKK<}w$D^tu!ITB*b}jH{BTw0 zy-(Wlkpn1_*J%)}rDA`T15mS>kyYyzA)o$6+bv#3^uw-)t;(^D zYU3Yn&VH?$9slQdF^5e@6PO(jqU+NzIWMlunc!_TgJ3Pr+@rPc4V33|xSS8JlrnPq zOsLpReO-vAW!~-9l24X&$G~?7{E@Fah}NWcCwffe1l^K8!Nq6xMbnJF6X3f2RSk^2#Q5O zP>f>`tVOX8h(?bl$|9(eb!pkg;tV#$XHv~YS2-C~&&3>;Wf8I)vV+MVPPJIV1VxY_ z)*ap@rOF6bn_>{GrDiP0&hY|~CGT!|A2DaUd*K#Km^l3Gi+F>)X!{lKLF~D;SMEn% zwCYG-gJ3N)TbrxSekqW9&9OPmVhIy3@7>qq$Nnm6eN@1O-7*!jAN^$?gJ3PrEn|PU z!pOHH+Dk@NHn(PZ)o*m&*OC5Pczt)3fV5UfSj0T5ee+wv;LsK4** z;);UJ#N>o0^%%8$_$d$%-fxp@FkjT~%K?L6twnj(X>TchkINtigf*5K(fgdO(AVO+ z3g#~8Ore^8!0#WcIW~=xJBMJdbBmc4OPIh61)tbillVT0lv^O%RdhLLM@JY0Yw`O> zo*~6{`S2C?_#L&=VhIy!1%ZmAv7!L?;d4dGqG(sMs_ile*5db%C^gS{dlJTv3140~ zxVpsEEQ+siAK&wiw{s#&-JNoQgC$H*6b6E#JEP{sS`_txpa{~z5+*2`1VK@%#RO|n z^a_F^VFyc?pr{xGMcWn=tVMAL|5ZgD3|}n4sJ{h{mfPYQLoN&4CsZtY!AQ zUfJH;ldfVsZ{%;Wgb9^@i=8758?#$kaz8S6RSw)W2-f00A0y}F z$V}+^0b^G1VYgOL;K=&6>Pj zsF{`EtIJtu<{kBP|45iHXJ+2{`+#*Ct^MFNOFi8`1Z&9^x%L0I>pct4%Jy_vkKir6 zDjMlv2@?+nmXA?h-`eJ?Qav;MNoy8tyt1-bOt6;nDAj$a$}i%MHsrh67 zR;o>6^5+DiH{M5&?I|smFrj9NsCI>!9qc>SGYBrTq2S3Kockzncry z62J6qVX=e>HFrg2oe`&l$U0=KP=3k%Wm64;wNykAn@I&xtIKRrxT(w8;?P8kB~0+F zY3z%Wa;<2V0#*Heiw%OcRMsOlBaD9cc*`9k!&~GmI|o}VVZxk&z3Sc`(Extpwn~u( z!CESN6I)k>jXHlzu@t^&!#+V4OPDZcU@!T(OLRxfxvI!|gJ7+=`M1h{K28;d`&@vH z!D%;(Szl2TZV_#PFz5~WK)MVR!ErvQsrbWZ3(h-Tju>;yR+*L9EH{WBTZf4| z@cNGLxuEjjeIOKQcg}O&c}_ZZR;@N!-1f$4P)!RPv(=d} zN1T;jQ^hLm-a2k#4ufDVmG6nI_ToOe`1ceW;ll+bkEb(1|4Nupv1V-D8AQN?c47gl zuiL9HQ|p=k%uwc;%RCbpJLCP+SY!lov&2ec#xD~p4pe;!;y2iMv$M1qgX+@f8?y|8 zwRlD|#*fRn#W7TuPOX??%v@$d#eu3%MEr)>+0`$usDfTJ!Nsly!CE}e8ei1sQ0vtg ztP(muTugb<&{p4IlKn$v+hbSkSE;6oh1g+WV-32yw&Ae|p|H1kwF-ow6iES~-<>-5p z#c|PdClkWkN+<>Z?Vh1fqSFCDsyrQDY)8@0AGF;+eUa@3U^5 z<%zF$VW1Q&VM0Yi>Z?WE0~?D!OY0V*qBd=|8w6{qXh`)}h>k$`dZw{d1*>V_WX8O3 zo`_&69+4W=^636o2eXGgfqX@1vV}oJ8lrH_370dZKKl&HTV44+s)dB zkB7I#5+-ORD~Kl{Rjp&NaWBJugJ3OWzqAeIc_No_H_D;%iNn5^u~@-Yw;QioZ55XfK?e) znNzLT$}OX=+J1wki1X=}su_TGY?X}Ln?U~R&Nj<|JeP{JkF z416DVHrfVZX#MxyfS7T3omB+iVChL%YeNzyP-(JbD_9`XRS&a@XT)inEms)?Yw?R@c58$5&V>LMw$XV-tSJmzD)fV-&x}xG9-#yVFSWEf2u`{zl+=HL1{M{@= z#!8kjft$lTkh8q&Z0F7Eu=!}{VJ{F0lEBjtwqL*&|<{-`MIRh4f& z>Z=+zt!V-ge#{~EqAyudf2m{%6R1aN-$(7Cfqiji6cX(`kr7@VZV;?>DNcGBGH#0K zc~0$t)ic>eD-Uuq6)sqkS9c=|tk;#OSzI&@;?9@;j4$?KJojziL$ZVkRA_V$uI3_m zc#LjVK=eXRrqa2o2Ekf1o`Xnvwz7DGoXm#zizG{!P%G)w$e?B{VE%5G#v&6ufIX#G z8U$TqCH;LpI9sEA!hZ>5kaT>G z(E=@T()c7|C1$HHzp}vCL4dV*F9K9wOMI|4A!{&w?093B0wyT)0vjVLp0_eSgwJrj zzCo}SW1mcW6Q@p+H>%@$0$vZdDx>SKVgL>tp znkk4p!|?!-2)Xcxv4bQ_m@sX$e=|qaL3EcoUSES?EzB9zafzBKh;zwOM2N&#!`mq9 zUut#59|;qDPuL}GMWlF%y1|S#?F@poP|ebr2~^2o<5khNqVY_40DaHd6#ZHhJ6oUX z%#?F;P8OY#tMd(dTpl9g4n>YE+j*NMOiE();DZWZUDrhACqzB27I3l zwn4C#@^h8H3%?gcjjNco4^Mw_&sDba@MClLYL_0}pQ~MaDBA+!(xpA3E4+-S(<6C> zy~Tv`@Rg?z&m6>~c2ewuCsS!fkU_8(Wm`b(d?H10c={O^M;dz$Frhqr<>|wh2XQd_ zF5!=PuQju5Hwf0^{k<^X=lhU~*n`0-A};Sj-dJY@)x1jnwkhL@cfPt*OUvgg=6=lI z=Vl2L=2uIZRD)nG%6P&CWm0XHFhSW*5R^%EGr?Mv{RA;3?QN?8dY@+rli4g`LamsM zU7G{qeW$o$2}b7?cXAm7Yw`XZSc6sPr@a@m)l(N}XUvr4xwTX!$7tYK`p#YsqGpW_ zk|j*29y)d%G>G0K0&F*CKwN7P-ym3vYWE=GW*?+04JE@K+ALuLzJyTG9r|JrG;_cp zSc~Q$fS}n4HcObGnF=5d{5J!_AXtm$Qh*qI>qu`(?o$At3j0f;UlYjKy1))p=1dYw6C7JsuZQ|mKBVj^~?`oXKcn^YR&`FvDCujy8&yxdD@x&oJ0eqi0 z-h(BgpMPiL8H8`6JC^rFKash$+F!j6b}ask73(9eca$t)8#F@@L~j{o&;1LtSZ_@= z2-Z>~O>Bk*MCJ0+Y_&Ec^)M-Ur!qCt#O9WGHYHm7skae!Bw9&=f_sfU&zMjnO>Axn zHVS>7Xum=$iTET9g0*OdDTp@H7ux+X;*2S4?%l?O8fjv4OCa{lS#3YXKHHwX-NtTj zti^j!;?$me(`}E0IKjU4M&r(Te?ZII~u8RUe(mGGR!^OUW*8_SkG~iB}`y0fS!ehZYnLZMeV3Q4v?wF;_K1!bGk~6EvMG<^^nA`mjOUXxAj2L9o{4*=x0p-`QS+*fr~g zL*04DHJIT~5+*jyi_kW{FTW1r`{^^aXJrFr*<^j0}sRg1hi41%@z{UZkumfKss^A!(^+AXKe@K(=#e)_cXcCm5Zs$HGQ znn=Dmwcerrzs|JOc)CNTZSYoi{%lffn%@f?}=}zsI(;k^;tgW8n0EGND$4tNVysG!blspB(0;-eC2YCc#?Vj*&et_ewwAw5Pwg%N0Ja-&DI_C+tG; zck6d>)?>Hr(LYN6|I{fD&`LaWq_WjjwJn<0kT7w(#TrfLe4+MlmwC==8w*Z(8U$7Pn)pkglK0R_)4}dW?I&JDF5%wD#ko z_PjA)_3!rC*3e$NI-&mm+co>b#=*+9ZS@9!6kg|M2@|2+KWjSA$2K6IxUy;+w_XGr z1Z&mo@l!wDyQ@M$v=~&`R&DowiQ{gTF!A@nC)!5uk<&n=TAfKO# zD@5%>KPz2XZ6m1GXE#fj*m38QwoxgG8f*6-N}z2dy>!JOSc_YzhexHdd9{tx?^D_= zVdC89z1qg)1~zQ8^3AHBZnpiI41%?|9b+}QUr~KkO%n``{&7Ezep4$(CUsk{5=!;m z4a?!-&Uzu0{{QQaGuRU__2E|fs)`-E8_g0XS|v`P=`po-gIMBMNZXh)GP&_vti`Pd z^BG<=)i(N-Y-zMBCfe4Fqiqy>k{x$mY*7Qd0^a$tDgg$;THMC|Yr8(F$2h1ZTBK#s zRaw|M@;@66mM}r~K{{36EN@TYG>)RdFhg;ObE&6WoKIr=}Buvn^ z0%F{!pSs`uI{%4-e~Y!~`v);{L;?MD>l8|6v4jcwfc_A4T80}^ZA_@wp*kf?{sBz*Qd164wf*nX#5*Zf4?^jM1w0C zw2iA7Ru}|pQI-ls_Ke>8>8@LR*TE7dD3=A|%BQ5-#>e?b41%?|^`I{qP*mGU>6y@C z2@{lIgAK~{83b!_8^g+%WtO&)+T*I5e%Ge^u<04v#?y7Pgb8}mAcp?;1`UF>=*@x{ zT(F+bUxi(daI=JobbWs6H(0-#1)^%ky!z?R{`Qwau$GT!O5J)6R89h7*p}j-(H{LTq+zW51ZS2mH%FPlc@>EKw zZR|Sg0+C^SQElTx)nU<0uvY#8X|;|2`MW7Qw9z)Ad38yw2k5qCmMYT6ZHN;P)jrj)}mGkVor1o+Y7ac@|hM# z@zagUKU%2y+v*+AGsHWuksz+Ta|@M*3-|b0xtSQ;Wu&H$EO`my=&S15M!(j<2EkhN z3~j7xtl^<;v}v)GpOwu7uOG%ry^dA1jqObf7zAt4(}j(Q{$Fi%9}{+^w^+gi?RW&@ zd?tss5z}NGKV4(RGWRjaAzyf7WSO;%@uAHaIm1Ro$->%3g@&KlLpFbxcE3T^;BZ%M<8g0c5LDa#e^r^75!c=78+;q`i#=q? z#LuSb^e#7PyN|$CO`h$kZA6``Y7neNJ~fC8->YgH-IvD^EMX$F;45#{+l@^;8br$d z#iP|b@8Mg6eQL>C6pMoJywlKI-ACVIaXEf9hyp#gxRs5)1=X$*eM;5wRyI0xtHDvK zWG#wCK`gow;!rkL-tiDDVS-oPzzc7l(xGg8oK%&gRLNQti^4|H+X*dYW5kT_9CI23 zuhT)ry-jazW8yQ*AXtl{RM=?Qw~Ds0=Hy$BIe8wsEHT+1Ya2aN4X`MuXAm@Z6gJYnE~9OT z;8mQtGuDh!#v8=(P4Bgh1=}lfmfRp{?kI?eNQbtuKKCfjh1;w}`D=Jf8L#}%HpI-Y zoC|j|akb=d{XXQ@(y(zRs*1MpV_r^!U@guqdw6v6iX+r_KCr|%2TPbZwQZEPaXMK) zT-CYsHMEV9tNl28?q)6eB?n@)3URfKZk=**F5JNc{S6{;{r_wXOmLZV;Y{%TfoRn6 zfA?`?$Ukm+iUvXVWMPGZZ#8`%@%y~tI*x<2=$(T&*zc!)A0DS)bB)Dfg5C{?=-EEn zM(b-_@F?WB}~vaFR)W#*<9MjwzyBY zK4`HP^@*^tIO8F0<8aE=HcObGz6&;*wo9#TjLe(RAPlYl`eWF*wr!KPalV03C%2fO zJ{UH(j_}Yn0=s6gsc*Mfi^eF}NP2m$w$bgzIh!R+&{zT+hXSwb@uTFFdHCS#v7X@OprGK;&kq*+D6_T zUIxKh$#%Qcc;4t(4Vwwp z;%qef#CRpOzk6p-9QL*a6Xg5C#?e> z#Id5nt?nazipmDTS`_1eC^;aXt;VReSwGu`4k6 z^JeEY2-c!_7dGPOSf*{C`c5!iSBWjf7jIhO8ltBVf`rJ!xV?fpBHcObG+!Bb# z;T5%wqUnM;Bg{M4S(GCKQFYrFZ6jo27MmsfyOhfUF)x8r+sNYGz|90}QLYdERV~cb zQ{Uj@GLkdG4kjok2jar+YTCxu3-_Y=w^)nwjL0Xxi=%A}>YKpL5+*peh;zd?kCIkz zmvhGGXKLq`e|Ijo)x7`Mb$*hbwC&-MH^mfL9_v5G-$*1_!UXRR>EV&=V^>*XG|sNs z{e$1L&05sPB<5w@nj{xjbvfnj+=3-c@Q#x3+uJpl@kY6vIWlB62-c#O4;z)&50#E8 z*gfe~Wx*0A=yU`SS@u`fHZJ5UZ4j(QUoeQI1=?#HBPRSMSi%IITmWL#&?4H#?+rB# zg0-k80+D%A6>Xzvj-i4jOwj5P5X<+c);062EjsEoZPUrsX!)-rcce$lL?w6Kolg0)Prgb8z}+oL`^?U)`eXYQjDjh&#?xk#$* zs$Gp}OvF`<$Ku5J^|6YsE>6+-Z|svym^+MT+&0)&?dtkmUxQ#R8mVDp#+w1QYF8&K z&J!$Qg4Tb4_?_XsTiHk+cY;B%7I_>Xs?W6D%0}mH3)mOowIGtu*F%gmBAu7AG5o;< zgJ3Q4oM5BDm6i@=qfeZ0_QH(c<&y=GNp0}Mp=^wOGu|Lri+o1dIPkW%rEHwdKA(L< z$pr0K0b-1MzO}u&%b5#jcJpts7Vmh2d6vhISoPz&oS7f26D(oE+=nIIp#-9J8|-Lp zj~Bd84WCR)UO%pCL-CBFHQLp}RuctFn4o;Ap>5pAm&qVli=twTQA^fL&^8ADC?Z(G1g%(yjS_xS z#bNYUVQn)R1Z$bQi`6Q%Oti&{^;Fj@>OJ89-FJ)$b62iVF+tSESXPUBhjU-^MsfZ^odEY|zc${-4I|EmG5T2*xj)q)Sc|ePu#u_iT>Y$4giPl= zjLihCkOom=+<0x{QKL)-!CI7!a%1j!odw#){QU7OmN3ERiDT98~YnS*%vxEuy8^nY*|Ff|rG=_6;d``KM%fiz=K407T)g+%yPtoGvrF*il zM@qtR`aarYCOQ+WMeiKM&zf_zjU{L1b7qrIXt(IyfcWAQDk9K!ebTuNg0;+*_t&Rv z6!mciXzh~MZI&=$u2>&m*H^6Vf|#?_cVhM=m{Y%xwht5Z))OO`M}-#my-&+2L$m%HaT2-c#W55%E!y|j&y z2^vY3FhPA6h~lrxYa25x%OF^bdTEMbEBU=TOE=Fm2d^=oVptVJUc zh%~<*Sx@0DZM!;Ft;qee9}(x4%pHNw-Fa#?ACD6%GIfzGVZyZ0uwh2=sSZZ9p_2@P zwP?J;Rk>G|(Rbb{?KoqfA}08ru!}kNFdcy1tj^S2U=XauyDDL<#X0Wb*fsl_cet_N z5)wYrPmILAHlJ9CF7*20+$dY=jG+X!O%qk*CzPG#?xZHZ(F z6F47E#-3jbBKM7MVgd-SwUGwFTIN1Qt^$3;C!FIx+HbLB2@`6!%GmR3VWV8^{)rQ- zFEa?%;$4-n1}k?fF&BHJ{7yOF*gc5}obn;n{_W}nJ8HzuI;(c7b97r;GnRTQUo>;>aIVV>CMdE1v0=+N9phAtoL~^F zMbQ$7sabyO7-vX}1(GF9P=o{`1EzMVXZ7;XID;^>{)_rR96d8t$7*xi&E-guPi^8; zqCl)IvdP|tvDPy&_MWESqUcWVZu8%s14(b5wx3~_o9>CXO5Tlt33ILf<)W|b)@Zwh zc8oOkPT)NmC<@0_MR!jw-@;Ga>phw0t>|5v{@ula;%E?_ixWuotbS(eY!IwP*#r=q zy^Bco&d)rZ!1Hee6O<1CalcVcZDW3PBZFWq%8G#K>QP(U_;#(oWC;_L*8pMdub^#g z@9QuK)}rhVh}NIGXd4|SwUjJjg7PyUjz`whHmbVv83b!lmI}nmm{Hosl_K7fB}`DB z35081du?N7m81s2T9j>rfAuDOimZnBvFAV*&d^y*sJ#GV;}Y1ooOHZQ)XC*cGW8SB zXtP+0a)7XLZ_iYDvpr5FNx9AbHTS=h2@!wj?4Zh38>)t|jmrcQ~m z_Ty=bB}^d7&@EAATHy69Snj^^3+DoaHF6C2UO=CIXa}8^!%Jk*fA{|RUi!_==F_y( z9C2#$QHfdi#irUJ?=a$I5*ACC$Z#u#kJ>${&EC@>9`tx>KfdB}W_`5CAXw|l*EE`V z`C&hZD+R_&KX@{ua#s=8(!Uldv43;;hplqQiVtGnxnR*gc)J`K@K($W3l@(yt5bXK zH5@DZU=Qpn&mDp#O#Bt`MXb&dB0lZj0mAM)LO#Q;Dr4?d5G-NBbI~{Pv|5O8G~Nl~ z?8|}DzcEIf&{77$T5|1g@o-UyC~|5Si0&Es$||j0&iwC+3YIW&sGf(<_l+Tf4lDg0=G1j^{HiL#W7qELxgG zsiLjr@nP6IA!la65+)W^Pw10(c&I2l#fFWi$C}DtW3j)_v~&i+TA3au^tn7eRHS~c zh$n~Z$UvNzTIW+T!4f9Ct0eYmeKu4yuO0*9&eCc!CC(oVf0M`{SSv;PBtCDRgo+`D z6!CMUk1R3=d+9~R6D(okX@(>|%Rof$QAFBtmK-n-nbZPt4T7~w^iATE<$b6){#6m@ zj#ZM2BCx|ozh4$hnD{J``RvRWCZ@*O10uj#NPgdd_tEm9L9mwD+TUHwETxTlRFBgZ zOPIJ*F^x~D?O~$K81;Sh!oDYGFCzold!a$F7Jr+V{dr=798$vN+_|B;@qKLbd?oTW z4i?YXY?b__VMfZpNwQ=iLr{Z6D4;!YmCHcwj^O<&a2zvcA+3qD`2Ct@nD9`lo%%>Tx)9(to6Rz zEzuxRkhq*l5uLNml*6%0TA8XH1WTA`vhjwA+&I{6dT&RAV6Bbo zZivx$XNyg96*1=3Oga6xuk+UGPJ$&&)a-dfWV|t3^qZ=P(xYd|6F+>N13Gmv2-eDe z@rwB2KU;JiwI0Np-~gEp*{DhJ{}wD^qDA8iB3+@`;$|_mQ+l~eA+q2BoMwJuvUvM+ zvlx|VmZ(`^sr22vP2{gLOLYIZR6c&URjjBuOVr)H6huV4P&wluc8>hwCs@M7$X`1} z$vLychZoC06tY8P*nVGUukuq2BFD?k;yUaNDYR6wZB$@>j=CiY!lD*{K% z6d$`PV$P&s*+&s^rW*unRS#Y*HdUP|p6pWRrKTztEYpHWFm<|M2@^%ntQ6HUBPUZq z5n~?&$rHPAlGz87V6D+5SBbB=XNuNM6j5kZkX#GmuWB;{OPJVve1)hVXQnv(bRmeF zQ-kC}5HEURUs|$WGJN}}=1V!Xe7$m2I`0#y(U+#whV@iE6w}`OPH8-V40{F?JpL1Dk5_5Y`GM~)M+NcS`8O3 z75HI)>wHXMYjrt|9_Y z&yp?>O}fq!EMa0piEt5-*k8Olr-*ZVX2}2$K7CArwTdSU7w;4Ji)@D#VXvGeSAz%` zF-x$7iAw7ih-W`%2>c78OV&`?<&dv4!w5gYV_&k7JH?Udv&5tW%cMCDhLjJLR}cF- zC$5|%Si;1D%F&|riCJP<@N(G5;0%>zkf-kTX`(@}R>~x{nE7dzSezvi#M>I7(v3Z^ zhnAWsSi(ecPbrQk4-f~sC}M22Q2G5hcFmqM!5~=cM#>nGr$B%hwpkJ7yhCN9lfKR$ z-^UAoG>Kgo&vL!~Dt}c(z_1Xx6{ldV?l#&WSnFG{ zBcfxPK(S#N&Is|S+cre*#XhN5LPiOeFcDGUh*+LFP&8hoh&W$^<%{bWIh`X6g0;3* zIw6kr4;0 zPCrePPuzO8N4V;TiT3-F#}s+BR}3AF6Rlk-V-7~{74Cn+#MzW7V{qnu$J6#I#Dj0Y zXBI4B0(la>Pb%U?5XbZEwrd>1-iEhQ7zAr|%XLtce-$QHCQc6`M;^C5=LE7i<8g)? zNtjq){<^lY+b;=-*F{ITJ0erm;QBrXvO@YKZsdGokS)@GBYPC{_kts$LxVY@Q2eYQ zKKYilk0Vo5{`fSDC2Ws>3A-oF8EnUSj?dqT%o@uAVF0>u0&ilbH$@#>7vd-mv-LHu8eQ?WP^mw=M$QdTOB}j&+JEYt@yTl5dclV%_ zU=$onMDsM>DYFTd@X;n=ZPdKm<3Z9Nzxd>@92eQ6c3`gUCT_gt5AZVw?? z!bIxjG2-U^P_f}*Vh|boCYB#(xtv#8)G!Fv%6r`{dNm0Zto87khnRZC2FE0ZiX95x=eG6>eneI;7>X9^WZTEqk48lO$}9EhGF-Cu$w zOuWqSaXIsi?qm?GRpernSbH->)SVXxMB?}P4=jsXZ17)*77;GOWax7Bx>ONfYH69x#DFmX87PLZ}!h=}t;eS^zWmzQxdXJWzR zVFtlkRTpm;SuX{P_~$=>$kD`0zC`86f6XZI^w2huEj(B(xcpXbKDu4(yB#b(HTo#o zwui^|r7dK>wAj71;WQDjcB9CVF-WX!bVn9GuvL6&87%(l_)3mPo*`$FAW?AgE!c>h zUSICb4dRWTULgHFV2S-e4PLME-_p&OE)p@+w^(LLnlPrlCY83T-`%f#MDoWhzmP)O?tuIk0z zfwDY2fScC>4T81SFIy=REe{X{Vh(`#6*5NJ@Rq*52^K72V*dM;V*2#}vE#}?5Y0+W zk_F&dHcc925Ugd!2Cw3*i&j;cOvj|dH>Qjpy}Ar@#^g-9!%}A!*Q!%3Ch7C+LRDqH zd{Za=of_W9t*SEX^DVPj!bF#V8 zDOy&tRaK_&f<sEeAptF*#sxl)Z0tHK$c-i`xrK&Q&^QjXHAC9PCtEx=$S~CoSwK9fX zvQ$;3{)ZeOR(h4URaItik*R{UDmJ}jsjAGGTRCD(;!)!=wyMg62Tl+yVd6`@dzPxo z*mHBkhMlgIt*SB)()$_&YgLmEELD}6SUeAi83~Hnsw$JY-5|jdCcJ9CvQ$;(K+}96 zj$SEbtE$X~p}h@)wFXXlYpJTttPJ@q!Yx&m`4OHP#DXhjY*m%Xb#b*|2@`qm1z4&obNOlt5dCtLwpCT8 z%(Jxy!CLiS1zM^qb0v+6ae5RkVXLZ4*2^0NOPHv4cB-YSGB-qW5P4b^vsG2*O1(`6 z!CFrb`B|zeb7rdY6W`1$Y^$nFtG~8jbpB7mM7%~5ELD|hy-)e=FX|SuRaItvm8}NB zS~;6fuvAs%%5Ftu8d%U)Rhh73TLnv)Sg>cjrK&Pdmnb4)TYg(rW%3@~W)Q6P&^gpn zRhhfLlxKN+er{V;WjwC#5G-NhLW-`Is>*zOod`t8n1yatmAM^qM6_$W#i6P)Nrt_V zts{>(R8?l#?{~6d#6E|r%0x7MhcRkf@ilH$m5G<-h+qj5y_4N{sH#lK_@6)w^_=Hc zRhc@6O=3y+Ee=(cxiIpLWZUrJJ_fo~Ri<~6qsCP+k)*^@hpNgXUGfSxCN-MjR#ln& z7cW74Nior_sxpoG9u+KMV!)@_4po(@dgKL&)9r`5RaHjJH3`;g zb->S|sxlY5JO?p$K`*ze%5;`T1xuJX7c<_Wsxl*AKLhdJ*~+b|GG!l{1Zz!t*TJEx zGG13ztag4s;%*KtEx;~ zaZIp;iJhNQJ5*I>OA!I-7Dub9%)q?I1WTBhT574cs>&okdDl_);Z4kd=T+ym3lO)wK!CK*a#(S%(%<^lurAef%*Ctw3 zWj@9^CRoBmxg}M-RaM68m5PeC=B^U0sxryH95o2mYS*ERx2npl+@gq!zcWUws!Xd# z=u1e#gvZ`E-l{5dDvlxw?@th|sxl{UngnaTJe0s&Rb?Eh6mjhMwJ24UIdJx-xJZW63@w8IuJRh2p2R}rtG=0>TijQ5_Sf+b9p+dJM% zRb{%QSH#{XlcQ8sCZF3RSgY7!KQC34nU_rwji$DXQdOB!+l~sBFmZoLRWDVQsdeoJ zh(6D%MyaYy#3qwqtvDUac&VyP*W-#+O6b5yW|iAHFT; zRh3y6X%eiJqvMuJswz`#lp>b(_uHkaGHoJ`3YIW|eS=o0s?4WCipct6lUr3~?9+z@ zkA3al+;XU@jF|ROn&V*g`fj(X${cKXSg?eNUXG6rRh7A#<_l~D&Dif&RhcSR4jBY% zU6*kzRh2ogU1uido^Y$GOx`Ak1WTBxu|I*OsxrgFzrn^spYv{2m8o(6ph2+Kj;o0+ zRh0>x^&Q0d?N{BZDzm-cLBSFx?mbCmsj5uI0zW|%zIw~8sxlXon*?jk`Iy>LRhjlZ z6!BxqL$|8R6q$TLu!MRK}~^_HS-g zmD!GZ5EHD`rFmgXRb}F|SH#PqKi#S-leNh{!4f9w^)76ws!R?|3_9vztEx=J8+#3c zwT5*sW2vf4^X@8hSAS?+TUBLZeD?~LFj2T|8B0}Vrgc_?c%0ByRhj31?=cA0S{G5( zQdOCfJ}LtlXG;=WRb}3E+bvkaMDZ21Emf7N@>~%gd#ABgRc7iB+aOrW^j^iG47RGu z9GdPHEMa2TyAGDB$|M@9{N1FfvfHXEBhp401Z%P9jGb<0r?*s9ruFiwB28`&sj4z5 z1{I1a7ZFdYs>}e-A~6pS$Cauo^I}n9*a)tc!ctY4W@Re~mN0=hQK}5f|MDegjwY~F zRc6n;LI%NFJ@)?}V{Za(+fkKkZ)`Bq2!>7+1;GSR5DlUsXU!e>1yn>)1TTsxC|y!i~W zGM7I714lB~vs}#%W!9*1%&gIwmu6jhvNC`9r0)pvzJGke5wbE5{m=yqTO7}SDb;Ad z_Ay7u$~^2%Z(G=6VrGb2m=l#GyK(D;g+CC?@-;bYo%g+;Y-NMw43#Q91!;MEMC@lUFjQ+l9hSIS?^(VJHd>giHuv1v453(>t`Q$ zl&s80Kl!eKu$SlkvbOdu*I$s8`SdgIJlr3?@^5$N&o9Z!yzafHW~}b>wy$51mAT?i z?l#$C;zj3wd`VX3GkxCYU+#621zDN9|Lwg8!d|!kjgK$M%G{?DpFZo91zDM=|H@BK zwwSp1?>@F9EAvnPm-(v?J>=#KvNGTQC%-Td_PX{jUa=%AbN9#ID8yr*f6E0~nKz&J zh{+ZcXP$ETlB~>`r$IdOE~hQX$~@`5j~NJiz4H-&yCf@f|9@q6@Y27$^@6O-A7vL0 zTTGn&)^{w)%3SqbUmxNH-*=k@S(#g({KSE<*L#2KvL#uWC;tzK8@&8G7i48V{42jb z*<#{5AM$5QvN9iiH1ndL`}yx$kd=AXV}EBL?DZ{Yy?IGiX76+1dFItk7dCuQlYwuUT^6^WuGM{@kb4#y1 z_0|irGVi?dizi!5ICl1vx#MXIvNHF2-X9Evz25gT&s~z0dFjiThdb*I-?bnsbH5+_ z{mB*+V?U;U|IP(jnJ>TH`2%6E_dM;zOR_TGamKY17D@Px-K$;v$atykUi80Kr~lCNEmmHFl?Up$QNK)mX-C0UslJb>?# zOYZa)3$ik|`^3?K_(yr&?)l%eBrEfEf6X`CCqMqFBV=WM{KK!CY%%ee8{B+JR^|?O z=ZowmuY2whvNBI;Zybox%fAiK$dHwZX66VQ8Qv_cdO#z?F{>fa$dHxE>ifh%BSTgu znwf;%3|X0IX1aQ2Wif$9hOA7KF(J^%kd=vMrmJUG787V>$jU_95(143S(#{N z2EtxwWXQ@y8507H3|X0IX1aQ2Wif$9hOA6o7LY!BSTgu3Yfi-KqEs|CYqV9w^{uy6KG_}%0%0e7-(e3%0x3W5cWbNLsllr zm=I`W$jU@B)73L8iwQI`WM!gl34un2tV}dB17R;TGGt|^H;pphXf6KzWfG%{pmqL~>8 zdyQ8+8X2-O(acP?m_Q>#Rwing#6TlMRwkO6g$aB4-rU(iBSTgunwjDLKqEs|CJLB_ z8f|r_<(F_YGGt|UtTjSN|tXlA;4W@RyfMux0Rv@Idf$dHwZW@aGlg+_*~Oq4Mp(8!RL ziDss&XI2&yXk^IBMB5SqjSN|tXl4e&UT9><%4B_C2sAQeWulqs>Y0_r1R5E#GFe*~ z0*wq=nP_IZMux0RbSn*w3|X110&Zwz$jU?+69SD4S(#{Nx_V}1F@Z*gtV~t}hd?7k zRwkO6fj}ceRwfFVhCXK%JHK(Fks&J+&CJj$6KG_}%0%0e7-(e3%0x3W5cWbNLsllr zm=I`W$jU@B)73L8iwQI`WM!gl34un2tV}dB17R;TGCeEv<0z5P$dHwZW~QrWRu&Uz zWXQ@y+X4}d3|X0IW(LAu(FHWJGEv5aKqEs|CYqV9o>^H;pphXfv%h{9jSN|tXl4e& zUT9><%0wBH7-(e3%0x5M)iW!L2{bZfWukKlfkuX`Of)lHp|gsPMux0R6fkWh(8!RL ziDstjZB~EF1R5E#GSRjq1{xW%GSSQoguT$nkd=utCIlK8vNF-kboI>2Vgii}S(#{C zLZFc$Ml>@6VJ|c?WM!g^34un2tV}dBT|Kk1m_Q>#Rwmk(5NKq`%0x3W5cWbNLsllr zm=I`W$jU@B)73L8iwQI`WM!gl34un2tV}dB17R;TGGt|1ptG|UthO7)%`beOWAuAKjOxN42 z{+0DnbUGGt|< znHdOsp^+gg6J<2Vgii}S(#{CLZFc$D-+GkK-de73|W~d zV?v;jAuAKjOjpmWEGE#%9M{UAks&J+%}iI6uHKetWXQ@y0n^6!AQ~C6GSSR*73t~? zX#$N5S(#{C(ke7EWM!h683=o!ks&J+WlRV(GGt|^H;pphXf6QxQBG%`IabE}cC7aAF|GEv5aKqEs| zCYqV9o>^H;pphXf6J<;YG%{pmqM7OHnU%!^8X2-O(YAy@BSTgunwf#H7aAF|GEv5a zKqEs|CYqV9o>^H;@Qx)b6KzWfG%{pmqL~>8d!dmbD-&f*2sAQeWulqs>Y0_r1R5E# zGSRk#KqEs|CYqUnuooH`vNBP|gg_%hRwkO6uAW(0OrVh=D-&%?2sAQeWuloG2z#NC zAuAJQOb9eGWM!h6>FSx4#RM7|vNF-Ogg_%hRwkO6fw0&3^@>J@tV}dBUHiTIt~G&1 zhOA7~Fo}UihOA69GXr6-@tYcr3|X0IW)^5<$jU@B)6mF}m5BnTp^+gglhyu-fkuX` zOf)kKTTC!d!h8w8{_+J7jSN|tXl4e&UT9><%0zb(0*wq=nP_GfwwOR8LyUbD1R5E# zGSSQ&VOEIQA?AFTE#jEjBQ!E(WulBp3^X!iWulo$&GX|H$MauGHK=H0$jU@BgVN$4 zhKaFNXk^G{L^CtA%3f$>XyLxb1dR+?nP_HEj2u`@ppl{H`x+B8GGt|CHySWKXiA;!K|28|5;h-PLW>_z*DL94SfMKm&GWulou!E<0SLHmh8 z-0TPxjSN|tXl4e&UY^C<*+C;iRwkMmlt>3Nf+n~+h{5<}{Z%wFWM!h683=oM-Y*)g zXk^IBL^CtoAHMRtMkZOAC}VP6p^+gg6V1%R787V>$jU_95(143S($5n?!O1ZUT9>< z%0w9x0*wq=nP_IZdS+!YfkuX`OtdW_(8!RLiDqUX?1e^#tW1m5FAit7ldg z6KG_}%0$~jjA&%Y%0x3W5cWbNLsllrm=I`W$jU@B)73L8iwQI`WM!gl34un2tV}dB z17R;TGGt|nP_IZdS+!Yfj(yyJM~ziks&J+&CEd93ylm}nJ8lt1C0z>nP_IZdS+!YG4=zE z3|X0IW(LAuXk^IBL>ZG9Xk^IBL^IRXGb@XUadgqhkd=vMX6OeR8L~1_z%+D5t1;Z! zK_f#}CYqUHbWNaIX979J68pjSN|ttiDeSG%{pmqM12j ziwQI`JgJiv&n{_bWXQ@yGcyqOV$BBxYc(<>9E}WFnP_GfXk?fx&Px6z8X2-O(X%Yk z$dG%9GA1$5$dHwZW@cfF2{ba~UZRW%fkuX`Of)kKTTGylAuAJYO9(VFWM!h683=o! zksnP_GP!d_@($h|}v69SD4S(#{N7Pgo` zBSTgu+LjP#WXQ@yGcyqOLL)=&CCZo(Xk^IBL^HFn#RM7|vNF-Ogg_(HvocpXWgzT@ zMuyx=lrbUD$ee#())f8SjTg3m5F9% zAnb)khTKb(F(J^%kd=vMW?_p7G%{pmqHPI*Mux0RG&2KXFEldbUZRW%fkuX`Of)kK zTTGylAuAJYO9(VFWM!h683=o!ksS^C))t09BSTgunwcYLWXOy}w{jGX4D(D`1$-2Z z47rymW3pQ)8X2-O(aapN#RM7|=A5!3I0PCQvNF-k3UtTjSN|tXl9PsVgii}S(#{CLZFc$D-+Gk zK-de747rymV?v;jAuAKj%n@5mpphXf6KzWfG%{pmqL~>8d!dmb_Y!4H2sAQeWulom zVv7khGUP>~S_y$hhOA69GXr5SG&1B~qKpZFMux0RG&4tRF@Z*gOiFYvA<)Q>m5FBN zh`rFrkd=u7=IBVEks&J+&CC&7OrVh=D-&%?VxW;BV-n5GK-de747rymV?v;jAuAKj z%n@5mpphXf6KzWfG&019W@aGlg+_+lOO!Do(8!RLiDu>uTTGylAuAJYONb{%BSTgu znwf#H7aAFIFHy!^l3x?i$dHwZX66iAOrVh=D-&%?2sAQeWuloG2z#NCA@>qxOb9eG zWM!h6Il~qcXk^HwMCTF$jSN|tXl4e&UT9>8d!dmb_Y!4H2sAQeWulq6tt}?d$dHwZw&k_iFFYCb%9s#nWXQ@yGqbS81R5E#GSRk#KqEs|CYqUnuooH`axYQF zgg_%hRwkO6g)Jt~$dHwZwj~4_8L~3b%nXFR#;;d2GGt|WulBp3^X!iWulomih5>caXkN}sL!I2AuAKj%u!oRjIBZ=LpI~)=UzIr z%3f$on9D*@lIo|?$dHwZX6C3ZCeW79b2K5zl0_p!RwkO6OH9}cjSMmJ6_aN>8X2-O z(ac<8iwQI`#7LIml;mrpk)a<+b-%`hy%alFA{rU8GSSSOVT%dH3(++)i4o1rK-f#8 z9s-RFS(#{Nj@V*C;}!yqOwY=E_JIRoFVFi$;TDYyS(#{NhWo=;e%Ht(D-&hRA~UJc z$dHwZW@c%N2{bZfWuk2ffkuX`Of)kCVJ|c?w8g|Yx@cs`%0x3W z^aG6yS(zwc79PWV^+h8?RwkO6VRTKPks&J+ZA)5(Mux0RG&2KXFEldbUZRW%fkuX` zOf)k`Z83pHhOA7~Fd@*$kd=vMW+3b}{x(1(Q*~vIYSly6$ncg)hP-QJs;*4lA!uZ( zuFMkk%*vv*4P7I{8z))u5NKqouFOE7q*-}sjYbGGGGt|*83=o! zks&J+%}fY1GF4Zm*ks&J+%}lcw8kwpq z(^WOc2{bZQSEl)InLr~`b!8F*jSN|tXl4e&UT9><%0x300*y@7m1(w^KqFIiWkR5l zAuAKj%s|)+jSN|tXl6p7k*T^e%@z}AWU8)A2sAQeWuloG2z#NCAuAKjOb9eGWM!h6 zS=wR(jZD>*34un2tV}dB17WZ6YDXhORwkO6r7b4V$W&dK#6Tlcb!7&^UcNVbU74Ph ziDqWFKhVfjU74;%Bmc>r*6YgjtV}dB!#!vMjSN|tXj?*{k*T^e17R;TGGt|dG`*OrVjex-ucq$W&dKfv^`E8L~3b%!EKALsll5nP!U#G%{6J zCIlLpsw*=P_Cg~=RwnEFLZFeUx-!ic6KG_}%4F4H2sAQeWulpBXk^IBM7Pp4GGt|< zfaw|;vNF-kgg_%xb!8grnUw`q&5A%HLslkhg+ri`AuAKj%s`-#sk$;&o=3 zOf)k?t4yGgsk$lMF~K@pvNF-O zgg_%hRwkO6fv^`E8L~3b%!EKAQ*~vUEhf;&kd=u7CIlLpsw>m%g+`|8%5+uDaRQA@ z)s>;*%)#F>fkuX`OtdYDfkuXmNi;J9VJ|c?WM!h634unY>dG`*OrVjex-ucq$Pgo% znSrnu8X2-O(aeNEBU5!{nk^>K$dHwZwj~4_nW`%@5cWbNLsll5nGk4Xs;*44#RM9e zsw)!$jSN|tXl4e&UT9><%0x300*wq=nP_I3Ehf;&kd=uVCIlLpsw*=P_Cg~=RwfFV z5NKqou1vER8X2-OQNVOn&2a*a3|X0IW~exG@V88$k*T^eiGfCjtV}dB17R;TGGt|< znF)bLrs~QxTTG<>%f43T4iIQ$s;_b!9@Jk*T^e17R;TGGt|nSrnu8kwGz`2aD{$W&dKW{U|lGGt|dGVr8kwpqGZ6Md zBSTgunwb!2WXQ@yGt+D_am#3As;*23G%{pmqL~>8d!dmbD-+F32sAQPSEkuw0*y@7 zl?jo$GCeC3&CEd93ylm}nP_H0ppmJ%GR+nfXk^IBL^BftjZD>*X||X^BU5!{LZFeU zx-tV{FElb_Wulo0fkvk4$~0R{ppmJ%G9l2&R9%^YuooH`vNF-kgg_%xb!D0@CeX-K zU6~MQWU8*rK-de73|X0IW?g(abbkOlXIM5NKqouFOE#3ynUCv$RwkO6r7b4L zR-ut0n-R^-K-f!4lC%nqOx2ZH+G0XlkPv8O$jU@BGZ6NYA|?bH8L~3b%q(p&Ax%rJ zD>O3nBbu3ku$PoQA<)QFU74jVCZx>?fkvk4$_#|PJd4-s%Ji&EG&4(EOh{vt7-(dw zuFOE#%kzG{u1w#-ESj0&{_vIGH8T5kWiq;GWU8)Av&94&nW`%j;#$$jkd=vMW+3c^ zMux0RG&3R4$W&dKW{U|lGF4Y51R9yDD>D%GLL);~CYqTLXk^IBL^IQDF@Z*=>dJ&b zBSTgunwf#H7aAF|GSSS0KqEs|CYqUMiwQI`RaYhi8kwpqGZ6MdBSTgunwb!2WU8)A zv&94&nW`(3s|1Yk_&#Ww{YF30}_qsAYD-+GkK-de73|X0IW)cI9 z3|X0IW|}P~#(toYAuAKj%s|)+jSN|tXl4=vjZD>*X||XcM;DDu)s-3gfkvk4%56KG_ru1p9tGGt|s;*23G%{pmqL~>8d!dmb_Y!4H2sAQP zSEkuw0*y@7l?j1Hrs~QJguT$nkd=utCIlLpsw!6DGd zkd=vMW+2eWR9%^_&soLpb!CoJU74X(CeX-KU75r{BSTgunwf#H7aAF|GEv5aKqEs| zCYqUMiwQI`RaYhi8kwpqGZ6MdBU5!{LZFeUx-!ic6KG_ru1p9tGF4Y*Anb)khOA7K zF(J^%R9%^7iwQI`WM!gS34un2tV}dB17R;TGGt|_b!9@Jks(GjGXr5SG%{pmqKpZFMyBe@G+Rudk*T^eA<)QFU73Nf7aAF| zGEv5aKqFIiWtuG}(8yF>nGk4Xs;ggg_%hRwkO6W{U|lGF4Y51R9yDD>D%GLL);~Cd!x) zXk@CcOtZxV8kwpq69SD))s-0td!>5JYstz)=Mn;qOx2ZXwwOR8Lsll*mJn!Us;_)s^X5(c|wyG%{6JruhwN z0*y@7l}QXVGF4Y*Anb)khOA7KF(J^%kd=vMrrBZwjZD>*34un2tV}dB17R;TGGt|< zj0u58rs~QxTTGylsk$;D(8yF>nSrnu8X2-OQO1NoBU5!{nk^>K$dHwZGA0BXnW`(( zY%zgGrs~RsKqFIiWd_1tXk^IBL>ZH>B{VWsSEkuw0*y@7l?j1Hrs~QJguT$nkd=wf zB?KCosw>lMF@Z*=>dJ&bBU5!{2EtxwWXQ@y8507H3|X0IW|}P~(8yF>nGk4Xs;nO!t8WM!g&*+nBmRwk?c69bJ5TA65Onk^>sJ8@!$CEAt{ zXk@Cc%s|)+jZD>*34unY>dG`*OsEz}2sAQPSLUc{jO=FCXkz_tG&8$sWXQ@y8507H zOx2ZH+TwWrOTDhl(W)!6w8g~ODl{@=GoqOp2z#mON?L_Rrs~QpZ84#`DIw6vkd=vM zW*}x>r!orBxr9I?Lsll5nPvC`%Sc>sDrYd-mJn!U=tnd&1A(q`<(1Yhi4kQ?2sAQP zSB6%}a-2xKJ`WddO9(VFRaa&p?B!X!URUNw)sj5dW@)H5+ikGj#OQl zfv}h7{d!%QW!04#?hjx2T_dw!S0*v;6OByOm1(w^KqFIiWkR5lAuAKj%s|)+jSN|t zC}TpPk*T^e%@z}AWU8)A2sAQPS7spWg+_*~Oq4Mp(8!RLiDstRVj}fl7FAa!1R5E# zGSSQoguT$nkd=utCIlK8vNF-kG+Rudk*T^eA<)QFU73Nf7aAF|GEv5aKqFIiWtuG} z(8yF>nGk4X$jU@BGZ6MdBSTgu%9s#nWU8)Av&94&8L~1_UxYv-Q*~vUEhf;&kd=uV zCIlLpsw*=P_Cg~=Rwk;B5NKqou1rHCLslmGl3g@1WM!h6*>&t*S7uptWf~e8G78aq z?4pq&#}Wn1E*cqfFHy!M1{#^FE7NQ-;n=;d%<}19-|NZ@guT$nkd=utCNa>+kd=vM zrrBa*><1bdvNF-k41~SV$dHwZGA1$5$W&dKW{Zh&bkWFEU74XDXk@Cc%&y0<*OggT zU72BY2O=7osw*34unY>dFkn z=;hxAKY5kAALG};!ykN&V_B!an>RqqdWq@6PhPVhzbiYU)W5TbX}(2oeXYB7;xRvP z@`~sd6Ul~mdS5H^FIT^7C%*2i>kfpyl1qnR57WeW{XgEh6IZ>#4UXBefoS{0_ndsE zPTc%fHy((hyH_&&Jw{e6B*xwE{@tDUREfc8XmPP_?g+Ucei%zU0tvJI%Xvj-@aLAl=ET27GL?})o#KuvY+WL z_2;ryV~97#@ZUATdW_nsbk-^p_Nvylt^Md06BUoOA+s3C%TBew`BcY^|B?%?T@q)6 zEgJ|jz=se;cQ10yvl3?3DqBp{NVlvYIfSs6M`66KY%x(+3~P>NF-+KN99^EbJa>6Eruxj3 zoKTChrYmWZyFuGBrFzIzRY?+K8)2{1%9)bEYS97B2ow*QV{d4CQk!GSjCqUhV0BFW zj~S5~EK@QgE&7tKCrJjQMF(<7tK1S4C^Mo(;W3M0qK>;4x(_l9(QeELTTE2{O1tE- zs^0bOu+B1{N+VmNL zGBO!=)QwZ>c}>Zmw`dhl@E$Z#@mf@fvlw;OsC_iqYx}dLuD~!5UOrD_jEA3o>Gbehp3`pf)T{0K_vdMk zc-?gJ{myAeF8ZqcO7+{>787+`zfw)G|3XzJ-K}^N@!0zzs}0$|VHP7*BeQq&(^?eq zeOD0Hp=K|TDHSWHtRrhtuu-*;Qahc&w^VEjvjJ z<2H_!$H&C>o|~{&je2&4+j2g-#e_$CY?a?+^~Rw}Wmju$eyjO?XQG}y6K}gQh6#JI z*FaXcp}3k6wwS1=-L(Ep^i@*tb}B%v`az|pS&Sm6a=N;fsH!^oFOB`MrLM6~)Kx;= z*I5j=x1Q}(FYCK3eDR)}sJ9Pw$!0M;R`yCI)G6x|TXuPv5w@79wPQs@lSbw8~z7u54^oe`feu zQt=us90^-Yu-j18;XZ`0SGBNZH@}W` zi+|$LeNN__lm5TG+J%($`qQ7jzgNU)AN|PZTpc4lzr%m;6DQs0J5~hsV+Nx3nrz9V zXD7CIT>h&)#&7=B4F|$r+Nm@ow)sveA%8Y8;HiLh*TzRzut-4e92pzi8}6H z+CMYIJ8zWQANk+A-}eX2mJLK>RYdmjx^$m-<|}SJ5Jh*d_MVy5zYYDc#l*PRq|cxUdwC4UR(UU0@0nVAoAz}Z zBjH_Wi|Fe?>M!;6CnK@p@AlnPx5u!hjyvH!I>#6$>{Z8oZOBO2Vxsm;ZL9|w37=c< z_v@=?By8D0)E>V+gC;!EwJ&d9K{Up&#l#mqAN{PE@EDFUY%$^8g0~a)^7S?n9(SLQ zy7C)qXGX#n6W;Z9J7F*1n>GJ5^(*>t|e{WIJK6s>jpz z>-^}tI!9=hkQP%;v(qT{MPRllLHO&DbxIWT$!d_MJp|4FJ z36G*j*JC&mwwS2%)D=G4348ep9SOJB{iqrdef|4L*kZ!vaX=4nqdt+WQ}yyMDl%Zi;0TY_N$C-BkZ;PS>k6@UF{9Uo@0;w zu*F2(X>Gp_*0xsJ%TJ{-hVNS6kFHlW61JGAS}s5_}Eheg_O;_J+C+y`h z90^-YRBfKFBHB*a%h%gT)YGz|ZmYUW4NaN9=SRX86ID^E?N@5@Id>f-*In{cdyHX= z30H>NPS|Vv+raIu7B*C9?%x>0786y2sqNQxa?efJtNy+JLKZ#e{2#jf6+nb)G7ARcdn2U5#`@ z_0xWyw#P8x`m7`2_SSQELVxN0jf5>G>djDf$=nYU_Nq##ja?qb7`B+GH(b>va}1AS z#hXypdDO=kwwQ2z*6oD7e4a+aQ?guSZgeZQHJu*F36sqd~d61JFd9q#Rfy{b=rccqcA z#f0l{Zzt?kE$n+GjfC$USLE}ZHWId&aIL-VguQ%CkAy8ITsdz$VJ|;XN5bzrzXv^T zBVmh)IyZfnsO^Nk#`6(%P0vk4U2|qu_U}dQfGVLyE7Omou3?o3$7pEsl@WDKC!(%d z5#3^<_L^)_*Mx|=rV~-u41~R+$>=enr3evqO(&wRIn$O61iG0J(S39xI*@@Vx_d=i z(qlvu5+d4?PDEXErY#!?bTc8MU+F~jECW$=_ll;aF;@JyYh*eR&CHp$Y#`9hgus)$ zLDV$^QFQmBHN@brbahQ9Xq_z^2y`)Q zXO4bwCQa0F_u}dx24^*UK;-Ix_-L*cTTE~ThUiyh_TPQqH9PTD*Zh%zuvZH`w zWS_~b+3!15vSVc(_uUdl!WI)zsPz34*)4H9VXr#wyCsfKHZ8 zjPU5zSfPn(K2Kw-Y%viPRIkFxzR%kUd)3)QD>Wl*sdy7tjAL()VIpdkUK@}-XSWmf ziuR;e`eO&#k%%6nMd5u>^BT-)6Vj>y}_IvHSyKX1!RmT(i!H$G2 zCZf&Qi+ZTYmC#D0pTuHngh$ z-K=7#t_(Vz8R51^X+cGmUJb?Z#(vmhBH9e8`|K9aG%HOyqqHm#66MCH4SVia2 z>nl+Ysl3qRoZ!>PM8!joGmGJ;kG=es7<=yaRtwSNoM6vQMAJfTC-gY8R(Y)KHU2j6 z==yw^cK^nH*kYpMp~soE%7ndqp2iqaZM4$k?D=rST4lmsMNh;VV`LpNRW;H4w5%%cb$_Y<8`T9BJ<n< zTTIlG2(8R4hDW#FyJ%%r{XpfhnLsPEItM6Un*Y++DqCu#J5i&HR%RB%?XBl7TAAkl zjWKL7QEvvcGP4*a?3K0kR9HnTGb3y>@xd-W`>m-%z3lg zA{rU?muzTe>fgJHAp2R~hh0YZH8ZxDsJ$i|nund8XkXkqM(ib(pB*?xp=R6C)a#PM{pIWdqTbF{!%nid%OA&5VgUF0UJ1NTva$ zO7@g}1uM{3nwjI44MaO2k{Mnnc6K`5y+SXDfl{TnD%az_W@fak5!FJ}K@ipRgTGaD z_sS^re@Cg(N4FC-x(AjGM4gXlWWw!hX8gD6xO<_bq96NLNi;H@;3~1jM6RBRtCA~p zXD1q&PN11FVXr!_Yd0F1p2s1(pZ!IbXh~QNpZ!diWMx?4?<=&cY7PinOhj!%rN@Sf zWIJK6`b*Uhw~F&zyOn3e@56CptylIuT-I)gvlydgjc6!GzG$o14|y1ok?>emKRS_} zm3zHQbQRkPd)2s2T}y#x>0orTr{pqwP&L-;M=7wZeL454e;fK?i;4P6?C?2jl?i)| zW9U}7y)_D5h2#<0-g6V#Yj#Ul$JG7=t>BG?c2 z1g~8ajy=Zk`LI`=n}!-@By2IUy&oISU_Wbh9XGTlV+>n-Zt5?w>+KEoB z9ch=f%kC_O348f|>@j+dh39S*C`ZW3u&z3Kk~7H4u>QG@CyqxVs+uEYWzYenD$NnH zGOS=fF~VL^)f^!!!^-$E#)ek)mP9*qgscoJ%}2s*PZg9i$jYFGaJ-E~|GOrl=sAO| z4El-fguSBsIfJYWD}qNNtGmyr3MZ(8@S5=2PGsf&5q3#q^?ft|N2<;b8kq%I8P-mX zF>EnW=Z1PkhYEnW*TTfLu${11Dn2a8%CN#}Bs@Mfx)bMM`&ijx zqRu82b!M$HVXy61iQDUbq^iV%tPJbE#(vmhqOSI7{c1O1uT+&-kd?FB`bs0WM}7g z`Z~{d;=xlm0?Y<=`n^aCQ_?)K~{z} zz1skdnR**cyg#sEMNFKJ8tI91;J-As$`%tfy3_jTy1n(>rFt3apcCl1iFz|omuxn={#*8nMrJ`) zhE@4vKWs5kZ#e3b&0=^ID;`xX!^v_+~Lo*vn7UF^1oFeh+%wM#2^o zb#5AJnC*nU#`8f18fMSY%w)|(pYvwbIu&S`|3(2*|6Y0nD$qcnnX$#hkG<})P9LZs zI)P@!guSAOfGBMS6=;Z2N{a)_2BNeXs+EE^@#^ivg?L zRcK~xF_9}1qBJJa$aDhDj0t zZj9P1$&xfQA@%PQYqB;H-D0ASsr@n|s#O!MqLK=EBi8P3ZnN^l?i**zfX+9#u(i~B^7cWs22Q}HWGbAO;96+ z{0G{G?S#FkctZ6U)E6UR3$;F|D}#RG#9C#7Y9!Q^K^ZZ|@ZYjm^{FumBVmh)sBL;( z8I%#*347HjwDqyF#Y7Yqy{-&eiZO->d({}W_0jcRL~SDScqlx!-%+-hpgIgyX;5{H ztukS+qN!msBWy8IqtMnz*Mz-_p4MAsi-|g$T_-j6!-Ty&(j#GuiMlEq*YS43UgH_e z^ETIGCy!Begd7X2`l)h4j)nE;RFj}~4QrwM6M7?IFKTj-V_}{9NKmteJO_FP>eP_I zU@dGNPaKZ~wI0a6us)oc4CIYi$L)9{Vao=huchBk6y3e3ctY(Ov=k#@i;3#rME^#@ zJ#^2h!q98iL`yRgRMH?T!|Ho#a*&l_g+DuTla*oZ)JWK3qRu82i4Gy`#eT(PWmsV~ z#<0aiT|E<5&vwFI>}pI_h80#L;ZgMHdJIRx787-z+WHwZVJ}~yV+^;~{b1*0vNEju z8VOrW)crB7-ybII#qRZFWmr!(#<0Z%)nUlWuuge9VJ~*YCo996)sbKqf3h;HD5f3& zSs7L^*GO-8GT36G;qJH3>uU%1{Gn*%Amz4FKXDV-ckL1H4=WF zo2YnH*_p*KVXy6P1Gl$Y*l3~qH@3>XpCXPUQ{L_D}$C|By2HJPoio4dF9cq_wK|Sxnfga zW)`D}iStn-O??@(Ob6#_Y?Uo0YILXd(RF+4xjXSZcmKv1wwS0l!?ga!F<~z%w~&=# zjr|zI78CV`qXOfM@F-S1YU7;XSedBURNR=w@aWph=V|PR$DL{|WMxp1_%DrwEhebL zLRJQS$acbBz8^=z_nPm)iq~l2NZ4Y68YyID&~9ue>{Tsn>;16B1T|8~%Ah+KW0KMcCJHH1#ZX;ofi8?oJ z{hXVy*LXfo`|uTg_T!0v{6CNV_%&b9vjBhisvGRqapU-sH~sJa@2`8sO?ERw|J|2$ z;#;o!^T%x2K(u}08{cqIC;suG2Mt8g-RpDDxqFXsn}^*jF|PdC3p??ED?Q|xEgOio zPh9xchxQrzKfLvGcOP}mdDEFMc~*Pzsn;I*;r{LHd=X-z=O4W4Iny7U`pov=`<|3m znegALcoXrq6Siz1ru7&m>bQH|@duwiefVde(cbaoFPXK`m%RFZhGdQ zoZY_RR)0T@J-1~8F&$16-My~$TaTK)^A^9;{>Q!FFpFW!24dPL{@}(p?dSaGK79K# zA9T{m(<83^gshuCXF6r^fyF1E^0?^>AA7>;xN*F*W1_serRc2YKWFk^8VOrW-0Pk< zo6foK6WfhHef}(l347J?v`*M!;zf5mb9&)xp43jg{Qt~in6OtJPwRv&COqn6&rR5? zj_Z8f_kZnIQF`2)o;j(c~b=)}4?t3E2 zt6Pe0(Edv!VT*~sx&AvA|NFx3;PzU=<*T0HDgPi*Jk_@%QL zChS$m(>h^`iC@3#`xj^Y&Ewkj@A=!a7$)ph$J07tiwWNa<5-!nm+!8fonw#vnVz-0 z_~MW3`8@yg?|pvpvSVjYFaC>vpPlm!L_g;y>bOCVG3<4ZcYV$D&rf{%^t@lY>h2dM z`rk6~wja8|^nD+A`gHLvuAZl;TjjrHuc90AM#2^ouRrw;)0>vhnofW8jSeB~Rdic# zl`SUj^#?yVz4F)2nJ#_$DYF{WDIZbSF1wPbL!kdr0(5{Kp{C0rKm*18-hA_5K(6iguSHm3_+bch-i3^ z*|LE^4H|+vcMwsT4ulk-yHdD@kdpP7EgJ|_ts$s$M~rBA2SQ5Lc)j9OR&qpI@zb^>@2h&SwAj{i}pJcMx19wwTD3*cdCWx31ysL^Qku zVXr#wSLm>sYBx%~MQM0v9ojODW&1< zBVHQbDJs)NX?SNbM$695j6nN3Bci)olv;K-TDwK5Wq0c@Z6IthQGW@w>@0=}dyTDi z&udKjnX0iuCp?^|addqKO++)?*Rw=fJZqH+d)3)QSv(_bDH;v$3AV~abe@aS@Xlhm zRrZPkbWs}K84-QuqBOj_(Q__J!@D|04LT#rt6NM&ak^kVOBA`AiN@b5FOP74I18At86i`y&oISU_Uo? zccI~(#jwR^v;Gnq-a`m``Tie!Zi|Via~GxIoy9O=FFz%EjQ;f+4exGN$}W@hKpDal zmFIcC=j-_RGx30kGVExney8ZME-BUT>KILIo|So)91u}59xc`H6b;_dQvIGFQ8D`8 zjkfP-seWfMHnge}QNA55)$fd;dQ$0YrznOlDShqg7)9=kaBrgky`*%)hxEg3Hxb3@ zC8ZPI9HY10Ue&@4t%`o|XsLduXcUi@>bKVxDb?>RM%INdR~8d>ZczOmLf9*7#FwS| zoe{Q}sA~b$?;(V}vPOJas^9&q{ouOtS*x)^^?S$}^eCFBbA#%4)+!VB@|hj4cDL94 z$jbF)seWhuu*F1O?WlfdtukS+tcYKh>US2y786lg9WB-GEQSetMRl_*)$c4uG*L%O z^*cp_b+lB!CwPCDsCcM;XRY$M+iUxi!B3pJ+EM+UV5>~jordc7kXG4i`_spFt?$Po zQ2owg*kU4Dsb#5t4kEQSetdDLey_Rm3YZ+W3bKEa-wsCa0R zXRUH?N3Y|*!p2tlsa8)PRHnUx+2$vlpM56kNy1Ql8s-Vc*jcRY1 zRWIoIcBB7VW;G0&*jWr)Ohi|>OpYGK;f&buz1zQWqxo89^$xnb8DWdRim9K-Dx_$` z4>c&wQGxs`uaerH;ZAyUNwd&z-NRlChF@0rQRWgy`oEA zmYRG<*kYo-K2S>^LfDIni=`%?5w@79dlMD*A%wl6iCt#p2x{3GVT*~nZ_p(lLfC8j zwQGxsI{ZV(c8!=3wwS0foYv2W342xlruEVFv#*}P?0&K9r|Z}cTQ(5e`_Z4_Zefkc zv~_g5#l+YT=1G_f=gW+lAZBPYqq1b4H8ZzUW?fdtjpJTZ?|>+;ZZW}3FmuS6gFS?> zR~`2qB*z%Gn8<#UC@S-w-MMf(VXr!F>jd++zj2pyCiZ}2#-Evg-iOQzXTE*PoNp+P zl`SUfc!C}Y$LO=aH#}#`oGAyP1vhi+qU+jTTE2EMhnMQ z*jm?6ZWc}xAmTTOp2KJyB@=_=eC$|?CpfT z>fE&TGiZy6?fuwr2K%|Gr&8moG`7kXpUwJ96W79a!d`xkjf5>GZuEfb>@rWyZj##x zd->@)5XYD=WDYs=V@H^uWDYqqJ4cvpM%9=(f-|-g_F^`TIpoY39T^Gc4w;qB%-|W! z{-SEkZ{5`~vj?*n%+fHsoVl4J%%(6eo;j35TIH5(AliCAOw@7rVy+TZV`e31t+K^L z^>3noW6!I%y@&2OGZoB{vy0kDFbBr0bLO#*Fq_7#bLPs9@T-ow<@};qjD#&F>THr3 zn4J$3_TrZjv(EY5GmBx1iMo0wuAZ?~ChW!UCuW`VyJr@|qv+A~7>+S)F;VBKt)D>? z_VN`v#&CPx4}POD>zvzv5%%RO%Wx`&*-o_a9v}`;rnb$?tm|5G~`uln$Y%#&S zE~-ZMh8ziIO_|xwoak-Kiy7|Q`l&q{wI=k9U*sJJ?cw-D-i5@qf*^#itM2+;cem+dt%U9?a!_V`2?vf`w zvi;d^i;21iC!YCZ3={TZ{*Aft%$v=|$`%uK&rj=52IgFtr_Nl-f;k@MsWUgTUdc|dV%TDW`6cG5GkY{69KD`b6VE}ncI>$=ChCbgtv{(v*o%2Y=JYdTIBS(HChE<= znu8hPo->b_S>P$NgbR=1*biGwFprq|-RLdPp2aX>FXpY7Ps|L}jIhN7^N1(|GZ%OW zVJ~L7m`}`%(Twnz)K})j7puo`?71x_>f3Hw{}wf2uNw8X^-Am(6ZLI3t$!!_Z`rHP zP2+5i{jkMEecMgz--#ydRp%yk1Lx=5787;}%7ne@Y_|1tZi|V!Z^*CBVwkYk z_WRrx6Ln_E0L@~Uu$S+&@qGAtEqdaKv;Eq&#Y8>3CZ2X<3={TZ&Xt+%%)!nGTTIm5 zJn?iLW0{Z9pI$?{6C^Yv_hN8b5W0y0a5C<1x-TTE$Dh z^VRL&Z~xovTVC>G!#Vf0FcMKPHgu3E52G$@=n_!~*73ygNZ4Y+v9}ZUs^f{)j)W~H zw)Z1?&4z{(wOJiEjz9B#ztevAhL4}_bM-Iendq^yWdqR;CyMS~9>Xz)EgOi&sBb5V z?p_}0ot-Eq8|NIYVw8~$wIph~I&K_C3)xUqqG22fTQ(4FE72`C`G!}w&)xb-?QWm> z>l2J&B5KBl4iZJ;_Ey=e=!tkEVT*}6p4Ma7V#4QtjA6oFb=!WLn3Ey2~t4!Fdj{Dubv-9#V{8PWKzV=t{$8HN(19qrd*utJ$H=u7-~0d6d7b#Bb05l%4hNPE1lMzX zA9>!-^!MQ9Kk|`16Ls9Z{^?up(0HH!{3B7mn6PC7F&$16-M#L0w;MOUOJ0A{HD@tw z*+5K(6GeBgn_cnwCEsxWdW_YE?uRWKi0N>m=@q1J>&_~UtQ<$G?zxS~Ak}J+?4|($IrYk;q&;Ffo+ef~7dfcNP&9_AU{f&uX!WI+t zmnQzwcEVoumqN^AY-m-ZRgO2tu%(VW@!apZY5&T2`&-#z!~HN}uR5OA30qA3?Uk<6 zp81x3;Pd{vJ9Fkvs>1v@)$xcs60oWJDF=kEFp`W)Q<`M=SA z=%c?g{q0rXntqu0yWcyn@s;uAH|_i4@C@#|-2Bh$J+JX4^Igxqex7h9Z1Ee%@2-(> ztK5=0ZtJbG#l(aE^>KXrOgFeC>NB^>guUvxtrNDGIPa&Q+Smi)4IlZhSqu~Qs^hj! z*kYnaePYzdeweVA&(lcQVxrE|w0;In*vn^g_%1n9mOY*4J$()A4c{ea+OmOY`7Q~e z?~;Kix_jwsAcVe4&a`C%(ehmqLf<6=QFQmx*FXq;mz-(K2BPuR+~;EYJ;+Q;=3n}p z48LRRxN&^mgMOpE@1K5WdjB=p{UNhA2ZSvfh;}$pboa{a4f8&I{%4F~i;2vW@Fm0k zPP2aatoi(B)}w!4F>^7-uw?_mURZ|^MR%`i6}wr@2wOG~8~S0wy{!>x%vO#4u*HPO ztg~}VeEjr?Uw`H-hAkV2b~sUV_wpEy{jg;N z!Jb~TR+*^d?&Xp0b1}#G-eqnk^DoQV!D@BPo<+=`ENhpm#K`Q;0bxtgCfM2P5TfYr zm06EvW?0xaYBOOk_M>7hW(#3U9e3i#|NPy{f4k-r+wWib#j_YD>{Z9pI$?_mpZ{^J zOxUZAC+24Qu0wrvnK#MIL;sTD_rIUonGNY*GR(k?ge@lOxSs8q?>UI!v*z=k*@9*5 zY&C0@347HsJ5bFCTTEouqkoq$b20YAguUvReWPZCEhcIV*_-MR!d@Qru~oL1s8MHc zs#y#Z_VT&e*-;*6S2O19O1aAEG-XdRy2|71+OmO|lE(?5JkCHA-MwnQjG4O-%H!bQGl)}!Zfn5`IFWy=O)I-DrFdu7(6=e(G$7-QJ7ftU^_itb*S z_2ApCFe0XCl#ALg zeENyg%^&dBOSg86VT*~(#qf>NXF;|T_A0s&ZzOCn;r?wW>{WDQ24*B|F;T}gR+%U1 z&vs@HG7Hh?NSHmyyhYEq@XNK18^=34CTuCXLHjR_ge@kX^ye3~Fa6giw@-h~J!UaX z*sG4Gb;1@Cnf2)NCCprmtukS+I-b@ETTI;VRZnRz`02-|A3L)cChS$m>BpR~#e}c? zu^%SvRmbFUa+PGBB=4R5-_ZH}-E%DbBKF%LznOa;hhN7dVT*}6W);DV@KxgLDl-y2 zkHf6O7{itg#I%*@mIvSBqwSym^QqH!UHi$*dYnKE6Pd&4Um46pY;Tplif+Uk30q9m zaa)gJi-|f<6X$7+VZvTMvm;@Pi8`~>`Z+gYFQ5ONom>6z{&(V!J^G`3m+aR160R$b z`;~FiQ@_6d`~82I>*@O}n;iAlg20{xAMgC*FR$KOBgnyH~y?dW`)qnFqe(A)R>0EuYV~ z&w*tF(Z6c?3W)yg!z_q<>v79$!EUX~NI%%ao4XdmmJI~!G7ce%?p~Q+*sb*?Gs2b) z1nWxs?U5l-WbD{ zI_^YfC#G60GK*otUUkgcj~QW$iK|@iIny_M{PFDx&$#>$!d`VetrNDG@KrhX+=RXA zxV}r+Et_-Bd_!ghCgv0PWuIT~yW}JIo&IMZ`P}reho0T;ec>n54-@&tzFVtB_|6Y-CB{7E7624ChEAJ)FvF=t*X|tB4ySp_rr7@PwV}##e}cvu^%SvHD0^!huiCZ z)Nx~^#~8Mls8MIt%OQlle4fS_wwS2%#HyZI3={V9*&OO-kj^ z3)a2zYqgG9!_e|eenI|&U*IEQ%Lal~7Kac;cdrZn;ri3fpZ4_Whdy@I^dqx32d%Qj zMCLH4&B3aU8Q~H2xyj5*uU5j0$QZ+x4Fs!G4k3!}Uezkru*?WsHV_;7VZyzw5oue; zs#{EW-1;7*X&bhCJk;r_=qE>}4L$Ih-D63;uc;uXC zwa7t?^6C~7j=i0*R~=8Zb|h>uvArMp-MXq>!dDW}xBpZtRr0*rM%b%pRzS=MTTHy{2hW+laIV0 zuQ9^R#dgA8bc_O+4-@v<-g8?_)VQ&RWj0nO?B!7(=1b7y@Wt9SIQm6D zX_jId=1cZ$*+5L0FA1Ufl7T3?duf&;gyu{3Y}r6enJ)>U`I3Psx_jxHI)vs+(ERkC z^Df^&kkbjldRLx_d~M`Ahu`|l=`ZTIzYkw`i_cFNJ@oA9|DFA*#Yot)foO*lMR%`! zB{7#lE@T$N78CipV1|VZ&8#2pc^&uO<_o6J`|#y4_QRG91evBoh@!h!wW_VR%9ahp zhJKiEZ)-&QH|f|9TTFP|dNw1y*?;H0=N*5OojcBI@BGF;AI`b2g^|eHx6h>Tp3Qeo zpSj^ZTgT*aat2wqyNY3p3CG?}*sG2wT00W9nAqMA{YFOfvzjSd{MYY3YkJdfK7P9D zt*)5Guw?_$4kwE4ULM1-AGT~D$S%!VWulI|mq)sP^PI`~;EU$ASryA%4{zzbyZbww zw^02%nWmgOR{G9}ZZT2EWUyw0$Hya`ucSUF!$;uzm#g1(Anf%= zw|OtbbnJ0g331gM+@KS$|HnHYvtc*Y;o|Er15Jh*d`#tpk_86bIfIWUc z`N&f`are7__c2>G5N)5h??2z76W{-q#XuC@y&n7a&-WPlZ_dZvuJrBut@_02$86a^ zw0+`xK5=>{LJmaH-7BrxW32L55+kkYL|S*umJLMPC(`3ieBzO(3`Ei0E2G+DWHb^Z zquPm#@-bUB5N)5xnd?N(fN*7&)tn@zJZ_wG+8oj@e=&S0F^o6&d2IuK6RK zcT%~ zVao=htrPA?wQ8d69+5GIEhhf{BbPSzfxY+ZsWRqPnXp%l+r&tZ#Mv)-d878(OYZvq z>E>^|sIjx|PyE!st$MzpAJy}2F;RbM;xCOcOxVj~I1+Ae^=aaYasNib785sl@6pEY zt@k|n%V#||VXtp|_a%+pTi<+-FP#yue9NmFySIMkuAiRnb=k#@-CMux_W!Xuo;V&` zRbJgxN+r=t+K^uv;NY=wXmJAm+!QZ zu*JlO|MZU=ySJYEu8+@Rn6Q`c$Ns#{neVaAOy&1Is*Jt$^LujQt(*zfhvzi`2f z_`k0?zp>xzN8j_@=|5ln`;GlxfBo!(B^!vg-VYOX+`azl=mqVkvfu0fICb80TTE2{Ci*w_qk7wW=$@Z^(Rq#iUQfQm zocPH7X?(xqr zZ|wJa{?quy;=9&_y)HWaZH@h2@AnQWznl2yPh8a4@Ab~doukFtgKcnhuZ`>dLOJhH5F;RC~<4)U7*vn6)k?>vXyQ_$a=h#Tt zV&d{^>^1g#{pDA_=n%qQ^|YIKK8`VLF>#HnEF1g1UhuW^7$)rHF&tyqV&akib#Y_A z*H8V+3udh{VJ}~AV~l!QHlCK}e*1Zi{a)|&4bNSD!}ss`k*II=ZZUDnE1uif@AXBW zJ9pNqpMTJE8~eS!xa*WX^+U*DqBocylK5vChX<&G{*2#t)4y;&#UcEI9p8A zl{oR_8)KNT*FApduN%9bUU3U{rtnkL787;lPwV%`hHtq3oBXS;bCtc1rE=E8{&a5^ z!xn$(9l7YM_Sk>-v`4(|5W-$JdFs{nsGRli(=VM7Zg1V^6VDI#Z+p*8)RSmhf5Q21 z+3QX}cX?x<)L(q!%Vw>z#Y8<(r}eL;pE&PxjXh;QbL>y1N1pxh#-6hO^vXY;e)#2= zXZOpeO*cAk9>W$Be|*xvHTIPK=pSA*Yn6#-|J(Z-d$E4c*)N|QdmJlUO#H{g{-LoK z>#66wViv=Mz1mCuyRjGRH^2QgGr|@VCq3pPjlEbu`+`>;LfGpb_x{p7_F{d)<(JF| zk9&OqPJB)JJdHiK#YBB~P3zx@ChS$C-nO2>ZZT2cUDNtEod1@+>fAKW=GYHgOw@PR zwEhie!d`W5+WI-S#Y8=oruA<)6ZWdJ+1AgwEhg&ToYtRkChWES{;0)|EKjQga4Mjs(;h^eeU-}y{{T`4t^7j{jg;NvArMtediX|h)i2Yw_8k% z{a~(SXXiKj?DnJH{-^Etp7WgPZ5P~p_Xj`qxPF}f_U|kHegE6X#P@&yGZ$E{_@+DU z=6Ja}#)so;zwCSZObP%0evDt=J8i=9)4zP?-XpH|@P2%?H%@z3dBm6Y;}3o64tsd> zzkMQJy(M@Z9RKJUd$+mZPW|6Mcw~1*IEMf3UBCUoy|ovgG>>7630hJ8n8h$*ul#!- zg^e)=%j)kYUhl_x&;7UTmHu^tF(fwsJ2-Z1vk2A+HXOc6=F<+be{wv}uueH}L zUvl29_Lfh-tRFx4-%s7U^v<8|$3OOrub;)R#l)i{At%N!9J$URguUMSe^2hjJ*Kai z5w@7f-|j^I?GVCV_x$FYcH#pMe9x@swwOroJCVK}LfGs7oO@a)PX4A>%m|OW&xh&p zeAr@wdy>)R9^FpZYkR9~*+jhdWzV0*FtIwu>lv4SXK&Tp9&o{ou*JlEUwE5N-11TE z6te%n{cG2Rz20;0sT17$BVmh)tNrL1CqUTi15dksC;s!~JIrF_9_tqFxjbq5F;AXV zpT6{=-@2Wc^mnH`5jxG2W9)}5CVut5@6?I=e&n%-5cbkvT5gT8G@;`YBbFYKF@`Pv zyXw>Sv1<16NRKgWG2yd0600+n>vdWk=T4n;#Y`h%iwRw!hYOXVCQO-#MFOKWs7a z#bfZd?4`HFEQT#6^zPanTa{;CA9t>=uXyQi_2YYAzS#Zc2fU&m)9R7%-_<*6cY6$5 zOz15-i($fEde6@YTTJ+h8T(of%6qE!gD1pD=o@!eU(0;M_b+6==SRX86Z#H5gs|8A zcLH(tzW{78k>k~u^LmVKp}qFf*Yb?8#e}}840QUuvfkxI>FOoBy2H}@0AlE?3J&xPUM?<7K7id zT-7{B@@(qIJgZiH$~X0l@ZUADJ%%kN9DD4!347()(p&hy-b?kN{r~MhuWT{FZ-4s7 zGi*CyFCEXm!u5CgLhgT;Un$!OTTH06vlu4qrQ<{TAuoPe^cLn9%PfYx7WUHdEXL|; z$UVWYt^RlOG-$di+c>(mn9yBt2w^W>Z!^Lc6S{8>A?&5Aaz^NR)$}Z37H9S3n-R8{ z(9`Y^!d`m&?2V&qi-|lvd#i{$6038-8FZ^w|IXRmOkgqL5!p`IOYfCg3|ma-Z8z(O zz4TVw+fLYGLhs#K3={U!m%)s%#e~n(I94X?rSFwl3|mZWKj$Xwl`rRhm2mFIR@q{L ztA?lO;e@^N{_6zKficFxw_4s}2gjLD-cHzJBH!~pMt--=VwkX(`!}{KPlH{0$Xhs1 z>VC}IGEatn%sX);Y%!6yL??KoZYS)OQSHR~yVjOX#77@<-B}D1t7E)g_~16tzqIJW zu~oL1pa$$0C+xMN*XQAE*+is;ZETf^)iGWgg&Cn=6T@|--wCs;#1>yy%qh}y-U?%@ zOxTN-L8PTK!WI*Z(HAFXUN3^k_|1BrHXc|;;&vB8tq6ZTrs++`zS%O--mdONYA@zN;F2+w#O+#i{_(fz+W#<0bN z?%+cRd(kq+DlMH6wwTb9=n!J``pZ*^k@1`Ld}rslWh5@`1n=Up=O%V`j(erG{hV*? zhb+g5#M8g;M>%*>A6V?geL+8RCTBgj#RT^rMDDml2z%vhc4B?z&X$eDrn%RHzjZ*z zOJ9JqR@q`g-;ak7_R^Q-jIhOozLpOm?4|Gd8DWbFeZwC@*h{}GW`r#!^m{kg?k~LU z;eGweqrc|tzJ}p}=RCXTaNhp-w@i1t&$Fk;{q7Bh{MS0c^^^C+u8Grr^$pXvz51N# z{ojQac^+d$*h}w^S*vU@@y@;1O_x3Roayh*K+owIChYaZD_uHW{7vUfpPf)OZX<5} zgynRTM?7mf{|;B)J>}0YnVxjrXHDPqy=ePP_-|cu>E85$tf&3(b+5AP*dt+!iM!un zZ@T9@o;96u`>&kEFkvsZaE#&h-t6kHo&Nph&z%1B`*%*TRVI%7(8be-zx$cfN#}pz zkn>@$dq3mV)9c^)jOkA<{M3xF<+-1_Xu3xBUU|=T{vY286W0R&9s6O6iBH_)RnyBq z`Sj`gANS!y2z%Y@;#W-n@#{~Yc0TI7S5;(5~_ zPVacyQ>V|r`Y&cN+$wwh(D{Ebz3{7_I-Pgwn`eYAxBL8yrz@^Fd-}S6dD98D%0yH* z(^tLY?CJAA`KDP6x5{2$aitee-}cnAr+Yp7^)tej4}JTE)AjCp_VoJ8j-6nuOuX@@ zUo^e->Ss^4Jc;-Dwliq27d+#I(>>qzl7TxE z?sS#wo;6+XHC_3#`Go#!V264MUsH9xVL9Sa(DuYib@g%5f&8`B+CEytFE5= zt=c>DA3mS=cD(0&`<$xouCD6S=M?+o!#iDG{Oay0#XcXpVZif2V%{@;P<;HfDaCJg zac)L0uc)PLz~aXLnNoc6eCNcGpk(LIPb=PBX-aYY+CLo7D-!qq?XqHP<#zt$LFZc1 z2K$OyA3x=?;z!R+E}s92v$jZ3a@7YfD;EFxbOjW*~N zwbHBo{oma>RHk_9>18^4Hyz#rI`-@NkDp{-9UuFV4>moEI`G|p$;NNi*dY+FG#BYm zLc+gIm~J$dKk<`+`00{E331MxO9ZW%7r*E4M7y^2f^d#zAf7*ajl?Swzn^=7K>J@+ zRheu3K=@xCi&}1%+hlp8VgJ1baeM4%Jx}!SdOqhC`|oaNqv1X>;Xb2;L~6q=HsKy1 zK`po5Hr%#G!!0)99-xE-+oU~_G|x5RbI)^r^?XY-*Z;e!wXAq|@(oi;@T`$ob*^Qb zyKi$*vERjha?%C~YNh9##H%ysYJPh23ybevF|)Y-x%rw;{`taU!bm&2+DTArzNO}G zzNxwB|7lLj_N87?LgLXy7HQ5rcxrL?bmw`|1_^4h7gC}ezOR`6fpdyGrl+IYt&iVb zeEW}Q7vKMv^POpf658|cv9X;5ZR~N+6UB|nyITDR*ALio5+6SOsbYos&nr&WlOgqr zo=|K4YyVa}^7?tjMtj|q5p%rrX7PayFDUL^@wQ@U(tE{LQ!gmKaQTb@y&|!}hv#e_ z`OgcAS61>YgDt05)Z*2X67+Yk)<25R?tgx9bK{l)y&^H!um4>v``h!2|M|gB`*=ky z_DG}gjYD47z1wK~dfz=;epli9*>5QP+hd7;KXT^B!X4H6`3K9CpoE0qteEzjmfi%l z&RKlzaL<3`&V@6gweE`H9&Al|V)XeJhQd8~+wcE5>NiBTA?Fp9VLK>Eh$SY4`*HfT zR}|InMZ69zdYBTFkeD@XwQ$!ycki58J4jHgcgwFlXwIhZ+P~biZqnLM?l4EwckL<5 zt(LWe683_B`>vh6uV~}E2N!7iuKmHcPD$*gE$4Abym8TjP2aUA%y)X`6$xrxd;Nr_ z@7kyLxg;Z=TydGE@7lGNDMw#Ae%Yq)+K(S`?|@#BSm1XP!(Ds!gO6r5=oPhiy`?Ru zzaQIp@uu(EKb(8@fL@V!=I$k%zH1Nr`AvPiq8583@v4LCD!grscWv>;TkALd)@Xs3 zChEN7YVS~jyEf4A{?CZVbx-)M%A{$p471;6E%@Q4-{Q=<>08684N6GR+uj7VEyeQ}q3> z+>{ZNd_uJ?{if)m=G6mwMdF=HCN%w~Xw4-r$!yRoYCXQ#B2B+3+WPP3WCSIToUvfj zZ;JkQ&;JhS6^X|?3pD+vXoVe4$!yRoYW?ZI^ELgZ=(*O>89~WBN6*vro1z)7?mnPb zBsP6%uBP7vglLcP0`Eu%)N0+@VNUt z_(XV9G{+w6_OZd^l34TWPlPu`%kOd1hN%q_)biiQotJdjCx_2^IlL*_ZIMd`JRc-} zv-eBkP0>zw{cqO0^om*={r-jUrs%X+ch3k)4!q#6;Z4yVS8q9>S0ujw+2_NXqK|xO z-OL8PqSgcRKNsE<{bSMPGJ=vf?*4OlQ#9@Fxd-%$#40C08{QOs{ohYzR|&nM)^@{x z3U7+Ov)fG>LCH7%^K^Jqbo4#{yD^W{`zj%E^-WKOH$}VdzHVlN$D&qxwcmW)H^Q5V z@~B0c`bIdcOq?@;xlg&pR-1*j&k7&7b+pmg?eoV6V(WkXPm>Z7{#~z@8jZic@y$S7 zw*74diQ7i2f%oZ8=ALYt^aGB6m0kxk3}u~ zU1K8J(T2atJQ3cCKwq^fLCfi_2(+BNI80B_CJ|_PNeKzINzL8p`(c$@EO%5#U(SR+ zQ5?0{?`uQNUw`|eVynq_CK+|J6P^|4#D5oBxOv&T7ZxwF6&=Y4DCO;n6Ur3nGJeH zE&u(xdCv^C8jW8TdxWd~#f#o*^PKy4eQsX(+egB+@XIN#)^p^3)qbgKtoBly5)$<~ z!QW&x8fTuhf3R`LQol_IYCXC8`oYHEhn3x-{cTyJaqBII z1mfbw+6h6eXSUfe*jVwUGej&l=i!x&6>e%%LPFo~2OIkGLd5WIs{L{9`On1(K`nn* z;_=Gg=QJ8GZ*xqr@x$}ZYEzOE?&*qHYRy^UZS4*#@6+Id6l#rNp?K;gL{B>$^)+uZDA*kg(9KWw9$%(P^!FI40r!4uO zVvh&EQ(ScCVZ-c^v>lX?*!0*&b64HxYwR*PJ0B#d#q*Td=o~Wf@vAe z@3MbL9JKU*inDc%eeuD=M$_IUK`mYj$w=MASnJG};Jco?CB|d510!`pP^<1Yf0LDr z)J;lAU_2Iqkvbu$g%MQ*M(QRdBrqO}z(}1C)WV1=0wZ;k5)$b-$4H$J)Z!JBJkMLN zZ*hAVk^jB=)Dq9#@|X>;DNfMSd7%T&l~v zsI}Z@7Ya|f&%Jm{W`hzEX*)d6l_j5-_8Iq0F3w%xtm5kPE)G2!XGmG^lJGp&V}{z$ z_RQEbWX+V@{=3Ir|Gm-3iCRL!Gh@$?HKXlAP>XF!ZBWazVb6*+2Ttlcr38;f!t-1| zOEjZZ@3I{vsCC&=BgLnlJGVIROV4ElC7um?6xAHKPw&zO3D1%}Th<&nvq6GdJhP2P z`R;$i{A#`b?$+WNGpjLEy1%&g4}p07 zxUVDxwZ63f)L`TKbDe#5++Ozw;*Yx>)S`rh=ef3_F;lwl{^A#b*!GTt6M|X`+;@Jk z@#s1qm+q!d+!~0VO+2hc2?@`0Z9`+Gbcd&15r}=;MW7b{@;3M@$LC zY4aV^qJ)I!xwfIvRJz-(dukwFIP%zppq798POAvdjD6E;F4y!7*fU|x<#aWS<@`)M zaQ97K*!|nZq=z5S-$|sBF~YR(c|D6W!gFblmYTD*J(u>JS~F#NO`0|+A>p~S=hT`5 zi|$2G%X8_m>xu*=BzpH132L#YQ?J;&p4<9~qgm{LEhll)8&?e9_{VdKQ~x@5pO#aL zy&k*@Bel=D=eZu$H1AD3@vPOOsOGAbjV_T&#?G30q)d8uT!LDjgL<6T%rmn=2?_OX zu+hDCyEaHr%fFMWy-Tp=zu0J=^0DH=V#&@5NiU>*#Ve77*9RWkHM`B)L4sPI^Lo_Q zj5Z@E@v6n6vu3Wz{n*z3`ilHa#-@W$FQ~ zyEoLnM;bFa+ppjD+_pZ?_bvOQ@b_&_Tu1GgaP{+n*kH<+Ta=K{I3MWhdA{kI)t4MI zj@>gMsO8`F%%IWO{ng3A#&4EArp0s1bN;)hjt|6%pYXVQ`p`vzIN+kAT9lB`h#I`A zM(VrvxGoT%d*<+jpcZ?i(U`cvj6huS=R=deBB3Wkuu(m69^d=^K%Apz6puwM_FI@U zw0u51zw*r3BeiC+e(Hzg`rj27pIRP&pT6aMZ-&mfW*J?A5)%Gh&(2bUHas)-c%^x7 zVlO3lToRrcd(77yIP;1GwLAy)lR-1jc4~uH1FsU#jQupw>^37PAwk=z4HDFP?3mli z$F`eVys}engAx*HJACGR0)1ZAT5d|Y?9FEuZ+!fW(4+M^AYGm7n(!Ut`_66fZ{HLC zed(`PX|H(BMaACp-L2lG4N5$hj&GdkRmz4A!cXk2s2fq^*o>4y@6TI`WVV@HjizCUK|bAQrTBs|{QhDTQI zLaPzl#QF=)NC;}N->R9h3C$Nfo*Bn?#eQcM#$D&_zO~EazUYiHatI!??MxMsSO^Ngy-1t{dM(@tZRb=weDDXLi<{M-M0D7{_>1oQR4Y} zd>5W&FO#4R5}vQeci}o8y$EX6XVWvml%Rw}dhOB%32O1mPi(Y2Gxivz`C?el_*(K= z^UT;|qUOW;->}i5guMXUeF$oKW*lb7(}y#H5)x=fAA(xwg^Xa!zqRy)_Qr3VSDb&^ zqr+@d+Hy)rcxD{mq*w3s>nqVwneJUgEzgYO+u@9$#4}@$wVL-1=oN|UcYeJ5vhLai zA9-3|C-4l?D{A@gV|Oh^QOBd|(K4*8<5*i@JXY^wq;6Bf^MTPv1fB*7K`o4lA~3?W zDItN;PQ;XZt5Njy!|zQ9YGDKyG3TY#Nd3%{549;FQD2oB+eP4MkPy_ub4A2~YgA91 zy}$b}$5QJjPIxO6pBdq;pnq!~Bm#4Wj^~>3t!$V@dc4wXtiUrkBPj8_vnD*F^mwIN zVIP88c*11_B_uXo=ELnDAAM1=*ZR(CWIISui#?JOUK98krTKf(+WR!)TvId7)i!Xv zmNqD1FZg$ymu3WQcuf%Bo+tKF8$2$F5zWY6(2VTPd7TYNuSigfXEvF)H$5AUE5)YX z2#0qI{@TKS_f?`k)3}3GQ6eF+=E!a3lZu_+Hf=&5f?D)8wLu99y;}}%STrBbY*38rp7H)cy^A*!9ZE=GwJqX;`1a$usRtwkwXkj%ffap+ z5)xS5i&%Bf+x7qTnbhTnCIq$c#zMNo@y)~m&m7*NgaqC>i1^>Jw;u^XEzj_M-{>hM zLSI(|uN=dpBqw}FRfK28Zik+rZN23jjqi|kZpW&TOn!FN(G{1TQarlA^ZGl9R5C`G z_Bq!xHzR06??p%Bn^bvCnl>mQq4%Pr@olu|UIevXerKL?XuS)Ie=fITMo^;n)ZzVw zzX74`-Zn_+4Rm;yp&4yvgU6y4-jQYmB_w!eQ?E!+%fFLz9@bGl=bP@d`zCiQKJdO@ zJ`m3N*jdZYN0-pCiuzdoU0;2AiyI<;{uUv4H7-Fdc^i(Tc|=A~Lc;U)_-4Bgk!tm7 z2erIDh;Pz$++GAFB=mN8IKD&9ydpuZZC|}&_*_K+-h9qGjqBR&_7x?1pFAAjG!N(% z3D2wJ8|dmD?AoAL)Jm@f#G^cxbk8%-KO$T55HYU~B_uQwg>$YMt%zbQu9gtgLWE8P zVs{-%NN7Y2HZ-FZQO5_jx#Qr3pcW#HA`pY@P(s2pW8VeUwTn1sLQo44Q`tZ)wL=LB zJ>i0lYVL!0Z9-7Xzw234m;rP=wrghQ*-}?R!ZYLe?p0nPw%w$Jgr4WYEC1V@pjMc> zS8s$f8ZFpuJ-=2H+()DEG{gaEk_0_^RFK|5>wu2H9{yjD?Awe5@ z7aqPZ@mC|HQyY|!ICYtkVzRyiICt;oGOtKbD{VQd6tIp@=}dKJtSbXMRBrN>sI2mK zQrCdBo7yCtsqTz*<)rr^sD-TmjBuv9GuD-R+;*nAGuD-p-bRjcnR-PnXR146U3utz z2p)@sGu553uAKDDD-zUVFQi^MQ{B0*$|^5OJ5$}cugXu)+Cd2k|Be~!89^J)RCn&H z^3W4|saHHM31_N1_fi51A0Zmnd;71 zS5A7L^Fb|MJ!#A7uQS!1`>H(j0lgyOOm*kJDknW_Is1xQ?2#mozT+xi&P!DduhKQU zoX@H1T$xwM)$h;-30D|%KBww=$*W!jwOohH`JAfrl@X{XQMzWEvv5_BtwjBaaR`qY zx~~($HQSu~s#*E!*Tujh>&%&~s$@2xS0r5P%$cmJYL?lcSJZN?GiS1@!dXU8;#z0UWK|`z0lgyOT4&B= zRaLXh2EC$|Yn?fhRTa)Mf)dv{b0(`QnGNU_3D-JvCabENWi}G8pygU;u6d>kXBk0> zYn{2~nJSqL=oJaqI&;l4RW-|O&?{=W)|qRbslr)CP~uu=u6d?PW&?Uf!nMv^^GsFE zG8^=YTCR2GnrEu>l@YFW=9*`!WLCP?nQNY@Mp+-PNYI{Zow??jszGHocwE;ybImhV zGV5c5$0gxfXRdj++`X=#-0NvTEgxxYmO+Aj;#y~}d8SHc1A0Zmwa#4gOjXVLcttJO zI&;l4RXEECN?hyAHP2MZY(TF_xYn6#o~f!?W`n&;E!R48%`;Uv%Lqzb>&!LJRLN{W zuSmGonQNY@s##`(UQx@n&Rp|M70xn(64yF&%`;Up8_+8fu65>`XR2zJ*`Qa{O0Ra* z@oF7ERue2)bD&z6W__p?)}jQJzXI)5YPDiP<*$T5O|Ld>CzZbvuSlTsm%KvFvxJ}) zYN3fh?Y0)@SDaI!rki>f_2F8SkVtKy+FL?U3w7LN1J&MIl#pPXsya)41)%yLZP!+E zzbm&k{Pqmczg=g^>p@jlQp;VLsU|2v9qBeITK6HSe3SCFcM({`OD zuOL-LNm^q&C8SHyqZ*fq|62hYSF{g1|=k1XUS{MS<{@;z`i0ut==tnoh7e1 zRTC*`t?Mj#&8g~2nT=G!{%K72(?I#@x=QF3ZMe>o*PN=Nl-NrN_7w@&S@N1w6_qlt zNKnglmb~Uv9ixnJoh7e1Rb{B{I!j)2s*2KpUXgH}C9gSEQ7N-Quc+m^UiI~sww(UD z&XU)hs-iTYS0r3#$!ktkRO;guwb&!UtMKN|cdf3g`c0$n+VI>nwR)t9nIAYh7o_Yc*9@%50>Pu`7|@rZz}W%XOB#=2Ug1%myVS*uK;T z+u=G(UZ1OqQqrcB;8jAxb(Xw7S4E}FD-zUloh7f&Rb43~C~=)7uToV-X+WnwSdswzqYdPTx@mb^+; zMWxIJy`q-uEP0ix8bcZ3I!j)qs)|zSI!j)qsynwSds!BAO4IbBZmb^+; z6{S8lcw7>$v*cB(Dk^0*NTgcXyrg@TuuoiP$*WXVQ5w)I60WlpDs%7sQXj9VnwSdswzqYdPTx@ zmb^+;MWxIJy`q-uEP0ix>Pi_wiR&zRm8vRA1A0Zmb(XwJRYj%D2EC$IdbPXGk~CdQ zsD-_$lQoX(EP3vu8bcc4TxZFI>J_yp;Tp%k$7V~evt&ZmhZ4edmaL_^LT%b^G+bxN zgsKlEUXf@tR=mozst?JlvHwm=2x@t6T(8?yyQpeM;M@+*?)D^1hv=;saK9~#>(7@CysB%%G{X^N@&l&lQ)pvGe{ebZ^p{piM`Y-9+!mUo3S!? z<`oHQIldVyb7zF(n_hD&x>q{B87p%S=oJaaH)Cb)%m%%p7O$SP<@DF_%~+XxK(9zR zz8NcX_wkBa?2+o;^F63{$xX*M-T)K`qBO zObi=M046oe4oLx6A7*+Y0g8K)5}eUvcK-7P}p8XVpjUEB6^CBvKo0u?hD8 z32M3Zw&Avg2yY-1?`%;*f^Dkeo3^3YSI5y2AIoc6|8{Hr+wo1W2Nl&UQi2i^b%vv( z54{O$Ilk!?tD=4x;rM2VJ573G*zrxTAQioI9r`ePRbH}ogm%QIZU-d^p(u@4lZs0! zzqS|QC}^!k4^x5?5{_?r&8bLc)(#TX>fLh3H{-rCNoyV7jQh%D?VyCc;NN~4%-&bD z;rM3US0=HSww%W$;rM3US0?j{1hpLBjQh%DgyWlDb1J$w?D%HfS7t!3NI1UfHK!t( znGJeHEnaVF%jvJ8?-#(iZ*QyY|!ptrpVYB|0c_m#=KqJ#w7m)c-E9N&!l$|P+{3HnaL z@y)oeOxAJ|)N*_??kkfKlsLW__mvsYD-w=x#(iZn8}y1=j&H_&Wio;i$2a4?G6Q-= z!tu?xuS{lxUQx^OO|McF)yxP=9N&!l$_(fg3CB0%zA~8&dPObAH{-rC89|BTn{i*6 z0lgyO_-5Q!CbL1WsO9)(+*c+eC~?)yG)N*{&t5iibGlCMwH@!+#^zvssQtzvTgyWlDr7Dt{+2FCLm0scUK9sB1=eMwxoHrrp7j#b>QiFI@{B`6`GOwI89 zuJ;)3O;F26^7+skii}W3Ug=e;_mWknW*PH2n|P0+vxxU_&id?XDLb?Dn$!CV_a-PI zp-j#2ZLRkhPHm8&7JDHjlxrE{oZcmvw6ZosoYVUarvxP={5!sZ%m~_0c4mlkdS7AE zsSQd3w&Vof+bs-dC8mQ-Tr_%G4}lK4+iv zK`mZAsSWz8?9347^uEHhof4FgP^M;xb9#^A-UPMSBT4kNrOd*x9#rJ5PP1jXxr<>PrPy9Z;Jsm?e9o}?RrE5%Jw4{@?j47y zB_x!08P=SNOZFkC#rE}X2MJ|rhPAUInVAh9i(2gU)CT)R*_mMlsp#c^=YxbYHA9?J zk<30`QA=5yA=R{Yh83iumwj4J8zhve8CH;rWcKljTFTlCD@a8(GlCLjXNDD| zqL%}DMM9aHVFjs3W@dx!pq8>W!wOPS&5WQ#*_mMlsp#c^UXf6yW>`Tgl9}0{SJYD0 zW>`Tgs+kd#C_6K(AQinF&?^$k)C?;~MKUuR^om;P)$VAeXEM%iv1H} zgfl1+acd${**tzMqA0>KR1?mJqzxW7B@iF%P(lJxK-q9a)Ha+CNrGDRHi_4EIKT4m zdgg>Uu6h?S;SMDv*b7yB(_T5Fl?1gAyOj;cH%+KL9ZE=~?Qne4gra^;$27f))0#H? zc02sr@y(deslFmX3BLGkBD<;&K`qBOV?Jk2D83o<>za;l#(Yj`J+g{D)VmI~oL*5v z!tqV7CKZ>=Y>=Q9Jxpy-Lc;OQn9rHnAVIC(EmyAPaLngSTC1$h;h4{v*+?bqpGQ{l z(_r?#q77wd4##}X#9rER_7w?bY7WPI&de(k)KY%raLnh-2*)?Q=2UdAsqD<*n9n(& zS0o(YjQO0I4SGc_<#Tqgx3uN-SJ|1vF`siluSh6Ub2#R6_VJ2Z?2+JAxX*pp>beT? zent9x*M{G|Yn9a)zGzj{ud>l4C?VnB_5GjPn50bTn9rHCRymlXF`qNDkxIs{M0%Ur zAVDolS zy%tqeGb1QbcIIfz=N!;063WyZjrp9J4SGc_Wo?eee9nxZMA@06F`siluSh6Ub2R32 zW;W;*wUo6v8uK|bf)ZtCj>de>0lgxjOwG}l&zaevSJZNRGv;$vPv`FFLy6;?F`rXf zW1~dxdys_Vn=zj=v%zCg%kj;a&zTXFIKCP4IS2HLgyWkrpEI*Tuc+ntX3Xcz2*)>L zK4*w;#(d5`UXh?Z$2Vg>XJ*53)B3o|&b&S5bM~>p=YU?3aC|f7b7nT!SJZNRGv;$<1SO7d z#(d5Jy&~cGX3XczY|txeIldY5IWvM1$2Vg>=YU?3aC|f7b7nT^6}8f<-O);~aTN9I zaFycU^?V1piyGm^{yVADXxzApwG?@4DmpsqHHRW{{#|EIia;J@VuQy`3FJX`C?SDt zN7-;h)Sf9$m=LMfn72t@s=eyY?)(|8m$G$H}p8NMF>p8V!!?xG8UFp{ZC9$sp5!>Y0 zaOM>WYUOPj^NJD@`W<>u zk(BQ)_DT0q`0YMB;l0hn@4a3;RnhS3zv>K9LLx@SOZP@^f?7Dza8IKCA|V_X^kBp= z+83^K+o{?S_x34W!5req zMPfo;U-Mt6zD%!Zy+9`qS$3(dLyl+vg{_eXrBWQ!i_0{2) z`%I=bC?R1j6B&EcI3v#TWTX%QqT5mu>X^(K{PkVKr91}%?;J-vct?6|Ur zztaYfMJ@GuAZDM*P(nie76?64W2RcR z?~ks8gs$W8_i^u!EDsphlh(IUpeO8uK%C6tiRZVbVOcV$TX ziUhS{WGjr|DM1Mdc@}I`yLs>`(YPCY_ZY76G5q#e%l4%ZmYmq)gs`ZJhe9ryuDQ$V9F(yfgP$AZy2x_U<1L3D$+73!csNVwNXJc=IS~{D7&{{1cC?Uc3OsNfB z;oTPM?&|*boX36Tr(Q~QZRo1*{+1`b2}(%l$`3ZQy31^kpccJNz0ye5w7(uL>)#$N zG}?u~d#p(b{UuoUc&PCz{Pt+7=VSQo=VVGyLPBF@AUtOFCaBfhD@sVnv(OHYtf>tW z)T(=7_U8xBGkcUhlG>nzgvQ{|a;=K8Gf0A3?6=egB_uR62sX63%WROKmY(gQul)Q? zZBRl&GlM{AP2Go}mW~|=&m&SBl#t-LNeN0wXl4*>Xmy{Ra}w0*ea>r%?}_@iuMFMa z!G`X*%myVSG%pQ=)=_;3YH4;J2;KV`K?w=XuLmHgrSUcpe(I&Yt8q0*{Cv{dApCZ0 zO6%S5d-muOB_te^^cZu%AFs{gQ6#8^zh}`U9M`d;+QR~LMo>bcw+;3W?1hM^+cA4z zu@_0eUe>!Ls8wGvo*|^?gOc$GKjV87HEk`w*L6FjeN{?OLc;HL|NjKFYT7e|)W&#P zey;Z>D5-y&KrduAYAsu*7J5A+C?SEf*@vJO?#+y#gaod)J_NNe#$*H~Brr^{e(B#lweBEq}jp%%ktN!`aFD z3cB>Zvd(kX_taq@Thgfw64Y|mvc8Tky#s4X@VL&a)_3TocW@=05|of|MzOwDFTEFR zZ-QFATkfo0eK%ctZ&v37>#OV1ySdVKZyO|>kE}1gOYa`ro1j+jzEZ8?Lf=i7-ka4q z!TRdD^lq+$c}2qc$ok^D^zN~}y`mO-Bqf}$t1qHU@2=_$UwuPedY{(bUXh@db9eQ1 zbm?7JQyV<4^N#gpcj+BtNv8xQB%JfCugXjBP}`fJ7JEGI`3fLtT0Y zSK97PP|JC|`ck^|uB$1*<2nafUwN0_F_v^nP(s3a&iazP^lr7i32OB|AI|XAH`Jx~ zV|7ljzPc{Gvny@)wn4%<$ok5=^zN~}32OE3E9bfDOXAYIk~$|?UtO2p-*hmqNH_;s zUwN0_J+`-3)MAg!PAEI8v=`3s)i>0o_huc;D-x=WT{mP%gdmsWWl)t#j#pQ+sgwDu+_A>oW-eY0J9FWA&864c_E zO$le*>YL`$d!;&eS6@e$-f5LbN(o9xI6qilV3*$IwKqX6_F+n}-$M@i@{>#N7);wK zK?w=xo$Jf~(mSp8CaC3XUwuzqdY{&mpu`!)`ewWI{;#y15|of|*0R0}FTM9{Z-QDp zPt`2Rvn9`(JkRkA$+H;OBvLMFsp>-oXR@;szS?ub^^lZhTB^>Eyz)$pHfn-eY+p)H zLc-OClmS|*u25!!1hrhp+*D6x}XsNnF z*%@TZ=@kiAG*XsnsX9iP4HDGy-|KNK?JKrW``9#Lkn{m!9!tLBX2nxKS)s+)%~*t%EIpf)Z8#4kM>`JLZv6 zf)WzW>h~zBZ2ZyQ1hx2nE+r^YW$vcOUGGG!y53EXyWYn*B`8tt@TSLI@0H9Wr357; zRI9w{ao2k@_a><2BYE7_dDB}?om9CXJ0tM^lZ2{&hjG`t9rq@vrP|?P z-1T0`DM5*9k~cl>dJpEoydvTH03LUh9iQ3Yv8bim;Z2Xb-YYrviW1c%Z+hJI9?U#a zN>D;V_0XFhcfJ2}Z-QF9#zL*hFz&{>oOKMsRW`d(0B37?WN@}vmD%RIHrD0rN=V=i z)>xwIl)*-<%h@HIq2=Q`r;P8;s;o2Hh;=!;UXgH)oN1|DZQbhYIsf9ZsD;0)ubiQ0 z?O2yH9Lr-A+TkjqwYMUir)ENZ<+_|*35nDOS{`!VVlTQbXWb^(9>R46I)f~n|?d!U9{t z+d=Qz-J75m&r?dcnu6aBhCQ(_nb7pxLGPkX+bKbb>dQB~Fr*6_I zK?w;}&2RecpsGq_Hb_vb_xVs=`0#en`(UfWe0V$P9kqF+-d>SV75ngZ(7Sf`CaBfB zuT&j9ydCsz(5kZ@-VUk`!GK|cF?D_rxBouSlpS zeRwsKqmz5~|rA-VSZwI}@HII}Ml#o!h`S5noyKDC* zsKq`^3HJNLhdf!R21u#O9vjhiN>D;V72m_#LGN(go1m8J#fP_ps;7_AKngn&+py@wRoO%m2UL?uu3hKJF3Ij_J0>zxOv&T7nU#V{nI?+4uTPP z68n8^sQK$}UsP^2+0~6{g9Nqwch4Uk`%VdZ<=@xMd#1m*FLqh~nqp}G$>oIo&&>!* z7Fp-^;=PBalrvVITJT7{ZIIaf8^0`$yyxt4j;9<2U^{p$YOQtXtYY3N=arw>{;G_i zN%@aO&L3z>&*A3_ui4%5SsCkIq`wjoo5tCkCQH$rM(eSwz7fAQF$1C^0fBPKx z_no)hR!rP$YI%Emg07EV1hv>BDM1N|&%Jm{vF)7~mdky1q09yeYR%m1s^Zmi&MW7> zWR_Y^uT0ce2I-0SPcH6W;H>hS7dYdP1SKT?z53MRV-HU$U*F>PjG*;Xml-K0KX-0< z?%vO3XOK2{ToUg*c}cOWuB#1oeWhNJpjPTt`R;$)K7s4~cef7D8qelYzbnJpTzf57 zdpmggKLYXgMtgTCA%SmIMf~F0KLq0Std4qYjz)vaW`)JnBt%+I^F|cmHpWd6n>UGasE(7P(p&ekhYuzwZ8uRB8A7q zH(y*ivyn>1`s%{1?iuz-z4^WiX9Um37Q0Ly_7h;sWBpCZ7@c}W35jiAy<+&>Kk6%s z=jP6Akf7FVUWJj`SIHM1Tcq@8*?QJ39P{Mn1C}m5QvY?%RVy1^B9)90>gm#BzSr-e z9pe(z()llwYqv{Kk`uPkz1q73+wt-{^OQsDU0D8exfPQ(rCzbMB(}QZo>4yyzW?=j z2D>&$P-~4{CXagD-87s{-5*_ol9MmreAG{Xnd_$aV{flWOn!FN(G{1TQa-xC^VMD3 zwLz~^E#9>ke)CcFMWgYTsRwlK-f(K@_s;g~yQ)U_tlhWlkHX)#IdL87PPqE{Kx{DO z%NQxn~Yf2x_rM8jXny%m~CKe?BznD-!)4bBMXpgwE#He4NDLibqPcaDx(Y`V;c+dn?~qH?eG@Af*X?JLoL zpPi^BBsBYOdu;ctxi>+r-d<5lGw!yZC1Gxj>o~Q+W0BD8yY#s0`EYN7S|f8kT)yzD zv&%c@^_Mm5T}m_?EplK?w=X*GrGuo+DyP|A+Ns8d2LEa==m3Djd~*f{=hN8#`=q& zkr34KZ(ltX@#K&93dB+~UupBY;#EVvjT$JMMN+AZG1zf6`YZG~Naqo|!iqU-|Q)fmnaR83{ox_FI@4 z>)x&AS(+J#ao005XRZ2ParL$9cYeJ5^6h7p3qJC+-V|w;)Fmh(;orW4tJ-ZOXhXBT zw#Qx1$tzo!Hx zBqnU9S)jY!_p_y?Q zMLi!*Y;-6gfj0FasD<;C5tQVFuVc@LQm@#KJ64|1zE%UpT8^UezMtCzPqriE2}sEgtr^=N^W zw|e)qv3CG1N=(-T-VKNtj_&{tc;@hgpcdBZB39k=_Tbgkmmk`qgalUlBJd6%A*h9S z03z^CrbP(}ym=9UcQOen-I^3QyY|!V2|`BsHK^4cqilea7v_- zv2!q6Uxk&IR}~Wv+LNnvx_zpSqiUhT8dgF@W8}&~A)W6Q1 z5tL~DJRILN59k#M&8vsw8|dmD?4A#LMXmJAA|BDWh;t?c zwT>E#rOF0ksVz!KXao;7s(A_GwFyBj{~jCL5k+qMTY~r=H^lto8``XT5(z!GgLOZ@ z{gpsX_-l^%=2q?KMNo?#rUWG<{LM#v_nO%tL9N~`_g5S7eY@v7-8P+Z-{j(4MfI;f z&sCt<4oXP)_t;E^1a0^`kNCblv6tH5aYi@ev zEq@ac-_RzWXlC4uZ-iyTF^QU>g!Xg=Hhs0Lm-`UZ@^4>>vlH~{g>~j=?z;E|IrEAHwfwC_d^?;Gl=!QS_!f9TuSguT;Wfnx`le{11J2EC&?{>B z?_<~1FN-}oJ|8b$^p@XDbbFD#`@-Ko68`?nDL2c;k^5CK$Te1bsYwY5J!8We^vtu- zIP&e~M4>ta;I7_4Px?)}S>a9KRZ&E@+<883v8FZs@>n(=_;^M{H z2|=xAw%IV)Sn(yVQWu-^@XE#tH#I3Cq31@h;gx`9`oB3c5cmA&;)I}s|0&LX z@H^!fA9PLwZO|+Ku08SB74dDY?2w>@M15{NckE42Ynkt^(>&$1sb#U#ni)X}34f0f z-|uDwB_w+H6$xtjdyM#gH?zTB^w$;fefxmtgM`1}i0|98^FdFj)zhmMT3g_Jgx?+$ zJs(QWM+@h?n04(s%^&=AYI)WvYZg3GN>D<=UvPMA_w2SeK`pi~C8*^uM*J-Cytg+& z2?>8)5#J#Xr#47X%U@T-cgPt*$&@AkQ|zI;=%PCh8|IOE+aTd@Gd#|F4&0ldmTh>X zuI_V;)Q+o#JJs_LjM@dpW1SC-)CobY`pkMJn2gkIN=RTl7J-pEA*h8BRRl)rHYFr5 z9*e+8oeKTUIp*GOt{>pq98gfwN^*d!VH4-t8da>IBY~RULxN29HH8|2&ma7xEN`Yz;WCSIyPT*`=)gBnIuSmE$fwN^*hahV? zTSzTeCvdi`Y7%4wC9Y23Y+2PF7|<&cu1?@=S=AxPY|txe@fu4q?_0=(ZzJ=*L`J@B zAiKXs2?_u9-K=T_B9N<}5XjFD`)&DdK0efYy=snTnDr@FKk64fQ~a5)y1vQYobKzu#RhWW}mNUZ`(Zp97wo{)Eqg&zdXZIrmj{@N@=I@uWiu zkIU<=H$g2|#B;W+>cnL>ToKP1vZ{9%D&jf!Rh8_r`-5JQpbb~VbKb40zGXHx-gLfZ zeOy<>bB3(y-Sx4-J|yp(37hUsdmJK(AawuO?g( z&$+Lveb>h;YW40bSHyGft7^4{ig?a_RlU0by>bn`ns7xt=f0};T_3Ng#U4qoD_6vG z?yKtEg^GC2eN`p9K3*iwE?I zge&5?GM;MR_3?^YOU<|>TSmAdo-5<2x?8A-=gN4heb>h;*UhW7ToKQe@l@}w z55en-ge&5?GM;MRWnPh>7SC+jyRL}m%6O{07AoSoGM?()4d|6?=+%TP;<+-OYTxzo zidyW$)GPM8E8;o#RrT%$^ooQl;<+-OYTxzoidwFS=gN4hgO?GMxFVh_3P#(tQ9R#Km5}h;vnBs_Ehqn7>vzq_T>YsgC^20V zuI1zvtEx8jA*khAPF|&|f>TCN;#y8#XU>|o+JIh>a4jdVIaS9fv%z+xT4TGpq%Btu zba!oWEhn#1Rd=WDT25Yzs)AEygA&(r@+wu8nxr*$q~112xR#SwsjAwP+2FBKt)EZ# z$fw+DT_rq&Y^`fKd6lY4O#^yG!nK^dN>$aSK3-AFwVb?4RRyPvpv1MDyh>H2rUAVo z;aW~!rK)OEW`li2E!T4LDpeJnGJ+DdPMJ--qRb?h= zy24S*m4I;9hWM%PTGw*&{ir%d_OSckNxplpvP4ye+T61`-F4daq711fQeuP0O$k?j zGNGDCElNnZ5|nML@{x}2>Q5$~yXM4%NVUeit!g=$h%N7qI2^lVZ*;8XuH|IH?VyAN zd!f-#I|>tS2MKDqmQ&J>K)4;0kkA3Uy&mqtu&#~cZuhM5Y`T_{YdWcdlln?`ZI_^g zgvPOOEp$ifaS3XcB)YOOIu}HX18 zC8M@$IeC?;N=*Z{oP=vRd0nfjO_^70IkkA6(w2u>PFmNh%23<2oV-d^rKSPBBH>z2 zUe~H>Qy;IW#U4q$axEvXYgOB+?OIM=f2sykAFoKT7hKE9>sr+k%Dm!nUCYVqT2*T5 zV}r*f;aW~!*Q#n$W`hK^*z0M_UCYVqTGe(6wVb@JRSl*-UXh?Z*K+c@R`rTB;&Lo; zji~y#uI1!)ttvJ3vBBe#a4jdVYgM(WPs^#*`+T^Tlh?JXWK_DAlUJ##)a0i{cixq@ zgAx+1<>Ym(sy1aUCqb>=edStCUe~GuQ0ZDuUZtv1(|}%)a4jdVYgM(Wk5|-UkIdfk zdUoepPF~llQqzE5k#H?1uWMDcsgGCGaxEuUd{>R3jBqU{uWMD8sB|qSuUJ*JsgGCG zaxEvXYgMVK55Y4?!nK@2#rM5m%Df^$EuPu5cU{ZL>sr+eDqYLTt5j8L8qg~euI1!) zt*SQl@rqjP!_+JGyK6alU8_n>1A0ZmwVb@JRn?|GUQx@noV>181*eRl#I>Bfu2rR` z0lgyOT25Zqs%leagJ+OhJWt^rKvSBIce>_s+jBL)$9D`hR(ubU()#`W>_jag;TUSH z_%5&XzCE!~6V%cwJglAlZ%R-?!ZFlX@x2d0Eyqw}#rHmhW2mv>dx)WWm8!^TMmV}! zOB_Ru72o}4Vt{s#a11q8e9vs~Sk&_0>-TeMU$KRbp~i~u1A0ZmG1OS`y^mMaatt+A ze9s6<97By2-v{)Hgkz|&;(KO;eMK$DP-DgSjG)9Z)L8L-K(9zRh8iorXEx{+wRnw% zh+@n4pdzG>D2D6D_o9FMe)Mm}4a09mPBmw6w9R36FG+p~hXtk~7F& zug2S6gj??RIEET`8B_1l1|>W$ueaU=wH!l@yNqQv97Bz}jI|v@^_o+$Pk)zz5sqGw zpq68(ahI{o29N6)YTRY4j}0D|gkz|2m$A$S32OCjxnrntm$48-^_o)=(rjd4%W1<= z*P3t)HSRLj$17^}?kmSo<1S+%hUzt^BBTR)<)~{-IEET`8PnC?s~yy0kEDcSsBxFE z5JUBvQ?buJUXftGIffc{8OywKY_>kGW2kYLu|76W3%;f9Yc+~jP7tQP-Mq3^ndD*2gPq_3kUjP~$FRA%+@v85__mM_p^eG1R!rSRb#b#U4qo z68COBS91(C?lLx@S0o%mjk}EX@rqiGp~hXtGQu&`xXW0Gp~hXt`gr9?YpvxNYTRY4 z55en-gkz|2m$A$%64c_EO?%fd)VRx7h@r+^#s>7tQP-Mq3^ndD*2gPqu@6(P*zb;^ zdd;Z_>4095a11r>GSlrWnAZpcekFzH$uJ+TP~}{)X|Y9=qVJ2**%OI5tcPT2608 zpyljE?*>%&^f1~a!ZB3a2s;Cf^-n^uP02mzeaY&vHhjAh+Yw@@aeo~37sjiWqpP(9 z?Fe7H#F4rWfzd9+P~-kM8R6(^Eg|6;YTO?uBOF7G`{Rr{h8p+B8Ra#dwu4%Zp?Y1b z2x%XJ$0FevYTO@ZG_^s3T5MBFP(s2n)VM!RW`hK^diRxMsBwRsQO8idN>zk(z?PG6 z3^neLlX=CKQ;X**ZMkEpaetgq$56dWRfKdvuShtC8u!QP;}x~oBdJ%8p~n4jMjb=- z`ctvbK3kCWLTK`r)r+H%KGy{=V+bks3a zuRj(0?Bf*)+H(xm>srMLGp~4D$57+`IDKsJxFj4yjr-$dHb_vb_xW%P)$3YC5NA4u z>Q$;Dq%(P>w67>3;TWpdwThPZ@rqi#`^qs?uWJ=~o9P&;SE-7S4(JsL$56elRkU^MtD>cS`ifePp?Y1b2x%XJEhM3xZ^F7((b7J>OD&$+wB?SWdR?nn-On6D z^(s{n(gD39;TWpdwThPZ@rqjP!_+JGyJM(vf1KOdBPl@%3CB>qu2r=3XT1q(Ifm+W ztszlI^ zzCZNlKOvMq8ou~d?6VI+Ev&+e)CMIalyMrq7xw$cQ|$o z)vHwRm7Ut4L|LXGmg+sR>1|3-LP8m*A(ra>v3nEL@{!{Exr|^7m1SDSywoOb_qIVo z8K-5;OYPHF)Kd0o8S_#zf)Zt!hFGfi#2(Bm63RFYu~hGm-MbysQub+xrFyUIl%Pae zrXiNc% zUJ;InnsAmT3B(Eu+D;;hiB}{LQPep{gf}6mg&3;{$58E+^K3oJ*k6w&9B~l46@i$r zcLA^C%L$R%KukCxsD)^+Y#=7wp@an6lzh+7QeJ9Ub1J4<@Eq{m^d~%``m8DYG^{KY zIn^1&7bz`DcwAm@y$Nb5J2R|O6A3 z29K*O)37pCgtU(h9+!kNPQ#j0(bCKY32OCjxw0@rEL9Q2!ZB2@ITaxt&?^$kI1Ot~ zMN9j5MXla_rM%P-OI38Qa17OJPDMxu^ooQsPD3nJ(b7I%QHwp2URTO84Y5>3NDIeM zz2;QxvyWFKcy5#j8Dgo5;bmU&xXLmOu~bD!``F-dNhsqq#8MS4&1{fJw9xBm%avss z)|`rv7LK8M&8gUDAFoKzo^mb2np1JY%qt#OS*9VDst9Qx8$2!vWt@gss-mTt4HDGq zeLj?h8P=SNAQs9p4QozCNC)(agfdRUnp4rzK3-9)cV8)cF|0Wic`KA<8rGbOkPhe- z31ysyHK(GbeY~O;dnCO|+`IK$OR zdl{je%CP2CJg`v4X;^bATH41eYAMS!tT`1S?L*Kj63RFYYfeQ=Gp|Tci)S`%x$+&u znp3g5LRqF^&8Z0KfL@VM#%Wk{Dq7mdD{8S1Q?JfP;cs+$hy&t z3^@&n#B@zKh8puy`w-M}3^nGZW&|aUp~k$_#CC75NK9AmQp`)uY_Nr?)+4KU2B`JB zdY3J4G{z*#861vzsZGaFy-HQ&G_yg8vP_3#UaGXlj?~)*31yrP$Gp_c29K3${a_W3 ze6zQMt#u4F=A{nk6$xdW4#&LIK3-AFG1Qosnh}&J%XB#Ar4Hy731yrP$Gp_c2K$Oy z%03;Ad8rveiLy+GV_xcjUXf77>2Spc=A~v{k)Rgal=dzq zB$RPF8uL;!8ziXJyRVdmIU4g)n~tG+U8@M`fGsDXjMLGWmzsISmQ#!8DQ&qjBu5=f zRdlcE7^>H`ijWTI6$xdWj>f#yK3-9aJ(7B*EYs1Lm)dj;)$3ZtKKpn@g1w+T$kCXW znt8?JD$8^<=B4(r!Q+xp#_4FxOU-PMpcZ>QZMkEpF)y`n4Atve#XkFZMS}JmLydW< z)l8;)5AwLmG98V1seNqlxFnQuIvVp*`?Q=|z0ZeZs4*|Ka11r(rONkSV+kcB97BzH zsaeZOP^))eIffeZQVYjWV_xcjUXgGNHRh%E@rqjPk@PBYJL=h;W2iANbwIC3DC6|@ zn3vkeD{4808uL;!!ZFmCms&W68uL>7cttJ8P-9+dAA)C)gkz{NFE#Uu1hsf()82Iq zHRh!jj-kf9)B(LB;TUSnOYP$owb+NLSL}CXncg1rQU~;kgkz{NFSU{=jhJIR$FWIu*FU-cUrJf#NUN~|8C|}GyV6* zr{>Z*pL6@K2V!KCuXQLHhbSuI*^jOfh#U7kAt53iw634;6T!xISG->~wqEIdfjI0h z-{?>>4pCIZJ~td8PO-1aCniLsqgJEgcFeiPJknk4f>(!4Z1(39!rgTdQB=fXyHvYpzqaI22@&a_wa9v(2{ukV?Jb>&*U!8z z*qHJ7;T=lGA&QFl>P2@1;wS$-I3Xe(v`&0@+hF6fKYUX*R{F&+0&)Bu2X`nLhbSVk z?Qa5c*X{c!M5Ke(il?0tY^>OxB^$p!@cBUOf613Sl#D|Z6>bLD+xci%D)Gk07eAtD{L zp4{M>U}MJI7s;-9kdSL`^{kEzVo-0jWg~#AQ0!>^hleMafqTK z-j2J(v?jC@BGN%?@q^wCHn!euST@dl;?Q8@w`iL|`V95SV3*ViqN0rLoyki;{5&&zww* z&Bzi0v!zkY21Q`j*P>(`!ZSb-m{}$SW__cW)oScLd~EjGqGTMxGg%RsAtwZ8uO;T% zA}|YYQ8EtU8Mz3|^b-QJ@Di&G5m-&MC>e+F%0dKIED3?tL>X5vrB+2EuqtX%Lc&ib zJ-hrw5`mRhLQo5z#{*ajfrbM7Kl0C*}p}}I7Cqq?|ka-fw*<*-U$)u zp!L9K&j~hm{O(_5V~sf)Ew_A)n|EtbG7eEx#M#SC2*j6O*e)R=9kia_@tR;`g;|fv z#(mpY)svQ$NBuhbSsyp9`9S_|2@< z6C%<<>(*y}8*FSi|A=h-^rN2dj4+@fS0qNs@VkN$ihc3Jxa2@&a_wcp(@1RDn) zccyIYJ8`E#eCq!BTa=7L6cw?}zIz4Y$va+cl8C>9)`k22C)oJVYhRR&_s_jwAa*RD zX;Lx{QB*`Z??Hk1{>u*}M5Ke(_fB{-*f{7G&-y-oZ$&JB#Jx>Q#vzJ|*zb(Pf{mlD zxg{YY9kh1Ye2&uh`I;|Gl#LfYdqf~MT5Ecfl5vQlBBp-t*g&)wKP4d|9kh0uZ|-2@ zge^Lng&+Ucae>(7fiE>F8HXq;;_WF_hV)(QE|d_F4qC&1e}AxX%<>J{xbWvyZuqo+ z-(OHN4pCIZV-Hms(tA9%QbI&JXw^sZ2%_`xuZr0HvCD@k8HXrlBSyy~tX2PAUTxB7 zz^jsy+6D-FC;}}Xm#`LkT?Bf!O-XG7gnL>9&R{~IcQ?V+Gu&v@S4n5_Q`(e_L->jj zfh#c~aFq<>E)apMy-mqDgs*%NxT6vRSNkyTW)Zk++mwt$_zo6)*A8Qh5mApm zPu%fpo04$|k3=Fc!gWYs^clwJDxw}mzqs}XI+Tn4khCd zelm!dD?V{{*>Jstz|&wDPdgEKs&yzChwu|l1fHA;fv4Iqp4uYtbnZ|x4&f)Y2+RNy z0#D~*%sxb5meHYP9KtgW5tzv&1ZEk-m_>=eY^g)ZID}_TA}}LM2+Wp-F&h+tSzm{e zaR|=rW(v=~`=#jjFzSZ1T@Vyl;nZb~c&#?Mas^3y+eV zFkKPfx#5J)b8GG}Y5iiTNy5Ktt?QrJH1zJFlUiD_Z2s%7cfP&mdXql%`>mUl&p zcyW_sI}4w?#H3e#b6P@}uC;!(W;58h_}W8d<2u#lJnhlDhDMh>yGcn-n68LV%{Zd7 z#<`uL2k*QhAxzg=!?$c4Y<%@n$Kdu^@~fS7KfmatiR)h5q$DRySHzB|9n?8s%UvgJ zeBFHsVY=3O+ zU3VM`Hh%HMv$9csW~a{Hx4ks9)5-IhN~wEW*U zZ&8vHrYquW?=IchbMdbaow?~Y31Pa{(wPf3)Z?;IY_ddWqx(KKw9y=&Yf+LDrYqw0 zU(egQV|4CGm+rQ6LYS_#bd?7ix;ka!jCbE_pT6(Zq3_(XTZ@vMFkKOkKm51$PcHuA z&{sP9B!uZ&>-uYM2sSR5e?8ea=9=f)XY4d%=-!9E+@d5WOjpGGi~PF1==WY2x@Gu) zgfLxeX+#J%bSKNkRlFkKOo?mMCV@7=c>y6*#DO9<1omPY7cLnEtf zd}!9!+Fw~~<)L-A`&x^VoG=}U-*4Ui>&NyV(o-QJOxId^(hU3B)f2+)D2CcE{eGcI zdh)a=$qCaHv1IGs^4ZU|CQZEmn+ajM*80(LD+L?>H(?9en113#<@AjvPWtNBC$=cb z3DXtv`K{+K*E@Qbp)3B75~gddyN){l2Dd{q1ljof*54kzWzUs|e)Rf@ElNn-BEob< zEcCmfVwtDT9D3n_l%SS893AVc1%EeEeDLW#hW1$FM7O*v$%(ob^tSZPxtm)Y^2wne zKlF`+FkNd+{pKs-NV|OSQ)56!D-Hn>xYEK*5^xoqW z!gQ^rvstZjW2-CIJX__n8Mm55DuJHOhmt3j2 zLyMA}FkKPXF8pTmx5cMNX8d@MgfLxeUH9i-1smJ1=3TAcd*7U`;d36k^8VAm)S@IO zOjpDcdSkc3H4BW)r8jsa{JYk=Q*#Bkqk0-Vw8Fxz^?$JcmEWDULyMA}FkKNJynmV2 zcTb)B%Ap@^oe-vLEj{7dwoyGf7x>#st^aIs%axaWW^+F|yONwRT@m}dvqtNi4{tH@ zwP{5{n69<9`_g>jNIyPxQT5f~AN@${qtCuH^7!{QX;G3BrYqtn-&?1A_I|Jh+5 zO9<1omc4O1d=#zjZrr%F*UR%v|NZJ~wk<~wx5ThNC?xlmd~8qp(nO% zJo?S;T3+OxIez%56hWY}xQ!;o!!#BbqyS zhTN6pgz1V{;wSsIe*2MgMt=5zXA{D7t#!gW8-ye6xWT2eapRQzTW_7Y!t})!{%wr1aKKYf{1?@S2OwU$Q&w?j{C*;sagLtB%-_Oa<7*>lvZiLN9kOjpEj zesx6ahl|ZKeXdDYB!uZ&>jpi?ZNsCU)*pX4y0zL4uZ`Su*ms(g&pcw)!nT1VXb z^2iDw+CL#o*IK7+v01RO-jo$(IbpgYh88=a_2LWnjVwB2 z-Gne*Yx&9VcK9jOXzai4H(D?L^rVr8mS4)N)UG5aOjm@Tm^ZHW@`#_HB>cP9T0+lp z+o;|e_^JG%i|-lnQ<{>TFg-@x`GsYsizrF>cdZ56!;OZ$n&;}hr^~A_8;UI)&WY%u z2)F!?bL=zy!R41~^H}g|7`-mf+`GSg?$qh(-8LmTVH-LhB76pKcx&zHI)e#;-YszT zi11ai;~OhZ*HzM{BqwY`*OdrgiI<=D6JLo5fvY4uG2J7c(dr8bUG2ZRb+hSnPr9Ow z`y+T#9~alL2;Wg}KeC$dsDz*v?q(6bYxn-vR=#W7l;ni%={^_Xk>Q=oXN_oNNC@1u z;i>F)c!kkuc=Y+lsec-|{R7XoFSPle{Yk7z|*g~YJR>{inU_W` znzchhV7Ao6+)jjNeGkv^x#^nqbtuUR+t55w#D6ujyzdKJPk-R_FC_$KeND`2MR@jl z=|+>LYxdfqBqwY`cYp}bkZ*kULnD5>Mgp_fCT8a%JPTiK(mzK029J`Qunpb&B0ST7 z<$d!_*GxYlFbi*Dl_A2bi8p^R=X9+mI+WyuZD{==!Yh_{Z@A=2tymHQtBIzc%D%3& zDiYyU(a%r##g$qWbtuUR+o*`;wDS7vmMe{D<&_YoYb~t$WFxHZj^B1ftGf;*IbmAs zK@na-9=X)zBU(Ww1Xg!VKb74MJ%vPgmAc`}OHbD-wL?ix*hWS8Ilk?mUmMXAG$Bma zT3Ch4hM(h$JUYj8J=Z&wkia@xgje)GopADqR`dx$Exb(##Qf!kw=OqbZw)$>q_tP+dG_m*2;djPf1RguC6P;DOzpbEmqc>qJ%JAYvC=GTJE<|@4frp z%6c2sp(H0v>;0984fMuq`Q>j|S#P`&0&k<5o-4Q=)m`hiYI`sB_7!@o)}bUPY@;I1 z(wn;*cW8|0&0Rv6uC?&iP+s}%;IB9P)5>}~*r6mROzVB32)}{+*D^o!8_0yf+rg%v z{BB1z!u?KfIsbC@G{5ESP?8h2Q4yXiY;^T2D{JnM5T^Kty%==$|rp|XxRdsb$olxD^tZB(;AFYW>Ni{*bOfaH&{l(4NZ~u?E zjv$>&Ni-8W7`1$JO5^s3S|(ajO^`;M69glp3(x$Ckx@rT)Y4{Xwu3V(EH6Y~-#qf` z8bn_c&fR%QH9;L^f~&xl&op6#*Ab+1DXz-=C$13i$zY{9>9u7w^zCa&H9@*eFjBqx zX68s1^pyc$HqT^>L+LAsndz=->)Gk>kQbkUuTkZ5>OqVLG2 zVy?l@TkOC*0GFMh1oH!^1N$DF4rZ>w5x2I(7k}p0=zpn{{GR0+oVCNTmTRCTN{GG^ zEa8JkNA1>ZF#Fo%?%?(Hr-u9AJ1}V6v$#*rG`@QU$ceFX$HXYA4ei=Fr ze(KVw(|T=Y*A1MSXh}6ex=d_+*CkP}OSYeV?16I}K{}T@!ic`;w`hL`G_Wv$g;Rw>XRHFySnvUUO>L>go+sEvY6*mx=3J z9u*C3y5a1N`flL}(z(>=jfR+xEqWdV9V>U}7d`OzFZIpdZqk7XlOssyQaheI$aDq;sjgujpes z?%4Je=!kdSEBfoSU+Y)StWC9~njl>!PJ4crXyJQ5)c+cEa|G#J>V-4+GaY;O8wwpG zzTGK$qWw4Z_pRueYDqOgx=i%CZ_DV4D_7LNdj1iPAe~Ef_;-!z*!A*}(DBK@&7w^w ze^Ebw@X@K3R1>7j#7moO9R1m9dHwtUI^GeabE%+dE7S4Io7X_c_s!Rjg6lu6KktZ> zQZ1<_NSBFiCaela9lWIew=QQmf^;tR+HJoCTvtBsaRYSR7Jm|6+Vze4W3N6Z)skw0 zbeS0W#2ewG+dos^?7s6HK{}V3(|eWa`129!_#k~f?0nLD^<6$bFV&K2f^?a<{rqRb zL+^U4e!X{xID&L8HTckZreo=&w?IeJWOn$(h{g4L9WXT2l4^o@ob?p!eKs>vtS@RjMV`1nDwy^*Of%8}4~&eV@ZeJA!mB_34-!O~-o+sbgw# zU9j-{G4)?ugtuQvNi{*bOq|_#M)9cY>gw<38#aXCbuNYL65CNBO4sjla!yoAs)?LN zo_=y&e00C<@>(fT%B4_4`@PcgxZ?pUXJsv~l&~gB@Ve5w@d4>yv$Ec;5d7az58bEyY= zuQDB#nISoUlgHX}X3&yqf^=o}NsbtEe_PHzO7J?D!c1g3Dl=TNXzF)uvl*^ZQcaMq z%%aK5zni(u)>*+%F3C}{C?Y-Y~`$! zR1>5tt8*G{(z7O8oht7)NVriQyEC3u}nVdrEzDm${YX7yz? z*^aDIQcaMq?E2CH!^hWTyS@s+|IMYa1GL{OJInOk%Wtd6c9xZrYJzlS_nK~he|=51 zd#w=s-(2d1Ge+9)l^t^W#`}-gaEGiV)dcCvEW4jo+7QGHaqj@PBhDSQhqs#bQY>IqHR)%wnmOR1>5tR#Dn)$E7uy zRa7DPzq!=uKiy=%S1hk|P~+EXXnAQ#H9@*e+|cThbi!F5)Xau;rv$HasZXB0*>qGa z$aKTM-l(AksU_6}>57$_e*F4RHMCNd;B_vw=Fdr{qhblCFWvE54J~0UsU}EQtnKvK z`&ZY{+E#+sxfCpK(^0YL)6JT$uE{L=N=Y?Ay5coRFC6<<&9-H)L51M|=2Gw=*zfS2 zz;=dbBK>N>dhIjMM5UyfAYCTl{Yc@HX`gvNDg^&GmkOFrv)?NomJ~jj_Vlo5Ni{)w z9RZ&Vi9iWn=Tg#+zT{K)@%H!Y9)nGn^x2_6cR) z1p%K-3ZG1S%%ZNOnxGEMyCC3`N#T=ekC{5s|B_iWlsO*+d@?C~GVQS%L|Rf!PzTlz z5b(*Q@X55tisJ}b4MJH5LBJ=I!Y9L3Ez*)|f;zAcf`CsZg-?bnrz2!l3uQeA0iR3? zpA1*$NK2{->cDyq0zR1(J{j%+93iW7D0>O&c&T#=pA2^yk(N{w)Pa2o2>4`D_++?~ zafIwLLfKz|fKMicPo@SwnMg~j3F^T93Iu#IDSR^AkvT$kOQGx&LBJ=I!Y9LBU!*0~ z1a)Aa2m(Ht6h0a5EFB@czEJk4AmEcp;ghMs?lsbqYJxhj-vt4mObVY&4R*+mklkx2 zduTR(voU|I$#fifKMiYPo@SIq$9+-3&j=%0iR3)pG*y`)JRLJ3F?4d3j#iw z1U{J>Si+7FD>W3G8U%bY34Ag&u(l&DsV1lc_BjanWD@vfYT%P`gjn05_!&UJClkXb zQvR60zR1-KA9SLCLAGNgHZe>AmEdU;ghL>PbSimYJxi8VF3Z3ObI@j z8u(-!A>I$_C}uvHGEsz2CMPN-)xgqeKbus)gb;gbw&* zLil9baU^OSMRarSB_+%K(;L2GksV1nSOfX^s zp9~`=jv$>&VWqZzs_XzF_+%KB;SQiuQcaL96Y$AI@X6G}C*ugxxs*hm&{vEu!6(D$ zQlur-1nKhLhY>9JWEjD6ghZFPhqKyNc4QHJGK`XOM^-7RCa9xKFcJr!3?p%lAe~EL z2WbCP*;z*L$uQc-on@t@njl>!7*T{zh7m7jwicDAn8^X3Og(%u^Z`@|UguKqAlUEB zXDMfkz$e3O5qc&nCDjD!GSTtA(sR9^7#-D>x(E9WA5&`FVOkKhyeXWIQ@FgoVp93K z&(zz4ao1mg=i`Re-!=3AaoqfF!GONqV@ln#$As{-u^ZdLl?mD|ZX88E<)bB5hNj%yA5)hxXn^NioV)tu02WNcq zsY&g*;OcOrw-?%VpHs(%Z4a4m#P6q{3u4i6Nogk#J#Oe2JTRa|!dmV7?xo?7TN~T; zK~Iecr~Lhm5l?S65X7t>zb-WgF>lv4!J2n=GpUVVJtJ)QQ5(BnwZY)aBcQ5@f9Ere06;Bqg7)~ zYW)Ab5cEE^e7)h@3j_435j!6;AH)|oc8QM!v0}4>i%&i>-iV$Pt_hAFUcSbic?!=33G_g0qa?^iNeQFGq%cZiK6@n4%Q2rl66j?R z7$reAN=g_dCWTQF^Z6#h=luyh-z0D+L12^w*(hoFd-9DYg;5f74k5ug1*60Wj1uJa z^*>}nZC^aKotxTxRiqT>t5Y$acukVyi8{)&&(w2<2FZ=1qoqfm+3?P($0T>0Gc}mf z`>kS|RRipreq+pR2?<_fqyNYtBYrz>V)4)^7@_BN>-H~BSQxN{r3K5BW3M4ofpk9&vzx5!!@zVQ(OC0Q$yt(PpY>(4I? z5}B_+^get~BcAwSNH7kyA;H?AEhS#Rjkd|W3j!^VvzFJQG|XCFLd)%%Z5@j_-L>2Z zw7i7>HYv0`*k$8hc8!+vNiw25Goa;0pyl!K&Gt4av?oBz?HVl)W$cF5@>16FcmgD| zmWSIdSzy;_c__~yh}*_IUHoJ8RnfM$eiZ9z7i8YX%qnHZtn>(o12&i$d<$aUAJbwz zKZacPgaq@=<=%jJBxoM@`{z~B4_~|+$jOI9PADX7J!{KxP$;}u^JrWPqS2hOf#iZG zlC!Nng3-P#eJ8#dwYp@FEo03j*34z?Y1qy??GbMT9Z&E6My%%;q*kHS3hn5;=#z#T z5RJcCW_iYJEwg>~n=M z_ot7$JE(-7R=_*9wmvo<_}W#`%*ppVLZ$TnBWHWTDe(l5;R3RFaP${9Y_ZhhR>(=u2Ej#I5 z)4Lfxa9Ixa6zbZ8poE+C;{2BBK)X)xN);XT*PoHQ4zM5*Q(gJW+`}=OEhS z&hZ&s@Z(2z0)Yg2Hj&e330DV>E3QO^!s;)k*OJ(>(Q><6IU#5J5}AEK{Qkn=;<31c zE${u<5xT0$oDbstrq>pC#T{(6#mj+~C?Tr>h}*OEW4l{Fa)e6BS_0y+9)A|kKsyS< z-?w)>upJnYi4rf%8*k88xN~ed?qnb*WD_~bnw)`s!@BjO*LlYWCA56x0WUa0cK~vp z7q!~vx&A?Gw0zQ>If0fap?e8@#rK@y!BFVvf9W%hP$@Z=3>}BvHO|`6@`(9?mMDSM z(^gTgriB8>6I+h)W#fr`g*lgVmq}rK#kwcLDCzW6&;_;HuIEU%TT((!uVb`NJZ464 z3|hX&e=l@|O38YTTCGkV3NAyfT3tDTdy$0w&Rv)ivKs(#V76y?_>XChP$}6$uUmUE7hH#)?8E~uOPM?8Z|mjq{^<>Ov@)$J^mkheR4z`Pr9<;1+} z2$j-(Dc)0<&wVJZ?I7g_I^jlCU z99?|hYPDVcYWN!}Ep%_ckoy7RtB)529np@n$L}9=F3iTRd(VXQE{OWh6HLeUKRy)8 z^I`8YAkCc<#~FK_^KYThZrWMFZqV_@_&AoC!QL7`g6{y3rwhcAV51^?x9#L*vCN!y z9-IXFFO=C1#HGy+Dveu?_jzxzx+FGoDAsS)K5^;$4;wM0<-(HKuk>Ho?w>ogMd2>nW5IpDK{P3ZjzT^n!?oSD^$UwjYS(|$x)$WHk z(tH5)MrsWUg;PchsXY&U^=j>dMJ-W6pBua*zVDybSDWnDC{{wHw1&vVnf`y)S3mtW zDAp1sysh^6h~=g3=&NasQ%9(jZ~6SpN?rNIyRnuip|&CHkL5cT=`U$Fy$ijymHrX0 zTBtQ#=ZAY9-dZhDLi}^M9|tynrFIZ{chiR1MI}^9XCmZAEv+jahFYC=)xq=~&>+1lIuo5aIK0pw6b=)oPh~B-S+Y`=q*1l595^w9NTVQvv>-3YI1*wGU zE)-6WhuNIidb^b+{V$dBzKlOQZd^PAeO2FVMo~+Y@a_1#~=?}l)g=%P#F3ZB(ZYRI?@s)#6m)? zF4}5w@c{Jh2a|ST+`#&ZaRc%1G74bpRXGYU^T)4qk1&0!l@cYyQw$v|-tAjF2EE&* zZUR@F3ZYWE?jlcS>;DvYL#^Ivx-C7vMsP(|Lj1|lAzo)ksFZl4LG)~Li}h~HR^y%b zL;FfBND%!`+r#eQt?PG;wL}T6Exw>U_Z1r@?It{0QbMJ?cd*3|7ZeXiU)}e}sG^oA z;oEW6F)e~t=&ShTCV>(vC7yJ&15ugW-yUd*_};60mL0DeTZ~Yvy$h$iS}CD>BHZ(t z|FV|1yx_Ky)=H(+qf;nscT0ck-L8$-l(a+%zrULJ!b9;snBjWf)k{5%ZWrb~MO*fN zDei-{cH_QB##*BPt6n2y{La}vSP#9sYV4|_wpJnyq1F&j)W_{CHt`%HSX!cl#4K<> zmcDmOabNWAl5Slcp;Efb#G69i>kzC!bgAc$3yWH!ghV!=M9Gv;DT#|< zr~mh1Puug+r1N&_hjG0tJ{b_-7f-f3xJSE%B`wk3Ro%#rUi7DplJyryj!-G@Z-2bc zoy8jT)rre?ENY1oz8xRjyI=4&`s&fT8IDjXiRqvnh!5tGpQ4sX6sRf+F#hFP#Vt{* zYcBn*R%@k%S^$N@X0H^?Hu&|C^-4;plzIx0XZgYq>)ip%_I9xeCA>9p)_E`69o%ib zD;%Lxw57P?EWcqx{E4(VD9D15dqN>i9h zgS63TtHEY-wNfeRHxRVZ7*}JQP)n4MCn|*ihcusA|ySLmRJh5qD_2ld@uj*y5V2-z)_WWSThZmBBwLv~~( zt-BJkw@VO}fgQ-cf?cTlt5~Ic%V`I4T){5X*rp@IW`K^{v*_!F>(@C#r6ei~;?Q*w zUKgWRLhL~hvfnMqjx~|JZ&hZE*aqqsb%a;|&_SOo`-+}O?H`rW8scpWu(;S)u)xf# zOb;EbE|(P~Rv2{9s^i=aE6))sB^EM>onF5=uE*T|ecw4QqNs#K_(6!}6^k8}h~?#K z2v6!d>rSmAM~I~d9kd+TS0~PWMJ+FvL8UdsX(wc&u&;(ACr3;4f5kHa9V_p?G~Nb% z_5GLA9idXb<&psrXo(UUSH+isGK>D*rrXA1lP6-)yEZwmK}qYbgm@Fs4%(XRE7+bz zB~(glh`AlMCi@DuXP_lYh+hjjmh|Xh56qZy76FBNnY5XE3$(YLRyRVl3@&K1F`V_(6_3$#QD@f1Rbcpx32QoiMR zzRxqezY%DO65`*54)G4g;_FMqJ6M&`C>}`l+&MzLk9j=uSA67b$2woQBUDN}-XJ7y;4-$9kVpdv@jA!iH%`Rs?Aqi!+a;~L65{cO z4%)NqE7-T{r*@gET0^`u6ZS0o3id6d#FcCc{a=Z_KnLwv&h4;o9idXRXR}x#h>3ge zR+^8w{n5*pnWdYTC?OeQAS7-Oi|0R)7=mk)i?L`7(h(9#feyw6*;kB~X=_zVYls~g zEJyYgEJ@4Z%pz5Z5VvRLP0+4|6$>45 z7Qhkw-&_iGentQUqWMLRL`L_S`H+t*?JL~DN`5MQeMg^J%R9)dTrE+;w}TciM+q$A z|BuMqWED3sO2+%4gi6WzhVnhnPeH_5g8Lt{uMmT* z%Emx>_lr5p0V=TFYVI23jkX(u^dFK^ED&uy0+Cuo6BC>9k+g6#L)~zA~ZY z2$k}gPOtr^bh$ARa)9cYOXn)PIJNhym#^7*LrkDUKVw1yUgv=bwULB?951ms|@i43^0O3k(EekahAt%FPEs;}VRVPN^XDDScNLMQ*G&{*+kk)e8g+;BEO8Lx8+JSsNU>6p( zL*QG#LJsIqP-aUP88_h{{*=CZT2!hrr?;xzzqLygyYHckBX`=*Io+DHW zzFvDiU;{x1JgKED21!q9r9=te4#XhiEC%Tam6Fqk&>?3OOIiY7xb+WDqN#54g_p7z zWP_F{p}BY#gABNG!e*m?x6%%kLUh397+7Yg6>T*3E^IbN0V*X*_`E*aXna0kvpGVg zBp()WoOY9!S%xXIK(#~(&AGL>L7c@Pc~Y;^KXN)V)*4z2GC$8*(h^6kJLid(BPvtM zVvr3=ASz?}c+L;e8tX&YCuj#EKXDd=ENO`nhzJ?Y9ke?$%E(XUzf?-jl7cw>nQ~U~ z*87}Ut9_z<%)fr-bUZ7^IC7#2^n+LZ$rqK}7pXSq!p4OO){K zKnya@Vvvqdsmo!baV}wPEe4qrwOS&CWy^9^D-%+yTCJ55Qp2LfAg$$=H!3G2RZ98| z1kWb&`9KU(^II8%&hMr^1*qBd<6a8d;Q8p(d#WSk=?Z+7x8%@kroEj&;XZ*r6v=gm z4jG9>8B2kTMCK${YUoBgBZ`$0CFCi94%%p(OPDw62sst4ZL%1o^%e6*wM73{W^m|e ze00g?lKDsc?Fg09ymyz`&m0!pi_(9ngsipDff!^ymlS0-2xMNVI_ZrVWIpd|uCpU# zc7+baAZ^8A*1EPlDg&1V4gi6W21O!eR+PwQPP9AEB z5^_QX1Y(f3sv!nhlr<`lRgHNvHhSnibStN>IF6826a=k0jw@!G>VK(}*3e>*)>nu@ zmb63(+1o(}PGwqO@sy?#D&<=)CwTOnkL~~iIcWnOh(YGNrK0S2LfI`<(09HCOa<#G}!))FP;j1hFm zezzz))=>7oRquch+dxk!I6^D{=-}xGjw_x6(blSz*3e>*)>q5|)e*4#G3#ev^CjR%zsrvrL=|?gEWs9^Ix?@3Gr(| z2W?I6sbPCMLZ$Si72coNyl8X#rZ_3BB}$0T5<0{uV{g-7U*TC~4!!jibHufVh{~+< zUooO+eT65>5#ptS4#Xg>uXwUb36;_sS`5q7CRYIkF%f-JN zYl#x#_k|Ae4w|LQzQP#l@& zyrF~kEc=Q%wo0g!*3e>*)>q82)e3-w|k3+5)wlKff!^S zH?Vida9lAjPGSgE?~Rfei=GB_ghW!H12IU8vGA;-wpOLIh8Bag2o|$hwL}StW|H7dvPQl6-orF>aAReC|Z<^=Lfa! zO6Vy;JDqtD#}%`3l~5_Ip+);FUONSEqR|p1(1&v3kmrNhSBNM&LZu|Ojh6p4YNEZR zpwM|~tR+fF9sr0BYL8EUI)81j%h4OS_iXDMwBOygE_v|A5y1}!@U7XMKHM=~Gj?r| zMu)n$G~*qON&dFT>n7}LM8h6@gV`>H&BJuq+FNJK|s zEl;wR^9x5M68xTzyze(b%j2x&Akgw8YdODz6_eoCVC1dP30iKwi zwaV{DBKHHt>(94~4tQXzsLOSKC#9p#u@+80q-*l+foF#I?tVjX^_(!-VDaU4edS+m zK`d>$G+eOTanUIg9&%DWu0JJg*LiZV$#VxMH$5@bt`C~I6Nu-3YY{9vt}gm^wOk@=L&>uYrKdq$d+jdavz_Xqx4(Yhb{A|p zdjR&J>EK)PWxt!86K$TbRv0B9FiPTVl8zqUxyu?;ZZabl;5f~*PFiMhal*D2QCt?XF7$rvVd9+cIWTS-dwzFEX z2gGZ@r`Cw_Q;SiOWTPY&FAnp=Oc_k7;4t-~)4 zsEgJ=`mb0^l#qD^I$rqaKf~v@7#1yjy^H%Vm6Evx#5td|4WonVqGyBU?j4OXcU7$h zM}1inUba_V^huwkvHq75GIv484)z*s~)k?_xh_SoJ&y&NAejOU^zg{EvUn(VYB8V$S z9Tc8~d3Up2Z{kyAHL<5?-5eZyqWj6U;o4Sp(bRV1U5U)v?o3Oe@a2bhghzZfG}^aQ z$q_PB$2$(V$=Y|!nsKOA-vM32J2AKK-RcncUwYEU6WzBuBwW!HPwjUHx&KlE5dmu- z<6n5M+Ospld9M$RuKe*FN2t_)54pu^^}*L0g4p2kL&KTP>!OGLe5a%(O6a*M*lG_P z65bD@VdS2SVC32Zsk^-ellLDhQh>LGHlG=eoIW(_FydraqJ-!s(W_T@+nNzkn}bS> zn3xX!mrBXmH4xv9y*J$9$)VAvo6Ra}i4x~T6RqXtc+{ZLhlS_=H6nU+>w{{QP$@lK zhcBjgoE6@IcEq1eC~1ijq7S|M!iZksRnYN6<5`YSDbWo=T3*r;C8S3{oW9|I8h*#z zzR7moXl>;OVr4NBQ+KqAklbZ=0W9RLWd2646;I9pcs525S;NbEKx&Q=5G zTaf)jC_4ZUSPkNAHE@0y**}D`0|0^5AkJ0;=jD?9Lnu1{5LgY8Y&CFRN7+AwvI78t z)gZ}M1LvWY{R8)jNwyk*z)YQFGqro?vg{wYPc#BM01%i(lWZ0ZWSH-o8R3%nBD)DgtqfRZ(kn|=r`G}?~9wDuR0&ILG&<)k2ZP1+0MET^49hvbt}!< z?z+W9XNN1H`xQhp?%gzEt?qyQ9!IFu?bnYri+=Z=Hc0SZ=V$+CIu`dBoM?#>eqXZw z->s}2lb;^x2$eedWLWj+g|%P5hL%SQ8%OjS+!*bdXo(WC?t+-wcSmc-?-%Un2$j08 z|1GA2J&i2yA2u=_f4{gq))FOfH$%>e3SG2WuoOkAXj!>y%`%N|-zDV?6Qt|-%TiLi4vkOC=}N0Rbzd1 zR_kJ*gi48S5Y6{%V(qx#npuICC?Wj@0;Ap9fzj>=m6BdB>qvReFT7@!dp`7;fWCZA zjIA9hpN}(J7h^3^qDB8H3CC5XuS^H}iu=UMf2owt5_UiAsU6&XWl>9%5Pi^tdu}># z&jTe?N_2z3xUzO&Tybxh*D6p#W(g1&yQZVjOUoUhQZj3U!1H14!1EDmi4p@(o?v~2 zXAlIQLDPX}&=D%-SLc7eG%)?)rQgCrY4=3_H-5M0B=b7L7aITPh+FM?`Q6RpLIHME zlG{=0DUdw_ttIP`ve%&3qMMR^uzT%!bz4`WgzQT&UtROruL;N1!b8S7LZvW|S#SW zJowv0OOz1rIS5$7Np1ZM{oxbfGYJ*w#tz%TOr7&9|(t*8BG} zj!-GBAz~~Su1q*z)ok@O*YirBD6z{;z3ulao<9yc_UX2r^;O?3o25#qlyCWUYultN z@C@#y5-Fv2KC)E;lAYJ2il}sqW{}-qkcwo z*<=!k7Z)Fy@EP3m&t8sDsi!WRYY~&d>)!%mzqMTw&R2u(Iw{o>C47vf)u`=@pTM7Z zz_#7&4XWJH^VFYMtn^bCxo0T*sn1<+vmiNiSk&swyIqMA-e>v5;zNU1Fkda(t!b+N zrBdgv9$#c%E#71b+R?Q8g8}>Mvjf|uTA~En6p$$QRg>{|2JEZBi~2c2r7r$>LXpv> zt+t#B9Ygm0DPUjKetJr(B}zyn4#YX*8U^);<4k@oavoZVQ+--i4xvV-Qk^1A^U3S#Kx)qmr7|3F;fp39CBPWTd{4bB})AG=L+kq zKlZ#Hckran#cYKfa)v&*hOtnOb#T|dLzIwLF4bXAZ6)yxEAQHFm zfe!AALlTLr^0y!T>Rw^z{f0$-J{sprl<@xc83#_XzS?oY4~|f&P5N&c@`<|W;(wx6 ze@u9$+*kcKPPIgdC)(^|#5F4~1hM9%W!6`pY__)}R7xV%Bo0|?eKq3EgHkO~!bg$& zPUswQH8|?9##{|TKF?esu~J)2xO>5hYQG~!4;`0}*vBHgV_#k3N|aEm59bYT>K<{l zzdm@WBUI|10b-|%k2f6?;$e zuqHw!R7!dsghXXrbXuY^^gxDOoncLcc+1VAo5IYRa3xBJ?*s&_37Z*UO*lfOWE_Kl zHDQ)8tcg%dl#r(j1gr_`D_9ebP$_wCK){-?zJfIoYKao^oP&_K8ojk4cQTCqOI(fq zUF)l|e;3w7m{}99L<#KrjX*>ZI$%v$U%{Gigi2`*&6+UJ1gwcrOO(Jq*yb)+6VL%` z!ukrN5=*Vh z>uV76?`d=#LTMlc&<||ke zk(MX{Yr^IdSQF48I~hhy^4*Ke&a4SnqJ-F@&;e^A z&a8<@|4XH`hGtEeMGtEt(h?=adW8;H6G>)GI6|d-%VA9eFbYG(h?=!@A#9AD_9fI0c#@8tO;fUS_F%$zhrDx#cN?rB$+kgN|f;N zT38d-SFk1=p;E9JlFXVwtzb=*`>OxOk(Ma&WSf1AfHeUE)`ayHtO-Y`lw^OBIApE$ z6|9L!OO%l8PY~i&bEkyF!^X8MSr8SW`ZO$YOPbN@2B2GHVG0>?rf9!H(iOSSe8g zdkOo!oa>DJuIa#jH&$ObcCseL-M#qtW7|`we9p0_b|p$+uWfW?-)=g_4p>>z|57Q9 zQ{epI1E*O#U>gKlqJ-$fp8Apv`kRgyTV3l2l@i?`VB?q$*f^n?fIVnBU=KP%r8KgET16w$j-%HG|C_s4f-iqt zMl`-C?jjg#{+wjL<7?(|p|IY7Vd;#Cqrx6LbxE{DTJB;Y$bi^-c*;!j)9)GQ2x&+B z$+I_`4t$jzI=1e5QF`4$YlB6vKA4>T(@j=_Z^An%X%mQ>Z@VDfW8A3l%+IILuFd?t#^-Ue!U}9O8N>qzU$u0dbja`0~0M#LhciYUz+V;PwknVdpJU+B)SA* zr*Ai~cvSxtnPN?QvO2D z-L1&ElbjNl1FN-#eco$o(u+}<(+aK~lEYG!DLdn}g0=kV9r`&!BV*d@h|zc3+M+Uj z23_lVR|(jnHYb*2UK?NAC8eL?sO5J$LZx){6bgI(r;m-2IbS~GMu`#{*(wyCdi3mc zCZ3O-_h@j0O6iz}*WkoK=?S;34Q_ewT{qg5IB)f}_7uD@X``f2`1s~M(|;VeHrVj$ zgLu-yN_f)Zl|KFLdit{`B|iS~;@JJulc3}Ar}jy;M2Q{G9c1*tj@_VR;s*z$_n;j+ z{BsvasFbV{AU>GcJzdmgZO~y!8yA&PV)RBsOve^I4+8PP2R+hLMvV#|x??LxsFbWY zAex+dL|T8=+F(|{&0UmC2|1esV)?E}+YlGd>?;N30{tn71p;S+z=-rfk33SAlwN2l;epLAP;M!D6 zl+ZhiHv-LTVPkjWJN9yfO36M5I$qwqiOq0ZH{U+h5+yXohIO#`j_u)s|NWIHp;EG+ zgO1rhJ#BlRKOTGA<@_t5u|k|_n0ZvP29dZXKVInwm6EJL=qR<_FxkFKUG&Q-o4WG` zO6W;~LgC7t8>cJ!tPS3pbV90UiS)#f>>r`yhb=Zv!x5vxuTSkyKeeqmJaMFi-lsz0 zmT!Kxz39+S0!OHn?1Q0WMvIlU-@WhK-RV8InT(!zCA8P^-j9PHwfoWc>86fQDap)) zj!~2Ew)?Ss_Lqs4DB{AqJM*K2Sb89i>3UoI?2&cRI~VWk zP6kPiu+xoiR0W^KAEQpln^T%I`-K9@q|0%t9lP| zgi7g{#;W#ReZtlG(L*nGqg{#f4xMLD!O}+=)o5t&8xOs!>Nu? zDe>q*$2T3mG0$DE$NDl4Aol{glcnO<0`cRe*TsyVZ_!}61{Ff3#Loy~T8F#MtF}Ym zCd_B3oZ(YKylo(U3%7|EJzCP$^^Dy6-ST6Jn(G~esg z8h1ac2+95UsK?aOf!MeAoZa6M_}_|@jvja*U%#MePwnE<+$gCcB=_U2t7ew?L@io< zxg+qu6)7Flm`hHYTI5rE%^E-2s|Y*K&8NUtwJ=}RwH`w}ftLho#$@PC8f37O9@FzV?tAXEywfpA@3Mvt|RhI~Hm zez2CizDkJ_nrnj0<@=_EdfAo5W`*cG2ejAmPT4ul zqM=u<4Zhmv7}vW>boh5o$mem_%SWPCunnTzHqif4DIE)DpGUcU{&JuG_FuHg^{oi7 zsce*#^Alm+MY(mSB}!=f;J-S)r9~|Ve$;{XdF8)UN+OtO$BIuIMf3>Yx>eg$OO((o z8`x^Ud}yQO>JwHcN~n}XVxi-~JLcLbId;E)xwE=TVAmhgdtN^2eZ#6g;ZM5{i@yH% za7U;VYy*qkm)}nfYa+<42`y1VPZ^s%7>Ye;|HYhFdFO!BT`0VD*}37uorXoTKO5*u zl#rM=THfLQm#yWuKlYL%R7(30k?Ko+vEF_7$xmGGDj^YU=s4h=mUajC{C;zH2USYP z0?yrSzDq=ZdpNC?8zo9e%o{q+{BCc1q9!ld(-A7AV;ZC6&)SIV;3uE$o@$8_@B!IV zQ1&gszZ>QL-A|vr*-Gg7J>#dF?3%t__~C3!mouIEwmjc-%$xW;y=s*bCE#H(y6hwC z_1Njwj-F4v=?ImQEE2RFUYscR;%JEy@aUM1vfrom+T)_3qeq2zeEO@)*itFUzJLzA zPbT8~WOhAz1A3#Z9n48n;`lR0nvSpjVy@a#KOAQ5IBVn09HCO$(|B*x$A?GJHEV;r zzT1XgHPgX-I3?gOGaY3=96WcCcc(lWIk%!fzgag zi4urYSo_MEXMZiKiw5*s8?=6BLr198>+4Uoe`?&bIdmLy$mJ3DC7tiTGu9F%G+PYO zrT0hK*nOtBvm;b0Y&y+!lw)33|Lbz=t2J9~9cYOXqA!5AwpUrlaSz?;2$hoBfc^8qNP)n51j6I9|SUwygKaNl-Ip+r*i2Ov{ zUm@}nYKanhuFN7oVHWvuZ<i=pMVxfS@k7bx5^5Y1V z($Qm)9~&iz{J2q~gsc*wMSg5%K;*{}Dy3uEB0o_U`EjFN30Zxh1CgJ6XBo-fFqCyS zlpO#FM1E}cLF6aW5+!7A2Z6|s%|3|yI6|dlT>&BM2Qvrq^&?b5))Eki{6tyg#}O(e z>mvw6exfY$6KRPOvciEtaT%sc$Vv?zvS)CFO8Gk|Z%K>9 z<_Ps}%8nd5#5RbuL|Q}2@?*PKM1Ddg zR7!T_AQ1Vn9Wo+6p_V8i)&vMde!?vB;|P_Kw*!Gd5c#qDfyhs&B}(XhLT1f2`-NHL#}O(emKSu0t>)e+r-ayWAQ1Vl)Rw}I^GEwKS37xakUc9jmv?y$d8RgM1CUuFU@<_Ubo1PjdnzST<dZp;Eq9i2UT9)JQz0p?Fe5@vuS%B0oVE`H8ed z32mQ6e(ZE6B0r8$De><^2O>Xq0u+%S=4|J&f=~%WXzXks&WwUUfqFO2@QCeo9&7$Bp(X zB9DJUhvYNxjlFU9-r7*&z@fyQK_K#zWRagpOO%l4D+ok>k}UG$2$hnUFbG6`k}UG$ zGRc*YXfFsvev&Nm;|P_))0M}gK_K#zWRV}vSCtYaBnAxvkspg~Bl6=2mC~NJ$WNR_ zes~8fcTEY*D|SEdeqrc90=s@Hr$s#}8^;Jrgkemq+i2Nj3eNKp^syWRV|7sFb{476c+cmS2L%k9(t>5|TLr0+F9Ii~K~A4;4x_9rx{(Ubo0k znniwG?s=-El!rxr><%LGFBY@Pnt!3+$d23z8V{E zhz_8y5c#nu3Xva2sFaRri~OWn}F4q*>(0 zl_;U@!=C!4?sh-$1_4K?lw_4d2i{U(+3MH6x`ZdBZEi;%d#Hq-&9V2~*?EKeUcbi? zDka(R(1Ca9+1SOq^mx+So=%<`S3=Ji*_($GzIphIW^EmzQu5{|=#Y0hxp!tNA#ZB} zA#cpGZ$$H{rL`(=&kD4*_U7Rvd-JfXl@fA70lsj&;m=zBUXQ_!P$}(od{^f0R@S?C z!=LM2CFFzxbl@Ej_SE7X5ROnOKd$f&2pc7M2ZS3XO2AKTPeJ+258|BmL?O=U2$j+? zjdNZt&$p-cp^4AC(XND?P(V8n$4MnhX3qp8ZiwC3H6vq)G+C|6aW%xFOb6mou0)BT z=`^D&F)wQeVqT6=DLuhuaW&I{xEkNjVA}a#N{BwR1F<_hyR`rPcRE6)q#eHHj9}$0 z43t1LEAJ5yh(V@V4AK!QB`1bJAkLXSQI2zlTB3xUv;uKKql>H^ohOZTgi7h%gr9oo z&@_wJGB!~eKT60MEa;FkSdLIBKT0~@S30=&6Qk3*QulyXV?1?!8PB* z%NUgO=OA-)h>ByrC(mw}l0R{vrV zM7lBvc=Dc7cyExMyyrEeTBm(~VL$@kiv;mWyD7y^Aa=i|b3p$UrS@EKwfV1j&A1f5 zxJUwDO$34O(HD0D(c^}W0exYV;+HQt1M!;vvdMpcV+6h(2x8WcUl*H$n73=2fZj|> z@e676h4LD+8@~V+QU|~DW#2y!et&#)I%3@B0sYaG;+HSz&E_@tDEKCt5&UMHeFZ%D z7{q-a7VP~Dlxn(ge|tXzuSwnuN$Mbpx3_-WE{H)iJh-gLw_i{yfBOZmS-W3R8xpJ? zPG^48DYy&7En}Z3@@?#t;+HSjVqUWco)Nhup8F)b5HVU*Z6 zG!*T+ck3zIfVO4%rhxv!-ZGn%+# z5^&FiPx93$K~O#4qQO;I|cRl*HL6iFy8*QWz!n4Gms% z4@^lCByE)N`{x`bC9d0);&;wj8(y<^tPKg)&PEBpP0mqL;`&M{zO$b#<~2r1!WNUj zD2Xdy=;kP~uTE2nU%udJKwe{%Sg(>Oe>WVXgkPQJC@JwQBBl7=e4b?FHSZ+v90`mP z=xDQ|dz_6DdxJ8iFiPwl&%9>FG{3e>qWsnA>^oQ~zk|i>Xi9Ouq9m_5zWD7b66M)v zD!xsHZ#AY%k3O^E?Ng5lkC}fjztUCYSGjo2)n_bbHWIwXE(2ebBk|jD6Zth`lj8Tm zciFg?U7!B!G@Erulv_Rw-+?5-??MjWY;Tj|w+`_gO}pkdBIP;9{ovPINgTfM5y6B_ zehpX?exY=`B@68O^9zGS<|`2V<}wL>gPGqzCc*Ctvn{+v+Y*^~L7?UQN+nxf%kMZ- z3eqKh<(k)QE58)&T5bedZeJj#6m{_nySzrrIWrhho*B?`BhYfIKc&#}fL{>hHCk@p z=cJDE42PEUTXbx>ech2#XnDx57xEe{x33A3D9_Z71kK}q|GX;w;fr_Ur<(T)E>C8} zJ9g?C@=M3O#+Q#n){Hc28X|sP^JrWPqS2hO@gb+T3MsYepN&F%<<_oWT=s?Dr=U<+ zmcA3;Jo>8il0CKz7IzFy>dv`C?7vAvm%IP?66Q{O#2Z1!)4RVBJpAAzR+A}B_f4c$ ziPQ@BIx9?sXijGipps!YcF}-#I+OcJ$ z<@~;y)e7IGw^g6?mJj!|Yu1X-Org-eWhZ`ZGab15>-M!xO5uyjA-^WcYu*ojk#XJq z=yl%lK?&^`dB6*f(0k5rnUX%bLkH;C=DGes>({PIC(W4?Yl#wk!l;9zr}DkjwEv~g zI6|fPg;na{IKX$q?;2dFcB9bRhZbEkxi7!U_$z;oF|G+)}e21AOj1H?Wzs7e>&qM5b z-<#Ul7uuI{>FKDu+c`p|_{DS*0}i+g#8!=#n+`rFTRq&< zN;q@sEGj)xDirW-Lu&`Vby(CAC3HS66t@3vY48#HYRb;z9HCOuZ!z8)QGDNOwO##c z?5!&;jHTr^hh+By#8)3L3OeEro;`m5fZso73o&+MX|47Mi2BYGOvm;=J`~84lgKlX zaAl(oj!1mZYuZ`CZqV_@_&DHqc&UTBo9?eZ;w>?c`+v?FFp z5!Ju{UVf!A-DdWSftDztYjB~^<;^9fLvRPb`QbxHsFbW-(9!%K zwe$Hqx6yA_lg@YVkm$~!P}u#ltK+fIaew-_+cPM^8HoSH`32EeeDR&_;1}Tazf?+h z9EHNX1*gQkAFFpx11(X4GahyD&K3%(>QZf>Bo?bl-(<%Vs-(#&gCxLZ!G0P&e9! z(f;&}&&93K@)Hgp!uh;XqQo|5?`6O5G5G}$o8W8H?5igD`ZU)({ulQNTnl;4r;EE8 zwu$Q&zOFL&y?7@OYX>)SyA0h~Vgwq^72D=SyMve$i&~f%WAGktZsYXA?yG z5%c)P+jIf$q|9*K!{u{SDDw)4OPd{3#Fu;1!WOGbVk6s^rn!%%HSc$1OW%Lkh#@T( z+PBFmMK6a~ruNNy-Ve5iU#VPC*0I}&lGv7^SdGCKuv)Uwj=sV-mjl)c-(YSKyN`B% zZqXHGg~KSB|K%WlfjGq%hy$_Wl7;I$P*rm~T3*UpUKAfvLhB@JdDSi)EjI!!FN%MM zHo4h=w6wW<%37XS%gZ|OJ$LcFB;r-6dd~T^>8$0o;uoPUYdUDl%5#H}2tV9&xgSn_ zZ))RuKV0^G=X5^4@2n+CNFU-3KKJe={1$e)Xiei-36+wy76fcgv(;d8n&rqoVZD{` z)(a!Z-3Du3fjCh#MiLJL=S zJj-^Jd~&!tE8*?hi?&)^Ism=pSFkH!CTkw=)49>Xl-#eW9}<9O4?0$w50!~ zQsUW$jut;$P&yoab>AbSidv$CZ^v23w1``wui}%N1WKqBeeUcl##@}fop~jd67juP z`7AqLHMSI?R(lstcePSN_e8koGyi2RZ+XFOC9Rc8c~8-HxAeE(?b>)vNlTRQ`>Q)2 zm}}3+k{&&rr%0t}qwy)AHHP*4=LNxQcs~AnbvLu#@)9M)9{}RuIorqUp?6n}T~*Z9 zN~9sw8Wsu{ecaAs6VD-nr6o#8%mVjg>3g@7_C@b5>DJW|Dy6$joN0KkL%af!hMqqz zENY1o64`)`Z@=ke@sFDkB~wDBBrbxM&;H+&!47ynPM_OGeI#y=>%CFm7f-f3xJSE% zB`wk3Ro#f!F8b3($@+^UN2rwdw?E$J&QcBf>cnL`7PUkP-;NLN-7kI{ef4PF3`eMx z#B|W|Eyo-b=kY-;;aep66fst)x(kKzFV8A%iCSHA>2I}KqJ&xig~Dd96wEgG^^x^T zN~jcl;GBKR{=^Sn7-GFUVAj3H1RY58&U$cs^rZ*9>ATwbDNl^9r_6 z>;76LB*x}!DtNYMc8hODt^RtXc~Pw`CHM_c-c3egT_mnn36RZ5hQwHAcTB_){+?CrhmD@Nb7hHl^$B_v`7;=^oJd#r9oN!F-XRyBIP>=`V_=w;>96~_^>ib4mhI_oQ1dHP=} zr8O)R7|rK1$QZYlC?R`0=%8nw9(s7{b!VabIrHUnjVk-8C8DTtM@LBH4?1MGRFeHp zBD&_7>B~~8@v7KG6ff8bEgAmKhvYI$Y(cToxt153vtUI-e93hq-bii`7zB&<> zq_$S2w1)U{7IJX-3=T(Tik2uLo(bsaJp4j?1|Pa+h9gu;Lwqup$;Q6ovnc+Vs+>FVUuiVM5#ptS zjskr7d3Goy{N0ZLmSzrBq*wc|;gm{FZ zL%f5Q!^ghj953F%s*FbQK&t1?5#o)64p^twSF~2OwJN1G#A#V%&hZ(1_mM$?mM9@U za_A6WxFb}`xBT%e)2T50{Xk2UkhlSKh}St5zp;H=nEl3VQ>~%%Y?rh|{M1!Bsjz3Q zuV~*YA)fTA952|j)>pJ|weCttR0i#k7>grRN@6S^etThX@mTnMTHgDy%REzpv0&~p zXc4=(f#q$of0%(QF@&m?ON>QhkdBb340IqaXfYPX3AME#tkFTS3O59cNr;4Xs(HiN5$Gd5}Qi2 zhVY~wGNGX_ylVS5?XJ-!dqXgLnpU^O@lY#?_LcO%R7#_yE}|G~Ni{)z{8F?L`B?x* zkj|w*=Vt^!Aj8S>WSH?Jk!lyCMXy)#Q{n4F7B24~b5pfMdsk~~QOkxbYUv1-@_Dbl z=gc_x0{BZF9X+?CB}({q;C|HR_d^MllJgB{xtxNCwFLJ+U|%5yS(S~8=cD#K)Cw_3 zS1Tnnf^9KKYdP&(t(8hi9sp_ud$z>hrG2X?_VITElfGMi7Iv^8{H$F;N0@u+f~gZKkdr zgx*CAvZVi|QkoNBt3fe~LE0$?>Y$aU1W!V+hCE5I?oRYIkFCOLKh#ViI{(h?Xbkk)eA zp88)ZC7CrKU~9&FK4^Pti4w3GLaraQvn&P~bNxUJ(h({pc|ahBA~T5lU1SQmygnr) zTL=X9yTvR9$x|tn{y{|1uDSQs8d?l8Kf7e7fbu?30(OGY<@fKxnkZ&5NbZm;y{J;K z8SHo3Sr&sVW-&<1+@}tfD8YCd?<_4DcRtDyDh1on2%d;RCSa3Wtan?s8t*azwXbj= z?0(=k5U_yl4$>ml5+!^)5QDT)LQ7H!mGWmZV5Jtb7-UIHl<@6i?xJb@ud{c|L8wqb-rqBF^fUES}CE~Nfv{&meVfO|57QVg<8Qzv)-l6rX@=FygtMr z?G7Ra=?ImQtXafyB)67l0qi-TZKj0JVny5_$YPK@sb{^&Sb?0*jJ1XqgUru!mb63( z#9Qp27@@JKOfic=HYlM|h`rcYz+M&YKnya-Vvr>*QG%!Sc+Y7mxih1T{8au+rT(5= zCU{EFWfj+IpJ-pf4zxR1j>N%ov^z*kQcILj-4=tiQNr9*B~;3vA4IgTn8hF)v_uKt z4#XgXEC%TamEuWk_EotZh(YE=t(FK8sBXOZYhA5swL}T2VbNlc)^fxkU9D6~`V9p0 zM7h7>Sw$^TLY|ud=e%aWXwL^vTqvPZnv-5AB#Sf)6@mBo<{X z1u_yDKhMV-+JT6BKH3>ktduArPXTl=Pn2^BVvss^iz=lxv>2rI6>T;xQ9|Zp=-A-% zIBtctcFW^_bc9OzmM>p-sxj6QC1hQJ4w*}eG8+UkuT-7%mU&lmogE>wD|9eRoqfgJ zZEdYeX$>s~X?=wlWJybukQEL(5QDUFg&3rs+YD4nb{QbHTDLE8X91Lu{R#-gAZ=Ac z46-O|R3NJw^JHxF(6(|br>;1TkW~}}GfUZ5wDR=7R7z`TF-Yqxo-o!DC1h_09kPeh zeVgv*bf*SF&dS8vC;Go~h6V&;koj(@DEpmIc1u-nDL@P|-;ouy?n=nsF0>e=^%Y`} zy1xokN^1z;5^_;FU(qhq5+%fDfR5X zQ$nT0b_TK2>o>>snA^YaJI9@_Q9@3;fe_0p5Ic(R3bWOc@8{4OT83$E-KkaN2(k2_ zgW0R>E5snx^5R(;d$wT}Gs8Id8i3$wc#bQ?AT4(`^Cvh${0|^j-hFAj4d(Xmznty} zmGUi@(}1y-D4}PJECy*7Jz|i7*yN#D^sa`Mxtx0q7*VXWRtfPYpdHM2WnUo%$*5(8 zP${jU#URb&McY$Lln}obbTHqQJ{iOy9idWk`VfSiQFLdpl#nxuAjBsVh*u>P{|xiO zt$pxDfe`-{BZ`$0CB#bw0x?MIE5snxC*$5zqcyY`r1cf8JT1}x6;B~_hzHUUD&s~X?=wlq@4-pGl*;?M~IJ{?O5jvcZ5ob#~Xy4`gL!nP(n}bIj?gde&bNQ&aQ^e zvt86aQ9?Z4s1H+dqbmh%6Wj~fKy`RA#vJci)fWaqr{7>k|;bc94wpo3=< z*;hQVr>#{ft)ayrErLZ$QcINhe|24VyjI1vJ+Xs;*sv=BEZDmu_sqcxMoLt$qLNsU zXpDj-azza)7HkM1c^Z4eLSBrqa?gyK#1em&;4>Oyi?I+zpD|J66ZEaMzxfVp^E3aQ z-<`d_xwH2^XU>^fvzP23;OVnhDG+>?k^fTFFi|5T7pD+h$(1_ppN^WH%fLD6Dq8en@B9Wt}~& zvI)Pc`3znM1wdq7fb`^?fv(P(&N$QvAmZYg zoj_z|hXhS;SLaOUbE-TL0i{16vNlJ8D!Z$5rteqO=^$d_aGpfEds3h9)-IiCxdXp) zZ)E!RO0_&9dOgf4X{a?BPT#sSy*~VvQr~y=O&@h94Ke7(jetO{$?#(T&a^_GdrSSA z&@V6Q3b7AX#zYmtmL^jAY5$8${Z`ZOS}HgZ@z#BhgPmejW#+{r9)JNd|xni<1AVPr{71hOPrmee^*T%9vyi6OYRNnLCrkR?E5O>bt2 zt8=D&AJ$(c0$Bn?)(vNtxH@OZlF0vxJ8`TXO$4$8h+MIkS>o!PAxjLw9VJ%pC8DJV znJe}(OI)2ZWQifT+rx^zL?BDh2eKsQEOFdHYO1<48c`ZRt_Zs zSyEe;#P_>*GE01&vn3}u>J7$RW(Z^n5F4F*2z7qqrS+shov^W|&aMYNcTq`QvQ@6U zxZY;&C8n0f>sGbUANM&et$WtudfW{c1XgmqW2e({M^7(VgR+e_-K7NG zrTXTPt5&R_ODopdW&K@VL#5Cv(h|W+zNR?Ex}0@ZoU-3yt!vf}CIU*RREDzaR#jlA zS|#YE)+_vEkkt`xTd|@sf0t<1!{*;vLAxk6DOQbX(&GB=lR7KbY-bBAyR+guub+>z zsPa$~4FzH#vI21p1>%Z27PNwzvFT9{?P*eIDXuM#rDTBx2&B{QO_uuH`;Ubl2cvsxPS%9KglR*FVm83JBM zAIPha^D0q^gb3tSq*e;Akyq4>Z)XV*S>J$pm8fYzE2?BmCYsVbz24Ho&dLtVtHe6} zIWr=a9f+n1I29Op-O}_%UPb7JGp~|bDVnMRL{Nd+@+vJle=+ka$(<8f>z-D~tH|o_ zIj?{~UL`1#GOrS=SksCsr*fY&9)_S|X;Vj-c@;#g&zZdEL@vg%YMc z8K{KGioHZ|4}ukYX~k<+*5!4hw#iDj5fytKLakVrm%r2~da_n=O+`;_Q3NaNvX4eJ zlofj;RYMh_R`N{5f0--x^8Se0q6m4S0+B2BMpW!|2(?llHWhnoDy(XYBIF5nHeIhwDXs! zIoniYuLr)=H))F^WHtcew$BHr!!Uom20dX#sFlnmK*;>TCxi9QCxcq)T|f@x%ITD| z7uWAV1zhh5DmySUsQgX!2#%wrSwPyG--<>s0BgvC(lg9e>G>+hw=E!7uR#I z9p?~g_19>Kd$OQXtsr7en(*%{;Lw%`_OZPoYeb8=FITFKlFgv{qj=J2Ri zGM@thm6*_uxwcSQu$>vmp1^T5c|~>kc3w3tilDL}(JejtS;wzlbw6Nnz2n;>leWk^ zLzH(0{8#dpk+ek-ejdzxU=*pPR$w9mO=VIdVQ@ z8tqJb`cQ|n-J%G2F9G7T!^TrDwZ8I&Kf2#iD|xGFJrk>o1}$zs6Ri&_imMfsg6Unp zui(F`CR63OhRU(2PO}B?JGHzAu|B>1QZwUFL%KcVG%bq2>|=ejX0@!=T<7Ze4MMG` z`^>&MC))f$wPwyArq)bf@$FvTua`7Bt;BCYWc5=< z(9}yy*qWrGRI?d8DOEBAHleiy|Z|(Ff*_D$gGd zp;q$F2!y;RR`PCWs=AB;zgXn{00Q$zmFEvraitaC)#ZLP)lhl__c;(*XO#CjwS;Vh zY*B>V^FUz!Xg^CFLapQ(0|e%e06i~06HT{|y<`4xUn%l@1OoF%ndgs6p1Y>o$1(An z3bRD}2@VA24=Vlf*=}lS>;p54L&$R;2+SWHdH!$+wZe6K#sLEJ2i3XSeY9tVn zc@GNmZ2$!3kM`GuX>G9&evK+Z-miej8a$jocn{it#rs*_;dswSj<2QKgZU%n`NOR( z$or@1o3L-pALt{i_Sn-$-d;_$hri1wj=aeNf%zll`NRE|TFD!7>zSDH{K03Ujf3CL zY9;U2d?r?tQ=UJ9ysMY;ZBWWr1`t_Yh4V+y7DdR{3lLddh4Y8|Ew$2bD(j;?M+KQ> z_+Q!6nP2xZtDz6*m{j?zi2s#6uQ1;^gnZEhacYkvE2!7SyMNl#A=K)ikuzbANY z5TD$=A62K*n1}lXZBc}-YvHc_alZ=soauz4Unmu!R{yu>m4T~jFTS$^`oJ0)6?NkD zdXoDpx^>i*F|U`^`VD9Q6;*rEK@azH-)f2&GjgV(F^<|sPDM73+#%FTA`8UCw(Uh!>05j{uEvOZdG0KMjnvvFM2tEG>_`+x|w(r@absAi0^ahyM9VTZOT zLi&TRdhFP(g3@0)aq7*rc()dh*0N5GaV);IyCLQ-nBH|j4$?2h%a@b=2CT2<_X(VOfH4bSXluFh0xBRv%brsQ9F&GLXJUY36$bl!5I1Dk}pu zzoiJh3&28}GtROd@t~GagHS8|Z=qMT{3sj8V{1(-wM7v!Cd6aAlLuI~AHUba4n?Sy zdL2x_U0U%ttXD^=Es79NqYvCsRJBS!IQoTJGaObi-$gDft&hYkK_9L~5yw_D4Bd(c z#$kP699@!ewOVObT3%Tn$g2)*QH1n|aUic!&Z|-pY9)OGfo!)vknN?mC_>iTfyi20 zaoBI3acd+p`?zOJQDi-@2t6;?q6lhx@kzA!oj=s5#y)dzyK5g<_gsfiD~%JhIYw+~ zBmeZo9iz4=LdJnUj`(0j8~N9dz2;)BR^kO9CO>q2ocr{|bmoW0@oCUxh9a<=Wjh-! zmiO}a?h|k9(V6c0{P`|Ls1^1-4bkFkXHC6$^&9_;GV8llNA(+Wx235Up{eKAuXLS~ z8gBG1l=EVv$d;hU<`8P7err_U(yRy0irS(GzmHQrxvY8j(rPP*P%HIYQM~o1tK)ay zoS1gnrpxW{C_?v*iemVf-QzXubf#_B+S4J_O6&eK%8T*nm3q6CJ9#^Ep2qs_^qp;1 zJ8<7+lX_GU)Cr__&-|(%yi3JG&Yb5z@sj&3wNk%f<@csl?8yMd!l*5Z@cU|6w=d1# zdxAr#mHG{}?mwPMZNRkCGT(~Yq6po`!*0fuLGkd7J5%pXFLQfzYNeHe8tu#o?aZXB zj=CDDerxnOWBA!xZk1CJ)as;ne{x5Fcb|Twzj=4agj{J1ZialNMD<%yJb%dQmb=i%bt}S(pe8H5`{PFrhIe;)es%NimVaN>A=FC! zhI4nPd=fcx&b{yTs4a@{`_8X)e}$Tp>B#AKIfPoN--_aqbI*;BtTrh<`ScLCBdrMC z=LU1&^?tD$)S2d$uhsfnYNgePzzTzsGW5^m0mlz_YvJ-Wxzt|KqCFQ!zEe+rW>8X( zDuTMd^zPJ!KZJL)0&$wXWM02ssAyBL#UP1fyKzP3V2*}(@{yj^`q|HsoxqE@Hn;_ z>h=v3L9K6k_eUq6i#`?|{%YiN_x0Y}I)qxO-@uxj{vZ{I)5@b(O4_0b&&$aA&I$U? zQ4wmTenVY@mcDa(=O3pz#)cx42Lk@ps>{WrhjpeW#`Sgxwc?pqvM*ZagtO*-EYlB? ztiwcE(Q%$GitFkdEO#e;y}#RiRRopI>D|w^x(MFQ8tdu0I|n<2TB+X}jrDZOI;$mZ zQH1BoT(|30mb)7~{y|iPTB+agp7_MpapxT;r4cV*;21QDP+m?^OxyD9ddHESX^Uew zbO^N~3x?k169T6ozL*f7>6{V|?skgX+ZJYp^EBqcKOAA+y?DW)ZU;*d!w1}H-tE4| z<>=$^oiDK5z5C(4973(sZ#X?LeuCw0kN4L}+M)>0TY4A@_P@t-_s&hfjEYbz^;@H0 zpEh53xnndbLU~e{YY(gIR}bh+(}r&D5NgHQjNaw!h7-9vtQh&+z2g4U+}@q;%BkP* z^x5H~n$O*iH;zo&qKKg@jx_HM>2($QxMZ)b%)57ddq0OzEA<<`4G!yTv)XgFZj`h| z5uQgj@cC^lcVC&YtVamjO#N0A5AOeRz3uLk(idyZj@qKXtGqREQa77bk3Fa}4S#zF zhfpi6!-UfuXW!UC?>_a#8A(=}xf|ME&0cC}^rELv?BXiU;q%A2ol!*`|HZ{!d@{`M zH4EPDcJVbepSu&D8tD*frG7&Nv%T)D`P_YT*ZxUc6ybS&ul4*}&3A@lo?Ou()Jpw^ zQz`4rsNddeQtGq!HIDJ82;~vNyW1U5-*-r7x_HCE4xv_}*?^H>u=aCh=5#&b`1 zJQ-wV!;MkDK|gBzy(M#Zvw26+S4|8Q0WWkc@$Soe&+gb2-W_`DD2Grh^&8l@+w|x% z@6H~Ov_%nM<92af18iK3<2Up7srh7hb+hgcp;qd*qBwq;-gVq(Qd;Zi>l_195n%te z)kM+92~T~}wct?j`rfP@LansElVcS}VGl=P6`PI?pCzq&Oa0c{KQP;`I(4GkKi7S3 z^>k6}xOhllJjP#pIG+qn)D(dXEg6s2v*f*j@0QH=VZR>X5Nf5KE{YFNy|CmP@@n(? z)4NS<6`|uRim6wh*uiXH?kdUNbQb_~Fg;RTEo9Xw@n6Zdc}P zJA_(kY#e8s5iFTMWZep9I|@@CG2deSd&3Qg$JzUhPs$ch7J+&i?+ht1MakVv}Vr7=Iv?ZExgS8YUKFX$}PDV>S^p?ZSz~ZKQ5i|9moAp#D|~1Z$50jC-!-5 zw#8%2`MW!WTB)atV(`a@SUj$suwK#@MdbLaj9O!GYZU=jB8DccwprNiOFKTumoAhk$r| zu-Zyh3C`U+M~!kE7GUdqfpT*=?c(lH}X1usd#rb1{b2mxCTZvdhw9F?L zOFdl_7cTB=`%#;Gu|C(Y%!(XHMQnW8e&&(Zir4Q}?N)LA=+na^)Ji>#ea?>OEgt2U zUqx+EgpLpUA2YABc)Wh=-yA}%)YI5kTYJaw5#n*{xQkrwD#H8fuD?EB{&GZTdSHdk z973%$^W90LC?}3sJKAEvGbVDX84;ZG;@;H}Q>MhbuU^x!)s>;Ho-T@2`)+Ud$BVmm zzpg)Ji>#FUTJ*w0QJi^PQ+IiqP?4Rqdk(EFPcz z`ZkyCo z?>V;O_s6%lm=}d3Sc5ZTo+jr~J&kevd$`5pj=w$VVxS1@2$>ICdv~{OxwFNi+j&no zgj%VmQAO~So)zcwb-q7`yBSSv6`|uRiYafrW$}3Cm)ARlTB)b;B|P@LumR$6z=?Zs zMYzdbMR;HJAHR0^YS+&6>|tNHY*#DIe0N5XJ0{i#Pnlsq%AQv|eI{oY5s%A%eqy!7 z1ykbp|2oT^#}Q_Yiw$;6zI%|xV|0&;xbNIVO%X>NG2MLF+NoY~+7OG!fv;WT5Nf5K zE{YfS=wtC1K7Jba?wZ&tLdS>i!8iYD@pydC^BqF1)YGT~`P5}$JH%t?Px^7kq{&@H zcwbGMwn=yh`%%xm^FJ=z)k-tpodB)nq$jmfEFL`DCnrO(f4_( zrOrp4``fYALVOPvU7JUZfg*(UggzGRHO%6%?5<-SLao%(cqXpAfyLwKo%fE~q6i&d zQC$CrqT=_*0~?HV2(?mAWBwR6I}AfSMvp7FKiK51L%4c(@WeA=FCq7`&xn!@|!OO-_9Wb-9{nTI~%C4~uMzbNA@vVd3nr zCZ`XUy}3hM6rq*o@Vwgc=5RH}QNKCeA=FCwOhqyNoPEOy=;NL~gXU?ABBVcz{JryU z3LD%vF|E@3X2(@iEBSAMIC;s)$zf@auvUarfdk@4J#GwVVH^V|AK_SYYNfFOM|jSj z;dbz3=AE^bO)ZbDoi4zdu zErrZmDz!xs;x{0`TMC)CZBc|g zOV9^+OCj@?973%mcY(P7gMBS`!CP`CM&z5ydD?hO_9YD7Ql%bMguD&HyWlOEcfnh7 zzok~{H{>cfnf<+M)=V?a&8!OZFxM-jYM8mHN$iOCj@?g0?6^=0W%hyrqzNOQj;z zN@h_Yj$W{>c^AB;O3%c|3PMo78E?sQ7rZ4h`)wX1vtJSN?Sqknw`AT0Z^`|ZTB+ZR zw`AT0Zz*VtBIMl;eSo)Q-UV;TA=FC!X1t~Fr)4LRw-mHR5%SiDKEPWFnYUCbLapST z5eQjTbEo@d&C>bJcuSVM;4M|^QANm?KKcM}$-E2Rl0&GK`ptMtw#o_KQqUGf$d?TI z0B^~>3*M4LsFnK7cuOJkmV&k@LcVd(2Y5>%^Oj0QsFi#n0Ri5UeRG1hhMyv z6Tn-tHDvIXD)p!$WL*n=fVX7c1#ihA)Jpwkyd_(c0dFa2iz4KU9({nfWZngD$syEA z{bszS@Z?65$Xg29q6qn-M<3uVh0I%W2(^;+03c+?geQ^OJ0?MPNtQa{cEyC}TRT|Q z&`Le32w9UwAK)$7iZFOf4xv`+H{>cfnh#v_%oJeuX~3TQcv0w-gkiR_Zt7ErpLZ zpG4kL&=y6=`W5;BZz*Knl0&GKtbPFj-jeMPg11!3`Qspag3i;%Te92*Z^>07QH1PS zpbzkt0{73sTXG1sQok8*$-E2RQl%}5kkwlB0p5~%7rdpQ2(?nb8E+|M-cryOMaXI` z`T%dK%)BLsP%ByM1p>UKka3C3j|2SRJgr(`FO^0p5~vKfqh6v_%oJ9}NU}OXgkhmK;K@)NjUHvRMth zrAk{AAv;^Oz&=YK$&?<4xv`EYYhZ=OLgWgxw=uv%9xP%HJDv5@M_LZYvlNGSqdXfub<2Utj5nT6yKYNdWd?yffV zVS4xd@z)1!QG{@c(8u>y`1jyX5A967*4@J))QYt&Gsg=EsR_t<)R~3E%8~7wfI)a< zK!Al5GYhHGGv~r2U+PpmSV%FmklYz}MF=YteSn1&GYiQf)Ji>VETouONPIFhu~meQ z&sa#tfdmW5A=FAeZ7ifZvykZBCbo+3z5)xWE3=RsLaj75#zJaWTnxg%Wc}TC#l;}3 zN%%_60=U!tcw3Hq`tU@*dfHe>c7K3{ISP62DlQs3`*P!7;Ot&<9vZ77wtH973(s)5bzF1~yno zm9{8C$7d`giw9Up4xv`+X=5SPnT6zXR}tP z)Ji>VEF`->z(V3zQ4?E5==h9Yq7eC--6B=`y}q?B1ml~(S+x}U`(ulqHzF&2`Yy8{b} zt5HphBIGm|`Tz?lWfqb{sFix!SV$HRu#kebC_=|)EF_BuSV#_`R_bYEA;ru>a=EJr z?<=s7>dZoN2({A8Hx^P{e@Lg*Lza_MRFAM2P;UaO26m0pPVg02NGY?BTrF0ta+{}F z?^8W(EF`->z(V3`Z4)&`U=7eR6f7k40Tz)Ji>VETouONI_c^;e7=bQp_wQhfpicd{?EJE5a5J*6hZ5 zyWJD0(j4R@D|`hOlAUA)3n^%Y9_($Jr&+m2J#8!`iw9UpE^3Ov{*L(&EF|;+7LvsS zEF_0eEA_OokWywLx!5W~$7d`giw9Up4xv`+X=5S9%tGS&Zj-x;@V){IDP|Uu%XYQW z%y%`gx&L8(fQ1yWyJYbI3yBrf?V2k_#zIP&h2*MDOT8Udt!rXqEF_BuSV-JOZdw!} zRT!{?1s0OU11uzmP%HJcv5+htU?FiQu8FN8bbQ7_vUq@nAzP z2=6PfkYZ*bxolS}&3sp3yp*~IR7+z*EF`O@3l@^AO$9!Sd7AZ|)YC-) z7E;PAq@XQ|keVat11uzq2UtiBp;qc?V8>qo8fwfRkcX(@!Zd;`MJ d9LKo{a~t~j)qrp4!~SLl=Q-h02j`(@9Ms%L6?rl-4XCN|su-~TEVvDu2%_l@MEo-RGkN;NKtywzfs zy#KCl7J^)N)b!L zMp-ENonYH>#GJ?oMYQZTOe2_1&>A~4GE=0okvOy*>6UYUp@`tsy%m94{F}9OqIsI+7GK>KIXYV?;ok{FRO9#R zcc*!I=;-fmyDQ>#x7HegTKt=@dK^(GZ*fITPw!!&1c~F1GDfn!b|MAY*f_O8Na zZ<5492@-tgn8;XoE7|yPqo*S5+uuc^t`u-Skx{tp8God`H90ff>@I4+zm5ioKGO5m&vxC+8%OSrlLDVk{n zYVmI#Io%H;;0`)af&|PSB4Cy{Q1Uy$W1@LQ1k6N@fLS8oDImg%pY1)aN(V}QC)fr( zA4DWPQK?qNY6Q%70Z%g#2~TaO*;gGX`JG@J^qdm`D}zSBQ!8MNAp%yPn!juDacPbE zjer%dCLRk`9|7y5gSLTRtEfhx7ObvBz)D>cB}l+JPXz1+8i87{OAzrke#d#!t#wV5 zAOZUo5wNRi1Zu%t!Kld^0Un^ENt5{|+o1J~Y$V(CQnHN=!m}nyeka&Q z9O1FZQxOfkof^UPFD;vmZDiiufNa!W^quwuo2}z5XHEWpg5-CC>7N9xzW*=5|CXRd zwDD^kbXN4V+idY?1rnY3b%rT6y;MZ}$bS-i+ypJU3W9C?yt*_Rn=St8{*?SqF#Yom zDkA<4{v`Og30ibF)xZCoC5j-wooC5U$?pWyKWCyM$ZyvOrW3SiR;nY#&35wJ6+wPG z&-R~^-wCGU2zsIvL4LbNFrA=9PnSB<&!<)q6SQcR zP)8zn+pdg~$1# ziXbnXJjYWb~;)w#i0~ ziE+ffrc)G=Ai?AEZytGEGy&t#j)humJN`&6Z5(QZ2@)jWH|>Bh4vEJ?Ef^o!fN>}S zuWtOgn@q>g7_tHLN}>d9!0aJ{Vw{9|6^R6D!Tpyi#z~l096=_`YULlq&sP&>4-pjO zB+M&~KrMLEh=3<55+%PAY>%EnA}GdDHsYggbyh5a`6^+>AcA5XMNo_riIU$5wh@;D zpcqFH6ysH4e^lpcbshM8HaI z{jS9}I1i%}6yqoxoW(&2tke?rl1OrTe(g9Kfm*N=5dpiJg%TuSPb30%PK`h<*ing~ z7)OnRVjK%4NWk7s1b6@%fm+}h5CL8WXYLYw2F?g3_zaQY;Sd3yjD?cl3BEUUzlfk1 z$HAUue3nz$Uk>IHj0Unu!lHUoo5tn2AjH3w7I^(hUcY+r9)MNu<93~_`IeaYAQoqTMR==6%-!@y}fwyVS+iVv` zdTN<%Bv{TzqG&=9y%e!E#HkUw*3UR0ju0$mg8$FfEx?_cAf zkvmwEVgo*_pAsbSy4h@J^T(adrJL(S-;d=S+a^wzSr=3{`FD}@s|5eP@K@ZwmtC-m z)^Og{jCuoI_FRN_#o_&pMoVhkhjo5iEp93XG z{9U<>qTPa1(VeLKW1=G5dREd1)H-~tjI#0c$tSY0r)wM$>{i=>5+wLHUy(Q)4Q|F= ztNue0Nw`+V#W{Z@?BVu{tNu^~-QP8QC%n{I@h_BU#4nn5XRsmu55fhuX&jlu;?Byw zN*C=8f(=C^+)bOU^3gaV^Oxd^NRS}GzY{zI{jBglqZXenAL)M|d4fbEe%T=Z3PvvR zSU}jpwxNwfq89&7@XmAsu9doj@gvvnAY5It0ndjc}33$5%7FO zBEi2CwD>9Dv!&;Q2zWjsQGx`_UAiY@x5Ul%kji$AKrNX0M3gl*na3YFt!x{7%yDIN zI(9UjAqRbXD=gns>Z~?ZzACcbNT+^xiatfe&1VJ8l>a%cDo3BYkU*^w{}ok7GJ}{H zIBJ`Dlx+0qJK01D5^LUOP&O{!k0D~-_Bm$y*G}v7jJg_uTE&y*a;#1=L-t#Gl!)Vz zkIe>`o!0O#Atp+YSer77W8&)R^3VK-h?pOcTuwdVv?i?EWugR$OP@2UvwHsS01^H- z(#d*bpSi7WEgh-y)~A{$^r{1Zr)*pVCoiNq}@;&BUd4_2m0Ndd`QYlqf->W5#5TEhz$I zp{p(;ipMmQe@%5-)B0x62-JGxO6r*N)n6_SW8%`o4zlz(r?unPc3RhZ=a(o!qVeKHj@R@2 zWy$mVh}a&`S03!+v{Jq;tP!Y%Pnyk^HE@7*^l(}~b{5l~K_p!Jeu%;y{H5dUUb2z? z`w%&#qtj{~TS_BP3!g`utxf76S@g80)#i_>vf8GlqQ?NI`v2}rhs5c*K61(1wW4U` zLD8(UkKD9sE!p_|YMwMNdRjl`Pm(A>LK;WK(- zp(v;2=#)iP7#A%%=A16=JJLCLjpcoipUVo94v4XXr^{PaGm@v)h|2*?9}uNK{<2frNjeDDmw|fcz-ZkPXN6r{;ivoR)FB zv__!Tm}*hNb(fxxIZPZ1ZsEH0-D$a&u6FT`$vY?ShrH+UZ{F!nPKyzXvd)mci*gh3 z$!ncCiT1%EK{HLC z9n)5t?quU*_k|jPT0SQ~t1Hd_x7ofVcQ-GRjoC-sO_U&UIaz9Dga2={r8u&{^duXZ zTCC6r)Z+8!yUAy5v&H=9W^N@LO`7B}QGx`YKVLVtYqK@mHp@)UK11PuGy=8QH(?um zEy;%Y-NoaG9#p_Y2@-gpY_=XZo#t7xF~8kbjX*7&l{Q<~m6gq)H%@EJq3I?{kkIdW zgF(y8GZ&rKpxiGt0<~~X(_XvjquH6f{h^+fB+fXTiN`-jik|BOWZ9uS@+ZT-o6AF; z*4bm#BubEopq=LNvH(;f6OGy=6oAC44NXpc&lg^8E@lE{(^oz}PU z4v7*Z+SZK}%lral4Ud#WEP0herl0GyZiUs+2-I?aYKlA_0W$mjmh_Y;L85rteZr%kzdYQ;MmBQoE-WkkNksL& z8i86RPwo|^+WSknfuGtUZ%RoI+CTbd9V$_RguUe+QSOVMbX)#~h?EQdkTYA-J%2t@ zBT(yuwOhQ5^^;vgKM^tMP8Ip29<5is{+1{~qT9S(!Y#m0?q2hb2#=?BIaoNYyUizS z1Zq9lwo{yI>L8i88*LpO_ow4b-ya*c?{=pHh0BB%9Y z#Vm;uB(^TvETR|s$}Jn2xUs&coc_bpn)E^^P-~d~X3;IkSJofE#E71~<%zGJR{4p6 z5+z9VnXpOJuH!57oWDfG)TI4n=8vA%Kl5g51ZrI`y-{?&F;%u}8B2ukr-3r|m8X>} zYK}y$uU9vSHHW9larMp#ov0EtOkN>xsn@Hy5+z8i6#s~94X4V_yZ$8`je3ui)_qUQ zV_uL(pw^#f){6{9r^+4GP7vW;Y^;pE;c4|*G*6-giI&UPi6=*VWN1;2Yv0xUTRyw$ zX(jrs6R5R$)jAP=)JJ|P%|yN62{QVUr?t7$e2EeylK;0>q?+#|6F=cdczM5xatnEu z!^X{*s8#FpT2Y9!ay>gFbRu>CNwUWUPixDP`4S~alsdguwDt3mpS!b-vMDFap!1&A zxJ^2NT3^Sk6*C9<$Yuo&60xSdr_3AcX&pT|U!nww6p7Y~vGsjqmxcR@DB9L3cc1mN zx;@hg)GB;)jc921krQ$;5!Ba9z9TREVCn@DB}m*azeaRR<|Fr?;^^-586r-3T2pfA z1Zp*FxJKMh?IZum5=F%9zXRp^XirKR1j^h;mWq*oJ7t;VAp*Vr7iX7>Lr$mMTsDM= znu7!7Y$DD@=>%#ey1i8R`8#F79!#|A6DXZT%sCY(QG!Iw{iS0345u74oQbO)1LY7R zw%pMP)Ozq`saU?qDYNZmVr%O_*^`K8&jTe&kO=>@RFq%nlts2OVbl+ljfp6qbhbvI z*73|CV&6KaOyeF(#91Ry)*#|!=GhV@NOZ{?B35p8%BAI*s8cLZW+fs^4V^%(1r0;Q z`=d_zem@glIRj;4BA&OHEm49*#=0RQ+hM27xPyt=wm^9`%G0_(K_^hF`=k(If9#Yu zM=vAd#Isq_B4Y27*%Bp4c+L(Hnch3)w_QvWw`NISA_m{q3DkOZH$=S6>?OBeT24gQ zIy2-3%hM{pE=V@2vRnk5@{;^)bZoU;)V$;+Cze|$jyzr_g7$dHZO7LT@nh92*_UiA zN;OB~ai3nHGs);BAMIT(bQ?kAX2~iuAf3N|0FUwoJ?&;UxnPa(3H4V5STsBK$9%K&>@7mx<0} zy=2a$tBJVOW~Q7+#LG={B}$M;(RP`r=kF!Q9%15WiJ3Bxh)tJt0=244Stecvd&vj= z!-;tR-wZjOh$6{@BubDNwVdYD3NP9H7!y4Y&rmk5RMiR8(q~DIl`~`z*_hucNTLLZ z>ra-6{WP!Y{mb*}*}xfc84=g~bpo|;hT3cyVyDSs2R*II7v{_QMZ-jt^p>w5ZxfBJ zF!AiUw|w|!hv@r0Obq_vEj`J@wAmhi@|80Vd0L@K7D$vJ@$T6wF{arRIsQB6MLSLQ zmIF`HDq3!V#1$D=>ap9x#ei#5NeZ@chltwy62wvf+Vguc%OMa`S8h0)}6PWY$WraE;G@}kfHQEwbCR=ka*u` zg}6}GTka<>jdry})8$}Zucqn*YPtEZ5R+mzJ>uTH0CUyg#176U-rHWm zq`JWym&zwb)K6ic1c_X+HV5Y{YlRgiqVwZum9u>N`kfsK)T-Myk%KdyQ*xIeB2XSw zdC?8gA$F7?@uB!Nl`o}oD^*|fxo=k)$g_2eY2)~`FpY!jEt67C)5c`8-LAe_Rb|{3 zmoo6&k=VG|-N6-_n|(s)tY+6*uPP?rzL(Po)LMK#lY=WJqYs1=(Q5H(RWW(dtBQdV zBr4U&?BI&YmAPw)xG{W%s+g>NTU8@aYr8F*gX=h}H|`+9mT{S?m{bq1W}w!sLs=bM zB^e&I-PDPapBAf%$xM5710_gY&!5A=)ul2yB-!}$Yp|*=-7csTsFkR6P6yYfB7>ue zSp6|bRj_8CsAix9iKi2DIk>V_Wz-QO+D@ONvgcV^=mcs-M(1*HzP;4UqeSG%a8Xqh zi%g$w$Etqsu{Bkm(lfGx#Et@+ty294s%qIi`{x=cL83vUI*QJhX*bz;`u3u#jF$a4 z)Q$vdK_!-mV4qp4Zt!VPRRhl#$1%M_9#xyT>V1lc$A8aIwTYZtsu(CiBK5^Qs{S$i z_!%N9W~6IC^^aAJDr*F4^?#mM)mYAsyFkR|!oI4;5_P(wff6KYR>-gFI5mrKUxt6L zDXNY$u4x60K&`eu`Bkkb^RVkg#DtDhwIbiJG6qVJc<`vOsz>d){ECPsyN9TH)csK< zGy=7HW+|d-ULMZZL>brNIY9!LREP0A4x2!5;v>9st*!IhtpQ<-=Z+ecM?c9$w@q6CS9tqVK2@>9M3 z3nDg+8Kf#dF_(&K1Zw$|Dd^zJPaS!Wh#Xx;smjlcWTj1%AYm>l;NZ&7rzUrZxRb?G zReoHV|Ii53YWgm(gDXGTf-eveGG~ga{M>I@!9=aoH}X2T@>8|-1w$wPD(SB(KkKVk zHc^7akHWbfT={w4@fg`i+hB&O{M`M!ibkMTXICxkwmooI8Rl6ipS~%YOSA=-NBU~N0SI5j*VZWDnD;)RX0(B#M*6H9d1qn`YNgzq$-$MMs4U?`#Con)m7g8ss+cH2;<?vkC;P}^8i87mSEhDwHxY$mcB;xx=*}W0N|3nyJ*9&yKlf{nA;NZf zx2pWyTv9+IQ0vRf6b`QZ#HQ;*gvhi{Ren-u$YY{biZLl1T>07irn{jNho`$#v{dECwmp@J5+nk8 zC3bM-r$pxpL_F;mr7Az-VRDT?t+ss=JGk;Qwl5QBJfl_R=fcp$CQ6V<)Gd*ND?h#4 zmLS6SdbFzioIh$aQ7bQLapkAUpb~~o;upWshAbK_XkxZ>sWh=TQbCN=+kzDnH-+?rQ{Ub?g64 zRelz}cPFA#XpE}-tQzjSxAcT-s`8V!$M$NNzbL)@nyUP?h)z_Up26@KRr$%D_KilM zR-fb7ROKg8j|xOg`X@$JepYA6u@5CkG`Mn2RetWStW8A7))-a!8T_QSMxfT>+}Bm* zr}PnDBL3JJqbffw{JZQ!2@<`tTvwH!O3~g#6n4d^%1?BwX&QlAr-oivm7kdI+li0W_|_77rIwg{9U zQT@dYRr#s3vNjQEKgFoZ&yE5f8i87qKi*W8pD~AhiAYoCn5z6_YgWv4S3FdepO4FG z+Xu~ms471_);6>+Y4Jc+e#&;OKwbAA5*<^OpUh1t-j8ex`B2@(xv-c^;K zM^+-bR{qtGsmjli{x>uNwLTrXt13Us4<#ewsBuhHesWZN6M+&Ww)}lhRett-bSI*& zIHsyHQx@4=NTAlSRQFZo=VgZ6L?j`CD?fGqadV*riL8C^tICgOxq?L0uMuaX^Ko~L zKrMZi9H@FsRenCZXLq3liAk*G#rROP2*_)#8t&ZDaGv$M=UE|efqF6jqV`5Bbv zE)lV552?ye@yj<{xFX|9Jty!#Rr%R{IVG*syM`T7m7jCFF1t{I#JG?zs`69sKr$lg z-94l#KldHyGy=5_?)t1MKUZZUA_}!StSUdN7oBjS1c}QTKdH*kK>K?dhsUMEs`3*w zmOk=>&5x+cPu-?27fO&20q<4ir^~AwWWzjlL{)xrJ=>}gsD)SEW^>PfOjUkL zFRbXo6$kHg^~;Y`B9&rP1$=*Ur3`5EK3SR+sipB0Pe;OJf^QWWX`9|-65lz?3`hh>IMF1dv3>s;85Y)D?qL-n%VI-O_*3ixs2_f zxRcx-_QqU2#c9>A*Il9ni94x-#fxixazrmTBF=A_XZUzIt;>InmfI&>HW#!SE6-&K z6I*VqFh4#XE(<*!D*T=`SHDvo;BP=&x!+WrrEaS0EyLyYw;g4ot&?T-@w>$4C8Oo* zd0ukV^k`AU%R}-wW_TH6H5a#be1 zgQ@-p?q^}n^(n3nus!S`eJxRYjuGO;2il~cBwcETJ{YO9)8-VOhu znb>0YIx`dX4z>>1C5AOUWi;qFNe=9PP!`E%8GL=V#BP>jGPPH~f7IGRHioRg@ltxUHZ&_^*_$s2?sk|6Vh?^k?z8 zgpYhV`<=11?N`C~yy1hl#&hdG!S}rQ_0Kfh>&#mwpHkQ4p!OAHm)61Re8ZfL#mVE# z1>eDt2F1kk^ee@_t#miblq4J7FVB$~o6>s|TXvZBS8Nn}%Ka_NcfMd$coizfFBl_N z?z&=p&O2INtK%OAlZ^&VN63~wPU};jr6x*{s5oq}BDy}yPwPOc-6ozd zj$^-D21mKvlqqUmkj`pJn#J;v;k35&3NcZFL{Nc34t{D&ZRYIx$c&R^$@2m zfm(yc=XdZk|DY6q880H$NmaY6-!h$v*B$T2rv*jS{g|A5ED;s1y^Og0!)ck*7et&` zQ9|9d2`3MWet#EsW(P{Yve08A&iDE_bC>#A- zao5vX;&du3(gg%M0d$lIglD0)L-WaaWEN|4aU@po)3Wg~1ypbH7q zy49?jvXTF(KiTlwX_#*GKBvELpbI5P;B})|ZS6|w`IP$lw$+q4<9LtK#x#Swz zoYs<>i`z<+AVKSjh+kKTh|RiCrlK|RWWKr@fm&goZI1n?{iIhu?iRVVEl7^fPVXo# zt|(E0#DOQ@#q5RCWN7a>L{z>oRvzr^wEp$Zp%JJxsbgBlj>Q4ec*UJgww(Rt(a}!p zQvYNUB}gQrOls=CsMlo)_b2Y?R!6p2Lhlugd}<HHlSK|M=(Gm9f<+PIwlQ-0DEZ}; zpIUEu-KF(c?y{9r#FIVChrJb+1I0wqZBa~SV^kd5*a+sMZB45m%9N+VDUuZYdI)V0Ta z-Nb2y2hS0_Z}9#>`-s{%c>kbXLE8FFHF)1mQg;;DINWxXS)cZgmdS<-l<-cIK^v?YoZC_&D+t zWMsp8@p7{d-N6EPcWMM`t+<;*3@1Oh<*U?0WcfG1%$&k$E&jAwpcZ+_27AlwHS5HJ zT(it|_37=JGYbStkeL7G59ROvajyW`II>`cS+}{HsFr6{5_c*-7}kKXdk?H^@K*CR>YyH%0~3oLPR_ZnqvNU#c9>+{>A`L zKay87Ue#z7iX44WDjVg>lqRBb>yBo#`%WvS;VAb0u-@vE=qX~#oDVoUN=ztW|@tb#Bu<`uPU9}e-@HlE7dGbkA zDd{7-t$Aw>&i+xHrx>@>aqi@Zx)Ci8obj}3kM}fCf<(h{HU~#V4LZ*xqEI?NS-F|h z^17BnU{o}{L$LDnhr4CeA|%Q{Zkr$tdaH5P#3u&EPDs!$CwRA`U5{*>D%4S)oaeMQ zp4+Dps0FbB5k=QHWr?Bm1%W>g87M&_Rkp?ANb@n$ZytA^EpnSJ54NB;++Od}2-L!> zPWNN(TIrtNY5nv5ly*Ompx9RJyBzD*ol>a>Qw5EPKs1c}zaU#vD!z*Naind=D ztSbt>U#{Y)E**=bUn)CvJ0N(E%H%zPo{!AeR?v6a=zW|d?F34|_eGDBh_Z#($ZE7l zB|XwsBfyj8*k8qioC~noQWpr7!zl9F<>Mhxg2b8WiB;rPuXzv=qZJkXrcZ;-+`Qrm*%O^Wk&V<)?%7_p#w}T-MtaMtn58gI7o01?wVqc`Y zgCqR|d-f3Vb!Zv6cRQ_Di}z~;YJopT#DzqsOn1sNObi@upacns$cT7&AzF2RhHPt~ z5vT=zA`$Icq;hd|clyYy>JZDw#>1Qq`?hKS5p^pP1NIMd!1+ggEXtTYd>U)jMw#SYVB=EYChg`^#cPTT`^-hR^ zs|>C_5UbM@<+vneDIx;v?8W?rw!*Fb_dn&GKU~6nmW!RMxJ&ogS z@ujkJRmx0^T4tcup3-R@ykDJYnOo{a*j6vOhvKMK?PeJ$L898k{3?#xU$idSs9wH? z9J$A7?HgWSBTy^HqVkTT8>UOqp)?Wu=arTxsH1W1fW`(&kcbK@qT;A7>zWg>yzw0~ zDR~(w`hT}0fm%4nXqJ5Zq2j28jq(^MK>~6dWTVKB7iN;%)JIl0pGKe-&M})UQ|&NO zo7StCJgo%9*0eV~O}H(>4+K+0#nWEE{|KK?3vpl-XV~ zN3?G3v^wsatr4ijQAB*^j%?VvdyB#JeTJSn1{o+pqUN1Kk-T5Ek4;ZRuG92IJj#BQ zDl$qVP-|$h0+F+cC>KCD^-0Wf$2_a3{@wK9h`#C2 zPDYB)PD>0uY)1(adM?~_vl|b{Z+}rLTq98H-pII4U{0k z@e{{U6g3fX=8rnYeX>#OuctMd@?7D0QN|4a6RfiwR#Gos*?$%GQ z5vYZ^ew!`ZfHtDkDyQ{ye;WfONZ`Gpt+u+qSV!H4-adK7h|*7G>77$$)y(8kPz(~E zNt52*86r6&ynHL?OM1^7Ahyuj9+WnTKnW7;;m7C5h{&46A<~hj-?j7^0}0gPm@q!$ zMZ~d6=|pkLp6`6@E7;rPwS>Gs$-XqNCFChfPxs_%WtiHX??;E_kB!c>mTbD#L!bnS zuSqYdT9IM)CgM#ahp0`@;2&j|39Rs7<%fMYeg?^xqlo3t=t3fvvgb9^`w5gF@ubWS z$=B-aV~)I>!x9S*is+M_@1qf@#oiu2gXH585gF}a9HW_dq4@#h!;6KIXI#&}^F?yS zhkuio7Rk>GKR5jR&{t^5cVi#!Vxm(9N|0dxko`pR>xf|gko`pR7X?a?(9h~_x{JoJ z^-e4DX(f$7t=O@9WX_b+yJAGVtK(xoMbG(PKouXas5<&9z?HXyzMV5*$l&-GE|idZM~{tTa~AUOOq=)Cf)M z&UurwgSV4^C&J3H$*4v9dC$M2gbgG}u-D3U1M)nHNVY53NKSsqAZwjQpw|BCDP+!f z{xYkTkFM1pH$x5IQci2m*X05wNU#UXs~!2LL|l08Wt^t?+_%XzjXi~;vqqp6&U|{)g8W>r8<5{?pacot|9<5YcRa{$ ze51O-l$@_L0=01F+iX=D^c92X9p030!X?(_x%SL+iEBo#jKQ+5r?+hM-(Eo-jX&Co z5tIWsU4JQ7*|n-ZRNRS}{$QjiM(^+r%e_+KvCzieLcy}0kGD);ejgD9uKg*d5K(SYdP(MTPOs$`R zGW2GAhFYJK z7?1nYUVC}6LZ9a_!@-Uxb*)py#Eh?) z;7Y_52s6H#LBy!!D~%bnUftSas%RlW0;?UaF+|Kbve76>>s9%wQ5pej7gr$6_-Y0b zkNh?p?a0e$)NTj&68w_jQ-TEdg0KfbULg^Q+ICPLfEZp=BTx&T zU?Rru{a|M=V^YS4CQ6WiJ(!3>8QqK++6VI&J*5$-1uFv)C$BB6!TWj3-7g|w_i|AE zU+w2y$%NgGh*6H$_JXvZKTk2zLSSI8-j$}!i-c9Gug>;J_>0=00C(br)PO;9^0SKd*A1o+ov z!+q?ZhK({svuEGZ2-LzkM&I74v|Mzg`%$dU6_cyr@$~_N`^PwQLw=nBc?N^twe;H} zn$ox18kW0iq6CRTd3VW)vEyay53xjipS?|F`{ZdAd>)|@s0CROCPq&aHj34n3`wJ6 zG+uWpW)mEv@vcS@nAlOXql(q`4*NmGA7^{1yicjxcTAKZ0eK%Hw&kuWmQkHEYfy~I z5fJ+ybe#mpO!0Yfj74egK1|YAl%dFLgr^PTSB>DPj-xw@<%l@YW}4_$$7z*4noA>4 zOI~^^OYNO1oz{a=YfV_r)j0F*g^6V8eA9z~z zbM7+nin903I~n=bm_eeE?|CFe8S=ujuLw8sx+B5fH+xRxH52imixhilSF5%rNFz`S zvPMK)xDX}!(607)dN}rla>eZDaoPLkrbiExu8g-bv4S8i87V+1(?(HcylD zrk)|9v}2Q~L>|ETYGEcykYMjSKA%k2YWK@0y0QMWSyAO&O2wJ ziisnTKrN1p<2yl#=sP^tY@L_>vPx6xCu?!b_>uK5nWN(jjtvc7OSmEjJ(onJzJAJl z^3v1ln{o$sV`{|t9A}Jq`6kIzZTXx1u~XNXAv8sf}fH2h?R&WnP->}Z_*cmR+}1uTF^N{>u%cuE6wLr6Mh=7U!nvFev;zjTC#ES zb*LFm&quOi(HenT{9MFGsYD!Jno2&PT)6Wyy$wriVSN5d@LCw3zY6=k+ON70 zQS|5)RX-2j&_|*K3FzJ-V)M;0W=_f{{xSES2^Dt-^iMc=jf~G4(a51^!bAxY&>2Al z^h{_3YC&%U5zsSXq67)(j3A;x;Y{j#0Bf^KW z0y~=NjgeQ?u7=cCQ6WidK=A>$$sVKmq_x+WHF6EEshD|`^AZPRl2(Y1QCZN5gJ7IboujVqg_bls!=cHcWL zeE$ROtsWu8{mJ7c)rsiKU&Tl5ktN7a%ZlBwuDmL%`X8AzZOcJvl`l zyy9tPD?C=~_dx>tizwQ@b5LfXuOZeIi!=hY$aDJHYh<%6t58GE-s`l!oGYVMs>y#) zeZic~gPBj)tHs>zvJCkpg&Q~4s^LhGhod@|Ip0WMfjSu=tMsA2|8dn@BTx%wK3%H; zXG3LIdIme}^VRwQkf`4`orAm37Bu2o>c%5`rKJ1eU&l`)Pz$>jY__Ty#!7on^7=-( zv*)c=HLd_)Zwz+B*lf>p&z4WgFUkM4veqYq1a{fb_W*7N$`x5C`_Z6|Mxa)*kY|Ed zA6Kt6bglM(S|n%EINsFjEKq_(HOkoWTJrTezxlFq1O1&Cik<(?JVc-bi4P6-srRPd zmE?+IuI3>!lDb&$UG6DRf&_LX(V94Vv0OvX`Lk*xGy=88R{KZn&+8@A4xCFisui0j zS5d}m`<_7pB}jxd4p7fvSlAFEPSlwt&AXJpigaoOYBhi7tDbZEKM{-b`N)qHL7oow z5-33;-G|CoZMLu?gJf^IA5{}A)(F(1Y^{jTqp*$oz2qCZ zR*M%e7AQdiJJ)ICvZriCodbDm=mcu%y`10e?PM4c_lkuIlpuk<_4JkhSst?cH%}|) z^~D;2TG-b~bJt^@db?&urq?yV)8i_lNT?!G#zJuXK^eA4>dbsx$~^sw{w~1x#aeGI zYJtZ|#K0cw%^Jt3b6`z6t(OxCe*1yrD0=6Ci29wLn{{Y~8*;g}MxYkze<>YZ3bu%YjrmR6(H-Qo)z&j&i!271=7V>>^hP2ZN z)MB3}J`YQT{c10>H~Bt+bA1F#kiZ^s`YulA`!y2L&UtRh9#O}#ski=WOxsB_uGSjf zUukcY6|a}F^UhhI#4h^xW=UQ~6riu;-`!>kUGj^_GpM`0OUX&H$f;vQOuKx{<)Fyx z+UxVxvmk(thF+mHy2KrMat%s7_OI6$3% z@0#q_<`ojjV~d;r{p%&$xIG{nLoV#HN6-paxN@XM=vu$#7`+RSK8tYBZ2xNX6j+Og z%xxs^vAoyP&Pp~eq%AN0A}^!e*=YhLNI;&N2xpoOBAP~?Klu`kKrP;td6v*#OvIe{ zT==fKs{~4rz;}D8->1M}@tJCO9j2|&2-M)dy3r4;Lswg8PrT zhD2S*L<~H{KGS-Q7-v@~0 z3N$;h;Tqx?%GuXs!s79cc{=ReW^C2SlEsE~ebrmQ< z0y{S8yUruRMc(6{R`&y4Gy=8wT{zAyab=ml$?;*WG2pq=dKFyX;N3U=eOJstYrS#w z&E=9dar``Wg*}|Dy&I05ReCp7I%ODoFLex9?{Che?v z?~Z?yQ9DC=r(vIms6hMq&c?5`9xo*LZ4}Pd(!NeMl6@a4&JUpXiVma~c)Z%v*IdjKVE!qcHED?!l z?v6>+PM`#dL`hG{Dgi!njvM#s&!E2{v4Xxi@E~Gs{& z9ZP?EdD{|=KrQb2xJ&Aa^vxZntG0xTChbBsp;QmUEamdFbBI%G`q78X{x$|XG zotFs`B-q=F&#(~To^6`wXQy|5GM7+(V1fh*y_Q+n0&u^n7H=+Dju)i#^KtyblqvH&zLg zB9^dRU6ikxAVGq?J@)#@VvY z`glLF)12A(H5;un54=Glz)#c&)B^8}h|~|`{KN^3d?ZScI7)uvUGfu4RP`s~;PwD< zoZj><)O(yppq74h+YJd4g~^ATv~Zkut&m_3pLaF#>&Zs9R|`cWTB+SB$Arg1Eq#`J zIQQ5%7)D*i6RTp~D*h^w>iM$&ks?5(O zDpG!TX1U=Sfm#sn&^S`fDleK*cEte4?kg8Bdk zg=qw8@zXNI!(VOzS84m8} z>d`L=5R|1b&tOIg1pKtK+Fh|6o57_;aZJY$d62-KQ+r?}bg zq?bIC`T-GnOouU%Jb-HZBP2?YfE)l39pfYVER`cQLf48a8lPt(0hC`#NI=es zh`Wj7vQZninHqsw9v!;dvrslF$;o3xTySo1WurB*R7{ja2@;g0FygZxL?k*QeH zjeR(NGn?KrZ53#Gab`Q&8xtjv-~a9FdjrDnntRFX%XHqZ{J?}`K_1`1-X8mQ{DwLC z?Tx;f(Nmn3d(ke+4@{6Cp?|M$=3lwx;f_wLeVTC^fm)OURFyccyV2kOm|a{}EAO=S zCYr&uxt|gwxH~WY9V|Mlo1GnU7rp<{Jk1=9KrNpftHoLRUdG(s^i5Vzd-+^$D`*HU6t_<-R(k z2l>?3do0rk)PgS_5dqac2^Bu9;|Zv-5z&sSeIu#b_c_^gi4yYR5~_$IPs~h_W$I+< zIe#e;DU*zn)5v?xe>YGgPz%RL@yGemav{|RyYvdy#(@O;Zt>Y#va#@eKRJfh-D+i* zXas8McW|Z{F2B(oED#i;-47%vx2$TyTmh!Py5Q<5+tVyrRc*0Gpcc+I>gCKdTfWRp z&-sEn+V{xV`-;z538)W~jTMO(%Rc1ET9u`O z_+f*;hZ5q`}`w-E=9^$n)}s`uCIhqA0_XcYA)L@)vqPDpMv+f<*hHClp<6 z;#MNwhbJ@G#=WAK?RYHITA%HmvJo<1H4&92mNlx8jqo&y4U`~pz3MGxV{fvBMAV<< zu59=w*=t7vwR|2Y7CgTBy{8c|;?fK?a%ayx#*@n3ly(2EZo+x0xjJr(b)Su$SpwC+ zXShz=ziso~D0@{ps~-95Xc8pyPo1LZ{E^Sd#)WsAm5nZ~GHV2CU7Wi?+4zzBB@ufA zpV@ijJ^rae9?>re5?dFCDjWZ;zDmS@r%o#y6<)Y$1Zv@(rOHp*)avR!{!+%IL|cXsjnyRS}evh)3D6u>>g zqXRbA;E_L>+R;D>68Y9GxAUw#xFs18|K5C~Y<%}Dp%JJxu1GF*bw9jLOT^2pLS5Y^ zgWDP?L1L9pIyLepeG(I~?odN@b*t|wtP!Y%vxmMqlz&c~jrPs7d4)v!icORa=hQEB zbq}QpxAV7(Z$>xL2-LzkMwy9eXZG<-Y_&}Px-nkq%_(cS_*%6NOHSh$c%g6v-;cR> zN*O3YqHg+DF1{Zf=4K>fM5X5ud_U3$chCsby6C#0Y}o20C1Tt7cgjZ0m=Xp`ka#!# zjk3}0JNH25JJ7|&HlEFCtr4hIsYDr*$I&4TKZ9pxHgfSelC3Ljpah9gQw)>G@w9Jh zBE~HWcJX?ZWn@#0KrQ&DG~JJ&ZBvvD|3C8?C_w_gHcd9*`_vkNTJWuEvT<gmKN&aM{iFUp-!py}Ko&fs&T8pNH%)?sZTLP#`}^_V zsB+7j!Q@%ewNxREK&|3QEoI}3%_3rFr5DOZrc)!BTDP!@Z&+52?cQ!XRtWU1~{bv24L>#Ks(B#?vwZuj{N|0F4_oJc< zzUTS<$eByoxbbYBMxa*x{@>JD-CnnVh<2lDnLMxVmOXAq2@?GdJyJFXjSnCq!+LjR zW8#KA8i87Ko;_AJob&lFP6cMJsB8o^_-IE761#6*P&TTi;$7{);bh82>I;`N0=4w3 zTdiUtW#iP_^fY&WU3VnTevDQ&rZqFkMhDMa>gwh`kX<8COS`kS`*lmJv*Nni*Si_j zomw+Kwaa*sT=H}G+rLx&qfc}vlXrs~+dfnW!j443@3DDpMC|r0rEIiL_E(MnjbN=@ zu^E)@tM=1GxF6}DMqc{Z?HVY-<90}yOr7DR1{M)3eTyp_e&f?>$3iWfq4d3sXRVcu zVddIua~Fxu^%E%@r61*?t6O?`GqVbf{FujVjX*7&$G@Hrhx;TK%ytvBOgJl(zC-`Z zh6^P~fIT9jG8I)LH(yuQ2-JdW=%Q#MXInM$yE|*UP=W+p1tMlQE~#u>EPo;b3Dkl+ zOGI?{j><;r@B1Q9f&|=6B4A$aLjtuDe)Fu<)+-mRY9`EZ6P_EoR`7gi5+vYRA;Rm! zH?<~yUh>F=$3iW5{)rg>cTqL+M#a;ZC_w_AU?My(rB+vW=F6ilBv1?1F(TY~MCC%rOCQ6Wi z*oTN46H3_GlNtM0JB>gsh%AV($`rKo$cuC?W}*ZMh<%8-6E;oRNb|b6MxYkNA~f4q zR~eyf#P%v+q67(uipU1UI2wUk5aW;yh|f)wAOZ0?*?{<5BTx(CXtH5uxu-^+xI=Xl zB}hP2OhmcaQEKEb_NOyZf&|3vM64^3!r(iYWL8OyKrM))iLigUrEJvck=R5D5)ii& z0r9y;pccgEL_prhg%TtnS3?BkeM}@!3-U8Wd>m0qjXb?uauX#;Kz@eL>O*RS=kEI@ zM_njE0IEbj7 zt&qA_bH8-e2-I@8rB~PLV69X{jJ?!Sjr{fU(RP#|@w9gm!S_7(_iuKJASV=8Hk#B+ zrxBME6s(q9+1MN7BqFPKDP`kb?XfkGK&>K0GbtN! z-fQ~qos^Azj-oYCf&~A~s)Q(vdW7?qRyHQNt=NYIYJqL?sk3B^v+=R^*a(y$0rrTf z*}9~%@p{2AjX*89>L%5lBigBPJULg$g%Tv-x{-~8tB={M)4RwEZj?Ze%z$qY3h=w= zo}d3W*tm6r@}jNj+o8XFHI3Nj$g94W5t6KqpiZa$ua%8}ZMii9wZNYz8`G|CRyNLm zkHXl%K%z>;O3KEymu1ODjy|aj9!Kw1X*B}1z@H}@7e*gcHX`2tgRy~uM6neOl#P*n zvy+Wl1#&7Ihn{@I*uX$7hych&(WV!b4ac+~6D3IC7es8fDZ7d(8?k%NU~FKZ7Q_Z* zBQnoJWn(~w5hhBI(7#5K>173FL(E%;v4MeF5bu(W<6GY<8%uXp#TZ#5;0w4!gofLd zjZFn6U?hy+$u%H)rKdLArLW3{nDrSWVLKl8a=CHpe#jl=$;Rn@9?Hho#rZS>wIF&W z8$GKh51c{S7Cny`I(hMWwY?gY;#`yo?>dfP8uKqthh!7PaNk!R(QkI$f zIrk#%i}Y2B5T%9ok_a=lj3s2rSjU=FmMq2G&zYfYgD5G=)}|s9C0hMnuhZx1b$)-< z!~6Z5Gk50R&)j=n=lOXr7^{@3XTK^8X;lF8p_mXNvFC zU7VzL$eqYux+A|2#sw(| zkC4|q-XTx8rkY!0dC?zq2Qt(yxh7(bnHR2iYiu}gL7){S>$TjQZU+XJmAA%A_a z#`>|l-QSN!!)kbhcIhW??3c{%@7B1g*EfMyl#o0BVU21RFLP^*?0A(&XqSHS#>~m` zH@G#%?fE&-iV||qL#(l_dbV5Rig(jJLc8>nH}2fB{2aGNx3B*Qw4#Jeki;6V4ruDu zXy2=aM`)LR^2Q#(`!iy^Cf@o^n$e09wH{rXE~!%6N@!Ua*Z!n z7cp8<;_tgE1YF~S?!2qR@RMuuxWGJdV@%jdW|2za-rwv`aq~V-Gp( z)W?Rk6*QhKEYjA6nO~QRa?xtg&oek&wTS@vSR* zgm&p?Tx8pSu5xR{Z+llyS%gY7PsH6CoqoLnYm^;Q-mOu6|5+ZPUHTapCsNE-w?@C> zxq8YXRKlN3`o%TX-5MR6AJ9`4-uzPeWQl8g-^u&k8Z8G8)lZ`yq0@X|3C(Qa)>zfo z>SxYSyX2E4*0_565x2(Et=a`zQ9`Hr;KWw(gj=IZ#_jrfP$!6n`e_NDoy(+IzCONh zZ1wYCQf7{Z&vonLejgiW9l^V$9R=69HJ0u8T0ajawM#$4VM6!uB5sXmpC}&FiV~}8 zzU0>U_Y>r#yzAW>O)Ae!S3I?Atxc=Xt)qQs_)6au}67q8cab1^|ZjBXp)$$1KlHV+d=}-Oce&>T$Rt&YGg#6Ay zd{Q~)*2r(0l~h8zDD-rxjfX05_0Xr8gJJw<<`g&H_XnMzQp;nZTcLN}@HazIo z_`Zkn2jTcA$ z8EQodc@Gbw#eF^88iNl79-&?GNe09{PqcJvy!qiV&1=0ou*+u=5Lwy7?8}{C-j`g< zsYdQjj-0OgPtHVB@yX}yIgR$}j@#&{OQlyn5AhYn)zmgGXqWUQw}=I;5prqyDA6tX7op&$rM0 zpqyKy&U5#9gm&o_6=!SfUE$Wqsxj2NTc{HL$^Okj1v{%nX2IU~hI@o|>77b(3hCUd zY#+Fm`;X7|?qRBgngqDlBxXoA?U7l~_xAqouFt7Eonn$eYI3vjuG(qMwyY0}_sJ|M zlJT5=cG6kTM(<9G`}<6s6P_H4E5q(C9^rM#RU1jeON+v__ro!H7kA{9iW2^vZZBN^ zT*&9{?wkQ0p|#2Ur+-0jvlJ@G-0&@SI5pL|b!w?@q) z*L!Zb60(1ZH4Z(U?$)^Jrk6ZIyZjj=M^}}1YuxbRz23wSC1n2+Yuq>UEJysatgA<8 zm;Vmnq1Juedxr1c{5I5z60#?Y-}(8aXSw$!br)Rg5!&UyFL~*X#YvtV__}EY-AOe{ z$muPtF?H34?%Y!2bqSBqE;&;M!jv6o9_p4^u)6QzQ180`+s&`oGHTLc1hy!5WoY<+$h7xf4cc664KH@bBExFl(S&5G& z&bf775PiDcz<{X`<;eB2COJwoWE!)ZcK2`^1JVLwVIuGK} zyR+QyW9z}IjaHP9zfmBT9JfV@%+*@ZjFZNj~T5fA%CMl?0xW3x5lO?@AL@mlIuK(dvsf6C`55Dt{e+9>2VV}Et zFy{@p87#cUFV8P)2VULF_8u@nr*`4HTKUR1LE`buf?1}ok-uslA=AJ>$doaU&@TDp z4Pw~sYl7Oif62ZoL-iB3n{OXYFS8vs?Ft_m-P_J6F(1TVCnp9+`(c*pC%rvFyX5^N zhj$A@5{C zF*^0sZkjSu&;k3F&$ z#C7F1gxQ#Px8T`9hPyY>o_bK_vJszQ5@`)bAt?#ATINtm0za~>BgYfl{`s{4wlQ)QxGmBe3cmJ;1 z)g!b^_8&mJlTpv|dG*o3K}IV|$PNOCZ`xeu)|isl#v`;#_EA7Qn0Av}$zAU?FhPQ_n?J$QcUGzYxjab0``_>&#lfBl->j#t#TJ?4a3Q9_d@ zO!K&XvU}tmA9}(gv`eNV1Zin4dkl0x-PgaX>dl)_LK8FGMKGM|)=0Krk<_oHT{`6f zcli4RcbLVq{kiVNlUh+ilRtR$fBn10mp6BhDWP4mHr`(?dHCNoMz&uO(~1(Z9^O-z zIcJJ{99sw77AT=z@>9ne&1z=3$8lcIyY)BaC9d*w1F^0P?xTc9eonQK9-&>bw+!OC z<)>U?GGTBP-H-M%VaYi`d_S$3OR(xy7$4KGrCpLVg6LDdmOER!uTB%qAVVemld=c8 zwsB``8ypzy5!xl^p0UQ9mmaY@e;ZKn=Y?ZTy_t*5Z#hG4m-Tz>n70<2hdvx?-)i%v zT{G_u^JC#)YlDq=eH{Mk8QTPRO5gj%Sfdps7S5S(ZtpPI*2?E!gMTLUvmx#Y`1{Y} zJwm&t{4(Es^y*;y?yhwp{&&?7TMPFJyX%~BMk`7*UpUotc{J1FzaTod>}_18+VQzG{k5{iDhZa&BRNG*{+G7K)lnX zm3a@dmM?gOc6HqLp2@77ZO>}? z7l^G_HnO|#$}IR{(9=dMO58JRr5STuwyja~G>E%))VGi0J@tA2Jnj+N72m$n)M%e= zldDK{>E1uwh`WV8_Ut>s&I5&RM%C-ToSz?#+vX-0JpE^_{QK5ybN^mxA15L--FU=J zwc2<1@<1y}^!WQ1NB3@61;mAK4GuSBjjO_i9-&-WU$ znwK8%2<@uAE6;4-nr%1UT?|C#z^eAqXEF=2E8K6iqQvCcNi+7ZY(#LL~!x6cj9ET~g>yU~gg<>uy_E2a#$iw=|mQR#_N z_QYts1GxKokI=4V>+;RoshB2s0e`x0?k{Q|&dDsudBhm4DDmOye3Qr>ZcANA;(}AB z!&j!^o;5bzBeW~``vP;rr^D?-#mj(r{@UYV!`Cq{_1mkAR+LybZ;dH(#R&WHdFO$+ zp~*L4ttFWSt*@@_5!zMn=o*u3Fv32ONupzyZQ&bXX2G#PFEUzD;>fQbxaZZb-^+v8 ze0f25JtmoD?>pCMMTv*1tursp9bxB}stBU*8!N&gTQDfGe6e{iqj*V@Ezt%!5Z3$6+lR~`5Nc+_@iPSto$rIB{)%Y`5w zA2%xOhil2HtTzI^X6Uu#q33>Zzw_fW`5HWaq*VCMAIR07s~TuUiR9GN?s_%0D1YZC zJ5LJBVU1-k&+-WE8oc#)w+8-;?`q73a^X&_@kfbrfmW3Gy!bipG2y>hqfXPiD08$MAw{=kCacJuG~c;wqR zHMhCban||Ce*aj;V9_`w;&Z65BciQiyWV4t3h46;^Hql9*yTd{P!DXyZ=uP5<$ zpSZ0zDYM|GRmF@}l*njVDn4V_aNDjmi7#hgXU}^zvtY{4XM2QpRX$K6eo4#Ww%m`r z&*{MpH`}qpGYf9{t&Gu%61lBQ#2;%g++H(`#DPtB*?;=u6aDZC9-&=#cPbYDa9g$= zwkHq7RrT++n_mEN*+oXXYTQ&TzHLjktqG0IC#Fq#z@EZB^&i8k8LcR>{?@d3%ZIaV zowBR2#6<(H+ny$~pyiJ-kI=3@V~&|mZX0I5dx!HTcGkko4crg8Z}pZ&D@uG( z@h5Zl#l!5hUzdS6f6E~Id_!E}7Pa;W?OI;)sClf!F#F@1BxXJ{#5SsvSy1ftwRr*6ANCp$L}Vw<-jo8u}Wsa&13KM z2<`go`ESgQdN12ruPp&Fzu9p61@1f8?xX)1ttgRp;v3Vd38vM)N8;8JBkkE`GYhWo zbFW8e*QBHSP0jr{7c^!u*Z6j%ty~Ie#upuoSCOy#%R~FjcstbYtW2US?(E$g_vLKd zsTtiPiX0)sK^`Ds6*AKCO?S9MpMAx5R zwO`!nr|`Z*BW9U`gj3| z2Xn^T9hkj5u=Wc^D@shSwb2~fFxcLi`v!<2zmKdT5;~Jz=md@h4M&Cwot@i}Cq9_u-d}c3pgUow)*CEqYfs zCO0S3e)k87!$(Hj2S6;jYqZgd5;d1hGgnW_wDV4pxcaOy_7)Jq4L+e=Wy(!AtKP`8 zn=4EMv9-b&n*m~bFxqHEiK$mlH?tOH+K!i!sF*RvRswNdZJ*Gt6YozqCpKoL|MS>&KA34c_am`#${1S! zV$0!Ij8>HR8#9eAIFV@wj3LqUt1)&ch&ly6p-rdfZDqqmH;O+k$7{fg0w5}zbznt63Gk*yXdHErlK)?Nsr``tdFU75iw z)1gV09egW^{AFY9uXr4d>%C&MqJ+(#Wm>k(vL8G{V%Cpi?M@IM{5{GewCj$Uv(5Iq zvuuTBBtE?6Rl5qrfz_joR+JdMc8+=V=`1_7B!5=(o_p2K29Z77C$y`|S#wQ?7qaZ@ zRY?4_@Krk=#IFC1GFnmMg$;Af_1RhW>~(7BkD@rsdX-&DcgY4RF zB>G=B(f+x4K*7jKgFHgJ&MO_7Pu?D6XI3F`?D~l|xe50qziP12iV{;>TSiT3ji0}2MuA7ZqkM43MCnR8nXvP0JLXVndV)w-=8 zP*CZ`p&p@K`cua}=)N6ix8Qfa;MWmGuQ>X9Zasd1`R!De#nl39oPXtbdjYNt#j{5k zttj#S?zhZm4F}p256%RUGi1E&38HNgpU|#PJG^cBWel_>vq{|a(Rlkgh&%faH(F6* z)K?45xXuIZrawsRE;hlo#9xDqiaw!T4A-|FnaBj4V-cEIH4vT{qk$I-9U%OR7WQhFIV1x$X%v{>K~+V%Vg^Fk&+lRv!x#L=!z z113LhC(kunQR0hN=Z8#wuFa?bV%9Is0wzEEo|@?q+BNs>Wg(NFrD+#}NT1g{VDghz zeumMmr&ccwnf!dYu2Q~FjEbcPOn&N}nryV9M1zZL$mC~lwTrOESC^*;Onx5v>ot$i zuKd^5giL;lT*<^_%$DW>lb^XK#~H0C(e&93A(NjUU*aBe#Wu|YCO_>)jP(fZsy}LD z$mAz~4T+i~#>ANXTyp--;KxI!Lhc){|FS{;fc(am`>@?!NaS}Lv&a4Wygm&rhK+X zXxH}MpM^|*9yxL;h}9om6EOK%RAZ>oiV}&MdqO5ZiN@7H^uDcez~m>p>mZNNt_n}? z4VnD38%$#8>;?gopTgT}MIml!5Lr~YUHBB#iuF(yAtMtu?J zHAAl@l_sXUYf1N${0){I(>8<2kF9fOpcN(FIrNmfUcDFcdeyP8dj^xACtB?F2)`@s zbw00l&bbPNX;5+{lb_dT-5%f$0cR@zpWx$reQIkEQ*L`QkI7H&b(|&fAHn}mb>X`W zxW>PaV@YB6JSIQKD!RuZmH!B==YEF&K91HuRZBAYxhQK7AIBL&yYMq~|NifFx9-%{ zd3+pOuDOjr-7^&>^!J22{C$(1+>SMN*V^e3+NIA*>>AjwUK5*qetF2`XKwEO zMk`9x%smz``Pt>Ji5HZv88Z3#vTaw7(5`2O91EEIjIP8r-mPCNWb$)-$Ad;IN~GU# zG+^?x_AXxA3wPBCnfxs5)x#sS>pJ^wz~pCegUdmTEPiFk$PbwO+}M-v$m;B99y0m4^W=Ds(60Ecc>$B31%oPs_@za9$mC~J zpB$qVC8j*GG+^>G|D8%8K0V$%Wb)JY^i+?~u8y_e4w(F0eG7BvbMI*$GWn@HHP>iG ziAnMK0h6B=wfTPclF7|NCODXdG_Oxx(!1nKNs&@&Mvvlb=1N zEQrh7Ul}s_*>&p@qZK6%t{)mO`S~cDXIOroTsLI$)BgUY9-&>u+F<$+KK0%EK2!a} zx6}!l{48v_%xFc4%i0YJnEdQ2AW`|5+98vl*Eactc1>M9Fktd?a2AQ_%WH;Aey%87 zZnUDrfkdx>$k-{CO<_w@zeIF8`DB2KSTGfG1_%&kGcVqpG(o@6Nh{Kon-QJ zaohKeR+MOaZS8=`&(f+~qxp(Il1zTyLsp}Nc0JqR@_@-t<|ytOl$muR$>gU}Gx)#(TWn^%xaa+ z>-*V)AqE zW}ncmBkPN2F!_m{zYj#=<}X$;`C0pMq0x#GX={pPF!|Y9ghbsBisv!;*|ygww5wz1 z#u-e0<}W3&K9`gNzR9+<)8XYLpKt-r=U`I&i4eoCLe$!JB1?5k#HF!?FF;Y+M>N8{0XOn%ZX z@(Jx4-DznClb^eSuRx5hFf)(I&oftSGFnlh^UU`%nEbr3j6}bW-pOO~GqS!EK$yM8*qYK+OxrqTyMT=!yfJT?cnEX`gPNKu+a&C z%jeZI)v70%{4{Lr6WXQE(6qFP{bnSY{Oq5w(RA#vG{)qo^b0@RX4Bt~G5MK(*KvFA zyp1s?KXXnW#~RBUyqRS3Q>@BHqZK83l=&vc6;G}+T2bQq4~hp&etJ*)1H^&&CrKth*MH*^+O^vj37Gt> zUBPpfb91&NnfzSQcD>Px5|71B#F+eiUj7t_aU(xSGWlt_%O|wUf8?!iOD388ti5A{ z(TWlsf8G~k@?(b69=Q1Mk|dL#aGOtPm;Tf-)oRi;NhUw#s%oK%6>vaFWSS znf*8_fWRl5G&1-!^yYy9%me%&f*d&vm$4cX`fxJGHnALr0 zjLFZAK0jlPUL_|dnf%%-&+?vK&$T?x8AOn%_#;Jc#h!{i6e00=hnKH}gOtPu=Hp2a>1m>H6^B zVfcWc>%-&+?oUiBO5psqqj`QGXN2MUF!_P|6DXlwbbYwSzh}>#>x1M6?vK&$S04vm zA0|IAe6R*xA0|I=e~ea?pzFir2aXO1x;{*P;Qn}ocG2}=@&m&M1YI8{KX8AHR+OOY z!{i5!4hXtFOn%`0c!YM*^e0JVLwZ`Y`!{;RAxM50f9bKY>=1fK}k0SF~X88{BuUVe$j_hxWjk ziV}2vnEb%e0YTS?$q(EgkI*iC-M}k?>%-&+?vMA1Qi84zlOI?;Sc9$)lOMQ09-&?O z>cT8jxIRpN;Qko8K1_aK?Bw%N@>RsgM%RbQ4{QkR0nqhf@&otBXoap1lOLEo`TCXc zeiyC}lOMQ0-Wp2K^?ooAD9>*==w1Ef%_BVwSre1UKM!N z;s5hd)AeEU1H%IZT^}YtaDV8SoVjM`wS=w@e+vJ)GIV{I{J{O8`EsVB1YIAl_pd8M z*N4du+#iq7F1kKk<6q~8t`8FvxIZ*_&Qz43>%%qvb$;mjF!_P|;}P1$@1JY%yT+$& zxIRpN;Qr7=I#W@C-#^#jy0|kQTpuPsaDO~PyLi3j8vI#e4Y)ph9B_YVRGq0Pp}!}1 zMR0wX{J{P32<_5mWm+0tA0|I=e*s4I*`Y`!{`{NPXrO#=+XMpR&_6F==w1Ef#Cy!t`CzRxIacKO3?LT@&jK71YI8{KX8AHcG2}= z@&l8{*+KsibbXlo!2L1$wUoeFUd!YMjt%-&+?vF=k7hNAFKQMei(Dh;R1NX;h zMG3k-On%_#fS~Kce0JVLwZ`Y`!{;RAxM50f9bKSnD`(Dh;R14jo0 zT^}YtaDO~PyXg8b`GMgBg02sfAGkk8D@xGyVe$h<2LxRoCO>e0JVLwZ`Y`!{;RAxM z50f9bKSnD`(DiZ7k26N-`Y`!{`{NPXMc0SP4-6lyLDz@L58NN46(#8UF!_Of1A?v( zlOMQ09-&=yeVF{fz5zkkhsh7zA4AuN$q!!}bbXlo;3U3teVF{f-2g$?hsh7zAERHF zt`CzRp3V2ypzFir2kwv2iV}2vnEb%e!5VaZnEb%~@d)jr>%-&+h7Sn3K1_b#{ur$& zLDz@L4;&p3bbXlo!2R(E?V{_$%-&+h7Sn3K1_b#{ur$&LDz@L4;&p3bbXlo!2R(E?V{_$j{$|7(Q5ot`CzRxIacKO3?LT@&iW)1YI8{KX89M zLc8etxa6k;O>eqBOn%`07_BHl*N4du932pJeVF{f{qYFxqU*!t2Zj#_x;{*P;Qkn` zC_&eU$qyVI5OjT*{J{P32<_5W0seBr^e0l3G!Mt`FZi;r%-&+ zCXe@+;IY8e0JVLwZ z`Y`!{O9O(g50f9bKS{bi+y#WG5b(4;_Yisdo~{r79fl7Gx;{*P;Qr)kMG3k-qPnxHt(e_XGPbC$q(EgkI*i< zK1_aK_<*46!{i6xeVF{fxG~71;QBE6f&1eT z+C|rg$qx)45OjT*{J{MQwW0*=7e24(3c%We>%-&+?oX%{CFuGv`GKPYg02sfAGkkB zCA3RlH~1U{*N4du+#l~1r376cCO@!xum)Y9^N{?&{qYFx(pMMusp0xC`GNZr(Dh;R z17pXTP0^!ut`CzR*bo+<=;8V>`GNZr&;m+T==w1Efyv{nq10Exz7Jde0yfu`d z>%-&+W<-bt3$727AGkjrp?pXz~2u1 z<)rJw#02h7bFC;r*N1ETOVIUU@&orLLkaDY?-oBRx;{*P;QnN2MG09C1YI8{KX89y zN@$n-3_;NK;p3<~b#;bTl#rhr2)aH@e&GJZl+Z4D-QdyF^iKBwWn!u4VD1NSG;XPiD0>H0AFf#HM4LDz@L58R(XD@xGyVe$h<2LxRo zm;98j=@HsR*N4du3?C45eVF{f{Ry<91YI8{KX7zF(Dh;R1NX-xw2Q6}lOGs9An5uq z`GNZrXhjLSK1_b#>wuu^!{i6uaAn5uq`GNc65!yx9hsh6o9T0SV znEb%~3ACaFT^}YtFm6E5^?oo9~eF$==w1Ef%_9^MG3k-OnzYafS~Kc z%-&+h7Sn3K1_b#{sdZ4g02sfA2>Q7==w1Ef&1eT+C|rg$qx)45OjT* z{J{MQw4wxEA0|I=bU@JcVe$j_$0M|ht`CzR7(O8A`Y`!{`x9tI3A#Q^e&FkXpzFir z2kwtYXct`{<~Ze0Vp>sxt`CzRI67E^t`CzR zxIZ4DU37hz{J`)5LDz@L58R)aR+OOY!{i5!4hXtFOn%`0c!YM*^e0n$z`R@&os0rS4zQ^s>r7;M)K1_b#{-kR~3A#Q^e&FbUpzFir2kwtYXct`{ zCO_6F==w1Ef#Cy!t`CzRxIgJyQG%`y zlOH%bAn5uq`GNc65!yx9hsh5NpFG^*53UcBAGkm1T2X?o50f8QJs{}%F!_P|lc9um z(e+{S)3I}75OjT*{J{Om(25dteVF{fz5zkkhsh7zACJ&3x;{*PVBdhC>%-&+?oW)a z50f99pHI^DVe*5M_({4x+|!4uUeVF{f{mIa;OV@|V4@{mse+{}mOn%`0WN1YR zx;{*P;OOAHqU*!t2kwtYXct`{CO_6F z==w1Ef#E{}t`CzRxIY?oo9~eF$==w1Ef%}u8 z6(#8UF!_O_1A?v(QyI8FF(tH%t`CzR7(O8A`Y`!{`xDcO63+EO@&iW)1YIAl0r$rv zw99{%(Dh;R1NSGU6(#8UF!_PigEi>-F!_P|;}P1W&rqDdg6qTN2kuXdt`CzRxD83V zKFo1oCnV|mFyDb|!bc9*hsh7zpO{vZpzFir2c8QEx;{*P>U_R0rdMRWQq%Qe@&m&M zS8BRGOn%`0#I&LWT^}YtaCAV>^?oo9~eF$==w1Ef%_BFiV}2vnEb%e z!Q-Io!{i6i|H$e3F!_P|6Vr+kbbXlo!0N#obbXlo!2R(E?b4rmS{hv+CO>e0 zVtU2V-!okwCO`0Xum)WpCO>e0Vp>sxt`CzRI65Hc`Y`!{`{NPXMc0SP4-6j=bbXlo z!2OA7MG3k-On%_#fS~Kce0yw`^kbbXlo!0N#obbXlo!2R(E?b6qZoAcw6AGklx^@-;E zaE^^LcwobDHjguVVE7m$yl{P({J{Nj77#NbR+OOY6V3SnLDwgm^WzcPMb{^q^8f&1gkCgxmxv`WzRiRS!Z4Z1!| ze&GIigm%&OiRS!(pz9OO`EeFds-gs4pJ>hx2)aIWe&GIigm%&OVe$iC2LxRoCO>e0 zoHvyET6BG)IX|4uBLrQaXwHxGhEiWk3A#SfoFA+~*N4du+#iq7F1kKUeqi{3pz9OO z`EeFds-gs4pJ>hx2)aH@e&GIigm%&OVe$i)1_WK7XwFZFc_r?YHynnzoVt(G^>I6? z`_7HKIX^KbKX89SttcVqw?WYLiRS!xgm%dZa}acWnEb%~ac)xT`_;!m*C(3u1A?wk zH0Q@zK&grnbbX>ZKOpG(M00*TLc8etM00*X(Dh;R1NX;SK&grnbbXloz|jFg*C(3u z;}P0L*C(3u1A?v(lOMQ0&H_qRl%VUwXqhASY!1amd{CI09LDz@L56lRxLDwgm^WzcPMb{^q^8<`GNZrYDEcgj6l%!iRS!x zgm#HH1%j>*9|zo@q*j#B-;KaDPIrDB=Ik>H0)-emp|E z^f~S3{J7)??oX)CIDID4^@-;E;E~hyVe$j_C)A1(bbX>ZKOpG(F!_P|X5OjT_IX}(!Ag>l4lS0YTS?$q(EgkI*iX z5OjT_IX@nuU37h-IX@ui`b2YnoCTDsC_&eU$q#%T5OjT_IX})cO07=UCz|ua**rqf z^X5OjT_ zIX@nuU37h-IX@ui`b2YnoCTDsC_&dJn)3sKu1_@Q$0M|hu1_@Q2LxRoCO>e0oa@8n z2kwv2{R_H2(VQO;bbX>ZKOUi7bbX>ZKOpG(M00+e1(d2NLDwgm^8h+R_6))XwDC(`N$e{eWE!(&NND`t^{2lCO>d=um)Y9XwHvE zXct|dXwDA^x<1jIA7=rjDoW7xiRS!(pz9OO`SA$tqU#gQ`2j)Khsh7zA7=rjDoW7x ziRS!(pz9OO`SA$tqU*!t2Zj#_x<1jIA7=rjDoW7xiRS!(pzFg_2JVkXXct|dXwDA^ zx<1jIA7=rjDoQxl=ifO$An5vV4Y)rZpKW?h{J7)??vHbQqB%c?t`CzR*a@8Gl4lSaTZXjq6A%^XwDA^x;{*P;Qn}ocG2}= z@&m&M1YI8{KX8AX1(d2NLDwgm^8KGB>XkI*iXd{=aRnEb%~@d)jr>%)8ph7Sn3KGB>XX91-uO3?LTS_5AP1YI8{ zKX89MLc8etFs*^F1A?v(lOMQ0&KpX7ExJC@oS(Q)(DjMt{5WqY^|h3s>l4lS!5VaZ znEb%~@d)jr>%)8ph7Sn3KGB>XX91-uO3?L*=KO%5>%-&+?vF=k7hNAFDR5~((DjMt z{DgFUxEBtGAuf|P;&grZ@9=d%(Dh;R1NSG?iV`xj0R&y2XwHvEXqQZt072J>$q(Eg z=O(4TUws^OeVFgS@Bu;BCz|u)ETB|H3A#SfoF5Q$eWE!(9-&=yeVFgS@Bu;Bhsh7z zA7=rjDoS7;PvD%N#??U3^@-;Ec!YM*^%)8ph7Sn3J`W@Lf&1eupj1T(x<1jI9}skXqB%bvpl4lS@d)jr>%)8ph7Sn3K1_b#{x}OLRZ&9bf`Fjw6V3T? z77(A+@DAci(DjMt{D7eA6V3VY2<_6>jhpk6r1Jy!$JukKSCkTTeWE!(Sc9$)lOMQ0 z-fK|1^ws6&{J6Wl!ToWr50f9bKXE)-m(lVu(e+{S0~-Qs(DjMt{5T6JRiWz>&H0Jb z8cKa7H|NLQ?G5gaw}ujQeVF{fjKCUneWE!(9-&=yeWE!(An5uq`GNbB#MK}*8;n;U zch@qwKXJM~OnzW^fS~IW&G`xSnxWScnP~%pu1_@QC)A1(GRFo4U7u*qk4N}jV{7p@ z3ttC>bA6DQ!2Q9Qr2i^Dv7{EAA2>Q7==w1Ef&1eTu$sIX@nuUHYta zbADoUe&GIK(%yg1S0()4IbEM<&JSOMXP)8ORLDwgm^WzcPMc0RE4SXFC zbbX>ZKh7IUeJ#2^(VU;SPtf&Y@&otBc|)nMr377{XwDDTpzFir2kwtYXct`{<~uNa zK+yGJ@&otBSwN|Z5_El-{J_xxLDwgm^WzcPMc0S<4h$aZKh6S5Rg|FX!{i5! z4hXtF(VQQT&@Q?@%y(e;fS~KcjHvw%_+CFuGv-+|!+g04?A=f_zl4lSaTZXj zq6A$ZrZw<&K+yGx=KOescG2}=S_5AP1YMtK&X4nkQeTU%50f95JaM0(>l4lSao$ks zYbin3Cz|tvHR$?8bACKRyXg8b-+|!+g02sfAGklx0!mespzFiz1@;XHx<1jIACJ&3 zx<1TzVEBNb>l4lSaTZXjq6A$ZrZw<&K+yGx=KMI*D789WpJ>ic+$ZSzF!_P|*feWE!(9-&>B=Cg|V4h$aZKUOPB(DjMt{D7eA6V3VY2<@Wl z!+ZyZ4+y$G(VQP=0i`NR(DjMt{D7eA6V3VY2<@Wl!+ZyZ4+y$GOn%`0I14CMQG%{d zH0K8dT^}YtaDO~PyXg8b-+`|Kg04?A=f_zH08xfqeslt`CzRxIZ4DU37hzy}-T!LDwgm^W$6}?yKYcyrJvE zeOR2t=bV-#ckbbCfS~KcZKUjmV50f9bKOUi7w9!(}P&el%7R~u_t`GOTVLceSK1_aKCm6au%y;0LU=6xH zOn%`0I14CMQG%`yQx148An5u;bAFtCnYtqDm71;(^BovIAn5u;bAFr!l&UB}*C(3u z1A?v(lOMQ09-&=yeVFgS@Bu;Bhsh7zA7=rjDoW7xiRS!(pz9OO`SA$t@*g=}pJ>jH z^Pf^b6D8>SM00+y23?l4lSadu(qile`0x<1TzVEAASx<1jIA7=rj zDoW7xiRS!(pz9OO`SA$tqU#gQ`2j)KCz|u)ETB|H3A#SfoF5Q$eWE!(9-&=yeVFgS z@Bu;Bhsh7zA7=rjDoW7xiRS!(pz9OO`SA$tqVbk`72s|QaDABk!2R)FA4<^miRS!Z z4Z1!|e&GIigm&p`1sOd~EMxyFffLM0o=h(D<{X|>rZ-_~e>sOInBzEM?EW7oTk($U z)$%nkmmxE;yxYF8)B9!P>95T;`wp!(m{t*Qv}U%!*>=N|@V(xhZEzkP-xbfbW0y05 zbMB#5l)wqvc+K~PI-se>r3#Iw^o$E zd2z$vAph%5lDo&jljKTh7r%f0r1?F#)9NAiEECILo)v0E34Z@vgX_8z@gep_6PSkK z5!&THcX8@I#NKNH6E{MwD8Xk3*Wk|&cM)vgI-G*vd9TNZdW3fA>n1I2_|Q4wue&l6 z_r395s1+snEaw`0c4EK1$BYoWg9)4u_XzEx{cz}?*|Z@*U{*>9Zz5sttLVIlRK+9U zQEXW_n>GXp%t{Hdd!B$l;SsbgQeBvWVut69Zz2JI0`}#96(#6PJoDsi zgVW_8etNQ={o(D*M8(T~@U9H{n#bInc;2J44J;cxOE6K#B4bIwvI(`K1g7i6mo=Vk zVBCPf)EXPz#IZW0||Ll z;=(6Nd4zUhj#2!Isk02MClIupka;CwJz1?NL6hpNv9k;eD6a8+dy8Bx0kg^@vu+TtY z;*>=OnJD#34XYI;Fn!7t`*Nm%kp{w2)v zOstrFw{t~zJurh-DW|iUB{Opk>`#N4apv>?&7en$H41+oYS&cHOw1c`o7IXEx^`Mx zqth?jahGH!ik-Z}BeV-M1x=4DXBbQt zDrY4-h3MUS*LRBtAa!j7Mk}=FOPggEI~66cDsgkWD1I zS9-!~MF~u$F)MzbX<(}0uR&E9FUUUEStDbU}}#=j+21NW3{3Lrumq?t7jQ_Kv?6;;T0^hqQt>XcX@<%(Lj22$1DRQ z3B=7XkdQ|ue%NrcbCXgPB`}G|l)rekft>_m8Z0MdUI|!F9-&>Bm1N$;Up1IjAdapo zW|6BUU{+bJD1nJerV|KQRv>6=A-hY!-tq|T!ptYLBbaUAfq|eAmODK&0Yl7cMG61! zIju8fkO@qj@(At1Br4OW_iO_@4QpUpT8R8S0fW+NMG1ZXfV)5~YHgAHB+lD1$a}V9 zf{)odIoH7VG5Wf}KHLL0StLIRxIf-2N(oH!F-7jmHE@6M+{K(9i{vK(_s1i&3-fr) zViv83v9Hh{mltTO>aTxIb1a zN?@9g*;{{xf%^jjbABw6p9I_=kI*j6<1tM@z|jFg*9XZ@0`8C1iV~RSV?M4q!@&Ik zfjK`G$xj0Ak4I=1U7vS9n{HtBfWVv|i{vK(_s3a4sfrSGeYQR`ohA>6^KhCNdrOIH zKbv524|Q{G+bIU;Dmf#->>oFUCyEVE7C$g>3eOFLz$5{Sy`=ty;9Ab74FyPS!=+2gEsVWx#? ziY}aU=d24Ms>~W`v6Gs>S$cPNKJ~SfzzhxZ{56w#t{!W2#rb^f)+TUX-y^gOQ$Eat z^(GrQ0U&<;bEL(NZ~{(%)ru0B1!7iRJlVhx071`yYrs432<@WFu(i}=1GfPL=9pOQ zY$xD0ILjebQ35kfO!2cO8+Z;NFe}Ak_dEfA!XvZ`Q&-Fl2XhP@4G`bK$-oYM;-hO` zwOUaEvsuiF9XSTR1_;c2u}A?D@IX95yD&Y*Y~7e+;F^HITp5d`0XKvnYqg>T{gsPs zj)8Xq0<&u@(u@Rr7LU*_Ou;daypcm^1_b8gSR^J1I5W_0Onr&-Az;pwFsa6&_X9A|1bKX)FB{1R2Tzy}Tf%OIgld~+c)C6og zkI*j6;4&-Q=NK4!ATXWFBCk!r*t1$u0+YH-`~T$_*n1%2Jx5z)!invxeL}nF6E19% zV=zk$1WiNa&Iy=@&NNI_l<+^XVCIWO3Xp&Y;;fp~UrWqIo&>~$*eA>t-vadIF5chqV{2~3kG~(fRNMkI*hm&NFHMOf~RqL13ny#VLyf zJX@<3CHOaXW0h$J&Mk;5OZB%n$&u)_&?mHuM)82!)94F>C<8wjr$rL*g`I1hswjau zfo2j2xWgb8JoJ)XhR^3?UhoO+!X!g;(f!j5yk`)*CiJy9^^&-y!vw1pB{0d*bnZCK zz<~yVIf@o1YZ7p)Jwm%MkpNr*{(Yx2;x`z}!YNayNcfD?S8qOSfk% zP6#DhjUVR`+U37{#mq^IQ%DJT=+0qJy{}b*)_Ro=(+!+-tbw_f7AKt&aNRvZyZram zJh9B=2Pc^GcuJW&@jRoAJJ-Aa=jmdeSY{%GbE;TlVU0QA1nh-x?cFn}6(wj`aA*79 z=_+5AJ;#2(D>ISz!#0o5E}rxzfpf7~gJ%Z0UxG7)A@0T<=Y9!J=mk8B$o&$WA>>`b zR7slxzQ(bH2c_e*e2G1Q6@Jp0J~5}btuf%~4j{gPi>q=#Bjg6Au_UxIUyAljT9 z@AgY@-qItqi)T2wUxG88Ab5t8`z1Kj8EQod+{-=A{Sut-1i^En+%GxsVpEUME}mZH zehJQ|g5X(H?w8C@ZxU)3?n58vehJQ|@^14&;9mD`zvR0+8}pv_XDUkYOfC0IaC#PN zd|PpV+b;<#T;&nk#dEvd6~Q@P5Incb{Sutx4Yi^K?%yBhehJR>f>?yJ!Q3ywSz(XR zE}lQ;ehJPagZOF3gKocMMg3Z#R+PXTf;jg}a5fnP&p5mNlF~IjLc4g5n)@X`nI1MVX23M_lL;+T}mn`&``AS|p=sTgq~R%bC}K z60{$f@8EnmULU`WEMu7!;Y2wnxSS!hOJAGre)?{QrRwBn-s^+sXt~3JbG3oK(%k*@ z-3|-R*m|!)C3vQmJ1jV3i${+8>AM{koU!!??ZSQUAM{koU!!??ZSQUyH1StzAGhg z&s4X=f^!sD1NUNeJ1jV#;St)!GauYX!5I(`JoCXF7MuY|YDEd$`_=8R;5-NjlT+w+ zShjWQ?Gf6AyVJTI7Mx`Pf&13F9TuErNoqw2+{4!Gu;5$^2;3Xj?Xcjyj7Mk}&){$$ z1!rB(g7Y~b&abw~?Xc9Jbd5)77f&2=9|b26LExU`ZifZu z6nP)=GZiIxE|I$;IDrP@Dx4qV4$HIEswcGz_l|ZuEI3cbdrAwzGiuynIaRK5QY%W} zUe#`g1?ShW2G7B9_XFqRJVLv8){Z+YIC}@8C{E{bhXrTvl3Gy$_uO_nEI5Y;g6H|T z#^9VZkI*ij8RR|+&JcpY{leW23(gScX+;U#JKXKC;5;D++>_kxu;84cM`#z%K5~Zz zXCX6?bK>kHcUWrNU6`j8C2$XPx5I*Sksxqyb+^Ov(ns%jgm&=^CwEwIrV|A2-|lu; z##ES@rxhi5PL#VMINu2Z_lS2pENvQ(_6Y6bc~|bR;A|=g+=t%nu;6TJo_66r^lpa* zXH$8%c_B{VyeoHDF1YnR-qZd}MG2n5w<+hM_J=5#j^!R@f%l(a`^7f)Vu9|b3|LGa`?cUW)|dzDs{zyt=j!-7-UATZg% z?Xcjqw?}9fPmpsT1t-cuV0whxVZn*=Ra#L3lO)^@3r?4Vn7*XY?Xcj~x<_aiPr`GD z1?S&EU;M}N3Xcy0-avud}Q~92u?RvMvg0rbfttf$e(z_iNoKpqC z^RC=s!TDE@&@P^-3XbKvFA8(EH#H3p@}InEB#%Sm1#qwW0*(zqlP1I3XY~SH|tI zz%}s*?Q;GKc39xEfWYh;x5EOTC8-r9Fvlj&9TvDPAXeahX53-9cEukappmUhu6;tmV^A`tll*0>#( z+jh#o*j$>$sD$<*TPT_n#+aaW4RO=K!9Rg}-mz3{ZDc7WV}Rcu#>;g?9@`5%Q@I z1ZIG`ld`xkfJbN-W_7xgvhepoG}(QbJ1HApw z-aIKw<68;s!lXy{9n${B9X7J|xRbK9%C({dO?5tU`sr>;r8_B0b6pATq7BczGhEx} zr=`(`AAl34wBxm+1dV&Hfn5pwHK1|N$3X*M3GI@#@l3=-Pj^!GepvomQ9{-OfvKVH zq%7|wpoDhG&kzJAle&|#lW?~JttcTsHxQVM9O51+3EnG33GLE-KbVsfZgJ;D|1P}9 zdwu9LpZDV6c~RV(BXo0k-FeXmwp~Irxw)2@_3O@y;{G2Vp;{2Wl)#K+cU~0tO#v~y>mYYtw9jpgJwm%4!98AhUKICy0kIJGc;R_b-18;SiV~Rh z?9Pkg{x2XfL)x7e#eHQwLc4gc8lD%$y=y>VPPIEPT6J;LKr2dMW_6tBMR6Y+5EF4f z9NZTtf&1flgm&@1K0FnQ`}~05oq%{=v{IYqfmW2@-G+E76n7s2fl1@;yy)mH%>%6{ zfvMwho)^WPh(J8wV3Ip8y61{?kI*j6LXY#jDDIC0VsVWr?!4%4pEeJw^{g1@dC_C< zy&dvyOgt}&do6KhxqMg8J;IM0jXo>3tt&Bu9O6nCG( z8rw_EcjrY{)w(9oiW0gu?)x$84R>Djjq4kGgmz)le4OV+arY^#@z5PJ+&1#|fl{Rc#ogO`QrvBU;tmT7EWS7_yifA$vQOT>=!co_og+EP zWM+~uVLsjb8F%PP4}W z8Lmq0T&C(pv6GoWuvYGP4wEhrpt!%$pD&k`7CF>f_u2Fwy5>qU!!McOhEyzKJ z=k6jqbUiFzj}8)hEVbCw#p)BX&)xuz3_GRpVU~) zK{QfUTOr=(XeaBZ3)R0{tX&ORC;ejmck*{#BxZNt-`Mr1yPUu5>ngT14-mUXM2N6h z&$z$SM2TFLqr{F+nc}VohY1%>drgM(U(xSoa?0<2`#MXZRw2(Kr>LAEK-BBALGJb_ zFVwX^+q+T*v}&XO?pkXpY}8r0QvQWHvVrX@$?)`%;=*6cM0nX!;@s(QQSQhx5!#@* z=+Zhs6H%_lxR2Lm+RNxjtYaxv*Zwnc37@MQuu5P+4&i)I*vB(%lxQEHUicR*?4z!* z^cI!#imbIX_WBQGGcv#NZZ!X}SP+lZK;w$UO*nT{GA3KF*jG3}*2fbqizk}sPU!!8R@svHh;*y*tjb)ls)y!`8+1HM z{F*&ds^_Af51x~pIyFO_x~lMP8*u0Kr*9MelDeGzD^0ZP_e~df=*mj5ywNdhR*sBu z?`nmMr86#A?_ED+6g>UN&3p0AvrSCtQ1?-|a^l#=L%rhEeKd}?!~=&%Gks^3;NV9RI1&bS`m@X-Vl#fDS;Ubg0*rtX`!F)&b0zW!OJV$ z9pAW|!&9xdS;B<6FMWSQy+F(;lS042MEO&?nP4q-_v$I&X@H1M8DS58>+9@LdADqL zHHV12xKcz;PVMt&@Mo)k%22WP>{rqJZIsodXqfo?C>e;D&X2qk;TyaZyjRxQ?_sO< z>OE7{${#4!uk~`VdYBZIZ{iFJwwYqFJsZe$%G!x2R)oj z=;3@$%?1)u`=x3=8BRfOgt;QQ>q^B;#0ND&4)`*ts|&CPcyNGL9o`7Uc060OTMR7 zE8N!a9xs;T4R%_*NV+ox$bA`uMWe6#MB=`E^tg1?o-dle^ONd(#J_k}4L(d18S&LV zU*;!S!o>Vk(=D?eZ4uF-F}C_|s+y6M0&sjZ@=Q%V(;O z`Mi0sC^rD>AUCAvaYC?`y!Mw2M;)ZA##|8VI{Jx@4piN{aK;Epm`E1-T&l0j-BZ=Q zc3T-LR$z4gIKQ4juon9d9v*)#4Hl*FtO7o?l`LUmb<*=PDo?05>=_0dEq1IF;i&h? znysfnu$JkUJnq$1w7`fH8rsFKF|mLiEe{o|tH!1{HAbnC2O~|KY9(rfK)p}a^;QRr zA5W{UaPv6GW1mT+x|B`~xa@L%S((*l2@|!x6^IMWi3-+=_0)Z=?<{(UxSWw`Mi>NZ z@zr{G6z?-tbi_KAN4^7XzIN8)u^nE&Ot+3-mEe3$+X?w#D|#%QL$B2;@8qyIY(Mra4E^D)d z35;gi?^2@>qEX%Agg<)f3o`~71Z$ah9#r_S$by=?Q*%4oEMWqpS)3Zx)VPJyJp5xs z8{EgUUc(H6wb)a`x#7QU6Kmna%_%w2I#@Vk+^?9E)!%u+#%LC&zB@Hmk!>4&$&45= z88#~XI*h$LgTQDOr$#k33SmC@#x0WKeLUk%gt$Eg9Gl9`e zs!>giLfFakQLOm-%-1=udntopEqb$V509f|4vD;YgL&egI9S5Om(JH@AGDIv5AT9V zojp#h#(h+|JKP{xi`y7h#gFag^#h|?y5hfjgs)5Kvk<6m(kmpi)$Ti!n zk&`;6)xD4PdKdS{AnL``5|z+j?P~nS;@@QgqnYln)aZse&h-c}@UE}(xA0bCSed_M zM1wFVq{A42Zq8reQF7^xqv2+l6hI_uwpwO|#{DbFbWiduw#u)Xf z+H4RTcFYl{(YL?tIaaWQ2^!%*ynXz?aj<8j=?1}CG@^o_v6e?+$pnqNAUY+C=fxK< zG6>cxkR?D?%@i!Q|JVnjqE%89PVI8GX%!-ddS;RpyDb%SI|Rrs9ZSfT8<&Yf@55!$ zDYbMzHm_C?2(Mpiij-)(tx}*)j3i8atUgNS$PpwStUUlC;Cov!0z~)vAqK%(e1&Sg zbAJ(ztV|7WRKot}i%2HS`?xiruV{0R7c|XaJwsBkD^ZF&ISZ_0fVQOoR=^u3r^`#l7^WK`baZNPI@kc88e}2Ekg0 z7U-yf8l@2f`18K?Is&UR2MIADAWVLK7b(^j%MuqqX0Kcr8YSLz$QVcdTpWmn&#j9f zE;R8LEMWpZk5s;o@>M)MoU5~o%2=^pzvxhdV6E7tbM;L4&a|7jsw}fBis7g*9lUX- zU*~@?e8tE%VOD%>Ck}eCkE_QaUit)IPQHHZaeW3G>Xj zt9K^qzg;!GaUVDCwy?78LDadwLwpKqt9|OKqe{eeS=U_q)Cc^F#=(Qp{;u*uaKdWc z=GK^Kj34h?D&OX(gbDaRGGVR`V#nQIt>TC?c)V+=JfoiyCg43u6?0I21S&HR_Ov=L zb~!hD_csXEI^>l?E}Ru9vhB|g;_9LK);-ju`uX_@)`AZrl`o>a4U;&!YPq$%w97eu zRD@s&6Eugz`)GV_idCzG%Ng@9${<(^5eqvZVu7oAH^pU5z#A-FB}Th!^YnS>53Qj6Hftjqv|Th=6xtC(NC3RcE?Rx1M3-?6OV@LqY`26G7x(*2J2F zo}qy_Xb`NGJidfI6tlZFo{vEkw|%UM=zSU-iWMwjf@Y8)eoL4S7O5I%5T;hmH3?A) z5ERQ0h?4%4FhLOu5Y3YOFP8CeyKNAxm3Lq_M-*ZiMbDoCF(G=RI~O7o-;N&;EMWrP zg_SUO266I6TKgOByhdHO@;iP?n4lO3h-y|{yA9sQyxjW@g0c3JK29? z?tFEgt^B8-5+*3d0itDe7rPp4cgeXb5+*1T1|sS6w(dQjT+XnuLoEI+)}k00h@kw_82oNk`0@f;wfIqPrSSjd z5r~<07s`mNcpnYwh$j^j`DE=DA=1{_EHNI5ggLo<(fq2usy@kXHd~7ealt%BMi2 zs0CK;;HrLfF$vb<*5l!kBIk1X4H2(IkrRz}#l)Bz8$`7ofg5 zgJ3OgV;&yuTBLHT(fRk|ue~rT`y|A|rHcNl(OHes_nOtve;4>mdB`P~Dr*p|g^}MUA(jE6#gcBaEM^l$8aK9B!i0*_CqzO(OdYjeeoy6c)){-+uJk%g zC=WSu_YJFl#3rFUh8ry82cPYhA?SB+^*?B{gozs$E~6SdP+Tmi z*RizUCyV2qKiR&_AXw|#$DP{7>Pe+xV_CcX@&&%ylkLaYthFH9N0Bot>bedOwM?S% z zH%pjMaedX>K^>JGB}VL(B@s`|Qme0n3DzRpwueXUZBp)qjR)NyI9S4jip;D2O8FF6 z2YKayOocm7^1eJj6PvXL<@hKX;kk7>t*Tyjq&O;s;N6md6m#zyU$$=uWFZMS4wNEXBU@hunKvcT*DpvJZ_T1&M$UW-*O64LE%g}w4 z%0)hTT2B9cZh^`Pm#AA(s@X)+dHZb@nNNsW=*WCRc2P&oRbPTQ1BhBRYDhJk$P{qL zR`K+IB`TKxFM%k9?n@BY0I_GWCDm-=%)QGtOPD|g(a&MWwLTGIN`AF7MadWA<^9fBQRSUQWkY}d*5PO0g_=!-^;#@U;-8dDVVFDw+_5jov zj~xAmFj)<=i5)qAQ+eQ@5+>k}=LMtlAnb zF3e5r^B{GA=rt@t4D0FXqjE$E@e&`bypMip@55{&^JRx*3DsrzsGO9VGa%yxqG+py z_7pXnNcPrd2@_NS0m46j5?jqC)|G2+5UfS@6CgaZ@0Tgjb|+s6RgvbO;{=Z%+~*?> zcUH<)@Dl?H>@)gyCSL4Eo*wlqC2oJlXpnU3DmlK8%b95RN`qi6?zOR2AK&?53%k%J z4l~9mCJuRK@KH~_OY1^-AHy?EmQ}~QoZH^bGYHn=e%{05eBqAr+)|fw)1?@@+tBV} z*zCpP%LWa$RPdyzdYW8``ET`lJp&h9eb-Ewpqf&_rT@Cg$z;Z z^0z^xyEj0V$BNvh??ViNwLa$?rEQ%4FbKrF$17#-SIC&8sw=tYMATU%M4frgfIIJ8 zYK?4;S&} zMW47~uwCGz%b9rpcQ;FzFh}Rs+Yj0}vCui)yP+{UvsUq9dG)B>ua(-frq1SSx<)wm zjO}I#6Suon)gHi0ON}3)f1j{Nz{c>Z6>TP1>(lb0+Q#JMV?d0Huc>WB?Of<)2@^Cc z0`Z{AIr|K3+^d_`W`ea$Pi98Dnl?^ebjBPQ;bsXFGz)``!Rxo%?Ovf`>)a`WU@i8$ zut(#di}q2>an2@Muje*uj)S?5RC60O$HB}+QZ=1aXHK58JD|0%?!1%h>dik-w_Zk_N=orzs4%lIlB#lwK!^oInMAXdk*%QnESWQ^?Q;D<%uhg9DX)zIPK~7 z6?`8aiQ)``wK&d%(+a}F?1lISFIPG!Si*$r3ss+pJ`6S{=bdBQ7}a)-kp{t9X8dYu zP`KS2xuSv(ccF&wzsMF79M{6rJv+zFk^*1Ur!5A-TF7-;%5PV>PgK_Q@w1oL$2)Hl zpt7JpB}|wxvWcFn>}c#DaIW+}RkJx>J!bH-kZ?(PJue*TgQsaxQ zM(6qqrx*llsTxI9tB9IK5C#3bY*n4Gv8}(w)rK^3#wmYYdFLum2>+^hpuIKT<#hb> z!(s^&G*W}8-|2;22T_CHuGiMS|G&S*TFS#$Q3I8i#JZyS-|U{K<&28#ELg$>*LcFe zDw#+2=;U(l2^nJ$tc6Ue_Ni6o6srgREG65P!D^0K^HmP@r-TXR?JKVzBNB+9B(-En z2A8wujU@)bT4q#j{DNAt+dsa}T(^S+OPD}DRgZ8gzY4$I(N0FeBm1Lxm_e`>d1oMY zAL<~d;2SKEG1`drF`>pkH4b9j0+IV$XL%mq`ON(*4T81EX9Q7kVjI~Q<6zn}tBjZ> z6KecZ;~+*l5aMD(+35kYmXo3kg0;Bj7Uu#ikFe`DcRBAjTw=tjm7k;h9e6ZG%o-<| zbzW?jz!&8=b&}vnGZShCtY*USfzYmYmM@Ou&{2^Rn86@eizCoD3u0AHJLg>xe|@xA z!UW=SdT(`%FRYj-e>Kkhyj!;>@*10LiI9Ld9NA}CZGO5+bvs348g94nIW3Kk5P+fT0KdZS70$Fe!%Tn2EWO#2y$ffwA7AI+E5UfQ$Du{AL*2o(8 zYLgys%YLn@j{o_)sA1Ey2~@{}=>0T61|@bmlf9{95Uj9Q2EWWCyVvN(cG^E0Vx(N#=F<#SQPvMNmWL3A+fquCZqn4lRX zh)u`$NvR^jb!Hg^YpIImgc>gpxeD)>4>9NL@*vb=2@}VkeG(fG7wx*{Zx9FW9F&I< z7p*igsuCi*RChU-#D*CJYw`O> zoFUzA`RFC~_?@uVVhIy!1%aAJV?_b(!{?fmrO~by*4bweti|siv(!SD>=_t8rhR(u z;Or7-vuJ*W`}kUTs+}LR)cxs094ujiW?>*`c4y?gSc_(TAZP~ZU3#REr7L zqS-45nh85t!UWBVLC|d5VuH13-VUO2fy#Q8TBlizgC$H*>>WhQb&s@PQuFq3iwV{; z`(3X*f7>&zV?1v$-(m?9D*l#GBMuu&I#}{BB6qcp+&2i;;yxcE=ghRC;we-PwAyTO zRUsl1di{^8_U9@@?CJDjt=0d9%lSH>zEPjZ1XojHPmWn{t;#oGquy+TU@hgr{8u%3 zw?rE&*=Lut(Sm#G>Hd^3VOD0|`}K%*9vY22kGS8dAMq}L9mvZQ6xlCK{V*KM3ijpa<)4*-C_w7 zTs4h-anf%TZPFpDe<;ErSW87c5+cIrcTcz9BeK0g%(CZFizQ5$71-+@91zXmC+?~d zZ4j)bqBjY7RoH0ss}xc2MVk-uw^+i2S%Dq-&py!?bIx_8HX8(MB`&&C7IR{a$)I@H z7@2vySoj$^;dZeWOPHY5pdeb8-zp9uQyq8pnnAFZijyVO1b|2}ZJmflR4rSp>#ADd zr-TU|W&2-60SK@9T|_+MCEL1fu$EOCCRI%4$_{@!-<7`l@32XyY!z8ah;oDYwsVZQ z2e0q+fp``F{wZOi&yIz%>n4A!KJ`E=iT3EV&`(JFBXt>nau&bk6f zd5~(=ClhM!pAZX&jgM19MHa;29;fVS5Uj=3*w~}-OQZ;ff92J!yy6W(T9-7c)tN9y zoV8xF#X9WXI%Rr3gJ3Nc?@7q^;y!xK?=QB(hx1RHL`Q=Dl`z38XW=3L(M5zH`?|aC zDqZ`OkfW1axy+To*ctD)mLfZd+vV086~9cVd7$b`Fn_~Uz1~|~)=&iIv!4VC$U-{r`pk8jSmx)9j#C9CaCYa`_3CFoC$J z{crRW_3cG>SZDB^uRGkyAXw{L(rem=W%q)OeG491&fl;;N=y(eVPaQYT3NNsQZd$d z8Hh~79$O9kFn&zzW)Q69n=!fm&S!K}qw~;@Tdl;ee4Pg->{jcae%2l0iaK@LZ4j)bW<#pK!t4lyuV*GpWw2TgPGi)Ca~-j9!#`WbW-$4(Z>17k7T+QB!dde#z~Y(Q-@hDA~8T$|xLEnQuMns~k72 zX#x>?${`M-FIm$xO0t9rD0)eDi%<`+pDF>0T19n#kB^(TK%G2 zGF8=JaV7O>5M9U2v4-44MPu-Do7cGWntJLnaOd;d{BWq4%vZm`HcObGegy>eR|dga z)boL$KG9|g6VyL~pnlgNSc`ga5Y)HZEMbEBc@Q*y7zAt4NCYC!=aIVKz2H^TW(gB& zHmt@ERU3e;%%PmR-<|U3M}uH3^BcU|Bctwjhc8MYS;B;xGpl|Vb6wa_Ghj6n#*Ek? zSc|`ZoLAIlrs!J79}UgA6NOOsZ9xsxAYoH1(=XHR2%iBWOP%5Nl9P-xK}SmVavSPD2K9 zpxSP^d)^9BdSfRL`9i{kCsvGnINR7DSc_&$Abz(Oh&OkAov7HBymJGsOBJXY)GH@d zr6A%Arx%G7h=qqu9wAx6glVJe>lLCAW_KBr3^oYXLd~FFIjJfIaV}Z9Fp&~#cw6ND zMXj#*DPe-|3A?1Ni54%AH<;I{i$Sm!vROJZfh-wpye!>Wv|IoWVDLqoX1^BAovjaz z7Rc5E{6&wn>U@KKS4WA&qY)#^bIE226EtrJ@ox-Zd$$cd*EeiXYyd>~x0yI|1HR7| z+aOp=`MJv9h2IOJ-u2zWf~OzRf1RyX7be8+wTGV&W9PN+Ag)|FAbP{gcse(lSJ+!> zPVg_GJbdNp!!rl*xQi6~;K|fj<8KhGMbQ=zd!I;A7M_0gh-hQa0Vb4(uRMMD@*s}p z-6!Uw?zMid-3Gy0yuTOfeZG#Wjy)KhBJAou#Eo@CP}NoPw@ndGyz})H+FL%KQTq{m z$juTa%&(RrsRqGX6!C-&ilo{sVS=KcASjaRW`eaS`UzrI=DSui^ghp$r?FYWgjzA1 zur>$8-#rqGNQ};F?iDZy*5ds+um-EqKlVXXt7k0M#i*3!+FHtzV>EC?y|q_^s9&#} zWC;_hhfY`r4PxN9MYbCi5I5Q-H3-(C+&zfIc}M6>L-~M5HcOa*FCo$a0?5PNN1I83sH z399!2G4XW=IS_rx->ISvg0)nCt7b*2ngBV-{9UB#OGeu(B}N6-M%c0VBUY@ByV+f`gl$lTAc%o7#t!@iRjhYr8w6{q zktQL+0-|QsIksAxk#UTayi*zP4@dQvXzl0TgxS$(CCQ2(H1<4WLX9*Du_f3j@o~ES z60IccgER=%q6$+Go#w8zhhoH;RN36SjR`f_n^e7 zJw@i)9?5ZneaEfFo%8;Hykj1o)rbYQUC-sLTrt4dOOFYv7Q?e@-XO|u(-3uJ2bUTI zYpETL)Httl>R1`(USe;=46;oBDUu~jpcX(^A*oD1YCn<(yFC%bIXBAN=6;F$E2=L8 zk+WMC`vM|Gf80D{>^sN=<|Vq{#V7i4vbeaTjUsJ|eiw&9m#pPLER zn*KDgQ1`d2m)cEt*tL23&Rsq7+Rv(X)z)YK;wfF{o9o|gvF@|IE9*l2{~2zp?9!Hp z2OQOLRox5JF(gbBm@!S$1>&B=#+7$lw2dyUvKRzwU0t$K+xU^^6^MNcpF7l@ci(^t zf08h^fU<8;y3Hzu{dpN{dAx9DQ>fbi3j8MXd6?;s9l=( zzsqV>!Bw>@oX;Rwi{C$D009NP)jMDFsI=XF&OC4R+=H`bmUqic@mB5X_uMJu>vNkO z>i-+f$%v;rYR(pKb?47!bhKH*ME-T*4n-f?nheC*yKl9P@4h7sg0;pL&8?sAhc{_K zyvio@(`_=St<4f9R!vW*@4QLx#30rkZK$8F*WMxq!CKsU5D_l0_04^f&=>MNR>kqUN&wLqdbyb~97d9kJ+-fw2cur zKY=*1`m=t6C2Lo*S;EAr7K^owc7f`uCN|%yZ9J%!#UNOVTd0ReNX%Jnqta2Q(RP`r zJhQ*Hkvjc5*!Wm_r(5+tYohBL1Z#0S#tP}C1#H!>oEay%54+Py)kYisS=tVo^jZJz zpk2-Fjq8)^|G!&*Fl-#H+0a&R@LS1EZk8~yyzfU%7kb|b#1mI;ZR5`Kr3S%T_51y! zpYHv2%R#goQPWm!_hGryZk90d>(M9L#=!A&Kx9~-QQMffaj!wJ*5c<+wGG!YwGaKm zES0ql{{|o3EMa2Ly(`*AjZ|u^J$x*gwvqbEHG^O+ZlN9?H7Xa@HqQT@-ew6C7e5}< zHfA=nVWWd@ZvAxg9L`}7ti|mZtI7RJ>#J&=Y-H@Whne)7S~EVi+j^N?s_$-0J`Z>9 z_ze30Z#sU*o`4yTchFZ==G6UImN3yFWim}qYOo(fq+bbbW7hbz#&59}w;t3pJa4US z3@P8huAfNTDDxyQ?z~KRGrJnz`Kelq41%?|js4eleKJmRP)oE(%c85Yuyf>p zHXJNrg6x4fkhz$?bNfwIgJ3Osh7Q!Q{a; z_!_aQhig8rlf@Dy$a4ZQD_@lM$g2J*We}`I{v(JCzopVocgMB%7E72Q4-iDh-Uap3 z?fz?VgJ3Q4kU<>FK2+Pd=EYTRp2Riy9m4 ziV5;$@CM2EF$mV;Hik;4gn6xRkGvMmUj@w|ESj<4K4|`7NSL6x2(D^%wP6m`N-p;- zXb`ML^DEeR5H-`Ge4jLLnp-Skf@Vk{_LnWBZ4~WX+#pzs=7}KgOem>sj2YR^VhIy8 z(*u#wUZrP{X+M`T2-f1S05kfqnR=Fb_CrVG`(T1Reb~5_Z0x^t1A|~K{#J16^nWoK z2gOS)nqgZsZ^!$f`MDusg68TVyuRGiPq$9@#0J4y6n_A*u4D>Jy}=|4N?9ynf+7eY z$}c*gZM-^^&LCKeTPW)Ev;LvqVB!v5M%!hAA|bFrF&TqkEpEq%GYraSskS?`$t;Kc zI;Bu^1FyfETElvMwp0&yVrg@WB1N##;B{Rc@%oTC*1-}c!l%C0^w$StKs39SP20Gh zZH+;&7DcH*+LgBbna8#D;kqBjd-Wbr0C zeid*t%*_%evJCo1zrm(;ED*J`7uHXA$(LUYg0*}+)9coAq-H7*W3IK-cm5`Pl$#|? z{M9RoP;D&F_kZ9gKABKL+h|fRok6gc%$rHucFTPJNJ#-~^;OPD~^L)-Wt@g`pxZDW#WgclR6 zMYbK-10vJ^Y<#Re#+xNfkUbF2)}^$KH_J~M1Z&Y#w-7y#ZKvk`mM}rj4K~IX zET(PTDN)rRSc_T@Y&`1OLfa_&Xu8ptFhTDh1hqtiU@dBuAXdcIv%Qd;sG1`phM#Us z(TPIUZ>x7e&k*mtUb4jU-W_Bb;vev{ax*cq*LY2zh=aUYd*EW`=2;-jGAZj>$w2iLs z3d2U7G&!}6sms5xmtnIOc^R+~9qZOM-n(|O&tMRx{jkyltujq>FWA^rJf*e~h?qM6 z7Hg3&0UISVL~9$HhMr`f!Diz5fK1xPxwK7TqxYtlZuNaMvhx}QYmt`$!j)ydw&9w0 zlYIus1m&Ya#B4pTZ4`_vWe}`IJ~fD2wR>qB9sHlMhs=3yV>cS~43EOJjh>yW8U$sk zC3()U5mvsWwo$G52lkN7-=*De5H&d7Tif_^pfCu^ZU4WlOx(DeZuJemS@xYhWXZ%o zt+VJ|ZZh{BhpU>o#8cadxmepESc`mW5ZS)g);9XCP9#{u#PZ@Vy;ZxKoN^+F^oPsF zs(0Scw;ub{lC@|q3c~YVb8mGYgUcl5`Kv(`>%YUTY#c1Ec8wTRp^>+;(XCHCo~26G zqPZxD@N3H)%EsDz9)cxI@Twbl;ce49l#TZ@YV#~rvKGxnVWafjvS+bPZgYaxs ztAjiD>Gww4n6n+Hy3=p57Dd}&W9H2*+Q#MY2RL$PGf}N_6>a0zt8%cBvv(>>z4KnJ z(i#M7QM3&zzfiQ*9rw2k3?)f(QK1#@W|N1uJ<$eqnv6rY2QVok4V z8$L7rEtW7rRiPlJ?Jllu#P7Ypkvpy({eL-@xV(RA8~rm3vnZx#5L7z~8<}5K(l*4> zbsV`f){Iib8^q~te`^~dyQ_1Q+#slS6hv6GL)+L~a017|ZPudrHN2(l*S={RV!>yQ zg}a%!UVf~8A980!*!VrBmbURND8E6l7RQ!7JbHK~66!l2UT%tmB}|;#H9^}rpJoWI z>SES<+Q#_xejGh_vlji519P=%iM5SBJqmCv+`$C>4Px=;|JfLx>?+5?nc({a(W3kR z?&H>|-`w;R4TA2;!U_f7I{H464tmXb90zOBI|p%e$Upjhc$|O5ITnivdN&|qm-uKK z9dEQT2-cz&3ZmrVciP5-#Fe>K^Gar;iW&PYeXOQ!Jg*(#=HH?g&R-gAY^nW3+xQSX z$fj@5_+9!2LF7MEM%&mr=>X>kE!LvG1ccv?YuZNH5sPh>FhSqEz)ppg3uqg=5#Z?w!r1zTILi8lzw%_0>RaqtC62HcObGu>>}bExxJ8kMgsM7zAt4SPSCI z+R55Rh0zafmM}qMB8URHcWN8+x>PU-)*_z)MB_~LwGIDUuWgnvLEZp}^95&X8-@3H z83b#QhXdl=uGHE_uLobal7m+O^NM2-OMI(o8y!a1Gzjv2*i!>B>(EN=Up3k8A<4Tl zewTbL5MA5s(mvd?DRsH_L$DTkoFGD`FVcSE^FoOwOPC-p6GYhAF8kDY-r`g}n+ew9 zXf*o7B;~cgd+$IZ_O=BRBGl-AC4RH4TEbXpRG-{IDXn8lyJm{%9ML|K=PVKZ8+BaWwV3{nuURAS#poIao)eYL9iChIq{vR`Y=b^cys@j%@QVPZU`Gc2Hep$ zf|e9E2-c$cE^H*tw@TZ%pX9X75+-Pl3mZF+CbHH0SXwu$L9iCZ0ASz@MA%|2iXefgc=3g{F|2l5nrM3{H5vnWOeqV}#&+Qzc!xonp3?@}xaL{KuPwvo%bnVSjLqF5jNs|Kjm zQ{Uj9l_W=m9ZXP64n+L^I@-q0_y@84Tdc)#M#K}}Cek)W3{K`|2@@P!#JSZOh_h?< zf8+OTvlg{6iMotCGh{?u^nNBfdaIgJ3QCfYdWH|-a}5+>;60ubv)m(n(VY^iS$ ztVKN$h@3NOX&a^UjTS6nf>w`!SbaF7wozhaCxc)u>QO=LD^*zAm{P<~u!IR(Jpy9G zpv-bjP3$%KVva$umbruS^ETzBg>@|P)+)ggCd{2~Px|b&lc7j&tBB{2k zb~U0g5mz6KpiQ*509P3`!KrUYPN_e6k=Ssm;DQl#R)+ry2xnkI~oLQ(d-4pvteFBJ*x%{ zCkmD@!Kc(>jA~z6+bH^?on4s0tAYOR3(>87u$zc$zMYCdzQIQ*_X&WQIl@csrf>x}gG+ja|}s_ce-Z z;66G`Su7ql!MU%6V>o`HPJq*^@X>GCypJ13oGp{|vnus)wn4BKMO$DaN9{oUtkNx; z%W)XvcWH$*h;mb=Y8#JR+ zE&6|WOXmxPY8x9P{bE_d1pN(STBrZn*s(m0V{d#;xe?34(>)!mZG3N4#HOcc@$b?- zS=b{b`4oL0T~Ue71Z&Yd2k}q+71~DR@4+0|g1$6d)rgBTL~itntJ-FgEMbDa z6@fcX+f_fS16CS?U@ht~K=f}nML(-^Pb*56FhSouh;7drYa3Vl7BvXgqMi@Lv5Nz= zjq%A^NR}``eHVzbFRN-B^DN6CSc`ga5Tkaq&^F3>4UjBhg8E<(w|nQ)Hcky`X%MVM zBN2#9-yd5~;VtdDK3T2E{kb0z$Ck_;fiB*AYPFq;6Do4_k}P4uw9&kIcJZMRMzzs1 z41%?2yuwwv*H+SZ-XrrAW1k`>_@1zfIrcCehTW`wuODI%ti`)3VXVbD?xEN<`-XR@ zvELFC?o0u4U&dh3=<7aQRrLma#Xy|np7O1^LlbM^%m%&B1omwNG57IsQ5>hT56KfL zS;7R)hm#5C*McZ`tB;rl!fRu+L9mv&Pm!zGAn^g`xKH$pkSt+B?N*s^el2WNN!UMe zdfin9!CJhl64qc9>>vWMN6L@%!N%@MOyHCcsrGMIC+MNNtx!eLvI_R0zcte!Sc`Xu zLar!FR#6bUg?{hc!`KCi37l4h97TF#5|R=#M?f}xz37fjI10>qXbQ}i6Cdh|4d zU@e+0fta1^ho0k%Y8N6|!UWBbKx9K{mwHw&j!iKLL+ig;ABdB`&(?Fbz%GG2Q{+>d z_>?FR8%u4ocVVpcOo_dx>9=Thr+2scZ_k0$x6j+pu**%~lshHwM!=N%hWue>#opZv+z*4*>D7MSg7~IJSjBuogu{K=k%#sBL_?F;udI35sigunt$# zHg*qo7zArkbO%JokG-^wZZq0TmM}r_84#zVn`j%gT}2FnwJ1sjVr|?6ZR1)gZ^;rS zD9!}JwW+JNv9?xfgJ3O+w!y!89Xdk}e=L#J;q|rkT4l3@ z2|8~AHmVn$qVGKYpmqkqS{%PbJTY~!e!AzTHRUQs2NQH|25fBqb(*#@ufuLP{}yYR zanbtULbQ#0jrtnZm`w0V(Hf5}>z zF+IlG_vbB^Fo9WyZiy<=0nPfAqXmzixZdy5e#hp_Mg{W&fJf~4T80< zea@tb7w-;(xK?bc^n)iepBkL=1a!a@feYaEYS@TXz$`c{FF5NB1FM1;y+zS_v zx98aN8`(*6zGbf8duvU&o$$gf@ zM~aMpDdNfTMshLEOKtQajbI5A-nCNtWXc^S+SZK&aWATlOpo&iLtm#b2-ZrMHI>hX zN>O6eF-80{-ba>NfxYx%k_eVC@ibd1pROQc4=5t@6iW^ZLL{|VVuN6S>QF!52O@fkiOO3Y4#9d|tzIZMc|Tkt;GKQai`GF$uG%Q>aA zk&o(k-eL(8_o`>|dGKfn2 zF3*?Zc2KzZYr{^-Um7Y>hR=}YOCa{zqoMH)GT}MxnMl++Tzp)$16TENq@Q#a!TC5l z8XE*_HSv2Y28eL+ww)r*JenoDm$Tk@oMuZBCRV(>D}qL>6b%+_RW|;ZCv&94i3m43 z8w6|p-RF)-(Q2i*nnMvi^DK~Ku}fN|+T8?8m}s^2mbhJdr6>@#1;opU1u}6W>^6O{ zyFswl)=jrWRS??(6*1}M0y+1Guk+6O9)cxI)bD>wTqwFy44JKniW3*gGv9oj!+P{G z2-eDb`I^{sB~0|5uo=XLrHf=1M5AUT{Z+7piFPgH#kt{O;&vIeQ+kyv%VhB*IL$nM zrg-yoyQtDCSkx~TC4IN=5_kQBMc?;P^3S(BMUSb$qVfJH5MfD{%Xvq!bL1yK!4f9M zf8Q&f-U}A*p05H?!d@l=4*NO>RGnoI`Ce=n%VBR+i73gok$qjfOkT!}UL2TZTon`T z{@f}~7Yr8ROCn+8{@`V@D~Q#3XBz}-^)9qk%ugRIig!@Nn;OexEFu$wSIrhIVPgLM z%_8~RAaUwT1c;kSmdRQmYGj>b5Uh2%^Ct27Y>@Drt%!!dFO}C1_&Qrno+DVo#G#uT zMdL$3;(c#LteCM>4pKy-xdy>nb(gLe1Lp^cC;QZSsTs;Fm6<^#n>|;sgo)C>uND9F z3KET~DPr;;{_@OzoMiUSBv@-=`E_FFpdit)l_E;4^OqYz{8DG0UpJi%J^&aM&FpmqD%N@)_yI{8a~5V<1f36?O??NqcFRT+DHhbtR5 zs{6}@AbK7%3D$btFIx026(p)nQ$*3^{&FsecVFiTmM}5q_-YZ8J4mExs|cL&plzHe zIo}{yD_7Fh;#|rgu_l)yUTt0?m%_%iHuD8bm{@pZl}MH}NQ8JQB6{Q!83khY9Ft(J z<`Ge%{?kB_Wv4o^@b}6~WDJPM2j&ZwFd^e2#qRh(ad@~QBL7+}uYx%Ik4dnW%Ze1| zP6UeSO%xHgbFq8}qEe{^f+b8`az}`qGEj6VrikO?7t8EuiGACd1Z!=(7B2d&3ly&( zhJtw6c(JSo!hh@n!CGk9VpepZ`0GZfG>H|d7R$aMzOPy!Si;0VIIZUUfpmPto8m-n0PfdP%Lk#h!-su$;9YOrsP^ESi(d|#V~PnV4&!dPZ3$Y7s+fO>J&E# z)=HBxOkC&}C{AZl#JMbsq&J9*)wg6=}N%is(-vASxzZBpZXU>YD^>W#1Pn zj(~XlMG?b+2~go!QXLPdu*f#T&wMO-|vP%Z-DGsq-Zt8DU6vAIQ{$a7o~_S%JV zJ%~l)77CUyQDbw6Slu8{;9n5Eaxa&?j`=#Xjq?*c_N5uWS4@i!7Bh~llIA$Ltm<-k z{kX4l`q~+SB}|0Wj1`%(g@{#4SHng&=W%d*h{<)9%de-gYxat12Ekgl(#MHgLqo)v?TV=4y+AgXb*f+q6Nk?47Z(CU#G{I9KwK`rTn;$r>+C$)Bv@-h)&rtbc!+4$P!ZGcbl+jO z&L1?keI)Y7jWBz`ySl!4f9AtT-f|T@Mi{60HT%?fEjf=c2E( zSX-AtuvW8zM})`s5b;ze$26OyqukRIC6|^Rprrjaepl;uMVaeI^=zzWaH5 z9p-~?zUCAxVFGayy-zCUiy%%H+Hco8hP@5%q%#QC>QmsTcvXFsSer5{hN`Se{+4co?dh9~my~qZOB~0`g`9$CO+lZtfPJZ>Yx4}k}CV35lwXP>i zt>b0*7etEV%WYrS$lM~rVhIz|&wbW5@Gsicm*g33bsvk4XEX@b!u4w#xM~o)W=7f> zVdG=B6&6dF!1e2>8tj7DH!_dC9X8&+NNEtP#Zf%eGfY`$PlAo#{O4ONVFIl~+raaK zjdJ#8`!tB`8>brtYjNBUeo6i(_LEI6=c^&5jPHY6e)ymJMQr~l(I;6NJl#=M-rD8X z;Jmv(DhQS^arQu**onAL%IvD`X8!cUUJ!~Md!?5_u-49_aiT`~C~+vWBG%tcEPoAj zIRpC%!4f7iu8tEc%0`JTk5YojJ~*X(ztH8p)~=pGuvX!lZc#WSQgqCe48+X78RWZZeawmr@GZr@f>|hYARq$G@sNXA6oM@K>gllRZ*?%~C zhAh7bmN4Qz9N9^`Tsnb^Z1SgX|K7}2+Qq-Y$J2t>-ii^wB5 z?{3GOzJeu8w2#~;lH7|BMT)An`(sye>C+u2VJ_@%5Uk~Mai0i$79rd*ifA2QTKfSKr9(CwGfUB@tR4grJRa5!}T^RMe&(; zU?X~NQ+co;h}V9CB}}kw)DC`ZF8%W&Q~hJ6L9mur&mCfJ&2W)w(^J@}KG7-9RYx|w z@D#xkCd~VIbi1Y;R~2>P$4!E@c6#g*DR+d6p3YaW;rZEHR&ctUk7`U3EMdZYy4`AZ zlf9B+cl;gmjr%ASu|*6lvr=?Fc1!Xz^zc|Uv7fy9!PogU`y%7%GI20^o#@^*R7mRt zuIl;y;j$_`fZI0~8w6`@UbR*nd=Vmw#T^0hec2>w!(00NdZ}Ou6TyG46?Kb-iapnk zf@o7=hAalpvUO^IgJ3OlZtybErdXAg$#F_LeB&zV(W}=OXI%cwdn`5XHfU5QF7;n| zh04l&`l3$yJ2!TaTV-W77g=Sogo$2@ZdocT6Ft5hh}b9R-6|_{FKueU1Z#N)q|#&5 zxTm?$&ss}mWoj1B5*OTWho!PIYqw{M>r#A^rLr;=8>_MQ^4l7= z%F49*5h7T^gin)LOJ!x&Ps;(~T}`ZVLRRL~_&~uDCNlPjvs6~5!JwQVO2pT&RaU0O z$E60rTKR^ZuvAv2vs?Kki=8!Wm6aJEwpg%)i5DGDSt={@qlh}O@X@$xw#v$+Z7|Ou zSSx$L6-#Ahn!d{iVy#zITV-WNmYOYCt9t7zmdeWfekWg?Njz>@$yQmJ(8bdPOPKi7 zOfOpq#Jpr>Y?YPC*=2-a2@_uRUs@_F zbEI_<5GSvduvJ!O%jkgy!CJ#-ys=bPW?{CXAa<87W~;2stN7l6B}^0ze`Bev%(bkF z$egOEt+F!rTJ9jS}H4(yq_YfUN2;ahoPb|{1?FzCKA{BVyUdm^EB%0%s=O5 zw^deVUD}2Q!CGc(_c)W*R#}4WTH#bm6poNyvV5L z2K_^-+A1p(lVXiQuvVFDp_aDfkuV6CPv7h5VTb1jpayp zwIqwf&07F}%2~vN8dub_$j-5prOvrLrG6>ds z;|{W$|T8kLa>C1foUE(R92>Z(hnd; zdj`2xR;JN$lZfoQ!=bV=@#9}hwhbTd{bIMu$_z|((zq%nQk9ExsH{xt$d|A&qs2V8 z%E}b2ViK&?HGQZg44vN9sj zBv`A%5kH5@%3SXC7l_Fr1KcVr(^H-lEMeke+*F6k%8Y;Y48-5g4sMl|sr<+!SZl`H zZVr`|@w%?&YL{lzajUG%^<<|6OPKh$vbIBIWgdz@L6lxm*{!lN848#LYjt1S(4n$2 z1D7cxd$Zzhm6b_T_LN`=6XkxXX?_2@}5M3prF)CR^V}u+jN+Mz_k!)b}P6?JUvG-#}hsw%q9rp)_>46^FM&18MuvYldWDb>;`E>Llh@6$*#;UB$3G0+# z2@_BDCvvE)OoRD~2<~?$R%d0rOoFv0yu0JAvNFY{J^)dq-N{&$m6>1plwb)H-69To ztE|kJo%caZ{C#_@%F4_uZ4#`tuWju141Z#~x=I5=lGLt{v1@S%36|1r`sWO}rtQC4-s<+C@tiEwqnndO% zonlp1=6#}5f+b8;iLC9dvNB#T)vRb|!CJ8@E0gxqNrPamF5N15tE|l09g4X8BYUjM z%5->)zJw%9cpOaRt+F!b5-FnO;bgHYD|7a?NwC(7W68W#R>qM*5vNYyh*4RYBNt8z zLqfm1Hu8{{%E|=JyA2|3+e0xbE7S3`NwC(*ZachGR_6R*MZAm&j8Rz`?*k_VOPHu~ zaH^Ne%Jj;rh=Z+W#;B}J5w}UOR+-~|UMedSlt&RQW_O8ES(ysEP70PV@i4Nsm&(dC zxN!@_pl7vXR8}Tzn@O-%qVAQvR92?0R92=;xFT|- zeY;O(Wi~~d1Z(B%zN3c9%9NR)h*d-V_NlB)r?8WPB}`!7pfxHh^Pz+yazEeZR#_SQ z{Bgl!UzgW+94ad#=De5YI9Ru-+pV%PN1GoPEMa1R>hGdu!M;RPcm34E0ew0KOjn8zvEU}nagQSg0)t>&uFQv z%>OZVCh*o>^ZmYPHI1<`6b%iP5JW15Cb{R_mzr8*X|zfyEv3}ZNDxyJL58X!A%=)V z5UnwUhP-FrH!;;zYA8xlQ&pSbZ=O2%f1h>MzV}({yyx`I=i~Ek_xF3w+SA#4pY_|% zS`T>?#DAao^_^5@Zt=YLPaQFF+^^hVLRIFVJJRoS^sE1KCsmne-TM7gM@+ov>ibTp z%FNydany6Zvy-aK-=FrrhH%!A2i;^sRp!{|ujOg!s;~LsPO383z25t#j+nUL?QS-q zD)Wwg>G8VVyMDHls?57m4>IAbKRx2W300XZJOtufNB_@GsxrTJzxPfZF>%kw95|sW zbE85W`Qf!0Rhi$q99Wim>gASQcl{xw0 z5Yum5c}7*{@;|?*A)NK*Gk<$RRp#IgdLXaxj=g78Wxn%>T~kL)9CYsQOsLA->2io4 zK4za8Rhg6id)5%nYM)-GAH432s>}yZ**SH@#Jj)u&%oF#z#pc)l;fe!QnQxwT zVA?qC&R3sMmHGYK-eKy9iTq9+=wX@nm;BR*e{n)p=Au{Jydj+RsP|ocpepmCYag68 zW_P}1ovO_3zxeA@M@-y0voq4hXP*S|qFa9GaH=vFJ?|^)>Fb$|y+i3W8d#>+Xval2 z7^uqp)5*6B@uhz|ah12Ig4vz3R(JV-`>j)zxxsOlOdK(B-IpF#w)~MlX3Nj}@FNeWD)Zgz z{9Z$}S!?IA7tTH7E+Jldug4!wRpzWae{qrlfVUz&!QTDcYkxDu^q{>CWjoG&&Al4} zdd$k&PH1Dk9e@1cM_x!(=5cqtl(kZ1n@D@5A8x)Kd%f^}7gCiOZeF%yi*S~E@$!z> z6>hYXs?2%M{{nlr5cCL|$bKtr%+Hcr|M+n`smfgb{m(Uov)u2OcWXa<{Rvf>AHL)s z&G*A+{vGe}(-~Eni@$h4_SM5acEbr(nM?ov{!>Rxy#B23&Zx@#sPy}M^TEF{p(=C4 zXCKlK&brgF-Yq*>F>%4ad}l^g=HLH={;RJadEkVq%sv19 zFB`&H*M9t^GpaI2oUmVr6V5qkLRIENXFg@>h>0EhUoxXAv*QqmWA1gxgsRNR4}W$; zIO|hS`Rt6U%%i?V@8CuMblVA4nYUyV4@XSA@S~rcQI)yM=WZC{wZD7&300Zf?sHN@ zIO~hYe_}>e=9E8#*!OLBm{67Z&!_(N)DaVRIPxE6RAnxII{l(QdCYH3sLH(bguiJB zXWjDoADU5>*}NFyy7xVFLRIF7Q(iQ6#Kh+57tg55T;WzX2=RiC9Xg>Z^SU3OI(5Xv zLDwHdRap_>j@XVV@6fx%OALIh#&p)p%bbyZ@cL$r{BHc z%`>Vp`#ttLo3DHG`7^3A?^yfQO}Cx?#HZbALRIFk&U*9o-%dMuMpfq4kGb0BQSW>G zjH=8l{`p#)&-mr%&8W)!R!>dJ4JI%2|YXFQp^9x|aS^WfL~Z9_Qg zOMmvN8C97#zmsLK5Mue_t#jzTy!Np?mt1(aUz$*rx#RbCHpIUv>yGE#bVgO?*FM8D-1oox zgLSGh5BkrGr;eC-_Pz(ssLI^s2%gB^bn&a!smi=ycz;8*S^jN+BSTdt&dfTF3|D>L zdccuknYSTuWT?vI?fbNWBSTdt&dkIS6F4&5OHvgNfg?jzCeBPlI15JxV*c(2jto_q zI5WkOp(>L%`3D>ssxt9e1{@ixGBIO@wKW_WsxonAiaj$%OyI~+m5CV>0!N0bOq`iw z&x{chI5Jda;;A^X8bH18LBcdU^ZI;9#W{jA?k)bLRw%RU zlXnY4;K)#wi8E6i8LBezRt6jysxo;Cc)*dNDibp%1da?St}DbGE`;awxkUl8LBdIW*Wj-I5Jda zV#b8Pk)bLRXQtRQW5fiG3{{!9Eg^7ZsLI5dX$WWG$dszggD{bBWT?u-nJMdz92we( zGt&^x!jYjW6Eh|Rjto_qI5Wkb86zfeWT?u-Z3%%RLscfuOhY&eM~13Q%$N{3GE`;a z%oKZOjF`ZYp(+!%B?OKPRhc+54dE;t8LBcdV?yA_P?d=@Q|y^BVgg5os!TkW5I8ba zW#Y^!jYjW!;A^X8bG@I5Jda; z92u%Iab_CASvWFOWn#vJz>%RU6KAH_Gh@UAj!bc7io1j(LscfuOhY&eM~13Q%$T%+ zBSTdt&P=gq#)t_V8LBdITSDN-P?d=@(-6+Wk)bLRGbRL%3{{ypGsT`6BPMWUsLI4` z34tR+RVL0%LpTdZhN?`=m=HKJRAu7K6nkcjn81;tDigOQ1da? zCU9h^%EVL&fg@9@G6%PWvv6dn%EXKbfg?jzCeBQ;XU2#L92u%IF=ImD$WWDuGgIuD zF=7HohN?{5mJm2HRAu7KG=#H?Ba^C3%$N{3GE`;a%*^eX8Zp5=ma0tLmJm2HRAu7K zG=#HoWT?u-j0u4wLscfuOtELihzT4Ssxom~Lg2_ym5DRc5YEDpp(+zICIpTQRhc+5 z#hw`>CU9h^%EWC6fg?jzCeBPlI15LHs!Yt75I8baW#Y^fduEK7z>%RU6SpM@M~13QoSEW&kI%IxaAc^;#D+;5I5Jda;>b{yi8Ip>&cczQDiiM{ z1da?%RU6K7_fULksi=<}hsh-G?@aAc^;#EeNBI5Jda;>={u z^X-V+^Cx9Cs5mlIW#Y_WT5PppqFpN-8LAm^W}3Bf7LE*SICo5NWT?u-nZX#@ikQHW zVaw-^362a^nK&~I;Vc{(+L*gCI5Jda;>=*aY(-4q$k4{zmBEo=JL1eVgtJ(G+F-3S zGDRF2sxonAFnG2iCRl&kpxulJ6i0@tOq`j9aF%=V*4A)jsLI5d!9?2X5j4TsK^yG9 zynhu(hN?`QnTBwd`~Biz#gU;Z6KAIRe)!DCk)bLRGbZO1jto_qI5QJROyI~+m5JLD z0!N0b%(Z^<^M-I1jto_qm@y%6WT?u-nJM*fV3q1da?Mk)bLRXQm;X zg(E{%CRRrX92u%Iab}7mLscez$$%q6RVL2N(5@AZ3{{ypGsTgiDihyhz>%RU69ZA)JLHLscebOxnPap(+z+rr0xM z#6-ItI5Jda;>LPE~xCKK(c{RAu7KG=#Hw=L3RwHPRy-M~13QoS6xZ41L9UlYfRILscd| z%M3?`+Dpusw1Fc-RVL2N#1RuXGSpsT#)QC;p(+z+X5xqm92u%Iaa%&*$WWDuGt&^x z!jYl&5;G%RU6SpN>jw3@=CeBPlI15LH+Dpus5I8baW#Y_C95I0-LscejO9&hpsxonA8p2sP zGSpsT#)QC;p(+z+X5xqm92u%Iaa%&*$WWDuGt&^x!jYl&5;G@f&Vgg5os!ZIL5I8baW#Y^@f&3rB{kObnQvErBCL zRVL2Nx+5lVWT?u-ZAlwAGE_|B%ru0vaAc^x#Ec1nBSTdt&dj%RU6KCddM@-65^ydGE`;a%ru0vaAc^x#EiKxzb4|y zP?d=@bGRcWaAc^;#BB+IBSTdt&P+o%3rB|9OU#%MI5Jda;>;ZGhzT4SDkLhN?^qmA)JLHL+vGIOb8qqsxonA4tK-^jto_q*f1e*WT?u-nP~`T;mA;Xi5U|DM~13Q zoSDNMF@YmPRVHrBdoo^l92u%Iab_CASvWG(USh_Cz>%RU6KCcyM@-5&}nt zs!W`jhHw^+47Hb-F(GhdsLI5dIm{6gI5Jda;%RU6SpMyDVfk)ieyGbRL%3{{ypGwY6+z>%RU z6SpM6iab!}Ji8Ip>&hnFUuDfw$sLI5dnc>J#m5DP`92u%IF<^=#Lscek z`{(L_BSTdt&ddyZW{hCfjD&vmg}{-aDidd>A)JLHLscf;NeCPnsxonAb~<7L`++_g zJcqOqM~13QoS6&N*E3PCQE_Cb%EXLG8#pplW#Y{2#GV-=ZqJ_-`z($ORhc+5I~_66 zt`&|9)r^q(F@YmPRVHpr2pk!zGI3@a!dW;n)Lvr7gus!ZDiddB=7&cczQ z_7XED1da?5&}nts!W`jhHw^+47Hb-F(GhdsLI5d$$ZP(5feBv zRApkSgus!ZDidd>A)JLHL+vGIOb8qqsxonAW{#M^k)iey`yvF63{{ypGc!j_;K)#w zi47A1M~13QoSBAj7LE*6nOGemaAc^;#F?4l$WR%HUoydwp(+z+X5zNw*yCps!W`jhHw^+47Hb-F=+!whN?`QnVBOd+P#Y-LscfuOtT$0 zGE`+^z)ZXk^VAndhN?`QnP%^rz>%RU6SpO6g(E{%CeBPlI15LH+Dpus5I8baW#Y{2 zbi@RX3{{!fFd=YcsLI5dX$WVvzYTC?sLI5d*{Qc4iX+2aCKdAH$kcgdau30gsq@Or zuxG}I-fbw340oJV#Y5o8)OlqZ0+VLU(mNU9!8LBdIW;K?7=k*V{_433zC#$WWDuGcz~~M~13Q447io zY!f&#bzYglpJf6^rp_yqHgII9%EXyz2xsBQP?d=@69Px3&MPxGVgg5|&MOlFM~13Q zoSBAj7LE*6nK&~caAfMdGJ_)~aAfMdG9hqesLI5dX$WWG$WWDuGZO+whN?`QnVBOd zaAfMdG9hqesLI5dX$WVvXFHAzRhc+5Ge=C|$kcgd(gu!9omZwIoaOIknOCM%W#Y^< z-wzy_Ibx?8BPMWU>bx=`aAfMdG7aG@92u%Iab`l`$WWDuGc!110!OCKD-!}o zrp_zV5YEDpp(>O2`$FKz)OlqFM@-bx?=&l%e;^U9Q}Oq`i! ztxVv^)Olsn2969>nK&~I;Vc{(sxonALg2_ym5DPmIAQ`vrp_x90!OCKE7K6p%IqGWT=?LnP~`T;mA;xi8B)dN2bmzGdN-bN2bmz69PwuHsZ`QgtKsD zsLI5d34tS1=am^8F@YmPRVHpr2ppL*g4xN>ZwP1M$WWDuGZO+wrp_xfIAQ`vrp_x9 z0!N0bOq`j9a2AdXRhc+5A#h~syfT9$CU9h^%EX2Vfg@Arm1ziP;mA;xi2)M=N2bmz zGdK%Jrp_xbx=y;Vc}PQkD4%1ddFdS7va;1ddFdS0)6GOr2MzA)JLHLscfuOb8qqsxonA21iWj zeYg-fGId^=!S_BKnL4jbaYeW9gE%sEUYWsnNE0|RbzYgYfg@Arm1ziP;mA;xi8B)d zM~13QoSDH96F4$dW#YDkz>%RU6KAF&oP{GpRVL0%2ppL@ugu_x2^^U^uS|%{D^sd6 zab_CASvWFOW#Y_)z>%r*$_$Q}z>%RU6K5s_j!d0bW^lv=j!d0bCIpU5omZwIoK+l| zRAu7Kgus!h^U4g4n81;#^U8$4k*V{_G=#HoWT?u-nF)a-Q|FZ#95I0-Q|FZlfg@Ar zm1ziP;mA;xi8B)dM~13QoSDH96F4$;UYQU$GId^=hHw^+3{{ypGa+zf>bx?8BPMWU zsLI4`34tS1=ap#)XSGkSI5Kr!nZXegI5Kr!nY4i;Q|Faw2xs}pxy&n5Mlg#rGvLTj zm5DR6fg?kWB?im}jtsSzyzReH=9MWUn8leH95JC05<=j})OlqZ!dW;nRAu6wgus!h z^U4g4n2_HP0!OCKE3;GH#D+##*}##Z_7XED1ddFdS7zpj+w&)td1XpfCeF;v5fklN z;mA|Gq0IA)JLH zLscfuOb8sAI%r*%7nm? zp(+z+rXie#BSTdt&P)g#8LBdIW(G%0;K)#wiQ5taN2bmz(-6+Wk)bLRXC?%WOr2L| zaKr?TOr2LIX9wSEf{D;><87O7T46 zdlW~e&MQ+K8LBdIX3_?ZOr2L|z@8Z+ST!Tzw#&RSr79C=rXie#BSTdt&P>|Ck)bLR zXJ&B3M7te0GE`;a%ru0vaAc^;#F%S^IB)WA;K)#8iO;fuBSY;aW=sei8LBdIW(G%0;K)#w zi5U|DN2bmzGdN-bN2bmz69Px3&MVUp&cczQDibp%1ddFdS7va;1da?Y!omXaX!~~8^omVDp;K)#wi8Ip> z&cczQDibp%1ddFdS7va;1ddFdS0)6G3{{ypGY#P^92u%IF=ImD$kcgd21iWb$kcgd zLS$Z<300XmGY#P^92u%ISAG<2;K)#wi8C`eVgg5|&MOlFM~13QoSBAjR(rPN$WWDu zGc!110!OCKE0Z>GWa_*!4dE<*)5^RulRB?V^Zme)sq@Ng_?uSdm6_CeWt#7x2^^U^ zuT0hoN2bmz(-6+Wk)bLRGbRL%Or2L|aKr?TOr2LI1ddFdSEeDHg(E}lC1y+r9GN<= z%;1O#92u%Iaa%&*$kcgd8p2sPGE`+^#)QC;sq@O@?z|l_fg@Arl?j0(Q|Faw2xsBQ zP?d=p69Px3&MPxGVgg5|&MOlFN2bmz(-6+Wk)bM+_xnQN$kcgd21iWb$WWEZyM-Ze zWT?u-nPG01om58RtrSOw8cW^+E{+VfmzXiRN8!lSd1aV!X6G2esu>9!8G57gMsNrm z8LBdIW*P!Vrp_x<{G74vGOx^fomZw=D-$>}bzYgYfg?jzCeBPlI15LHs!Yt75I8ba zW#Y^Xj+nrasq@N&z>%r*$~1(taAfMdG9hqe>bx?8BPMWU>bx=`aAfMdG7aG@92u%I zF=ImD$kcgd21iWb$WWDuwGskHhN?`QnTBu{jto_qm@y%6Wa_*!gCizzWT>&ka|wYX zQ|FZ#oP{G(=anf|%{GA}Q|Fao#+j|pGJzvg=aoqtI5JdB;>-nUYQU$GId^=!S_BKnL4jbaYeW9gE%sEUYWsn zNE0|RbzYgYfg@Arm1ziP;mA;xi5U|DM~13QoSDH96F4$dW#YDkz>%RU6KAF&oP{Gp zRVHRk2ppL@ugu_x2^^U^uS^IWnL4jbLpTdZhN?`=m=HKJbzYgl5feBvRApkugus!h z^U4g4n81;#^U8$4k*V{_G=#H?Ba^C3%$Pha;mFi^Wd=t~;K%r*$~1(t+NW0>nL4k`;D`wvnL4jb z+Q5;i^U5@Yv;5>-=9QV%d1VG18LBdIW;SqSsLI5E*}##ZDwDVU(*}+Vu1uVn!4VVr zoj9e3C2mUy9GN<=OhY&eM~13Qyps?(GId^=!4VUh3nT=NOr2L|r{);hNUzb9_jlvW zY~aXHm5CV>0!OCKD>HM%?fH|+yfQoMyfQOKOtfo-BSSSK&P+o%OS7(It#D-OyfQOK zOlaPe5I8b*UYUmIvJPM`#B&LOBSTdt&deXF zj5cD%gus!h^UAPRifj{UZ=4?|1ddFdSEeDH;Ksxt9QHgII>yfPbZyUZ&ytMkeX zI5Jce;(Ki1$WUX60keT4L+vGIOxnPasq@MVj+k)UWnP)tsW&Y1$~1(taAc^;#EeNB zI5Jda;>-+=m}s{HM~13QoSBAj7LE*6nV2zY14pLLD>FD^qTRbVGId^=W;<|X>bx== z-iKvgnOU7zrrEm<5l4oqOx%{N6^;y5nK&~Ifk`uF;mA;xi5U|DN2bmzGdN-bN2bmz z69Px3&MVUpZI*uB{&8S=iw^xW@Xvn+ouBckwk?hO1r zhTFC7Ux;Vld!Is#5fiC~7kci>eDiAeEyS-q|GEv~tklv=8+l_PZM^s2?oo)V?7QzS zM|y&_ofCK8=Wc~K@Zg&?1oW7d3V&%MZ!DyZBaXOpA-;di{<|FM3FtX-&ks)u@$hfl zsv)4qth}jEo|gDG^M8Er&_dk*3b)ziNKZh|2{JhzkS16jvsfGUI-jz(#@axzc8>G} z^qlx!witpvV1nf_i@i!4?2Y^?%3g(FFFVo`&~xG!A9(#jeDit(?UgzU`Mz=FOXqaKuE$Or6#-Q&$kqV#`1E@soJ- zrXw6N!TTn4oYWPBv)G5NgK-uXJxLO>8TGreuxLu5t;L2 zdaZqq8*qCvH^=l^KRkAbcTkq={2v{WIasE5J?Xe1eo663Ui`%4hIk+=*2-&wfnwrL zcRFr};nB5Wg5@y_@1xFd(h-iBVEgJUC>_Dpj$7z0-zSDeot2~`GQ-WZ&YUyNj5^ag z2Tyr}{Oeaaf%nEcf_KZuhzY!?I-Ac5!dbj?{yXa@@ZNYwIAVgcr_PDAf^Zh^oIn3D zC-B~QM|dxK?|L7$XQCq}I8LuW@Hp(7t_>5;@)_E;;q~=)@Lv1gFFApC)4MhtF~Rqv z&QZ03a2D^izy3of@NRlXIAS7mVomE@TPp}>@m~8i4|opmrgsEp6UPH2uJ_#}0A7y0tRlEdD5ojmM7sCU3J61KM#4z#nT7g;FMwg{Hy0zs-I*WF~RcouT&F^zffl; z-JrdLpK{KW_89x&4riUr_zhhfnKg3y7cYPA5F@^f3c`D+84ILX{ri9ExkGIHZp-og z#|Yzyj07Wu)VXt45YEcXo72zS;(0?x73c`>E4Jxje|PebktCY^*6u6s9}~;B+=R2( z>mPf|IT;mhcgJIlnDCx%*UEP??l^Up%3^En{;uZxoe8c!ykExMu5H7FvlwgOLI3(3 zjH`}t!~|D6YV?cOM4u(x+o_*&*Qf0|A5+%`M4jcdoJ+iu$hqWCYPZ7?&asi;EUELp zc5Qflxwh9i%E~AU|M!-g;O%6aB8{WIl@^Na9hxdEt;hom`efMy!Ok}3uX`Nem#acPb*OkS!8m}3? zmeAhcY(8(uC@5VUj+kJyp*j!u3c^{e;a^<%@(bc7=&7;T96+cRQNcilDNEVlg9 z_d1dBX1X>UF~K(dzt5b==t>>ohzUj;s`GGnYh}V&Y|}0O;3P&@>e_I`1lPwp4|msw z31_i}|M-cM7%QnG{LSH)9&ftv8_?gh_AGJ4L@|o<4$I=NI}^_G_oi*b5fl8rs&nmi z`^to~d_`^B@crC(9PhW5aKr@1=7x7VnNgy;y=%f*?eVzakDp%pWKQ4fw>KGul;;oL zu=wDY=gXI0_7l&JkuAT=&*#Km54&9<=!x$M#+u}lQb(U;tguU-QQA1})4$#j&eBMg zAx`+hGYfI2-~WY8M|y%bcq<|^lMc@+#O<&6(ZK}EW0uCx4DqS`GWSRR`}~*wc5tL8 zpm{4I<9J;(Cth;iZ5sl5%-S9Ylo3hSzcVLJJMa9NBRv6~RcVQd36{q!t?jH?tEnSB zQP(hpw!9&$l(|H6g|?cEtile34nEw;~+V?X`t8;+RJ z8Jhj|&s{Q4jKXp>_;{mX~#Vq9P9AH1_9qAZW+^lD+8xV@He zq$jB9V38~*pvNrFq0$nLnDD$QE#WQnmV1Vhmhdb(p0y`$sSnh5<}*8Z?>b__GX}M7 zm~a*|K2Z6Y&jsN&95Lbfk=iy)IExt{sQk?5f^Zw&i{885hiw~3^O8~d!MSA4Fe*RzknCxyHLJf-CTNe!&wQ3Kx8cun*79qKuTh-sRDLk_{7LPW zJ7R)w8kL{u;Cmt7-{HOfVM=m7n=6F5*$ye>R4M$AS-u8@BZo`DLmfsD$zN{gYA1pL)U%OV0m|zYjDnIkN zoxD~ioWRn{$UFCRpaTbNW#_!fj-{hfOLbjPhW*T`NaSFjp(JqWLVYJ{~5V1-(5d zs|jYmq`HLJ?|FZjd6OE_d`3?bj+pQq!0mRJa27L&(o@Xn2rc2ejOUzOe#dddglEWX z+c4oQ<}so+F`u8)TkePn&n4Ej;l0aUbesW-wzp?$avPqFl>J7Hg=64PTHb~U&(GQt zUSF=e_%Dq$i-~1ew$gV%IbT(J_m)p$$Hz*foV{Z%e zZxp*`zE;`Gj`RfdoZ!f@9UMs$ERR{79kjtw%@`0lJ0LF4+2V)^&NFDv$c(@HrE3=A z>eu}JhHw_kv@s|0KKKT0pIcp-6>Ye6mPaB+L>XC?u{zuBFySngsmd%8 zj+ltqk>7&F80p&ZvE>}AF4^F-r(G*YdScv%%L(u4m_4N`!}z={;fRUV$74KdCcF>Z zHXJcQ+tsM**2;vle7?19c)$C2aOPM4r)$Fz6MRy&omLRe@^`acD@RPkx+$aVGBWLQ z!ddM z-W@KLCgwJ2iM+WypW!4kosd=CoU&Z4q>jj&{bhC@X48p1Q0Dnz_MW^mRjM+~J1Z&dQrrr7FYB4{aNcnBZKfKF$ilS$VT+s6I|dc>l0>tKqa_UwOZq;AmE( zYBz0+``uZ~&l0b%w!^}!8 z5znK{uf%*vWK|z$53fEZXs`M>T^qh$Im>s6cCEa=tYP(W_HfHh#Azv28RlYY+wi_} zmVfWGgpY@5Z(mC|VuJRnkJGJ{31|5@wQa=O7^;u6>ED_0KZfe#A}Q z#6;c~FS7$P7jU~BCY%+kV5sl!cZBaU+zqNLGc3R3IAVe;Lv>}kHcU7x4#iN7k&bZ0 z1XrT!%5;SHE_c!D%9QP>uFP(T>dKU3P|cUYpVaPMN7&ON!QQQ|OxK3jm+NkIWd?6w z+lC`1xHD8&rfb85v+{2JP+gghaKr?6xa!Ju1V?b(i?ml=nLXTBCTP35GF=u1wd4BPQ6U>dJJ4BPL=*4AqtC*2;vl z*rw{rbZt0df~$6QWx6&@IEyu`u1rVxo5QcL>dFlMrnN`V5fl89S)02u-FBF8me1+7 z4M$Ay+o!rRT^lBx0~gd-+6Hr18s_O1zMwZ|il%m%$5I5WJd!LtGH zPQ;O!v5Ygr-|2zo?-|eXVT>|5cV-+hf&BoD^RTuSN2U-sGbWs+kt##Pktqbuj3Yfk z8@Lo1;qQtcow8O~9VS>FvowBYh&VEZz#MU;C!ldcGV8*5w=D$Dj0u*vv-UfeeTAu# zF=fx=4fN5O*^cxC^cIo&=pwPUw%@s9R_FXvVP7W9~v zy-@zXwRa0q_wH7tC!ps<9GPtY+?nxbu{>twXqHc!pCxf*3c*?8h>4s%Q|S4b7)PcM zI5Q@k#q##K8%L(paj0I#kr{Aha6dRJ$IoSX&xkQAj?4^K20x&9I9qLS)auyd*?$i^ zm#PeJZpC<+)v*mbqK&i!)eJn4whg!Lb&n%6!W zn{i}jRAsOv+BVo%R20~Y5cKb3!|+K|Ww0SyqW@fKEPU?rHXLDjBx1bG>d2~H8z!8^ zGF2H|igv9WF%d^*MpXtgq9uH6ImhZqz?(jMTEdZ@8290F!h1T7%nVls@1!LhF|qo1 zj7QCc_hH+HBPM9Ojw9Tyl?iA0d~4hAe)sX<%%>`YYtj;qnBbG@sJAN!XZgF?w&940 zj7U4HqwIEVm~fWA!KIB-W8u0R17#f(g}0>h_WR)&BfQPbGBpd9TOwA?I(7{nK&+Z| z>>A!+-!sBlv1-<_Yj`uhZKGeSaZTdRtmDw|-grxR-Q!3cjw^u;;r14Z@pDbY=s6s- z2Y+HY;jDN+htt>38^JA+x4RFoGn`-t9bRWtDa*Sj^5*_}ot*~ey)almBgtL~PC0<`|M;w_6RTB8daHM!!&22Kg(ImuRi|P`uhk$Rc7&e<%o$m zG80@G-ZXBv!-TWAR@Qm2I>HeXabzaAGQ2U}wqe3q-XksHh>18d>$oz!)4iNt*YYP45poa)xfgtL5{+BV|IOsLA>v*dTw*6++XGG&xB%$SyN#01OZ@6VQS8*yYN zRAqRl*K|ubVj_;rgsKd0>n+R!dY=-CRAm3kH2lhcNy*mb(Tu3%q4dmM@(>Ks54}CXNd`C#gUm%mBFQG z*UAwST#4!|V_h5GyWBU%Tz_ z`f}Z^vzK89?ZK9t;LcFzCF{1_pXIDLG83vYyp`W>ha)Dq!_|4ox;DHQX|K+zx`+G9 z1Z~%OU%R#P-gTCbQ@b7B?=es&b$;JHTq_fCOD1)0;T3D;EPo#t*J}K(`8!B^RAum7 zTEY<%@jfPXhVB)Fvsgo_GMF)K8;+QW_c5t6bgv+s#gjtx~AY?$SQv)bdq z3^Y7h;>_foiSlf~`}52|!*c@841cEwn!m5DF#`=mW~3>^7%>soq0n0vL?Liy{8`S5 z5mDOMGA#;GO^dBaPq2ntHb)_FX8c(!k6AH0$|uc@5oVxaJE}3V73m4+Ei0uE)k@hS z_}noohD!PSmiaPYtGW5I73m4+Iib00aAmd#mdC8D%?5iNQ)NB_4ck!-o~=kvK+g$g zpn<@d@n^9-W@WFIPs-j%8=B__6KN~b6VP))a|tyB^q7^iqkK}1YTAe+Q`QP+#t{=a z0}IXDJ!@-mWD0>ZW5QW1v#;hv-a^{Jmh;XwbJj3-4Nd@OC2PeQ&Rj3lCU8PZWps;h z#01OZx1c551~bCYvyDYyx+NSj!K^CuZ1e8^a>7}xEmf!8Z^sxhL3>n}Si`oBylpnl zUBg>*)6w~11{$hM*eNaHNKa6eSxrEXSYTGd3EVi7Q*W#9YpFmJo<8!?a+cq3A z;kK6(&f?fmD_T5)j+j`!9sLm;j~ZtpRhh*z(Ged_K8dOf=R&(3CYQ?T3;%=JL^h4;gmvxd46?{T}mmT;ses5C8ZhY6O)EM`2R zPal_}ZNm{0Y#%iQwy!0;h2C;zVJLIg-S zVuGVdRfeOvoNyN76;qYr4Xc)L!~|y#RT<8n<%F{s)tIVGdBe(c(e3hH^xpM8Y};_e z1jmW0+~N^5;Vhq_Z5v)+ZwGVMP?h1mua7~OBQ4>G3Fc>@D#JV7%L!-sd}|4=mc^CH)si`D zsLJ4)_&K;G95KOcG*o49P+Ec+VW`UBVvt2uhAdyTTfz|&v`1BjHC#?OYx&*4>&qHa zm0=CNeQg_#m|)Htsxo*d%L!-kN#iezmhka#d)^~0;fM*^qbjqwRwkU~Rm!c&cF~OCHs?6f`%6pglE>#)s$h1vWX7SDm zK~;w1!JekZ!ZGkCwQJ>w3HB~knZ>>9_2s%tRfg-ix36u(5fj`QsLCwfaZEUi`DCcd z@Q!`kh9f4p!%>x4e0ud>q&=!K95wHewhc#2&^A?>#kDfwEdD+or?w66cV=s$DuYGh zPihHAOfU}%RT=z{<%F~ReQXJT*Zdu%J*qOSVM{n-f;m#C%HVD+C!EC^Qk7ZU4o6Hd zM+#LLyo0t46V77GsmgHeY6(Y7uuW8D7Oz*1m|$)Zsxp`nZ5t+>#WqouS=?8SnBb~S zRc7(pZo*ltAyt{hedTWszrv`>@cYc)w01ijF;V7|NmXX?mzN1=`J8UsaKr?^WT?t4 z{wgxzEMHOEHhjPHebD=@B^)uqv7sunc+5>Wt34iv{O6^m_v55@{`sy4UGuf2clnL) z*mr|vo)cKU@B_~&f4}&=-`GeG{hdEih+AIwF}ob;3FtX-#+843ZXq6fg(G)4(i6~g;@pousr1ml@wTtpc-rY_PM`bmlZQ7PaP4M0 zynSnHs|fno+48Sm<@D*dFFA2|;=}jKTAA=?(cVvg@R}*@Ehil5i9dbf+0(@~Ot3s= z-Ss}FP7mJq#Nm^tT(Mg#M|$G5Z#!$cnt&d&e&O@aoqpjjPZ(}=@V`#mEqA0R?z8r) z>1qOc%(~X`Pn$mDtLe*l$oslB9O;Sg9Q}&vocP@;$QmQiS2*vP1GGP>B^)vF&)5It31_jq@!Hd;i-aR4 ze&JD{n>^{^PaV#>$(y@2OgM|>TfhG$(?!A&6VJNumnT2J?vsY=Kk%=+HcU8+iD}Oq9^e?|^`i6h}ukM)l#CXh2 zu>6CgPZ*%vHk|c<&s}f&noqrY`kH56Wn(olewK-k{ocOQE8X&}=>@mCTCSpAD}R== zpby&dyn*&w!VweiJ>V|WW3PP9^w6j8w}NmM^b241ykT*z95M0WzrD}&vHx(+^rBPu z@7gfoEaEvN?tsF7odvLquCY%NR#C zgKkG!;zbA0#uhPJzYVdrww)DvMjKmemGAD>S}D>J+uI>~neEsjSRS*o7s}ta_HJpT z?%l0OPe9KJ=DB07>Ji)`_}nooN3;BWewHxL9Rz2IBPMbt4$z!$YirDN2N8$2A)LkX zc!oA_Q*FdiEN_d%KP_kY__@q~S54M@y57^@aD?x~NU;2Ww-KvxQa#9~y|xX1u8FvW zlj=csYh}V&tZj9aJHinYv{zl^j#yi}X#eUWm-C>y$kW)eljpOKGf^Gh6$JE{ z6-#hZ9o~*`q$jFB+!1jqC)MHI_+n_SPkjjv@xF5&VsJKdq+58f<4V! zJ@K|z5YF;mXt%==6Pz*CaqrqN;jD$dTb^EHPHyB)*;zG1xDIYzomn2QsAa9Th%oVsllJtG^MGac8xDr*ZIhR_k{U3ECJxH*Vj~YW;R?^lLQ|G2eDp z>$fAAJ*oP&(-=b+R=>6^SHHF+ytOevFRY&MitX^an}~6GVfBP})5f^&&SDLBzgF=F zcUJ3n8b@(wwSK30`+HWc->wZuOmJ+f^}B*_R^AbxRqMAS95KPUP_5q;gtPLF_^evL z^Rs>HO!QG>UsdaO#S!#gG{Lc{)^E2~CY$h7g z6VA#T@w00Ec5OIfBBs^OYW;R?m~d9Cn_0DfyEfuP?X1@CG!E9zYW?ov_rnD3RqMA~ zEAMw_Ex$7Oio@Ant=~OdD-(Rvs`a~Kt(>*|>f>*%zmE{r`t90q#6(=FS+#yw5YFOS z$@?W4x1l2(F%jo$R;}L^gtL5{+V6)WCSs-Stk!SWh6!i+d~4f?>G_^&X|U5YA$@ziN|rgd-++`lz<_3c^{;xL6I>j&Q^T-_2@auOOTiCw5kC z*^Y3;1m|@1l2;JUTK=td!~{pS+RI%VCY(xK+*2;vl z;>6CXE!z=}m|(A0zj_7Xtk{{eYRh(nv)FIdyxv$&IAVgUYaK_SYr}-I;*ZX%W!e#r zm|!2)(H2$^&f+>&M~&zRM@+EStLeRha2DHFz3q@mBlN}%Aeb=l?i9DOz-d_LC-usC!-0{J~wrk~x36|;EUR*0jOk~`|4f?6mo7=Tv!dV%|a)Vy=^v!leMutou z--$!|D`)gi(odOw#j;GVGt2FEkTph3WE9K|dLYxsxPovN%k+yc5{{V2*qj^m2&eC| zYr}-I*mC-*7q{H|1cFKfpX+_tZn+~S-1c(9SsWXB=ogQmBPNz_M}GvzW5ZR6esQi! z?OHkFqsb>x1>js*PB_cgv6gVe#D0&x&IVP0^h$Sam~fV_u1y=eGGb)08q+_vo)II9 z)tH{0^^7rD+@|T@HWsTfJ%fj5JjP-*=C^KHrgxa-mdMy_ z#cE97%sRa(^oyqtWyM-~O?rZ!^u_Hk!Sa}u5h{z-m|n?ltsF7I_R&Ym_O;u=){a}~ zEzhWF#cE^}wU)@pcg1QS?^NVKE5{{VQXwvJ<(OgbAD`QL+ zt1-WOx;7j!!P!HvGiOiRh6!h7q>~MLo%6e=Yr}idd)NE0ZNm{094BfBi$~CevwViO zZFqgX9T`n!gI?$Sw(7RS5fgkr=yhKFewc7p#+clo*Ezqfx;7j!kS?(^s;dF(!-En7)}k{0^F+J$juN*NUS?Rfcb;vzA{=e2wC4 zr`MV9hd-%3f{vKrn?|oQ-?Zg~vwT%*34d$-eT1Obnd?|fIAS7WOctv#y)NDHFySn& zcJw-PeQeus#6-rJELLNBkGeKYILrI6ZNm{08Dp|ojp^U&*2;vle7?19aJ8g=m#byQ zm@HOfdTkH$^L0x&Vj`nQ7ORo5AzLCNI2NlheWHhvMb9=_zG}CGBPM8%o^94}IpM73 zcLT34Ye@etYv}E3+i=80#+WQtV|sAAwKCx>{=VB^EW0wAWAO(Wc~QSPru5j+bH^Bt z?OHivLcbY0!fj+U$Kns>*J{&V+lD{aL`HKg{$PHGc4xZ@XF*fDr@gifpNZaYJ{MZT z5fkibssM|}!-TVZhPG|^dd_v1{&ud^%dhQ@nBY4|e>>Owwha@`%4m)o^tY$qtlL+P znBY54fBWKZ>}95KP2f&TWzr#^3a#KQX<8 z6Ys-zI~*~QQ9?K9PfY(`w^k;cl~MOL=ub=!RYy2tBBLN~(4UyTz!ikEGU{IOywYRT z5#A>}Wzwh56RY=OyXB6U;MtBo{l#Zd6V76<)2F}tGjWWV;MtBo{l(`*f0na2HuULp zG~4ZP#01ZF^yx1?Cz@~;$A&)r#bfS>3BLdI=`TJfns63JlRo{$WA2CvzBlygFJ4Pb zIBWU$+z}HTS^D%Bzk?>65uo`9Ycu^Bh% zZ^u0Jns}RH9d2SD;uNl}nTRDfU}s@zv5afSatyrz2M@EZB^>DqY{1n7^q4h#{_^3h zd!9Kx_Rv$hHXJb#H*pjD5T|f)t^B#SeD`w(K6g3c2<@4`oLp?f1j}RA^1bUwPhg)e z9uE^Nk6AvlYiqF?cX7;d6)(EOyN2Vx^UUFvZ~CL=2>QsjL=46O4-)e*cHw}Rh#|-_ z#v#is;fM*hy_|3s%kTQ@mrYsQmT<(x^6iMPIpA<&o3V_k$?}hW_iu*#|HY}(hh6Pw zxh8sFInon5-}IzmH32vG5fKiFV*bHD^iR#z;5|8n=)3TEfTKXH1OA0q+uru_a>rZDRdl?8PqJ z#4^MXgustnB;1BScRAsR3EIQ8q`h{nOgPJH+Y*lS1g<69x14|;v%IHU!jYbM`Ss74 zE*?P>ERR|35q#Uv{=J-6H+bqJ7;T|=1-be&N3YN@PwBU&SIHopGCqE6A!-sO$MF@-n-W|vjuL$ zgtJ)YNoJ97#Kgbf@-72U1CKcdPuOjka2Crv^(_*PnDAb2+c4oQmbZ_`3HQPk%_!zi zeOYr1d~9y>pwG^D;<(${Sn(zt=?R`o7Kz;LXBx#}HjdTsnswrx0K!fh`noCW>T`#pJ}y_Rsq1k2mo@u)wz zdHFT*jDNl3j<>$@sNuV(WxU5zE}mZc{Rfukgu{+`*YvqhdwO|(IP#SDrwtR1nBbEh zd9#esnon9zIEzo>d1bMUeyw=oV6EI<+lC`7kHo9)ezWqF@$ru`!iKlQgtJ)YnPHJ| z#KdQ>aGl}&$31y?^rv3dwPC_pEZ^rNr%e|LM@;yvY`4RNv-~YsTYKLnPb$a!O&>aA z!$;7^;8EusJM4Y?S57~B6=sh%@h`7DbKnW!7jIU^#o4;!{Q0lGX5gvjw_bJqTzyP9 z;yaG-T`l3Y@|v)G`fH9K7T3xV6HolsbIX&=z6UV^jn~SAvsmUyW|45j#F>BkqJig< z_g(hCT^lBx#WGJ$i-aR4*y}uTu-Dt|FySm8rOX-v0_dm;Z6sR1*^!IGF;fM*hy_|3s%h$W!E2gY%OE_X;`F7}DL|@GK zd^Nmt^J>HGZ*|)ADbIRI*M=iKar|wL9##|3W0v<}yB&`71W!xs_2mTgnB_fP`eJtR zyi4Cq`d?;s1go-K$1I{}WmZSIN*n3D*&-Z)Ho;R3eKyMp=rJq39J?aHd8D4$mH*{^7a2Csd`=FOh7YRp9`1rS5Zo*kC*IxixtMtW` zy-UAIe&d%X8Gf7ls-1q4@+8Br?v`-G1k2mkcDLc9=Hs7!l35+us#_})&SJTaK-CeB zm`FcKc`l)UqumY@&SJTa8`Tkxm|!2)v8h%N&hlPw*UAwS?DaY}Ro8|IXZhHyt*MT) zpS@i^aQrS=k~S=?U&viv(*mwtmI^&mRuh z@zUvmkNwQdYumQrh>7&Yl;;xqI+hd8g8s8VJZ7N1mT<&`w{JP&ENJ?c7T3xV6D)7< ztMrqU`v<)T>4hkLB=jDn-=g$i@XM8D?$j)=t(kBHn)@!aKdB`gF>&%o&L3WUw`UGN zyxs%4HcU8+<>3x5n=TTLm`JZj=`W$@qFpN!&SIITj77o`6OVYu3x-eL=BRAPTGxgN zXR-W{H=mmA=m|$m_{?v&!-TU~u63N8iRmZFeP{j~+V_wAPA+vEei8f5ut;#N<@b$= z{E{z~6ncjAseU+|M~cZO{H(LqLyNKY8i?rHyA^`N?VHeRuuKLOkzRKd|9QPe9L!vmXCfh4}a#-`Eh) zV^*FeN*nVhna6$d$U+=>&^bK&Y(;tkdQLDRH{U^eLA8gd;ss-!JKiT#={a6`AGwCdVwl%gcz} z`~q*=aHJ==pDz-u)!6#u&wBNApJ%>gdi0L{%ZS|d4VbPCZ-)uD-L91hXF;!j`Y8kL zwS*%kSl-?aM$6`S(0g#mL7$m^c<*C}`#tYtGseEI?|aNriJ#W@Kyp_z;fM)7>0hq* z@+qIRoNyMORNp)4h<>ej_MwNu?X_(sukS^eJrAcQJ;4xa=p>JKW-g;UVXKKl{pr zBPRHy`nE_%IAVh3`mRa09gdh_kJNWGRuIneK5Vzc5fkjg`esenh6!hRPq%G&?|Q$n z{Knyo>F)RL7%|~*bK8bL%USKWR`X_1&6x6BlJ%yKY|5FzvgYi_8MR-Xo8#-}KVgR> zJprBBJVI#xkA~3P9Mp|U+qq+h&>SOFm$o83K^t=-{UqfcMW04`9?EPU^cZ-pynUr- zWsAt~?+JG@e&4cO-xeA2+ke7cl;7+v;Yd%^_e)j~&|}uwU%USFYhQTv^!L7Vm2A1U zqtAN6-Jds*wVZH-<&j7~NtyqH{*AT`6V76pXOu<45fk3)Z5t+>#WK%Y9H*9W#6)`p z^Cm|*g7lj_{$8J$-2Km=G5p1&-rpQSAKB8gvPGmnWK!P>p@(2n-$E(N^$m|4LAOEH z7%}0tmlMun`Q;xxeahOlgd--FZ%6vP$GJ<&`>ypJmf@<8|MFz#UZ+mq{RV!qcsm?{ zHt{!?9XYHfpvNrl!?q1adV(hzdRmqf&|{YOba?|}7k4#!TDZ&jY*_yyj!VZvD~^JFrrN?pyy&a;VkI-21G|VV&bj$IemJ^FP%7?dEs6i;Vt*pvRvOU z>9*Vv6X{tgbBxdr(QbzcXR%!0FX;$JOt2mAJo4=6;&zyD*77ZP#02}TzQfY(D-+K0 zUSC^Ne+fR$*hj)~FVDN2A?l@=HvJ`=j`Rd)Px?zjsK2BkpvNrrQiM={$)+Pc0iFJm z5b7^!29KA%r}0-F0_sWfCC&+njlf+@erxnHo%lMKrj-|DB+$K}cL z|Gn@Bla_F#Cw_Y13Bzgvdd$jGQt5NxxutEx5fgd3C_N!OA+&_IoaJ$A^Q=(%eRwKp z2}gROR+?52&|?;BMZeGDS~=1awbInJVZvL>9^naa_xoy$nDBlp^^dePzk`0^lm9%u z(=(18K6T@dG{@ZMLQCZCTY6Hs&!!eqdTzMSvdj|>%PrxE3AeqRa2Criz2D2HtZhp; zVq*Dr=r=OX&)8Em`QMknbb9PZPMu!m;7hwU9O;ScJpQO*H329lP)(i62-)Dd3av##-)>3h!03~2}5qHM>weQg`wauaTQIpHkmPhOt+ z)zV%|IAVh3?d{;5TJ|o_KzZ&ceKOq9e84y2vsmW2WRY;h1pBa7u(~!(ILmvzT`NaS zu-9u{t!u-CvwUpU){cJSHOe>Yp?e>(iy6^5Qp{@pxvzh?ET8-RYi{s&?pOSMZSC3j z-lq_^z1IB;F-A=M(Z!!A^mYIB>LGsZ`PVJPH?MZzhH%zfZvVy7#;)h?9pWnc?puiW z{@XovInooX?VLF9;F}cU?)%)WA)v>sM?C32N*muhn;Edaf6V@cIO2#q?{cIkpy$NH zzj3QV-1EbehJYTkPWbpwOB?w&$K(E2xXpa6zIW&@M|uK!PTc)_hZZ7aLqLyNS({Dv zdOjs>WNiwOwcF)LPe9L!Y;hsJcg+3`0X=4Aua-8lH_}G-Y9X?hcRA7%&~qY3t`Iqr z4FNr7j$Ffc;w0h{m7mYZ;-Cm11ik??k~R*cxn zx_ghbZ8&1$UoX38U>w+oyq6gyy;dfi#eQQXSN3#EyzotL8yFk+P51rs^uYI@KQOZH zAOFd>%a-qcJJ|9uVuDX%EM7jTZNr4KyboK#>&rGVjx1-4x347}G4UH;+&M6M>jU@s z#cs<@IP1orzi?pm)(<`4N*(d`55Ftp?Pg~5`~GnH;7?pIFna4R-08o|GUI@<+^!W_ zW5mS9r`|mj{CoxBES4F)b&+ty#4Y~$J#n*68t(CmD|Fjo!dYxNqqi<@x%UYK zqqp+8-iPg$J7U6ZFDIPEv0?Pq#Utp5iRIhTAHnh1a2_*yD`$SYR*v{+@=1)|%DJ$d zaF)MmE#ZiX|NP)P2S#r_<8$Bb+A!fPe;>>BHb=g+wIegXZ!%KZM}NA>6UElm*;nnB zc<&eAG%#n_5C1G<2LIC=2IdU=-8-B$9X4MxFcRbYGXBnT!dcJ%%3B8J4ExB>&hCi+ zc=uTYvv6Jhg;!1g=UuNJm|yEzFPtwk8Y;_e8&Cd+*A2`j_De^+disL*zjk1}*E9Bd z^@_Ffn)C!Cxh`&p36{sKPwzZ?V2-LkJfPolM@+DNjQ7g+wcEkgj$7z0-{<@@2j)cE z=Po_*(2u-+V3x5XQ}@5?Kb|`<%h;uty?Xk_>s&N2%h> z81HrQ2%2z~&(O9Fudlb`ikE$0V7%8W|5v{qj+o&4!FaEW-wzYc`q`~MG%()lTVMOP z-M(_f!~?$Zwt-p3&U!JwAoC=)b!9N&tn&~3*uZ$NkN6}rznl2R_s$=fW$Yfi&Y9lm zTW=qjW$dV%XB5PxR|ZE+&>rKxF0PdcXDz>$_!`C8&UmkUKm1AUb~s{!ZyMvh@=aS# zILlY1mhiXM-!2Hod*wRT5{{U-~=S4+lwavc|sz8^z!M4zkbG)EXI2!%UA8T4M$AS z9^<{ThRX?OEx#LheOW`sdu0v1eQg_#n0V{0Uo|kF*S9~_Z@CF)@%Ql;Qrm`)hiUJT zmT<%b?J?@<;#!$-mXA~0hOcT|eHitW>(%lroFgVU6B+fCD_`4&31>av_dYW)>glDo zVq^-R?T(n>%xBco#qUS|499O-eqmqzI(u(29^FwN-0a$L#7}zb=U;u3@plh-%Ec=P zXZ^;DuDZ$0Sw|mwQAc=v`JOXQD%THh-|{Ut!Ig+{QWvjq{w!zR?a`MEjFbBKliu2` zl_Ms&qB2hE;?vR}pZSx4F=c+h$>yzsjNW6J*f+uu38-`g%37*lq?Gy66iG4am5 zzCAFe?B#DfzgsI4FZ=eF2F7B&`wQPTb=&Q}a>T@cAN93?u~-i{{k*OX6V4jm^z(tS zSa0$1cXxy%CiZ&vWdmce{`j@;SV1`J0S~#-CUZNTc*%tw;r-4NAY-xeH0k5iZn+~S zc*2U*U6V76jlB8P0^WIGT*bx_HbTF~N6}u~-+ca3-9!{QKdE363mdu`Yhk zO*qTnwDx%Te1&E#R=%mr&s|4M@SSHYR<06l8z!7}y{}(+lUc@olaIAVftGh?xG zRchNX;ViEC%+9s@yTKSS!S|oBSQoDh{w!y)eT>Dr_&xW1g8LP-jM3-dJ5jqGj`YO1 zw#x~xA$x?eUw6NE$B2n`JLoG}TRX1wZa?kg9~_SO+UutuJNv+m`~2X!WjX(r=PUl6 zXO$d}`G0fbp7(sogvg~gz1v2XXX7$CEMNPrcQ3!W`2Ta_S(}GUiTvr4cWgf8sz;aQ ztG<7_x%X49RF=Q~gS%{!&3|(uS!GSg+FJgD!#8h#_T9?gzq-EB5pKhud*9nUv8?R{ zd-ZKNVuH1(+tIaQ!ddxy*$caEqlt{4oA%0fEN;0!%URjJLa+~MoBy_s;FQnJ5!~d+ zvCNU=$g#}R<~)BSe)(FPC33|x58j-e`iZjq#Q!>A^P+qFuq^-4X*cZJaKyyZqma|a zU#?$g1>vlZ{>MIrc);|RI>HeX`RqdEZz~9AJ@6JcE5uhG_l0iD9WjxuFGRL&1>vl} zJL8Z->~queI>P(i$HR1cJRC8>capu!cXT=7tmSLv$nJ>uy!D)}4HM%sS*Klchq6{5 zd+gaA;fRTczwY*hIOu7N6f*yBe(suZ))yW!Ed<~FmT<(xRsZ1dJs_O*l^5Ts5dX8! zUAi{%9V-#ObGg!#Wv)EqHeKmSw_Z+6^|{kr5em(fqumZiOg!V~cPqrhFFRoc;Vga9 zY-t-a6I$LgV&*;4w&93BSKG9FUk%Rko^IQ4#DtG#ON>V<=j(J_&Np?cGiKTnj+oFH zx`J?))~X{MF`;vM1>r31k&eim0#DuP6D+p)ly3!Gjn9!B4 zBgSLE5i~viouk=qha)Eb?>6`>XX!4{wc&^f-Mcp0waPWG?03$uUwZTLW%(hOOg5hU z*z?LVYuyt5T-~EKmbc-E3Ef4zHcU86_xX-+#Dve7b~{WsOHUtN8;+RpIo-Bl!dc7r zt|KNm&$!nv9uE`F@{w)V%E#GRdiL$M+>zZ9xx2M(nAloQR_;?}JGer$gr0FX^t8+~ ze0f6VdA=naF`?(+6@;_;-wCuce*$pCM3%=V=fyTkg!Ofno|Zep5fgf*UO_l3dwSq3 z$?uYm$eCCod8X#NTbB7I=UY&g^Gw|lj+o#%w?0#^Ae@zNb0P9f-4TwM$W@{ce3RQ_ zZo*l)@)aV_)Qi`|t%!+iefc}z8ucWrtaF{cPnQ#*O6SC$}-ogahvi?-4Xs=6U*Ch#Dv>!x7>uYa&0MV z_!nPf_M!QI^Xru(Civ~o_HhkcPB=@;-BY+emnY=%x%^65PB>yhYumM9!dY5gu^r0d zmql5_{9@_aP}am*TJG8y&xU*___b9&H&=r}XXViDT}MplTd;y~md>}1aKwbZH!BEd z>8$JsU9SdROX$TJuY4WhhzVWoRuIn8-Dk7iyN;O1)w8S>?Y6{t3^;;btMTs~&D|43 zOn8qhC!D4GO4o)XCUm#!w!>Mvt8FeP95JE$Zr6qhXX(kHBOEc|m_U&3ZVuG`VtLSRNS-Jleg6lxr#@4f1?qXZZ=}%rxIAS8t^QDda zZtL1G;Vf@oyH>dxY_Nsgg>$7Y%iJw1TI9!dWA|*bnE(?ue}6(5{t)&btm9UsCGL1G zM2_$ZVr^|ZD{EVh`EIvEk!>RF>F@KsHGd-WXE}@S1#6Wf+3hPwOz_=<*zNJy`YdPh zEry^@)gD1dc1z@{w4B(YlcnB-j&Q_8u1f!(vGahNqpJGVaes^c~`QDrC z{+G|^eKS7ieCM2dXXehmbM~AYyqbPYBtb2F<49~!LPBG3urd7=Btb2`B?957Q`~Y& zNa)QFi0Nk;B&enLRUrKKj%`pv!YfK&LC>aQg7Y@cseN~t@KY8Ol#uWpXu?l*XM$Sp zRTF;7VuF$x5grFR6D4geKdrW*FEPu<1SKRqA{4~X&IGke+D}SV0WEnOuK5hx0m%R%d-!|HN_(VkOQ_}N!tKzNOj=F}2|s%#^u%=`sHLkJ zi0QxFQ8GhfM&DlB=W5f^!VEC+iV_l-KXxIgg_&hSP(lK;@atMD6!6<)t4#BiQG4}|C*lg{iF9p zmBd;nK9IflzX{pv>pB-XwNVn(!uuofiV_lkYTTENxkr_UH*h{DZIGbWS%dD)jy!Ba z_TS7|jh%?K&#Y&!+sw(*`AF>mdyehl%+K&^0l5rp3o;`Z=`0S;H{^hws=6k{a#_gbl#78^cmK~Ul z&$c@K-7W;RcD?J??9QpmXZYmJgrMa4MQ_Pw`|*|8e}49Ak6w|ub?nXAF#Y29mK**4 z;9bIYP-~y#Z_4ic%N5y>=Uzw%O1}E*@3O^rxgtAu(?9p<6^W~}8?tl$IxhSC4}VN- z&?{>FX#Dlr?z@i5u2_C*LQt~N=htPI=(ny*OnazDuSh8CCY!pryxRSt#0I^h)@*~W z%ieqO@@&^j?oS9x-dgk8?3uBbXZJtV?9nR{5AHoFJAJ3iv(;wz`@GW?q}DYTP0SWp z`10)Xjr_}H5|o_w;5FH)&t8_zecW9=dPQR2PbOrqU3gh`a`?R{ZLqJXwb}9$vhOKd z;lp=-pLq57g5$Dh_8*(gJ@|_3?Jq9R9#mG!B9lYrONVEW1nvE1i*eb%jvbqQa=)`0 z=@rjA=x>*2lXn`MeP@quHh5kVOFp7p`X7$XR{NGSUuc5_wfy%oPbVhWCoAl9b$0H2 zmu35W=awF?2Z`Cwx+?qkA1}?G+r_yVoxGx!vH`P$&b>6-=1|#tMfG}A>m^arYn`DMs5;_KP=oA5$DgeP|%uk`8WQZXxp|v z5Duya;_Y9p5_v`9#aZVHwEtCAm05-b!vFGI)N;GrCd(@o`|p;!J@&JlC;GUY&$-3^ zyW837BNOg3N=U>u++q{%0TR@5>utkrt5n=#6Yc>@NU%-X6G`)26TbGm=GV=!Q1xHy zs#?o34@JLWiV0pd5-ZNKM0L?iuF3Yh+;2|WAVID8nv?iw$}H7c&c8albi$PE=C|gk zUb5PRZ1BWJa<`M9)*Oqd>V@W_f7G0m?Tfvlgv2xR%~w6<&I#E=lbq*88ziX3UWkdj ze`>bJZsW51CdH%Loi99;Z8CIRcG-WN?@Sw%(4LP6#vB$$NX9ul%Ww!EFH}}|b z5-XhXYWCvxS7xW^%@BJZ!|tzf3MpTV$fHgXMa59s_cKgT|K!+uSl%B!c5iGHn=+ba9PhX*m8PBE#5sbL4WtE{VSW}HobK!cl78LiCO;q zarWHOS7qP7>JMGKq859kQaS0+Pxb6pDu3R0&ziqg_<8mh3Lkqc@$u7Rz89XT+P#bC zF+m9le_1i@FD;!3YMsB}8sVAW|ABcEqPEsD;TfzAeYyVjJAL69yz9k(*ZqaaHsrjb zGHeGW5wXzF@H|c$|6#o|@hPL9H8a9$fWP``SL^65^F*7OVQHU2UIcUNU(je4YuRK?fRBsS<3wZ`lqk6w{DcH9@?OVOqe z%$nGsSJZlOfzQI1q60VlWW)Fwq$C^jN%&H<>%U*!kY|bsN=RJu%}3!&(aw{mCN@Y= zYt9k>4qu9P-Q~7~ck<-`bnPRU_ zcT)H=ksm!@RlgAqD--8TVD6J|zU9VY?X&c^@2poUyZ!itKy3Y=?^h`y;p1|(RH^*q zvy%gH<@R@FB<`xW&iniK4zJU8rSjGdt)1V`zVS!QsjQQ@_VP`F4b9uH)BjaQ1sgu% zxu}J|YfMBt8t^xoC&F71=&J@LXgR$VftIru`{@bVBmynZDIvi&sk!T47FMa*l1Df7 z%bCz8ilb)x{i3gW-m}+aTb}zsluA?nx)ef7M-T#*>vyHa* zS7+Mbxu~_-Nl#|0%|9+1^s2wy_Py1snhDcUH=$yB!?7`eM&V8Ry{`jX3K{IUEV#N37+@mi~7Pyee0%!^O&H71g>ls zf?A7>U9;L>yC%zaS~VdkA@PI5*AH)>A57{`2ueucUg$zl%g4oCk`V0CEp(kdo^QU( zxm|jf{X^p5MgN;^se9}vj~`x-dzS>YcrQdFbroZ+Ghc%5{>2lY#bwp6B>^J`= zD;lY*l#sx9ECM5SL{JMOstAnKRZ2);JQjhGIwGir5mf|6>MA89;%knPIwGjWJ0^Oc z*FN3+?l2;Myz<34-n;pT^=`=4xovDV&w&@nE6f0Dl#syNIU#6cJ$qu|-x5>yx;C*vf?DsaIjFkO?pI~=Y>09Vv|R{lu}!fJYI!#7S+VB8QGKVF;JHY6 zp6hpsX0+;Ewu1z7W*7eSt%RV&vtf^-nge&~UD_bwS+Zx#ngb^`NKlJc zwo=Kz{$H41t^L23)6x{ejr_zC$8{T60ak zDA;&r&2^+Z{N+0XanF#$Ym|`iJl8ffW=gkz{DeU4+c+vBsI|maKMXc*zs`9q^B;9y zAWoZOM2!*>p6A+zMpNl-x7O%Dyz}#8BZ68!_LJ5kJTvw~tGQg&GhokzHJ8)fFp%>z zoNP|I`af%}RCB_ulc6$xswr(>_!yPn(njiXs?k1Z#0+h-H{4;p$!Hu@j4c4;}a z*z3WoFjD)Pd!Fl2P4nK!6VF;bifXRfve71D$-q@pkK|GB&XAy%=b#?vHSwl{QmW4%YS+1)!D+$rK4Vm`-*oW39k=4wrh5qw1Wh-Jm>YO ztr=}XP~ugKM`z7kqvx@+S0ujm?27fn_qsIOe)hLp&tSXd^eWckQ~R5fpQ(Ce`1{2N z)*f2#;?RrD?T0lyw=J*p)Fpl!{=Ut~HPw#6*S#HxbqkTcwb&z-%8{##(o=UcAF5Ckf80@1_^3CJL0bV zm*Xa6AMTXepoB!+4qrK6Kwp>DmOL+i?yKKqpRIFN=+W{TkZxV;lJFDb=gw{Lv7ZSa zU-9SV8!x?hO}6(O52<%)gA&iBi?7asF3%Jbv_Zmi>Ef$%VuJ*=I=6#bo=X>Bnv?sA z?cljccrIOhLr%ORL9IcvJeA+DTPglFiW{{{HyQ`^v@{+qZJCR^H~qDkUWR z#x(6wuTuHvVKZ{f3phXuJd-k*yV-%XETq@R(bQaDKS9_ z2_O5JZ)N>@CN?7*o*x$9LL+;z4W5^T=h(&f>w0H`TK6qCxUrvp-L~27{^c3HqQvv{ z;#+ufYnlFa+jPE61 zHP4JaCTc#c{|y^8O4tjq-G!i*XU1WMJgGk+C?SD%bRnpPUPuVG{LDoMH$EOdKD+3& zXZqQuxaE|P@XWaQlHT8$pq6LG#n<74pu{s{kF}cj_UILfn|FR8UrJBy+)uxzUnlSi zvK`d&-v^#rjG~T5HHy(PtgL;PXynW=9;^=5B zj-`g))f*>#6)N5t;j5sJ{dbL@1M{n<=bFV=*)WUrc%|7`hIep6P~v%KNq9!-@k+D8 zE(EpkhD!)aNDNTH9Az9)wnvVTX>nV^=w4u`p~e^U_?l<13a7-F=c^^^T~rR z%eMS-a$*50=f?8O&i@=J$ zNeKz8?nSJ)=iU1M`kB<#heZUn@Wn#9{l%Aw17AO)NeKyja}aU*z}Jt6pq6L&es1&@ z5}{vL1g{*!qa-E#M70RdjNJ~sK^ywYSuegJ>)H-fBRTht73(kQYt%Dyy{*5Kh$RDr zX(Z|0BpuN}zB_#A+v|fCT7EP~6Q0s%QX3Jka@#^f~OD>ZTl;}Hk z_3kI;hGOzHC|2iZky1#vhrL$F7G~l#SM`^{}v&5HA8}0@;01F^N56?goNko#h2|a zM6A`R9n|vrp!kxm^L8RAA)&9s{lz!r#48fi+V-Of{aYyt@cCQbX`H=FiM}WI7hjrt z^ooS%)x{U+)-%|?9`uS@@x6d}l*f|xb>{U)WJ?|*=GCNxghrxp%{8MHkqyMvB7$0o z(1}3ou1N_Aji|wfX0#&8_~1789TE}LLZndyVvtQrNO)%Kr=WH3BF-5R)I!8mHV{i~ zQbIy+xL~6-_d&ciBBQiq<0~xg{=RCaHhI5)|GqQaHhI5)|HdqK#p=Adqpj0syky{ zdFWjTo{NMt)t#}fob<#i64YWZ#9ld5-MO#ID$hwfQ{B0*%1=+)K?w;T7a8jbK^x9g zckZk5&?9@XS3EBXXR15*RXOR24HDFHrn+-ql?k2@&Qy2qtMasSXR15*Re9(=dPTyS z>dshKPI{N?K`q`ram(qiGu55@syy@_y&~aEb?3e+Cp~F7`-)oZktmP8=_+5&OH~c8 z+%>zL&#CHMiC4(gZ_)+{R~U0Xr|Nmht4;*9T!+m0oT~Gc5U3}SyJnlSa8;2lNBxNz z5FRu1Tt|d!wmJ7zwbr^2)MEQOw}XT$usMfURn!t2JQuat>#+^?iEEuXlU0?>db}Pa zTVbXR@l2S&v?kaIG_EvZ|_CVuO7ZX?^l$sClLe zX9?jdXwGr9#I??x$*M|bJ$gmLwa%Q$s;Xv*4SGc_*E(}1t16r&1SPI@=1f*qGV9SR z60UXTOjcDjOKi|9YPr^#Gg(#PEFmaytutq`ZuI$eJ$gmLwa%Q$s;Xv*jmRr#xz?F$ zo~goFLQvvbXRdjsN@hKJMZ&etT=Ps-%@P~*idwF9=9*`!aF!61xYn6#o~e>qk6w{* ztuxm=Q&qFX2EC$|Yn{2~nd*EcglnC-=9wy)<*s$+nrEs}*2OClwC7r9u6d?vP>Btm z*R{@E^Gub@y4c`(Nx0UTYo0Cnh$|>}dK*y7XBwDgkYJy<)|qRbsghZbUXgIEGuJ#* zRkJQ$QOmW?T=Ps7&JuzW*E(~}GgUI{(JK^C9s%n(MI`u65>`XR2zJ z*q~R`itl#UI`aZjb-ZdP4AcaR)*PtTrCA?ph1DoQ<*z_{mD*adpz>Elpr%)Ywxh~l zkyj*8`Ac4*=2=8g3$@Thpmtl0^DEA&P}5Dli~4XiN=U>uQ0*-usD(OivVm%EHA+aZ zO|3dhzJjX%(Qs`g_q%dy!?9<8K6afYuLo6KNiBC}rjnopb)*}pXx)XNmg_8e#j5H< zDWN(`UO}o3PQ!JUyn<8}C20-pln{GG2?^I(@@i7`krEpus6`KB8I=Zv*A0>n@>JwBb5SUURC7Qe-bC z*jFT6XUS_$Ra8p6B0(+JS@N1wb&L|ib(Xy5RF$EI>nwTAsVYi6dPTx@mb~UvMWw_B zy`q-udX@KE+;aNsI!j)2s)|yNUXgH}C9gSEQK^ep)MAeWufn+Nr&jk>`K8fMZ8-K* z>pDwb>8biq%SM}^goKaF=RdaLI!j*Hs$NmlTGv_fT20lJ5*x8(;7+8su?-T`a-Aiw zIaOULu|Ww5wlB89cDT-x*XOFD6tyWPc$biHoh7f&RZ%JNiUhS>XUXexRaZ&~N?d2j zt5j7{>d`9_uCwG-swyfaHs}?#TxZFvR8?0>2ufUM$*WXVQR>kv60Wo4RjMi~B{t|4 zwOnV(Yf)8KN(f3^XUVHnRZ;5ED-y1=*x z(JK#5=oPhGXUVHnRaZ&~N?d2jt5j7{>d`9_uCwG-swyfaHs}?#TxZFv zR8?1My>Z&34<)X%GdrG%iwb(XwJ zRTZTky&~Z{OJ1d_qEcdmUQx?+mb^+;jiH2aoh7eQRYfUxoh7eQRUfH~S0rf9b(XwJ zRVA9l2G8p{OJ1d_ic%LFJTD2?S@J4X6_pYjBx0>(Uedlx*e9;DGdrG%iw zb(XwJRTZTky&~Z{OJ1d_qEcdmUQx?+mb^+;b)|%$#C4XuN>vr59=#&rI!j)qs-jY2 zgI-Z9zS~`ANt&)DRKwoX(Hh5fmOS@SjUkP2uCru9^@?hgaE;^Rf!UJlESXUCp@?vu zC2Og!P=mHB71voZq3T1CS0pNxWv(@?>O=Bs;J;B3K`rl%>vfxI7q!|EIJbkdJ0F*; zJGHNWpyleTK)A0cArae9%X52Hw7h*TYN<`(@9u@r@<6!dl#pPX!WXZqZ7AO9h)HhW z{jcMjMP+VBGeRzaV-_(%2?@tHi^|+x2x|FE?yKo-IKEj_=FT18EGl#Rn@ro=*ehx| zzFAb}?n3ZfBplx?Dsw08AVDqmLhO~}n_hD&78!Zs_-0X=JF!6t?fE$R0@=QTwBh(> zQJFik7kkC?l5l*}YfeQn6R${6%kj;kGIv5azFAb}&K=(@Ds%Vf6$!^Ti^|-I4SGc_ z-aT>4>96CPMP=?Dy&~cGW>J~Di&xZQkF=gWKZE*~Ty=c2*wv`v_-3(3kz@3@+x@hb z1SKRK-z;`i(#X(>pqAsC#lA}k;iuA1r=L>CH;X;0{5>&v<-f-^C?Vnarq`T`OLifs z#rDNEC?VnaX0hW`VuJ*=*z2(k_KD-0#okUmUJnwEZx(wy=`QJXJ*egQX0f+ZLQvxP zX0f+Za_@GsLBjFPVsEF!2K$Oyj$#&jJ0%1qj&BxwJN4)l3CA~!y`2&p^om-JZx(wy zB?KjoZx(wy_2?A|$2W_;oe~@Lidv3u7JEA-1SO7d7JEDO=oJaaH;cWU5*zf2T8?iP zdpjirC5~?vdpq^$6$!^Ti@lu^8}y1=j&BxwJ0%1qj&BxwJN4)l3CA~!y`2&p^om-J zZx(wyC4}Rf#okW2fN;TD^450IdiTW=d~TZr%mLh;TTB_!CUR(#Vo6#HsAI^uJA zP3vQ~*2j)-dOfJ9W)>5akSH@89ewCbP|NX6uUHlJO9;m|L)>ZT%l(dTdIhQIrR&g# z*{kxBwIj46K4m*7i3mk$yqZ*8vcEIoC}^og4`YH75{_?r&8bLc(hd^T>fCb2H@)Um zEHY}X?@PU1SKSVTs;2?;rM2;uS}i&=J;l@uS`9*K?w$7YB|1H>?@NHlsLXw>?_lw zS0o(YEcTU2Y|txeIlfu!E0YkEIKElzE7PM_Bplx?_LWI&&?{;=zFF)mlMs|RzFF)m z)1y};9N#SVl}T*SD{48u=~b$tnh8OPifSeVC5~@;m8$4vk6w{*eABB`MKY7SgkDk0@lCH%71c}#N*v$xDpk?T zdw8bKcL@o{H@!+#Br~zWb5Se4+a0s>+Q2b9$N#*paZC+!pAg^l+{dxKR(#Wh;+@`I zCCrK}A%WSF=GBh!nQ+vPgd=-Cuj6^N-HLCTP`opzgoNXprlq#Lbw>poJ|aOa{9R+B zu^F(+n0)6Ejb%J%Z+p^-e0xf4RdKaCtr@dEBIFnfnVjW$L2}(#PQ#1U2*Lw_iCaC2z*;{>~NC;)*G74aR;S)Xk!WoPDIb9!Il&IBbSl&KkhTkAcBV;dx>#a@UB$2Yy^^e(}q zm9-h-oZfFZCMY4{UeT8W|CMY4HOwADI z^d7^V32L!NqUdW)nT26JsK{HU?98x^QuH$M$`MhIKDz6@Z+IC2jR<9GhIN!8newU= zK`rGjHi~@Cgur*hO!=H)^{eP*h*V8)#qLh$ue6z^s>_SkB?d#kQ63WyJYiC6= z6B|4iwb<*i4fct$Gs6l}(aRpM2MJ|rhB&7pnO(f1ma;ZOoKsQFgrG#(nIX=p=w**y zkx-^)h;u5Enb=@oMOvS{8RDFZY9@s8IolFtXNEYZqL)2-MM9aHAb0ku|cn>rQF4^f>dlTA(WjNR*;HbX3Dz^D@es9yLd%{ z_LSikR*;GSB{q0o$2Y?Y@^9U2@Vq3HsTo#~iex4>NKngvADCtE{lPv_c4k;XDtg(a z<+MRUnVMk*sYqrQuc)Q0&9H)0R5KwcQFdlnK`MILqgN!9sTo#~iex4>*bZtbYcs4M z71c}#N|c=$R*;Hb_UIJ}Wom{Mq#~J#4SGc_Wo?EPq@tP$L5bs=MLuVbUXf6yW>`Tg zl9||`SJaB{c1J5clW}$Inl8MG=mnns7cOZScG? zf%ssP5)z04%7!DNw&8q864au%QM|Uv`IV2$nG@o;>RrTyo0O1XFSO#D_R1NpB&dbh zt!y~HX+rI3QbHnbhvS$u7uSigWU;I{)UDbu4mgAd6 zK4(fOzFFkgRUO|f@;RmT^z!yl-#XNCdPNBd$2Yy2R9rH#L4sQJFt$Mn3CA~!e9puM z32Jq2x#OE&b1D`YwN_c1{Y5@!Vk4HYf1Y06Z-eRkiZ+y;*wE7x|n~ zn__}@2?=Ft){A`3#48fiQr2d@$mdK5N|c>hFY-Bi^ooQsHS0w_XJUh1QOohoBA+uM zC{cE1y~yY6(JKhFY-Bi^ooQsHS0w_ zXJUh1QOohoBA>JMc5aV8lsLXwgJ$7SZE2;@OVHhA8cKpte15)#OElnqBj?V0i*BO=xs@HWazwO8%gosY}a zouim;pQ4(rc7*mT-r1yt1bZPwc6C)kyfY%G<@ly;DBjs>M^?j3o6W-C_j+%1JtioT z2SLk(W9g>d8=VPi;Y|Gw>rV9EK0dE2n4=wG9~=MOb?RfU z{QJ#PG9yCko-Ra5Tg&?u`AqU9{AOanD@sWCS0n|YUy`@}Yqf&}wMyFi2E>G~me1uj zw4cETvj(2DMoi%TG10o0wC|n!&S!F8#sqEfyuLe3_)5kEB_yn6LSso6f?9Z1rYFj$ zGf2ww;z{d5P)qF#Eq5Qr?QjIw=he4Fe?6`GSl|4r_x|9M@b{lwG^836l#qD*odp8D zV>VktP(s3XY|np-ZIGbW&MU7Fh`$~BQgZK7Lc;B`4YxD4L4sPk69ch8pW~dZ|62F1 zYtQ>!u7W?uw;SPjrYqK{x>COXZZak)Au;0MTYDg=<%<8d(b`FXUQt3~wi{0g#BMM5 zCti`D7M_)apk#)`bR#v1_OZ0^3??=xA%T0h3qdW9g)_b$l#uW!_x~qit$UX@(b`vr z*TZ{Sl#-ZuI{dx$CAAabd8uh@c`WSc6(j?M?BVaU!E;edy&j0^XEKzKP`?F2W6AW_ zqkS%F>1u|*Pyarrgak&^#73LYEUbO3`%3q8urb5uqb(t!`#Ai4hR;Wvpq8Gl@b~GT zb4Ox)r98@bPcCMY2x&jQif z&4YJ|#@*n%$8e30;n-s>+ZWrQghcs1pMDf2K`r(|XB!&ZgI9iM(A$`xgoLO-`wh{V zpqActp|5869&AfUu-9W7JQua}W(a5UyCfzkA<_8?lAu=SdzTUtdUpk{roY=sP^4At)h%yQd35t+J>6T+aA z2?@;MyAagEx+EbeA%V3>7b4c$=vrTMe|w5sUa1U7Vxlt1gx`9d2}#;o@;00CeU(Vs zgzWV|P)ofY2*34WuP7m*ehY-(jhzW<>1qZ-Yqf-+gap4c#Wr+@w_B*Et9|S_kNe7R zy_jg*&|Td=mM5JFN=WF=4>q*AOKgy!7QKzV(pXWozaA~iV~-XZ?ZV$Z*2IMV60CbX z)OZz+J(}wM7>@m(j0s9eXsir`$IQ+IwK{u62?==?+ToEkwn2hgWiL$s{@`_HkFrN% z8SPhE{ip4HDGSyFK*P^m7JENN8pd2(76T8ziWu za|gonh`1e;kl?k62}($4W)N&>b)Q^w64dH^%}a@&iSpQYhMwK3p8bTNgoNhTJrLB=cpC`6_2S;uxEdsWKWS|cjvbrQdN&+TA6=q^gkzE( zV-Ec5jY&L;1hw$@B)Ww2I#yJAn1N0RN=S6J!Ty0g$5w*9>HCTj60n!_E(vOtcZ_EU z@%5l&Mugw-or#jRmcQ%zdPw`)n4pA&zu5l&32K$JX9%&48EN^w-kG4JJT`$|NNki^ zwoWbddO}b_0#~yOK`lI+2|)=7+;3e7YGI5?2ues`l;}cGtL#I+_2Mf?$&3h%k6nn8 zwie#O2|)=7jNn}eYGL+~5R{O>{Gkg$Exfg>abHnF0`K511hw#PPY6m#;7y$n9Q!an z)^Xfr6opn@zZ?i-;`F~xfL1@Xa4Z|n_H~ab7t7U#v#|@G6ZT4VJ8s|lobctJZR$>V zjPjLKh2U(&!Dr{npjFFhgA$&X*QPT;tv@yH%NAPU?EJ+Iiah#uJDi<-;A&%X?UXaklY0kO(lJ2^31<|4{nD7+d%<=l zsMWdU&gz|g%$d3OW_3>R8eg25dpB3w?rejE^O1+|cUJD*V>=Vn>fBe(>izz(Gji|E z>YU(DetSml-CTR~iiGo#cU9mV4LL*apw*yyN>WIX(A|v7}>y5)#gNz9>IE>}lJXpcZ>QCY+-?Vzbe? zcUpCZ?+#~<&b@;xZFeT9s&oZx%&Q*!Tb+M8D-oP&JuH>c#@J+`w~)MAfJPwa8P$lP8y!}rKvjLf|^Yj0kW zP;KPw%(F)3-V1hm8-8c_oYZp8^Z2nN!=AP=;r!VP?;4eR=Tm3m)?OHud*9T~UQx># zzMpphU8g{ zYZ6VI`J7zUhx~hnFeCHdrzd>3r-bVvoiOq2Ty=iB5Y%G(VjGl@aJ8X9%blI8u25ow z1hrh{7DE(T&w8)M@Q$XE0kP8&q2%H zrB@_e(dg+5M(3(yl-M9aE&sh7$Kt+X3$>3;b-ByN9AC5R~vD;yM$9Z%at9 zO|7hc6UvUS;aiV?y%A`C@hrbNw7#l2qqrm}A))H#VGQD`WbrkJ3FgtPiRiYgnw-kG2lzt6=4C92F_^|-6d^}6bMS3T}}ALE#y#QFLj zcfD6K&lD4skWj7is>faL&D@!wme1sISJzEnIe7)yT2*`xojU}p18Eh1FIopIYw0vIYl=0hHE9=ZQin^R_uShsY&a~97vu^9x zb3Wp^sD;0)ubiQ0?V>JcIG4vLw8K?IOK(LuPtAn-%5^#05)!cuw4A-@Dw}1ST$eMP z$=PX9%R>fR(LWKvHbvLmyGNAmh`!LfE`z@Ts#<}r2cFs{C1^)GZs3SOX9DA+_rR|D z>!5eOjtNRg40~jys=xKEzSPVKp=#_^f1&g4)2iQI^>;t-SIws&wm~h`h_CwVp!dY? zOi)5X_35kr?x*?2 zLGPkXZ(|#jkWdx-s=p3;*Y3^)wRoLkLN(&6{yOMAu~k*R>aT;|MVq!`f)Wy{Vqf*w zLGRk#nV=SXBqmhlz3Q)n-ql+5;;a5T=>4&2yE8#8Re!Jg>!5eLjtQPumFuhiI_RCc zNyh{wBvdKC>aT;|8N4$=E%tg$sN#G0I_Mp)RU^LYuY=wbo3=X>)Kc~L@O99;UB?8^ ztIG9Ne;xEr-K1lJ5)!JKU-j2PRh39=kf2uQ>!G^v;p?FH!B&O&@O4lX7&hdYI(tPz zRqVspLGRk#nV?qZzEXAc@O99;L95Ps_&TUM1U-61LRIX;*Fo>v-PtQ@u}7vS%GsT2 z#D}kg-V?jGz9QkO4*ojmJ-Da0QAWL~r5gC*>!A1ijtNy@4_^np!;2+_6_Y7qxh0V?s6C!`DIYQLT#a;p?DxxaOH+f)Wy{ zHXptYdUx&41hv?QF~NR+>d;rh*FjbGSf93If)Wy{_#VCvdWY-I1hrHzK71WiJ%xmz zM0M!H*Fo>QP1~JqkWdZ$@O998es?CQ#p|T$-ujn?Rcf~6(M`s-|2NOP)xY09CVyw| zKco?N5RAB!*zXs8)y0ONlW%$M1DgBL1_^5U@16}h_8k-S%Exb=bew;2uU6lX9kkS_ zeDDDmBm^b%t$BC0>F87P$;(}w@l2g5!7Oj!~`WIe)QfQ*{_cqlP~$hc@i5Ws5NCT)!^Oy zjC|H{)6{Z$Wum+@NDq1R+-#xKPRdXIwKEP$P(tG4l`qbYKmC;a)6MTr2wES#*u?Bl zm!F35oXap7mSEN~M4N zgh1@uI4UBjwZv9G3^s1R&J{N1KkB?doHoaZCM6{B3v&_Mtu;Cj@BIAOh@h5_{dD

+;S4sI{xkX zGLMO$zqedsBbE&G)o-?ZxZfl7X8X>Y5WF6n?{aRx-vC=2>)(_N(6LvPkl6O43H{Gs zpkG=OaAZK`ErkzwKv?t0Z(o}aM9c&^*?4>v1Ox8#F7C*J)L`w z>h*hQ#|#N->H6o=hli`F=c7$fa>~`4)%^yTvR3>&cJ_+Ixo@mk-|xv$`7?99 z-Fj-;t4+&!c3l0Y1I$lZVJSYUOyrtsKp+sREEqoIS}LCJS^%f z68^QlZTMHNmC6fyKN^Vh^^W4XsKtH@Z|9n?hv!+EMdlu?sReoNsdS zDfyOPPHw%=+XN*fd|b{~I@{2^GxzA@87AqNpoE0xpt(ml&pbO5)Y6PH_bBSQV@yz@ zH9_w2+_OsBjtNRgtUB?oe7XOO$?qCp%q-h|MS@zqD`Oj!kkGm#_gl>?jLrnL;=5hf zy5URix!lwx&&%KZ)A9LA>z);^L3!2aZMZwygr2d6pB$Yt8@|{IjSp8jC*Nz>LtaNU zd?)(v(-WnHgl69jkL{i{cP6OS*(+*k#@+C{#B=M;1SKRi`_4V?dOjR`MS@xrXL%}L zeaz_mf!Y1b8ul(Fnhob3ojvd6nPP$x5}L2)9<@DF?o3dNSGH2wZ}O4hPMl-h^^LzD zIV@bk-|cX5rm-npHP8OCIr_ujAHR8D**IhS*6)y4-sZvvB_#Cz3$#W(5&wK_M6fYz z!LuTQT0ZvO(;{B^-CluMWXgvP-dDVr9-X#!AnK$2E2On=-Zv0OE&WD=5)yjz2d_Lc zuT*XrcTgaXeeH>epcZ?iQrU60g99;bpGTv(n!XfimeeLFA>m^`!L8bDBxpmk zy@tnK&*ezRHYg#X8D+!cuIF-{32L3W=-|evo6pEEI?a1X(<|N$yh}7+Z-jZf=I=2< z35oLBc%I#vpqA$A4UhAlbH@ZFB-kUJ32JG+-tZg8v-Fstgha=_YHDU2Mm5hcNoZyq zMp4g)BO6UhNT5w!2x{RvB?KiY;rrP0q1Y?7&v)|EXeB^LMK-4*FeQ_O$16(U@4JgapP)5i?!U8WUfC<%x)(7RD|S=RVRJ6VE*2 zkt!u5Fp7%6m>3b%!k8!m@2DyzB=9B@fp=6yPz$4k2)v`Jl%z!QjuL_QdF_fnFW=a2 zvvcyj=XfZ(9=uL5q1kDerFtH!d1n|6Jln*3KCwXw3C%~tc;(qWYKnuRx>9dTE__#9{FAMP~RH2}(Wl;^qOTZZSVF+m9l zKkFVv-TR#hYWcWW*CqtL(#$w~ZSlO9_F@~9kkHIH%#b|??o3cibKWrb^^7(qDAC+D zjJux2(soQxLSmT(FV64ND)sl@OipZ&pqBqWa9>@2;W=S`^}#kHYFNdGx+v~Zj}};Y zt9MTu_y$m;#B@pE+klAv;v2w$uOAT+)WTX_#EN^~9lW~k>ceW3kibe`1ik@81hw!D zKm@+Y)F>f=FE1kSO(r6!#k(^4CR3v%B?j(Ye7~w{W?V16A?w->RB`#%vn$rW{Nt#6 z``O>t-$}%h0m8Jex!<`lK^vMG*Ng9>YAtEnpoD~G#`WUctLRPyweDYkwtVrA&&n5W zE}am(mv~p|`*rvR;Q4TDgAx+>e%XbfmS)D`ONi&gu?alQ_3|!{{I@o9v>YvQxtDkKjmrt!%5&pYpQ!zma z3C+GkMA38Z&P1%$$t!AUwjZL1o;9=IVjGl@(9F2M_=cQ#MS@zleKw*0Q+?AP{f}7_ zf)dT2`-?BlJ$gk#^XmTM3v}xlY+nz0MXmVCA|B>$Hj1ynJ$glA#CkVm_v<%B^Bj0VVuM~$ z%YPrZub#~IX!?4*cgYw2GSTiu_U=3Ht{(pWHR7tB=n9ASI{%h zN@dJB2Lv03F7lU%pw=t94+}Q_+3!kIpDNa6ufEvx(JCb*G~Naqo~Zo+>LU!x+Tl#n=h(f?-8 zopNgalgFLYKpXVR$E7F!bw%;DR(42GLZZAjo;!9XsI}PGHLFv9cXpobv}!_7Lc+ht zD8BC|1SKRo_Z10h`S%#b_ua$>d(pqHD89G%cs)q?7aYa+_T+ld6KZwzs)p8PxE|ry zW1{Cn(eMC?>TU1 zf?BrWk-GJqW2AOmEj+27hhWssFdplAV5E)+YL!>kGr?%2Zcsu3g)Db}~jHn_o zQa30ef$>-bM(T*57DiMN7^xeSkl<4gjnolAEk0dQU4xJn?PpCHzYSL>aFqg8D~KwG zPEUBOO$k>gaFqg870{@Tnoi8TZcq#P+<8n;Lc-MvT%|yD2of74sO9Pe&aYK2e;2~l z37jpfO!82jz}d2@NsxHux&@`g)d`#}tJ(uOZFg=530Eg@wyf$9BsO?1YWeR)m4bv| z3tgSSRSHylpusbB_KJk76Szu&>JW74D{8qqfvXg#CP6|_;_3v>mR0S69{Y-fs}nd| zR&@xHma~P_a&-b{%c>?pLQvxB1kRRK?SUS>BH`);&X!djg2V>Bq89J5DD%FCO!x*e z?{j42%LcOhYm|`iv7csDD-eNP{fIz*e%NozPxA?(-s`o4s$tfrT>Z!^63ErpHUG~n z!vdjyBZ68wcNp{4P7$cKP(xLPXv9HH1re{lwpg&CiVihOP@lo|^kL%<3-<*=JrEJp zLgfY7aCHK`tt#q)8YLvyrl?X#^YpPxhOAgs$P4xD%4@)D)1B}&@Ktj~Jm*x-3dxFVi&Usd}qu|a}bom=jTc+P!QJ-AR2&$+Lvch{p= zuAx^Fu88N{SJl4j;uWm>;uQ(nb45H?##7a|#4DcH74e+= zs(N=_Z1B7!ToKQ?ud02Q*dRfz&ey{g@mv{C_25E9JXgk3y}KU0at*zba78><##8OP zE?!Zqb6>e4o-5<2j#{XQ=gN4hch{p=uAx^Fu88N#c&dHZ#VcyDN8-E0y<5)JToKQe z@s@n#@*ce+;fi=6_w{f7_R4XWSCCqZOdc0*AH` z=9OBmi08_9s(06gpjRYZ5zm$JRQoRRiUhTIW#g8+BAzSbsq$K=i08_9s(06;SFWK~ z60V5n%6O`M*TpMpu@7Uf*zc~0ceg6zsoq_WUXgG`JXgk3?Yk~sQOgzaTp3Sw@DhR& zSHyE=Jk`7F(JKa-fDmW!JC~++(uToX1Nm>JE>TH9AYdLw9 zs;W(i4W293x_6RCKIK;HF5wkqYhBC9t5j8L>d`9_uI1!as;V}1@rqim<>XbWDmWzs zC9dV18rKTfBeZ<>Ym(Dj79g%gL)$Rch+79oV>18m7#`f zIeC?;N=-d_MZ&e5yslN%rY>Gli#-y1*Q&NtsO98!t!glJ@rnfP zxt5dHwW?R75tn0$YebdjbuA~aYgMVKiw&Nagljo@U8|~1U0P19&ey}WoV>18C8ON6 zoV-d^r6#{E+Vifs9h8u8Ehn#QRkbN;ISFcY?km@F^14d0nfTLAh%= zd6lY4O+9)=!nK^du2t2hE?!ZKeHeSies?V=uWMDQsYkC!xR#UGwW`|G#VcyLmXp`D zs^F9ml(?3Y*R`tD)T37ElA>kNmQSrSCK`qBni;C}E2**&1 zitizY>Q$;DrwQTcYAJCHwW#>+FB3hqgM?$KMaB2T2G2z;|J~!5|Bd^KEp!aEsQBKa zS0o%mEh@ezHs}?#978QCz9$4Fj-h&$st9S1UXgGNwW#=>*q~R`atyVo_?{4yIELy~ zsv@L4dPTx9)S}{hVuM~$i}zTFDAxQ8DnjarVz__&Ec)2bqmLCg49AL`YR=$jr3wG5 zs9tz#{jVdGe!3L(OLpj13^EXoLDB}#Ysz#h&Z!t=ARL3FgoGlE!7IgA<&~qZ_R29x z64au%trnY5Ox62Mv_~Hwm!pJR>|U_l5O)qX+#X6uuoprUIS_6S32NDY+pwoC|Lv9A zLkWqv9UeVRc%*X-wb*4Wx`OQW)_B{AaLe5u$54x1#?-sCK?%>x`>iuUEyqxcUB(g{ zj-eL2j5QqVEOr_5?=mpL(JK@wEH2G2{vG1Ow0vBU-mYISaT zh@rN284EE~uQ?SVO-2T`oHiVFEeXd^i(SULctx$wedQQxvCCM9p?b}!2x*UAIqF&x zj-eL2jOlLg)DCK~M`FS;)MA&h5JUBvQ?bu3UXftGIfh#7GM0Gd*lc-T$54x1#=6+x zc}X~iTI@2G*dReI_IliM$54x1#zG9$YeU68yLd%{_8dbkb{R{&a%{FduVbjiE@NG6 z@Vq1(LoIe0OKgy!R_E*C7;3T0Scst(yNvbdm7}gD;TUSM%UBn$sMWcz978R384EGg zVwbTVy>isGBpgF6b{Xs96}8wS@m=EHE$3>Ep%%N0_2?A|?H`sGyNq@5idv4L7Q2ik zgkz}1E@L5v>NTgLrCq#oq_xy?47J#0tP8>WiiBgR#V%usS0t##D;xK&W2nV0V@wD)SB|=tgkz}1E@NH1q89rw_KN-P7^>Htijel`6$!^si(SULcttJ8P>Ws05`q%P zP>Ws0di08fW2nV0V~Gu3L2B_jwPL8A`}pgcBQT!t`0KonJqz=(W2pYSzZk~^B_td} z^@>%|(k=wG97FXgRgu$#pu{m$uQL@P?a?a|j-eL&9Ygh6RFTuf1|^Q67W?D44t)lr zi~VsDf)dA2y-HPtv`4QUFPVTuH` z@OSlgpNL?a zqG!`!mj__-jVx;auV6+P{)M9^}gm84Vl#p-? zwb&mgAsj<3_Q$C^hFa{8Q|CP$w}V=ap%(k&bRl>y5{{u3`{UGO8ziX3HpK)bBpgF6 z_Qy$Vkf2uQzH$uJu~bD6>yDv%m8uA7k1Z$R7;3RUPU00?PAy)ixaE$a7W?DW9Yggh zRT0u2y&~ZlYOy~~7q6(r9*Mnj47J!Fr|uZ4*Pn`gcJYb?d%-c(Vt<^(E1uUe)M9^} zE;e{x5{{u3`{N`wNKlKt9=F^vRIh6lA+0-x>h-5$pIy8nL3@s&dR?nHVd53f>lkXW zKTa1LJTD2yP>cO>5*s9_)%kijhU#^#B8XEQL-i_E5z;9sm!iyLd&d z&VA(=s@JuOyiIWo)vHuRNPF~(gkz{)*D6{%rE@!|#U7cSXwB|M4Rs9F>sm!fC$mSU zC(3y(3CB>2{c-N@Oi;@)RIh6l+e-+?P`$2IJaCF*s9v!uTH2+rsO1={*R_g}b|Kh8 z659DDtZNl5?b5r{;+2hC?ii}qwTji<;~1(}sfv*H=oJaaP`$2Iw6u#?)M6jTUa{XD zL-o2=5z@QaBQZe<3CB>qu2r=3p3Vfd97FZGR*}<$pu{m$uWJ<{y@$3t+aTc>s@JuO zmL@iME^6^QMc)AU<-e-D)bJ}`@1l*b_0{PKKOg$?9}&tQ4ZrwR?6V6&Ev&+`*ajse zlyMqr}%V+X9rhgNHEmW3i?p3Py#HQ`eHb^MrG%xZ}yYv;clzo~Pd8r9OiDRfm zUTTkhMM4>;A(ra>u{*beTFO2Ru~hGs9TSu|hFavM_UIJ}Wt@gss`tl^ZLr^|#d|D@ z4>l36t0F#_AqprPj=Fjs<-ATxNch+*NIktG91%6)EKL%K6=t*@MHC~iNFbu9YmNwS zL{JMcRuPV&+AHVTdX%xh9!oglAa*MPF=6ilUdERrBDR5;a70iG(O%g=Ot?u23AQQv zJwr`-sbS5jm}@#^j=oJatP_AWI?Ugj98*PM!w z_UIJ}Wt@gss-mS`yrLF+B)+edWg23sijZcGp?b}!*k>27NbuSy4>H736~jxs;(3*2 z8e*x6kan@b^O8`;X^5pNTAJ7(5ow{<o%QUPx6(Q}>D-y~$4QozCOS^bQE%r!!m$-M!xtg*} z!N(g6{ME(Bg2|gvAu*)PGwkgDjt|QhUzt^qNQEDqL#8u z!H1UcAwRmOYmMh;etT`2{%ammr)|`rv_UIJ}Wt@gJr=q1@ zyrLHSF!qZ5?ii}qoQjb4=oJZNoQ5^0qNQEDqL#8x!Zjb>!XX^14IOTsbKA}_TIK`qBni@el? zpu{oMA}=+v-PtP=%E9a}@=_BUY+Wy>p-0f}-3`-{BPs$-~Lr7Cio z*q}sNru{`;s}L-o2=5z-#LBB6}adXbmf z#VcyDM`Ev(Wm+%tQmc-kdR?p7XBV$XuosjESugTZ6R&t)WtrBCywol>cwQ39IIS0X zsfi5|)MBs4Eq4sH$V<%}L-o2=vCl4Ek)S=tP>a0O)=Z}T4D!6nGOZVRsaojU|+ja16D`OHEo%f?A#X$}!X;FEw)vwa82D z(JK;;p%!_mUA&?ednCR~+>UZ~=NM{{m)fIOB$RP_cafLc#Vcw#hFavMCWK?CMP6#= z7^>H`ik5cqidrFts#vNbq+JMJK@yIk7I~?OS0t##D;xK&W2i-5YUUVfk(b(|S0o%m zE%H*kcttJtVeA$A-7!?JYZW2w(JK;;p%!_mUA&@}W2i-5YC=%r7;2H1+M`z_978Sg zQWG1zg4E)5@(j`cO`YUl>pg$|cdJJ%FnWVIpTB0xW>;+9KK9>tUjKXj{(DQGL@6QR zE(IGzz=k?0o()&F`(WTK&Ka4$XI(yOQ~MrJw#P^YQajUY+8TzKgg38bLi3!uC z*3#FH-_SN5yk%C|czh*ip{pGyo!q1(B}})7dFQV+Obj_iYfhZY$EDUaqv!3njji^X zNj5&bZNEUQaPVajfi#U9j*6!J#EPQlCm@c*ETYIZuW8`UH=t_J#=B8j{@(V{a zDM<;_E#k;a?hC~4|9414m@c(OKDBMI@x$vsmyKobzdsNs+;>Qml9VuA5ZgW%hzIXJ zARIP&FHnv|r3=@#+E?pp+6%8pA%gy~Z2m33baHYU${ ziEO+*dfPy(x8)*DN>ajfi&*2Sp9Et3Y2S(n)1}tB_d3hT1V{td9X3{qHSg4tOpMa#D%v#-Jm2TOt*+Hi(O)BgBuZH zy3|_m;ID&?tvBwMjWI7D7Hs@wjmZs4Qo?kLc;knyU1B!=?)Zo>U246*_sp5ct0n*U zwcfQ~ZPMB$=J(H>)1V|JOt*-Mvz!pT8a?}#5n;O2`p$aa3N|J`I#M>)dg{bLJhAe! z4N6kNbc@(-?bdr^@%q&{2_KhQemA)t9-k|fzdunD%Z9gBDM<;_(-9fZ<>OKdwlxEQ zR~aQKQFtfai$bUj4i3PuEacM9&FdZmK9q)JIj*oN*a5x5g0 z0(VIrPk{*B?Nv%r!Z!4Lh&XfLiHZo^?R7lOBFd+B{vBVbQj!w3q32u#Muv#MQ(MQV zB%&OBt~~8qHA+&#HZ)#|zz7!+7=7v(T}5CNtx=K^wxMxXL^)C)_3|nafl;)Mw}c41 z4QiC6gl*{kA>!u)Z=8t0+n|oOod~?uYLujeZRkBH0&mWUz+0`3x3-A#?L5^&)iE0sfmvUTl9aFw%@ajnW*HHf_0=(})!2K)!0fd~NlMs;=DQ*=Lyic{UUST~ zMPL?Qqa-D4L-TeKnCV9ZX5l$j86vQns8NyyTRZ)!+ z5`H(?hTbV6u=0usYGKtU0;{`PEEza2)@>rNf{X}iVf8BF&4E>FjgpjbJG8D9ft7GX zV3nFPd?Z+NMTHN|SF>$30 zYm}sf=@zlmd#x%^hb;BIh%jAh{pr8=1si80C7$EDV9_Wf_L@tse8A{*bDb-zID zn7>}7BqdC@h+oRX z=o{{c2-Bt3E}IR?{hY7*&Jfvn=Z8lHV*S-7RVhgc(=FoSOOFjiW5H7+!gQ&%(;Tw~ z8z*kw)GYjjFOCbuE|2}RN=ZtXZV_Le*UFH7aIJYF!gQ(C|Icp)8zYvg$i{E(ZRLiK z|M=02l9VvrBA$Jsl_9;yv&%+==~AmalSdF;kN>oY-JiX>pOTa?JsnY>5n-+J@A7KH zN(El!l$16~qVP}zT0TR<=S8oJK<_pvDQ%R5ZRmQ4z!i)L^zMeZd-^Mt@-AsEcxr=^ zl&}rmS0ZpHMg;DXemn&taJM%oNeSD~^C1FHR7Buz@5j?D0#9v&l9aFwJ?A1YGDHNP z+J1~NBFfR{<@-KrP?8e1q47!tMz|&kj6VGsT}70m=ug)8c9W8nunmp7A}~@%1V+(* zyd^~7ZP277C2T|Q4-vBzZ=7A$TRS4~Ht5IOP6Xa+O-fS2HuN48fj4JF;H}n=x3&np zotu=Tgl*`3E&?-vh``&qAF~e;m}N96NeSD~yhH?MG7*7UMn7gzA~0KOQj!w3q4|{v z%*Y}Fv!#B_21Q`j*Q6vRY(w)z5tvy<1ZI8xnAK_|#q2eTE~SKRIMP(9toFN+&0ntm zP2Uf9{88>m)nN^NYE#OZj7kB>TLvub|yMfq!^ua;L^JT$WT&BQ1A`gd6^r=*|* zvEa>{2ck8$J7#xp{$gLHa%&$YByc>XWutGmrH9H!)`6G;+x1pEt{SoaP_-lDxr*Zu z+l+~&zCW`0vsn%vI^xmGGfGn8*v9xwEtid@N1xn$?9&s6UUU4*5n;O2+GG7zUp;&7 zy&`7b;pFCqL(U$0#f|S~l%#~|7V*nlPHeul>JCGPWqnl=J}$Lxetmf8-NS~~v|`!p z&&M~i9MTNeR5gfXP5V+gxaiRNURb(DNlKV*5&P{vym{-kYYjc{ zffXXcbg6aNh=qcUUmfTj5#}4YQFH8l2Ms;xffZ|%q=e}fao5%BH7_{&prJq6am|P@ zU1~`)*f@NItLaL!dE0CU3>8_UBqdC@h=WfY+WhjHorZ3>-Nq4Ny3{&g(8rm_#C5Lp zUP9|GyKHm0{qN~p>Ytm{C`k#^E#ennFWTI5!Q=bJ4BsXqOqW`^a>0grTsE=|7iz9Q z^?QBm5BgD!l9VvrB0l}|?9Kb?vktvtx1A%xbg8AgJlN3PDH~^f{Y~SHeJ}3&fNywx~sr^$VfJn^#{B`IOL zMa((hpBwXE`cB^+{Rc*b=~7E0La?DHSvJny_rXSGo*jn%@t{L$l%#~|7P0kg6B|p_ z7aRJ=Q;v!V)1}s(b8iuBEVagP*;wcM7dAe6eYv44?s!a%l9VvrB8E;qvGMWl+x1QT z_AesBbg88gI@r+2DjVOK_KU{;t1Z{J)^@+BQIZm-3*yDC8~^y;0eyNaM1<*5OK+Nf z-@AH4xE)zvTOhnXi4!E`1YTiV4%D)`Lf1bc@@e8G>y5cCGwrhYrfSEiQ|7Pkzr=2RD;{xDjgpiw-6B3( zYyIk(jq!cMA2}f+OqW`^nz`H2x=V&+J5{&*X0^U|HV=16Tapr{Tf`SDombuZ@z0if z<=Z2CU$qGzms$@_Iy?OR(v>$P@^OzOt**|=l#6;m+S` z)F?>_(=B50M;EJ&9X;zceZSp0B21TBdc!qrqxI&T>)mB*|K0qKYsPK0nctjkNlKV* z5&L|#O6}yQHlO&5@mWNeF15D%=^WuqzZ*Tj`s#@9u3r1@8}Cni;nEFjl%#~|7V-N_ zht;mQa@I-r9R9tCFkNcd8@Iz}(dzEj4QhLRFx#XTS6-t=NlKV*5nn8{S#9~_Zl5@D ztX zm@c(^<=hUvv1Q|#leeoKIp*Doqi!4QSzlX{5~f>(=L-E7Up`TDhlns;YWXg=4ZX2t z!*hj0DmPBl+`%*Cwj?D?w}^#)zi;g?tDisdo^QVq5vEJ66W3ffoN32(uaJ#f&pV*@ z#h9fhEimt2s+6RJ=@xO~jfd2J`pHt07F+Rwh%jAhc|>qK^v0HrCFVM;cJ42}H)-`f z>t0Q?B`IOLMLhSXqiWYLFx#YAhE9kG)1}redXL+NM?I}S{(ektr5!$*`0(MstWuH^ zrd!0zJ04d%>X8p7F8!SYBEod3b?W9D2ODdjw~TE3WbpB|B|f@f;wdZdTBRf z1x~EJ_s-Ob^G{wYB21TBe)GE>ehXD92ds5c?Y%#Yn)t+0i+GjVmZXH~7U4JMtt)*n z(Qi-^J}$Ku(tF%CT3-$PR{qZA4^Q-4nv#?-JwQD0e~V2Lk(2OosRi5pm5RNZ?Yg}u z$*V9MDq7f|5`~BVkE}C~w`zL-_(`TFAw-dMZ#0py!99ELMn#jMjF}24M3bRgq5%nC z4ayLy?nM-3=AON`3@Nh=(O?LnBC~H_mEY&{oV`z&bj-Bb5{rw1?*$1V@H#b2nFDWN-+1YHe0# zJ?LR%G8}!jO!&IurF!cl8Lzxzf;RF5N4VjOKIRDL5HkAMj7b~xlrkBPqF*mv$x$?x zao0+c{;!OWAU?oIy{2vB%JEO{;}EJPvjhmv2DgnltP-<9tde4a_Aq~d;EXf-p|VQM zI1VARfz8US2WB-NF#ybJzi0baVpfY~9`uU|+Q<`}IeV41<;>|2GOPJAYr_U-=YP&@ z$JsenNijhin9o6Q1@PxvCsclZUztP5?Cf(^W5QcTcBp5RJm zj}0ePVkP4cq*E6Qvc@KjPv&<37;5M1g1TD?XkR{9Pht8ibu z3=s4twm!T|CA^7PCB+17!2bY2k7fH)v**KOaR~7ye9p@3SMZ8J&?|an%&YU^6~!tk zCTJs191PFv`|gKT!1Hnl(y5kseXwEPU3u>ccz3Z%iV4#22SLz-98rI61w2TH5bw_C ztju~~76L&pwcSq#R>Dh-RZ>jQMxNk2-us(BD=>pP1nE>uyl~jyJYM(1YL%GRW0fc& zel!Sr^v~^ca|JwlhfpnvCKypOZ1?=Zm53U|Dk&ydLc|$BFf#G|J9R4&nQ#b+8nCUh zJKKuUkKs#Su0ZsIH7`htiL@1vQAC8L*7%_v}`JNRdO3PPHUTg_<)O_3!q7OAw8URZ>ilM*IpyTSUAXHF~N95if_3 zXq3;j0_%}~Y8h1LC}*saVuCjE1lJ1fAN{oi zYX^rQooaEdKpXklfNO>ChmM$!wL`3uVuEy@U_^M^{zuG5MA#unr&76-q79_<4 zZR80?=>4-#D`jk730|jKk{v*)sQLT1x0aGrNijj1zvVLx+qz#-icEt;NEX0n)`9gv zHUk8+8Dm#1DZTu)BVv^l6SR>hm@)aThW%r0G2@p&n-OR-9d3DU?%f#`q?R=WLSFVt)9+VUlw2>#cR%m>ARVmgE4naEA;)p;Se3CO6 zt`){_tH*2~y@`UPm>``em{Gj#np#Z{K6ar)kWRHEn+Y4tTE07@dQ)UABb5{rq><+Y z!OZCLfj=`d>JXB(v=N&1;K&Nk3)$CqPy4PE+1H3;cPc3+Xd_Q>7P#TX8qDxI1nE?Z zvoimQGX!EXm}$;?Yi%iG`zk3WNaqP=s<)p1Rq1SegHs7!r&^LFhYe=Kn~zvjifp*E z51^PJo!>dYjQfRie=i-m;sJ+{Y z)O$+s#h=Bc`d_LgzbAVQE;-~(+iRc_CB$A1p74p|f|6~!Ro)Uk$Pi}_Q#-bt@0t?Z8MS z#RP5Si8bTOgXiKVmD5`U4naEA+Wz-6vvF+SDX{TM|ItCog2O65dZAyWl462%p4eF9 zx}f@*jVt%)ev3npPPM*#=`OSJQuWtikW6Z|4JDS4A z`5&GW?D2lx%KA6&9;>97Ae|>}t9N=Zyyoted-U4ZAxNiMPh3{7dvMmUtrer6J=7scr&^6JA7nQAx9S8N$2UaYW7YbKPNhv^ zl@t@C^TgrzctPDZTPt4Qqm@IDPPJa|*~e_me(5~gc&$xv<~>^~&g*nstde4abe`B{ z(^0`almD#Pvgt&JAf0L*eSJ@}asNRVz(#n)QNfOjey`X(w=7mkF+n;{T=dG}!Satb zRs8OCatP9?*3yB;n~fuT4~LD>-ya%0+jK+4BOANLDk&yN=ZWr*>=#^r!^Vm?uQ=5q zNT*uOe=Ri|M_e}sHooY;cTjiw`ijMa&xlo0OpwkKukE#G@OS-n6(4_ownLCkwY-}3 z&BkxjI@NmX-rqdVD{H#m z4jcD|U-%n3sn&uXTg=AaPtnFF@!Niz z^FFHRux3cCl462%p1ALd7yXkSe6M1c4~IGg=~Qd*NsG+J>Lqu>M$M?we|GfBilf>N zk5y7kkj@jCkEZzFEPb)!U7Rphg4e0mr}bx;jg_sZ!N$mC6a5Ef#}zxg>tdA@6QuLR z$-4~nk6Q3(Men&cI0WfbYsSjc%*F@N4A{tCcZxrB-Tf8qej6RDq?jO`C+e-)*FWmg z+bgD=JJumcr&_NBZ)SPVx1Bo^Hd>DQ-s`dOmWoFGZ;Vw^OpwkKH(z$IxBHPJD|((X z&LK#rT3=4M!)$!CoHk}gw|dL3m{76)YP|hIB*g^jJaK9DIoZ>1Ew6Z#Z`crm*Qpk+ zbF4>!$lZ4M`6*G56cZ_pefrU@;TgRfq@_|KmujJe_Ish`VXL;A=O;BUNLUgjcwK1S zux-3!e$u)Hg8!RpO<#Fh$a)m+U^Hyno^}USQcRF8^pfbt39rs)FHwTmsn)9cGt5T5 zC-&H7V6^VY&hyz5RZ>ilF7)=OR<&C5+1r)ib*eSwq(x?<@I*xociVM7pD2|S6Qm1I zZ8Z9qCiD5!D#7bi>+v32%tm2kh_2Y{=_VW*R8mZkE{s0WsS_S;!qG``e zq9cxq4?T8R>8AWDqd@R~Q>{08_Oag!E19_d+6kpx$*825Ae|?$T8fw4)VGwYB_(*B zYGLJMHVP}UxOD5arOAq{ASotD7gl|7zfqG*lT}}V;QyvtSOMDag_UJ|`E~b}CM(N= zq?jOGSiQyvKUz_mtX>NQ|2Ne-XTTWyy|6-#-}(5NQm&9yQcRF8tit1m?~Y5k3Ri;H zsTNk`W}~pukB1zTD@|7V1xYbMy5LR3cl?+uO}vQ$!T(LQ;91!31&<{jcKXuN#A7K) ziV4yMuPCn7Xmx4g6%`2nZ>n|i&v)AI1>Xo7%`cqN%W&Y@PAV+ujVZKy%1rE z5tC`k2#ZRJ3DP?W#AHZ#O7J?>l6rU+lZg?NVW}7$N=s$55=jX`u;z%#u;#uJQYugG z2MEMuV#H*cA|~Ujq?n)$+z$|l$;61sG{qfs2x(nU`T_{VWMaf*nxdEZDk&yt1N{mF zVlpveGELDF9YT7ECw&?OVlpveGELFjeU%gww1MXX1Y$BVVlqwfL^*`?c2Ay75Qxdd zh{-fXOvYD9F+m%6&Osn16C)m`seA zOjC?-4k4qDFXJu<#AIT`WSU|WbtJ_EZD8C5ftXB;m`qcQ)Peq&jH14b`5+LJi4l`& zirFAgNijhim_I-uCKDqj(-bp~L&$94%RC4IF_{=K8O~~fN{R{Ez&r>7F_{=K8P1#z zA+wq<^En8_WMaf*I6DU_DJEzG^En8_WMaf*xB_qpnVo%EOV9>Z8HmYnl@X|j}9lZg?N;fl;5WVPhWIuQh7 zGBIK@T=fMiDJEzG>qHQU$;61saAoNbvg-3?jS2!WnHVvdQmkGBl@t@Sf%Ps3#AIT` zWJ<9@b_iL$`m)vrftXB;m`o{F;ekqu3EIHA9Ry-B5n?i>Sm`^2tipZqKR_TR6Coy3 z3U4A%Nijhi@IOExCKDkhQwop8A;g>T#rFY$m`sG2OewsgKqbWlZNQHLftXB$m`o`= zFNYAX$QK_D1Y$A~Vlt)h?gEt*6SM(;5Cmc}5n?i>@E{#RygOffQ4om9M2N|h!b=TQ zQcTbW{8|u*$wY|Bl)@8s2=P*V@u@)|CKDkhQwnc8P)RXC8}QFTASM$bCR2)-j6;aG z?Ms{i1Y$BFVlt(O8U!jSCTIh31`vqJgow$MA~N9+5;gE8UIGF!nGi9VQp98el@t@S zfd~r-#AI@a$&?}{;}8=4pp9%2lgSfV#AH&UASotx+CWUkLrf+ul@e*(hizrQ7i#Vy zCR38sydYso(*Gr~v#l8MLQJM4Y25;$S`uwTJs4F(Ovdh@N{R{E$lr5D?hunHVJ}fa zqH4ZG4PgT@86Pp3681!u6cetdDj`u$U!u6M!DuaFGV?exsHB*njr>@`h%jO@^Emn_A<HOM<87#zPn89)g$u4mXXQeHy$O6P`{BQ!_J)m`nv%;Yvu>k{*DSwy@F<5R<7$R{8}=F+m%7f*D@KWGWJGqCoI}Q!RKF z_Itr&2@sR1NIaH;q?jO`Czz>5Or|37iV6h(H`S6XdEWC15R<8(=cSTjf^^ zOr`=c8HbQ;xF^~EyayQ|CR0HVQYFO%ZRCAU?i@f&rh;Co5|Y*TWY+?0aCZV?G8OcM zRZ>jQM&5Vk4hY0#D(G!1A-fY81F$wMc=Q2cG8KtOUyu|Nw2>#clLIlC3dCd>11J!@ zPPGt0u;00#CBIt)F&XX_VPv8pDJDqgiB^x~UheVixS%}O#XEk~gj_g$zUS4u(_hSU zySTo7TK;O`febCIb_Iz`IU-DUFyWXO?HnACr56xVhDC;h)cp3r0`c$2)iTPNwzV6TSRFua?>M(k*BBYu_t1V*Vc75r5nr z`-f{lJo0JAd-0*OO{?be6MSgeHAo+tMt}ry&6<)h1X1<)+U!3)t~9MruWIO{GB z`6!JMC>@9&H?$5P1abGoXR|fl8e>}1wruxMW4lHR_^7cF)BoLoUb5eW_Tlv)+PyhB z``MO>rZxFLOT8W!=C5~uf4PTNHR7<&i$ScvqeFNah>d%nn0@Z4$wqXWGTu95RQ?)w zl6TICi+;QcMB|NJ!oz9fo~p7P)9*0i((9_Tci1(0i#O-RYmIpBu`SrEhF+3QdP#_0 z;_(immqh=;fAbo>B;tQ3y(F?;l1+L^c=3iWO$)swV);p+mqaW-3D(DYNjB*vA$p0Q z^pc2e#A~)0+lU0)%z8;S=_Mh0iD{viM7$3qcwcxQl3oG=y~Im;Nr+xzTIeMa?==bD zd){jjy!X~iyrh?eFFbU%X`z=yub@AXVE>wj{zQWP%X*2I^pYHUiD{viL_ed?l3*YH z9etJr`>^#AFX<&Y^b*rTFA4cvkl=IjJe~^@Xo1jriI?<}9D0dqp_hbw_DG`mgO-=CgUy$)I3aTUIwY3)I5ip+coPt5o5Yj zb0bjm9RAz1P;>9_J-gdAYR)Igi2TTanj3+dhokmB+O$v~4>h-I)ZCZ8>s!rpNzKD4 z&`fIXH(0gIu2FMeo}8KgaKE|S8xT)sbK3Pnk@MYi|xG zq8^XN&p3Bb2|cZVcWfPSX4wC&8-uyiA9V=T()*7++siHpr=V0@4~s*UD50k=kYlNK zN_ZMdwW7@%4xw7whM7#arymJV0x@9w)KE_hXy27Pi?+JI`~9JZdhEJud8iU4^eI4G zH0dSP7ff^r)sh~A5$J_GUJmP{=I5L;)J~o7ez4X`=$?JNH9J^tZB?Uo*3R^hU=Pt< z_k5~&&oREh#^{9~g@?k%_QBPho~XS~_o3sB(m`x@u;II(=TxGEju@HDn?HSKr8<1{ zB8N~d-G`2IkSDA*V%ylMS+QYz-B~B>g3swVhW+hFtPM}b9qiEH@Uwa? z3)|uj);Qx&XG~Nr9Un89M~_?=Hb+}M`0|7@l_;@uA3DcWA*z&6EupdY>EGgQt9jFU zt@WCuAf~-V!vwZ>~5umob8Kb^a1hb(!tp? zaR=+oTjLNqtI3!T;^UgPWRJidthMj!o=TLE*#N|S$^6map3fXYwPY><@pRX}vjb3% z%&3p;9S^JrdSs-;>+;4Mv=#0gYmPhV$qCs=PO?S=ux{8ne{>&mwwFWA$FyDQ5V``8 z^Smh4fiL&*8lvXY7A){oqJ*v`@D<<7MtQ?wqtD0}9YVF_TrzB&{NN<3N4--Qdn!=^ zv!~6XoJ}(s_9xaH{mc3j+X`bY$1c-C{|a?YgkIA6d9MRX)u7uLXSJk+oL)z7pW1hh z*B3Q!`M;|iLbYT*N2#_(Pk7g&RP}F|!nH`mcIPTg30Vz*XqT)Rp8RW;L#URlB|seY z@aNvKu<`XFbF+LdSaXh1@+De7ixnflUD-J6yW(nB1@SAtNAt=?@he{kmwdBnUAoj=e z&3lgLy-MH1fzi%t%TZ8T1S8y(#>=c8k9d3JRHB5g&T*Rjht=L^DAkO^COL#^NxONO z%o*8_tyB#vwj$n8sG;-r3%MU4zFo7zYlV7TI{Acw>6gGsSEi{L>Sm zJRkNh1JYbMv7fQkIsRrcC9^K^n!(09lfzI(277A&3BChBo-PopygjmP-6qr5hB9*6 zd2kYFKVL>W5F=}~&rMo~_j&KTH77o@FWzs_I&t;KPZ}|_-twIIuZ&;V>YninuHARm zqs|o@^ER4|&WUg7i`VG6tBkK-uO6~gwR+xKC4L|MezQS8O=fNMlEvQ)dWpo_pY7_2 z7iV(@y%hRs?)-t8XOo&|C59A9bf{?DMa_*s&9n54`M->)(6i<>{WQ6Qc+OGtyp3j~ zvl4rWB&rgwhrhEx(3dqE^kt>gg?!+_>r?EH01*3vFj`w^ABn2@ zTEd-ixK|LZRf!T3pTqrVSNn~!L1^8&Rh3yKR7*!9?2TGoo;?|*y6DCe89PcNbiNW2 z#e)q*ge}(B91&q9R7+xjARcVhENq3=y}i@3j_<5(rJg0;)>FRB?qJ8+=Q|#x5^6h> zxi}nQV`9Swn{)bKs^!Kq{%W;nb^zL{qSlO*^X$dq05e8WG;ror8PtaUq9-e45|V=%&Xd$7Ak8l6>`8!6ha&ud{% z%(Z*=IxSR*{;x)ju;X{Z!QL)t-7OQhWVN=EY4Ej#c%s&nSZ?BFWUy4Cgybx6KURNq zclJ26?y6259YVEqm5DcneAL|Ai0o3gpO$A;qJ(5NVB`A@tu6m?7qVnZsFvhKu+snc z$Jf{+EUA2wf(JTJ8Ub5@Tz#&x2jkiD3^MPzB z+Unf3jj}3H!mYH%ajd%uw}-{AMBcF8HBS{fKShS&%5 z`_cQ5$FtSZx&!7vTBd|*sZWI{&fHGkT`1L#r)pka4Fr8O=GB-dREZMuM1_ba!bhX82A|C#R7>OVnM}0elki^5A73o^-igpF zA(<`Mke-;6z7$GNEXwdoZ?Dp_DLb~!8^*TLrjziUwRR)Ot zcdkpE{D%^72x`YKc{x90Q%*{|RiYHrgZ#Akqw`;zSI?z@&dglb7v7Q{(AGrUfY zUJ3CBLCAVHCo9%S*1knMYs5FuxTr&j2LKz4xw5SoiPZK{EiED5wg8WdZ3Pd^qRNcW z!RvB%1&J318}#Zpw!_PF2-Ok~8N{J)-xXG1Z2z&>0w<%Wgk<Uu^ql9+X}v?rxGP3t_2&bx^}gG^}u5b9YVEa#{~%4m*M1{m5_ZIAS5OeN>nA1 z_)O8BJBeRuHp3w#N(CDkWHH!QjO}Y}RZB~Vb4Bp#*jDiJJe4RRkwVyz2&6-(mRs|5 zzt4*;-tknTgv57YL!yJB#QGwM4i@cblnA6o?i@m*k+4DUlx+oXRilH>-byWDCd2(> zY^x8klTIc2zY-&7J$A;z9YVDv;tfLb2F{KxB_z`TLZZ&0#Em0~Iy-f8BHKAFyAl%d zh7J0&Y%BP;8mD%4u4)PK&P@2TY%BP;%n}!NQ|SLn?gcjJ&vI;sf9nvcMSnKQ6@r+0 zbhF%IjO|OVTWg+fDp5jqh=Gv2K`4>`NOA~Hotzwt<{%wHGAXdZydc|(*)pxIYH10v zB7^71wt^>VdpMI!RiuQQA6$LoGgSwnt*(1;nM0_STl4wvRIeJ1w(2%^ou?8dc+ED% zjvmxQ@=>9-kL0GD67Jl^dP2=Enq7*NkUSo2NVYGhwN)*aD$SBQ8AZz?r;=iVel5IM z*pRaT4#EFTwLqt51VA90pJh*EcAq;R(tf3Fg*#Z-pNd%D83W6B2e~U(B}%yUpa;xe z0+0Cr5ow*=eXl(h%z2ra(Iw*+=2W8p>(&FiimR9<TtqLbcqTPH+9Uq1O@5N4p{Kdn!>vcRkryl1p-sd_D^8Bj-ONEurNg?ZgOjkfBPH zz!+@*#4`dmQdcE8$ea?YrF#NwHpnG8$WSFp$axdkNKd682k8*1C8t$DjD!cw=i~d1 z&p3O$w5@damgOMr4#MlUy#yTL;7K}r7__vOgUs^zfVY~}|57b?CplICxg-afQ;8C8 zJ+R8iB{|4Y3Dx2W0``1(n5em&$Kkr9Ai)~Wu90Ia+TV^fTrSB$I;BzqE47HvJa=JO z4$^84-!rSFQZ3n81A@LLpAYz+&aQhU;4`GVcR(NqX?GAgNQY1@cRyUqTK9PU@qE<% zWj_5V+f&3nWJoySY!4p{$^fkF3CaWRHB4i z4|u|1l7kGDP%Sz01sifQEL4e{5-U0}f;dAi$w4}$QbKnpSq{=_4!kRu%YLT6{DYRS$zM5B8Avdnu6&&U66?&RzjRl?nEh?q>6i1OZR(OR4q($kU5no!Lg9f2S-55 zLE1?@J8&JeTAkt5l+d?!~hlq{o>PJ{#k^g?gwKvI928z%xUs=%cZ9;j=LdP>?9$?(3tE z#^(b*n?tCU?1x1jr)2tC+hNLGpej*9_uN|EAWU+QJgHY`A32>FY6&d|nV#p&sl*|6 zp7TV_k(J3MImjv{kd-leJm-gOjkO{C6VwBlpD@Wm=2W5tGD1dk1?`*}W#*^wU#cZ% zNkLrvVt!Zg0mlq1(>Bqz(jCT@gS0ycPm-rO><%)gr-a(J9HjLU96BR4r*Y5Imd6=L0!N-QUU_bb2@SDL~0)pY@v87|%!R9y1+6o-WVb51HvTqvQ_+nG@;NR*JL05<5OaV+7!QHPLI(OM_VL0VgJ z->6FTe`N%Rjp}FQY%E!P>c0-5TDtGu+1bxMEVdS9{7?y*YheR9$aE~p%4p!pxKeb| z8#%~y+||9#4k4o}Y#;||GY)sHYi(6aOK3SrYb);1REZKY!@&k}kk(enL551GmaI!a z;H06AyHDcep-PmH6DlB(gS1%L9dSeiaSm9 zzf?<0XgNr0E94+^Dp5k#cCdj{nbuZ3rKyB!xiyy)JbKPYSAd?Jw1ExeAk)=SR@OVd ztd@%2Qh*#}x+2SJ*_DvBoo_ivYb)+eRYJA2PS_C-Kak@U_ok{u3Go?VLrx+&glf4p zmy<}LN|cZ@MzA64-K?xweOdb!y#qpg13jVO5aI#A22Ve*U-2A>)>gH&gqDM}w&E^O zl_()z7;K1l=MbtTULOeYot<;rN{CMlLOd_?LODY+zb2kn(Hl09gG{|U^@e43973X0uz?(;wG~fRDWO_gLd!u~TXCnUN|cb;B5Yvy zs&PJiTlEaLD|QnMR#Gi5v6eOB&5C zdb1Hu*QAl{td?B~iFm^X{aLmZ_t+|-T3SNOL0VgJkF83SkZcWX$SG`xP%Sx~4dRcT zC%v7wcqkz`BoN3!rg;N=2W_73%C1f7}h)>GSj(@&lyLb2*yE*UK);DN>cwBi@_wLEw zrnY=*cI!_Y#oH!s_u}9r=Pk{6M`M(}E%MeW#~D%8l5a3OJhP7QH}(^=Ogd?jZpJ2sW}MLJW6WL?_h-__%#@LD|CdK zTkE3cAW-u-sd+5#r)H_r`w_|g0P*%KB|+QA_76JT`frpw{W7cJ?9Lsd@7oRZ`;VOI z-Mqk$c3XL!UEi>y35eA-SNqGFofTX#uneK>&DIT_Imlm=+0+{+jaZ7hk|(J zk2>Dkv&w_-n+3k?nc(Q-aqQx`)OpKJ_DGMb`5&Jri!bvY?pGc>v%bAAJ5ro;kSEQ3 z#E9Nar+{d*+e2RV^zz_{rpNN#c78h7%6=dJ{6-s$xb%WaAQpVR%zLs|dGNyS&74zh zSjia8mCU8VK30#()5}4;(fudyuWseR%8G`3x1DJrN8y}4d*k{ejp$c>Fo@$W+|%Eu zV|g&8q>e8;0lB6&ns3RQbxt=UhW9)JM9H87{T=PfgZIwe>d8J!U-nu0($XMqx#e*G zrPk%a``>+Rs|(hgEdYPeZ1634az8+v-q#xxnIvN53cy3V)q(GV4sMkLN5VXI!KraD-UJ@m}Bot3L5>GfnFEN78 zqxF&~=_P!(ot26$AW;K8wMOKhTJ(}A=_R2=akwwsXl7#2ON>A-ferMMDCs4k#K^eo z-U#L<{u*SjXuYm?mdToHMvolvx7>; zl}JVg63u3K{m(29dVYJHv!hMMl}JVg5N*y4y|oxiCUtA!?EaH+C6bW=#KczLddK%J z4_aQ@$k|(|yEJ8F0P*KOyZQsWmj`cNw70X@RmPP_Mg|Z=FWb+*9AinzB^hU5u#79b z=RSL4{+=%yae%+RZF#Wk89PFiC?VqtY%IO$CjXUvM+D2??%@2FYROmv;<7KA_(A*f z;3aRJ^NvOtyNYIm)4wV8uRW?f_@d|PQ2$E_8M|QPx<*s{PpgjzzNyv3`7hOy@e0J; zlUw^6FeX;Nf@AzoO3H)X4|s;X+FFslS_v5+(RW+^GTqetbK0Au^n^*cNNr6+A%qRalB{f#y8 z)c(-k`7b4q5wQ9(|AqIey)?&P^!D)JhMz8T2-W&u=ew;`pM1AFh~1t!$)8)hJb2>o z4{|C|LeEXXS9`3p|0sy6F-J0kky`hp?DiH+-ha$U9^MvOd#*ob_VA$j=<^+k5@MS~ z_wN3^+eQbC+vk`uF&q3Z)snMoAikeC&p+h3;X&QK=Vw)-#AU%$t9d>jHE7(){uMh$ z2TKlUU#5g=>FGLrF}>A%|9;dX{Ax;0B}#}rwC>W;-TfP3V^j6{4xw6N8-&z6rxGQk zML=A<`+uwc#Mr)9gHH6e(y`rngR-mue47n&$!tI(-B0PfL0MJ+ATS$*$!y^Gva){g zWd%T@*^Drm4V>75tRH+?0f4}45GJ#M6Ni!YgD)!p5SR_ZWHxZ3T(W-fWd#5Nvq6;1 z22Rvb)(^g{06<_ih?3dBiO|aWf$PL5nGHZ-q>hr2+Ii=)tRJ{eGy*FC5EwP2#j!1GQv5z8(BYivI4;Kfe|iBMmR^JgsdMxV1$d35zZl0>yUnTT0Jnr zfxrkCB_o`ZeUmkc=Mosi0h zDp5kSvNpm+$q2`DqN(*z%FZ_g+wWX++XxpWBb*~qLTr=h-aSf2IG#%_{FiD;W*h`Y zxF{Lnaw<{c(qO99yfDH=$p}}aglcK--bT168R4=jQ9|sYbuq$4$q45VswK8TNX@e< zQ9@b-#Kq4Y7C*Ijmtg&dKb?C}+2`(vzH|HcZwveNo^IEVgf-AsZTjvOJPG2ny_Pz@ zv#x_&Z~Lk8&E{=)+;^(uhby7$6=XB!)eTsxN8f(fAyn(W+a{Vv-{R2SBD~l6rGL!E z%C3VWl_=q^OLqOYzSU#;3u7EYwa!0(irLuy-CL-6u)KP}sKFhb)ia>z}@sYCgxWehhE>r>M>;CM-HJ{XZD_M zHu87y=e9M?#<_cCLzO6@^KK?{%r&KEb4sYzUVUbmjr{Ymy)tiO(GOFyDp5l0 zd6~?%qe`uDD|T>QXp#vdP~+K`KUqn6?aC*VD;MV<|d9r30aq5yc+-2?-Bde^3D?- zLbWiCSvxmLYpXo=&=3H=rHy(^lxr$Rp;7Y9746+n(x#2 zSZk|K+SQ0vq6DJR*1C*FXEF;%91x|k42^QhdbcRz)w<`HgnwJ}um`)9>t$OWOD^^0a z+?wCIy>Yw|&*0%(4~|u$MEAbEt*uUc`drvJ@SJnQPKcg2`shR_7Ajs*QC#$e6J~{< zJTN@CbjL%EL<#Y{V552Oy{xUis<(SA9+nfK?OFPG$dS6{es_Tw)T?g9b;&i4HI7xH z|J!Yk-bQrTYZ{1GSDqH}89egu?hc_^&tJRHGA4s}y&J^w+dD)YuLeDMUaS%&+#E~& zu?J_rKs>SSL7nUks$9|Y)Sq~)j8kX1X2{2>FW+TvFFI*NP=DY*mw?nAb zHEX71nO)j{znQQx^thirwpH1e7sM)2LNak6E}K-%t3V!S`pbb6p_M!i@4w|(kjDYB z*FjUgZ@Zwax<24YlyIZ9>*{>tacsY2`5v+UmuhJVF>{{V*yl6&e&wODN|fkP`na`K zz9-(^y9&%C2MjtI8apXo@HaO2d?KWOc_E)JnuZp|MGAGWp{@$YG|N|adH>St@KmulP&8+Ts6 z)Y}c2xaE&EcfL3znYf~O`x$Q@<+nM0M9}lINsdGbH{L#{-85^fM$0xiglg^8XFs1$ z)YaGAgi`%A<;8qk_1QC4i4xB?KE{ago38?~?Yy^esXor20ou>&XAa?tt4E%U`Dmyk)wx=>qZ}A8QzI+u5u(wsMm+{ z26uJ|*xTP8yxJjD>*2F*F&p`{&vWl)&BhxCFN##6gnE6M%#9oRn2mRPKH(6m)uGFs zX5+KR-^I%EjOks?#tRK@id3S6_#Yq+z2|r*}e7Q-a5+%f2 z0x`1o1$I9c-c!dRR0}I)t4Dr?Jbbr4K^u%dOY7glwR1tDg!*t8MIXD!>M?Dv0~|uN zj_Ehk{wePj1ylRv?|Hw?S(PXu_B@=AYM-}pYvWryB~(jF3u097US{LJqyF(!qJ*>? z2zV1#4|o&45~?Mw4nndrPIg+dGK@g_oSorK_;}0BiaY(pn{XsbNbCdzya^i_;7vG$ zYDqr^0dK-QVR#e1N|cbN3k19gYb$sY4xw7|+<<^LVQmF(!dHnB@|=T^yc(mmK36i# z{Yzer@m*`He0&$)gr9g5jzkHp`i($F5jNmWSX;rHa0u1X5}G$*kqLMczDkt9I@rc8 zcoVPzZ^GIN-h@M_mRoap6V_JnCIXcxA!8+Mz?(=jqn_k8ojn>_LhSeHIn+{@(Y{*K68IyGN;_T#+)dvW86JFv?_$rZgkS}XH5b!3ft>8@r zN~o5sS3tmtKLO@xUz;j2Um)G6Kd0vqrq!o-^hlu#}B47tRc00D0zOuUIeB}$-9spka( z-b9#q6AqzT@ELN6Hvt0PM3{IJfl8D>Tcx|(K){;_6K}%F@X3B3_7bT%yooUJCLD

_I1(k?JSV(~DDfr&t*vTl3C)`@j~?Dcpb{m1{(GbKD|i#A z2fPVuD|izQp;~Uu;Z0au!J7zFqQu9oeztxEZvr;pO@xUz!JUAX!Q$*MJGP4QweTjQ z#G7y=O1Sx2coWuE@FpBWwcs;Ei8p~#!JEjpRi8Zrl_>FC<713~Hvt0PgtZmC35QTE z+5JhP^LA@1coTt2l#tz@AS9~hoDz}<8|SWQXBHVdgra1JkRwq7s|+LZs|@THwYI{3 zQHM}1%w1OV{0abBGK|%8Y)xvBSCEgMU_)!*B zgCE6tupm(aYYF>3zthqk7U`J7`-?MRfsTHENty4`F{ z?6*0m|D{@*r@;Ba$1bvZz&G$zqJ-GPntIr7eayzI^>1+q)e_qv;NzGL_&B~wl#q-7 z2>4NEquM`D?qo2w{XNZo$JflmOlFsUBjPzz$NF6l?GUL%YVPDhumj?NQ89Ot zU;OYShmd-NU%Yge*}zxXVdH>~SI4)u-|nq=^YQ57pYJpYz6tMWNu5C4b?=pN%SmJX zfnU#{Uz@gxL#Vw>=7UquwASrg`!G%d{m!}dq*l!LNZ$*I#$h&E=ElMlgvxbPEys9JsKcnCx^2qRSDfo zk;!z%j+7nPb9WE++{vC2XAi8F7XEqnnNfFUWiHA%^^iR*MLT8Zyp^$!zhtSNJ zwmNe3oer?9OwU2LIIXJ$d{G+{^Et0QZ|M*-&T#s=2OL7RwD)8(NB*~`^^yhOyy)~2 zB{Z{@$vnU0(s(YOkHcD4IfQCypGMT++(Gd<_ip#@{^&!ew<|GZ>n-*aES&W=ncH6z(Z*I?%7AE0Ii#K}qvFq6{ofor-WiXiK2H?)+MkJUfU#o z@3yi2zk|zSl_;Ti7Ht=SS3nmjt%o*_5)kP zdH?K)lu#{M&%s9J&o9{8=dY*VclP`%p}9hwX_$L@v<;cK8b96O5UM4+0%0T9WcTRc z4&}jb7u0pm8z`YC2{M@*4yzt-?77{0Z`wJro+Z)~L$ZE^jZORR8T+Hh`rlpHhjD6~ zad_fL3B6C5%-tJ)v9;*%FFc1(Em;S{#+*8vZN2-*_bnJbw~>sIcqO#e@!pRUm)QO2 z^+HXDP%YV+2^(XlKVhbqE5+%f^hK(=o?_oXhhMLu4t+{Gxt7kH0 zznpEo{lUQvoz_)Cyl~h!VBJi+gZ(CUbO_bb-jm4;{A60R86L}dxAt{rP20WMe_ZSA1JJXUtLo1%8!KCLufd@+Z;wvtvfW#C*+_>_Ew@w^ z^=}O?FWc_GSZDlLzv-fDnQ>2}XAYtD!xJ^= z8H=hltGdu3R7)ayu(6@}28-Nvf4Ud<0i;nt=VYnGwLttd^45^~^L?vquR(!OEr~ON znAQ9ti>e*cs|NQo6wdG|A<;GvfA|N6EAf1cJ$0UQ>QA-wl;FB)}_k#_I zy>jWB|es-{=XcS^+*+37wI5VH4U!u?m~7$e*D3ERn0sJUus ztD{t{YiBL?I^wK00-M$RbXJpd+tGp^TRfg* z<_zcV1L!>UdA~nwd{_6XSS3mfK53EB`H^9d(uaMn+r4;*L#UQS?oq17GjI2MCeOJ_ zl=!s%46~6R89v@R*nhWttbbOGVa|RA)xz^=`x$Uz9X9%nIobc={Ow+s?bkcIMU;^9 z?jSP9@8R=){O9>m4xw7w(ulWTv&y^S*6rT#`^NAN7Ver7a=som=GVW~OUElER15c9 z?x38!kL9#I*Cp0IJd2LifX}E}{`@)CC4RatQHc_IXET}q4F169eun-*H)jWgYGF0t z@7$Nsb^8*Z&&NZLmvPlskSL*hO|WzMky$>U!C?pO>kz8tp69H3@d}^M`C~`?bG2R{-pQq zTYCCGw-^z8_v`U<0J z1&I=fuo#_>k#&FiVyj2DXWw-Q)skH#s5zoIK^nzTi4utDn2mhgr{VUqg5l%F`uBhN zyR&0UwPg1NY~Xz|0pBNc#2LFW8fEq1o-`%S9x%pie7l2t)t=vUven~~J@K)lRsuc&sl)uZjSiIGZ_keyB-9=q=P;F+_wdz{U}jS{*i|bsa*r+)~NN;LEe^ zNgwm1$G`?MKS7fD@l~RP*3U9OHYOtT;}EJPJ1AiTnI9W>k@@jeqJ-|)v&@g}hePJa zAyiAw`N0MibwKL8u@mI6;DN+9!N^JD%DFET%V zlKJ5|VUzI9HuAOw$F^mD{3P?^)I$k(ebAKW>R&L6%K zGM9ir<|jxpKMtWb=kQojHGCx)iWPTh%wX~%z^AjYQA7_WD5;9Z6 zhO8MJLbcpGC~rv%#OLt!Zpw-rHpDjwRHB65S6U65~?LDauCS;*a{h$A73R(h&KTOnIAvN{5XVa$=iWIAoG*1^qu#S zDIsfk5aQhh;>G#m-TC76fk5UbNHRZxN|ez1WSJkIt8ip~9746kZ-)(Jeti0B$ovE< zQ9@hYGCy`dkoj>4)e?^$Hjw$T`+>}luM#EnK4E9gfyetv=EosaOFS>w5MRxCqnr}r z!+}8NCykK>66NwGUgAq!1B66a0+lGC_sKFpc0Z8$aR}9txCU$>^JDh|nV&!I-uz}2vpJaZV_wp&B_sKFpev zPnja~FkewqS zkok#|%ugWup?uj*$8~$5)h+WACz&6ob(N6aTd*O!!W=@iv@bY2GXvRMN$)P=Gml-G z^v|tS`LkrQuaDk#L864#&oV!@_Z*oYhfpoqO^13Q^AjhTpFkx_$bK&n$oyC@LFUI- zLbYT!9SCH8td}73fXt8cen7V#$oxb}=Eo_O>=$&-Y*^;UYL3j0L+B|HZ9~iaSnDG5_JiWi#R=o54s?p}a~U24psn&43NrhwKol<(5kJ z@A`<=*nc65*U0wxvPT#;kok#|%#R~cLhFY$^_^Ype&7uP4xw7Is~k4)mIB+Y ze#@JyctYC7cI;#KmC&;}_MSUCZ}7<54?Bcv$?kaAz`OLU@8Vs0Jn3yuCr^zlp=XTj z&BGDjJiNYE6NgYOd2SX^0c(}=HV!L^RQDY zCFFzxV&QnhpVj=Mu7e#ywY1goU73IDTkGNte@^QvAtw}I1Mh&arxx#ka0u0M`xV{+ zVZ8+JfN*+=5{OgVQ;+p{E40S!s)aKn^laa*z(8T5@6t1oE8m zv-v!yuM#EXq!oxOt6gpNXfti1L#USCO~k2(508_4Eprov{-cDP!GaArgXIva<@Sr~f+k4)U7sVdizunfHbGswkfG+qeEu))mBAi#vJr zU#aylzI;I+m)Cf=sE;qiW=TB!;$P1+!d zx3{h-@j?()kFU-0?HANa-+sYsmhN|yh6GE8)0rDudk=!Rd*ZWMzKxw){PG2B%xkv5 z^QbWiwt#(m*}EP@yEi9inIEK9njhpfV}5K^68Z01uD_#$cN&O|d!LwPu8~^IHS*5! z8t+&0p2eLb!8>W+`t=T{jeDx>?cdb8^t$REdk3%iwsCw%)d=<$>m|9QmxMgsO)b7% zitldYHEc!vf)j16uUqy~Mtu!E5xAs0qGkO@iOnv|f@+dP&H=^3*~v zvHkSCMw>2BsznlGaQ3{d4w`9OrFn@jK@%4X;@` zmWBjNXT5~qCTB0naek#1-`UR^^BTP*VvR|lmxP5cbhDS(SEs4PFJJI9Ag|F&tW` zBLCIt@yJ~8wp-xm4PqHk@(}Rsr;I;Y4Q8uhws_lt}lLRmW?_j@--iU??95^cOggZ zeY9!uTZj0Lrd{(Jk@B45e(>w9Bu?4$RBy^&zk4hRzfjs>)iS&O`YJDy@d^aLxlDrJ zVCFZFN$|VEtP8JEw@Aia5U4r7QpuW^@jK4cf_9Eyx#l(N$}dGbH8%n^w=WP=i?;ZM zU0$Q+92tzrj|`}}5vaM9pIWH7$1jNT8a21?bJ9kBghS2wEjrfRzV1jZ)ZFLS3we#2 z+t&n11`W z_a9%vJhWxF2W-61;vMhF$Dgv2%&2)>B&CX^RJb4aPIw{v7i=7K&u1RLoyY$@w?Ws4 zUl8Q=lV5d=_;o(kgLf7lYQwyvLDHU;(Aui83(U(HH|@6y|>PkO&6yV*5M#b+jyX^+6=rN(_mzUUCD#V@SV2KxcN8~)%Vt4F<47uy$BQ;8C6 zVg8O52l3w#RYn~5`w;tvG$j*ez2x!h$-HL2;#160@hL#-wtn90fSNbxHpY2Al;Br` zN&mS2w;+-)5XUY5ca=k^mfUlcD)|C&T>pkC_8neY=X0lo^cWEBl798%U$Y!SwWPm+ zIO^fgy<>6DzdmGc4!y(5%dhc`@7CF_kGr$6eW9JUIbvW|TfNE~fSONw?M-JaQG(xb zXU+NjKEz~#nBOvu8@~IwL#URHM48NkjaJ(I`1Z1z_7!ki=QF1Szl%;Ad@c)LOpnJt zRN@e-#V@9l=-2i^5c^kKXEykp?EhpplW^qJQB+zam&xGUhE@-J>oBVlC3HN_WDfpe zwf7m?YQ|xc9746E-9o%IBKxtGszJq8tgQ<*45j8ah9vg`#J6i!c&%^;FP(gX$M2uB zhUmMY)K*&rL`9n^X5-+Wp77+!iR77xIJ40PdnCT+HR}?u8Em{WIrR7)UfQ57d4eN( zxa3X9x8b9N# z8I<4%#DC)Wg6u24_|AIp3-J11s--KAOlHxt3qszHt%t>)N|fM;M;pAenao?&P6apvt<(^8= z>k5RfyYOw2oKuMs!$;+9d^uq*yt}h{EeqS?4%Rs1PiGabT3lVQtvI@7GLIg)E^Lmrdhq25 zRVq<}YZJEg|0BwjP%WWRbFN@`2eG2jyQX*3la}_-R+}C&V%WF$vCo=yt_`Fg`_e0Y z%!61f&<55HwpL(y*+b-s^5xkC(RB18e(^S5hC3-E9M^E^80E{j0%ByX_E~(nH_q(4 zH77o@eQBEOXnOPRifr}APZ}|_-g5gkIkgz&5YN=UdC&X7`tU228}l}rjn0X0>5JFs zt%ui=^meorzPaqNRQLvSmH2)1`%{lDD>EE=$>MJY@e9N;zCi4W7Z)wx8G$Mq+fnme zQuD0DkRo~~NzIE^;i$P0s5!smZhjx@L+^wHJ#DU@lA1?W^Sljw&s}0KkwjIBo^yU} zI;nY?#6{@KnhpB0^4y>&A`bU*8i&)^oBFtJ94`63bG#VecUFlK(uTN$FMl|U-@=Yp zY^xqBp;|K6f`HFyz8ZW^^BmbGEVmM_H<5fdJg&9x>kgq>;`_kHeTi4p;GWOyyWxC3 z;1xMu3dchJ&e6#tkX2~}QvH6Oqh<_%(MT;}CX;+OJbtt6ar+iF?=zzVO6YTw$&~l{ z+uCZc{v`%>A;_UxeTmAgUAp2rE+lphZ67DmYe2+eUV@l2;REuAoXU*xu zVXpmeL$4#o-F8FXcf30#)C((oV?8dJ-GR~CLi!H%=fxA~fPkn^_^Y8(49!VxwmHf*ptr~jo|5>G^_ z{%W;nZoseO;)+^xvMN!+t;g4`7UVjjt%fc;##2JI7`p)z z$JiZwW5j(9p<3dLfM{9k9)KkMeBYt?QrG|tgV)=G49YVDv8V%x}qo;T!SdlGjcvq-xqHRU5j!yx81JUQAmUaj4 z*|n7uHBdrJi?bOE->_a%GG$3l|4X$bvJD$`HeH!J1#R`nQ)9C#QNpdqC4K9J_0d-0 z`87NxREsfpwiWX&PQ0D_N(vH*y%)tSTirM@7ob!}XD)V1rG&1DaL?y{ZZ)rW<-IvA zm1?<>q6T;OvDWQaeOpc?O1SH*2Oe8!&&R5+U7bjgYSBmIQ$TMF^Z75!ytnXt{O{&Y z=Dnp7B_tjI;=~09hr6J4w@loU)!Is?!PgRIGFPuDvE0PV$Y7~N3CUUDeyslJ?%Z)` z-Bq1BI)rNJDidcKK58CrM5dwJPs_6^Q9?2su<`wd)|UUc3t2KHR7>(AsCnf-&v}R7 z`M7vtV~vqGYg{)P^<(yYyMrxDmgiKWt*f??uU+xC^^#pz1`eTGZoK`Oo)6?o(N^cK zZIo4s5^g;{nRk5nKH6$Y`5cE(Ey?Mi=KD=(AEx<1mGCW+e2SPWRNI-%Fkeru0*qJv7f-ozzCUbp9? z*)G>RglaKz#HWCM7UEZkLecX=RLY5RDxonz>;w2U8!l$fYy2SQQVZ=PIWJF3n8|## zGfS3Li9_tnp5cDty1}lu#{xO_T)lxLEtVn2&NEaLm9eZ4+%P#@~1c^ZxmrXXo=#4Ob4MM_-UAp|A-QI)6TXD`#~^Df`fMtZr>iIyUj2-mjU|gu{nsI6oM+z4#uCN=olFDcNd<`# zGS`BTu_Py>fxW$#ZN==nme3h@HNxT$GP<(=?z`1y97c@vzf?<0h!g9x^RpVgBb6v2 zGaPLE(D4~-t5NX4lu#{Mmw;fjnd9!0%P#O#qJ(73Kzy3aYEPHX$;liQ%B;qympy~| z9KFn(I^#Hm%%ZRXug=95+!792OEscGeVC@y{;^DJ!i3e z&QbX|wPX}E@8}Sc`GXBvE#+jr6Ul0+Xzz!t$Z}eCC1hZwEt$$7$ttao#=VvS_&TeP!Ad;^V(I)r!tu))Y9 zXEnxPwYI9IC4{fGYb$FjdSEJ1LcB285bw?*R7<=*5aK&KdkvHjZySVoUbd@=V-)>O z@w|%mEs1xhUXeqHrw1GG9IdU+g(s=CRV^(czMO?UID7_2VP}d;l#s{-Y_u75l|6$` zjGyBWs-^i)XRm>i8C61ap4i`-c=R9EJjmLJZAITxJo=(tVG=dSY1x&KXaed1U(?!( zzNZqZr6t7JUVWQIyy$zXLo=TLENFi+0 zXw$&j>fe)Ja0u0MYcBC!PbEr7L>M+CI%s?N*j60lB|2ENqfsJ|8o6@_iAKT(yi;o{ zdaGJn)zT8;v@CYc@frN^sX?Afl#u8-Y)CBJAymt)`7_B*r_892J(VaSc>~yxsB;k&qUm(-n=!=&NC&L3+5_=9r_A7dlDp7)&E&81F7ZG7OW?&iDSM*kuP%U1w=G=FZ$;^MJ zdevyORkyM0oE<4j=w1^i9~El*NNy_95+ah?c}i6;MAc5H*+sKU_J&}#G`()gw)`GmfjB~R7=h` zpyqN4B2)?PzsI&h4zg%BE}oCFAt)7ckWQ(T&C6MoM4|HkzZhjnrj>(7MP$=JdZ*OZNoWY>-WIkao&}Ht6Lk z!IKayAx{$QJe7hRq(i8doK^wxV5??fE41$Iot|~}2y0vEE-TAH+8w0Vtr8{NdcZr) z@%f;)s)TB}JIS#E$R;_+oJy2%>w#59HpxNS84|V?y*$<8ITN-OS0B!K96N!MO0b4A zEuOki+gOkt*eaXkAe~Yvft8w1+w__&2Wd5@@2UT#TC%eS1boeq&j)=^l_&w9!RP!z zKg)8EA?FX|ARR)rWFHWS;n*3(^)7Y_Is5vQkljKcu-?rkIY^#LDYOqVigwMlua?kq zkm=baI|Y=si4yP=jLyG*7v9AG)phRipUu_&|CCEcMy`WOWRzQy5~lg={c$%PW+tMG zOF2h{lS(s5`8JYVbIBm5qYzROol2$5ckdmYBkCvOs7@!65`|86x;cz~uh;s#KYN~Q z9`)b%@qMq?=e^%+t-aru^?I*0EHOy0kb5msN_&R*zxP=YgB+F^WH9&Lhg*nnJk6H% zPA1)tN(f46Zx{&Qh!GQT#`&S$^*1^zF#)M7*&*zq{|TWTa9GegVzv;G$DtTxc!_tC zL{KW<&Co7&SYnXVY#}0#Lp$NB#2_0YDCG*f)|Ge25rdrE3~SipD!!KT{U834X6KVm z9hMkmdMYBwPKp?0jNJP|{uZUkZdCn`^B0D8y)R@75t-4r^ybeuJL>(|_tJU1QIYsi znKik=!f!SEYkjrG`~xbs@ORCR^NP$2$~cp$N(^$Eqjh~}>&lULK4HWl;})G_kkf1- zLT6cl_PwcyK@Lj{G9f5MzE_;8RV4;F%@!i`EsQ?Q!iX4T66sH zg@`;3#UQH^gG>lYndf6``d(SOqd3hL+*b@%qrXbyr&0`ZSYnXN_*6uYix)A-#xtk) zY(!8>(Si8-Xf>s$(jG0e>pdG=h{(J?#UR6iia{m>rNEk190%N5-vx;GzV&$|J}@jej>Ku_7#8$Sk}X8A z?}$N$mzbMM1f}x*K}Gw9B?h^SEkxvTC^(79#M3!-zq~$Q6T3Pem!{O$hTuy}t5YMYa%u_omW4ud8o~_ro_Xh@ccX>4QOg z`@PM_HGkayxrY;5oe13EQy=ieA$+NVCpvyU@i&b_5%-C=JEGXP5P`QqeV8ZeZ;4`% z^xYw)_=FLI3|)E8#ug&*Jysv9{j6y=(pmN@DO68H?x8hb~!xkbiuc!}vONRIw zRQRr}bkiH(U2>fh0$*44VV1geW$rddODR5K#2`agia}1Zg$T@W>O(Qe@GHe2d2h3# z6jm8RY`9`wlI{W!f%S?Iib2M#rWoW9b5w;{%{-a#9`CKv%*h!iAux*yVP>gyFKCp)4x{d2OuGECUU73bD;qT%OjSz}KPF71ptaoaxmR8DA zpcv$2MKx{FK%_Jcww202;p4zXgbvG!dl2L$#8yrGZ~*a4^y-}|s%`8EVcODR5K z#2`ag-hr`&2<*bthjw-G4tkeI1f{Td7GksSp4WU@-}Yb4|6ICVLj-QS34xtgg?*HB zg~e>?{2YA3V3=MO?WcG-KHjrDE+)z3ef5R}Rz$8ErdEky8+QN$o)N3R%Ug*|zV9esMjU@lKi z4IEMIM@s}w6EqIr5tQN+Mhr4eyu9~h3lTWiQXl5K`b%A8v3N-;>DQ>PqDd_raN6sOkT zEAMaF!rw)-Mtzu5>vz!mTOufhh>#FVU$*u17xiub(g{CFw;G8+Tuq2?-S@&t+@QkA zzi(}Yu6)mnPZ;;SCNUP?222P#X&r(Mg(i6tXzsHMwHC=2l?zoxDTJO zh_k9b%)+&<#L9Ixo<74DrTByq?TdKrMasd$79ym>$?bmi;hYKfD@7C&f>MZ73-QMl zv2FX+B!*oRfoQl8s<1k|{|!^!E}QHTnN7T__8yuecaHDbJ73r=87vi|H>7PU9(NfbH*9RH3Ez{>%u7^N@a&mHN8`wGtTF(@?gX`-)pJO(WxqX z%5%o`mFsjEv1otaM7nPAtop%Srn*&M`*d27arNqIc}A>#le45L*JSs_w&m3J}_bFSD-2<4ir@0~r>tv>69in|H!yj)kveK<3wvIvfAB6S~|eOAT28uzuX z;AF&uU%gd3mQr`A+v1Tq6?eis18@x{BMy4%G$G_A&8J^KWiLsQe0fP@k8w;`UeXvL zFKNR|n&KrX&zZa=5RPrSF18W!5+O=WZ+l6~b4I?8^Di4AFA<{D4Y!x1JZJKf)=%X~ zoO4GTAukc4WbCzZJbd=f7&353ts zosrZCd5IA6l2(?JABnY<(rK2>$*P$T3eO?XNB>ouqBB{|R8iW?lwrU#!J2ziMR zn;rKC*ZFDBX%^S66L#gcA8F>?d1mFhWY?Z^Vza~bABk#d{(GD)^nJ6A@1FaC<;@YF zI<0ml$5&o?Sfk2|mGeOQ@0TBRcI6zD6Li#F>Qr~BxoW|>BWKXHl=JL5|E~X5mBPqK zYlJiTM#U-T#6pw`#EmKtk6g#X zQmSSgbu)mdRv=34f@JgJ*RD2l zl_^U(Ke206`R`(nK#c8CYG*d8of&n>{9E=0*CI1Q)ix{FsPf;=dK?)^U3sxl<;B{y z`rM*?uTdM&f7?swW8xajI(}6AD(XR6$`w6b8?Yc6AmqEHo|pZqa}6&`xf&(L(JIsN zWE^c@$;^J$$upwG)pK3R%xG8Gb;U9NJ+3oas-@YlqB7}3ifH*&Af$EmA-}4NUv;iT zVubvvb*&WtEx&Tz_=%SYQR*AmuR7N>u#~H0!xN*@ytO{AgQtH3e$_dPwWVC;6z{q15eQc-?ehrRuUhAnEq>KFE3DD3;_A%9{(D@LRh2N~%iv0w z&e&^&V-U{RYbpQj%)0)&ueRw-x2-bvCIqFNm)F14SM+qQ;>Hy{*+PUf>$;D=YN#{z zwyqjV1f}pz)Kiv>y?#Ghwh)0Yst_e(Z>x;G2|+39u+P}rxWX!1h`<+IeUyy7&F$a5 zHX$fQ+eG!cP8DyPZM#QW=b^S1N55UYrPb&Q+H?N*KR6qEeXpR~Mr zNL9f3PPnpzJ;Rm1T|L6%7}s$xwIG`BUGT<^Ekw8$gwemh;}kvBH47hak3MgCbN!`9 zBm|}MTU+X}G(S`hX;*4-@5iiqe)<~l8za9u?uX3@XDn}A^PXQE%!#clqWG6K+~8t8 zRjGW^)bC%?v4sd%KJhs2xy^`KhhFSzH_a(eWdx;MA7=%kRD+uIF`V>HDSlo18dc3F z|M1?9-&)Mnt*cs1G@`Z7xJFgziY-K7cGfs%Jo0JR+G@VE&v6|Ql)~ID1m^P&b9hTB z%;!R=N=!YmIa^#=aN-&Ap4#K+{mRwlCw|qp5aG&#Mvv>!Uv%{Pqcsm)-t6>?1sz+k zW@xcy&{JWR(XoYyJP($No|CsWp33ht=U2|!gTWhDIo!1~o10GjzchzqjS@AoJ#v3z z`r4WC^>H1}NedBJmk4qEAxF7hYIFWQ-%r0qDXeP7-^9_GbCyrOiP48Eic`v!f~{Sz zSM*e)6J6!FQI+GUI_(y%cN(mNoS!~^sh@FNLwYjf^esea_K7~mvs$Uv+?4G2J%UoM z`|Q3wC&v8YYR#TMqFS?c<<&jbS1YabONDOFA8FM`1V&!P{NbwX)>T4K3VIWwR6n%^ zqxxyFpsNbRvzHng@weBgF@Lx=x#y1&R(dsj$@M=%Bjc(h@I+Vh=v#<@SE>)qAEPpV zBm||fW)uSJ#1YnpQB~JA@QwxVhY*@SMrHnpDz29DS{?6WR1LL8^qvb*>Wun5cP*h9 zhg*oiJ1>OhkIAi&3$NQNeF!Bh0y#lEb~V~P)dJKW*i|jf4Dl=q>st$RZ|M{ zl@QCedS|N|hn_!1m)Vha&ig$tqiqb>7C)IOVNmr_`r3xRce zRAe*4J4i}l1t3JJGUhcy)QPhVyi>%QA*x#WmwLbI%KTw3X(ug2V2z?aG=Fqu{ur?Z z>!2EY10ghjOm-7dYs-CjH%bK7S3;B;Jf1)N4#rdYea0Hj?|kd=jjQ%({^-j5kuY}#M<;e={;085udp|$u*(plR9Er*QL}{z>|TT@)m1!yq~D?x_f*lxWR9va%lN6{ z>+Ib z-(R<%t4?i_mUzxJuxy$`LfK6FOriaPDt z&Em8xx_aUHZ8YaC6C+!fh8@`RuiEGxvK)fT$8 zQ+M-5r+YOKe&y8!5i=KF6n%_W0Bc`!M2zEtwa4{w{2mxVDekEUgVEB3F^*FYer(7V zBG8|7wbo8EMymAJ9ec`E4Yb=pqYcifHIC(1uNjEzA31yaZKI{3cRw!?YcISgY(5^x zQ!m|er22#1Tb?&;*g^#Rj&X#SXdKf-P)g$q4;}ZRbB2+>)UFJ~brd~6BUBkE)>ox6 zQ2$#*@GTGv>6#E(TBz{4UcOmMXwCMiaz95L$(ls{xlBxRag9~B7#!rTL^i3^dWDr*g^!(+l45# zw%U1Lxg(vCVD?Ghn8Bdb^J-PkE42{e+Ft$=Eq~}cjk2*{xOcp@H$L~|grF4dq}m+w zUl1ezUP#=ds`m7lFUvIfD*_=|)f)FQujHz4cY!x{Gf7K+6^)avW!L+bW^mb4J@I1f{6A!QjCk zT++VgfkoXbcbHBQ9wHbw8VvS7c=z@bn@n{t+i1^(pcM1|^pzLeBiC3bo!nt{mNc#N z-LrR&S?#s2UZtZ(iEy1jYxn(6Zz1ivVxecwQ@{Pg^jnmo-gNSN<#Xc8po)bpTZqVU zwNkgQyL<0r5`t3Hn{wU%_CnVN>|XiIXS8e~f^j@WGnUM04}H;8x6W4QrWhTim?@~Q zo!P2(X2(-Uo<>q{eSOZh{+Er?DJK!G)oJa1=ySES``vHO4(;xC#$VGJE2XG6Wg|Ig zwb1U5*1oxA3lTZa`ETQTke%v5CIqFZx4s@^r+SbrTZmv>RW}Y_y+ixU9j3Zxp7XU7 zGo_Rw@$qFC-*zfBa@)TiGdD#uuuEyFx5419H>@ANs~WlKM3@NIWVLqR_s!Q!ySv=A zerWe4zgjmTC`G;L-rc)@-+Jb}{;T)5Y#}1YoqxRMk6m-Jd(+vUPY6m;Z-c=%Pd>T* z=6Z{}+rGP7ibxZ|IJcMs_ixdT=1g_Vs{0!L7NwYtNUShbQda%*_Q0d}PiNuSO|BFx zdTP(*t=H5i-Z7`6Mu~9UUu*Z2$KE0BmI}n(#T#ys5R{_c`U=FIDiF79AtLhtw)yP8 zhjvwmHz6oRy$uF;j%)pPS3huA%N8QYI}q3TZ5y;l?>^Pde#;;sD1|(*8u^o_{-FKi zIZN87u6%Qcy?)Es9re~%0dEf*?VI8TM7Y+swfnB)PF5dJ9r}~j-`)Gyd09eGih2`k z^6am>0&(~3g==(dAtLiKN`2=}^_^QHC`G*~ufe#!bNA5ij!%pYBFF;~|7zV;+au>q zb>BW>orIv2@4T9QF}^2UYTmb1_s<>9VOpH%Bux(nmo=XX-(CFI15)&r2v;_@cK@{f znbK~lvEE&F?c9W*6!q5ESnuAw$$A}Ih{!yd%XYmWe0S4ZA8m=C6!oTc;OAHz!$jccFPJhWSnw=I*b=$r51qneZvtX=Ue<5@W;)!G0JEoSjub=Vm6x#-~ zB57Ll;CBuW?Vk0>8&d>}i2b*`Hnh9u2Ir}dLw7zceD}JW_DTp!QE$3EaMUs3yKDV= zla4J!WZu$Es$l;g`tDx4)srm|l%n4H3ijQ$kDZqoO+=6_E9UpqdDu-8p>`~Tt<2|+35VbX1mldc$AySG1aLWh%PM?)v4 z*(*gx&;0JO(>}#H^zI{4WR!@bpEzsUUxvHazDU}gan>gqe|L|$eL+G{ih5H9v%Riu z{M~(E*V!Fgh{(LY`)2;U@tWZ+w>>K%C`G;LR>~$zn_uj;xSO^2Clce22=WM}-5n2X zzA6^$SudEI5R^jA295l*jqj{xp0cEU(e>|5JQ;aq&yAtpR6pvd8!G$m*2~^(UG+8~ zLRuKE(C&}+zIeE+w7c)s3loA;)SKA2JFGPw+P!$ojx9upjXUkrL9uZ)j<4LkPvbAc zPqtn&At*(?4F*R)bDgH$XK}aDk(VU~CJ|!)PO6EjkGJ3c`{_sCC|=(KqlBOo^E)M0 zaSQfv3s!N|vGKQLoNsB1=N(Yn+b?*}q7*-8oST{+40c++TWxzBb?Kr0GW1p>LLOS# z9^-Gx!`u9_vbWFs^8AFL6g52=nnd;6-N4}0_o zN>S6QaJ1P*pZ)$P7Ij;`<0|W_w=EIOIu+WTE}ZRzpcHMBINP>h@TSeW1!ubjQ(iXT z?)f*=pOQUJ+V7~2Yyq+esA;Vk?!BP)*XOV^4od6FDYI-o3``b5!JuW@wc^zAb z;P`Y`X2IIE?eW0+t0x4dsA--1yz*bFdu5NeJRRSw-gk+}y1MxfGpnD7d;aj&@xAI1 zl%nU01G)Rht8W}I)qP(~a@;FOIh}A1LH2lby){OaqDv3Gd12zPkexzJ4+iJ|^0#4+ zMfX?UdPi=#*P;3445G@h%BLDQa4C)ZHJg{k^(noees+5W(>&kJlyp zg+1QC<}(t4Qq;6~`qcx~f6E^4I^|!J?-G%9HS_Int3IXsA2&QWCm|?>yCBjoZgaG_ zwc#A5wdagdr#${1uSIpjGWy<`OC~2Q5fd~c7Ho)>I7L@qKQp-JYh3cu#3>@;E1T~a z_86Z5Tt4%$u*YW}-Zmj9MNP{duliEFAMn;jqUwr~bkFs2)Kn zYFek~&s)F#h3s+T|13?uO9XBrO1m#u?Xqg9mHt*QdU--n3O8+pz+D;dylSsMeA@wc zWqdm#>@nVXExmV_k>`(1PkwO+-iput!t>3=qNWFfGnQ{2@u(L+@qC|Og_JpvM7-$S z{X!$-6R&??cgD!`$E>w7f>PA9;+(^~!XDL=Pq%C#g5y*C_f`L}Xok{%5yVUzk7D-MISJ2|+1({$PNcNG)z0Id^o}z;{e=t63Jj z=H9(Whc8*uUU$iciLFkCIyF5Qth@QkVEvTrG2`*~C*LI^ z>*_z|Jzo83->L5IPd_gqC`Hd#rPvksyc(Uu#rxr#I=JW6;zqvgao?*BiudE@LkAsr zWQi3>O)IMZU%Q1p9(&cpj!lF;%ws3>P-o;}k8w2PV~1@M_L%wJ-zEg5sA=WJ`Pwrh zw*BV~Z}a(XZ(AZbzQJIPJH8k8c*gI(o)DCxrU!%V_kU;o>`yN0sxQAe`7RMzSFd>U z8uhw5vpjqD%!Hs6JwM%|^BHp3!}p+Yi>}4(I@#lEUwZ4v`;QlHx2y$6un}h_G;Pi$ zHLY>{W&g0p=YIb6WCJ1;5eglSV|Sl<$B0K`CllJK@7VTyH9S9C+*=J`wJHmx!#Z*+*?$KfUWz_q{`& zNZw8~YXqXFBfOTaAdr4?jC}IF3|5>-62i94Q_h6R!Z2zcl&TNRPpm?9=tgCC3|nSTVfT1`?1pfsFS~S*yu6s2M5#JwzL5e zU_GgiNA{W*_E=@t!xDm0)U>{d&)zibapcZ>w`?JT;~NYv|IT3K{l|@)E=UMUQPY|~ z=3QLRlRXYPV&M2-@4E?+^7Y+*&dclF6@8s|(DljNsZn~q-t+%DA!dW8Hk{Rv@AG$f zInvdy<{S~;e#Yj(zY1?Rn~DfA77d^XBk_FKz|zf!>3+ZZ~E0m-E-EtDsj~)g{Kwb zxD_Kehh;Lth6rSV6XIQKT~U8P{ zAt(i(7DBwGct6BjO1GDZ!1#m^Zzg}0PE zky5aY5aKP37JYDuc}wOV_qQFe%B-ok;4OuA#al`(L|}fbgSQmg6>ljaC`G*mZz;a* z;w{x|Ap+kLjYGVp(5`q(2|+39EqF_H;Vo5cAp+kL^&#F;U3g0gK`HpI5MO)r)#1D1 zEu|YH*i+TiTkw`*CoJC5h%H25H7MyEroW)TdLVY1ZF$+A>LA~ zWW-xa2ue|J!CR^eZ>eSr5ts+1EAf`eM;Vo4}Pzq~CA#kdeZujHNGU+XNOX0iXEsdyABCyj} zAL1>AcEwvt2ue|J!CQ(`PVts%wh)1xjQS97DYPrzQbJIQdJEoCU3g11TZq6OM}3I5 zR2SY-MFgd=LlQ!~rPy#Tl}AOCxHO2%KxF5Al{lyW%Y+1f{6A z;4Q_OjCe~mTZq7pUVVtS6xtPUDIq9Dy#;TnzHPI`<}KB1Ap$#k^&#F;U3g0gK`ERE z2=U~Kh>33^O(G^Wq9iNbaQo;nca0-hqkTuzC=oc5RUhIl#fh+ZO9??K>MeLnpOjYTdE6hsb&iiIIUG5;w@E$x0Dc+!db5n;w{yMx0G_dAkLjM9lWK` zu6Rr7<|Gk_(5Vmcmcn<%TS^E@QE$Op3hj!wG-3-8h)t*u@s{esTdIkm6!jLorTU7w zi_KfA*+K+j6Y4{}rK<3j5`t2QYzQIVQg98#TS|9E!Rm1Coe85r2=SJJ`yt-ah%H1Q z9xa4;OQBuymJ)(e)LZbDVpbDxX~Y&H5Q$SC;w^>mino*yl%n2(w^SA0Qq2}35Q$SC z;w@E$x0Dc+LL5&B@s_3wZ)wE)uF_S150-ix48&U+7T(f`EkuBQp+3Z03MPkmO9??K z>MeLnRpBj-*g^#2&gw(FrC<(-x0Dc+qTYhHR2AM*%@!gMceZwSJg_RfrG%gqqSiu) zx6~BgQpy`8uWWpy&bgwfx8N-W=T5vO>#DZ_5z@kh6{bGKTbeGsrG%gq^%lIPVc{)} z*g^zY7V1O1rK<3j5`t3HTkw{u!dt4@LIhYA>O;JxVc{($1f{^y5JD`ZU^I$_lx|^z zTf0(LF0qi>!b0+U-rIl(`CC(1Na{l@q~P3%g_IDKqTYgq)D#wyb=6yn2x(!$98w=* zAx#$+QbJIQdXw+2cgjuH?yrx!yk-j#;1sEke_Z`9bN?t-*xJwCBOxf|+?IvoB?NK; z+8&XY&lw`+?US5-ATs98mvj_N^9!LU4V4EU#sQTUmxG-r>2926z_*vNGXE=5nwc{53!KK z9%3OS1f{6yU?GJ)#6lXeg$Rx>SV(PQAteN*sOexKHHC$ge3yuP9Uu#kd*Ef&&C4%D%7E;(lEF|xWdIY7Y>0lwXg@u%S zmx!z@v5=a=LP`iq(eqO-R_~+Q!a}OGOAQ++7ppV*#@}KgNmpVab%ljAV&)E=`-MHq zxnFOaU?Ii5JF$>_8r8QDf!kc_LoB4Ou#gghQq**?kis5fA=PXlg5wJoQrJT*q=cXp zH61LZwy=6g3?zq_Brr zNHtrC;P`@t6!s7cDIq9DO$Q69Ei9zuyF_GNiG|b@7E(e`ik=@Vq)8s(N~db^emJW% zZcf&?+b3O#g%t0HSV$veLrl44sOexKg+0VVa-^ZR8t%3G{5tF*7Lxi93n}a&7E(e` zikc13sOexKg+0VVN>(F6@tx42 zSV-zaETpi9SV##$DQY@cNL^teCEF6g@dXPh>>(CXLQsmD4i-{dSV%tK?R}SstShmQ z+QLFg-cBice#(LE_($|17E-O~QrJT*Bxg{MzkOm9ETpcmkW#j36g3?zq_BrrNRGtywk3k&3l>t?LoB3(pcFM7ETp!u zkR1Q$eV2%=E3uH;!a_>kPAPhR$}nCbuYs$jg$=|)s*t5Xx)KX1vgwM2lyXyv&k~w; zekW>rFc1r=D=eg%Ekq#ai24ua5gzWn`O_DU|8^BmF+9Su&RH}Vh=tS^7LwUJeG3sM zTySpu(l}3%SV(PQAteN*n1Lu*NNr&u&1DM_=uaaT3#lzEq#+TM!qW;N7Sd$oW~5BU zQ4s-+2q6|yTUbbDz4Qo5(Kf+CY6}agVha&sz=W=p-$#9jh13=nQbJIQ*0hE{@L7FP zy4&7%!d4rv`nvj^>#Z_e^M_Y0!{2lFxpd$D{~5uSzk`^one))?KK;`#oD}^~s{Fl7 z{jrag5a?s>-#`R9o@y(NW2A9>mQwh8S^1^EfndwuK`e`LY^iZXKa?tehu-i@D~x2caWZuvL*h-WAIZz5>Hl@ZeJ{|A5#!b$)D literal 0 HcmV?d00001 diff --git a/GEMstack/knowledge/vehicle/model/meshes/e4/wheel_link_rl.STL b/GEMstack/knowledge/vehicle/model/meshes/e4/wheel_link_rl.STL new file mode 100644 index 0000000000000000000000000000000000000000..049fec8658b304708eed19aec7854851e50e1c3c GIT binary patch literal 476284 zcmb@PdE8Ca7yqv$g`^}(hCKJF45g9eo^yzzObw(#^MD40lnhBU2z?XLEId!8D3wO{ zoRbF8oCYOLnrZkpe--uneAYeZ`t0+2{r>wsf1TH}*88r#_t|Ifz1G_MoLuhz@82Pn zx!isaO^9#W|KEJS0mp_%-QB|s{R$=MkW@Gr>(_!PB-G;{p9oL|; z*+GkZm1GIhC1Swj3*(_ZPpv$B@k)mvooc=H#sOwy(wt{tV?&R@@sp4Em2I#7$X7|0 zAYCFRMrXzKj{7Np@u;62f^@3Y{}6(;|Y*lS>X_EQ`411HuARFWk~mx%6{^@+z`ldC-b znI;ZFI@RiSR%5fV)1Nh>T<)(wdc-GGHL2X`gBF2GvIOZ8asKID<0X9$svP>lJ`O=T z)f#qrBeU_Jq1(d7P7}Jsw=KV*a{LSX1}e!Cq)Wt8^A3w=Ty{a_$pa2_2-2w*G|k2( zmp6h9XvUA#9#RQ1P)U{`T_P?VR~i5P@4(8=$9HoG(y7*v8ozlQ6Fc0~3^qFMwO3p* z_}P5(ACC%Dk|ju&h|yb`#Aoh0CO@TXABP~FYT?eA4YW9Hc%2)?omL)_?^NU1KqXm% zbcy)mo$cf0#afkjpLUW%kWRJG%gqLQCv4oX<=^PK^JeF7T6$Wbk}N^GM11h(chRGF zo}3>XpW_guQ>}*|e8gju!(G3Hi&cFQHxq(Wu1nCk{XQy|f2Dg8kUs@RI z5TsKrj0k1}Pcm#wJMYCPw`2dx*DtszP)U{`T_Sqdu8Nu$cdvYX;s}QzooYQyHg8o2|OaAxNiM3$NVEY`ng657?-lFej|;)U0xN?+JlQvIOZ8aa`{@;lZO$ z$f~P^&CPdxd8|W_PPK41L)N3zOPYBD{iFZg zFaK>1>m_ALmLOds{%Sql@BQlkDn4#_Ir~+a;B~6?V)c#o|J&PiMm=7dJJ-MNx09>x z@kRzJ$r7YX#9j>__y2BkVAb32Ug8j>Q>_tLE3h7=r*_Zdmil)bJ*4XJ+b;=Jk|ju& z2(A_0=rMBv)(#FqI@OwtwE}IFMmVk&{@8ri0<0YZm1GIhC1O$iP5%4dF;!1LbcREa zPPG<)vD$2$(7H9+>ff5%1cjSlTd?Z7L4iuL1nCm7ZdIM2#e;RLwrw`hAxNiMFJP^} zdX#2^*ILvM4!w8Cg4@3DAE+ctkS-B>tlB-eZBnfT`Gvh5f^@2d87`uY(#%=+yS;)x zdn{dWSFfWubCxApf^>;EXLH-&syBO7jh^c{1nE@k_(40^FFiD=0ov-)1NILNSiiCA zgWEd?D#;S0OT?qM9~#_!Pp#@_FFC{^NT*sX4eP;Q$>o|YIXpP)huYO2wrL-zBukJk z5q~v0D%ktV$E&K^v~md2sn(LU6=vhRMqgqL_x%yQgWo@ht6n;Gk3c0^f^>-(-S_z5 z(r4CIb^YJY4naEA;+)}D7UBzYX`27%aSZXx7LxR7iw5Z;t{`cXC!JyxpSMR>>3l2d#)#8Z2dSJ$ejiz;n1=B_! zQoa9~MS2ruNtPg8BHmj)B6whz+SS`u&UXmXsn#Qy$7zG39{i6lM+L3>|6aA?lAC;$ zWC_wGV%>l%gAp(PP}QQ<5QiY0YF*Q#o7p&cdP~?idFL@f(_dy(O>A?juaYc5xOfLXXRFRuBhTHt&%K3dMok5iMv;W2$kSmXxX>t&Wnhb>H}EQZ-sPQc0Ge4cre9yn~PY)xH{c z&>^ICJ?T9l*h>cduVpoQNu-i2K^y2-AlMV7Mjx9oX@j0pF2_;y z^X02KipDbTT1nF1mGKe8TNtT7>e#aSn#Xo_2-T8V0t9D+8^-NbjoBbpNtU2J%pV{) z>>R5kOV9@9a}Zns{QkU*=svDH}h#VW}Xw1IUZh<~uMTzO*e>Q}BCKp`D;jJrws$v9BC0T+t@a%)&O8@7YJ5*z( z?+~&I_r=QqL2qKyz1vj7n}}7CC1?Zw2MBsBTOPS<0X!Cm5O2cgtjvA|uLuOaqUXjv zzW`oQtdcB28zo{-cwXQ1+^Y(nmqUvwIrHgM4j-kC-f6qr$EmldEpp6nS6_L9o{c}}_+&Kj4R7;|UC>5iF z?{xdT0@1-(C0T+r;)x&_f&6v%2N;2L2#F5*ocURg(g?Q(QO+;_GnY}$SS4A4HcAB7 z3Z3r%xdLkkhajD5ajifbrP+XMg>Qz9T!6JhtdcB2x(ttI&-e|S&!1pc>$v5dlmjuQ8>OE zXU?)DOVCD%V1(X3>9{;&`%3US)spN0N=40Izq~$AQYBe}H2+u1G;Hp9VIG+Vhmb6Q z&#VLMfoui{W;4dGc{D%dg?(a`WC_|R5zLr;)%Eo}GA0f|I@RKxqYburF2}6Q+;#Ps zmEo$dEXfk2O9V4N`~AFA<%tvPI0WfbOL9oC!R*qRRUhV&U5ZtbB}gM51)>WwSo^*; zni;G}3CS*5FK0d2J99Z^$=bB&l^-_hXReT~9+YGW+9(lRE3_Q4ERVH=Ly%6jI3myn zpX6MQYlUkzH)OVt-b7iFB}kVDW)yF@v~J~|2Q6|4(y5kYGhu^S%hzYstVGr_Qc0E| zjXWm^W=2<@^CL5(4k1}f8=+Ybj;!#!kbQmqxUcfazD69oQ%RPfjS|6G;L4|WV20Nr zNT*tymHA7YArO++24t0YU1E)mRBZ#wO>{9TK_vo%5bTclGh$&$kcv*E2r zF3uwx?(74|5~NEz2bgg`W8Sa%%U0d#5RwfqNcO#RX&=CUcWK6b0M70NCAdF;Hn8rg zW*p$^_}E)3u(M%FUVlrqIL^&h`(T zKgg@uqn=$aJakmZYroDM`+q4i@xmJuf|JkPuKL=jxg#O11h2Oew_jSHM5w>T>r_i@ zgJP)$Z>q^sg(}Gsi9HZCo*N&GzG27eiYsbIN=T`~or|-q9v4kH3dAd|#|L-J-Kn}s zttOF5vIK3Eh>s?W4W5WwRnKe_I0WfbYs;Uvn2m$_Plb)=28{_S7VcI3&Qk*-m1GIh zC1S%4R|GXrY*}5q=XDN2I@S90nVZbUGc{j?jl-Y3ENH(?%j&U%W=AT?5~NGSZg&q4 zdJf;S`ozN)It1xd>+Bz=n~fXhzX2Ol8xIc-JAL=+s^<0x!krp4h^PP>{i|X^LHYZWC_wGqA>fMpw9<&tN*@agF}!` zwQ4*#*=&rOxf5(0b=KKIxO21W_Zs{ZsU%B~E)f^ZJS}KaYscz64$H+#@H*8x>FjZ4 zs!l!P;8-PD zf^>=4X5;?Bty6xl`f20g4naEAI$(5fvvJ4nr^80L&;G$bXZ~9C{k+bxO0op$5^?5p zdj~7u*;w_fcZ5TbPPLYwbBNj4ukQ%h81qewU}@#oRrhV^5vwFikS-BD@7pyPedUI# zmoGflAxNiMt$)s&jeV{d2OFOZY7p!+bA8p4p(n&D$r7YX#0&Me5B_ZYan-vYp5zdu zQ!TGfW3%zg>({`>clEXnyc<5Py5QJTW0hnH(j}tF)SvwEhp(ynt;^XCK|0lX<+fiu z&MO}sc_VDx7JlMi*7dcj6DOV@t0YU1E)nCFzUDu==hIbn@4LVuNT*s0d;MfK{(OWs z-iu%LJDmDXRhN%0h*gp$NSBD)FMQfR>h3qHwt0J)Ly%6jh90%pY^;6sX4t3`Rr^cF ztghO>6O66RRXkkS-Ao zKib9L|GXQkrk*n1AxNiM&jl|Rc+WSVG8;D9j{3&ywdlI4=7X+^Rgxu0mxzhy-{x(% z-(^+3k3qadev8+s)~A!EnT>Z=(#GuQdT-^0ld9HVG9gw;mLOds&Z{}MaQyXStM32R zB}k`QxGu6DWukb)-lwHRS&}7EI+wdOx;{Li?;dHXlqjZJD53qoT=TG9$L|*;H7`q8 z5+!(DZr!kB{Lg}5+oQTQ>Mme!SAy56)&)l`HXG$9Dr#D5+XZ~0 zRFWk~m!H~b%zs-g;8UvvuT!lDd;MfK$|FN`Vg1Kiab!?QmLOdoeWGJ0-QS9%j}p92 zwJ;Kyjq(T=t(yI9t7L>LOR@y%@+ca;`0IHU$tYST_`9i=U#D@zdtM%?qj8tqS;3K7 zC0T-Wc{Yeg+_a&Bvw;%4PPN+noHrY#8Ry0N+s7lqt1CF;s3c2}F3)Q5Kc`n$a8^@- z*Qpj}II~fnIpcZX?Ve9&&axy+kS@>8aZtZUKAD}%1b;Wx!c1-dFRuXNb&pNUCo6!m zBukJk5z#*T$1M&Tp5ItnWt0j2ZmRWC?|%0G@=7LdylzsSD;bq!3DV`&QvB%E{qtNc zDZ%Sh3o9qHQC^Y7`AwJSlNDK6k|ju&SAFq-QB(5Cs;^A&cT+8_0PX+fm1R8SirezZ z%CaoU5~Rzk*LctStMbX}wM_7LQ>~NF9%uhAuaM){-hDjJ6|zdQ1nKfBJihnlIL}qM z61+~eup&1b<&}PX!S2O;veGY0vIOa}HxW9SW8*KNKwpLj)Og1?(;o%Q2%`+wQI2FpV#vAAXSnjNSD3T_@h^U%+pI%g4e0m=09&S8)Z*8e&LSa z^7MpNk|ju&z3up!`#0t3Z7ad+R12QB*(iJTaf3RW@`*=ZmShRi<)}e?@#KH5TA*7dh(x*WnCKDqjQ;FX0t0YU%2A&TPh{?o=$yDNratP_|o;;f%5R-`! zlc_{Z##c#}pbb3dAP|#@5tFIJ$lwt2)Os>r`4*Fj5tFIJ=;Ny-OV9?!D-eju#E8jM zVuW)D8GU>icR?T~6C);5iBZ&%WC_~9xC;U?nHVvdN{rNj{+5iQzKr=G5R-`!lc~gP z5U3_ppq;>8<@{QASM$dCc_ngL&)sx%UXgqUg!`bCc{-mppq;>8(5cs zKujh^Ool5Nhmcib4}2~?6LXanmj5Qxddh{eZLEHVDLIV#H+fScL~F$r7}Ibvp>eWFo|5@>uCRgsj4S@jpNyCKDkhlZQ7E zs3c3!2K)~Yh{;5V$>ia&ID~i;zW6>M5R-`zlgYy?3RIFMXajx}2*hL}#ANdDyc|Nj zB42zs5Qxb{h{@#P-32Pi60`w-5Cmc}5n?iVc#sYu-kmSLC98XdCLms2XB2b_Z3GC1|5`&l$NxOs0apLg)35gE+68(e?MmZ6aso)c(k}N?RrDu?lRK#Q| z_|z&PQBGf?xUj)!En+hBIWnjuOVCDXEMY_#F`4-seUy-BEyqNU{i-~|`H0EPPe!=1 zBumgniC|VZz>!)dS%P$FY-fZXF_{IN4U~}Rxi8rP z*g#AsKul%7G`SurSb|OKum^N8Lj}zk}N^GL?9*;ASP3Vn2bY^PPHWKgtlUK2{9RF zmjab!3DTvt4>MSZ$uNWE5RzTu8qP{vUXcZe$uLXC6KK|0mK z3ebM3ys``slVP@xE6cJZOOP%R%qSuz!;GRskWRHEn~An!))Fz9Dz1=Kk|ju&*3`_5 zA|_MCRk#w8wWJ4Nr7f@Y1H@#il9hg0k|k)PL@>jPm`qjTO_T}#ZmI>(!v0_OSOUak zsuGW-EXfk2O9V63h{;qXUQwCg@1|OkB`i zhI^9jFL{swVlq|qAXSnjXrttFa_0bIGF9|am5{8yC%YD4gS!(Dlc}O7tdcB28ztYF zJ0K8~siL>7gzQdW48Yp3?9m5^$y6mCeOZzvXrn}MCkJ9ORfx$j22dt=ooXS1VE^ZS zmeOt!#ALWzgprA|BukJk5$*0PKHF>QgkWs3yLZT_NyVD2=XhSj={|Sk@_O_wrR(0a zZ}+afVKknP8#jHs>_`v;mmJ{@=+ix<*1c_~`e#nw-mVY3ahkvMfuD*b?tS`l5HsHB zS1f>tzxTW~&E}id&u3rn-+b-$cHMu}6#tCxE)GdN(Qi12Pby{=+kr$YrnbDu6v&`*>BZti4nh_H3Y<}fl;vqh$C-o=RGiB$B3mm`0dO5VYk+_>rPLO z@n`+}wGmG>7zAR$4__7QfmpmxOK0r&a`g%X^V#%+cjFiM~#h``R~{0CA&`Q6pjXQ*vnH2AN(}gw5I%L zx!3EA()D(4uJq8VM(ovX35fO6x`fAp*wEnc!V`~7F`~!RYrGRim9B9odFPBc^Sg^d zwA|1=+?zITUDo-ZnbV9o?~0lpdWT)3w|H}(zTAi>9{34+)zC`{NiPY}OFZ5|^pfa5 z_-$UJmqh&Sq?bh2OA1LZ3D5faQ`15(iCBIT=p_-$PlENaUQ$SUNr+zJC%q(M8}XWL z#x^3sHnUz*NP0<#USeA4B@yof3EmgphoqN)Kriu^qd$>g|FT}`pUg9Oaq=;T(TIeMqpFI+2<&e)F3A8c@^b#-W zB}McS(?Tx^`FxY$^S%_%HwoNH5a=ad(o2^8J9C<8p_halLr8E;K`$`^y#)LE`gNPy zxeuP&4s~q2Do~5#)fwndye7&1L>r~iXZHCcylC2lVC@O#EPLyW{?Q%h&-P~ZdZWL%kZ2-G}GYTg-AKdE^UHMeWlbuz|ur{+eW=0*Ir zX`$xc-rM)IYt)=ik`bkm0W~)QH4jHMIKZ?}9}hLRYt-DAzUy1fi%HGHsnASn?(eZ? zgxuT>rKwCm$j?p%Ah5EG_#%F86%?(Xca!8Ve_TvKKs(J=@wM z=ZCD#No@(=2sOK1@RKAo7_2{tblVy1jHNReG z`;1vz?)KG_FPz(15B7sxuHHdY!o5JWe{`{(C?vr>|9Tcc?^7<<=JJW*WYpvS_;KeB zDxs$p@Q$tBP7DXVa#b*I=KT(#T6+JnXM4rz;Z&4r(_V3?5+(H11#&DkjtP%LsaAD( z$strr+c1~w@z{OgQ6SFVG9%Oz1KM}x&Z4dE=y^xzp&r|AJ2q5_68aP%E}Ha`nhPg8 zglb8T!3gx!v}eP{sQJmq46{=wydSK!61rzUm#ZJFw6@xzUct`vkYEqdUH5#dc+WAu zz{Z$G?}RO2W6RJQPEXX{r~A-zxz<5!cd+T}9~M=jgpL@w+{-_FV5Qo7%wmU7E!~HX zbC8FwHDdGl83nOnd)-+l?1C@qIEMZ0`>YF(#vSak$I%6q$nO^2ec=Q9tOz^e4(@Qm z@6MR0S~@=Fa`*4|ao8Gdb@#KAI;%v9t^3e9rV6o43DpuBYo9@FUbUK6Hf*nVP48wX zEse3{pN;nzG5pKhZ8S@s+DQ6wB)t;j)xp1BV8s7MF0=C;B+x@5d7>hD&Oub-&hZ&s z@xupp0)YftHj>k45oZVXE6zl@+@|$+btbWEjgRearG%XAi)8cx@%!?jg%fcH8_xg8 zA#_%gF(1Ucb*?MygF9Gvmlr*iC?T@}h})C-V~<-ua0u0sxdg;xNB&tj8}-PIde`3Z zz-(^obglfsTWY{?R?rW_c4Ub*osYD6Po;Hhe zHqGVOpICGBFY8ZiD~!1uyG#rHE7Ua+dP(~yy)G!#9zDi6t0g7m^g4R`jQ(@I{-}A| zzbrd2f@E>y=LbYTq0b>7qKlBcQ zjnA9SEAY8s%{fNN8y!ME7qrdwBc8#vYrL~j^J`yt*;!dCA#Zm8fpOR4%!zT=AyiA( zrFgGF^VN1gzC6EWwO^7#?Yv{cFLhc8MFF#u4wL?A5n{sH#u`ubo&U+@LbwN~hm})lm{NbTco)3GM z0cozB*w5JN9Dj4UiaFiB0A2woG!<9wxUm3r!)ji`ET)S_r$Bq|n zDB0L|Oi_GGU%W=oU1fa!V$G1Hs@wbeW#aeI?>8It(`430FIn=%;Acp@`oXrIcyTso z&`Y78=FT6ec_FEJL1IXeM29ltE^2NBYF?mk%->~1g`PF9>8HsZ#B+|Cmu&1irXaDG zNTMp?diZN>D~`pv9BS?*HSa8O5&E)bgTAcvWB9d*!yTT+;aEfZvW&eUCRg@x`TwL9 zaLKo%YI9BNSLtu57W!3z_27LmpVNFb_?)3i zl#mqwh*R&MU*vezr22V>P%T+Mfavo2nqoIR=U;Dp-%ek$hjaC(gm`2i5P|HRMj+Mi zM>Nu60E|Xz33IvA#|-Oy0ov;2&JPw;qJ%y-x!l-3e_C7BKcq&eglcICu@~pA|5#i7 z_}k!6B}%xy+UH|FE_O#-&8ZnXglf4pUy^vK->-i=REZMm8^Ztic&`HEB^7sdVYIf~ zJ`z>)wS-&aaL*xHs}dz7K8O2pSiP4z4@T?mw5+)v?8Qpb1Jwo=a$Z|fPm!tP+#yH0aF zNF~&EE_YTq(#FK5dwgHi-%>3%mhnfs?F(n4t*YwIEvQ5Zw;rFjTUh9dwi>qLKt|@$ z*rcyo62C;v5erYFoQ&&PB#m)CiFjrrEc-TTR~Up+O*~?@Qz|8NmdNFnUV5w5{M{uV z6}42VCEf%|HT2v@7Abo6!oZ0EDB;dHXM8`-e9o6f-tG{prEe3+$dGel_;U5&E-y7^pf?Gim8tll~64=I=JJ;iweh}t?qkd zd_g5jxb--<|BhZ`v{iW84xSRKC6RR016i3g-tMVHV(*!lWxJ~;7Xp;(fZSP5sg%$) z5$^fC53S}6FS@O$rBW@8=;U&H+}zJvw`{5>(Ru)vEgk&~gc5|TZ`{pj25!9q>6?%50O@2rGssZWI{&b%YMn^3BM9;sJQi4u}ygAK{Vbyh;P zBtr*6BB}P(4z?oSA);-i(a&6N`bnjHRMXYNow%qHYCD&MA85UVexd%BYPlJ#Nx{Q~ zpZ+@`=s5a-&MHyDt;g+m9qA20TRr`U?+~g*PmCTJ;~L0EZ6%heM2Jvr=WpUojuOXKjlT(s)F@HWgJ zpDg^wiO?${nJw6mo>-K=6iQFbWO${wFVnIsAx{Bp&_`oi!DrLHTU0GAVJ=4>jco;= zjZrm=a=>SEvePnx!$z&o!>}>hYS)23ID~4sHUD^Pw$D?E5|a6Y4H-*{G8%+3t~e#k zWLA4@?A)TvQK8IgncWF8bLx!a5HgFx2E97A6}&v1IYZUb z5+WwE{jt_o%72x`YKc{x90Q%*{|RiYHrgZ#Akqw+mr0;cH5412-T9TEQq7F zW_X<(y%ORNf{^uYQC6&xtbH>(Ys5FuxTr&j2LKz4xw5SoiPZK{EiED5wg8WdZ3Pd^ zqRNcW!RvB%1&J318}#Zpw!_PF2-Ok~8AOX$Zwjk0wtv@Wp_5TmLNfdy#PbTpkBY?e za!QCu>Q?Vgy&{JYPY*WeIkK%zS@e>6Ud|3GEg?=jVJ8aPY83Y5s6>BPA``Ij{XLh3 zP0&`~eQ}pVsFquE*#Y6HL$pZNB?%6-9z!oBk|~+Iyq5;qLy6=i6)>P^flR5 z@I4DksFs!xV>^6JwiSF&PbEr7TnjeV9C@Vmt2-Z9Yttc2{#03k7% zP@*c4#Ah;l?j(Mt*$jt}C>3nvki}qIF}AO@RV^(c&K1F{V_U(?^HidQL<(U;B9IQD zT5iqL{XS2(dCgOa5)$8q4T%nh66=d3I+)qfC=p1F+&P3qBVmKyDccI(szwK$y_H(R zT#oz4*j8_2C!I?4cO^#7dTfn_JA`UU#2bX<4V)cYN=T*wghZV~i5o`}b$06HM7E1s zb|oa@4IA`l*;epxHBRm9T-6fdotf}w*;epxnI$gorqJJ&+zV{bpXJyN|JET?i~ekq zD+Dp)fPITgFt$H>#X9qJQ;8C?LkxuE4MK_hN0LKu>g42DGzaMrl1YIL<^|bS%$8|w zRZB~V6&XB7wiP@{+ryb;sv;%a{NUQF9$&UQ+UknCS2%=fxiw$#TFqr+&{jRhf9$D5 z30|`ev7-m|kbG3A?IXDt%k)8!`2>x!W1v)(=00PslVHdpVsYD6g^<-m7G08#l`6#!Kod1ZlgqDM}6C=n$ zhAL44W3c@a&j{E^y)4N=7L`yf-4kH5K{3fehAL4)&YQqSdMX7uNQY1@IjsWXGI+pz zKECPtxU&l4Au>OmdJ# zl_=rX1FMW;l7kGDP%WMyV9$q#iJHrK9Ii{s60G6u8acMi{&uY4ib)RADU}jfsYQI| zxeLQ`kXCc}o&_zHYRS$T5cDyN?X(-C~l15pI|gk ztC%-YOmdK1A(wwkwcs<@|G5Lka*)L&2N|kF37$-033;Z)IUnT^ss-QB2%d<6Uwgn* zuL94BQMEA1K^9e_1jj-? z9~=QK2Wcnukb`sx)k6Hz2%gQtmrwqF!fS@sJ!?@*-IM6-Hk18{An2X)4#Hb4s6<;= zOKUku>m~5=9744a>$T?tJ`ijml3Gl1kc_03B}%yUKn^lYa*z(8T5|djHsp+AQ6-3l zTl?@Nn%cHlcrnRAE>npTx);xKkRE4F_-u^tmg}Kf$PU;T1J4YlqL0Sbh0n$;Kv|-M zyRVNv8lMmNY!0DXvL6ho3(OA6wwr%StvcRTQ$&e|s0R=UI3a*%ch;Yso|huuNu^psHBmV>ljf*fQgB~;5j zKZtB!G08zLQ;8C8J&=P8lN_W&sMZy?Ot-dTX)Ont5}j2dgzc8)tX3kVRGqa{N=OL{ zmV>mK+rCjbA*ou@ZXkFzkIq39m>QjJ{-8Jw9uO*(3_Pu61ggjlIyUSbl z(CbcnJAuM=0%It$*Bv&bCl;hHdD0WPC%Ifgr?)esSe7UuPXTPuN8?z+eWMN`r=qn^ zmV>mm;=WOp=IQJf*3GYPmI+6Fhp(M^}KJoV0-r{mPoqP0~mEurNg zt*y8VR3%D?7X};R-8qD6iPr~0d}rs}wi4n~gAmWlyil&TnO_snEAxg8plD%d~{(%OnAtCUbJEurNgt*yAzR3%DC zY!NoFd)3;CyIGY`Ew|9Vab#`_W-%)EO?B9I!na|nq>!Unxl z_ABm~)!M3-me6vL)>g6Z#^d*szeDnSqvMPvXWr z`I1JnGjBG+>6$dMUC^>CArWubpg+sD;vQQiR7*=}IY?_O?y*&g5|XWf4LODF5UM4o zvqAi}^`y7+77ryPhXevS$TV+Y?~Y-=;=VY^A!ObgB{>#74d@V(Nr4UIAT7tjvx-_< z)zT7L4$?AM+|8;IB_x{#8}v>&Ucp;+2-V_sl2HU9IY{ROs1lN!1d(R2_+A{zNAdh% zny<^el?xd~%aZZ@pq5<;+Dme5ut5)){ffJCl~64$p=J9lUpotLqEU$wXhS)1$n(K$ zD`XTMLbW8fjZ*zHeullJAlG4Ss1hY)9{`B=I-eB(c;Oar?-Ob{@7dNjXuo~%*yzD& zW4w(W`PS_A?>CP(Pu}9i!BNgzn(>atD1BSx^-~WvVp&_h!EEo`&VD>{i??XlSiV!X z{GL>OpXttPj`e6`ay`E3c45CC{2@1O@fP2GCf__3&GZ>qd*>cK{oN;P`7QNbSLws>dWd#&?kJbi=R>K?Zk(SGrbShu6* zK~nRWZ;NDY`DGBX5s8h+Y91vu=NFEOB=|iadEak@nukfvL7?VQQgeO>Dl%G?*g5|E zHaB_`7y41H)mPZ{mH)H?v9``yf5pB7gVU!z0B%Oef-m!e{IBhr(X+V;pZ#7hx?2Tp4x6- z=TsY3GDdSHb6&8s)nm%cu^?XR`GfaIkFmk(s-}FmooOLQ;ha8uY4mzM1`PI9&x?s)O0`LdT2H%n=_XEVLX$SdTE5`;s`Y-0Y;7p6H4FBA&`Ifxi zuT8X4J%7eFApYuG@Mr8kHkiBTBpPLa`FA0-g5@|kLX0-^tBush<2=tOL=_Qe@8MtpLT{A>I z=G|umdI<>hk}&Bde79Yc^pZ$cWYOu(zcvEB1O$3XnDi39+s+93p0eJJ&JT8uSSs`q z5a=ag(o6VmJ0qCM65k*~FEIkW1O$3Xl=PBFb6(=BMYo;Y!wB>e5a=aQ(n~_|gd_2U zBlHp@_&i!KiIQHzciUO1*a8wY;8SZv>8V98iIQFtN)(6t!i{Do2ED`x^b*)WFNu;~ z5=xAWyY7u(ZsLz|HyD9l66SIjuKK0$?a5<RC*w*aBLj%Z z?Y{I5={q)PdtP&AZ>8?il#v0%?>lenpVM<}@bZ}roV~6xu0%32fEafEuKo~=B^Br9 zoPEJEuJE4w?1`m&zIfzr{`!t%gKbavCsc_NGOobJ@~f}*pW9_*u=3R|&Tpxfj3pq> z|D=^4bQ&8x<9+PBqfy4L%xrM{7kU5k{l^BM^j;h4Zz&;T7i?V7e5(I`&5^+ubz3>V zrCKsxftYu6d;e>Ui8ZG^8LAe&uVj3TTw-Hzp#NUQ*kHTe9%rw%R%EYMLdHk*-M0Uo z>DT^sL~!UfHJsm4Eg2I*j2_>~KNaI{gMFs+DYBB-Q?zvq4qc-AX`THojmHMFE2cOS z8MU1=ExFtm@897c``L)#;Pyp_kdZoUK47}lum9$2QK~)zy83rwY(JoJH|MwXq>W2- zZ`94-PzO)#x1F5dQUVzPs~_`Uc(2+sbN$7yjtH*&;e3Zst-re6Y^8edtL;G4di*GV zUcIrwLw~+iREZLLZVJBI1Ks@lK`a}$A2S%Kbx+D}Z^7jK$Bg9RZK3t%`Qz>y5wsq2 znj=v{Y?J8O)4y%=n4o2+A~PmtgTJL(a&`^GHg4PH^6!EGqyIm<_^Y zHgJ4dSwHx)0wA&PtT34koY;b_AADH>fWT}JCbNMPhmrMzFDn2Lm<_^YHgKX`vVQPo z1porGL6pn}PSjD>55BAbKwvhAlG(tC(8~IO>%=IT4M1R|j*^kudFQgMAGl650xJLz z7)7IG6!m1C;LG~KmlXgAjBrsh!a2DcSwDEP0>JZu5iUwbI7gy{tRFyNgo~09&LLE* z*?{R*4~%diFv3O225*TA5jwO8GvyE_3GQv58YT;S2QelJx zfe|iBM!14Xl+diKjc`#i!ttDFYCV*)^9{lFf3CT0go~09&XFh~wn_Bt86_he&!v`s zOSL334gw=wl#Fmil_+suFvDtI9^s;7gj=SBYH9A?Mz|;$;R-5ILhPY+F~UX32R}coqJH-@8*cUbEh|N2nY0?Y1j9KJD{yP^sf~> z4B~_O%N^fY*Fmng{m9tw&D-v}%M8a4S3=h-$Y#vnDPXDYfAwC6P_5fn-;Yq zyw~}ezs<(#BZo#RQNmr9Z2NCxtH;cz#yNy)opu_$dbGlpuUo+di;LTAr7Hh_w~EkY_O%V%X?#Ov+?iqABQSY0(aBrm{?k6v>4sW>T$t2 z?>K~No!ED#*(lw?A3N4D8>iGSgep-&=iOZHz)SOHV@UV!i%O_g{eH8|M(O$3QeCpK z_}i%kl_(+hyj*Vc{&{PwbDI`CB~(jngQ$1N4pxtgu36xzLwgQNr$r zJ+(u-e_v3E5@HW_aL>&K?zyLgYKd(S=vP(`^ee6n(^7d#$S45?}l&pxW%H5 zh=qp#JN8z){`j7{VJ-(hDoXt*jTFe5f!>m}NGWR2bJg_dK&)PSOl;*yl#q1^#;a>S z`!!;}TG?%~L#P(UF{^oLgqt{gN4pOXyk5D8q3fqm#lX)5wG^WhedVKR$U%D z!;vTh$&4qlFKdbl#omui1V+l;Z-4z zGxOQNiO@c*ie1j_v2JtQ~7@RZB~Vne&vEKA*ui zt6Rh>QKDD=L2Ij0PrR}Fem>i3;a#TYkp67ueH_4e~*h*qQvTU zKU!Nov%`(BF@5xMuNE?KD<5d>d~rxJahZ7g2`}&OcQ|BZ(EEdH9f=ZdynXIrw^&;> zU$N04RI7f!U41@Lmt1-^O7+Lor%P?sZ~Is!N-S-8pb^)6e=&&7r>?WM`lP`D4xw6- zsV32Fi?!95*E_{3QNqn4_nF!u;B0XG(KR_6_`3l5q8c8P)!e96fAYG3G$a z@J@btjU!P)y*`{bnBF~LZ+~^@T8B`rdk0=;HcD%sCtfd@jhFUZ9H~SJ_4;zTtG@1M zHeT=jkVB|em+sTe#s?3+j+NyJGmkVIPwjDaq!J~>{{YeA(v!@_)NrIjsFq~)LHx3) zm)SV+*;bKCln`$T#AWqPxBIc^)*T%}wXj0AdX!ekBWm>vI$-o!-uODMoy!s>)Q7_! z`UlRmdfZZfH-}KI0|(5uUn+S;!Hj;Tdp_X%f=ZMSdmhe5bt>7ozU6hE5~?Mo1u?2` zAG7hlQGa_XQ9{}c1iT5W2fPVi3DuHT2O(J*Cp#@!8Ac#|&d%^Ae7xmm)pS4cCLD

iN)9746Ugyv0H zWCGrVuM#D&4z{ri-UMvGo3OTmH{lSf<<=bDgtZmCi9jVv$XE#*@FvpCs3*BiXOD)K z5c_?45Azdmf^qe7n@BD-vy%hfgtZmC35SrZuCFCDZ^BkG@FpCI5|z_?SzE!IKt141 zSX;rH2=up9%dI)Q2^+8AO#~`Y0^Wp;CGaL-Lsl}(n53&0XD5%WK0v^m@DgvrSBb2H zd|BIpfHz@n1#coyLbYVQ0s`KI&Cc*90+lEst3eR(CTwOs@Fr|_hBpzY zLJJueXOCc?yF@go!udNR)8%obV>1#G44TwyLEiG;hK@dUz9o zN|gBV&kfeE;7y<&@FuLS;7vG$YPmIsH(_lBZz52M67RPA(fSp<3D|%)5hmUQcLG`l zi?hG%*vjN<;Y~z|H{nQ>aPzhBCakUCO*n*V!DomPZvv%)H&JSCIXcxA-g|8NL0-^B_t6x&Rx;gEHZWoMad2!N1_B) z8Ag;=8Q3psZH4`!4xw6@yR7D=6#%ki7Oh2=jPqbwq6F3w_J8<0s0Vhj#(V~`i`5}i z3$tC6cuOGQM_E)2eiY}yvP222CG7vDz0O$gnhmUXLyd)FC2Lw--AjBwv^90i=NxNl zN1_DQ+D4bx?Pg>0fbWa?TdJjb3Y;H&;7qFrd;?DXX zAIEIK$MIF7gk%Ijz>hK;1D}%~S@&M+5K@oulV@%+8~7?aZ0y$clKA>gTf9{-KNy|$<8+hYoA8d7 z)Ct5*w_Oysy>`5R&gZk}*QRaa5Na=%d+XQ}t#$j?yTKt;OWF!HzU|)ATDRt5gCdnE zA@>QyFLj&QQ+rN_BOOAuB)bHn#W%GqAJuO|gGePxNM;K}*JXD_XCbElUhWxZC#h=5 z9t{w(lf&7Qs)X*P$mP0WN6J6gb9XED+{vC2XAi8F7XEq9*-=ksWzNhw^^iR*nVqt8 zU&&d`pK8|EAv80lt&SZ15xZGdruX3MoYqwWzNn3frJUFH*L8^*XE^@jI~_u`wD;t4 z`~9!C^^%2OJni%nB{Z{@%RTw%dGS0vAA7Z3<`Al-eHu}NQwGN;-?qiO`JK0&-mb(2 zo368`VEHYzqg?KzoA!$jI&6!#-Na5jX<-tcw0Nm^KfAu`nNuS-|MC3fL*r9nr^T~yf@j&7znrY45;Y#2Z1os5b0^sN<;}C=cfBoMoA_IYP%ZZk$|<2( zPon7ElywPggqOF9-?(AC|L@Swu}YNCJBv30E#A@k?)G==?+~gb>mb;8apxUugxjs& zp0P@l&>S1)!NOa%hV%aZCsIPSWIYEP)jvLEYo9+Jd(+wTuY~3bai(G3@zG{v;&%Aq zN{3J_*%b&I#a7!zdv+Nc{BrtE&UphR^dvzpcjaC+;|;yHcyHWta;#^G^u&;?A7NwT zF5AccnDPEsXY^y7+GZS{I8s9IQ!aP&*Z;M(=!j1|hfpn92gAnP9ly8r?tS01Vf5Ta zGDhN+&{oHLKMsG??nj@e>NtdI$<9pJ7(eqKyB{A{e-Wuf3HJ`})Z~!pN8FFnA(s_2(luMtbH; zd>q*Ld-D6y@6*Qno9CYqt3(OCPZ+P-zhL)c+KgiyLbb%Ff{kldJa6~o#*rOkl_;V2 z3HM|5f6RA&zQL{zp<3b_!p5l$Cq;~9ES&sXq!K0cK4I5O(}vNPxF1jbG{YfOOT0eV z5P#4)^P_}#dLa6Dy)As^xUs=ommch#43a&Fr8faMWUZ3f4Z# ztbVJe$30EBvKEt9*uHNF^_1opnJ^(#yxu)?fv$488_ZqaA zePeV?_buL<^DlD<)pAQ!)%f~wNarn{f93f2(@E3pJm)(rXGeOrQzBuoacz?~!yT^~ z?^iCqoEi5tdgc&XKRi)`AGfI5zRS*V2-T8^9&CKw`fH2a^?a-k_W`6)K<8ws#I->D zaM|@C^XI!Pv%LmoLbW8$2x3m_dn~Hftj`YI&rm+Yr-Ve?K>X%630LF!7=P@1=hUBS z=_$dj(ZLzmYoHP(B<=?r5_{$Djr8<@v#Uc(i|=Oqaq&KHp;VO@FK|l5Q`qS~5D?`Z z9>`|gaZ!;mvTYx-ogC$wtCqGpO4Ytz!D6qo^UnRq5VH5M|D4k!0(o| zwD%wa`RYXldumso>GYBeA$vd0y=q>OPt>YSS2zTIx2&ao8e_?+vkQD`ui5PO_6%X? zx%m{>tmdb)nw;B?7WVqd<4I=DaPB^UZZn?r2f@ZyJ6#;BM2VqCEjGF|GStrB>vP@i z#TPh)YDwfCrD{3*M!$FRoU25M_Z!bL8>Nxq-AzON*T;_c2ktQ3+0UR_cphy(15T{N z#(;50``@0n#p}Lhw6j}82|4c$B6mn_pZDWGPmXd3)zX$my#3NO-j&yH@kZP}j(4zp z*OZX+^{}y^@%3IhUMZnkxaV>Q<>Y-Vr|r2evG(CvbgTw^M%7B^&#^A?({+hTl+Zhy z%l&8QTR!(Q3<`QUJ0MgGs{w!OzKkQcJnHlLxaYynT=kVDO6Xn_>|DNYj?ZUs`0l$n zglf6xIhQ?sq0i_1fqnjVc8e&XduDREN6)J7&+9xgX!HF|4xw6d7M;DM>unxa8E<2i zp%NwZj4IycJ+@xJ-hTX$-m&fq(RU7LtK*%r3+o0WuG->#d0>C1b(LuSbKd9kxX%^i zP%8KaLFyamZ>g5{1@q5?)IWc*cR%|r`sDgn1o%|eOG^6_;oSwPcc&61w0?+Roz&2> zmV-WMP5-?7TdE})Ow?n;r!@jbgl}!sDprXSy2}Q>+Ar^0FPV7qrbr3Zl1waYJb1?< z>m?^1@}YB9R|%~8eMZkqC%td{ski@Qn~}j+KaX+<)q-zex%<-lso_m{sW+h#CG?cB z`GdargZ5k8^D6HgaBSytZ(KgaU)f@0Q2p5;N1}w}yixPk_rGX0zx}Zn9746U4UwrH z{)@Hl!%uwTw5}48!G?{FZ#A?#xZig>J9kjEv@hV?-OhUljJNx98aus23CVfG#yQ^} zU{BP{HTyY)YH6QFFZr``z9g_oNm{Q z^&$>ueY&*MsZYZT&Bo#x&oQc2mMDP;i_xVRSDb`np4?mh2)y%@M^3(kPBf zlt4tsY?R_YO}7jTMobv*-|^|M&W3WclWnV7*#VH+z+P&;$>!|6o*6PE|ADw znNThF4*oJ?M6mwGE#Bw{=0ti2_1?&vVi0w{u*M};kB+xYj#Q$A>~sS0z!jr|#|Lil zHcmUiAyf-F3#$in7C3iz{$;@nh{=4=sx`A2Wr-5VQ&{~Ct?gN|G4P=~9YVFFv>=ej36eaHFYV*Wy>a%iS*|E(gIv*Hi}rW+ zswp9@4ja)GH4pU@)9746U_gLn~dI>T=PA^eHW(nUiKQ=NT z^WzYzrG45mKS7fDaeBKFGW);=GC%3cGLW^QFY~T1D*zD4{MhJ&%uk>aC1h*|fy|GM zKFItyglfsW0z&2w?i@(x4_^tHOF$s=6C{}*hfpnnV&!%wV>_3T`EdxLFm>4nIA97{5YkO$c?iH+A=@Z z6Os7|^tW{1v$ncreyq16^W(Ix61oT4GCy_)k@;~5)zaQ$nIAvN{5ZWt35l1Yt&sWg zlgy7psFwC=%l!CB=Ev#nN=O_QHjw$TxF|9|+$o#JSbd3d`bt~o$4@dp&Yo>0Bn}H3 z$o%+8=Eosa%Pkc$KWQX2kcg=-kyKwItgwO1kC$YA0+lGC^|Q>6oz6t&$01Zp;`^|H z%#WP_MdpWlw$ogJuLLqQcD4^^MnNF+<0Y9NhfpoaQ-DC`$4+M=^TWO8X=cP%0vVe0 z>?;Ule!L{}!~N}LLbc@Uo*>dwrpWyGDp5ktkAlFvCJV{CCLKaf>HIh?!h zHw>QZNHRp4-+>KeehNwE$Ei8$RMyf~x6Ds5$^1C2n<3JC8*Cu+Q%EvD4uRh-YiaMX z%ug}N{5ZWNL!_BT*g)o|kYs)w0>4|<(mrjOpJI~vae8}(Nb{etA^REl#@;Y_Z>=wR zU|;giAdvZqlFUz_5+x-23Ids*D9QXdglb7n7z8puQIh#_c9JV0*+ENDdkVGC!8vM&`#MR7+dhGCyIG`QaTb-!&yLuGsy+`-Ncx znV&RM?GUOZ***~R=HWng2ytCfzMEJLL`micgzQM+s;?|jLhr0)exfAv;}EKa)j+xr z2sV)UiIU6@SAAuP60&Ck1TsHSlKF86)slT6AdvZqlFW~@vtJ3>uK@y?pD4-vID~4+ z`(;5O^JDu;X{lSQP7?AmK-Vf;31DT&F$^1B_lKq0tnGMVQSk007aR@yn zqHSoIA8TD?ew@}-LQi>E=Ev?JGC$58R4wg2midX3%#YJclt8S;`WvzXXe(rX?1@6= z$01Zp`?O_#;w1Cq^mZi>1G1iv%nxiJn_)JP&0tK%tn)01?5*{cwrob6WHT5kDwkIY z#DL5OvKg=;`;Z+%wcJw4{#_r@8v89|k$gmP>>Ak~U-k&Y1~NZ!lKF8YN@)GCrk>v2 z?g!o=;1H@MyUJk$Zz-_d>es!zh9{(LY{x!!UkN>%WAC}M^9J|5dapyMmh6s)4ZKUw z`Yzt3$CKXnbn?`=5_-nS-aH)f&BN>KwsHv7k~cTOhP>0sd1s~)^0p=r^2RLtMl_#V zdaLsGEKf^oZyt`4HxE0dQbJBBAQp}{{8`Q4IdZ5&sFt=mzAN)@V{2W!;m>JZCFFzx zY~URb_SE7X5DuYQZok4iAgq_*9S}}0Q37#ldkRWtevs$1CklB^hfpo;(>UkV@IrfP zADZ!;)7zDh6AGvY@;I?%$?Tb6#tpd}yJlt#nIR7*|_fk2)!URug?`YKUEPFjJusKzB$j}Es?b_mtdyNNjUh!Js;uVrqc z+<%miGgz=8XRsVXwcK9P?!MyTy_Qah#}>PL^cuqv3qr5qbpJViuLjqA4>PZ~`>Z;| zS4Huh-?-`9&PRe6xa0_r{wuZa#g{MWv*K+-| zF5Ynm}}&n<2Bx|<}JmYBf&dq-}?3Trj1*d+1tOVb>0;^KIk! zj;aytE!InlNiPX`x|>>jyAIx#t(SyJF9~`6m|Ey1_6-eQa}7*Q5+tpc z@cZZNB}LBL)Z%x}SsGrmbSw=Cmd<(!zfI0wQsn$fExxm#HRd&XNyHkHKrac)U+88p zv9C^3i(kIrX+U11msqQkD1A2^y@X$#W-lr7EF!h|-h7^91t4NeapV{~}6~5IN zuRY%lt<53<%g?;8+{|CrKyX2*QP_vkUsc|MfjSA$7^*XTLldiaky4xw7o-$3kt?}y$&xaXfYn^#2du=4V2eAo2oX4eN#Z)sm>r)`cH znAO&<@yB*c9_Mm=f6f}B?}k!aZ4nSv9j2O%J%4z}lP4#VXCmUvMjPyr_@39C zbG?0Gpc1yBrxJcG7@oyE7AsMIDC6x)hEmH zAZmWS&SMWG!B*z?GI{;_&OIXj5(&0AJmK;71<4p+kaP&0IoShAa|}jS|Ni;>N@d)n z`gu#zxeGSx9W*7}3-xIK=wc5o>eD)(zace#vyybU zr&**cgIuo7%lL;>u;%+t~heJ#Vbw^c|SJo z6?-aCf+HSn@XqFPuhcjuJPxH=)!`+FP%WJwbGaUm-4`AO;_NLmykQtu`CG|M=JT$x zPsywe8+Y`)BlJ*@ZMPlksRX^QOz64`--bH=tY(e5C|#DYqc&^2l<_wo-PSgH0Nv)Cb23(t$$;8TX@{4eYZb?1($K!wJ7Tt8mrg z>Vj>>(KVO5f4`5z)@ZA{pPjT!B}#B@!j}HOh|Wr=me8m6Jd_L97*M18WCcE3mxmA@W4|@@#^r9J82Typ31jPRa0cE=XTjt6d&2XG|hE1y?J*F-CrQmSt8moZ2-LhF@g4f)<^$5x=ISY_d1N&& z*}(VQCH4|YR3-DA^J~*d%{xn6gublVpf4-W4SFKtaL=Z3IM$H9EMsr#YO$NFM)DhmLczV^{+5J~^e$|%qO1-u!QV|N zl-T^T+A43&40;!KI>B0;C!DxAV~pDB?8UBzB}~}gU~nJ3ziE_b5v(P*&P&c^4u`(> zN(rYf+TDk{@3dxjOzyp3N+ACITbscUUR%`j)nV|JK zyj5_6y`L{_q29`#{w&s_bvO`>4kmh!VePeZ(jyK_n2^W;DNR}Hy}8y`2`j=(uokTW zg6LJMijKm6tGmXUbF!^?HiYdn1)_kp1PVvCSCA8vs z%L+@yVpY87@KyusO}5^O30mbu8lSv1Nprqu|K9?W+-M-G>R9 zO@Qchx}TQdrk+zRg0*Na0-|!RNzQZlKJuNLuOmwNa-?@=!k*W@S$Mbi5Ujg*e0lL3 zsIA0rKCEt#XqS0J-7^ylX`JKOPn z{4=ng&fd}`Owf7&h)0%`G#O#tKZpDo=G>B}!R0p$h2A_=Mtu`&;lW}F6Xdf%c^v$H ztoIl` zt=b*FJIoR$?0oEzcc(MCN z{XQyYeAgmaOID8LE0B2>)~~P%B{MIqN?EI%Oz;{Y;sE{%o0a188q`&Msd4*|&&%OA z426!}^pb^HVi7mJXDE*rcYWk#f_0ytzbJtT^08TSDy(eJt!Gm4R{yQY9p>2<6LJTr zl%{xMEl*qm6Rah-i3%ZpT#S9bh^=xKdEkXKwh7xx*59NAWApRTZDanZ61(4)8GT&B z1gDMjkTDOG84KoxUoyd3wg+o)WV!d}xn%#LcdI9`gb6zzQ)e_ZufSGc{Owu12ywEqm3O*7SMh-&$$r6=OH(cjnjL7<+u2U`3C-*oOLA@x_z^qPfC9^z!7HjbvVoe6#eE9~&$ITKZXl#cxWMy7f z=&@4IBMTnS=~}+@QL%Mu@+h+3(IUw6hcsxk?AMHWFbJ*0t|quQz+W|Ev+*5WtB%~^=Sk#Dd! zB2!qx1g%UUjoQ6m*KhFSL9;D_wb=h@#TrsRc}un1bELK-2g<;yoHUJcGI zYw;W6`zW(jZ6&ijmM}ppg-9bu?K{<0Hy-=kB3R4LIj!$HEMbCHgpmfV4r&aa*h<=X zS{=M4qLEf0dF9R`Xf+aPV0NmulG!TfmbLf|v0E0AbMg&-x1y`V5+-Pk9BI&6xJ9s* zo%1z8q*JK(9)~4Nklz4l(5kbcbz{9-SnMXzru>H1%C^T6TBp7xCKdBpwUx|onV^;Q zTVlL0pH*AQ{FdLH3G&JyALL`P2-YGW3y6#ByM>>|y3ZZ+4q1_BOo%U7Mj0|Aw)_Sf zw<-3K2wd_Z+>&$hv9J%)BFHO)G~gFhAB*@2Ik&9EZ-^1u?za=9Udc?7B}|BCOXi$1 zU&IQ_11}`V_)2E0Ot6;xmYhr6Nhmb`>r82VVXMadk5~~YOmM7;<&QFKAM#B_`3

zT7OhpbF8Y>%GrRuOL{`ESXyS?BN0#JskVHyuzEZ`6>EKn!j%$~*i@FVb?tm$2AmdnE&m^p zo?AQawds=CkGzKUl2yq|J(lou?R=m-64J|q3D%MxM z&>e3DAEfnGOt1%AeUO@SncwnTu@=Pv;H@y9^~Aa|zhwy%c1-H=zDK+U_&%m&@-2e3 z?6{?sK{W2^pT2Wg!UV^_YFiQ(>%s>q-$&d&a*twqyTWgHbH@mLkh-5B@F+%^KpU*I zwA$KICv=5%;e+(}S**n|0oogc10SUBa*#A+mdAwbgpfCsodh>`rN9Si5v)bKRY1(F zQqfd_bw}3w#EKDSTXB??`XIFgW!B9SChUA*cIwIZA+uE`Sj&zi#|R)C_#i!&Fk$Bd zql|FigVa4FVk?>Dv6k#J5nIXV!`hFdJ5bUk7{jTS?7HBzF(4~eB^>x5t+!$VBQ=em zkXe)ZAT{SQ_vB}>7Dd*8z+BVF_aSpnmN0=igDd@q%(K)7X{7&v57Hu7i{gMl^gv{g zjCT61NXLiuzl|zWj#jgG}GMq`QEmJj5nUV4k3K?EGEK zCc=RaQbx#eE3y{m4ElGOXQ>Y|9QYtLa$nLA2@~Q^laiI0jI}??B3KJ^LnUNK3?cz@ zj8*I2QFMeA3COlWIcRy{Zy+!O))JH%F-w@R^8p{E))JXXGQnE*-VDrA!+{UdV+j*> zJ}?t@0w1Jdg0z7K%-mFjvGe`YCWG2ZGrfe&U zPXvM4sg|J3R$0OXzpeTpwU)>%j|tX7zo;z(dI+R}mDF(HgOrujxP%EiAMimsfe+Fm zSWDu3q%>t;nYBmJV+rk7)Tl;jm11uNA7nW2L8kFrF~PBT>Vq`WbIP2J3D$ylKwBS- zrtnsnqp5Xe&c+fZ?6^MoAhiVHgR}_NqNrK;aVWM{_5$d4AagS&>?l_F4V=ISDLeJl zisCDv-I<2pP<@c;`#C+9FadvyK1n<@>XiuxKFBmCSPQ-vtqT~dA|LQUI)M+;V+j+o zTTjYdW=htcQSto5pT$}?Cd3HYC1^zzC$LS}R+tBB3C28em^o?*%1n|aOmN!jgVb6g zv8hb3mc4%v-o9|)gG^%y6Lvn}gLDEPq(!inM1zX0V)=j%GMz|Z2@wvbjg!A_zEuKC zn4mWds}E9hE;BGDSc~iiLgGYad?kAoS;7Q;HxBlBE&NKq57}|S1Z#0jdMFg#w%2@s z{^RJ9->hhLCTIsA(x93crn=-%O%(rmdVNDa;Bil{?c!04OPHXq0BJ~^sI(>UL2}&< zvlhRh`XJR-GG}866Vx6fjV#BFDT=Q|5kwIyL{4IFA$ zZrSNg?JmbUTLiVPNJFC3#a0r#&ADYQena&^s;%II^jN|K^>9c7K1i)s@ImsvO^3B; zlmVjf&2fpf7k~*GuYiCLQhPP{Aj8y0In=93oQ&2UnOj*sC-*oOLA@vli7XXc$t;hb z#ajG^>Vs5U$qr+dFhOHGq(Ngi9=Gv$jz?-BXs?W6oA7gK4-E+TAk#-nVH)qaG+Mgl zlmhr5(??`ses?BlZ0D*EQf&nvB#*Bg*5WrrL_A_qrM;4QAxoH`IRny|8tg>MnmN%T zSc`TjfoODdx0AIOnF*Q?f`AV)eY_i{5vxmM-&@Xrpt%9>P_PJ^0U!<8_aXI4c0+J( zS&QFLeUNG^nSrr{37Ul=4b1BF8jDFjg6-$J1`l#q(gIZmuB?V z8*1co`l^9=6yv#Nf>sld4~cgbTfqk@UduSaTKtCUgVYr-nR~K?30l`e8WQg+YclXb zS_Es+?n4l?N734Y#RTn91VL*u4y~%Vv_2zo;hI0JynvwfEAc4CB}~vN6$tns)mHF9 z@|uiwP7S}I`XJR-GRtELKbKYtkp`_mS_Es^IZr>=;EVgdHY{O+)_0Kxtq#h51O4u# zji=Q?D^I!$B7FstSMDr=RwI#yM950Lf)A2c2dz_p_zl$uskVX-Qul<*H;8B?i=Z`f z$;ZvLaEo9qTJZ)!yMC>cDVX40d)BJ6L+i#atvXw8Xsv9A*(OZTiZ|X$Vrs=!@ImrA zwROf4zadWYL`&}MUW>2X~^D0v6bxDk8;U_b<3$- z@F=R6O!g1*yE7qa$O;QQibzAEaK%=L%9Yc2;wOBu7Qdl-`_x}M5ohqQgbCO%eRn_7 zkTVmcUcsYi5v)a?Y7m!h`nIKBrTeg5CdeBO0ynINkG4(pA1YqYl{b-Db+Fem-M6Wy zX&*_RZTg4Cfe6m>_9p~qc?%&kNv?@RXHB~AR891cHaqC>c$Y`|ICoNsI&<#C?@au>|)n`K3?Rad;-oYXEWwlMrpL4F!Q( zVir7;D7D1$JN2u~!Jx5~P7z5)EpJ6+6grmU6PL5U3>}f)h!lmS{AXyt}OY zqn2nIvW_pOlL~=a0wOq(RBDNOC54ccc+?UlWQ|=;BozX+1O#eH6gOu{EwRoyLoHE4 zR#oNXP$5uDjMkFqA2}1Hme}W<-Q2-p?s{sp5~w90?s==N-18GnF+E+mC+xXilTDqS z!yUPoEZ^7>rrNTRdRvwRAj-Df&t|ccL%X5X6^RVUba)Nd!R6bN7>i4{EmcEe~ zku%#xA}71ciSP1zS9GG>@?eC<4a6XV8;A{VAdbjA7NUjQjP>3OBAlB)?_ll&`ax0De9XADo2yTNi zex#A!=Oq%!q1+55zwd9+!<9RKgifn0=UE0fNSg9bW{JoxQ=%p36U!Y{@;fLGC1T|f z+?{D~cc$J;CeM=EAa{`of!j76xuZ&c%c;kDBB|WGXmInQD|hvY1n0f#-GK62Y6;gd z#2OUo9SQ1{-UlgKa-*l*4HyuH2-Mx+J};?PzTDv@T5=mDI~0D>s=5EjR4SjbrjVcF$;VTbk4>y_qy!i)qv=C17==fqLZz^~#r}S5e#>F7?W1EvDsG0U_iDYOPoPwISD~UitLpMCGh|(L%k7%IWVxy#j%H z<>O{jsaL+7Vl7&7%PD>5QXWdkjivE(gr#0Z``q+U16W_Gp+*0R6a;64_!4`)crO)Zjox6EU$)_~g>)T_7lnLfj=8@cnITO8^W zqjDpPJgIP@$#|>a<`d(-*WYIe6LRy3GYsvjMH;LdjsPr_# z>8Z08x32L!s?3aw@A%x-QcoR~TdmS9g0WBRjw-bkOPHYE8TrU@a)I2nWmYwM%V&bM zsBZ^B{kczlc$BrMKL>$ZV%+pHXNlY_m|inbdtAv!yk5!e^6B*|E@47$78E*mAN|Bv z?ug`k;<~B%OADVRG-im>m;rA^qYR%VOxXQkaHD7XSF3L&-!u2G+-rwI&t~c%cW0Wl zegCoga2liN9odp|X=CDdXKL#s_i(05n4ob9h~DkG%6+M3?DyYU&tfea)x_Gw$nZMX z)7wN%Lv9pjEx9RJtSjRcyj7&H+;VJi%dy@%EfS1(42^^2e0qISyvLC{q|Iu!IS!l}H2qMaDs`1~Oxz?*jz-k4Vse=q;|I zC1Z8^9`)8xu?W6%5Wzj8@}0|FLYhO7FhSou2=pK6ZHYy&7PT=T(0{nN&r8}wy|+(N zNB?2XQmB0df&Rk@`i}^;yLxY*gEgAuU2yPjZF@xR{CuJZrMH(~c ztyc1+c)jw2{zGa>G+n|3jZu&W`VT+oKO!ulaga-M0}$vx(q|KT*OsIqvr#5!d<7!7 zgGc%g`3Ci^n*I3j+OzAM_vAvsjBp$gwuj5Bd*j6Ez<)cV;abUrU=9>FWpmhf8C1hvo(j%`!j) zx2s71;j)AYn!SJsZdZ~1!+I8L@tjK2NbjRu>Sg4uv~`x*J@slx1NWFjf?1Kgm9|&t z?<|65^dNfW?ij)Cbm3GJ>6o0u2Owya)3C$w5i-W?LW1)w967EcwGx$?YpHT zxS!L1^@Z;pCRppA`eR*LRoi=#8WLMD2;p=&AHsjCONkV)}oRH(IZPsx!cKKU-W$$O=!K6(F7BDT29n7Vk3aO zi#uyR#^;UQk0alK5Uj;>>QE>$uBGN<$Wy1oEMbDugROGc%n`v&fBtKO<{PrEA&VMX zr$#=mFU+aLvXi5{mm}lU?()7&tZ^nHgVOi-Rs9uK@#R%`n!4NixdU@f*fA^{(Yl}Ee0VTUD5kfo6Zz9_lX z%J2Td_l9dYw4%XRWYtPd!F9V-vyL(@P$JgRYqwYXMlz0x#Lufi;0 zg3?1iP_O);UO7y#7NrdWwO!LdZFgA01g*D&2=3a7Hu>ZmYmJ0@AFGWCg@XIMqPWk? zk}x56dr3=l{ls>I)7U38)UWpQI|o<HCMX|Bqr<6en)4f9 z9kI%swa5w}`hGb(x@<=e|GhIWOKT9X8BD;NrJjvgly{ajjiPgNC;A^>-sLgDTJU=+ z5sTRl?$nD;`|(1QdVOovk?n@M8@p34iaYhJ^($VdlsnwSy0|$n8o!av$Bk?j!CGv$ z_^ogL#LxRhS;B6t1{YIfsv#07t zrx#E3s~4?r5v;}M{={!yjJ}XPzqN8lqch9WSl=C0TYI%9AIs#kMVXL$0>!%T{Z|^+ zl^YAC=Nz(SpY<%(V!L7GcV0ei8E|7^lqF2qezoAY&V>Be{O=@4d~a( zm?6p%CfJV$Z$|$*(e~vM{rnY1TRuA0;*)~ncV|X%cc#y)j=UPlc8lN78Fi-=wN^Qq zkh?m?x&xQEusANN681Z%O~ z;`c%NxDPVQ5+>NMiXDfKRg3;wEz!@I@|oo`Wi5E(wPlFyb_(vujo#>%V0klWmJ(&V zg+ja9-l26DcjQ_t!c54WtYY1F*F6L4KD6r&wQiN)3s?kevE8um?(OqY={c8udNj%s zCTzd+!JG%>&Pl)HsE;jzwb*W<(7FKwqU#Fw^tbMK)bdC(!G3N;4je5Vjnql>)0`uQ zpT$~y8WEzxaFa6bKaW1~N;7LMoMw}^_=>L8zaEt_b>DC5_-s)osze* z=34`h#h%-Egi! z?0#qe#9zIwhz%w<4g~R61u{opXp-n}>73spSWEW2O7ul+pKx&Jebn*0`?L-dr4=2^ z(xK2SGe_%g&l{~R?<*5>v$h%-7rqvQZ-t;W>3HQ{-IU`4HF!f6AHaw^xtoMpGB~i^k!mR>D{m+_rYvYX?Mqb*4y&ku~&}mhSul7vqsw8 z@Q)pRmN3ycTMM=Bqj|?8jgbxRSL-ghx2Z+27TXPTgLb8~SKGPp9-k#l*l}c)c2(25 zdvIJPo1kbjwp%FlMeF^hdflG>)uNN5EaB&J+!|t1D^4`eJ)P(``{hB4U@bm}3A;Ix z=7z<(+phNUX{A}bq3NsHw|GW}?|99VRh;&_J6oPnCSJKZ!jqO^cixGxZjKStjkLSn zwzaSb)?&Ni1hWPo8EJQqJzU0T2@`f)-;q2&8yPdaxHX$auol}5yHbjeGru(G=@)4@ z-HP~Qg5wBb-3Oj9pSDf(N8FuY5v)abHX!Fii|uss4C)^(x9lA&P6o9y9vj1U!~IcR z*EmvlE2ec4TgA(O30NU~)4KZ`P7Xf|>o#84(jr)k?S^RFYPmhN?&PvQOPFY1YM3YM z8i>Y4K0evq$Vkg@xMEI=U@f*=DD+Ck{3hC{r(g7iSylul6Nr0GzfBZryt?hYck)@p z^&N{?1Z(m6PF7TL6weK(zc0m8>$ynMmc-6mDqW(rE46)muO62Foc-Kv=}@TV^+#PP zkFGP@OUn>1H6~C)9Vw4kTk>0_UmdCKO;$Iz2-adtheBt14Rd6KTrjPSST|m_OmO}} zp+VDL3rlU!{IQltoM0`sG;TP$r|6>ZruXp6zCK@U6)#&RC^8%6ftYPCh}pIX*5b0U zVz#9O9Vriqx}})yC`HO6jmjn0xN}e*Nlm-@94)|61Z-)H8TO8MrS*AkSQ{%kfr+MN zKhpAu^_*YrZtY5W+<&==MX(lI8u@6R&z0}vt;MCJEs2*c6P!QXGg@huBjr)Dc@B$U zEw(iF%DBax-6)U#t>#&EmkHZeEB|g0{tKud_yLH|Y?eai* zU=;3NO6i|I3U>m(n#B0%%B{p=u%+R_sRJSAv86+ygmZ1RJZ5$);j@GZ&L8&5w8-m9c^tbVt3|LDTN>*=wWc_GQ64Y;r|ng| z?lNK9YW>AL&SAu!|5j1kt2n`0T=NkFS@#3y%hrkhcZejXeFfH;PP7jJ<#DQD_K1U+ zyAz#SS}`mfox+w5g~tARPRpamQAg%D@ls;~BWG9ItJth)(B`kSJVy3>$Rb#aEsZ{E z_ZU~&tFQ7G@>#+J=MU$2O>3&<@m|gh7QtF1^1J)q?gTLYM#=d_l`hriut5v;|QMtMB4O23chpXZc$RJ?4N z;QS#9>5jo#9*c)ulzCK~U@f*ZR?kb^;r@d1`25dtR^4TSb|S*McW0U9gfY^uP_BkW zuomsK0YQ6ZWagz_GTH4wdu6Qiw&3C2`%pyskGlqx_bF~AiZw*7`4Wr8mJWr6T`#5n zsPb1!%KDXRNemzWYGEJGDHT7s_Q3ti_hb4D$8US{`KzpNO)A3CfJ1K(;iz`Uf7>@;Lp-Z{nNK@{l-ojy%K~xt2%Fn=$FRN?IOy z-Z^Ixti_hbxj3I?RNwaH!dqp1H(s_(aQ;G}?B9H=<&oj9FD!z!*wUfU{mtHRbIs`C zJF7ccb(aa-Ru6W{?iRqB<)|`wEP}PT=3BeyWDQx%L-s+@F1je~u0wfzw(6yb%s=j} zoED`RL4%kXwY0=svZaxaE6ub#mi+vMRR&DJBcwKr`R+cfQd`R-$KWj%!CGu-oFe#k zo{044#h+g+-i&zJGQs%^h5G;ala|Lf%V%2zYq6y<6Mk;6dl$;%iP!4Mig3K{GGW`Q zOxI%We-9`6-?qDI)ppk6ns4n<6px9fA-l}rkJ9!^cAwGSMU+SC2d_mc5A7d){`f>| zKMqCKSY-o`Nvo%|JlfAr`?}Y-yYWxox!j0Lr8Bz|!I|iPv2wY+JqmetGvx z_@j27*kjdp*5aCP?Ep2j(^KwB(ejYJeY7(a{_~7a_0;&1hW9*bMHN%*$1VG#25fjP zavJl&kau5{%YX@rdO{i}8#K}K$n@}Y7QtFAl(;{PgQ3!xAR!XsUaD%c9n8`A7aJ6RgE{!-*$pGu$q)?%vRsR!wArb{r!g|F#Ib z^V*VjLlX?~a` zOz=r_Xs@cwcc&pA=GZ8UU@eYk3Wd5RKjyxQG*%UzJT@;z*-@;ri|=>=Q17eZu@K*5cCCxF!8Q5VvH-=2MUCQk(B++>(ADh+DEGOi+sf z0&z?FeIRbhB3O&+Gzi2k>Gy%SC2RLG6O=y?h+ER{193|ZKZ~`foIoIM$qnL`9F{Oa zb_0R9B{zs$vT7o0QQ3e%+)|`Ra({_ilGtONJ4@^_jWS)fo5n4vbrH8@NtmGi(bc#m zwJze8EP}PzZW_0wZ9C$YT$V6FZ3*&$xFxkN;+8Cewb*VNx8w$KOAbqzptb~QAa2PG z;+8CewW#ib`0UhUT6Yn*WbGKCIhAE;ja$;0FyfXXY*8j?GzjY=Zb_|+xFzdZti^WI zxFxkN;+9;NFhRW?(m>pjj${zGWD%^zcGI{eH;7wuS;7SMgRm9imfRq2$zg)Es22tC z!pZ7tUBoR#cux$iAh>Kdja$;Xi?}6;?ALx!BKw)3xes!VxFxkN;+Cvuu@>7+)+xB5uiL2@^DvK^ll# zQtKja$s$;b?WS={ZVW z;+Av`8F5PywkQ*{u7xxZx1`oZ+>%AG7TZnZmUK-9aZ4^sn4lRw(m>pjS{HFk7QtF< zH;r3zx8BoJ;+9;NFhMhVq=C34H;7xZ2-c$Y01)Ick)25C9ut?mB)9Bv8`Eu9%!3ta z9AS$xL2I%|193~bB8<2ti(oCbo5n4vbrH7|VF?qoeuXp;x1`oZ+>*-#Yq8xlZpl4+ zUr&i!a#_LztzRJx#4Wi&+>%AG7Oj4PK-`l02NAavq5a1$`2;OXYuu97UBoR}r;#v0 zJ`1FQxFuKo=ZIUf2-ae|Y21=p7ja7wmM}r9wMYYTOKM%jExAmv7TZnZmfRq2$z=%> zv|5Wa5Vzz6aZ47#TC~;+0&z=j5VvHV^+JAb%hDRRq}D~;lC^V^3G&b(4a6;J-9_Az zMX(mzP2-l-x`%AG7Wwf& zAa2PE;+7)3-xaos?}KH#g+hp13I}mZ5tcAP(HBSqaZ4J>fw(1$U@f+r#w|HP+){)k zOpxChX&`P%BL@(-WD%^zcGI{eCx}~eS;7SQoyEEjJmCa!OBTUepj7sM@D1Z%O~G;S#z#4SZw!URQG zAPvMVIYHc#MX(mzP2-lFAa2QJ2@@1$fiw`e6b|B+EP}NtMgs(*kTjwZQApMKVD zB$cWxxdLn+c+jkOrcVH0BObNEX3bY&VTUGC>rQ*eYI9Ou!21kwZuW zQAl18g=7(|#dbs8EjVbcSoe>vvt5=jK`}*0qf6E+374Kt^z+_X&mvfhB9cJRnSfFr zCWu0klOxm51av8m3647;t_=u4Wf{&J?>0UR4CFw6jC&ZLb3?f zVoPfjQZ$G{l9nM}woGvTGzv*$AQ6RR5v;|Q)+i(sL?MZF<7LZ)Z7W0}c|jDCMX(l^ zjYc7*pSb8!1g4z7n||V=OHq@s73~GEcK2hn9F^8bcJ#BQH3~_;4@4nZCkQY>5zR;g zQAk=Ih(fXm)?!O*6q1$)qL3miVS@9gQAp7s3dtf^i!H5DNG6Cvvg$4qwyh9_WP&Ip zi(oCT`5J{}f+!@HqKaLLz;-D{7`8$bk{?7NStlXTo|aoqTR;?&mItDcWX2LNH6}0) zjs{UkNCQzwS{{f(vIy2h+10C zfn-Z#w!JKmFZ~CikgSs_n4sM%NCQzwS{{f(vIy2?qw3`cQAPUJ3qL3_t zwb;@cg{0+yC?uC9OmO}*3Q5ZYQAifST5M^JLW%}aNLJlt!nPHnkW3JTWD%^zHD9BU zq9q?q)bo&O=ak$Yp=BWVO<>hPe`B{3Y=tN!KZruI&SJ$Xw^~}x`(#UN6q0@)h(eOp z+IXokfi*y_p@>348i+#D@<0@lMX(lITBDG(JP?KCvV;lFpGF~Rc_0eOB3O$ptx-tP zAPUK&Co61)C?ws*8gjQAk=Ih(Z!C za$Ld$ox%VQ7NU@}JP?Is5v;|Q)+i(`4@4n}CoW#LOmO}*3Q5ZYQAifST5M^JLW%}a zNaFv9*Ig!TTOkT58bl#kwVk!N=36I>J9Msr+?J+gfG8w~PAPz`5QU_t=^_frI-3gd zENW>v--#_93Ly%~52BDV(I5&*ynXSy%Y zNG23Q6jC&ZLXzm6xP*y5<45b0V&@bg3Mm>yAz1`#@d-p4g%k~AfSSi%G%VANJP z-v?yAz1`#acPQ$`z=C?;%|MqPlaNcpLX9Um?F^QSS$GLAw5px7J|}9xDBDSzEuU}BZ7P^VlDce7Ch-T1WW!0k*4`5 zi+pH0tQGuLyU~+wAy{%7LTSmz03UrD(pXvcHfiX)GksfvOYl|#)~(P;?hQe|UZszp z6JO}GsZ-5~iw&ZEa${zX-?=wB>AxNM9SUW5Y>pD!@9pUaS}I{8+tPtTI~@*(p}Vue zd?lvO>*2HHHiU^0W20-8Xw~5jiwJ1ddgs-Zn#PjpHK3b#?pr1LR_yMx z{T{Li)(U<*F(Ndrp%Sy!m-bo0MBDo+Xd1^~KWGqB)TD(Ho2M4F2-XUInZqQYUr^g(!h=5kD35RQI8ehLU z2Wgx*_KFhO=kJNKf zc&N7$U9wHEh=5kDy`x0i7lub!avQ?Lh?BeeDlsx!bBhRQ)jCqP zk*3k@&{Et2ezjhIC31Bx9Aya;{cb2>y8JO1#Hq7MN;KQJ)-b_Z!EYxp^kLejwf&P0U&2f=>_L2u;{k*=lBrMCq^Id@q?ZxtphI2eTo)*X?pxka#6@Y_Lo zfS?j|S;7R>9uQPZT$bF1kQxJmYNAC@Epg~80O1FUsTTddn|%# zyF*_yi1e@a*)fM)mfVJrFBk;13>HCOtwU`L2x@&Ix6#5~$p>#CsD+F0v#9lPsC{(N z4cu%+ErPYEbp=5!b%Z5MP&*HTdIO7KE$SseTnKuc^Btauu!ITfuRu_*W)ZAKy&VYZ zIU_7#f_iNb)H_F5avMVWU=TC{un6kUT^fCWpixGICAT4D!~tSgFp`-zuZKm@D8mg# zH8LgwL8GMzOKwBRSPKM=$SfkDRVx^&IT)#dNb{eK$|$2kxxNvW+=h^`9f+PzekCUL z=x-4;0(6@;o#;tli}nmemSuk$N#kQDDZ-N55Ym!^sQW>Z5{(BYTSPzyS_8^S8nJsV z>wWMa`h-xZ?Xlzt#=ddMZHV9|Ob}>&|34AXss%cHGaq;>eC=5OiM)?EL{NfpB6zN9p)~dH@mit;#_du| z;*#4CLA^pvR0896iwJ1dLao#%#cDgo?Mh(WF10-_xeXC~ANZn_z_{Ha0$R23b?KAh zU#$`tx64->m)wR3zH_t;N?_b>5dp1QXeIPX7?DF4t&b8Ix2F@VC8KcHCeXs62I{z7 z+N=1pg5OG@eU!f&jKcABjN6sKxZNUHEBGzrb`WT(mB6@NT2W0yBut>4cO?ys!a<-n zPy*w2i(swbw~X5*&(j(zfpNR^2J$SGFoFI`(~urc$L&gB+-?!975tWQI|%fgN?_bB zy_%*G^p^4GN?A+V@!nYpjN7Gmj!QU=;O{|yjuC(o7`IylYhg5?Pl}H+l)$)MMj3I* zZHQo8f^oYN7`IzQK&uu;HTop^0(7*b1jg+$T8c|b1jL4M0xZNTGTD34b(ff2HdMMa|H&)~O=io??0%HJ^xkBvo@z$jcsmT?Iab{ZIqDiMrD;{W8fJ$l4OU75^P86CYfU5f6089VQ}y z3HptkFOSBEBYSE)|AR<>QktY63O$k-Bfe}lD4kFVKR5Ut%qA!w*0WeENL!wSbsx${ zdJa{>1pP)2Nck}QEY_m@Aq~n$I*~xum3Nofl9ZFw7^Fe<%CLmfpxOfhbDZ>g6=j08 zsQiu2ankFR%pf&&)DrD6gZk=G?Eyjc$|6{czBCZ@MMYV18$xHr)>ms0R9_9X7)S$i z9L)#jI8m0|hS1r)&T*8$9LFN4WzZf-$|Jrqp#1;C=R=_% z-cGVswwa(=h7w(rSUDrvB5bYrJRwFnl7!7yNeQ_YXZ|f3G@eKHB!M ziLJxc%DBT}$!!QHMhrd}TkEU$WM-F%;J0cme6Ome{rs52NaMT1{gC5ODEa$)T$V8L zZms);aI#O%iIQk=BTY9&G=-7vn1M$kl{;|X&Zqn$TDGld;5NVV)@=<7B?5zsa zZf}(!rIAi(X@)|zw#JA;|5QvTRKi5?TSo@=TX8wFR`9l{vHv6IDzS)I&Ls_uuPEn+ zpG8Chr5(2NVOT5pt>s}8WUKTNl$={7NY+If^nF+aYf-HPLEndA$!!RO?*jyVA5kWP z->MaS1rELs5cGXSS;7R>U0D8|6|verqgH}Nuol&P5LLZp-j0*We$kHydwr_j>ApUB zis^p+g5wX(sWp6AtwTB3P?p<`Qnl=2Ohe)3<`y5&hk3 zd?49>^Pd?WOPE-cqp(}+>}2y|sZAgzj>u|;e4Xs~UHqxX5+?RvEvRpG=Hdnr!;j`Q z4L2wIJ4*W&!CK$t%jc%OHrZ@ixE@4_4kOKXd6WH%dE1%_?;myU$vNH(EWN_Xx%78u z*Wcq!oi3}Lk6Rvd?k+msjQMy4h?9ffGKZc>_P?!C&6F*7!+C7-MDz6AFPzMEuQ_#| zpJ>|e{M^ZK?W%Lf!xPPxQlEp!UH2XH&SS~`>tEM2EMemBmY1Bbew<)dZTl3&qv2sD zYsqB4QlypP)cLKR>vY!n`{@a$(#AC)-W)W$<%YLi9MF*HR4=4M5esc{=n8^J7MW@6M6HL81l8=%7`{`;Fs#A>W9gGubSsAg0*rK&FNk}ImvvpE(&6%sbfZCyl}^r8y-uT z`09?FZqkWKX3ZucKIrP0mp@4Mm;9K~Fu_{OPvmfq{5;7NSRlmyry80|srb%c&tX`? zMB9Q{+-|KWnKFmcKvdk;-1Hoh?7#m~ev4qO^J$sg#~V#DQ|Ae>|F>sMl|IRSp`*nN zOPJXDR367kbXT@^-SHJg}riu+~ErGP*s_O*DVqD@57E&ZhFK$^PNz zOBt3h@%YpX?#D+an)~*C31an#m(0c&lKmVP%31_#@t21EIH|7~w^Ooz%11Xk*%pj3%jPda8duLvFy6i-|Hj0Ah9yjx@K$Hx9b?VjxaA9lHVoV9ZCaP?yU!LjHTtY~3cfhmB&^BnN*gQVQu!`x^xNQ6|8%lB z_E15Lblbf0y;pf{vVZW4l7=O_qwAfWZ%sA_9?9qOlR}|(FaP4TTY)q(RJ77yVt9si z&gW$(o68Qq-jI9bl=sR<$$t2F6^mf4-Vd*Hdfz|Ulo>0;rpYbS_Wzgcr%hjwCOxL~ zoYEgkpC`Yir~CH(ZO#*&rIXspyF*aji?Q7Gf-vF`Z{kdKNq;a|96pLW3!QWn0OUwVb_c3b$Zy(Ya zv!#H?5+)90$)#z?|A^n+GRaFq8h5muV-c(+?=Ph(ZygG4`!~C{5@|GTdY8u%CglCa zZjvre1X?xP%O_)ovL9IlYsuI|(hyrB4e!4+$;bNc_j)X0g3Bos>hxo>w;O3pd}^gd zuol4?ll|VCMtUq^!Y=d1-Di2=Mwzn)an zaE;@dxZ`Tnx%0v#Q}uPp`5$lm=gpp(?C;+Guwe-kYthrpN00M+5g}eJpV7QE6(u+z zY!R&0Yje~&2O@7_A^!X_leuq7vVZ+O*RX_%HVvXq+wUfsN9yJPG3{J7lW$zIe{5cT zi(st+r#xrh$VsNy3Ar8k@xODMu_KcG-?uzwSi;1E!#t-U-jGEa5LB*Z<%&5n1H{pyw58rCYeeXTR1$Rty?Nha4O{ux%vTz!|L}NadueRLz%BC** zkFG^tH!NWyq1ETk@AW5|?6dy?kz-PIlhO)he&%h9V6DIX&zvQ9;}({gS3vapskZr} zA=;}h?;4gc(P6@;&R4r9n9n}E2%_$(1oNts?El=NzeTXtud6F*GzLzGLgN4P5`o;1FrdQQuKmXT*EP}O8eYD0Y(`thGB>Pzq zl{z;u)hZ_YbKV|eSi;2R`Kz7A*(aFngZ=>FuYTM_%A!r|In=O(iStjbc2-;%Z<-GM z9mHc}TbcHECi`EX7-kWyRethHC$-mjbFJ6UAlmGD(i|+5>@Rv~gkcF2?LS}XTuT~n zLYIVS_+DF+Ef3nntfMS~wHl9E;rv)}yqR+LM-Y1swll?YAdO!}8I~}yuhq$^U4=7>i)7BUP3j;%eireB}~k9K61VrH`ZMJ^c$q{*z<22|3s2scfxp!V67Lw zTjFegbF5kO@Yf&)R(QwkIhy3Z@WBMb5++*BUhFI=FxJd0FZ0@qk$27MLrH#yt2V(} z%jYk4Iu#si{;48F!^wTk`u$1%@@FR+mN1d^-$l;GBV$a)KV&96`{hKl0wc>e`b;#e z_2|__&Jk#pIK9cSiCkU#nNB|>`75SPG%R7F@~%Zr-tWeks~shcsyX_b@q3f}KFe%^ zwXXGEa;lFVW7<#o3Pkxf$>y`&Nq&dZ zHo;nDfBewNICPBZTSAEOFAXpkF$&+93oSoMm^kskhfdL!W6W1OWp=mgI}kgQ{6Qsb zg0-4A`OumD)EM(o;dLO!yqjv4tWUy{L8>XaWx8`AONzNa>kNlS{bzSicV^~DG0UsY z01Euk1}WzHr$SWpN1LG_UOjFTtaa|^8P2kf zDQ4yV*&v>)KgxXUC;1f@k2jCip6%2xKHA8)(YEz$=jy$qO=7jh&X(V2In6SRHmi1g z2;#>4(dH$j@j=e9hM#-t;0))R_9^D%7qcBZjq!a(o7y1GK0em4go$U$&vZKVOflc5 zNi63}PmMN3L2P-?CRl55)0s}8#`z$Ik4Q1| zKrHNO6Rh>&owJ-mc=DZ@7l7FRWQv&p;?HH{3`>~E)@GJ-dmb2toiutwcLJ*h!9c4y>D3^7-VF?pGX3uig{+?nwZWp5S=24o)!G~;uwd`6_ zeC{YS9%)Q`cD!K;6G#4-<@7_nYWR)RtJB>^nOPtX54Q={;u;zX<=^wZsjxB0ul2)3 z)2RGBr*F1Y^VjdIoX7on&W8`Bn%~Z^abCJK&nfpD{FP7g%y>Vr+%_9XwW zhLa3Sn3z9dfz$TuR5SfiS@C-1@4=?VHneaNn_w+F=YtmwF$cCJ`4ehQGAv>wRVHXllP+Q6(hGB(vG0yHUtyGnUM<5&^QyF0Lu`VzvJao*)E+Y0>}|Ic zM63QI%mENhc46#K5+=6)GskJRc(h45z6``8g-4jW=nW2K!pw>Y)~fK#Txa*D(dGrL z+=oK1%^z;of;fj2c$P3Rd)!>7!2Z$Zso#WHaMy6t;j1M7`0F;oTKpBD=Ug|;>;=(a zto?m3(W~M-=McV|yU(mb8r^FRGm|%r0{ zMX=V?y?40cG3m8oA&Ayf7pTYNY?s<$mM~HCkwUI`Ob(7)1mftMbJSxp_rgOK!CI?B zMP2dZELge*M5y2_^_bLI_;8rDj%_O9ikIZgb*nv_xbMnT^_Zk2)CseMi6f=Yn6DoWvxJFLi6va|Y}M|u1w@;X zV|Desa7&wDt?2p^uB^9LPT30LuKfGdqgZa_m<0CfKmSfd*C~^tH4H}-;O@*ujn!+} zvDno|Si(f($LcG6&mEs3jZ+u)sb{q6<<}FKU@h{*f|xvbwE7LMbblz!@5}iZ`OIDF zn>aLZCy3wQ9i_gBJ6F^WvxJFU`|eWz$Cw@8fq1asaP@!8f2@{8uvXVIcdL(Ocb^|X zEH67$eJtyCJs4&Q6OkIF)Q=M>Cvh3Wy9`o4PM>BqEP}P#3@)XYyF|}>braN@v9(?eD;L;?z((^SC}PCoSt1tJ-jEj zWHj)^jc%m=!SdsaS_EsomHj^TF4mlx3B;2R)>a?ng!*~IEMbED^&r+wt*CzIUE8vR zS;EBFLe4V}3ItGMF%saP_H zgBktUIz~J{HJa!5SW;_CC09H@RqxK^@RP9alhW9T=jX4g#jG@#IGwwKE1sW>b^i$? z)?i+9Bc7iw-Ah;mYxQVX!4=O>|9AccQEa|+^YcN5yA!z0AUZu3%SbF1&Q+_}N$FzQgVoE$FKKEkn)v7<<1o8T#N7VDv ze%nhH!CD+^gwAtrbM^c<_hK4IT%`V>Uisz^3H_DcD#q)Ef?RKP*r|~HD z{QUfGZHr*7c4;MC@%-HV)>aVj%^a(qpRtjLJ(e)h_|@XBczz0Wj)G`)d4hU=D(<;Cm@A$ix9M6C+u!>@JwF#7t>dwTiAAf5xZ?Sl)^#`AF>G6%CYs&ewHXCm@%&UNG6O`Z zy-U>dGkt#zi(svN2lBe&`6=_$7!Wo7_*gwZZ`}QW#}X#?7tH61=cn1(u^>w9Tdtm; zu9d1<1Zy33^0?ypY5Lu85c`|1RL@W8XR3HCVPeqS3E!Wv=L(R_BHDHDfV^+i(swa=jL+7 z^D}+jKoDiNeWIS9nV*#NSi;2d|8ltE`8g5k4I*^lGxhxZIPG4GV6A`t%;t*cXHVW2 zKsa}Nsh*!)`S0>rD_ieuu6TaFINvdB6Prh-sprSpT*PAu6Ln8zcE$5^|A$SG#;|Li zdVVf-FK7|0Rn5)pisxtP%z7Zsz38jwC$u`J#}Xz+bjj$7=ciJ;8X!)+yiPqo&Tm;Q zg0&pR&(@mW6v#qRQ;U>iKE8K0_URgA2E*=cibn^A^EcFYGw1o}UbzYJlkX(Khw` zEGS(3OO`Ov_~2pn{QNw(9*7w$x2fmn)j#T41Zzz#c|<)wRkjQTQT>x`>iKCoy#1Ff zVdDA1N7VCEbNxUNWz)8)=VyKE_br08cD{Z@JwMwzt_JbQx^3$DIs4@YU$TUW4@MnP z&(ET{Ux8@5W1D(@^0fKNB3LUS|55e)oY|b^5u985-8S|7Y};}0OO`P4ZHA-j`3bGh z0AlBnZR+`{v?0q{CRl6H>Z9uUY2UF1h^K$urkiOxtc_@h7_itCvPtoQT(tdV+Q_s)kS@jaSPy9_iKb;meNto91 zSM~fn|w z6X(_Q^U%z%66W7Hub!W_3%5$n@7$`MpHJ@pD2*jdRLlIgdVad+{u#ucJe$<>Q}Mvj zG;Wc(r5>C5uX=tyJCFk{^`~!aQqRx#pB_kK2@`#0{G*iHSca+F1|7JmiUE0c4ZdVX488f$$YOze5@oO*ud zzO))?Jho-4dVYFmpK1}T#otOObh+}Hw3>*N{cvF;FJEd4@6CdPP5CFUdJn$;ivG@( z@1pl!>Hgk>p~2?;{h6`WH{+Xk>O2Ud!I@`KlLwR&B4g!j&W}|FJR-k$mB{8iJz~@& zLQE@s2Uff)zqZm@gt+h#l@i0#`sR(EAB!l3d7HiUWeP->!mrY3&3E3Vy8e@Z-bHf_|0p z9wX;$@+M;CZd3SS(=PvfjRpQ_bxF7H zjWKsuJBsp{{9hZV#~(?4r$*DA%MbN39luR6KP_5k=(#52OD}2~o4gbdsXMlYn`KP) zi~q9JX}5j9cQ*fUGb`&Nlez0YuUFsUW_IbNX2O$`Jb9~$?N)&pxpz-^@h{2#;~QIq zXMSHkT59YR^L&m?1{RJ=)HN(_%!l{t@AlnOLCjBmBmCKwWPi%CClh|lSTTB6m&s;L zw_@g}1UD*?-L>X4GER=L{@$_tB@j7I%y+)Wn0o7(c219x8%>U8h=S>xXiDCH)GYVM zn77UhHI4dzYkF=TV=^3_0V4OM7fjW}WWTfcr-1NTVY5jfU(KSfpwI!>( zr~XX#vwXWf?ex+I+&RBZHlqeragcLeJw?u)TD>Z2WdD_^Z5))~H^#I^Jly0`UwG@Q zTy@s;9Ao|*b1}TK%{529i6*~Z2%qu)b)?KI9=VFzUVp+Ya|%(D-Jh;u+CMQ_-*;Z} z3ncQW#d7#}7;Tq>= zI(-TaGjl&Z7`}RUFSXTnbV+j)vzVWIO&;7a_MC!@aruL;I ze?!jCJbqu!$5+|&yT4=Ir~MP9@mAAvPc@su$^MEiGdz|sG5+2%u6(tXm&@w;+XefZ zTJI(MD=&_+2-fQUUMW|;`Clu`X(VfNeyhH_My>LCYwCsudA^e6{>Tsvna_^}QR|0y%*J-f{x<`QTLf$MYn#V?9Xs{H z=Oof8bZ1wywO6vgziSr55+<@>C3TZG$sCv_@ri3X)Hf}sVPDbPr#vQD>%TmC-C5Ts znUl}U&dEG26U;jcll_+2_joK};-MME-BtZ3o0p49-QAxtvuV5=y}{IJ7QtFv^O45% z)84;_ll@DZ`g$y3LVD|sdG;ra0Q${ySi*#Shr#FrX*`hlq4f=|y*R3PsW5%%16`qL%EfvECwBOZr&pYte@xjsACy@Vp~Q z{wMDkhb2s`zA`Vo@(?0Wf6Ib222P#ry?_$D_vcS6g0<%ST->QNZoFxAE*FTx-;D4I zWlQ#_URmz27DmZo87<4G*(N5H80{@?gxxjYO>$Vm#KiN}b-Y{smwS=MmPvEG1}&2P z<4wj{1ZzpJEWI=OVh~;1jrA&`uN^wDAKLJnlK*4tti!81wl*F-xVsm3m*ngT?(Py? z3dNlw&A~O05ZpDmJ2`uDf@^Vir)YuVMZS0K26*Q_-~H$IVXa@***3Fg-dQtDNFOVG zE&5y#{Q`R0bC89%9Z+4dg$c=df{5v94nodpEA5 zSk6NhTbMAf<3PDNp3jKU?Sac6*el_Y=}wF@#Y!W_`ndBv(x0Ck;BT>o3BGSWK67JL z(DReIz2&b?Q_^cm?}gq*mv6LE`A!Mbg?c^Hi_)%8RUS;!VXYqE`&bi@Q~yyN`-@Z? zso0BY>CL29Lyv@C)uUx{{VLGyEjxawVha-+>&{Z2^3Ko;BYZ(*2>xuhM_aODX-k7( zFMhI^r~dlNX?#LGYIzL=Z`u_*KR!sxzFl3 zGb|o8@MwZYsTfUUtFd1ztoY5cWtR2)?mee3+F#*_efY@-^%7Zs>y`i5-P65SAsFMf zI4&zWqHgZh`_BY=*uq5h!9D>pDyr5p7(|XF<8`SzZtsZe@f44WCN-PoWcs~* zQy3#8%s_4#sx4GCP8s&Z;;|DG=;f63cIfpG<5Z63`s8%Ccm26N2Ekr5HUN=(rCaCg zi5&zw9kkfOM1r()RhC!d^!Vwr@@$T8h(1sc6>hI~7zBIqUB~m7wn`^Y>h`XEd&+no zOkiy5^t&?F_3^p?&vw1`S&(oBDawxu!RM(eapElIv#A>40Lb)$zoFEG4T&c^VkBWV`u|ZHKD`S6WJScMk zK0XPvFVwv-^4c-Ff?^93XC}pTMqX9wqUzA6NUCP~G-f~cH;SYFDi$LkFx3p5xY7ol zsb1oMy8CD9`cJkyb0*TZV@3qTv}Tsxztrumc;JpDvnk&#OzeqF9v~zA{kwL7_}sIQ z-n|v=)!cms!CsWlfw&msl${*&48x}Ow%Ec1jmSVey13U_{kdREHG^O;$`e5}sh7Yb zqr20GU;5ElM%V1^=Zx-ZhFhA(J|KKn1=%?;y4zB6vx_ZE&D8F19ei_YE0x4zIq4nTb|+7g*fNaO*>3b$n3) zm$fbcVrr$`Jbz)daI60O*U8Qw&69PObKT4J5aiT#PAoDA_M*`}uH&D)^L5KIn3?Fe z$YQTu1rrBIe|4gMCT$YSHjmJ|Fpg@_WQxTWCdv-W=8U8E<*tkve#QKC-(7C+p59dr zg1yquDHbs5?JTXD6$G(wdO>{xD;igIt!c4^iKwt#&NwP?bzKmPYu>eEBg=@_<*SPc z_TqO8Z^`>_&Nymzjm#EXn4mch#K`sSg&pe-){*7RY7p$j@0gEI%8JWWMYLB(GdEBe zlRI;kGIv=iX{eSNuefgl^+c@pi1mDuew(fdVx(@mP`!B`nB)yq4K!>{rIQKxpO zx`h!-La)b?kxKN8mn|ce=ov42M)5vcMl2V%hT%=@v81P}fh?m%v2_+(n8UZqeY zKrH>TTXjZd@#_2=EVeKaGuJlVO8|2=-dkbb}M)Y{WSb zr?+iWQ_+8<{J2tP8h`wDz9tzHM9Z0Pnj z-xFdG>?Na!=$Sjj@M$wrb;te;?b3I%*uq4)yE!7IziN6uDTs`xu_GR4KMLgPXAtbw zGf(!&8X$^Uqe;7ADNOaNE~qJw)FAqCmJou-E;*rJNY+8qY$EDXIUorebXH!pdN=g$Wry$v6t5 zCJ<+eRIT}8WFHK{?c7ti(M zjP)K{(KBg!RRlW!2Y97Zgi_U2IMF?(Jv>3GE!CY}`9rsZCp zeJmp{cdwYL0!H+4E_5^q_L6K*zCq-8AR_lxu#VwPyjXX?_3p)NEpJ@A-?K)F;v@f! zEG<&L7x`}F`@t@>$lWA|yA~((7E`7e?Ed8pP#3=gcj`ea0_Il~A6kC|!y8vS9GwUpfGqwB;g1sb5mevP3 zFk%dv^vO>$%aGggU7~NvJwb*UDH)~c2I#RPFWnsG{JXonKZvNtD_q%;Ste>f!eR>( zrD}F??)2*>c|g3WG}?6v-+BMRl?;Nt4wjwe#PBwfd4`4Ma#Gr1{ho8i)vkAskIb+?eK8hAPld&7i^gw zyc72;2yglgR(bU2?S79^K4f7+vR2Uzka>cLvtyPO7kNoH?`nf!uYG>;^m#Q?r}1XR zy()TZp*6OE+Z+0Mv0@7olEF&bh5Qu6#pffe(-@zRtu@Xd*lXy+q*`WJK0c8duWk7z zS)v>Cyfs3xg$c=XrA21|5<@-b2w1bgwDk4g*VxuP2&@3q*%g!F$u=M%R*OlN(8ZZImt zOM_r9e)D~NN>}Twx}k-tZp=!*%DgK+2WuHKJxT7{dLGVgJ3UO4FO`nUCNU7|qP(P{>Wzs7I0njp)l(PW#f zCHQIi+1klmzmsK%A`k6uM>{JQ_HG;4t&4vCIiAj0Vy1qXDO-SK+|u_Ue+$4|zmqeF z@{YX?dp5CTrfAW(#-hRhurMKOK_mk}RtO?S<7Q37AB}q1VMeRL9iF~+90Sux7oskc^#B97zBG!_JJ6K!$&#&`Jz(+Hd~nB z`-Yn8`+;gc)-8>$yxdux^Szbf)`#*^yorrE)K}?1L={`btD6)PvgSwnTG7;Tn#YD> z>JQ8mrMx}WAlQqtGhD~2wmDUM%oIK7G0|B+^!;x^X>j^i(a}v}`Ip#gA9~Iat-ENp zFabrt={ZFq$8OVE?pVQi+r!RT2EkqhSM1U^tXX>3;^ZLKOgv^)U+?y&8Cg=Zg$XDP zPR}U{ImS`xr&(z)p|-EfCz}cO;&%+Y!yFvy^qiu+vxN!DuMs2ppiY(#W{N^WZW{!9 z@jHgScSd{8;GK3+dK0<1uEXP*}??P`+(Szsf=0#oik0?QCmhpl7HYnDH$_G&x`X| z6z}e%Se;cNjJ)~;`SAGFAY@c0qdSb{Kf%}^KKRVFvwdq!w#G8sAS*LlOea} z86;f!uD`S@ge*MWl5m^vI}?(9OXh^E8N|att#+eVE4wnxAlQp$jX+$y7^OO*S9?4u zoY#elV)oDug6U$9E=WYBbjV6XA%l1KV~2-DNYoB>fVV1p`&4B$f9 zWj0%wknB5pJ{k9FP3Uy>4)4{enqv)uy(IgVEF3vE2+6)B3r99?vxN!Cz9kDs)(k?j zZ^^=ujT;1eN%k#SIC5?fb=S019p}5fixc&;*}_DH&)Fhxo|>tBid6wIxKdV?;5cI3 z&TSCvB_ma5#2Rjan6qo8<-!j9+dm)lu!RYlK?0FxSbUfCoHa`7zBIK$`KGzv)9;5QaC{$e^6WJT_LA=+ zdXx&{(EJ4YA?Cu}AICXuVf6f!lD05<{z}Cj`Px~FQ}JaWh}=i6I{NvnbsaTZn4r}= zAU56_XlKBDV$o^$ZBpC=2K-!E5g=`3^sEuCoYqX(Y+-^{Mu4C-69&Ovw6*~Rt(mad z!UV0108uSxN@qWS*UA1g2=+q8>0F1XC>VJq>+6x(5AU$@l3D(+FhQ## zGFn&bhrPU$wy@d41Xff9MAsppH>f&up`K9E?Y;GIg3T5tNaqAmd(UqD5NkgQR2gp& z>{S8lG6FH$F3>UkO4>Ab$;))2Y_o=pD z*G5~iyxT0BElfZ+a#knEdO55$xaHOF(Vt(a*4-f3i`KA!SXIZX$KX0zwV!FTg^8(i&#vs7q99;#k$L@%Uuofrp-CXSntCGuP?%A z`|bgq8oMD@R&xx3y^uMn=!^`%YEf~29kSc){dBI7p;RM(aMlIOY#zP&xL@_Awb6x; zm*lKj(@?{iK!)S2T$cGp>;iRiqAuML=YL!qX%Os1Z$5ri*Ruw0WeXu zbCLjAg*LN>XsPQD@75a6V?w3z2EksuYQe{+OtL}R)ec!-zvPm6|5(GqYh!pdjE~Rr zOdwM?HIgklR5N!AT;Vl3VxM8Slk zbU%!7PQ;mH5bQPKNU)lgaI#(%HXp>ZuWp?SU+rS7fn*C4n3Hu{2F%uiC>E=yev2#L zlr~JUg$Z7n?c=j7S2x`O&!bF?xdy>rn5|XO^C%LdYJ2?}_i8TAHe?GEymB2^uG{Gb zSUHfz-z3<}T+8{@)kH4?aX-&O#TF)bZ9R7RpHe}$`4Z&KaAU4PuotiE#JgKzx>H>< zIpr&V%Jf7qg}HTFn_+x)@3EX;*Dzg@;Ol*2`0 zHc~~;a>{ia@wJCv!K^`HU&R(CC_4ku^=)l?6LOyn3z`@Ndtp{pMbE>6a9wL}cR=nl zb=qjf7AAO&IQGS9`M^I0dd_q6cBx8UAE)Zif82JwaXu@he?{M@OWY{nlAberz8(1Y zIN^i`2GTaW8_Gs0~R zMQ@O!By^ykv+_=#_nnZHzS1(Fcf+sx=fp%S0GUidm&YL3i!=mz9=+OGdvP5*hDNd; z;jAG3{&ywkk=zG)3y6EWs#>Y=tG4urFbMWC-=4|GQds-367Wr}ea3smMBMXv?Hy^S z=tjN|5u?Y&9j*wpa5+mw8ieWf^BqGiK+@DI0B`$etDRyko@Q<%rH_@q7CkFsTufX{ z^+%S`iVkOmJ;4*861d zu0BG$Yc_6)L9mzfxXkbbE_ zuvfNJv-Ged*dzYiZV=ah>#Q0>8Ey0;T(K8d8Jk3suU*w*Ga0#d)JfDz-2oJ->V(qRv7MKOUlD;VpSOs-I#D z6TBW0b*X>PR#or~*7EIX5bR~vJ7>DEKxMj((cS7+iY-j=icRe6+$UURIUeL~vp>)v z*h^~RWNaYHGWO(nx611J-0giitEwfvZ*;vY&p;b%>)V(8B^G}vJLD(SnUD;bSnh?<5y6;yHb=i6(( zGS+x8A=N0+wU&qx=W9=Op)2Z&_9s>R+u4g(q@fj^G*+GQhbpt7fU#DM38|NnRvVQu zh>`o`0`=*2koRI#6@y?esacenJ5jaJ4=$OfV&L5!7^8_|3llM7pVBYShUidVS*Jf4 zXGko;o&ygPwl@g&;Jr=S?OJ@8p&LlgA3c`kzhwFNbPU_08X?Bx4t)$Yg9+*R zrKd(852EEOkBW`wQLW=3gJ3VZyC8<2jZ{N%ul6@-Xs9wwNY5WV`vGF%!wB^OW1K^^ z^BV+v(UZk)Bp(ayQ|a*p+im>I!xknsHovSp;VnsY`WA?*X(ClPuH*d8z6QZw{Ep%K zXctp0y@vfuZfCPukB}8dvhqk~QCW4s_&nt;OKSU`#7$(gg$Y^%tBkd^9wyj}*4%=i z^}9A(n4q=1Ail2=eqJEl!vuSo+THD64_K%E!j30bEt@S&P%DZUu4nZu>m$}oL|peU z!CtHzVyyP~rM2@acJZh`-ewCE)K(%!tkz$xo#%1(@|Jl9!CtcJQ$|Ht>j~oT?fz;F z#yHnzJ+j%tgsiWWF%EJ(5V3o-SB;SMWy+e;S$X;0!h~dd(K9R{lBXS~es!VdCsjTt z5BzRn!qifWubrccyun=GrTPZJUMtY<{)KjTzpqr@2W(rS?jdLBGNOTI3lp+qi>$@L z`d$$Awk}eO@qMID)7~K1OESvnc^?qxZ!T9hMl8!R20FRscMB7e?Mc>$j19!ipatqP z#!>DET zFTEP_dc+6{g5;K$M=5R+Yf~Zg7#_2Ekr5-obSwm{LsD!N{w7#5iO1 z4il0kNuP-92E?z~o2fbI2frqrXAtaVu4o+XJK5^p$L$^e4^EJzm1n%7jn}YYcjH&n zt$^ZK#d>$4vAT^38inImbssds8krC40J<$R2=y}Bznkp9K2eW;T8O|bg&jTnfnQaq%V_I4-jaV-YS}64 zr-cZb0|0SlWi4w8zQHrDy#~Qv!FTi8+0sqXXA(XHk=YKgh9LteyDvhsg$bGi0MR^p zM4!4;q(PWow{u6&Gl8JlD2+WC$$geo@rV}m!@>m3Qh~UTud-bq&*N1luR*Yv z-R`EhzaTF;lsmR&g1t=rJZsEBwl8Xa#>K&| zL!_)TA!~5H>*{z*!m`?>Fy{O_Np{V@MAqFzuYxz!cc}WQ8`*wnMTh&e(foIrkd;Bv z>-2FQMY@c$t00r97dXlw*vq`T2XBwHS66X+16R+|Y+(X(i&peZA!209Imz~ki=A7V zZ!!q>;&%Z%&}5Be%gpx5!gXz$l{Z#$NbV*%oK$9`%Cx~$dxXqv$9ZkDh35DFXZO9X z;rHy_$of)Va5;J4_rFE+_yLmbNp2?<=E&P?e6jbAa(k2K4s`Os?-nM^{rZCYXVQn7 zyS+^l4K@h&!W^KZ#EI^P^FKoJ>axY$-rX@Ki#GSe!i22Oi>|@Kue#MTK<_~PN8LoB z2EksV)2~p$*e_#RhX;s}Cw4g<9Lw#EpJt9`3lowbN}hL-{)THuBxH zDVAxrFcIFcoLaFPryyUKQ{Rew4$u{lQ{QO2$ROB@c02+>YM&;Bk99mn8XJfvQ2Y8q z?fV#Kl4c8XxbG^W%6v3f9faB!G-E!9__6xwamZe?-J5C*leU@v~h ze0(mod+Tcd+3j6;`IW0%_#sR7Lk-J$#j0^J(vp2rH(ZXiGXH(k`S+7qqcFpgWotI8 z)F;$OrA%p9m}q+BghQ7dwi(3R@Hm#lxS#uqi~kmTtx5aFiLs#T3J@iS6}HMEMtGu_ z7F(FOQRcQ2V|Sd{AgWGD?!*`yYqyID_8R>-rjqNM(P12jK9?suSMF|?*?Ll{wG(|p zD_`Y4RoD5u^;Unhwx^!z{Clz+=>B~+-ivaT!LMqYt&(A3BHNfz4xKIX8Dd;~v(bqW z*dUcbu-Bz&>zo+hGW`u=_ta-Dx$?GaOIvJVV)NXEPKETo&s(pZ7+-_(83cO` z&Xv)*yYF5l2Jv?q<=ov`-5XnMVPg5{B+ixB>KGHm>VwstyX&_rr$Mk6zdhJ>C|l@% zF`Cvf-YX`OmZ;^#aF6+fyL&KExJ&jbzO}c8L9iFUW0;v3cV>^gi47K+yBqVJ-Wb2U zNA6X_WpQyGzg^53A#wr*JnQ~IkHmNu+Rz}_t7N`Hwp>TEMDh)u39jLh z>xi>Dr^OZ~`i-(|xsIou6M`5#XO>6WtJHmK8w7jNp3-<8VOvHyF(!1%YO#e0+HD#! zXn$&hU@zLM8Zi#6_~=}Do{Gh-WA#FvD{M07zST9uLg%;lyY|7l)nu*n?^&NoEr9;z zjPtAJpY$~>O!)NPsss9#C87tR@I&$ z4wkQO%iI1r-+C8Yn3&o5y+i-u1H=j*62==Pl<%{#H?yQ~(qDjB_t)jr=#;XJ98LlSzd7jd8(xS4b11&`hFXAA$`X7S@Vzi@ap zFNmdM^Exrc4@qqNE%xF!6#Hd7Yv{!2Rivr$?lRG`Y78ev!M`%&?iO5J$1aU4KUN{c zAlQrFIdT>ueMGrtq#Qn3>eOt2R{SrB{MG6+}*}1y>WsA^_DjEaES5HebMPTW3^O< zg$e3WL7Xoe<-~|}JBdLUUO#&{5Wn5`ajtww(;_y%S4>dv41)SvgJ3Uy$B^&dS?rOv zBvnXF<4g<688l@$Xovgs@9kX2+y2?{?*7P%urJ-ulP@So0dX*GZ|7d!3}|2w>_wRx zh~^!$J2Be+n#X1f6O?O#NY*2P6JzV;rUt=YlyQO>pJkboCzkq_-)0LFlrw@@cfM?d z+^f33w=f9y^1HRZl=N2vzQhILe>dwM$xFJr3fgR8f^uIF*W(QSeqxA0uosO*KwMfl z&Ka@%`L4Om7A9z90V27*+!?VX`k3El3llW<0daF^K9^)NgZeiy2==0p1qg4UUtDtK zxmxD2*}?>keL&n@HqMEW=v7^VU@sbr;B8+~x{nj%eEaM+TbQ6x5n|97#~|2?#yE&U z<8zxWOwjloF=%{l5bQJ&W-~vVElkj;7(|hfDCf#w>`P*^g$WwBgIJv} zo+VE()|C7P!Co|u2I2a2+lf)BZA_ajOwhO;1dY!Pg1u;b4ua-=JZxct=4wFDypPQU zd(r$1i1&R8I9Hz3H?GYVCTM;}e$~5#mb|-f=N<8|g$bJ70g*YazY}Bqk~;>$UW-S* zw4`PD_wFDNbuOoIVq8hH(!&-eXr>56wU?Eh8LxLKBMgGQ`gHi{#5gj&E{K8Mvp6w& z*Bb9(3lsLs_)11ge*e@4(LYZuXNG0gwS@-3Ua7i&abnc2WPzx^+;Xlwxz80B-7AZ( z$)b3caUCwUFhRc-1YL(guowM85Of_bwlG200it5s9L~L(_NkRYuvdU@Qs-VBD4zht zpv(20D}S|kfQv0mJnaxm$urON^@|H5$f0?i7`3V-F$nh3nNv71Uiwc4ad$yeCx$me zG8bEz_@!)IC&uohZV+ik7I0#`sW`}=3HHjBJEarjzw9+>n-)%tJpsA>*}{aJS@nGs zhBd-j3OX@{`!3nT1bb0zv(c5hledp(0xOU11pZX{7{QL^JYHI$Sm4}P*L86XMW+&S=Q~Fm=|q`y+eQIY6h_- zAd9nK#)3GN6jnNQdF8~IxFwT8uova?h%xTkMkmIFuTeZUu$U-aqNEe!`rm~SBYnpN zmRv`N28j)Vy(phYjEe&fI58sLuH~_T#YCPZ)tnf8JEud8^4T*uF%CX?&tn6Ny=Vl0 z7`ba-a$*FG3$xk61n(f?<1=bU9w)~6U1xY~V6hjC4G<$T^CKrl*JOQcwlHDtMw0UH z;!X@TeKn5_EcT-DE@B+t{Eri3{*E#{Mm7lA0T;x=aF-KfL-wIO66Sq!EgHSzt4(|P zvlBy2`N$(-7ysQWMFu<1LvJgF7^nACaAJI(o7EuLi$<@A(atZ1l6SXn;SnCTFmZDG zP$$NzM7=v4sh0yAY#cU~(tMkQ{Lh!tnapf+NP&?VFt# z=jvb%nk-CE8;ls+e)n-=gmz405bR~n8YH|l$BEJD`dN!DOi=HG7>7cyIsHeG@i`5G zy?Eq}`I1$CI5CP2yl1h63EC?VF|uXc=ERsBSkxfci$~r#b23F$Cq~%ymlj)?pgj)} z<5czuPK+Eo{S1P=c;tX@Sd})}<*|R2P=id=y z;`_Z3661O8%B)&y_Tq6gMt5t@I5ASE|Hc}mLGamCnAt9%JQ5>ylJW+@UObM*xVBGD zTdreW#`mm28mDE^PCB@bZ!IP}F;ZmqGYIzLQ8DI_?bc2V*UG1?hHEBh7azo^pKqrV z<5XA?gJ3Tn6=VJGyNOPWS9h+n8g4W3?6(w3p83hdwdFc~yXnN3J1vJnuosVtv9c!1 zawo=}SjSlnx0xs~HlGtCQC&a8*mf|6Eze_m<~kkZpNfqwwlKk` z`C!FXoN`W#4E}X^Jjf@A+B{mq*g27pmha0C~X$Oa=kOt2TdyCD8N|H6q;XMH`JElkim z1|oLx;!cdO>(_ahU@!UxL2SEq+lg_n_u$}VhrDR z%84-}-a?x#Owc!v7?l#GcVdj3`N_isdr_N+7~v5fC&pX%cAG6sP}_wV>+{5SV$2zx z#30y<+IGaqmn__gvA*|Fn=MRG8;lqo*S~Pu_8N9(gJ3V}qd>S*1v@d^ldsuqVS@S+ z5PLQqc4B0Y%x@6vMSU%Z>lHgVF`9)vvDv}|^@$+*KUnC*Xy3AwL9iF)3?LR3$>+o< zUH6^M7A7bg05RflM<>RkZpt9oi!vM#k-uMa@{(6GzS@T6=LwsNvKkQMrujNC_MEL~ z5bQ-c9EddkR&-)?UJ*mHg$c^FKqTE?$jPs|1XZz_U@yuaLHORT>*R?&3&zxJVS;i- z5Z#N`aB|T$ovPSOuoq>{AQoSq;gbGi)omZm7A7e71>x5?sY`N(w__^WOt2S?06-MD z71xp&zfbALS{t-{!WK2|AGv1fBF} z5bVV*DozJZI8w*M9$N_}yyMKmVnX&*k3QQ8*U_eUXB}@S_TG8=*&x`9TU6|A_{UgX ztpZN3dz)Reg$Z+2@#(GNNt50n*o#|KJi!eEwF@yCoh+}}!i2f1IK%$(PK@)} ziWvlZaf^zI!`!W%7{8BdrP;y+uVRPhH88&uOa&)Kfh+?xTbSTg z?9d?hCwF4x?cc&6*o#|KtgX$T!-+8>=U8L6P$tZk{l~3TdTDvL_r|V?2EkskYxDP= zO0fzlNl`rnwU)PDFEjQqWr8aSu-7EckS^WL?HyX@4`n91B!TZIH!Gvn_9=7X zkR4};+Z)5bKaZXGtY^i$(_(+0nal0>p=cSdwKWLCi&||c4Z}9t2U?-VWGD76BnuPf zPPb{d_qXNUy*4MvAlQprZR`Q@vX3qA?w@7m@>tf`L6_^wFjh7VzAH@prj0 z5E($7&n}7a$IFoh!Cu^ILos<(-I5q*GSAa&VS+0hvF5J-9P0~qR&AAahC#5`)}dGI zvHiyDbE%i%%5NSxV3o)D&L^9%GfvuIg3pM+)?4M4tM=IUW8;^yn(L_L)T!?~nwvG% zW9m&%8ei1*0_indn4o!4wCzjRj#6^v{Xge72=?NNW9)|L+eA5UV$O6%Eiw}{e~Bxf zQMI=deYuC1bdlhjJ(*B!iiD!&*sL7AxzNxC1SK#65AoZZfkE4 z>}6&EohlD;a)yU%@7ru)g63rL%#$Tp>f|N))|4~|_A>L5VRbioWaYr!(y4eRRWU)U zw-96goVv#Za?wcaP6=Vtj3o)1td*^WUXwvaw5A+!4-ow8m<8CfJLfIfyS+ zXFD;Lo}S0rChvH|=TLz7)M2KYhjw>g<2?pJ&)nwoN1@{s*`%VdgPDElvT-sg6MR-D zT85(|RC#1F13MkF_%u>_6ZxISull@gkh+b^;^R^0`OD#RI&Aa2)NtQcs@-Iq2btU? z*o)eE#Q62aNENrK+nZ4(Bo1fHlVqEH+%OKc`+IbL%&i>}a7!s$RVha=0M}a8xqLdS3vSk?rdr>3lo&df>?aBmy;pK+BnJ}*o!iK5cMZ7 z^Orm^ef9;4Elf}j4`Soi5zc6$O!z2+U@sc6fS8csn=_gi&}2T(Y-uKFECM3UXqPi8 zdVXkxK^R^?$5$YZo}S>0isl5)Q8e=6b2|835Di$?SyYVGpT z0myxBm2mUPAo6{DA3JLrd4up>5=YCs`z2F*gJ3V3e*m$?Kfjju>h$ALiY-jg3<8LI z^|CrK=0(&q2==0R6c8PKsyi`0UG1&d!UWBPfUx$Lc4F-4=`slRqWK^Y&EI!$Vze34 zRI!B#n$ZDqJiL|@qoO;fL9iFiYk^o53DFMs>T-U6#TF)LW(vgin`88nif*sImE9oN ztJmU1s(FbCdSJO+AeR5OP(S__OiwX9k z*vPLo|N38y$<21S*un(GLr$G2;XLO$PL8T=F~MGR*Ab&kt`W|4B<J%ov@4=c5fxm~>7Mj~0}16s-KIrn~rWu@@ckTw(MO4$eP>p5#{3q2TZ5bQ0B^%Y|yVG>r zL)Uf4x=kue+AzJY-fg`%e633l| z!TQIDk*{2R9XAv9varS*1bgK>uuZ*dI$gJF`vSz!iPiP9JlHvM)ELDUCbs!(SM|D1 z*X_&w4Pr~%ih2O{ZVTQ%(jeGt%h4Tb->vETUA?y;20seWjmzTvkF+BcdsSSrLuI@; zUB^E6Mw>(lA3xm~t>~mbhAOr&aX8y9m9p#%9pm#y#OQINq#lIRXcJTzWDx8XcxspO z>o7yduJ9Se$$~}nwT5o*U!(dcwlL9j>26hH)(o99*EbLi&lk`=kW(l9+QT5&E8y&I zb#uuK?b#zl+s=R3N3dJyZ~eAdmmVB-&Zt`XPqIim?38nIL7#tfN4D5|%K7&+H|0cx z(np>d&j3~Of)?3Mj;gbK!}IhpQ1#_i2}w2op66UkRZsv9^>aN~pcAky@V zuis8Z2GFF6L9o}hgOMue0ZtQ4DR+16t(f}PId1QqE=sY5i9e$v)yKbP>iB7eNcrKL zJ!Jv*tkHf3!Cs3Wd6iGrS-Ml4L?8x~d~FwAiSttL7gcOw;$Zk*<>@g?pGle&MAcIF z?A)8(-pa-D7zBIef3a5$9E?-!-9iMmJ!P-9-QHLKrdMoX;`y8X&UB*Jtq&P=$`qof`U@!iDy&e1QgwYe;+Qp{9oOjNf(H4dmDE>XR+mqf6{B=R#W%Am_ZGRnTa4od3pE>#=h(1vG3oTb~?v6hx1(V0$>)k`E(R zTij-FThgijU(Pdsy+ppj*U#hITRuTo>z~PD3lpCC-<TH=}5bTBa)`@|831V-z?9O!@wZFR9 z!UR7j=r~O_JEtPHz2&x;U@v|vQQ>xQk{$LMD%sLf7F(DwpLw@Tf7@qp%5k-BiwuIj z_?^ZHt3f4o%Vo$JHoUj^jpH}5aL)t*8UC56kAIBBm7hIURxe(Nwa&f1T5MtBahe1H z%h4uAU|&rtn~onMDnPy;?2& zpw?uWq2GCTg7CEeT|dDto5SyxR%~Hn=gK!~-`VN9^>jHC>0aGGba&`vsX}TVd84)zg1G42)*FVHW0~9jM4)NqlMd8*&x_! zyYCB?qyBXLbgd9e`i{{>^18kG+ErIu?y0E*!gTIgn?bB9Gf`i~zJrZVH&Se2 z!sqQh^*Ja^2ksK0R@})tUShYm%8=#;!Ctdp+)}slhUsb{ndUrpBZwDErs$Y4+}_B&Z53OX z*tGt-8g^%z-aJQ$;V-7>Ntj`|xu%^#uvgWt*Hzl<({!&1LKGV|RiF4AF_0OwRd8g?c1!c}MV^pX1xVCgyFU1xnKJNHaotYM@m#VdhQDJ(R_F{L+8Xfu? z1bb~OdqN%S9jZH>Sp%Zuoay>J&R!mwXOLnG6AN=6Q7e*%>iUaUgNX5Qx_)*Ir}mWl z-5}WOQ^6yuZHiF6ak&s1Tg=dVvDbZ-Swj_Dn27o0pgM3PM92MCRDfQCXXs5BpD+G( zm}0Mt&km{^@GAdtl{Se@^JeI_*k?Oom*I*nOnhu}P$fBolVVRxjKLdb=rHU~SvdY5 z2Ekr+vL8@Yx8pp>fkGTPIYVbTALLzGEJ(41iNM+WR8j1nA1{Uwt)I=%JI~@gmd0*_ zV6UMW_oG_`&+cS((c? z7d2IffGF49B-rbhwhPqP#KAho9U($bP1SA?4LVL$Y+<5X?*(db(qMh`fe@SSPSrg? zTx)I;?3H%+0+k?5uzvVSh-c5I>UJPDH=L^2!bGmk3sj@j!8-hd5XEAL=$as`swTl+ ziIOi=X|n|D9-S33xu^{q#O@h5PUtX*>v3$ zIJ3CYWQA``RZ2fa*C@SM4=b`-eat>ZH*c_5Z#lkF)s8VmAAY7k zi-UElZ9@E6Vw&Cq;z3lfVha;f4=h);B7*gNU%6M|{io?=ASO&S3HHhmdxc6B6|7fg z5aRC*)AV!@mm38uwlFd1@CxNCq}zNCc$3jTQZ|Xm<~gX^h+lzwlGoU&y{L8 z-m4o=B*t}|w!R3&v)@dDz4#6F@hNq2hR$;UXF))tfAx5a8X9k^u9|z9e)M{qT3KeQ zuIXK-gSKo}xoS++o!>4)jD@jg>d6Oje$yr2Iaso26qAz!VICl1jEItcMcrJ4HQ z<3ZlZvqu>OdnHX^t10hresTsOUR9Z?J;$&odC}2|ElkWWAEBC`n5vggUjZU@xtY2+ z&Qa|8&Lr5&yz=R#X6h@4gS?|xjZti2BGHgt>d2(2ddva2R~^u+bvP8{P4oL$gJ3Vd z>)3@(|be$3{L!1ed6kC|scWs>t{e6ml z+i?kqIb){l?jRb(FbVd$&~m*hJ!XpboghT@)6?}85cU6#W=lc5#H@G(h#t!)D7G-s=_*CCX3!xVzMn@uO@}e!`9?jJ!X6qAki#;ckf|?{6(`i}JI)yUaRARE=ke@>Bk` zN3n&8^2>7CqWok$@0{ZL>Wxd3pO%mJ8U%Zd%9PI*<)?CEnG0XHcY#ZkpQ-wQVha!vyM#aCKiCY~P z*rNQb-dV(6mMA|V<<}SldkxqhZj16W_d-e#FWQ&3MEPkjcZFgL6IZ9LvPJnR z>7NS3(tpZWqWs+Ky~H5cYsLC)wkSVaebR#P3omPl^5c_Ykz%jjQCn?Mer_L36KN8` zEGK0vl zsk9}^&*R@GE4DBZa{P=f%1^>eLM*RQ$`a+LM2ZOp!Cq$vU$jN}>GC`ah^W&gEKz%|qe>Rl)tr7Uid1>Rce+2IsPVh4K^jdk4i9Cc+oL zvPJoM=Mc{Vb6BGMG``r{AlR#X&5yPyKYOp`MvV3+GFzhj+}PPrv4x2Thhu6{ex5DP z2O@V^T1%9lIa8_{1bdZS7)y)t)5kYIi0PG*SfcziDp6Xog$dtT3ADUdzn3Zm;`Grt zmMA|_bMq>;Fwtdy5-rM4XexOVhm?Qs66I%eU{-@*FaB;&v7Y^kOO&5VITI+hFi|cl zgBIoI^u&^g@vQD>mnc6SPOdY)LH6RW3q8*H1hyzYPev3~_hQ9VqWpZRlP?n2R*Ef5U_ZqcCO*`&&dwLld7mK%Fo@@K?cEIX=h!uMER-xM*6`A^^4o0 z{459^rP!-X!;6+EKc{bIi8P5dex+*JZ0E%Fn7TX+T_fUDg)mr@^=R2Ekr|dDdH^ z{1mGxx^t4IWo=P@^37kY*uuo@fK`?#KjrgCzMFY&8C#T}-{WG{J^d~Aib@@BiSiSF zqvX`v2A8%)`8gl7La~L3z}Sl{QGT8$mo*bz=a;fY`Pmb1rD6*c1=B3BMEUu=Kr;RL zmy6q?{A9bZ#vs@$$K4Q1l%GpiWKB`8EX8b5eu_U?2OZ_7g^AiPLM>5#E~k*SA6@bl zwnh2Lcxj_Suve`!6D(1FuB*f#erZ zt+pBjd&R0Z$`a+L`94wgpViE3i}JIf!ZyVgCbBjjWr^~0*(*f4zIkj>er6pr3HF*F zHPRC0=kZb@7H-dFi}I7>=yt^xCLWXQ3=c}v`x-~DmEy|D2m7NB`Ugwi^v_$#& z^mjZE36o{EMfp)F_bB$-{kn}M%1^w3@ghw^9ZF-1@^fgCN3n&8LMy9VqWn~ND(f=d zc1vN4@-zOkZ4m6WeqlvRl%FC2LilV=V2kqevXfV_g^7GEi(8`nOl&WsZS^RwEy~Z+ zU!x3yy#{qIZi({KxU&!!d&aay`8gA`SFweO4vq6!qWr{YEu-xVM|^Bie#YL|tJten zw|tf;KUv^q63+&H@rd%1vB5sY7A6{$%wvi2vo({%D7)j6N0gsk&}x`quYQGou|)ZC z2g|HMqNQ&=qWq*uw_mY^iO?jOEKz>!O|n{Kz?hdFQGRw#HwpF{kvxMX%1@#4LJVB= z*dxkMP~iiLElk|~E14zAPukpHKztehz$3~}fpI3mUbEjOw?z4A-9?Dyy~pkr<)_8M zqbf_=tz|{|DL7Q-EPl>k)Y}`wPn4g6i{;2Orl%E4`hpL^<&Zo8_wOO&5(Gal)} zt%|!u`I%SmA&6A9T11HQ^Df3Q#ea7})JT6(epXz)rOg;$Bi#|A{3J+rOtFQD2}PIr zi}I8B@NLAXTYPGSC_g^wO@h6qw%+P5%1=Y<4v49#mPCm1(>KR4#TF*oEZOHT%Fm!} zLJU8>B|?;+$puV;y@tNI=`YGp?vZyv$jeA<~z49U;ok5$l*@3lqEECwGbRv+4KyAV$sc@rd$MS(yZT z{hch6OO&5u2_Ar`wAR-n%1JlCc$3jTk*nD{T%!Ce|MnU&wijCK5#=XVh9inCOms_h&n3!Fk=XA*4+v5@C=Rn=ViY-h8zP#xYVb^UHhV<*u}_%k=38)##Hi%@^dB5F~t@p&PI-OiSje#?Suzz znjIMH66NPYho>O^nE#tcl%MwcsA3BfecnxTiSkqN$TJY9TMzb#@)Iz}B-pEU(giM2 ze)>Fn4&pEL>h(OT*uq4D!pmHu{3Ki|^&eyEP4=kz>N3D-2KdAjt z{M(t3S|3q|g%1d+^%3O`IMqQv390oFm$k!YJU`4n2=f@QGQU{0zztiMEODOk3q1P z)cT0>gIXF8QtKni4{Cobsr7MYGanq4RrirH11YQSrPfFO9Th$xq}E52AJqQ1*un(X zZ#%TC-^UtZ)cT0>gW4a93HFj&ABpkb+He-!^-z7DDN5#NUe`3KdAk&*usR= z`iSy_iW?A8>m$k!YJUuZy`vA5nf#`y(|bKiUj#OQhCE?!teyGE(a! z$`5LPr1Is5g$b$kk$C^r%1Et`C_kwEF$ngOS|5q=U(Juy`iNqJ+8?Rl`C(x~YJDWe ze>Fc+>m$k!YJUuZz2x^x4EfaK8OqkDH zYJEicLG6!0uou76$Qe-UBgzkIe-yuQ{3c4Rk0?K=*TI!bt&b=_sQpoFVM1zsMEOCD z4hX6B5#NUe`3KdAjtY+*ubeMI>|jSdK@^%3OIUQ+8L z$`2}hKuE2RC_kwEQEXvCYJEicLA?$Lsr3=%2em&2!Cq49Bgzlzb%a2zk0?K={ZZ^C zwLYT!ppqxjB&60ylpoaoD7G*mwLYT!phgEVq}E52AJqOB1ba!Xk0?K=@IfmowLTS) z`=Itmv4sh#^%3O2g3(K zu8%4|xIe*HoRI6I$`6hXgj^q0esF&h!lUH+sPcp110mN(l^@)n;44nZ^-<*qs|P}^ zk19X7KMCPca(z_!!SI2Q>!ZpK?oaR)C*=C5@`IxTA=gKhAKagW@F=-Hs{CO1K*;q` z z2lpo-JW8&QDnIx-5ORG~`N91O9wpaDl^;x=Xb1gG$n{a>2lprV&vHVpk19VnI_x3W zN0lGkpM>xzxjw4=VE91D^-<*q_b2#@6LNi2`N6({kn5w$5AIJwc$8cpRemshAmsX} z@`L*me8ma5KC1lS>p;l$QRN5sCwP=xA60%Zd7>TkHzC(Yl^@)n;6KX=dU;D#esFZy zL#~f1Ke#^$;ZbsZRQbX1fspH?$`9^O@D(TI`l#}QqXQw=N0lGkpM>xzxjw4=VE91D z^-<*q_b2#@6LNi2`JwY0LavW0Ke#^$;ZbsZRQaLP973*-DnGbCL9UM~Ke#{fStYgn zg!ZpKh7W{XA60&Ee}b<#A=gKh9~>PBxjw4=;Ql0pN6Gb3*GH8f+@FN-D7ikW{9yP%$n{a> z2lprViW72uRQbWtfspH?$`9^OLU@#1A60%Zd?4idsPcpR6MV%9xjw4=;OIce^-<*q z_a`AdO0JJ8KNvm`a(z_!!Tkxo;)GluReo@EAmsXJ58R)G@F*E!e}78k`l#}Q`xAV{ z3AsM1{9yI4hg=_3esF&h!lV2XivNM@qskBNPmt@Q$`95!ZpKjt+!eA60&Ee-gr@(pN6m zN0lGkpWrJ_$n{a>2djrY><}j zl^@)n;44nZ^-<*qM+ZW#k19X7KMCPca(!aur>{(Jxjw4=;Qj<(aYC+-DnB?n5ORG~ z`N9232#=EMqskA44}@GFReo@Pg0DCs*GH8f932R`KC1lS{v?D)`L}>GC$5hwKe#{1 z_rnRfKC1j+^{|IrA60&Ee-gr@{JT!ZpKh7W{XA60&Ee+pl5LavW0KlnNj(ew4xjw4=;Ql0pN6Gb3g4*U@`L-+!ZpKh7W{XA60&Ee+pl5 zLatAAem2#6CD%ulAKagW@F=-Hs{CO1K*;q`xz zxjw4=VE91D^*Q!Brdo~IwD1)t*GH8f+@FN-sOb7o`N8mkkn5w$5AILl zD^AGuQRN5YCQy&U^-<*q_a`AdO0JJ8KNvm`a(z_!!Tl+G#R=Ij`drBsz}mv~QRN5s zr|=ag*GH8f+@B^VJj%Z}+(+U1sPcpRlYFC`kn5w$4^|I*$n{x)$`9^O zLU@#ayU0`H`l#}Q`;*D_QRN3?Cz?&wtBtOYDnHl|C3p0=KC1lS{$#R%YAbSmRQbW= ziPli!ZpKCI*CDA60&Ef4bYz zps-gPT_06`Fg$o2a(z_!!To9SV}{Y092va}@?7fbM` z>!ZpK?oUE^lw2R}!MTGor(7RZOmKg?`ic{BeYD5_2)RD0{NVm{cfzCWx8=Q(>!ZpK z?oW4Lal-b4kn5w$5AILB6CP#nA%t8Xy^eM_KGxk=oUr!|LavW0Ke#{jPI#1kZ+P`` zeN_3u{i*jAC**hi{Wq8EqskBNPeOQDiW72uRQbWtfspGHD?iI@nh+i(*GH8f3?B%&KC1lS{$#%5gj^q0esFXksh6KC1lS z{$w5{*GH8fOr9boDiW72uRQbWtVGp@Js{G*oB!oxF^-<*q!v{jHPY2S*1&u8%4|xIYQuQF47$`N8mkkn5w$5AILqD^AGuQRN3m2STooDnGbC z3E@$4eN_3u@PUx)qskBNPv$F5$n{a>2S*1&u8%4|xIYQuQF47$`N8mkkn5w$5AILq zD^AGuQRN3;2STooDnGbC3E@$4eN@N6*MX4hqskBNPv%i_eN_3u!ZpK?oUE^ zlw2QGelUC>DiW72uRL8--fspH?$`9^O=23EeRQbW=DN;hNk19X7KlQ%i zgj^q0esFZyL#~f1Ke#^$;ZbsZRQbX1fspH?$`9^Oy{|YS*GH8f932R`KC1lS{v?D) z$@Nj?2g3(Ku8%4|xIgv2;)GluRetFFhLG!{$`9^OLU@#1A60(nG>4GuqskBNPgl7< zs{G*oO!xeSTpv|_aCBzy9mMrf2luC5u8%4|^v^fR^-<-APW&dhKFaCiZZJ1Pu8%4|xIf+f=gRd_ggh!>H61hIA{NVo7`-&5CeN_3u>R}JLKC1lS{v?D)`6rbAD_kE{ zesF*4<@%`dgWJ#~*GF|6?1Uz{KC18Fn&_3|`l#}Q`%~{LPRR99!ZpK?oYk1 zI3d?Zl^+}(i0JxI$HDzc2#@k_0Zs$1k19X7KgsvQ3AsM1{9yI4hg=_3esF&h!lV4V z66gHH$`9^ObbYEhKbm6`4IXS5&E|<_4~9>m!i(#p$`9^Ow189-(uxyueX2P>5ORI0 zIX?;EQF48%IX@6`eX2P>(E_TiIAP8Ygj}C$&QJ0>oF53e zKF3n|!TpIAP;JEtxjxmL9|*ZVs{G*oB!ovr*XMt8ejw!fRC9j*X8~0!PRRAC=KMg& z^{M9kB!oxF^{M9kK*;q`gKGm8v;)GnEYR(UYT%T&r zPeOQ&+&QI{4#2&al)tsMX4=3dMRC9jVL#|IX=O-aNO0G{e z=LbTrPc`SK$sC+uhEtI1qbdM~2ZUUoYR*sL#|%G~m=VLfE7zx*^HcbW6Xvu)$n~k_ z{3L`&nc2f{CD%t46WpJ|SDY|6hdt!_sPcpRlMo(dh7x^?oX4iIN^V%IOiu;esF&ZCp^kOm2u8bto-2q6u#m_`Zt&BQ_cBF z2#@m5be!`OD?hkDg@5AwlPK4xn)Aaem+Pa-5AILlD^AGuspkAZ$n{a>2lpp>L$#mf zQF47$`N8mkkn2;;`H2=#ZN&+>KGmEb2)RD0{NVm1gh$EsspkAZ$n{a>2lpphK(!So z3`&mxN z^-<*qM~6M+`l#}Q`;!nJCD*5#^8+E*rw7+QxIfVXs;xL7*Qc8E10mO^n)8zo9wpbO zn)3r8*Qc8E6D^?HiW72usyROpa(z_!!Tm`HkCN+C&G~_l>!ZpK?oYIUYAa62^{M9k zK*;r}=KLgtN6Gc6=KMg&^{M9kL<^|4;)GluRemshAmsW~bAF-)R9kUEu1_`R2SToo zoFCkugzzZ2KGmEb2)RD0{NVmX3#hi@gj}C$&JToKpK8ueLU@#1pK8vJ_Q3V2=KMqp zXwi!OT)95goF53eKGmF`gzzZ2KGmEb2)RDhoS$d`)mEI4>r>77fspH?$`9^OLU@#1 zpK8tzgj}C$&QG*}YAa62^{M9kK*;r}=KLgtN6Gb3oF53eKC1lS{zMC?w&H|bpK8tz zgj}C$&QC&klw6-`&JToKpK8uew18?WPRR99y*wcX|VsPco!quD%0 z$n~k_{6uf4_OqOj>r>77VGp@J)tsM%@F=-H)tny)xjxmLpVC*Hkn2;;`GJt@Q_cBF z2#=EMQ_cB-kn2;;`H2=#ZN&+>KGmEb2)RDhoS%g7D7ik>oF53eKC1lS{zTWOn)4Gp ze<9aLl^+}(2)RDhoS%g7D7ik>oF53eKGmF`XaUt$oRI5N&G~_l>r>77NeGXU>r>77 zfspG{&H0HIP;JEtxjxmL9|*ZV)tsM%@F=-H)tny)xjw4=;QmAlsJ7yST%T&r4}@GF zReo@P62hb8`c!j%AmsW~bAF-)R9kU^c|8Afes&rUA=jsx^OF!BCD%ul9}FJ|xjxmL zpJ)NqR-BOQQ_cB-kn5w$5AIJwc$8e9YR(UYT%T&rPjr1$`JsPaQ#WGehfaLWX^E8| z+zkl1KC1lS{zTKLw!1p;t2sZK=3{%v^{M9kMAN9YyAyJKRQbWtVGp@J)tsM%@F=-H zs{CO1K*;q`!ZpKjt+!eAMJtrlMo)2eoEx}RC9i!E2he!K0i*#^{M9ku!me9Reo@P z62hZoqt!m4an4Vy{NVmX*Qc8E6Xg1+@`IhAX+E*?gKNSba(${fKhXkGO-L(F$n~k_ z{6NU{spkAd`?7XK_9L}ipK8tzgj}C$&QG*}YAa62^{M9kK*;q`v=KMsvu$nBUiDQfY&T@UKIX~N^-d5ORI0IX}??s;xL7*GJVFd>sh6KC1lS{v?D)$@NjS z244q4u8%4|xIfVws{JgvKC1j+@-(D`T%T&rPxOXrKg$WZKGmEb_K@qN$`9^OLU@#1 zAJum-d?4idRC9i!1yoycLat9W=LbTrk19X7KMCPca(z@u!KHza>r>77DdhSn7mmZw zV3Rf)!ZpK?oYIUYAa62^{M9kK*;q`5ORI0IX?;EQPK6GzJuWdA=jsx^YcFos9JGCu1_`R z2STn-HRmTGJW8&Q>N^-d5ORG~`N92(7Eo=)37ZQ7A=jsx^Ajx~eX8*e8k~^pQ_cB- zkn2;;`AGr>77NeGXU>r>77fspG{&G~8KXi%FCrlU`MY8mcNgIpg~elR>Bp(=;hl&aA4?RhLucX9+ zwsL-ObRgvVsPcpRlMrP47e(>g7TN<}2STooDnGbC`mJo`Z-V`5^NJwk`c!j%62hZ+ z593e5*MX4hqskBNkKWxyD^B>|DbD$+ujc$Dgh%EB$gPc`R9 z-@!$naF0qq?Q(spIX}@Zt9|19lPK3m)fx;RUb$Q!Reo@Pq6Ji2abi3E@$4eN?T%*MX4hQ_cB_-capl$@Qt`{4}J5Tpv|_ zaDSpVRQp*@$n{a>2S!ZpK z?oYIUYAa62^{M9kK*;r}=KLgtN6Gb3eFwt_Lat9W=ON^-d5ORI0IX}??s;xL7*Qc8E10mO^n)8zo9wpaD^&Jc!2)RDhoS$d`)mEI4 z>r>77fspH?$`9^OLU@#1AJum-d?4idRC9i!1yoycLavXhHTXIZa(${fKMCPca(z^- z!PkM1>r>77iQZ7{XUX-c=KM6Igj}C$&QJ7)YCp>fxjxmLANG*zQ_cBF2#=EMqxuep z4}@GFReo@Pq6Ji2aYC+-YA@I~5ORI0IX?;EQF47$-@)*Kkn2;;`H2=#ZN&+>KC0H> z>p;l$spkAd)2Oz)Tpv|_FnJnMLat9W=O=nYwV&mLT%T&r4|~Yj6KGmEb2)RDhoS%g7D7ikW?_l^q$n~k_{6q_=w&H|bpK8tzgj}C$ z&QC&klw2RxcQAY)!bP(z7B+3pK8ue zw18?WPRRAC=KMg&^{M9kB!oxF^-+BX!v{jHPc`Q!T0o0d?B~k$QSAl$212fnDnGbC z3E@$4eN=nFzJZYIQ_cB_u8;ES^v?&mKGmEb&1q>;<{ozgLavW0Ke#{9G^*_`*Qc8E zqiH_2hg_d(&QCOrYP&lj*GH8f93A$M>r>77NeGXU>!bP(h7W{XA60&Ef1(9cTX90J zPc`QULat9W=O-aNO0JLUI~YC?a(${fKhXlJtvDgqr<(HvA=jsx^OF!BCD%vw9ef=K zxjxmLpJ)NqR-BOQQ_cB-kn5wW4DL@tc$8cp)psy_AmsW~bAF-)R9kUEu8%4|I64q= zeY6MePeOQ9`YDm?qskBNPjtmXT&_T4&e8ma+tm7-EZybUS?1DU8t`2M`Jc@4YxQG55ySxi>eYv{4 zeZ>j-#e@EW`fuzckFP_WV^%zwfKHs zV}8)oj|yLLLZ5Q&p-(6I_7iU^$PVW8hbM$b$$lW?EgJ%YSt$kHL>>-WHF^=Xm4v{f zAQvth0)km71=;f)eK5fEcQ@v%uK!7LWbp4ib8{N%)*lzJZ1|KgQKzKFl4IEvzTyPabsDJS1dJO9nLE^R za!j6t@F=GFG*A%=*g_DpgO0tfF~8&87NxH^!IYo|>QMo62to!D^{9OHQM$OrHwW zYXe3aL^RtDYs@j-62haHb`_|928=xjIek=ka~!|YSDaunSfExM@CYH88CFt7&hZFK zUvYx@VS!3@z$t{damYDki`^RY$!)qMgh$DRq%s~b9U(^Cc|rL_56&O^bSrOsl{jrp`my`w8i=YXtIO=k;K_yhK5U}jvP??4_Y zdpz^?;Bxkcjro+}dz8N7gzsHfx8+|$%F*jK=8ON-D6R=Oc@OHodld@2<8u#bfn}s$qC_6^zsHeQq=x63DR!YzWOa3FOEF{se>!3-ayx!d@4ZzTyOPS^}B- zfYkxP1ecPWeqJ1LUg;}NFwG@UHwYLW5Us{;RZ=&|U;g5ZgzzZl%>*hC0XqdkHVU3fM^yX>%qoa4XDnV)SIaT0qGMHC zae|3Tf!bZbvVxGUMeQ!f-bx6MV&+qz3K;OfAY_EyJfShi5G#GfiS&Ff>x>#?&cvyN z@F*rx1!|K4JB>YYpVC*H zV46>$z7ueNAmsW``N?sA62haH#}lah1gsti=KPdYesbKO(pQ{dnopp<6L5bZnDbLo z`N?sA62haH#}lah1RNcRt#>%Ir1F#F{*=Dr1k-#1^__tG1Hqi1lFCnx`;!nJ#XO!s z@{{BKl)mBw(|iK;oq+oT!JMCx%1@5_lMo)oY@R^1CSdhIFz2VF@{{BK zl)mDGTpy}6GI=0YpqrT7QohaWV@jT(9=NLx^i^s`Kp<9o~<6ZClB;n>Y3|{_NI6| zN1#s?qU)-|O0pk0{jUk(QR=BBj}qvlh1ln!VI>)soF3cKSDfJ4`hhG?px;)+V#7Fe?s$77Ogm;es{8;@+TnF*G`r*e`o0EXjs&CXQo9U7aHhu*Q^U8 z*1F}2l1yq&FMaHtul+11)SpkbR(Tce;sfeAeduPlG)C28%kesf|(|P?0LX* zfM8ZiN%lO)pGXLgV(LmD4&DTX91E3e}8&cLKrenv!Zpj?a=19>o-#KwU)63iY zP(2HnRS-;3DyggGm{p~(IKf1vKKZzY6BG4m-<1q>Ks5HiB359SzR zrLQ=_WT-$5GGL2AFmbA+2AN}_C4@&YyDCu4447^ZOtmVhbLNX+cg`^nOJ8v!y<=hKOGy&S%$Go|AmD*$7L1(-nJZIL zX~@TP8C&{_6U>+iR5JqJ3BT0|KMpFXX5_2oDdAB}!3oqw0?rJC92qJmInGS!D^4&g zCs384m9d17heK5+$ID3wk7AlnpuQ7ue;}CiQ&RcKaeqo*ae|pYfj)qM2L#dgqDxAu zOZjVCri4c^V<=E{3Yee}FTZ?oN#{V0J6igR6HJ^7^dJQMR0w9#m2@ZM_^G9@IKf=H zKnFy?RfTA~e`84pM1JV!V-munn4A~rr3l!x5X{so>9WZ2Y)fBpLg!dIIReftM2Dp> zD(U3N&%P%mJW56}Jt6XiA(lJt!jf*09A7xP#pZXKyORHdxn@d=7N&0mwflWV@h9ff=Pyf-j;v^4Z$46lFphOw>lv_iiwPY9-V-{ z4Iy8f?wuTeyYv+&nA;fW5DK{55W63FMoEWIzQZ-66T+j?t5;@DmUJQIc<9k#uU*$V z!TiZU4^zNNXAkCDmUKGhxb6wzQGVqdrxnD?&zFncJyTuE%EYTjnZ^OKhn!lTsbErPyS_E68D z@+I^T7Ceo+LHQCo^fI0o-k^L5J%oBHc!TmKbRA|KMd?dazJxx-!dIM7@1yc1^g=@L z-1C?(`F{Iug|9flGte89FQG3IVy~aBiTM)xEfd0{)WfNK2|b+<>fuzrgr3gASDa9v zsB#?icS5L7RQZw*&)YU3JWAcG%9qfa3ZY(9+tU55}ONv#tN(hfq->&i{^zlNdZ&&#e`gjXpaf0XfHz;31 zPcOv1^ad+mLa%T_c$E5&l@*~M8RDzCN5y=}wDxTaUvYvt1P#iU(3=dQ9_N@ZS!UCO z@F?|BD_=riHN>s-Q7d0UUv=RtPB2fQLG=%MtRbeh-nIPg-p2gn;j1TvN2QOarTo!!~oRIyX`VRf!d_R7?V!2YaB09=7!DSKQQU2YG&(n_?mUXV*F8O|_ zk5(BL`f4-(rp4#!#|#TSw#j$U3H8(}!$OZOubk)U#|#TSwh7@;Jommq85VkBA!1K0 z85VkM3tw?UJ+;cP&|?dso?2yC=&?-*kK(!a4a%_43k$*X^kasF9^1lKoKR1#GA#7i zLhwBOm|>yEHX%HU=iWCc!$L1C1kclt85VkM3tw?UJ+;cP&|?e1^Ymkeg&y04@F<>p z-=GW&y|57Ksa1xB9^1lKoKR1#GA#7iLhwBOm|>yEHX%GpJ+;cP&^-&m^Ymkeg&y0& zSDa8!te^9;h5iLSi#KLi=oG0}2aob7^c>X3C-%k+3tc>V zuJ581C)Bm03=6$15b9%4hK0U{gy0#bF~dS%gPv`=Xm94-E%QvwuiJNHg&q(H^?WG9LJvrjuQgj%%jkO2*ESSV}^x3MLman(TWr5 zOH@{b4m60Z=pR#trT+#SHhC1!j*b}?`pNW6X(QC5rVPu^ZPsY=6(`gOrwj}IYwV#u zIAuTRi%STPQm>uzDD>Vzw4ggr85Vl)nta6xp1B<}EcD?)sGm=J47#o^Av{VwgUYbb zLkPk1!efSo9>STv;snnQj~N#F2_bkUdCaiTrJ6*RjW*#=_^jCPgGeE`a2S^;v{6N2}GAt|q^B_Ib ze$k2(>cUlqg??N1P#3N;EOg~2gh#2!-49jbOtv=INoZyN7F~dUN zFvJV*JQFi4bQdRtN2z0385TO2A(&PWGc3wxC7lo+ zrOs<*Sm?xtQ0KKWEOcVe@D(SRzz{PmbY(*@*&$|F==M$sk5UJ@GAwkILohueW?1Mb zpW!P`Fi9e2Sm-W?m~j6yF~dUFdO~=VI^mUJq5mC%DHt)sLTCI8UvWa+_R6r(B@c1; zlxJdwh3@<5PIweEJ7R`~nH^o@G>@2Jp~HW=uQvt(|*y} zl4q;O3=931dgi*F2j}$qSIn@`)7j)JPVg-Em|>y6lOqGqh>sZ-`bHDNqtuJ43=6%f zx@MpkRT&m~Q=5Fn37$zGGc5F}La5(W85a6q6T+j^Q>zRMJ+=@$Pd{c@=&^0`6(@MM ze$24YZwv8S>p3yQ((cXq3E@#PER_5Vfo_hKbm~S30XYKu;A!GZ1?u;m|^MvOr7TW zEc#gf{+)b z49j8rl56U;|yP=*C(3S#K*Ma;0^VkLw}rB|=ac8VDme6PY+oM6sVgEB0*U+lsB zsF-2FDN6{C@+)VKyOVc_ow6-Qt(q<0fAiQWyV8br(fwDaEYAWcnbjFPW%2jRI0H0x z%JN)*%vbcZfEr}KYN_{;l$V}`|byq*ZYd^=RXN+YtHkr zQ+DK9m)84=6X|ay!&{xQGQOSgC?-9|-%$29PuRHl?bs)=a)1{>hKe;-FuYXLA&B4sYxiJ^cA~GhcCnnY^)IbV{6S$*kYlFUs>j z62hbOOcC{q@{AGo&@)BUFUm7UGGB3m*}}13l;@2==(#287v(u73E@$CHj4U1c~%O< z(>xnR{i1^=byA0x|4}OJl$2`Fm`g5FT|L&v;S4D9?O>xQA!Fs9%(4 zzGS}Q1hbxFzbMatfnbJo>=)&^G6~^PdRC44MR|4&1aqomzvw#mZJYUu6U?k`P`@b8 zv4I%N^Kf`BPR{dj62hbOTp#s|@|+(CJqbwtqO0xIHS-lG^t2)Mi}Lg#2qulke$gwR z@0$6F6HFa%P`@ZoB7!)p=*soR>waYcA zUzDd$vBxV*-X8l!XSD5{`HB<1H_!dJWoqmfox1bZ3E@#pnr~3QC{LeakE46t6#GR- z?6h6xD^8@ZqviHD$9~c9+qMbeQF@A%`bBwO6?+`J%Z;&L^p25TGhcBceRtPy^I+^3 z<#}Go>lppqvJL7Nop|}Bg};Yf^)2~m>=)f;=32?S>x7 zF+BXRM(?uc^5f&rZQHwRx#J2~$A2&ReZP{syFb4vdJbyL51xKVxVP81@ayJd!i1Tv zn!j6aQaJq6vEjj=S89Iqh6!O#F*dYh{wv4bmGbh>?*`^u(5tY{Re3o7sbOK~qwg%I z)omH{yMOlRP35?K_KW{Mq{lVvvEwy2mH(xW?8H7>mp89)OIUr<&~S6dEy9b>-5k!k zU}zY>%Vwe9zT+Y>sd0B+$JZVDlv8fOW7%S-;^P*ZH>`WaxbV;kYlM8^#tprm7#sS` zT_KF#aN`F3hVAcF&FhvP*UWtLFRB?Uf75-p5l@6yhhqbsw@LE_FFqCBmFFk6Yd-6Z zGX8tZjvaU%Grzhv?EKEa{GY8(2`hA(QU3M($S{55ab-{5(KC5R7n?u+|GihME#458 zpUivJ;pJ?*@oP3eaM8GM?CQ6adSCSZ@IIB7T(V-beyf}Bzmr$qbI|?axFs6%;n8x(S#^azuib~JSAId;ds+<(lTR;0=XcuI z>;G@qPQJnWExww$AxEFPA1KOnPI~j%rUs4-Q{J1A5FV8t z88-ZS`Qn7P2j)AqeXR5qCl>D7Gt(#Zlyzk_?$maV;y^yTZ~WYx5FYizUe{;(Ts?P~ zy1dstaJS+kjwNTF`9$d}PVCZmM5a&vuIGxFd|SU_8}_JUGLI7;mA<-GAWg)9PowPd8PU=7dP2{{D>dob9)-?XDxk-j94alOtSN9pM@{!j<|? zaD;1kdhI*nzxQnH#9wgXvX5jLRm<6DZ&dbO@zzrJGIu_>PJ@nFI(BgkYv?ff(ej;a zTzK^6HW00MoSW^A8TR5mol0ME;3<4zTAMW3E@$n967Dj zvE~Bg1aLO%E-OIXa$~<`i@pem}U>_mThdUhVSZ zfY63-?dM|#m%ie}h-EH~^w}3)2(j$PgTwuw56myvZBRmZ)YJ4@cX()6Xt&)^h{X^2 zGkb(1+-VQoQ1n=Hv*x?bzBU}uWlosU+@@J)pC=xDG}y5n;;V)iQrM?y#JOTE;cGOb{!5e^}xa5zS#AEqz;E9F*?jGgmcCIp>9UV5@ zvoZhg`lAY8apKVqt($jyk7qOQy$-+Cd8^zT_HNaf-*oEegz%{Jn&F74kB0B)x+k+y zx5VcU$M3;{XYOj^Y!<&obbGe7|4-KWKdUu|DSQX#&Of8cSDd)_zr zEq>dR?RU>~K4ul5_iZEPTZY&SvqtOJ^anQHM5%(HyB?zU+jA z@Tl~aU%&AaVHJAro*jN*;VVvXHfz>dP3JA9d5oSB_TzPYcI4>^;Zc62#@z6e?+>?g z4L7XafNb{0ZJO`qo~-9XFBhE6n)SWYxytq~IF?*CBV5EDTOE74U)?1HXR~IV)pQo( ze(;;7umpdP_m4a$Aw0_7Lx@#hZVm%^uQon@U%zW8oZxI$>a3=-5Kr>_aAx@Jvw`^) zhi#D%9%X;orn53g=aqNzDQW-yyAaE+-W(?LI<|TDjD+wg z|BPY9pL=Mxzc{NczuB?fCcN6Vd4sF34M#3Lr_}Yj&T2ZlJ@a|z`0rxSO(o9@|G9nm z_rs0(=JyrJRk$64OU`o5I@{^2S68>>@FU1-keS$I<`&-yU&p@D(TQ3v!_s_q_gM-n$X1;AX}hz^Lth*b7T*3C#JE5A5B(ty>v>~B zc$EK!@|}+lH`DjpwflI#7Ac)bU&q@g9254Z`nunjQ-ZHJ!Tox?Z`b`hvl^G^AKG9E z&0X`Bgz%{Ew-^_{wLk8{HF4dfUylx_KrDO5l;A5)OgOEveD|Y~VZjQ|L5$q+r0@$p z+XoDpm=GRCwjgE=be1Lu@bP=u*AuZbPYU6JaTCh?uCd|vwyQMHJ?GJKF8Af%9MGoO zuIHK|uKYZE1>)s@b`QSd1lK&Ju6=Z^QdgHxUOjZiSns*%X$j#`Gp`vQ?}X=H`WC;{ zDnmPkGq%BMylY7C6(_jniPt{5R$*T1atDOj9CtTZ@`i-)sPvVeGyKwJ8D`1$(%<27}cvo>$;H?>#1 zrhaVnrp;Wz#OqyMg)m`tr(W4PQ#gP8u(z&l7OgnJ^-o#dt3y2a?y=csZw%DLDvyw9%$eoyz~6T+h&@3vGqH;fId%~~JgjmJl13+PE5Ja};M zD6TidfuvkUkOZoJJ5s(^elD_G|SK#AZc9Hh`ng zE|1R)zT$-4K|-8d-4AZkr8yzesJh##ECqz+GJ^UQYAa4y#sXr`#s8Pfc>jSSAv|i` z6A!Kbgj~j^FFgx!!IZn2)*>_U`@bFwzTyN|7g=@h4Drl=S{J|b%De8=r0b4FD^6IB z17h23r(!?;9#^bADsm!53V)7cg#=LR-8}{Q+Jc(G$CGnx>a%En_QRtqgBjq)>fRbOc=xxpYPxF z$j^=WgmX{L{AYQT<;WneUw=^f6ZZ!H9(Qq=wEM82%+{nyC+n^_RCn0r@^_sT|NqT1 z2J`pmuNe8q{OPmc(rmc1g}KKe$8X)XGfmy>n=j`?IxcvPAZ{{79f z$}w+Z*Bm}B_=*$cVuQZ5%FWW>{_C-2fBu3aJKm5G9(6{aYlCu2qd$8EV$KeymA{bj zx@gq+;44m$;|)5NDCf&7FPVmj|FK^8>l4DGZd!eE*!jazVf4WtLJWEL%5vhW{5^Kr zF?`Z#v4(!Dj0vrGyr<-R6smjj@{3+?#NX=ZmZKmZ|M|Ld1V^}UckUZ}#R<;Jp~~q) z95v&{ay_o82W-(VAw0^m=Ma5b-B3>8z51!+ah_K%o#5&s=v%963Nl4|Vear-{nale zJjy>kb#+VejPBpbcrA9zfaG)K#5rB>3>O|hBD6k1ul)HPN0tTO+D^@l3E@%x8LO-7 zz1K2LIy?XSUtf3QtlUuL!b@d;t6X@wV9&1c-y8f_SIF%~tx=AAk>{`+xJ|}cIacp= zmgcP7pp2K!ple>&so~Ne#)WV|2Z((h?^wRV6PlJ>ty|_RPFSS@V&c}_%d4h0=D)n! zF(EvPGk-&s%YfKx)S+cZ?j| z61%_lSh*a;Vy(6+e8manT&ufO_UJyesa%uaYUtpFO-^{!C1G0pt(5P;|5&@Zyq)jI z-p?G?lgh$!l+&k}Ze_1}t9t#g!Snn%NC^N6) zm98o9AYXs1T!vS^_zzq9ds2ARNo)KRuHt<==s9)0Jh;@Ha_W-<^9R?yE_rufowhKj z^7me^r!s%v=z-kjiE@u;dG^kU;|gDKVs?jL!b4|X6~4Oad*0noUYT8f@-ns5BL*gf zM=8%5PQs+UVg;iy#3CXCxl0(ztu&TcPf8vCJ$F`medFRH~jqWP7M=39v7~-v;%+l z;_GhZ1p z6~o8Qr1lt(SE@xSGhgL0!Y7~pBmVovk*W!AzEitWcN0roF{@B!zRFp|%zRZ{j9GIX zOUN@o^yu2P)ZN5N@j`itIDrdY0PgMyJJFl6xp3nWp^MZ zwz$4LiqF-&zI{tyae^~{yaLcUo*Mm~6UuG5n|N@|lT`;^wBiKUBk_B#>j--2_Z(j~ zajxzB?%}1cIALdJh@od*Uryp~V)cg86T+kVcDXZb!kM$p@uMI%-RzojGRO9-A3d@3 z6({WM3^AQ^ZOOTIh33YD@F+XiLfCbpUmN(dUKt42G@zdv>cugb_E#LeP%?M z!*$}oF?z<<_rEljn{!M&@2yd#uQC+zwW;`j|t zERW&u@t?)6PY91vuY`_px*j6e*Yk+-Ti&Z{uD`zY6({Wa5u#nw;bkAL6L0OB5*{^Z z&B|jBdYQx z4Vd>+-Y=$eH?i_-^`);^Uq*v!Qo3iL;smkjK35hO>u#duw}r1bVI2?y-=3>aGf}AgXzh!-H9(|{T9^E zviUo|a5h-tl3UC3H)_lmn|4z|c$6QtarOD0Kauei+7=U%bCeU0w_345?|Q#|H{$Pc z#!45JUCwXJ@BjXagzzXo&ezqwwDE!Ei`O*fcfUHLIP|o`!Xpirg=Y@_F#GlE%fok9 z4i1}U?`54&Jt_YGgFm{L*Kz;!3(JA0^Tgimo+y09i9fF!8|GX*BrLn-I}pn+IHBAU zBX^Gg7k5QD zSH*sea-#q6C&SWvj0}S>7yz;9yA#Vh$N?<9ASFD?k3{5P`>j3E@%RIYhps+pop^*BkTee;l2h2mQS3XH<@f zcb-yg@Ka;nV%DEczT!lBcHZ}a*##2|^FiHrP0r39wOQMB<5~N-ee}$l9q-vT_6W~> zzG(6lC*C=7SIUn~yb(>}THL*8eX z5U1|(Qa1m>;o*eio`l%zk*USXUk}Xp9X2f?Jj%01+~b@vsTjs{CWe1kc>iAMgs#MO zMb33Ld*sES;&r|sb&EA8ghzRviD?BlPbjYBJNVkxvxBcVp<|(ri5$b&vq*X z>8v?=a51(gfAfEiQx$a4iW6y$Y(T49izz%o;H{2_g}P%e%XAc7e5d~9w5N*r@BND7 z%jHg8kS#WAaF~Aka9;W8`BTLlj?`z2=pTH=2_1WN4CcrR@iKS7?{K7UbzGl#RIaT! zvBV|c#{G8qx*tTpuD=#KJNLZu;)L)h^(d-Wk)B0}4F`8C)SYnG{-ZPRHncNmv#!^5 zb*?%g*H@ceSKK$ZF|YsQugq7RuroD8&x5`wb|ho z--{#Y<(za&-{31wc#kL7SMAm*4?n0ef8@q<62haXl*VgnRZg)7KHj3-zXLYM zU9{qauJ(1+&lw5g`o(*cH?G*2Z~vcB3E@#`R_*+eJ<3D>7?`j1&h^1poS>c>&v2@* za@}6vyPU)o*$10VNC=Ozt22mcj~`H8%y)2uHdB&ZpA$O&={(4J3u5ix`<5^9Js&db zriAb)yJm#wG+@7Scg};Ym%BB|SvsNfpU#7v=^(-@yOswnq-uHLq=fJ&@400zz}Sh! zPQ4oQ_jaY*+Va%8&e8P_S2Rh^nn`ATuP!#{8#VZn3xj8xozNYy?u5Ap;&b)TmYWsj zt8}DXw_-wglxLus1##<|#hULz{P(BKSDYX(7oV-p`Gq|iS3ILhXPj9BwoeF;TK4H{ zg6^YV?zAn$E}N`eFb^{ScEuMmUvXmQoXg@Kv+q}ieolT})9=6X{Pqv)6T+hoK7L%> zu@ShJv^}U&~SFXX-RE9W*}90w`)5-yIVaqvFyXW+BX~R#8vj9 zZtjGj3LbM=s$Ns!eS2bg4d1A%7w?@A9%a|45dYZZwz4bV+9m$AzhBp?JATp6rH3uv zP0$?=anz^d%IjM+<}JV3F(Ew4GxvPjXJ1{ux?W@c!Mv@KoW2vfchk3vdpY)a{_Fnb zhMYf+ermOZ@F=R_v2$J3YpxkCKdRh??_lvs3)ROLtvEpiK4zm-k>?Kbg_C(AH#Pc= zZp!Q)pjc-0>%)5A3<;NC^S0kJ6qw$(HJ0s8Y0NJ>dXC?jB!u0IK-fJ_LU@$j`#|jV z(V%h*s$@s@IVkfCw%wnV>P1&hM)h2JSZv|82%Y4O&FBZNZ&mT|pkRNr`+*##{WIs+TPf7@n^4v1dhigZ^oxAO2 z28~T}$WCnCac)@ur7OZdL!M`kuj;3l=kQ+Laow1N@F=SeKs-3ADBt89b?k!aUQsBV z7_#IG@fw)_ku?=UvWYPf$pO*3V0n2^UAV4pQ|f(oSqOK<$r(fQa5_FxQz41r9XdO z@6{!*X4(A}uj99kFDcgNE_K!lH`e=#6LuE{VRv^)&C8?gt`EZQAnSd_3A>wwu)EaE z36HY7R|vZkuJ;uu?5-HX?zS^0Jj(9dAv$l+Io_r2xaW*|Uva{6?+|-W{V-maZ2!&~ znG+tB9(TK~^IdV-o1D-08j<;m6Ux6;J>u*!>VT|#g3MiyC*Mm5kMd(aXU-w5L#Joy z9N6cc%)1K7Oho@j-TvN%$TOXOygfVqi^lxxaXpj%L?^tPl4o*U{%zLzKkTvd(1h?P zUBUd_HTmx5`(-VEY0P&Uxj^skq7^67&ddeJKAFA5r+vC5(0>V3tD56K*;<(s9;GWvy$)4=xgXqW z$LvG)*#5;c^^IDz;)L~xL-hLB_t}?Rk>A@Z=y}3_ldn;X&Q%_0= zkJ9yeRl$O|>975RK8Zh{(mV4NC)B&5tTXrN5Nn@xQP6eC`?n5F2#?YoMU_c~*yYGk zq20cXdGDtNWxnEscTMwLoE7d0`z=pZ|M7_l;Ze$ZR2gB8yU+D`B&_xgIm;ui$$Z6$ zv;%wU!pFj%Tqi!C`ZVtlDb(ys2)1MJrAy%T{$1Ky>TbFU%!ha{r-sW@ENKy;M%-^#?~6>%D$V z{P%)uH7LB&yD`6Z&=SE3k5VqC@<-X@3ZAw-k#6;mmOUbPr?q!r zyW3e;xAcd%hFAHNJpD!A*a4&~NLimw=-$7|g|o*`my8dqkcazd=_3-tqr4lNXEgqL zOSpmSt8Rz(3BKZl?)|G=ID4$T!=$hSpTuX@-6tVD%H3Y-YOh}xMv?35vD!Y#EB9V^ z?@8y$syhw|?{;Sz)V}SKZgnTpGtTYZhK8v;z4hWj>m`IoDc@67dwCs4jyOKt$2HvO z){DnXP;JEt-D_5LXNapl=ofCJ`Z{f=Tjet^>QMI1W$y&$$#^I49ae{U=O4Ex9luWK zK2XOJ?%&ws>qk3<3#l&s^!Akr;Zfev%=zPu4a2ikmtMT>@}zUw3Ec`IJ@lo?7ZU36^DkKc*4Ma z^C!mtzwv)h;dKn#b9S~FeHruD8XSDZ3G$*vE&EA-`=$?O&+|Q>`ouvA;ZeUYF)!|s z6-Tni^pWpp`N{ZE;ey~RPCVS)x*V`@NH}-k7>Jcl|0vsKFz1f}hbDwa4Q#Vy{GMNS zsLsx({d8Z};;VuAV;4-5{}ewz>OIyKcjfT9=Ls=u&3m%#`PLqO9?$8vo?Rz&$E9yA zcS;b4^tdIvg>Te_Q|Nm&!lS%1mwunS@6KBBt-a~$GWd!Ux*O8Bmir#|nD|qf&F8M@ zpo69*gh%OaNXIMgjvxlMS}9WnYu{6rOZvjS4_#Lf$CzuP3Hg-5wV!PK57pUk$WD)Zujca;xb@MbZ%|K;J;RVS$f zu&AnJ{&@@JuNFL<)su%Sc~Y!>b`ye1Q&Cm0Ao?$POLhg{j|KM?36Vto{k?&>;$L@X zTksw1bQ!LVtvErYsi-Pg5UcDoF6+2D(>D7|O$d*2XPm30RmW!?x26x^)fg{8)6~Xxw_t6>#U1PUvYw*bu?ns50D&1{fO*G zJJpbC$6a3ee?HtJyux+KJ9|$l@4exy@~(GAP*Iqz%6B~LtHy0k6U6vu>%(l0CAaM{ zsq_^ms7J+XA3Z~Z=i*$kdFa=QjPT^~3E@$%FScqq=Hko4@vrC^SjR8-TDB26nQiB0 zrQ6+PfumQVE-pI{^2#Uuu|#;B^ZCF-jw^k|2`V)42(Dg)y1D`TwGAhblj-`((1h?P zJD)?W@bdQIYjQI8es^=}D^AFy)0sgX3-s?Exp!EDD}cv3-JTF0b=;)Ja_|3+46iTy z9K<2#49iY^i;l({J}=yHccP z;^FPbhxyz=PH5k@l$EJFMJ&x|W$KJWr`Wns0F28)t{QD4QZgA~$Z;=ol zrR!W>?{eJ>vGbdB?Q^9+@%X8QuJEhey`It&kLP-7k7ZjRUVr_ua1>V=pAMhmhJEIQ zuJCoG&y_jENBzn$ohzBHw~bB+kFsnF#G{{-p(9uNt52MgJafPaUE%9WpKE!DIqOaj zBj|hWxz@CV@F;)27yUlJowXg$V93LSH>Q&}ju}DqRr+_^GM@a+@7StO*6<6xA2&SS z>#*;lPlUn$S6PEpiuuN)`6CP#RPl(G`emC2bqt9ncE?4-96EbEi zHwWUo!&`(~I6L3AV1tD4D1SZ&4%Tje6tn48Z_~D4(kbh`wN@qPY*0Vx+hQ_A&z%n~ zeZ>hKp(_s>;>7c=Dw^nk_)qU862habb`Q~F-TtxCu;sW93tw@9Yl)z{JC4N=);W+6 z9%VfU5Z0Yg_=*$OsQ~fh-yIMM;ZfF00de8&8DmF zz76HH)f)3&%UzxHIy;eeM{l-7UXECtY38e4mk=IBwk1~eRfVS~b*J9tZRB3}-FQOj zD^6Iy55$144=7LMSn}O6Qxd|XbiCDFk-7<}L9XAg)Uo93;-=D9oUnc$h@ZFLvs}PA zYW0;SC4@&!**6c9rwpai-9>O~4O6!3O)=> zIHCA9!E#%KiC({=_`qtNtU4V&}%ZbEk31v-F&>ZZY1g zUb{>x_S=;{vf0-pgh%O#Mmo={rj8lbG^)6ZJID^lUtIc%6Z8VaE+kd@>HS#phNf0z zab7&Dd*R0=KVDgX8N`~0u2Q^Ars#vWo==`T=mhsA@wm%b2x9IQZHjfs`@FKrFA3pM z{u?s!_WQ$%XCKDRXqhEXLv#YuH1=Pq-+?Cxv^b||#ohLhmU}0JN2Ra)jl+MaKjL?; z!smU{bmEk!vd(pb!st!jEOvXnIXi8oLE)Zx&BeN3&5!^8#q}R6xTbz^gRBdgyX{wA zIazU{&(qIGy6b@ZA%2+BGSeO(w0*P5f0jqxvHJIMkMYM(hS+AnKeDduF=e?Hg|9gA z&UOpp9@AT13(<3Ao4Ci|#iutp;ZcJ=Z4vbP#vG}q>7G9CiulSK4_~+Vtji&B_n`;3 zDjQ$w6@TttQ-3KQUiHfO|5toR)unsif2@8xeyhVa*fCjgVuQ;rjr0c1pR>p7-`^Ye z=(o=*3E@$1jJhlC@z*+EK}^5$^LoAV!|tTR-&UNs|N04WkKZQ01@YTU|BicX{bj3! z@F@Sw*416zdfE8yetPs~g|9fV@VrOj9v7dZr!>#{e${LneyiRaua^)W<$r&20OL07 zuD|(hAGR<047;Mc-uD|;UAcU>!^Pe8x%&6oOO;>0cu&3l|8B$D@a~>9?B4Er<)2-4 zVBsrHtUvYUdeKkb*An7|cfXB${5h~)LU`1|MRF85L4&u8sFV+k8Y9>9_61NGQt~N{l7i>?3sM7oLHgrKjR*am;K7SJ7>8m z^__X;@6O&WAw0@IWAuJJaA}j?-JwUXU!1?uMTOqQA@i0fSGclQq4%fle!mp`FU{ir z|L-x&@;c7FZd{YTwX2@7N3!C?Htjk_`hey1X@7adZgG#6Q#VNnkNW=nZ=1CDA%Ci> zzy1^bn)Da^{OWxRUvc7%ruj|!4eNGZ0^-5*zn`hs@yyxn62hZ)T4A5K#{r{Of;e@X zFJ@|w6~-M<_=*$vF1>x+W8X_yB)SJe8q`p_qsan(fd06Rs(w77x!4W?J5c3QT_?7tGjW= z3vrLF=j6#}*NM(Uj*ojRyTbSE@l*SUnsoHJZA#CC@F@QrV@U6@L7~r8-sZxlCz_Tk z^%>put$@u@@?Rg4&%-Md|LVv;E+uhydD^83(=BG$+^us|A zpERx=_n80rH3{KSJ&*e%zPs;D9ShOB|MrDGyYK(wxh7w6;@CN##63agSwRpO+9G z<)6^Hx~`o!j(fcH-3o=TIPuC)v*R8^_AJ=rfPrhrcXyp9)<_7C^3O3g`QY~Px7xSm znKOTXf2H`By6yaBo3byLEcLxRXT7?nwdbxF|NmR{|K^#1ZT@vY{H;1X``%1napHib zTSofAU1mYtGI;a2$K~g@PJWh0`KO0|hR^qndz`vupX77pMBko^#XUNFvM#T@!_9jZ z+wwPmw#QWo;Zgn>`}?!o(B{H=`y^%-mDz8V@#M(A_o(+3Cu~26$5w6|UwQFOmxS;r zdk^dBVOeYc_{!gZcn6+bzvz9hcf#HUh^uzrBJS}^~aLIuDb%+!MR;$ z>Im2Cyn`}dal)>gATD2TQoJJT^4As#;Zb(|2(jYH%fxs0!Fhc$Uva{&03i-MYQy;M z9(L?z3E@$8g$(i3>Zip$<~Qt<`HB;EB@1!-nWx1)emHZ(gzzZ;^zgKv_ik>|d$r0{ zyCb`d1;p=90{~GKLBC|UdUWeU(Br8tXy$HY6jvK{2HtoAvLU@$jCqm4>pk3VK zoHKi8zT$-4=|Qw9ZjE=4t$*1fAw0^z1>Dh37!vPNU-$QgmRTywtl#JJoM-Fv-OlN{|LAqU-}iae zUVH6neb#$@O+^X$tq!97uOEfI+xddZhR`lK{{Z6Q<~t^Q2Dcm9BGHNxas~m!!NV7Z zHNJm-S3_u*9-+8SzwT$@8LWI}dvok6A!kCchMbczgm&q1jPndvG)Q>t{^$6+GU@uA z9Df_M|DkJgb&p>XzQZjYePSYKim=Af>$`+AUYl!|WVE8hlz!_2{o5xufH+}Qy|Bi+ z^&T>WcF9>P5c||G410Ih)Q>Y-Q9{mTfmpS9=di}62}=#3U3&E3z2xeaVT~G9cSy9N zgq&f+8gj1B5Za~37|fUHNm!$1!Mj=cyQw^mRQ6$N_HI@yO30oD(QE57XbA0+XBNbD zO^*-fug0yOoYjgFb*}g$JcC_3Cm=f2KOpSgk-wg62<Ual@*U!Xw`> z<@&5vl=!B{c8U2Y)R+NzSKop~ceBm+bWfXU|Jc50B&P zHxI~YMG4t&SmWk~O~M)U`b1^Bdplc>Ok?1KEdo&X258*?;r_l7_cF(S4Ow;<_F;2YTtW??5bD z*CniR)mftrp^eIgYp8{F3r< z^nb2yq7^0Njz=Kg+&vT4C_TBa?pw65&A-}aQtZ~AuZu+io23h50t;u8-IM?^#M`4Xm&l!-&d%GdVoN!WjK5ji>7msfl%bSEXx=wjZ-`i8|l6P=C z^4p$Y8P*uH<79oOHblGPqOit!KOTTJI`6VaSfk(AU-er?s$KFe18dAE$%ZvH^_i#N z84S^KVDqrXE+@9f8nc@26xJAzbL#rHv`fBAV2$Rx%?NAE`p+``&X6kc?PayX8n0IG ziZw2twJyuo$Fb=?hR`ngmI0zqogrb3K7&{5cLuM7ep-zT*VuGNC;gS`wM%}BVvUv`?vQYen+E@;zc~$|o(>ZCvo8;84EQ=Rgm%fV zRIG8vl^w$xkG`@&e{_@7E zHFy?3xIC;e_JihzFkM^Emtc*zUl|wHxZsqx^z28f#8X8LJfHJPRXXF57hSp`ta0~K znCdQnOS|N38`ijU^%G%@xBpzIXYNuZjyUY_u*RD255gLITwE>TbKc|R>W0uRIopOc z{(Jr6utv$INA=8IszlSNM~5}8=}CvTL&H788ZUnRlb*RtwM)*=VT~qT-wA6J-8m}J ziV|{FD2V<~Hw|mN_3Z0<=1#92&C6Iy_xU2M@vq&kPUM`PA>`UotWo>>)?p1d`e8kD zXPi+v;|*fP>>t7!6Q6FYXUPpA*N%diJR=jM${xp>>;IjVy=Vw|ObHBy-krna*#3(3n&V`&OP+HOFJARWcs>eNey?W z`|fvLyQKQJv`c;)fLQRz>tT($du&OyqJ(^h2eG`R%kpv5-L-=uv`c>DfH?T-Mkzm| z9^31u)Ks?q<}g?078GnbdvI8z);{eGA-{2){8qyn!_)J^8kvW_NwuPc{0akcQuAlR z8Y@Q~YzXa=-<)`zSKEAdSYyM-Yf`N!A-@f=#+J)I2y5Io@&H3D-%N}#$r%f*(ayaZ*0`<86g|t4C?RJlu*Q3bH4JNXZ?{&j%uKXP&dFenTkiWXtkH46 zKs{G%2stMM;+(0i!W#2$@p?u$(JncI1me&)z6)zy-RZPcD@w?@B@kasY8%#QS!cAK z5!O4{C321oM5lQ_hc(6w*fZ6N{#`kj1>(Lc#bJ#-3s1-@plxvU5^_!s#9IqGhc)KD^+}2TE$!0tj5wdTu~Jy$+AFJMwW5TcTg2S(r*84d<$a0= z-}*K0+>*OT3TW6a~aj1TVcQ#v89h_E_km(2@_I#m3SmUkz4mE^!$txJd&P~n>YuwcTT&EQ!WO4zBhkLaMYixPq zC_`wMyc2=g6dCDWZ&l(2WYT~_pLT6$@p;)crxm^(pp zE)tJj-qlDx6R}nOASZ6$6&Brbn4+=uv(GDG?=W6}-gPODtJULs8$!F}lNxIbUVnAU zL1t{GQ<&x3BMK2ulW7I_>B5J~cX-R=)LPtDb08-<^fy>i#naIISol_iX^NZhkGteRb3;XBk4f z7(%<`*CdEBNBt+P@!zM8aavJAY-teRRXshdv8K`PhR`ngRgBN5X^-{~ zYh3qx3#Sz}4~2MrwLmf-zr+&Q}&Lc8qU#g0B?x;qEP`fjV+hI_#0?mMQ0y(`yP z*WVq3&)PO=iMdOf-hEBZYv6I5*>{Bd^mxpDJz&0`zu*M8zwXzj_i@7~&J(wVebwUA zL59#SIopCYcJDMk?5kbJ+@t4VQYFNY260f|eqoKzyX|fW?UJ)mSzLR5?8LCfgvQ$? zT2VshiNpGRr+--E%h_uSmC!Ev|M6{U<^Gex8jnpISfUjrE zn{!#%yDKJyHU2!gQ7U^e(Z4H?DZxEbcIX=($9cFCT?y@y=N!ZzN8KCNnD*KPJ+rA3 z+7o$hK>S=Z)=kE-TT~}&2<@`w{p!1(bX_q6^q7NJr&>|M8teUz>+K%vf!~~G{$}nV zp!b82R~okJ+BfcSd*MBC`f0ViR+Ny}io+wXeqPvD3zJ<8peiT&0`WiW2hP1)|luHerpyNn!}?l6Pv$a^q|_b+Y`)>wYkNruoa`6L2S>(9@VukdYY-n+Nc$o=bnM0#$? z-Vx}HkG@Jy>xT&yyZ7)~QNpfq;)(U$=40`x*6R*KXqS9mVXLw;TZcz}VeP)=K1E9C zW5Qj`aSzk0aW|{ij+$r)?b5p{;jXyC*4uDIcEqZ|4L(T-~<+q3)!^aUc3McN#*w^zKl|it5yL4RN>7KhL?)+yzPr zOe+af&N*$cpkQW;O-aiM@VxHnUMIaX*;98A+$?=ErA%c=a%pr z=latpdaWoSzmP!G!=+u^SKqzV*AS*_>#sf#%U&B4eyfe|K3;z*>eMEk5(VP17PHfN z_^hqE6Yf1Ne@lMdg}d8qz30Hr@2^b1#$9fD?ljly-3XMhuKqhM*QICS*lqUA&F0<- zdQS%V6^^Yc=~>-x!1u&Og?H+8E8#9pxw|;X?`RNJr&jUYSAXn%ks-88&L)6(s<4IU zbN<>_{q_1Ar-Ymj0P$(JeZv|PO1c?ByX340h>Hu332XfN-haGSl#ufpAd(l32x~lj zWyTQNC1-a)ob^+Wu*Ug!oZ+>igq)uNv0}#YVU13G8W}>n|d88$!F}Y#Y8`t)Fz4?~LbT;o?2@3|*oG?*$ltmtc)|cJAkQys%Gk zwLzQpinc_%XE9`setqlL_(rBb*)Nc@sT8Vzfka-hWqiy59;gQ$4;&el3m!7}G`NW+kguVM}|E_u!V@3&?n}Ic+`oI2RjlpL= zoz=gkUG}`_QNK?NYkYKUPjfY<68+57=^<~Ht#Mt?DjEG-+9hk_SJB3_Y>n)hPiM5E zgshk1JoV-M!sB@8^Su)#v`h9ni1jDj7am9VORm&sDpf-E8;F-XjPRx1;Me{%!w}k~ zGiKoGkDTdi*1%`&rj?0Sl)$fya3u0f3%>PDd@#G}Ps{}v*DZ7PZ%xAV!*tY2f8#-W zhJRoF#}9ts_`Qoxx$s{1>Yd9xuDU;PP&#HKK5=$;iB^=T_rb13ynE8wi&ld8?9#8& zFIM#_-s|%zhS086ztjrEcR#)WVpWrVejvWd+|sb4d#~>It_JSkJn6@|{+WklD=5W|a``QM(v^Kr&nLui*h+Bd$vhxaM+s7qHST2bPowzY~5d3u~{eH&jN zm*KuAufKyckeACa(T`xxc^upgzUVKGDUzKITibpw5IBh1H{bDSZx>-d3RxhH=Z`R;q-C>e2*(~1(mU;n8acKs;VWZY~JGuz(n->ZX9wbxEHgz4J!sr$Y6DA)a2 z636c_*zZ`qPw|mAW16j0l(=`@hwj5>qukNMpX3^!4feb5goz06onr{?`r(of+zC65 za_{U;;-bBW`WtbVwAP)@cUn>6tk`pT7Xx9LR}7(%mBY@~btK;9|+@c)kSO&4RD`CE6o z4PQOwZrO2|JF3Y8zV}n}T;pShxt^OI@Lz14>mF)5%pJGj0T7e78|w$Zh&xCAJkV)H ziJSj?)*XEBF!$rP(?K*#$M|tC^e(=v&0U6Q@ZD2xHP*Yn*#lnJM*2EpjDH)y=-tA* z%vLFJ`WH{SnyZGoDI=$0jgPM!^!X7~c^@ySjH9Lc88RXO=tSj-jsVAQH#CHrl_tuy^sv zx8LowqQvv7A9Eva8tOJ(Oyb@N3|Lgm`CB~dR%8vrE=d{62 zD@vTde1 zu;f9v<@F(M$J0nWzG`GxV`=jthS07(w|~&pSvbT!v?q!0A0O#QV~tg(4slvhV%Xy8 z?)Z`+ZempuGp-xy9{@4vZcAv_iBlhNL#7OIb>?zn;cJJD^z%V{j#agygfE@ue!FLg zd*K=q)4mzu-vRN$AC}OrKFKs!r_T^K;CK?Hb4U0eL9}i$)M-VDH?vdS1=kI6XEq_R zPAd_mcNA~+r83#i2LTfN!}9o zRvY1ag7|a#P^T3o{=l@FE?tJW-ov@Z6(0}x13@%fUc6(uGfI@#^qaER;PfJEKG;l3V-&P^?$UAxqr?CLid;#Sll@oJsnz7WJ4$uOrC zB^uA3ksM_S?W+IWBv-8-UJbvJ`1ZSD{z4G5PZ{R4qQvF@ zndEM)F~lufOXA5-hWUSkSbdfyv}^whCSkVo5LfAA5+ha)^L;>^eDN@+6(ycHXp)<} z(-61r4H9oG9Oj3ED7wND+SO`@N$!U#L)_j=NTf4|`A0wuziF7$iW2P}pXk2+W3a=2 zLG;*btncws@8Wtl4Rre1x694Xx~2CFb9XGB?(OH`m^NemyGwc(514s}(~1%kJCwMy zULNMAkA4tq)GHqATjM%M)mCLw4y}!d!KiQjKICiE6oIP{oMYrqg!}+NPqSxbN{3y(|JaDJm4WV6? zzkbmzet)>z;WrXbP8j1aK*qAmrMEe)D6!YKFS_?ZbohnD@EgYXxtN0S$R)QLLc4xF zaH+eX)(H2+bj%1TIPRP=ei81Ix@ycVPAf`GZnD%pSaXCsX$px-zl`?ZuEr;4@lA%% zuDR`AcFX@W!d>$EBOopwKia>AJFE6-6GfPMohHsQ=|078H-%@-{aitHENV% z=KTdL(}(eUaKmqVIISpw^CaOusrbDJV#WRo(j#BOy$wIu)ezcs$$l@oHtWW@nLE`5 z(O~~+)R06gO5o@SYheFjjf2w1(-k1=s_cTjd;Q@X(}Nzuyt~g1aavL0m4&757o7LmsXmY0+COhehfcyB zdwqLDXxH2qOI`1^W8L$$Nj&mlW&eNU`xKAA)H$svQS-r4_x`72-4knf0#X0Uo&2U@ zeTr9|exxC^>wwi+ciG8f-C4D&fVi{gZvMJEkS;Ad!D&T_`yR-;Qnj@f7$pm-0WQ?7R|sE*4iVSPnKe< zzWw+b-v-|R-hXd|A++o9=`-Dq4-R)tN*9CpbIff%#kZwj){k~tQDVXmGu=I_hr4H1 zy$IseL+`q<8; zJAbo}V=D9WublMv>Wx=qnaVugXnLX*C3*~BlQ5N;aq~eSO1@l~Wh(Pg^_`s(+EsO2 zweT5rQ=3*Gc0HqA%2cNL#3}CHqL~R(nGTo|I^ohe2~(MwPt_~!-gH*NROZm*_*wh* z#&#)FnUl9nbXrlO==hR^smvq&cL(uf2Ut!>WtQJO-f2aNnirNPOl6L~Vh<3_-fEXJ zmFf1=XhUdMgR7S&Ol8i=@_WgM;&v%hnVTn%a9UB~yR()jOl7t-;>5zWHyx2Om8pL8 zU_)qE{c-pvg?c1bGWv**6$Z1#GQ~sMUm3i%h2Bntx{G`??Q<+I4`a7*C z@$>PYBur(}@eQ#?TIZ0Ismy0}dmBQ#I{VKOrZNLs?GIvbl><|zGJABt)@enF_D8Kt zn93|Zr4fi_tD2=uWuEADxgoUcnmaZmOl5}EYYgJ)mQ7NoGT*;-vD1nYji+o#n98iG zOQLqQ#wk;ok50bG5ZdL}ZcLcU>~JZGHt+7APMM4=8mFA=w4y}ij=v^MWxm~ovopWA zr+&&*=Hcqc7(%=3(O&R!^^~d1&3hf;w4y|_y?1g<~689_wDabn96)t zlfMoAHL*>~RA&B;4;ezc4y-pRVJh?cq?#Zmu40%{A@#L*HI6Q>HQpESqNt z?OI#hD`6`0@t^!=`Qe0yDN~t(cb{=uQR1y#FHV@s{QCWlAjaHwf0n7thhvty?&r+O zFqNrx!+L+#jHMZ-GSjzg^lc|UpJ6I9`IL?LjGEW#(JWJ$?e<*iw4%i2yL_5qDs%Am zn?dxddS8~Q%&|)>F|FsE3{#o6ZeH(oZG4B@G$PAX=JIOG%vLE;?VtxTOl5YSwhn9D z(QR;+sZ8U;EumfK)tHoFDs%O>-+}mf*8y3kGTp9R=Cq>3)tg6Vn96io`Yni+=iQiP zD&xjmLc7jfJTSvl=ItKefVh3)Wm%>&7x`sQD@wdk+AqUY=H~Ce2Ju7jnOUYXhpn}Q zcHOb@{0vi>_V4ny+M9QD&N7vGx5{#-6(xSUzf*>(%%|=P5H0ULEX!18xBV=kT^Gze zCc{+b@-ZappU^bRRA!e}%biw~IOyEg8KyE5x_u7f+Wi`4naUi}db!iCqDxz6n9AIC z^5@-*jI&M=i(UX4WO zN2_L;%2amComP~1_NST|rZP|7^cjc&;|szXUGfO+n(|_m3{#n(U;Grr9*1o#VJfpU zS?;u=#Fq;yWthqwJ%q%BOFt+HsZ4uIXxA-2eo)9%rb)j~Kr}jiSqW2_A%`t@T2bQs zsm~WOmAPT=#~^Nf?Wq!`GJ{)MLc4~YH>Z%P%qaB}`=s_OOI@^?GSwAyb*#fBF!_pQU|Dn95Y!ZMoB~NelZGGL?Doy$`)5 zY9D`g2~(L(m6kiLC~^3-PK8Wm+OOlUqPYz_mN1p6{_`?JXjk|1TNg5wnK_5V+gs|F zFqJv;bG(;GMTvq%l?s{4yjqDw^B1a=FqL`beM@N9cP~{bWGa){jl}X5@6Bf_v-tI8 z&Q#>@&Ybpqd!{nu2fq)Z`f1P4XDV~n3QK6$vh(M(XDYMuN)qelkDt#}rf}ghrxhg* zU(~NXQ<)xhNh~_~&iPDb8f7h^T?Z~1*q*7(eS4GWHmLi2rZR`jTjsQ)#HZ6bwPz}G z^m}VST=8|M`AlUd&$fhiRl1;cd!{lMuORVY-96?rmAUQFWlk$fbX!!ZJyV$jr;yma z`o`y&%FLQ!3GHfd!JKwXWe&WB#Pt6Re2%Hi*^`$!ttbKi_#vh;o12l?>)Y8`rZVZu zB~Cy4y08Br!&JuIy~*3p!7g31S*9{Cp18zmMTyHYn=(vg-mUdB))+PTg)CECdR*+e{fWh(Q`=obv3UDvkSKVd4*VL1R+KpY^5zLsnFfKlc3DBnRHp5k zMTXF>8+x`*n97{ilV|R__NtsRl_~AL$Z181=I69dn9AIJ5efIj4k=TaZ~kwgA+&4O zJ4eoqadUH03nd#PT^ zROY37vQ8^XJh$=ugsIGqz4(21=iT;6naa4@^9`Y0`pp@4x*b_JVJdUhgPmNhh6SFf z%&ylqD?NPjcAlxs)m2-Ru3b{uGnM&vN^`6+y7R6HQ<+l_JHly23H(m0) z=f@eG>q&EGhj7-&^WQvcRJ;(^r6ZMj?e4=teE8X28KyGVt(}@^Mc326glV*U_Rlbt zx&FnM6Rjv=x2pNXg@sHrUOud=A++nMum2Oa_Sv*EwyMkb`(>EQ?Adosq7^0Tjcp$u zdC#Bt$Y(F>S;$moL*0`MVY~Xy;9huWViyn-x?WYtRAx%&)d}wF`Bx>M;NE>_`XL}( ztE%nzI3AjIf+0xfy0Eq3oLt%CICojk5~ea&c6gs#C6%oN)(hw1${t76;U||cmGRBO z)&^-9Ye+pc2?`VU4n*cW@zNtnvK|I8^)D@x3mvLR(EvpJmi`L_E3 z2~(NV{(GJww5wyE4JlKZ3j?ufNaKX5%&41sIISr0?7QnzrZS&@$@5ohuWg<%l{x;I ze;Y!(>Rk1H%2ejG0sDa%@Ib4Csm#*JH#)5-QQUY<%2cMfHHn+MwoaJJ+r$F@nB${bc}kRh~db-$G< zQ<;0tB(e9CMH5S!m_moSxive5*$;n`U!Ql{x70>ZRAeFe7CubKl#wOK;oh&XlRl&-e1&()=ce zB}`@B*kPvAiW0gu?k96(>x8LH_h}CsLc2b^cv8w#X4Vrt4>zPs+k~miB`4nRw4#K4 z9PYOx5~ea$I!rNycD*-pX3A9N@WMJ+#t_;?M~0~k%oq@KWSGjpnF;nx zuA&4T8KyGuT(Ga`$S{?GGh+ztq9emp2A&HDIx1$1PX%D|a1uMavhOl4rec-m;WR~mi^!;xVs182s(29=;A!&C-t z3yyX=GE8OQ%oswu=*TdYff)mWjto;7I5WYX$yJn~Bg0e%ZVL!HGE8OQ%oswu=*TdY zff)mWjto;7I5WYX$yJn~Bg0e%ZVL!HGE8OQ%oswu=*TdYff)mWjto;7I5WYX$yJn~ zBg0e%ZVL!HGE8OQ%oswu=*TdYff)mWjto;7I5WYX$yJn~Bg0e%ZVL!HGE8OQ%oswu z=*TdY!S#J0=*TdYfin~AnOsE)Ix6rHx3*brZRA5 z%vLEuM~0~k+!m}sM~0~koEbxC7abXn9AU4f2=`AhN%pknM5l}@H`36m+;pgz5&3IVJZV>#t_;?M~0~kyb};~WSGjp znMt&w1RWW!QD#BVkzpzWXC}k5LOeUfb3Qy<#DDYb5gi$(GB9JX1|1ouGH_-v^L%SX z*VDg*X;5%vn99JJp=t5g8cNu$q9emJ1I~=uD(#{p!!0axOz6lkm4P!uW8|-j5_Dwv z$jclPIx|{al0V;*LOYWSGjpnK6WR=~=vj0y;8GW#G)vMEdKDpb|Vf zxCZwhuD^mK!&C;&j3Km3&-=l_f+NFJ2F{Fmedv)N92ulCFk^6B(UD;)17{}DiV}2W zn99Iy0YOKGsZ8ykw-`dZ=*TdYff)mWjto;7I5WYX$yJn~Bg0e%ZVL!HGE8OQ%oswu z=*TdYff)mWjto;7I5WYX$yJn~Bg0e%ZVT6dBg0e%&Ws_ni;fIa8JIC3=*TdYfin~A znOsE)IxzQyKUk zo{kJt85l60jto;7m@!y`jto;7I5WYX$yJn~pOae~^H|`>FqMHbV+ie{Bg0e%W(?M# zBg0e%&P=dpaup@)$& zhN%p$zQ-DLWSGjpnaOBH2|6--r$#D{yQI;PVJZV>#t_=YYd%QuS`C~Lh9kpN2F^@E zM~3H$aV39BM~0~ke3q1s46_%QF<66+3{x36Gl^D|pd-WV1!fEgIxEPwM~0~koS8%`O3;yEDg(C#1RWWsGH_-Lp?pnUKmy(_fNE<1RWWsGH_c!(2-#(182q%+GUS+ zIxGOBg0$-)(QwZGE8OQ%oswu=*Td8ff)mWjto;7I5QcoC_zVtNeVm{ z5Oidi%D|b)XcrwBrZO;KvX-DD!&C;&Ohzk8(2-#(1Gfch(2-$c0%yh$+C@i(*$d1V z5Oidi%D|b)XhjJ+GE8OQwt%1`!!_W{7(%<~$S`|>83Tfj3{x36Glg1Ff{qMR8MrMV z2EmbGDg$T65ZXmYhS>|um=gS&fFr|H2F^^OR+OM4!&C-t3kW(gOl9EA7(%<~$S`|> z83Tfj3{x36Glg1Ff{qN66nHKm=*TdYfiq(W?V=;YBn6%e2s$!MW#G&dY8M?DrZO;K zN-RM~hN%pknL@27K}UwE4BQs1K}UwE44fH5XcrwBW-l;fK+ut4Dg$SxP%BE%kzpzW z8wLa&8KyFDW(=WSbYz&lz>EPwM~0~koSF7oQG$*PQyI7|^Krj$I5JFS;LI38yXeR; zdx04Pf{qMR88|cTwW0(a8KyFDTR_l}VJZV>#t_;?M~2x8%oq@KWSGjpnQ5;TCFsa7 zm4Vv=f{qMR88|bB&@MVM;SOdOv<5*(hN%pknf6*yf{qMR8MrMV=*TdYfiu%i3GJdI z!|VlS%yR_=bYz&yz?o^M6(#7%FqOgGVVmG;bvQCiW#G(Y^s|qS3{x2xFj@OKNJoaL z44j#aR+OM4!&C-t3*H&%$S{?GGh+ztq9eoX1!fGtGr*ByD)Zp@mor*Xf{qMR8MrMV z=*TdYfiq(W?V=;Y>;+~F2s$!MW#G(Yw4wwZ8KyEYRY1^@VJZV>#t_;?M~2x8%oq@K zWSGjpnaOBH2|6;&USP(6pd-Un2F^@ID@xFjVJZW+1q2-#rZRA5453|gWSG6ca{)m| zhN%pknT%GHpd-Un25t)oIxtNrorKu3nD44j#i_Drrqt0qUt zuRaiTWSGjpnK6WR(UD;)1MdU`9T}!FaAvYvQG)gZ&&kkpz#4F5n99JJDUowMiJUbG zjto;7m@!y`jto;7I5Sz=Gr5Ycr+*3d85|j=GH_rbH`B z(2?O9NEsRH0y72#9T}!FaAs1i zC_zVtsSMl}5Oidi%D|a1gm&EnM~2x8%oq@KWSGjpnZdl}traEc$S{?GsRDwI3{x36 zGltMEIx@^&V8(!;Bg0e%&P=KmCFsa7dx3ocf{qMR88|bkR+OM4!&C+~3!^88|a39T_GH@I4Yb zGE8M)z$A2Jn7zP^!5VaAn99JJNwuPcu8lij!jWMr182q%+C@i(*$d1VtU*VHsSKQ% zR4Yo@$3aJisSKPMLueNr8D=jqW3UDt8KyFDW>T#vVfQW_8KyFDX3XQDBg0e%227&+ z5a0UX$S{?GGh_Cy5_Dvk%D`>GR?(4RDg$T65ZXmYhS>|u7!Y)1n99JJ$!bLjIxH1WlS;mt3O(f{qMR88|bXb`h@N$CdoSk%@ClBoGatCq68h8I9CP)9T}!FaApjlU36ra%D|ZcK}UwE44j!%D@xFjiF0K@ z(2-#(182q%+GUS+Ix+1_T|MI9J9H z+C@i(sSK{~13^b7&Xw_6QG$*PQyE-!2!f6bQyDljo{kJt8F(wfkzpzW112~!Ol9EA zfS@B2=gN56Gr0<_njAq#hN%p$6$U{^hN%pk8AH&KiF0LwpOafV%#{hL44fIWRZ7s2 ziF0MJ1|1ouGH_-Lp_?hN%pk z8AE6n9T}!FaArWzk%@ChKUKB8AE6n9T}!FaArWzk%@Cw`Lc8e5 zFqMHb1A>lBoGatCq68forZR9_K+utib7c&nU36ra%D|ZcK}ROemGN3pf{sj_D+7X# z3{x36GltMEIx+ z#%mWH8KyEYV1iY%m7pWTR0hrrC(iu!x0IkG6X(ic4LUMRW#G&hLc8e5FqMHb1A>lB zoGatCq6Fr@l({lpNYIgqb7c&nU36ra%D|ZcK}ROemGN3pf{sj_D+7X#3{x36GltME zIxlBoGW7p?V=;YR0hrr2s$!x zu8h};5_DwZTp18_Wa3;ILui-%_DV-4&Xw_6QG$+4oGXJh=*YymGKSDD{pK9z%7iHf~);+~F2s$!xu1u;GT~Gf~m@5-f88|bk zR+O+?MMs8d2Aml~XqT8I*eW_Qajs0N6(z(40YOKGsSKPMLui*6F(By3FqMHblWIi? zaawR((UIZffHPwV?Gm#G1Ra?;S0>ep65{57pd%CK${0es^ekSOD-%)~I5VkMln}=V zYtWI2b7c&nU3%Ux%#{guFoQE=ULSho2S=uCt_=1r9ho>+#%o0hIx=yt42arrWSGjp znK6WR(UD;)17`*V9ho>+#%o0hIx=yt3+#?z5uDg(bHI5KgrjMKHlT$zx{ zz?tDpl;C;5_Xv(moGTL?8KyFDX0QewnK)O*)1JvyXw~EhT|3N`38@U68AE6n9T}!F zaAvRu9T}!FaAv$#l(3J3jto;7I5UROE;=$yW#G(U4LUM$u8h};5_a#>k%@C<%;TUV z6X(hV&xpwu_hFbT6H*yCGiL89K}ROel>tFVhN%pk8AE6n9T}!FaArWzk%@CR;wT*+TVM}`>-e3l|QGR$6J#(EPwM<&jd@mf)Wj!c{@1A>lBoGW7p?V=;YR0d`Y2s$!xu8h};5_Dvk z%D{60K}UwE44fH5XcrwBW-RbrK+ut4Dg$T6YZo1vI9H~~5_DwZTp6zwCFsb+xiVOT zjto;7I5UROE;=$yWnjjDpd%CK%6P3PK}ROel>tFVhN%pk8AE6n9T}!FFk?W_k%@C< zyjGN;BNOM!fWTatgsBXi8AE6n9T}!FJ6y^&=*TdYfivT^q68h8I9CP)9T}!FaApjl zUG`|FBg0e%&WzWJ5_DwZTp6rEM<&jdF@$#MD=o~GN#a}?^ZKA86X(hl=_@VFl}X}U z8S@%cf{qMR8MrOjDmpT8u8bkHi;fIa8JIC3=*YymGF~f6(2#t_;? zM~2x8%oq@KWa3;IuN5We$i%raAn3@%xiW^(E;=$yWnjjDpd%CK%HY#^Yefk1y=zFM~2x8%ouz|(UFOBWjJvro2$^O z$q{s9cs2@G1cRU>!&C;&j3MaA#JMuT&&jPF=E`K^Tp6=fO3;ysb7imw9T}!FaApjl zU36ra%D{{PK}UwE44fIS6(#7%#JMsc=*YymGKSDDIx=yt3+1_T`$t^sGp5ZXmYhN%q97!Y)1;#?W86(#7% z#JMsc=*YymGKSDDIx)%p>j!c{@gEi>LFqMHbV+ie{Bg0e%W(){AGI6eq*NPH!Wa3;I5OieXTp2@X7abX< zGB9I6(2#%o0hUKJhZ%7CCF6X(i!{p_P7 z6X(hVS9I&=ARU=FSH|lnq!M&w;#?W5K}ROel`({N(UD;)12YB$9T}!FaAv$#l%OLM z=gNSfBg0e%&Ws_ni;fIa8JIC3=*YymGF~f6(2`Ix ztNpPC9T~bZaAv$#l)&#q$1^N&TR_l}iF0KPplBoGX)RMc3266z0lg<6N0kD@xd{q9emJ1I~;g zv`eP0V5{iJ#JMu5R+NyrDIn;`FqMHbV+h;zQ4{V3crGC5$S{?GGn3+a)4wW~SlEQm zAlw!ZbY%EA;LI2Tj?!OU*xHn9z>EPwM<&jd;Z{jyD}nXGc{sQ&An3@%xiW^(E+1_T|MI9J9H z+C@i(sSL~*5Oidi%D|cNT2TV?Uy?Xi1_T`$rZRA5453|gWSGjpi~&JMhN%pk8Lt&3 z=*YymG9c*4#JMtt&@MVMOl4rkfS@B2=gN4kC_zUi&XoZ{M~0~koEbxC7abXuhq*H8sC~j*8AE6n9T}!FFk`R=9T}!FaAv$#l(3J3jto;7I5UROE;=$yWnji& z4LUM$u8h};5_a#>k%@C<%;TUV6X(hl={^i|WzslT#_U}~z>$e_Ww2FrWSGjpnK1-S znp_th8KyEYV?fZ6iF0MVR+OM46X(i+pd%CK${50S>2HJctDUw0)@4Djt7|O4b^1m4 zobb3_!aelEZsFhW;EpKq|K~kS@m=(=+NT7f{|U8nM5ri%G(6B{uFSX9y9HveA@vNQ zUC7c&@E)dE@82;Y|YU(Em5*e(#KR62BlR>~oK8Np6IA0(BC z{|;T;8tyCpm4X6p4GC_YR>~oK8L<(Mm<0EL67k=mi+h!8aBtvO5%wwx?q#i%L-;bH z%2|5^;@dyE8Y0r6i^mh!;PHiD!t-kfqG_Fz7igs%!j}${^am*``_}v%R8R7X*LMwXY+oN3xT?6+sE#mw+T&rQ$vuo(zRf5-J#5&Ska>hw z$|0C!=MlUbB;F@AT(uGJXBw_{!QSN+D|v+O6Wv$w-{lZmQG!>y#QVVJt)YZ=>DJn# zgjby8wmpk0L*hMCxA8c14JCM$NW6dQHnvK;;uiACn><1*O5mQUj^8+N&(v)Y+7%x; zue`}4w4wyBH;MO2-3FmuaUb%^n>->OSK;`Vu60WZJ-$$YnaSQ$5AGsd8 z+7)SD36r-~T2UhIX^$&Nwn1o@?ge{XX+?>6#PFJ0!E8Wj=Rg;_Zc36_Tklt<8bz&UnLw+FL19L|_~cn7(EbN)vj zff+0g$%uzv5_}RQ7#<$THnvK)ga%3;;bC~>t)WExcj%(`!K4B1MjoLRCF0|Y?vn1S z_-Ml;)JI+mhDDr8lD7seAm&c6cN`|_xHy9+TtSX=mb`8}kKncCxr!3>qL{?-*|g7~ z657RU&T*EL*Nx{9T2Ue%J)DWO4MMwk%{k6;^1AUnLieKXUEPQFacD(}_&m|R$y-AS z?b0LEuA$qjkAv5><4h{AP0w3HD@w%I2WM1mgU~Ks*N!u(yf!_L(25e6iRI#~t!)t6 z#p~K}CY9Hw=Mgj`k+{=tbeQMmke_?FivRF6s6<@P!$QnkBR*@KedM&O;`fqx^o94R zc(i-ibpLRxl!&i1&sUm#&ULG_OW&0&p|4tfbwz?Rs`A#*iW0O@kblr9*#@Cq@!gIy zs`3b}C_$?RIS$R3Z4la}d&E9+ttdfD7I_p6pS(4c&@MgR>>Bai(!(Qjn2F?&RC@Sc zx$nN=zn0K%$Vy<^kwXUQVRGed6=oEd*c>*7-IkMkt;!m45_7u`<1sSuFr?k`uHrN6(!<&?(bWrgm&rk zWY_4`ZlUYdYMeh{#4bhp`?K|pi(IWs#`(hv$!$Dx&Yj0GYdC7k=3w}x(Sd~fIUvT&D$|NY37h@U>3 zOP05W?knxWBvgm%6Fu(okVj}miTEkXxny}ndOb69O2oA}_cd<~-MiYQ z&y#&VbieanCA>No_ZazyTcrdh1-m#~cpF=#UHZOK?pB5O41F(&>v?XWCA6Xh?=}?Y zaBqXquDFFBcXP=jw4wy>HpJ`OamS#%_gy8lD?W1GZzgXIttb&66Ys8+M`%R}-fbw( z;m+GCCA2F(Cf;2sZw;*|5#Jv&4XCd)`D z{r%US656G&8@q;9l!(8tIE627Un!wo`i^SX(9d)I#L@j`39Tp*pBvsKDsS&9ph`5tDTna9Dgu*9eeXcDsl37~5&s>!kwNSaw+MvR_4H`PixgvX{> zB2gm#J9Np`re>?0R>~o`g&^dS8$z}!m3;_8_O8=PIRy7Kh}<*S>D29ul#sof#%D9m zE6N=uecs%+NGnRn5sE!=!;@u4;-oeiLugn0H;+&d`<}76l+U^Q_k|1MeSJNzSrQ`m z?{G~2Pa<^1yP=j{w_(=UdVj&bP2#_?6;qq&9SrRnS}BJJ>8vGmb$PVBN`!Y-4OeosKIev`g=-Y>9Y>$dFj;Ju~CuE9Y@&MG1SaNqq*D&@SDFcB}MWta{JXcyH5i z-G(LfF0_#d*Mr2r6s|w9L^*#q+)cIOHMA1{9SFTgr(Ht{?TY^n*M?X^D@w$Brg~lv zVhMe2^?tv4^jJbGi>GU%>sdl8e58sA?TQm0!nNs^(7mX8SNEYMw4y|Oo`T_1F`-?0gjzzkS06{55fQF`w}e)d z(0NrA6WSH0N`&j*Euj@9bnaHggm%TL65;xHOT@Wk!Jv#Y!#sV+xToVxBz>K0MTxkc zFPkz}5usfbznAEHR6N=}jXho4J`SxY5npM(Yz|gMTcut4u4LEHSFOGtbzYSvw4y|u z1rw~5iV5w~c~zFsiV|_AO|Wk&CbUcUp(V7UM4ZhNETW1D?b74T67k*A({77%mpq*^ z{XTCAttb&ED*3WWP5PYc93-8)r0?2x4Xr4llc6dmw5#Gz1Kr-Zg`O6gK0dpKR+NY{ zn0(o6Cw=5fXjlCI!!IPehCUxk>mIR$R+P}mP!$u}rO%Tku05w|DU+YuZ}<&Y8gHE- z`o{^)OPTz9x?N@ao3mIeO2mKrzx_%r)-`ay2i}c4+_OPxyH#3IBF<_Jca^A^(5^_w znXLK@#_5-yX1~t;jgvQh*+fqzw4#L00JdADgm%RVqPTxFCzI+L`YEF`CoBHM(TWl} zA=9p*gm%R_M!~qUgjST$Sz?yZy{mJc;@WXilRk2tMq1AF)9^f1yoM4wpVbn&z43k5 z(ZAHkX9=w+5kDE?TrzzeN@!P{gz9;h2fKz=l!%{jaW0vzp?fi|=V;dHUbky#MG2kH zS}~zr`aD@e_q)#F)wM056(w|1aK(gn>Fd!F`dZW1U|i3aO(532s}&`54!2!H3GIqo z=y^96OK3$2ovK|ipwz^CbTO)rf_#9OK3$2ox@!* zpdRoqi7LezSyD zl!(twxJy*Ugm&5I19nZwCScbTr2-r1&fL&tN*-{8mu0?tgaR>~ph&46Gha|75l zhKO|N;?{5t{*_?Y1cF}8 z&m12IpGhU+ze5*~4z9sx759L^(Lv%H94%T=f=3{Ta75z%yC3crh+TI()ezbh|4jo1 zYv6kDBCdfeo)*AY;j~3sDY+v&9QpQW{~ts+^5JZh!n7&7$EjHZSAzNIvCv=Pzr%lF zkA!<0@=k_!tF%%M5$G5U>-S7H*#3P^nPu?0@Q6m1OaQ9ogh7#JPuT4v6MG06p z;V!$pGi}9$cIhj)?ERMSyL>mrHQSt`LfggTN@-3zp_P*RH?Ne(8hnS&5pWDRYljAp z$JOzii4&&NMEZXa+J&p`IT?rsPu?2kY*qNXxQd-~W$5YT5xVU#EjUpnOheK2?Bmdi z5^ys(H-+|4`D=tN(Jov&%vmYCW;>6-mCI!lPB7^tcG1nr{kt3jSN4bLJe;NjdmzmD z;q)F{GsVdcVUB}+99mH#J~#An^0rC|?ZTB+oCOi)IM_9`qC`9v=;P$Ap@eqf$|}x+ z2y-0l8oGbt-lgHRjeVv2U5WT?(x}SYDkZc_j|IC`y1n{1aJ?7jO@vtyme7h4@o1-y zlebk$Xcw*{*39Tp**Q1YFIGL2!@8=QvDHA^p=*swtKXJ68M0{tUE0ec|650iag7Z1U zbRzpWw4y|OC!#Bpw}$TB__<40CiggKd6ZAkmB~E^G+(^_CA(ExiF-N_aqrTV$y-CW zH@@%EmGS!c>>658B7QQ^mC0K}3GKqQ^_;LuS0<0piW2b?j;>4|5ud@Z7vp+#W&Yv5 zQX;NRS0--_-MiWq|Nrnj*?pz^9llAJ@5_0-`j;%B6(!(>gxSKJ7+f)-UHW>ogud4F zH5k{UE0ec|R+NCV5hiqV9=BaX3GIqoNLMD0(25f94SaNE^4_nM(60E%!)#`|Ra#LZ zKBh2<+!9(*0!D<7u1wxmDWP5QF@;Iwb`7m45#P1x%H*w~gm%R(40FZp8v4qKzp3cT zczvZ=LMuwdUov!M@}5B@v`dd^yM|Vjh`(g$%H*w~gm&pWs$D}r@APv}_nRfOqC|Xd z!bJ6o3GK4a2OOCqp8cRR!z(p-&YM?Tz>(qoB|V*)`2Pos0Qa-Jkarm^b7r)nM7-Ce zr}KdOFT;KyK^sB|?UFlHf`B6v2pSh!DTfGV4DRq(d4=N|v^tcC{|;Sp|4gg_ME75zH7&U6_4XAn42}5&s>#`p#g|KvM&U5 z%A6VfTk+qaizXExN7+#VMFRzf(|9-4Qrz1# zWhz5U!ak0;uY!3L2~Qg){v}Tv!V=~DUEWP~8*Aw5@!x^KJv!5PXVttll+dpDZ%>!P zZk1M)fFqMKm7y7734Lzk5$(OHgt&~HAeONJ}dm8uUO_|EjJF$dTl=z>|M|jqh z(0ypv(25dqZQe&XZ>yBhEgo41A%+NH1HutvyO_`VARCBsyP*HyzODP$_c>!0Jl9sg|!STz}@GV}m2l_tYf zhF7rvGeWyy)nu5;@XC0*Mmbv*wgm1>hN%p%G`ECqJEou%GL@kXq3e}Pgukl=RE37P``zP*Q$LFBp zeWev8;&#R~H z8cJwa#qSLIjuVe|PXk8(QpIa15npMZue6E@?W*|QM_;x2dW?ko`}>tvl)x;QgsBX# zG`3r%gm%UEO2>C_OK3$2TvMGemEjfB6%*R^&-Shon9Y-6D#L5K?Hc;Gv`ddSOT>3k zPe%ieOnas>bWQB{d3>|{>r+iDO2Cn6&s2sEid_Q+O8Yopi6#xZ9J}-#!xCCiBChAk zwotc93DYH?5_xOL_Qoyrv_#UsREFM3#f0tJ`gyBhE`6Tt8gOJ1rZV(d@H>jXOvCR%I5OcbX*6Rjp%o?Kzr*iOOXwPy zgqkpw;WfQVTS6;JU{-6wREF2|R!nGDq&br{kANeSFqPpI%$WO|#EHPAaAXpuGPE!3 z8d^~TGk}vg9e5jrcEOQJn9A@ve!GT#%EV6t$Ip+7KXJ68M0{s({3Nn#D4|`jEfS_O zbSW&M6(!<3k^B4mmG0g6Dar{@rEzUeYRX$95{}PD+|!QFf&L}CRa#LZ?p^oyy{p?B z-*-8^jCRmJc;rgNPX^8<%iFv9x3mk6Ou|%#SLNHsp%o?KCmiRJ<*lK6F|Nm{s{e3b zDG}Fpf8Q$IyV|AClYJbz-(jF6alY?A+$tsDmLzeuaNfSstfIp@3Q%*?%Wr`&TUw?PRBJ5_rqozUHfpjIk*RAfwUgAx*{Oi__BIY9{tJBNEH zozUHfpjIkVRAfwUgAx*{*VYN$eF$nL52IoP1{#mv|@ z6TarH@8@*_jn=;v0h9io;tg~HjR?ieP(s3D9h~k&K{%n984}d8hzK9mbRsRBNRbvD zNe?2$X5g$8#b$JfbnRLe+2Mb0MU3bK8kHkOjC3SDh!kUjGhY;A(jn5dYgvSf|Gg9W z;xiKqkz$u{mQY3{+O_QN@L#f4H5(Qq<6bFdh7uBXXNvHcmRikX zWSmgU3<+wbYmaI1UCUvWT;FV4e21UasF(oW`8w-GXV)kuBqt~#!FxI`x@xwRBR5_Koy~e{O?y!n#V=9yyW|l#tL_ zFFLzMu@uz=wRCce_K*~DkrNi#qSIia;u&;iiS6A)#ZRQ`pzEBVgoI8b(aAT859vwx z?aI83TDR|37z$z-4}fyt}_|5Z=~1j4our{%8GU`PGdZ*?qc8lGkz2bm`gSTOC?SzrQzsJjA*iK%#oCq8 z7go6qN=T%;C+O~}Ca9&X#@dz97gjmJT4e3A4s(JM5~-bHcMFoB7Vps92K{9@lsQ?u zGWzZ-CnzD2o{!M|e2}1)ve#=@M&Fa=HYg#X(_yqLqwkcf32G@TzIJ8w&1z04i@$bd z^hL4G1JJIFzFyE6LHxSF6=>g{yKS3yuhLgx=?S4Lk<=Qc=Ci*=Y2l#tN* z4BC~^H{I0)wRpefMCvW0Vl;FjjCN%dYr=7GPEbNZr_pFvMlmQkp%Y=WE2CJ9q@^=# z+V3cTU*!b*a}vp(PT47Jkf2ue+kpNi52HL}`Esu)A)(V@v@4^ylWKxm>6d(-kP~bV z+GF{0f)WzRUg-9U1hv>sxec8mqg@%rvv8iNGg1^QqsW+?po9cxtT{m&I_pKdGWw>M zbWTu0LT3)VYP&M}rnj1)R-%LK<%G^J(XNcXN7k7P+Lh7Qa|06-%f&B$-~%PSA25PEG%e##wRT=2PGuZOeS>Cyhu=s_jGQ95)x@96S`+b zB&fw6HMha{9p8hjx16AaL~5JZ-R2~ymAA)w&(HSNk5hjC-I3iEyU2F|F1=<{JzYm# z-!SWE{`Z@%Ub${7^k2Nsi8Yu0-UuZ&HwwHw<4kF-}``$*deKp9L=TCxS};)Pj@3 zZ&p1s91w?sH<$)AVQzCJ0eGW6uo>%TlHy!-0U+t*RowHk?}<&s3(_w#@A+h_e ztA|N@pAtX)=9Iz)32LS5&`nT6;*y<)!^PK~8drVvw}lN7)JoT(o1laQYdtSH32LS5 z)E;{u&^krwq*rR&g5P(tFP`#m^x_%Wx%DWAT)ut9=a={j^1 zl#n=nhbM+MdElhD+^)YUY>=QY=3!Q2V%X@|mHH6WN_6b@iV_mL|7QE}yB|#oH%?fk zut9=aiH_Y~Q9^?6;JoA{sFmp0?G+^?(sg>D>zq67<5&#u2)-n(>zq67%UcX@9bbi7 z$#u@12s`(#P3X(jj7Slcis3av=iG^~=**0u7UDdO&^dP^EQWW4k{*PjL5zq3gcJ7_MLFY(% z5Q@%i5$&koj7YR=8QqYLj#u{VcD#bb?U6|3K=iW8(IL{cYgsM$-#fMIHd5_&Bt3}K z9y;evUZoc75b1Ya%UaX_-nvV4&YcL|C6th`J2C36)cxi$yiQmQZ$?lnUHcuHeN9!j z7)AeD#Ntoecewwq&cD;wA{NPNzm6~B>y)Ht!ijYKUu;-ZE6b zZXY7iu4PezL;708Vt5OJk{*QOhYP}DDu+@GZ~c*<+&7eBc{P_MNy`G2x_I0D?+*;C?R3-qeCgmv=2e8RELV~Er@hq`Tb+Ds6+N0kz#7=yx;Qn zpoB#7P!ZC-ZTMYHtwaae%WY6XBGt6ww)+s&VlCu0C?S#V7{$03Hb_vbt9E_#YB9WZ z`%<=Hdmf4mQ9r2u+>-3yBP?L$z@z7cPvsNdGz-nkRmYN@Ui_1mWfS&Jl6 z+bHU{@QMVr*s}TEPJdYr`*OXJqJE2VP(mWz?TY#>ydps@`y#%PqJ9e-l#sAUtC=b4 zx3EEiS{8NFNKwCq4U37InWBD!#bC`$QNIH|A0(1JMg10DvEHdw-7~PqNq4)Veh2i5 zM0(N`_1niQYE}0>d}{eTCPGoag$+tbSgcedMg8_6sFnIkMg0~8B_u57tC6C9`w-M( zJLS&@B_u2=ZDxx4Eo_jW7Vo#*hDCZ_pCWRD&bCVtxdZkLBrMkUdiy#>5xIp|>=`mG zyjOCs(i=yyuOShNMYiANc%E-gN=PIR6^mSWMH{5)ZSGYrnd6B?&R%cdmngorut9=a zto6c1s}0=Wq@`Ho0ZUFI*;6cX;T21pYt5POPhQ&uU>}wIljMgpMtzln_C=RY}(RB^msaD)wVS`$v zE%L2lUyCRvt{`YVJ++D%^|Q(TdpSs?enl~(MLAeD@sz^DE_=& z-7`=^BGtO$&kL_eP|IRs8}<#0qGbz$5)!G_Lw9?Spq52vHtZV~Mavd8sFmt1sOPLE zC?S!0*PuQ)uU!(6SU#$-nK$-YrZ zW3ABJN^4QOB&e0Vjg{qa35jGc%ER0%N=T&Z*zFZ1B($!pb!uD9Eo_jWmR4!Cs%~qu z1)+6MMK#)bWkc(eifXiV#rAd3bzY97TOZq0>yuhTww0Ytwc4zx zMq4A;q?(|XR@1bGY%4~a=7iP`wJK{XgPUmeS5b{N*KJ>G^`Nk!RT`}>+uF>gT20Zq zxUHe|@rs`GAYykpNTh4m(psgW8f{gw@QM-=seD1@%S)b0>m_8#wNjxqa%EA=39W%? z)!EjuHq~mHR-J9FY*Wp+w6<(BnxUMaghXmh?FTD}8MSGB-mgZ<$ld-u~VMA*!T6MOyl1;UGqg7{H zn;GyKB$4dJZm&|Sc`rk)>b``1RJz+eCo6v`Z$U~(q$e%vNvkHP#a<~V_|)?0N<>gU zmJ^ha(CUp=oo&^nXb%$9O1)iB|CrmLgoM_YwCZfDM}-X%)M6dxHYg#X)ikX-+xk}F z6$xtbe#>p7-ZHAU)Vi*s8g12fV~($Lf)Wy1*Hu)bazo~XR!z0CZEK<%CoQdTZ_Hjh zCnzD2>}e&sut9=a)o%m(n>>v2kmbw0qJ)IjbrscUE4YPMB&e1C-aTU(v22bWKd8)$ zm~#ZJ*lFcXIUIAZC?SD4LqX7n=Cg_)wApHAFSo(pC82q_;sb>+rUQR@k6~gw~g|LT{@_1wrenzY6LH z>1|$eN=T$0HFWpXB&elzM6I{miecduB_z_DLEjt{1WT@UL|X+8wn{j}I?T&K2??zu z+WM}=TaGJikf4^Q)WgX@v zr-Vcr+lB72C<$t%T91`?qDx4mv0dmMC-S$bmD(n%HS=;%LL!arLiae41hrDz*tvma zn^Qs}J^$LnE4(5>t<;*ayUi&fk)9jveHAuHP^p{yk8R? z)Zm~W!u(Z3xX07>1ht?U2_{GsKs|;PEbN3J^!J*XCOhX zRKC#toKuoK3@R;usoJX^MCcv?@VC;nYvm(=`mgu(Z=+5;{HdnJ@ip}=pCb0sb<}m7 z`YHeW?%(^Rjbv8(U_U3OAN^31k{(2C5lcLIkQ1NyT+E0>yOzZ!x(&rP)N04B`9mk} zoq1W4k{(2C5f;tZ)Ox!j59tZZWKoAri*^i(DXi5vDpU9z^UT9j8Sor ziafOF!l<}JMF^(rpzEBVgamC@6VyuALEh#BB_yiLVey(#F`SAvOV?4?Z*4s`{_2w_ zhi@(XuJwtmD@uA0u|JV$*J2&!HYn*qMAdpVk!aUqP1kA`F&Wk7idD48$f#&ZMboA0 zsB4RbjEbmK3}a4E(u0VVgiBUl@!I(I`lrU7-uml+Hb_`BV^kcZA`+{;qE@1V?BxU{ zB+_;0wm}IAwtsGe1hvw&-)|OmHsb}~wNzAK>Z!d)wrIAd#o9&1u(1d4Nd)!bBsP0* zrRHPzO^mg5x3IgUhYcsFmFOUQIl*@39b*xbQE``wVay4O_G?-!VpPPQMHey zPE2>dz0P&whvyuoj1C=14?<6t=^lOVxBWf%=vQB8KDqsE4UJ^}a_v(gT}NH7KKq@9 zvJ|{LqA%#G2x_J4&`nT6V)vas9hGh2=J^&YydpuZbRD`0N=Q7j=H^iuE53KMVwYGB z64Xl9p_`zD1ZzFFL4sQ8I{8TdfH84_UpU)IAP6eTsZS?Re$}8H-ZBUY~otV7UYCg)i_ikm_U^z%o zD_w_ff)Wz{H`h|}%pdWANt#-?!hk2V{cE>q& zwjkSJzY9-@JH9wJ{NI8)J(|Sd&OSG41TfEPo)<@buxGjX?lKodjcPtWc{%HSNKnEz z4&PllL9ggZx{lpmQ9|O7mrwGM%&4^$eMYZHP%B->Zh{gL=k9ZQR1Sz+UihG}L4sQ8 zI(8G3kVv&2RO@*;NKlLIloOPYNbMB5TaW~`*qXH(#wEj$G||pYj0T$7xMY};9z?Wp zi4ho=WJID}3!?!eFfJLUqz4ggTw(;qB^i-u*TP%P2#iaHDd|BdGldbh7UR#LR$6Q| z#aCD~k4@K6*XJI5LVWz0vEhkDmHmMPB|V7PpGdT8*;1nOmuR&jCn)JbC>K^ABGImuyoy>w$!$>5gXmEX5-e@15oNRLT~{t4!Fuzx z7;kf}H~jnahsQnd9TT6Lc4OA&yccr9Rt0=bM)QALfAKXL&HvN2ug&BHB_wFOnxIy? z4)Qi9C?Qc@4!n!B7SkS)#ospkTAayaVvGYcD(^dMq?BGInJI?T&KNe@Cfy$Y{L zq-)n=P5WBRh{n5Go3ZtmM#^B-zE;j6t)DbfmMgPit2Z5jl0=hGW~)9#qFu{YJsP&c zqP$VP32G@HmDXY^2ujkm6T98@P~(-wPKoDzY+7N11hvw2=q4y3!S>JViUhUNbWJID}E3Nfu4bTYea{-D)9)!h1)iE*6?Tlih4=mBY^UmA>XEt~sm=O=3Zp4;GWC3`{kstHPZ5TV-! ziFEB+w(6mMoT!zH+$&0Y5TQSjXxFmU8;yOUR$y`)l=L8c#i*J{v}@V=lE!vXs}(sx zNe{wTM|_>c%HNvVV|BTKRp*ASNchM=Gy9yNqz4hZiR6`ApL><*@%wL{64p5IuMK*e z+n|Jmt;J}J;;SIl1hoaP(mVIr@FFr67So!dSI&%zDA zgvJa}s|vXd64Xl9p_|~{&ga8cR32G%e$X-rRLLyzKa;)=});RGS$G)g>Nj-gEqI*f#`o1Ktw(1K0_x--2 zHh=e&7IE-JFVrdNLBtl({D1p;@&S@nh}Y1EgMU?jn+u!p!*MX;?T7()YzvZ=|T9Y#=qq7v5!_kSX$Pb ztrpZZlF=+bCn)Jb=&P4LM50~G))(p;muQxs+n}Tep)XSU5Q%mzTVL?3*;;SNZBWvK z(6=~!h(x=VtuFZ>V#*s){NM{XXp@=^dR(o zNkLeT9MYE@8vE$lR}XAn?isr^1J7+x(u2_V69tjHa_c{sa$eYV{Zqmb!>dGko7fmli+fCc-Rg=2B_z@>>1&aK zpoB!a*0&}_IVd5KYDC{?^dYFlI?T&K35isP`m(05L4sPW>D&fum-UveLuKu{gan`F z+y;M(TKQ9pb2GG?5i~9_zqLlDYhPo)nH_cyu9VK^czXK5!<6(ObWVp6IR7Ifa5jhb zjoh}qv5mkPBidc+NO}-H8uxV)f8%J~#8w{sG!Ly9&?}ZNCv3((l)e_x>|NLTT12Y_ zL;CJjbM~B|qz9qzOZpIrcCGXOzFb&i{DiRMs|#AmZM~;cjviW3TGa$4>DmcfC-L(? zw7!wsAVIBktuImvf)Wy}_1p#tYNcy^ky6;8ghbwg_9chcm3?0lfAHn|h8{caw0OXN zw`MKKmi3jD4q@vdL+Ps!tq=^QuTa|8`ohCnkT#N*OGwamH9@U(9pr6JP(q@*95!!l zpIxF+lCJd)OI+v&PYlg9a#FZ%nr1942PHj-*q=zWYq1V<8X6j64Xl9zVhYkBwo8(H=%@t&E$P7 zp&4;bq`uwza9ionsT96$!alzz5%iuQVXGb?eW_x7iGBOg@ru7itwie!h=QPm#Fg7m z3h%CdW<2+X`3iz1XKB;5zAq_CP6-KHS@APQv<{J%g9NqGwXcHY1SKR=IYM_iNKmV~ zuFin<~}E!KLihV>G~<7kZQF*umf2dq+rY`vsONe?2}dWjKOFUg2RyB1a{ zjKF$Hlad}pu=NrnuwIf8iFPfF!i~UsiDG`d4aqrXMyg{BztJLpec74tMya!^8o_2#=7=3DEX z`|$k_Smur~@z0;SD{FJ!3prtLUtdYld)CG|zH+1YY`WGyjo6||B|Ql3E)`yp zNY}2#n)Wfzu-Zc-nvLzNSgrNwEp6{^e~0TWl>V-rCTlx=>01ykA(5`NgH;f$AJ(*u zl6*}@Bc0p^B|Ql36%_>iowDc!VVMiK-kVx05 z9QvkKwX4yFz2|&QMsGB}acp$qYchJf`MyDipoB!a_P1S5u%+07HoEZfl|~5F1hvw& zc4Z2J5)w8Z@o|Yp2)PXs)JoUdT`CAlNTfQ{4ptw6TCDZlD@sVDTGzf>VS@y<*fzD= z5r-`5Pt=|Z>^$=F8@EJ_OCEY>iTZ<2-|5#=Utg@A{vP!ATJ5LXE#buaAK$4>xP-(v zZo1Fur5{ti*X747?Zit9?~oDHx?+PzM1+x(7BFJLQKOu=`5)ViP||~lEn(u0UCV((|ya$?&%hcY73u65$Q@3;;7 z*V<#Jxz=rY_1Z=wl=L8Ci`eS5jhrwtBNFXe=1o&|WxrxJ%o``nyAeuy5V1vAiJf@u z=v6Wz(XM5+>Nc!4%!bvf6IRP3l=L8Ci?Eh+!dfyT675=cceo8}RkQKp!aF!&cgqMR zBcriTFP0J1O4p%9{O*n;M%2SCwcfbq^jXblSwZ8?A77w8<=K&F zCxFH8%(GB&x0B#=K;kp6+!QVAX*}qJMeV+-BB+&q$)B{G*yxILqR#WOfAv3IM_pfW z(X^-xv8y(3wUW~YB|V7PO|Trvt03Q5Be@MqNIdq!jZt}E_qbW-dC@Bp)JpXhRMR;z z?y{?*Wzdb6?eIicnRUOp*DLLk_b5jyxl2f-UkduA+y)71u?};B{-!bo-7zd* zPEbN(oB)L2?^S+Ca9I#CU&uZPI-lb?4_^QNq?tzZ7&YR1?(V zla>>dka+&K-$!L{J?FuH6*fpvi_fF?x7PA*YuHYHZ|an>yWeSQ+~98j_0H_IbK>Sl zE{n?d`sTOK4{QEuT2#K*tv8$!V)KHie6P3sP~$7>(>pduP;1PSS48D|z3bic3*x!! zrbOj?eevPR;r(mRi^}(U{J73_&~ei@yukRf(tsq#7tX zB$B-#5331kRlg1BZ}Kq8LzXYMK?#W~KRY=p-|H)XE=x{=TIui6{w>PE_8`p~$-Sb4 zM6wsUy&^#^wo`6{y;|yhg8HlK9*zdP6 z2>P3z^Pv8N<*P0^iPRH??jDZ6MXfFOe>5sj>JLu2vha!$5~)WG-J_*%p8IxGPT99c z{t%8H_phj&vd{eP_u(s7J!;u6$A^{9Ep1Rj;`j5t5|vZ-#Y?9bUXeKKmB*uUv2Hc) zszBR$T~R{fy~F<=m5X)NNmmy(NKh+Y_F+^m*3aB~T|rPnV!ofg5S5Gd-xpoehoIIj zdwis+T&zET^oD|9y{8di&}fqFl$V?m5^3BOy2ptmsFi9xR<@u^NThLB=pMuIx2Toc zCaN{_a!^7djk`kk7>)$BQrpDtHm8I{>XkzG7>)$BQftQUHm8I{dNxCM4@ZJp)z1ed zBvQ+U?&q8YwfLmv?ZNvs(LqmY^}S08iS*0|^%A)a64YAu>5ny)i*@lA8wEiLiS#rF z^-8%764Xk4eyn^OxP(M{{zG@qz~7=)DqrY+&iS55@2jXa2fm5&a!}HPs4j=U@91Hw zkx*H?E+LVZLu)0q+K+v8`DVa1&;cNUqAiE=FOIc zwpXU*o=B^6{k2V+8=SwT|NW^=>jgm@{M{YaJ;c48F<)te5)vp!VS@y_=dROiOt{al z5Bblk%^SCQ)33jA#tMZEN=O`QA>^|0{Y{tZLs0AP=az6{moRTZP(s3f+X?$yAA(xD zer7c%o;>K`qU4m2u+lqWW$Qyw>$m5u=fo1DuPzAIJKKYF-X4^Y&@-vp)iYX6P^;Q2 zN_r93UwL6+gGBpUT4y}Ep?h`Df#(+lB_#H~cmpTaK1P{BTK~0r9}?7hc#q(Op8cGl zgv3H$+hhQOT2GGO%!&7x*u1b|&zMW}%vn$4*XnuNW%|frpRFbWem7W;;Iw*1EsN=Tp|>qAfr z{YpVlLIOQsLA2XIEl9fkceQ3-4oXP;cN_XGYT+$W*r0?2-d*+FE9>*T-gSS?d-+fN zdXGnk>PH@UwO`BYoZ#=`9aXQkK?w=GMGG4wsD<}@K~O@1cT8Rm64b)zqp(2<3EtDW z4HDFU^_d&PF97RJ6s$tmec*xN0)L85bQTK1mua;S&M35;>; z7%giI?;~W5=W~J*5*P>fA*hwl6IxbUBLGTB*mZm4+-<`p@|Ri|Ef)kOBrvA#Lr}|V zI_fU5c}YRoo#+x9Q>)+gYdy*K6!^7`sSAP<5*p{GF?An;TJ|(MVPooopoE0=5>Dtz z&fA;>wXElJ!p79yePTyK!b{OkEI^kg)fO6Y4E;8ziV@;|C|yTjT^K zBy7Ag06{GqojGA+>cWQRt-7n#k67R2*XpavHB6YVxo3(~9h-_@GE2}ww>Myd&F z;k{DWpo9e8c11a;g|}L>nxKRP-n)ej64b)TpdctA!FI~)iUhSVUMXx)LZZ6ONl?p1 z&VHAu?Q^dvA)&iQy=Z@eTK4{PLj6E)qcc{sw^--e)|0CVN=Vpv-fh^tt*}9YS}b4g zmGuU7l~8YC>#6-(Z%gYL{95nCoS=k+y(OH`8?~CCmer~g-S1jTdJ!-Fbm_tdiT1U$ zEF#wnN_r9IVa&ZE(Y}@zYM~%7o5=1f%oB>cgc9CY zT2oZX^;XEeB0(*ACc-=|2uet(j{ZAQYKgG=D@raO+meEqs=r$c_aO}KXqmU(<~_?n zNry0d{JU3IYedH1qL!Wud1WnG)D9B>DK9xCB<#)LME59z z1hwpa<%HhexeZE4Xhx|P)MzRvIBw&ZT6c#CJ!LsT2?^bSBJ@;O6Vy_ziqKP*6O{BK z)DKh>ZCYA-T4lrT*j00a5)$eW60u4(L9I5erz|HZ=|$+Nt|r>Fv``BL!4e3T4N6Gh3GPEsOP;B&%+rFPgamq`K189lnrvA86(zS)btF0Q#Hu3nF3w9%!p`~V zXqmU(<~_>+$sEG$;qNUgou0ZQp_ZNtd1WnGl$;V0diF%v6W52JmbIo6-79yL^dx$% zy>@=9Lz@;xfQ46-kiht{4?!)AEDM4X5*RJ_A*hA%d_hn`0%Q0-1hp`;C_VvofDLh*m?72*!BL2 zVUx|~FKm#Y7Cp>u(BIV;zCQftsx!lF+tvp3io~Wn&Ir$c@ysyalz02I2etM%0wdJz4Gu<|I}C^=w8sjc{wN{@!BregsWbk5Vk$(`91`-cAs%| zc<=ZLq4wtA3xbjdm%S=%H}8b-`ga~1&?^#G|LV$c?33feRhR4i!MlXzpw_pKxgxwb zW_(!Tfrko$lJ_3DEPQLR@!_Z~{xYCfBrXV-hWp2#9^Se3kA)3-MXepD{3cwy`03%? zRqrSWO1|*Uv@m=2xUl?7vj+5vghkziMeZLL-q~|jVS`>#Yu>r0h5vW@xUl;QEVIM7aPxg51A0Z`)_pDscP~6HtUaIJ=T$98t&7gMIP7}QFT*)s(3i_3DEZl~ z7lk`c`(;?@=otfgMPlDKFAS?}{mXE?e=kZKtSf45x$1@Cn0bF0{`LIt3a{>7a&lN^ z#W7)_#m^1Tyn9YqVCgYond?0ArQ#VRL3h^QO>+_5WYky3UFSJ2|TKaoCB0ncsC#!w^g7D{AW5c&Uebs>NL1MmB z&JP>@Y;1U7H^pXDc||RY1`JpK&)Bf}8H$M`LCLOPnG)Xl)Yx$BI=>mvD-yRqe_r^q z#diMgZpB*C2J4Di8~*gX@Y^TGglG0s)D{U!rhekQu;h(n!Y4j@@qk{DSaSNgVa${< zVf*v7cSjraidrXbdu~|rgfZcSAw?XLpybuRPYze?IVN2F(3AnaBC+Rjlf$m{G2!vU z72!r3^om;f-Ttv(ec3ZpJofl19J@tJPFu5vl=7NU%(HCX$VFMX2rB=F{e1s=mQ1maS!_S=l#CIl)#V zvHC}sukX3tS>e0q=*>wRB&e0QIf>V1ezd;LmJ`FTFPs^!e0u)+?7vS8i(lLhIWC^p7?sW%+WiC?RqGqKnpNet%M!b&2AKD+eq&iPcViEPQf-3E?O9 zX2`vwC)8Tt^5?^!-kK0L-us$@nCrcF!pAo{Gu*z?j4*nY55v}z&J16>;JN|5BJugv z=B^+1>Y3qRpVBCUC8t-^;@y)I^mp&!e}*0QKO;=9{eD2NNPP4!Z-nLl?~L$2=U>~$ zD{8SuYPBC7^p-ulwc20y{noJ7D)c;Sg+kZrOLYCGQ$OcV)bNd;h&e$C39YP%)=En? zL9Nr5T*sgJ{cc&LAcogl$)CaDRUU0T^W12E250>3)rMAxWW$`dT^W{xl8jht6@MNt znes2&)vqGnf)+i@2}(%3G-VBcYM;J+?xGwds8wC^iw>N-uBY}N*Q}S7cJrO*s_Uu! z>8Le|a!|rr(6yf0?z*Cl33o48*He4`&wrZP%S+DRCGqxI3)S`19ykBVg;yk~b@`Qx z*Y(ss{_V*HF?*%u>UwI|UM@CXJa+lIp4tr$y?sEhNG$l^3jWlNyZipa2EC#d@3*|< z^!Ia{ELqo6`|$W_1A0Z`iCIh6_0%4G<28M}q84i;^J)b5m9I9Yr#8I(?gn+O8ZG$Z z3fAtp+eawDQ|okk{tMzEdnUB1vdWZy4YA%{T4=SpR&nOu?A@W<1|=luZ8bry3x2Xz zUF%n?kD9;miV_kmUv7itxOJz|b*=SmyyYudnR0@@lW6?vQ+2IOy}j*IMafA}>raoZ zSl9a1=XX+ORkjBuAC4YX*GkdLyWTaRS0uJNaJjlxiWdJ?v#>$0s5R|(OV_nhboPGN z6a*z-u-ukfDLSh@Z9uO`yf=CAx>kzTT6%I}gI-bVp(PfrYo+MRubf^Gl>F(Gh3Z-< zdj7VP2K0)=Ln8~;wNmuSoqt-`pjXs-@`L&7S}A&Z_=tj_WZom@t!t&|y4Us`&?^#~ zz4+0(R*Kf1`lZ4Ky`t8sd(U0hO3@m-tyd6~thmQqb*&U_`@J;=^oqnaqvon>rRXc4 zTdlA`uc+0y>O)^CI(?B*1wqL&tG@3mMNd7q*nnPTcs;?C7zS}hg zao<6+eWmEmJ+ImL*P~|pO3_-kpR_T5Dffy5wKiSsF<&Wq`L=mB$qD}Mx9@(`SBmD^ zYrQ@;_`4+5I_6PdDOz!_Yc|Slkf4_S-g8_s!a6zRrI&rBXpcoF57-_g9@ytaUn%<$>nlfvi0lgxz>QA2Xm7-(bc&xZf=oPhg8hX-KihjArH3dP* zkN*9*uM{0|+ew@7m#Xg)64S1E%vXwb-*dgf27ilM`Q1MK=pXsYL_B=ax_u+;GZV#3 zVC)mO+WLz=_xa?<|Inz__V~)NPJH?G|EW_#Lf7rtQmyvv+s8X`-dAS?5;GdD-~HVS z2RCTDR(tx=*2(XuUA`k@DjOuGp0l~zuyOk|`(N$HZbMi6Eo$NK)+eGIP57IQ6XC59 zsH-L=C^@|~0wrfH4$%{o$q1A@QbK}dvf^%hw$D<-sKZC>%Nef|+eZ!G{om2`znpef z*m}$@Swvkop;2*3e6a8$_4D4J7@pflbLY}Vo1m6`FYI$p{hJe%kT`DFh3f~|s?pG^ z$}>S5lw9~ut$y4m&I~{P5=yx^B14bI*U)?}dBEDqGKC-))_jy5<@$HYp*|o+s#=tXl2VU+nKT4qE2_ zGJ;yO_uRm3yfUPyl(+Uc(1~}yb!U?j684Rnd#G>AYPCQ7{vapLS)!Q{)OupOjoijc zFP>t=5_2EYvhm4lnv{^R@Aut?eR*NT&;za0Zf^VcIT=AMeOIFXO5f+yYAh%@&o)o4Zu&mjvBB<4F8+|pD z6O@p6>GE~!=RZ3s{Nkr;^&zOGI_zCnl$6Ar_Fy?!i({Amci8LhUxu@8Ie3UQl9z)L z5}O@WtM6{l`I@_pDcXYswb)LXjgf;^c-eb{r@pjhLv*{%`Aa$R&I>Dh-*?P2i^eVY zU8Jr)YU0+nIo-Z{stNw?qi2lvp8D!77LPeW2??}pAA(xT{c7F%Pv4vr!q?X-2uet7 zbMVIg_Sxo=p@N`<1nz}C1hsUX?vjFFjeg16S^fD|yN&5nyR07)2QK^XFwX9=Z`^%w zBd=W&)Z)F6_0)CrwTgUk-|f8{(H~nm&{Jmwwc7QjZ?dwUx=slR^v6b^r_Km!p+_|W zJ$0QD66lYOKu?_!)IyJH1bXT^B_#4TM^Bv*)Z!hJz0Zf=+Uk1mk>B{tq=@%!JaVH; z!*TX@Uig6V<`qT&!<3M~+qocUV~FXoU-*4tgAx*X zIW*2SOKO+qDR+zs;}`rzm^R@YuhBF@Dr%R6#<}Vrv zmXOfMSR-T`(e@#z#WLkKsHM@cM#VM;&hk6u1b>T!#<_Zz*of9@m*pTqt@D<-IBfCs z_%Pv{PZtCw8V#!#wJ~s?+NBK=8YOGAY-8ZU1_^4hWoxzg{s%t3TK|JRhS`E_wZk8b z-m>egy_V^I|B`oZOF=F1;;;;p0i%Lr9G|rU`>rG8}r}a*B z;<>|)$_Q%dT2ESw(8yR1t&QdC8Ubr0Y-2g~0G*hh6~4FUrqAtpT3F@2yX@~Ia>*P* zw4Ql;7Z-%a(&{a3%+}OcT4QP(Da-4Qz1#*RBs7-RnA*m`M$;=2)Y4db&V5CK5)##Q zMS@za>D(*UuEw@{<@==IslIu72e7aN@J`^eH*DSnKYU_ta{0jdRtj*|<0J zM59*qqBd4-+2|0tWKOGDjl`^WdlJ;r7*zedjXVn*l#sC6bsL>~w_}3@wRD}`?Hz(8 zzj@<%<6pzXu=L0$vs%dOiuV->%@5SK+vv6^2MKCv%&T78MzjS%iDoV8oo(crJ&)C1 zk@(nOS8rUq%-HbN`JQP#gPoGot6Ymu?Zo5nubXD=ACnFkp0$ykdt`ma$X7RLYHZtX z=R21Ft^a+y6V|nIEI#cSCq6&+JHwQauzud@*86<3wOU_tTzAyBGJ;yVZjTIVwLM=O z<2D{x{>WjrE!+IT$BuR4gfFPyJ$dw5P8@L7;lq@WupZUDYW38&?sbI|J3etpMo^12 zQmd`7;B`(+{`(KIx*}n32Dj0A<2-Oj@Cul<>WA#@y?#=Aw1b>%=M#k#%Z46v^ zMS@xygX+y-BhO}TgLeb(5{-=YHn7ocK~O@1wsRXKsP)$)XT-nmG%5V+>!l4!NaW>E z%c%j?E^Ch(8<(GcYIu9YQ@lpoZ9ux!)@?#hjGjA{LDzaFbban$R&B0y`dMM0`Ddw@ zfDKACmQJhAPPcz4CuoC&#?ookxv)WkTGi#Cmd4U)rMbATSPuRc35})G8gk(k32M#t z(fi`7e;yZ3pYPm)phRQow9-7FS0pr+PAkxb4SGc_-V3$bcdz@QKeh8u{!RTKKit6E z`LdlSMfFW;HT5ZB{vrSS-B<2wHctL(D+cQ`+fArbLPBp$(dzYTwO8&s(rs+8>-*muC!S|E*1vLJCl3AOQ*}y6XoN4X)YH{! zmrnkk6GuIMPexFSHBzhXV!fxHkC(oEXI57v)Zfa6dR9Ay)_Q0W8!U8PMo^3O)*2a$ zu<_!EM#gEaSZh|^?<#Kh-Q6CFmtOyiu;$+%pP3VskkGZB`Bv1gMq<5eXndH~LNj~0 z4gM|(jj_}Eb!&~RV}k^>Zd!Tq=H>Qv+m_Sy{OK z??mm&beuSi_E>qGH7_S7!)r^oH<1hyc(qL%(X=cz?6 zs{N>TZ|O7Z)Yk^|$5y-OshgCrJ<$6Yfww_MPz!yc5$NHXl#oDgXT;dsTfOMXhuoeK z)Itw##N6k$dg>=;-_xXoMEkC^zTF7C4KjjSc&`}oy)|2JoPB=vy7p4rZyaA0O79F` z71XtjgN(qKVMJriv?}YPNcC4X8Vh&_7X&35ceV+QDAixtsIU(~Exh3hf)Wy&Ew@_p zvLnt4dvBnqMwWvFwOAuLp*exxQ8s?hN_&TmIM=cf=Ng~ael2ZK!dlRE8kZIXZD>xA zR?jngxefjk>dg8b z%!)DziM1}C5og=p`HU%x_aUf7Z*v=zkg&C7UtzKFaAAWITSNBs8GU)dU#hl2!q$_0 zgskradS}^-V=iP+}{>-tX$$iNU-gF>{GY@q^pPhOPf|U15X2MJ@e(&Yg%= zgAukl+ZpQ*R=Zf47@>p&X4^)bnN~lZo^(J)Pz&>RBQT>Mp@alx_eQM#t?TXo+GkQ1 z{2(K!g%u0a9ZD+`2Rw1e2qh%2=3vB0b5=hxf?68k>$$PFkP-HEg?ptvJW5JJPgIN0 z$XMmDH)zvVIU8vW+1hqaHj*(DeZP>bKBdw&G z*Q9BK5)!s9+DNO>MpqHkdilM1D~=o=8)uC_tKR-k;`+{?zD01adJ@z!Z~d2S98nOIkkEKNt!(!pa;>UzP)qZJw32SWTSZVp!d8ce z(i(E%6$xr>|JsE^<82qPCK*xv9o0!V$W-Y5)#%Ed7Ima)`&1?Uo9i3g&jI0uy;2?2?^^_-G+^5jcD%= zZgl#sADoZD!PeXw7f5!BLk zdlcm(fD!fWHZs#_sUsnwk#SmkHLtL@U8jVEz0ch%{aZ~?%g64m72(1LB_wP;*}u!s zmlwGWjf~UkxkfJ?Pgb~dOqgX~EgXNQ^2x9ql#tN%oN);W+OV~7|Gq?DjgZc5P(tFw z^p$*`#fEEMS@y+$&said3>TG)fKUB5!jx&Nq3?}l{d4z2F%^mB%w%kMXXy) zdLM#Xi25%GMXD=e-C~cMid0v`y2Ye75u+S)uc)O+bw#XO9C{yuzePfk>WWymnDoLc z64YWX=RqBGnc9YLVatp-6SbzFM4iRHV9MUo8%OK(9zBQe6@27L(qmJ*dUICoehu zRiwINUo8%OK(9zBQeCmH7L#6-oOMMl)<_mdKcXyOic7T|UQs!_6whhdxeBikt3N^; zB$Q!H@tl^=%e<;0sHHq)is!UEUj>1D5>YwZ6oqRU*&^~!^dQt{*mIo`%GsvaSIf25 zhoBbAS6vPg%D|==Udy6Z*x+wbi?yEHV4Wz}nIc&&li7gnK|;CC6v=8?&H8vnE#*2> zB&%gOD+o%I>r9cXmdR{DuSh7@nIc&&t65=#b(LvZt}{ilT86WNP!_bdM7hos$!eL* z2K0)Aa-AuX)v}ruHs}?#lOgYai!&yO4qFiUnd1jf+2K0)Aa-AvXnPoLAY|txeDc6~D zo>`u+f>5qALA$l=IATl=bn71nnu;nR1?4HmJe|e^UL#Nu6i3#OTRQ{ltF@ZqFiUnd1jf+2K0)Aa-AvXnPoNW;}x}(>r6S%EW=qr zP@-IC%6Vp)%m(y|gmRrJ=b2?SD{QcKsijr6S% zEUQ^zgI-Zfxz3dH%rcx61SQIKrkrP%$!tKcNGR8ta-LaMv%&_wqE>#lBahecv2${Q zWpfT>>#|WFa)k|3g3Mn|YnIxYu^{tTMj)qGleV+WUzt}Vkon8JLe8^{pcZnW8G+nw z!yI36Oog0oR=da#H%tkM+y=6}Wdya5$IWaY+uJZDBv__ao+T{-SpJWuax1CcEwEBLtM*Exo?5@wQ>#2nn(0~gp_YvfK?w<6 zx1ayqhVm?FUTgV^veGKglICibU8%5W~r84sURp(o+ZsvEsN5CUXf6qCCySTqf%jm zUQtVVmNZMX>`DbeiSjIImTFm)2K0)A@+@hVY8jOZ8}y1=%Cn?ds%2Mdy>U9d4<*X8 zq*yyIB(%SoGIRGKsHI<0U3J^g{$|R|9ksuiGIMK9rsHky6}7a#nKEx%+rUE!Ifu+0!#Cd?n%dt?XB26V9(TK*);2*23GHvD6P2uI zs3NGP{mpdlQbFjc)YGY_RQsFhj4G`sx>x#pZi5mM+TToPRP`aK#q#AgC?TQ!&2-{a zVS@yF=I>@KNl4{B+DGo9^J5R_sHOeQbhcALP@?_KbhgugUXjrLW;)xcutBe=rTxuxwo^g){^p8) zwo}ypW;)xck5?pUPy3tcY^TBoe^>jP>1?MyHu$?Fw7;3ob}DR;pqBnVXOzLdgmt3* z&2+ZYfL@W%{$@JcsgGCG(*9;T+o>QZ(f(#S+i5_rNN9gEo$XZEU|ms5`YN=eBU&)s5*E*r{aD2s)lS-^|sGO}j zQeCOeC?S#CP>DsT21rm#rI!tr&3Aa6u>H$_ zZ)!ehyP6> zp|#`FE(awUVY@V%P1?Ss#n)C5+68TE(ZigegoO4tHRrUQ%%U75s8wBZ?Qf=YWwO$0 ze>0scQ0Ft@D-zVw{$@H?rXaMxsX3?Z z?hR>wGo33lpjRZczo|K=?PL}<=oPhizvU&TzuMnS=gJJ|6$$NcrgLTbcttJNNaocr z?yHDrFlv7@ohuV_f)WzCPS1ZqXn!-EE7M@TX@4`FE7QnrP(p&Do)3W5^tZ>Do)2K0)A_BYeHGKCF#MJ?@bYL;rdngv0L_BYeHG6Q-=Li?NP zT$#cKy`q-(H`BQ?1wo1SH`BQ?1A0Y5`W~sJ&Ig`JX6O@q9{-$QBwv$=dAVDqdZ)%omdwT_;{Y~w2+V17`+TYYH)%GQ? z=P%`6k)W3LH#JMO9iSU>g1@W%P5&Bqul4%a;O~;q{-$QBwv%~XZi581^!J|Ql3~_~ z_BS<4wcX1B+k=Fi7~`{4+sQ0ymtIjz`#lYtK$|1MT5y|4;K8?Wtkx+M{-*U7{Fb*$~%)iIB*=L97rEK<|I-_;qz)daQlOKJ~Wp(qH8$cvh# z>MU7{)Ql;fvyOEXYelTXDeAMMWzm^Yb55NrTuo3y!Xh>O+ghD5oZBElE!IL#SgfV* zbLx~}(iXMp`SW)X(Eg_8oH}>cqBDJ;Q|AiPc1}=2!XhK991!y@J5HVX$~kpZ(hIrSE&H&$p+y2ho<0u((T~bK1USAA(veUv)W1 zSfr-Uooy$xu)*J=7Hd7X!8)<%OrJs8?&W~(LBb+6eV@~IGW&Q%EsNUpeNNleEC@<0 zI@9+#ZTE6OuSi&=rtfpwPG(_)b(Lw^{$`5WEC}sHD0vdpV$2BrH$0sAW-`zRzj9ngv0LMQ8dxr|n)2=oJZz)bxE$+sQ0!&?{J6kGf3N)?Bf*)+Or5ZpF!FVP+^0=Ytfml8RV1wZ18tUSfr-UAZ;hJut9=a`um(w z2Hzj76N}FD8KmuA_9;1Skg!NipF!GAW*@JpWl@_xgS1`Ef}q5rGkpeWyO#rcMZzLA zeFkYenS~9OgIX4~=`%>%)hq}~EIQL?khXg{pjRX;QqyOUwv$=dpjXtgs7;?i+OB3n zP-4-UK7+K~%K^P2VUe0XgS4H@!UnyfR(`i@w^Ab+MK^Lb!TA7o=xo%ZokS6epu~<_ z9XplvW9RHB8lgQ@5sHVT4gPLUV1ICg5)#-2G#lCxl?}y1lAsp7&Gu_YIKI+#d*p(@{CYIA}@#bH$~X4UtN2en#I|i)~{6# zU2A_c#dBI+k)Q-${MHd&)rX*#_BT^JXGz%pW{R(?YkxDvbDCCdHF;=j9aeIBMF|P* zZ)!Ga`;vtX64auHxeZE4Xn!-sa~3v8P^-G+7Hc__;yJU@TGZxHisvkBSa)ydps@i;o;i@tg&r{Y}j|ZFjG3(V0Ujo^wF2 zNN9gE#d8)m=oPgrp0jhm?knH# zx1BycwSKLq)}k8yi&oq9YuV@!l#tMM`}xmptYVSSDV{Sct;JwAQaop2BbUs%6X|Vk zg9NoKYSX{1wO!4^1|=j|zT5`OVbPh56wjHJDJOWBkg!P2MvCVwydps@i`s0Yc+P^L z#G*4BDV}pcuSi&=W+TOO7B=V=wJd70k>WWEf)b0)Y@~S30lgw&k(!MZ&so@@SJcw} zrskryt630~SafD1#d8km6$y*fY@~S3!UnyfmPKtgQaootP-4-UjTFy0pjRX;QnQib zISU)~idq)6*+}u61wn~LXEsti=YU?3ut?2DisvkB&?{25%w%*R2-iH$HZ>D%o z)0)#uR6m0xw7;3+ISU*7Eoy0hGsSZj1SQ(vO!1rpdPPF}n<<{NutBe=rTxtm&sh-K z-%RnGzQ38`Is14;g7&n(nc_JM8`?K*|E@)6UZ3JQ``F;`lFD(8K3-8v`Jrt#;$8(z2bmy6uiOH0Q7#IbF9SCyhWHWM+fEn-hqG z9HE2+q8-hKc0}cv?Gt81t~JNoEG|`Ebw+o(ZqM$_UPI-xUCmZGy!^J`IYJ2u)`IWs zs!g@unGw`758a0Ccecvmgvvn)3D&xPUH_>qYPD^*JyUHEXOG^pZr5r9zt%ULx?b|i zt-J(th?K29E_7?Ccdjj8wB?ajEyPyldg-@qEO69ET=MiAo43c*+8dU=j_sCyo1i4s zl@qB<+8ZvsB0;UZOf4&&l6Oi=!mj=AJ#CQaXj%D!O0M$d<)DPWYh`jmwNOn^D`n93 zTF;3m$8V-JlKB1-o2!oeT6K2ZhgS|z81MA{jTs*P%bTKJ`*N}~Nm zg8we)!H6N0&+l{DX_X_L?Gu&39OY=AV-uC9KKCkpzv+@*gw1>U5N%poIgaGC-6)(JI~;)p@}E0nG?8wMEKpObBj{;cRjTQ zK^y#CJSzo32?>>0b!B}?AA(wVR=SDyb7zt{zl$fW4?!(FT?L^XT={EjiCR6a>)O`* z>NjrlrvLpLXRJ`qYnKudcR#m;)4POu3xX07vLk!?TW*5{wRZi?YEC?P(8I;OO9=^; zOEy%_+y)71*`4Ub5~Hs!h?IL?Ctud*|9I2uXYO;?si#c&QDkm|5)wxqc(v3032LQ` z|FLzFK+8(&iK2wWyqEvPZS3*rP~jB`YT;Qa2ugYq_I}JuPNH*dT6hKvf)WzAcl!|3 zN@sTTXb(zAsF%}S(%l{;axFibLnjv&cS$gw>l9_D<<;kIrvV%UaX_u2EFiUDA<|K#y8Q*eHy@ zYxlJOQqSk3BOzh;vH!j2^U)!wWlxv?z56anJ2BqN=u9=WntF@07Z&Z`;x3_tgq_CV zHgqaOURNZjm3Fqg2hRygNSJ4Cqjj1`i)q~@*6+IS>cg#n^lSCCEMIPe5)xKNPIvdB zB&fw&sJ3B!yZ^4<8T2+MC?R2#(|SWx6V$S|o!3>*_h3gtg0-I8;BQgO-VFXrdY9w` zB_yg_kOZ}=?_Ekr*t^TU>b~1aP^xrU-L^|U#>Rnt-P>at>PEgW|&?uyuXw%ZFeg=Du z)%8|r(|W)3wjoJdO9Wc84?!)oO+ipX0{226f?8;sf}n&1?w&pbwa_*NK?w=mJ$(pj zwQE|>W$*Toq!(d5bwS{6(A&lDaP>lXmlOmgB=GL)Lr@DnQ8O=SYPJ8~ zeJ8S=*&fwxP6-L#3%OS$s3mXGn7U{WN=V>s*N31M-h%}}2?>lc`w-OXjAU(HBQH56 zJqcSosU|wKX<-IX5R{O>7`_idEzC;_f)Wy#i}WE1t*L5rtv%%>xBssrDTtZ~z4fXI zN!nWGZRmYpm6A4L_68uRWwq{v-g>!Ll#sA`b3*UNYJytUnoihUtsp2N!F8tGhTY+v z657+%xz?CRwV=0NPIPS8UER4hPpSz@NZ6h4Hf(lR*dReIdYgM?Jy~7;s<&)ktGBS; z&i}5yCMWDKZe9JM^;dqa-qhZYey#UpPEbO^`bsC%XI2x`s`iQ!66TqgLp^J5g9NqO zwb1?kU^}x$StGd(N=R5A>?OBZQPF}VsKt8AZBRnOMh0%fW_N`R64bJHyVsT8zqt)c zNZ82037b>*A*f})?S#e=xeZE4ux)aJ5)w8ta2qzeFWQ_0wW`~^EzvX4zSf;#&$rvK zC$6wT2?-mQI$`suJ_NOFbnb*b`vpM>2^(JzKv2v2TPO6^%WK#ARhQ`fWOD<**4~uO zcm2A1cZm`b+LKftbHF2)7yD5psD-~5yG!_8?G?2>44?~w5)#!mSU<4mJEAH_cU`d- zNx)uFyCkU9zGE~($lHUGUWDH9)kK??mezGu4%42R6O@q9y6%4`sMV%5Ldb3O($agq znxLe8EdsSr*l26XI<-*i1wjc3v}PZIT6i`Kf)WzA-}(^LLLXBQl#oC#(TAW`yAJi% z%Uh6=UWE0JeTX(KExdyZf)Wzw!TS)@!sw$QC?SFILmz@#cx%`5x}t;x-obqcYT?~p z5R{O>o4O#__o07m;JQyQ3ay5HIpBS8_ty!~8lo1i&4!|VRbv*5rEJ4GYsb$@RXObY z8(;Znnfepzqtud$#I-C?Q75A21SR}kwoNrbtv@$!3ill{DgJGf6i44FhoY11E9j_m zWfkXa-&6ZJwxn|#B&emRW&1ih>IBxD;O{D~+P*`NI>D86PEbNZ5ykekdem94)daPw zORlJ1`))ewY*xht+gI07r@7L0wG9%AN477%qfU>lCa6_iSC*?d*mu)WXR|6M*uJ`s zI?Z)3uSh5!*}nLWIz6`9D{8SuazgRC_C<8m>8gtGwQs1S&S|aoiUhS3yK7%ZN1eKw z+u-ji?%2NUjyf@xbWTu0LNU+wRe972wbcZ*SnD~V7+w1cI_jiVMfln`)KMq6(sngL zEyeNLm(o$EuI2=PS24);m3P#Mv7~c?5)z7YwlB$}POGgZs8!t_itx2>sH4tfRZOsb zbscrGD{WWXAfXs!`^r1&^w?^GTGe%>I9L0UIO0>y?+pDWwG{JgUw`|VwmG5r zS^Gjc>f}>J;@Y>)QRk*sdqpip_}VwrQRlQ)6O@opM6rFd9d#CL?iC4Yv1M~Y5x4eD zbJSU>iruxZqoYn*Xe#6RdZSL0@r9)QQ2gofDLhP~5qF z*&lV%YBfPEMf=+K)KTZO<^&~*D7J65qt1V&?VO;5grb)1yYQ&9XR8Tnv7K6@B#o9d zYSK7IBP5Mtl#|F}QKMxa3LMFH6S~_=Livy^$~0P@AM;8hG1_Po)MEK^f)WzSHe?Z? z(eervHb_uQ*^MkNHCpbXK7?}lSbSx)tUWphUTfEPgavUZJ7|S#o+s zLK%%L$~0OYqrwIWYU%Ioek`vmme9_zsap(hv^-A(dPPEcq%0aZT4ta=UQx@=O{rT1 zXtcaS1wn~28d;QSw0uPadPPFHkt|*{T4tca2J4Di$~I&XpwaRQ6$B;9Xk<~Q(ef1y z=oJa&avuQ;uFgc1_E zZqIjGvF&;Wb#^fci@bL&i(=2dXw6P*&b%UFG49@D=-=$L=8T{g)?|&qY0Zl6@AN+G zaa3ZJLtba6H7i!XBO#I7z-i4HK`oVDHdMA&b^_H^itg`7NU%(;sD2R^9Y2h<9(}#x zv{pRZYYwedHANJ+2}(#btxIYEhK=B}&X)k(yb*SoHMSLYb#1SOU`ysmy%XC?EOa)J^PmaDw3 zephERR}<9IFR9g!|UpIbyjlj6(yFFysmy%XE5`Za)J^P zmJhwIeplx|R}<9YJ?6P4z28lFIoo>>%Cgzn1yHn>dIm*{wIbW})TX?g9SI3M!Pb{3 zT1!OA%h@3mp{3tdOc~eCT2W^rQeMuES0of8C)(7eNw@X&oUZs=)WYAbt`wms?Ua|( ze@lH7%AqWxZEuZGoSF!$E9K?vNJ!*1P;!rXOSP!Hob56xFQ@;KqSLaH>s-c;gapf! zwYg4@a6-H7@Ji=w*R=*{*$S*Z@YIe_LIOQsAA(xSnV{7{oqV0!poGK*x35vxTHj|^ z{76AqHukz!=ydwDJ)9-&Iw8^4}FKQEcSJ+4(inIYJysQrmX7hl)vpw7pp?P`Krmi@i1)j^$hofG_B%UoaA>Yz^QCY=+Mkg!bob*&ESWbkT& zTCDY)u#E4%I;az_Ek}G^tAjcdo3^V7YFYMoUmetG*Ezx8waoQ(tq$s>ZqhkH2?@)Z zU)SoOWtAvwkf2s|dstq0Umesr*p^}5R|j>XHh-zwD-xE)-d6{8YIik3t?Ih6?C8Ea zsMDY=&$_P;S{{M{y&_>*?0t1mr*>C+MJ?7yH_;y5S&n#L9n_iFgVhxY%SrF6gF1t| z+lE#@>_s}2T9yOfR|j?GcTQLac3&OTiPM(9-B$-Kzd@h6qL$^0_tin2k3Cp9NLWsK zUmesL+__i$Eo!l4bHZ}A`|6<1sJ4vnzB;HAuK7zjK?w=VHt(y0I$gV(pcd;eCs^JvOH8oS=k+WqkM5L7i}2O;F47#rx`@~v zD{ehT*^Oy~1hw>cjUTo5ofGs**H_GUs=l}nyKQi37`^|PxcL6#3xbkG*S$V`c+c2) z-O7^!f2rCAi7kJ0Z#e9>adEE4vRbJl>R;Dt16|)TV@6nE?@96c z=HhmLR1wr-jpPI+BzAn^_hI{6CdN@aEL_+iL9Lm4PYth~J|WIC`6Vkky%N#BGf1y+ z=a?{S!C%DV&s4-A2}(%3@tH~CbN7vnZ*6sbLD2e%%UvACJUu>+-{UU6aU$GpAkw( z;9FHAZod3sC*C@Gzl@;PH}{|9Hm)46%y>udeWw$T>~Y`-B_!~*u@Udze6thV-}L>A zpw@zSoZ&X^Uw1QOrNHR z+{F$Z>%`CIKXQZ;68OU0h@I9u(TV2{J1QfnrE5K1`f99J+j-@0532>2S?i_dQ(xM0 zNPW~nE4*xX!<;zk&Az_prnB}uEq>(QyX@~Ia>*P*w4Q=i6gCN3r&rrtG8EKPZ*%a* zg;$i2!1w!o2x?uu#o|Hll1I-NT@aLzU@hb&Cqb=ao>?@gPkiTvl?xlWWKLa8-1@d5 z_0(JLyGTK>J+|6y%#hvyUph+Pl+2-XuP7n0{c9Hvjeo?xvUqx)!UhRyb$R7IweFIy z{dLi(-g5XUm2i$H(+^lSs;7Q-?$uj1Iz%p+Ls(5m_4%5=dpUX%)Ux)E*}dB#C@Bfq z=-llcg5`Mmy?Nv4^(V$xN3E2VDffz{C9(B|w>9)OIQy8?f*l(qsI}&9V;bsrH}lrC z=c7YV@{jXWw4U0I4SJPp@u{77{QXuJwc0-> z9WXL$qe))xBVXM>Sv5MXcE|F+^}la-!n&rr__Sx7`25)Kj8H$=^}4?cFR6DNE@{qD)5&vN2`vko7jgoM6Q z7p<>cYqeYVy26PapEx8VsKpwo)mB*WIwvOo{RdfHknNkh45(%YI8WgP%^7iEUy~xY-I`R@)OOKkog|vi3VdneY_uT*g zbIx<`UBA{c&u{*Ff9~Gr+3)b>odo1hlY>|k*C>NmudxXFc=&3^KR-Qo;>;-Al}G&aRq z^X#wMWEg+H;flj#aagUc^GGKe?dc4J0R zi#;+J?Ei|Rg1GC@>$1Kgq473scxFBr{L7DDAH;4CU7ZosV!y@ASodx{&(h2|#$C_M zoVDtEMKQ7MuXyP#)7M;e*7Tv@x=nA2G)r0{C?VnBzJpEY1Z`-xH}kmbxg6=7poD~G zlrxXJp38L;)OyF3o6er|$8)FeJ>7dqvmLw|c$H|rK8ty~=I=Q{35n+1c%I!&P)qam zna6q0xpRUN66}#~f?Ard&-}#kEIlVEA<@}abIpunRPzjzgl5Juih4er*_cy80&VIc zsD<-X5R{aJuVc@LaN<*8Bsz4qo@dsi5WpH zjEN%fj2clw0#70lct&LewJ=JEz%yz@NlBz$ziYg9NqMBRQc} zL_F2Js-TBY(Twx4nsNT|nP(I>C?VnBX}_U54kXIY9{t-|HSl-TU1HwfsA+ zYYT#2X=WU6TVmb|4|5yzgoI|sF+=toxSODs=DacY^^7(rDAC+D#$C^1X*(weqXpFvcoA>Y}(uJz8Mpt=>I-`5nNR64MQV zcLO4Z=^empZ$CC8sD-tYvKvtM6_9ZthyIBK&vHrgDN35}JKSMA38ZZX(y} z@`_rT?MD>Rvu5^NZi5mMni&t%JLJME64bi#j~^L+M(^}b`}u|iL5b$i!}O+kL9a+? zUOh~2pzC{Z>3q;DYUO7Z@hFefOJ|K|6Ok=>h?v)y5)ys`;&bkqr=B>=akY$~79w;a z5W5>wLc(tgY{N6?<@n&-gnZs%#*ZI;Mn# zM)0sv&r1-m%?N7w_wv||DDuqT5~TOI5%W)PXp8DeB=p=4>wbRwD}jda*Bt51t=iE= zP>UYs1SKT=%}09oTG${#t?riltBv%&-SeHLHl1>>k{XDLoU1` zK`nnPk=_m$1SS4zBfSM)&?^!rth~HBN#7Jb?6vPHY|txe`R~iu)igW!Tu}S6-!V zw*IlTjjgX7Q9?q`jj-XBfM)vNdt(s)ecuN&f?Aq&gbh7~L}=X+gx4XIl!UMLnsD6Q zE%yvl^Vv94`hP#>FD*Q-ct-2LoABS`ZB#}y5)wykd0+MJ8{RcN@CN5J&<4Ho@5U2< zU6J0_$_@!iNHpihbH{FiT95g_(?+M>d)~A5 z6F6H|wFjoO-Q5lnu1?@=S=AvZZ17mr^50XHf`VWRU7f&H3RHVw#v^rmMZ(nyT%|yD z2zvU8TCPsuDg~-ZP!N>3I)SrgReNB;z9Ql31kRRK9fG3eY$3H=oxs_$s!31~l(;&9 zvt?C#U_q})xH^HeWmSiuutBe=#cM3fydNVIeum8ZDKhe91KIs!N=W#(?`Bmi5P@9% zj6i;V?6>8+`NXLA`myy!G3!&Ve&!Vk8a=D4ni=L}iZyX&#RSJk^)&@0!_YY11wbMC8Z-}QJ!t?s^ZMLg%e zs#aT6#B=Ve>fJ5qm22oVge&4X_f@s;dc2|*dnCWEToKQ?uc~(!74e+=s!Db}UXkFr zaYa1mzN#Wy;gu`xHOF;DJmP!r>bv-S3IsO;yL$K_3nCX@VF#g5zo1=s(n}3AVIC}^Wlnk zu8gO8a8VJ@mGM;XZb7eHL$4uR5zm$JRQs;SD{6K3l`G=8GM?(FMMXSU##6n!1-)_& zy@qf_JXgk3?YkbYsKp-1uM+oeGgos(JXgkh+%+Fu&?^$Ii08_9s(shv6}7flePQIj zs#04)xFVh_LIA*T25Z2s)AEN zP~uunUT5BQ@s106MZ&e5yyjFLqrwK;k!vmQ=90JEJ>Wi3wsO>R@+wtzcV@2TsO5TL%{5k6X0oO#9F1KG2zPD7PkqrIx75(2RRl=eth3UX=A!6DhO7SXCz64ieOIEvKv< zLAV{1kYKOJJs9iSH0~~)HJ(k^a&k>4Rd7;YY1~~RC?TP7EUty6k-C+jmTNhAU8@RC zg$+tbxR#Swsj6305U%CqwWVqX&0NdLD^^u)l2$RoEqO&P*K+duQsnQ6>aoG&l5j02uWMDcsjxwUTI}__ z<*w!Ab**YUMJ*?i-2dRk7c?(^YVPF~lllF`()oV-d^rKWgVH1n>!9rTKXYdLvctEx>!%SlkHyRTf! z$?IBG0Ghg%lUJ##)U=>iBwWkM>snQ9>hX$N?2&a_-puY?%gO6nRccz$D-y2dl8%dI+9D60YSG72gl} zRpAv0YVpkGz3W;|Ue~H-(A2e@yh>H2rUkts;aW~!*Q#n$k5|-UALd@M-(Abe>snQ6 zTF@&JuI1!)t*SQlcttJOa`L)X6`Tr!64!F_x>l8%7W9gQYdLvctEx?f4W2=2@jS&l zfRQy7?{v-OndfSLkM9_2s`ws}QjaD6`?^FUA>kNms`%bRP)n=uSUdaQ+y*5i979bN z-+KsZIfj}lzV{H0p?U?Ocvr+wy-HQ&v>+T^Z6uDNri$-=GqFHBNH~U?D!vyscr0r9 z@6G$Uysy|o$52zn_XWKo;TUSF_}=3cwH!lD72gYj630+e#rFlhBHR0U0tr%nwjzQ7}k88?w9p_XGG6=^YDIuXqV|bF-_5w<7P}X0H{#A=!|kDj1bZQ($U(S0B&cQo zZNr|{{@W|JhY}KbJ3M-tP-JoB7;4&OEIWhj^?JPRBHVJf$1&8j%b0qXHYnk7dA)TL z)N%|p?J`!_a11r=GB$Gz)oV`0KK)$=MmTy!f?AHDrd`Gg8$7OKsA-q69veI^3CB>= zE@Ooa64dH$xnrnlm$8VUdd;Z_X)!Xe<+S0bYeP7OnsyoM@rqjAedQQx+GQ+as9tj_ zLb{+=j=DC4W2kADF8^STvw98nJSJYyUKj-jSq#(KP>mSd=C zm$8Cy3^naC7BSSc%UF+Bj{&ureij-jSq#v+EA zb{SjHD@R=$!ZFme%UF+B)M6jzUa{XDL-m?d5z+;{BHkOR zSFDPb_7K!^4ArYtMNSKX630-z&QyeSL9a+ShMM-r(YNQ0Vl*vhJE-N@qg$>x$aXnF ziDRfll#p=z)^vSG>HmfeQzWQ` zzpJktL$$W|`GLPNUNvJEycOXXstL!2DM8EWtq8Q7z3AP5nw}n_O(GmawT;*rXt{qf zf^Ev~LGMczeWI~8zFkS}h!|?xA4mO#yLRm8Y9m2A;%k>QQuh!T?IMPn_Qxp*M^_sO z3CB>={x}8U7;4%dXW|%Y+8<}aYdUWSwH!nBx>ga=9)iar;TUS#A7_%=AVDp*DJLi) z;TUS#AE&TEf?C~uJ#U9DMatt-?k27%$)$32iK6|_(!Cr6-HSLd6c*Wy7hMM-r z>9N7%l5h+)?T=H~AVDqmdfsx!P`$2IgmmH2efD@og7zFk^}1GZ!on*a*D=(z zKTeMg9+!k;sA+$k!UhRyb)OH%P`$2I1aXaHs9vQiLb`@W%KM5E5{{vIU8`tmk5|;{ z?kmSoy{=W{ZH;57UZpBRx}aAi97FZGR?*Tm-R+4!Bqt~#;TWpdwThO0xtpMtW2j!&Dsoy7lsJa!b*&<#U#9JD8zdY<^}1Hk z(!vIhMJ=AE>>U8#{Ew8E8ejQ(7j3+)AFWIH{?MEMj8Oh)eDSN;XAeOwtir3@1|=kv zaT?zXdw=Y1f?CSjoTj|g9>OtHuTs6kv16!SrFyUI+y*7eGL2ZO_r#{RIY9{tWt>JV z)%#<26V&pN()+oBU<;LHI!$@0Biin^K|&d))0CIm(^u3|_USa`r4|Gw$}){us`tcR z%qtSgIE`4U_s8yT2ep)a8nIOGm7NomD9bcrsooQNF|SA{<1}Ka-XA-+!DCU2*H{)G zoFiU0LVU176i_xCb@e*Rd7YGy@Ncgmb@z&JMAU?{G)W*9n zK`q2sML33PubgM=QO5pyEa8ZQ*sTb}guM%R6JO4V+y-L889^;Xdu0PL;W;HF*rx1z zhOzQeW6i0UYQ=NFbJI_FMDHtijXeo z6$xdWMl4m)(jKp<#U9D8D`lBREL9QG$}v>0ITict@rne`jq)HPmZ}(D;T4aoEYpak zDni<0gU2PIjMIpvDq33DAdzXI*YlPu%QV)UijY>0p?b}!*k_MdBxp~$ma*nkoUrhU z$5obT#8MR@?Xkh*l2FEJ#8MS4Eo_jWR`>Z(7G|tD6+x_&Wg2TvMMxL)ii9#wW6h~( zX^&Ub>h3FLFUFcvk+(`&rm^N!gmgi#NGRhp)|`r#_IO1t_DFt}xObbmnzBq|&8Z0K zf?knO#%aCg{9o_%$8ncukXp)*j5ViXdj+AK%2;zM9#|>kG}fGomiBl>EoGU;no|+d z9)ezxP{wJjITbA}ydps@p4q(R%6E)4r($)LvP@&msR-$UUXf77X{PN`B(X0nK4VlDrLpX+-@=|*UYB`3Q@=^IfEm|P`yf3nFk#F60u(gh%ro7Yzy&|EE(_zX>?eU6Qj-jT!)PkTy zS*F93m%5-=B$RPFOnIq=4fYkalzlo(d8q|KiLy+GDKB+FuSh84beQr|3mf!`TD->U z7^*ZKC!8bq(RXdc<$c#8qf#~;Lp7mTmjJ6?9=#0Sdr6$poD~SE#r${#R&^S`Hqv6mpW3$=_KW)N~;**mfArr$52yVY7fC< zk=RZ(2U1>Y;S~vLu}yjJQbIx*r<0VITG${#t?s^37Um@7rH&j!^}1FO(gj;iLK&x% zl$Tm~#ga2ux7;z*l$TmL zhU#^#VxK);k)S=tP*YxNJ(F3w2YFm&nNCt(YL5*bmxMA-Cn+zrr{&b@J|B*uro7b3 zG1QcoD&M=t5=uxohMMwHijywo1AsO1=H%1iAbcm_#0 zhMMwH3$I8}i)S|PUB^&UUTWnSYRXGp&?^#-p{Bgl9BN86Uh1#)esIn%qlf(9 zqig)X=Uw#trQhlAtNiy?A|xcz?~FKQZkETQ7XH4fv9S)ZiUfWy5if8%<~$a)(%;>_ zb|NGs((jC@ziQ;MsD-~T_0>8Ad$(zmZHV~BmFM`0GI;4ZZ<;@2$EQq=+3d9G0S_Hi z>38MdKUnjlHU9fx&kc0W*Wd47gSceXTjrFs5LHdwvCE1eK6BVf8IkDFx?+>(hK+qc zvXN}OXxj$`am-KtZB9uGQPsqupFYl4^WaDCJUJs0owQEb&h1!##e=20+53JwG_l8z zPu7*PEFtmi+djFQi0b&i*sIMqeS*IF84Patb52m}ww+FSj%|GFv9|G*dp{h+(|&jI zoRSuzs)^BC&z{=G8xPHiM2FVamtDNdHopGp4Q1no9i4@)cKqAF&namks+xHCBgZon zTfI$dP8=)!4y})#_VA%?yztQVW#gVJ4-eu=N4<4UNefZc#4!ieyJz3~=;JdY(V_K- zU0)bBPCos9oryo3`Khq6`j%tol(Z04O}yd!tAqILUysg+M2FVNH|-NPUVPb~WMkW} zel>^_uReNCNefXWVxR8?@%5{Y$cRLT);6b~8aB3>-6b2}J@RKk9C6`m=9IJ$RZU!X z;07^PJ^TqT%ZNmW)@LrbC~Q1%$q!}Yd%t*S5G%jD|D2K*qN<6tFWD-H_3qg#BN822 zcf93`VdIn&u91x&?z&wN7r%RtIVCMbRTIBHcjq9UyU%knBGI9>*Y{^(<5RcHWaIdM ze0oiM`dM>IT8OG9_I&-bgE;c!T{0rkq4kn$ZwwnNPyCE*96hOmc*CtL=9IJ$RZZM+ z@C$-iv;Wo^k?7D``>fl;#_A2vmyMsDwoec%_u67kNefZc#LhPz7{tY=ZJa>qN<54Z#g`Ohwr~OBN822#~$*huyO5s_mPb=zW&-E z&b{(mGfG;BswN&tyTpt)on=I#Lu>P+{t`A`w8v03&b;;YVdMKdubxrTLR2+z$BXM- zV)oeO;*3aiX#MJt2UQ-g9{1P3=vn*cf2enf`RupPno-h1R5fwQ1}BDBr)|7fMkG44 zp0IMGu(A5OlV#)SH=Pv3jZfZoMo9}%)x^HL`nfR}{N3ckQxfTSX!+UXc35vP_{oh8 zv28rH8c7SGQMw>19xMG0E!fr!0A5v;v=H`C1X?~K0k77e*F~UrN0hV>?r9M?gBgL| zU4yGf>%*kr5b0CwNMTz|&w%Nekg8gNQdSKXEbwPlE}bb|Uap8&lFk_z5QhPtJ_MQ*DB$ zwut8Gy#76VjVWm%{G=9v89+wh={&*gLj-0SV@g^G&p1S2CX*4EWlS)O60z;_Y-vnM z3*niQiRBqtMqsuy!E8_jW_@EyS_sboMPO!`5t#K&Fss$rd+hS;bxcVM;hC%m%#bqz zv)3u++9EIuA5+poct$P)GyROfEPRSph6t=C#+0-WURj91iX|hknwX~5%T%i(5m*(C zDIt;8SAHUiz{)ElsD)LZ2(0eLxg^$Yaa^q1L|_G(5!Ax!Rm6{%SE*x4S_rRLMPMbI z5m=>8v8EP*)%KW@7Q!oU5qEv*ijkk|TYco%jKFGp`iOV!Gx5w|`~7@JeLC%heYW<( zrlf_aYT~xPy)kT@d+m`Kk?7Fc_3cN5jlX%s?`31Foo)_dy+0o@rlf_aYU0m(-W|jj z&pRX|5*=FCzxbT6vHu5tA{#5#8;srZ6`y;>n35Kvs)=_$X44>Ee&@a!k?7F6ZU4)| z#@2UzTQ;uUudbf7<$8OMDQO|9nz;K>JA{p+x7&)?4gcqvVdJGMcO6sGLR2+z==(-N zeDAI&XGEey>x;L4KWwag$R)Dzg`s+`BSVkl|w1#(Y6gEzH{6IF||CKs7 z{NmqVS5eYJR5fw)jdh0fD{tO5BN822&5=BU=zRRHCJw&&!$V41h-w{T(neUT`MbPY zH5kCFDJ6{!5cW_6THZ=n3%xD^y*s0%u>rz8EdpmSBhb66aP0jDm&y`aNQ#o)x#gMUENas<#Rfx*Nb>Pbi`qPIDA_8*@W4pLZRnNHoEdVck#OYiXXxAMeg(JT)&hmDpKu83d#V@&m&Q7asR zbf$G$r=+dkyWu$yb^BcrcW!=t^kg?7!b0J&cSpt7x7)wE^+&yYmE;N139-8KWpTr)O{#x>f1*Q>&a{@b^UcN`^M=62 z{MSds6W@8USl;13zDn{0>4Z4+>7ntSQ{&=mFWl=8q%*D3!h_AmC3j7Mjk9*RB;N1n zM%B&to9C+}PmoTC{u9rS2lqU=`r!FX9D;PF_4b?ln2iZDpMj0lJqE^4KH^vJdF3a* zO7aBhgcu*45jQycr{aYpes&1bnbwZy>}@vooVFM?g4a)v*Z+Qd@qd5(=Bp%6kWPrf zkDMI$Ke=x8y+i5-O7J?Nk@9v`3i)SBY)&XT^ z%|?s%U16icAvZ_Ad|p+(NB3DPO?QLpIR0|pf_D>ww{ObatjiG3F{1nc1yqctCGU5%M1P)VL3 zoe(<&uY{|P3aXngy}}_#XIgVF-_>lqv2737s2w*mtnJji`jTGb0+r+m(g|^NulnKs zBTg#b`>{)q&a|EzKJ5|K11kjBIJ(#M<%OqL73cmjE>MXQ3qX)gh^?0wy`4UtRQ&E$ zmryN~u)MLY8Z58zcK+WZ<&HNr0b}v5k`dEh`ooUUu;%ED% zlXgB7^|*3;BY$ACQ;K_BJT_2Co*P^=YLkL0P{<>-a}?S~JlIrz4V0+r+m z(h0$}!kay&&B5BiAxLLh6R}pHjbw!5TH%lNch14uAy7%4Ae|8N8m{v{@Q$c?`k~Vt zf^?=e|I1}&TE`67(thco360QJ7w@xou+OSB zH6PyAIZ#QSAe|78-gaPc*WH`dK6}vt4naE8Vrf_p{z{?He8IuN89&sk{itpGKqYyC zbVB^qi1nGom^5{9i2YcUC^K9c)4naE88nbUl`=$OJ z?}Cj5Qw9ZpO=?-YUBeH2mE;N12{C5g1;K#dTh#8f#|sWYI@98az>Ipj(YGvz8Vp<>Gylh%NO0~ zt0Yg5PKXu#FAs*k@^inI5JV81kIAbno^Fs}1 zP$hVsX*Iz-P8&(ofU|PzJ6^8gEUl6}L3$(c!f`v*f(Vu1b*3e@ON9bURqy^YYf&m& z4W%_K<%zU}AXxKH>YP>kT8pNU{+5)gB(08;v31}4dO|H)H&RKSpbgv)5WItr{MEh| zchDiEbv@}lAlOU#|F2aodP$^`JV6`iS0LCEXHR^TJ<%bgm)MNS7U7DvP+)Ig_GGu( z&8qK>pCVWxzOygCNj8|TsppAs!2sd>8dmP~$LPj5(F=>OIQlY?6 z^ozyIIEuzH?pjH*-<9zZ#M>CDKk3-2_NvFWbqLjxSpo!SgX_lZT8r5rR!N?qJ+BFRJNulKSr7aQ2(B_d{9;foRvEEM z@&s)p1XnWkzB#NGD;b9%ooUG`3O1TywY2BHd(>9V?G>vePmsnv0>Ks8rJt{eX&aN1Z`lQ2;v{CESDVDtM=7v1~`PQ`g~c{g5c`)u1?jp zSiQz7$rH4JCjbOj$O~4ru3>ad30b}RvN{LBRd}1~pK2JvQ%Rnn4LtiGxYGZ*?v}M! z={tn1!hP{FK+v05ch4rZ@FrrFTIV-bY!7Bnmujsik z&(DEZ6ssgp&_+V+0?+H)p1an-^KuB%nU;8cuwmZa=sq>@?qZeX3DWQfLC}L7)^v6a zJV=KS@6P9}%z9uJ0zohJpdWUug_jzuBu~&rLU11M^X2a~m_Z$abfzUp?}mS?5RHmek|#(beg&c<8 zJW_>-mqSQ2%I8{v^+=vtM%B)2`uDwvs>LeF6SR>KlM%UF(63N~$elxw&a@(ttI&-e|S&wAqJP**sB%j~id#AxLLhl0$+GW|vN{`KXBOQmm3ZK^ple5M7YL+T-n! z%wR=INOsA3IqSjRStu||*0$x5#UUep<_g*BK}nvVjfCJ@q1B*8MXVhhf^??E5rH=N zBo_)?D_pg{F|&R2CMuFVK{_FrQM~Trt*Up~Z=OSt&a@<(2^-8>zA?RSHL{kGO7aA0 zC^ELMk~~2=A(*LNcgp9*JLi3GYl7^zNM~A-C5H`W!`lp- zUqm+C*$0p(NGCf7m~lUC_OHd^OYd+9$%dCC``$U(2k_tRnsXn3vpYcv?hl|1Y%{no z*=umrEmhdru%M{FrCRd;bg#kL&5yIa1}afP?3LjOA3QFoTEAKCHPPMPYn#sS=N>r1 ztJ|Z2T_1SwfRNXI{h9XvBr@^Bo8y8L&)&TD>ZpYyA*}?jHxjp9+>k`5zs2iJOKgK; zsRpjA%Tk3Z$rGtP5Otm#8;rbe>)NWz>P1ROslsi`)2$vCOgaq2t8K;xx6j(9cE`~Cq%*Azf8K01_UktpHl7Mbt|>K@mswqDO`9D;PF_1QBwnvG}bz6cu!KRG;Tze%gw(F0~gD#;V16Jm$EE(v;G zvP=2|gt@GAhV>TAwTrVmVHr;w~Fr{jT+J0ZW8>u8ukWPrwjI)B?A8u9q_eHB6f^?=; z=fR0)W5l#=VB@ee&J4nBo7cYI=%+{}d4hC8oHy;1V8_k2uHE^dLaYR@Gp!TO9Ah@V z`llK;PI>3Vpx#^C)HWTzd90E=K{_F>YkW*FwEpI`^?GmT5TrA$arK6njqQ4Lf{nG! z`vedC`%BGM?=_88k|#(f#JP=o2FG8ru4dH2mJUHW(`qqjpxGGE?hx2Gpc(QW%U9JL zQfwWoBu|h|h}~}Sf^9mit9h|rJBJ{hX}#F1ui3csnUiVbg$}`SxBOId@*(@jD#;V1 z6JnD!dk42n`n~3-H3vHc=}c>%k-f~u?K_vEL$$7C#@&xIGxb6I>{lo5hvu2ZbhByT2Ol$CA^UcP`kKP0u^`lyU;izRb zdv_cft0Yg5PKd(0ll?CjKV9=i_e&jubf)z|)9GeoS^Jw|WBAJx{X6cAYyR;ri&c^* zNGHVMo1EqEJ@@{aKC>@(2-2C>^kqkzjklxeuu;0~2!F`R+iMQ`WmK$^JV81k8h^5# zzxO%U*GxWXtV58_w4MuIDe<1KKWPSR>^b6F@5p)A)U+6IMXZuMK{_GEpL?sf`Ch|o zdL4myiToC?Gp)}i++a4|T|yf(qHDb+=TE3vb9dnWOSi$OLT2`Y@eO8QYlf+v`|9(f2HPOyN+w;q&2TdSP~_8 zU1{C0WBkvYv~?>4e>c;bw(RJT^{Cvz=#rbausf)dJVCnBOQI_#JU@rMLqLq7fo5P-{k~~4W(%Yl0>TETKyr4wH zk=dw>aM98k-?dIhxQZlCkgklP(Tl&HQi| zFvFRR%FG$h{(h%oI&)Sed4hChc8-IFJ&Nh4b=O-#c!(-zCL0$tt5l@OLwhiYzX!yR?|D$SRUNLAtW)i~En5R7_WW6@tH;X<-Fu|F5hp<3X3*T1;1# z6-k~TU0J=xyWC$>OjoZJg1?(-op|OL`+sGH9KZhF<3+BJRgx!2S61QiJvYTguELez zb*6qUByD#;V1D_&~+$!k9r>7^>c>r89?pEsM0iYFYuaQkmX zdcrEn6QnENcKpo!>x%TYmEd)z1<%`TR6P2)QT=tr)T6IR@&xHh)F8fa;y=ZmlBhw2 z;O}Nyh#=Vi5j%nJjL1a%RsT(@)5t_ck|#(f1fm}?Vlvff^rJ%XcQY-o{!IISCBhOT zCR5D_i%RkY>5T+pG9)}Dc%5lUJv@ua#E8kTRE!Q~r7~KHw1gm7bHrp=b6*K5l_&QD z1Y$BVVlvf;$@nVC6SRT*0Rl0Z7%`b@+(Czs*7c+>fIv(pMogv}y~I~Zo}dl%D-eju z#E8jMqbE9q^b$|{Gzi3GV#H*s(c68M5iaL@!K^qu%K_Dg*BPLUgkvh=dl2O!`F&_kCGBIK@)tC(e zmE;N9!2AIMF_{=KnQF{94k5FFFY_P>#AIT`WH_q@D#;VHfq4)FVlpveGMqUbLS{8z z=5r8;$;61saCQzZ8HmYnl@X{UPtXR|B_I%! zi4l|GO2#2%mEp_!3It*@F=8@B#AE`MjS8DDdCR3Hxydq&q zvfm}Kv8@>KLQJMAZQTl?S`uwTJs4F(Ovdh@O7aA4B=?+=JH%wF*h`dWrqqT_1+{=+cC3%82lCgvlVZ>za<>;e?L~A)FdhAz~5za?U=H7IKt4Q($ zZ6pLE+la}`Nk`EN!QaiaB&v>jFnW%d%p8u?D#;V1ld+uwgenHFYh`=!bXAV5rpSsAVXDv~@wIw25~2@sR1K}^OWNM~A-bwXP)yM&kwvrBA&I6vXih4)OZ;?jBO>o;@e~r%&9%t`EBY27loLKb1+`^Yo=4roP#?TmliV z^}OZH?=`KT&%D;Z>FR6ky5ERN{%PM|7?OCR?@n_ z>MuFaho)VF^r2}4NDvo)QWb_E7CpG4^!Je$nAQguHuF&$yGH4Jl*R~@4#fB0v=8qB zanr*gNvH zrx`aoASl#I0(i4wNGNQ-itGr`JB-gl;ymLmJ{{4j@TCMIL z?nWE8Eb9Evv>S{#=d!vUdWT)3w|KLjzSM{(9{34+)zC{yX)g)UOFZ5|^pfa5_-$UJ zmqh&Sw3kHIOG;@k3D5ZEGt)vZiCBIT=p_-$PlENaUQ$YXNr+zJr@bU%8}XWL#x^3s zHnUz*N_$C&USeA4B@yof3EmgphqRY~KrivqUJ|00m==0T#CuJG_n!Bf1n<4|5-;r~ z;Zt{?U|Q%U(R1ieB-p?1MSmi}{$;(yOM6Kfy~MQ8OQIjqXGyRR|B60Kf_>O}iI?`0 zGJ1(=p_hbwE=ce>c@obB3A8|Hy~Im)UN|=iYc~ zJJh%Fszfc0SEr#r@tP$26Ky1;&x~`2deIHzf{%|qYth@M^^5u~xYwJ091WX+98YCdd*Z$!^#J9w8i z+Q+nRX!vWmWY<=9eay!5+cj$LOW*aa=H;~J;bds0HTQR3{<2-8 z=Ds|GAa0%TROyd#R|GrV@?of_U9j^unkrUQ&1NM2Ao< z=`k3Ap1R@LuqkSO;t@ma)CungYpsOt*)J3t21~51wro(cGd(2OLv+_YpDNySj4!Y; zYTmnHOW4>jxQ^2kwfE^h^g^Lc5ZfJW_QpqLl_;SjMxpS^4yxl1k)v%kIAL<9ojxcElar^4Q;< zF;TU2d@L01-)m*q25oiMvlBY2M2U_2(D^PsAr>j2T0&#(GobBjR`cq{?e(td-3+Cr zF_!$Z=58Y{`RX2-T9g1jJ*9{#iN`^(c&Z&))IC zdZ0%}O1vmrZSejJX`UObh)h)HM-$N&6?gE-2N`J;pezB_-taI(qxmezUxOsQI3M zUFZ<1CG$B-wJv(dyA-8rdii9oMIyF4S7A!XY5>GR>6+o;KV~|FYROsx#NPLOKXq)RtJcA!E_s&GkuYTbbXJx5`yxjo=#$AsyC&pceP%T}T z;=Kkfmf8LI>fHLaQlWLOSe3wv!%B-;0ya+j@(u4ilxpnVRSuzA^5z8)P4Im4p5u96 zr0?OtXlJ$M%2HYcBi!UxFIzqC^XipVqJ*x_ahm+QkG&63s_DC4?GUOZ?dBB<$Clo+ zQte!`4)KOc4V|}N$o&BE)hA26cBscWlMW0y7N&jIdC!EjE{K{Alg-91KRgu5^I`8Y zAkCE%`x#rE<8Pr*HS=t557>BpQW(m}U~df|!FK@2(*{WQ6Qc+OGt#Ks<@N)mgC zB&rgwg1^SL;#gcLpypm$^Ue|%p)YGT=*vn!hF^;~+`(BKjy0q&%h(%Yaupw!|4&;1 z_xy;tvkt!CXS}gz+`N)Xl#n(A@$5U7EMlpauCHtTD*G+fLcc1p9=tE+bDFOPpEFd6 z60!mSaq|85mN{PSSo^#~sFtiBKy-OydAS>&^KaICV5cwH!@2rXLOe1Mh(LDEB9Q9$ zBN}Nj07fIVgoVPXqlR=o4{h~I=LbtFQ9_@aLSc08Kdr4A9#AJ#LbbGn*o$-Lf2^&3 z{B2;U5+z(;?Tb+>%iYmdGwa3bGRP|HF&A>K(y{Qi)u?ssFsdI*cXPiC?1Th=pfSPR8{tlEyfnL_Bj5mOXZCR~mp)jXz|DQz|8NmM9b!UVMwy{JjOA zl(kfz}hKIcorZgU9L(zgi|3PZnwCT320M=DW5 zJS3Frq9)5q9nre)-@F_12G&;08%TVYSpb`_k}SaNAHL2a!i=p}BuYr67&cbF)4S9U zt=nbvWX?DhLbY_>#XgxG{#V)qrFy&mPK@{(!5LWzi6_H`M4cT%wImu1qQ{muS?e}# zI?0KCXj_Q~38L@md)ghmWz%+{N|eyj778cKd&zo9)#OLZN~o3_9o%}&1*Idk9+A2I{OHT>al1Mu0fvijxZ}(IpvG-ievfULEO94u?PvH!wR7&WY z2={#UM^^L37u;IbQmK|kbP9!?Z|ZBU+qLfcvPzV2*H=>)KNRkZ5w6EwJvGwktis$# z(e`~`2zz0!-JbkNzLpSA)F)Mzn|Kx(ER`rB zISbs6kKetiv_D#R`5|2$LbY_2i8qD3+s0ds>{5>(mXuVYgk&~gCkM?kE+}Rwu1!QBsK#Zav<=_W?#1rXrRwPQek-G8NF&CbE!6eFqbMhFHcKYD15## zOIA{e5|TZ`{pi#D!BSnc?wND$@2rGssZWI{&g?_H8&Rr%9%)cgi4u}ygAK{Vbyh;P zBtr*6BB}P(4z?oSA);-i(a%C*$_Yt6s@bwjoVchGYP(Q?A85UVexd%BYPlJ#3Bkjq zpZ+^8=s0qp&MHyDt;cP59_kH3TRr`U?+~g*PmCT}k{`TvBe6&&LWF9&P>@nBQi&2$ zLimI9(deteXLCxWTGDPH=%X>O#yp`)l#nMXL_85b8hthRY!0DX8iy|wqNVSLw_^VI zbndrKgkA~BY{7=~#Ip3IPA(=nekg=pJqd_R+ic`Wu zLB?H;usDQ_uCT!f5!;G!6Kx;W(h?R5^oH10@Qz9ws3#&wC4|4>5KDvmi0~~tEJrD4_T3w zwd_jB+Acy?27Vyh3VxxkuR_&wYfe9q{R)1e<~AKdd}!-ye?-~ka%IRL9dQuJG?xHP%ZJ0L9~4B#;^us`}e))IvGVJB*PCvJg-pvs7O37 zr-X>4ZuIWdD{=_&^k9RYBirhvc`vEw`nt>AllDp5k>TClPF&_k_X-SNOYhfpoqaREa1WjJ|fC1hU)2#Lvr z5><&LK9k#XC-E!IW;ldIsbHgkEC$<(v3;$rYH0~^t_WTo+X`NurxGP3QV1IofpiGf za%-OL_j$VQ>z+!KkoYcaNOUliSYIU3!Q75Ui9l-P&LJck2^;iI*;epYH9F|*t<(}0 z3fw=&wt5FU=~SY>D=~7`V`D7bAyi8u-XJ7z;Oy8^LNW~?Bst zA&9B_>``8TvHj7@R+y)oNtBQsVjv`M5K81fk{p6lCnv|EIY@_)ObTo;FUYoHwoGfQ zT3SM^$ly7$t>8)89?mpV6)EB72S2{z@kKkKtuDLkWrt8Lx8`$Rue)dz+N#Icm7YqJ z;5FM2J9w)#VYj!D8Lh^X9A=$pN)>gGxsx+quLNbb)?Thk6 znrTdk>@0vo@OLvU(AgOQ5Xk12*b|xE=gx<$Uuj$64p#Q3BGz~8S)F+Yxhq#CO1Sl) z2h3gqkNE#0vf8@)UXPqR>se+-A00QZtP=fQw;tG4yogyc-VY^IOU^f-=5h)mR0-~X z$hJZbGPfHSImkt64$>)=5}Lub9HiA8{;j8_QZ3z)WI4zZTNnPVvqxA7cNfy>zpO9y z!X12Ra@iqN%iZbp>i?Q~UGaPzblzK@N|exDPd1j6(;Ot9k4pQ<`Hx6TXgNqbF@hXq zs1hYG2HP+3jDU^Qi_#oqSqatBJpncwl+zq!s1haQya{Y%r&5rEbO_aw(<&f_!vp5? z@om?~ojqRKR=Ru3a*%ch;dR?y0*-L-B%M7BT3X9NmiT zLsg%Gww3@^BENQ7!OLo?Pps&g21HPxT>s|@?4B74-5XeE=9YhY&AymuV54Y!5w|E2a zd~EaIIrO7!PZ9T!DdFxT!+N)z<{)`0rP4k;#laR$&zMNfk%P?6E`?flCEzC*&C@F8 zO_b9dBv;6l-%>634EBHSfUz88In6WtX>ra+IfQD#H#CALV&K>AGuf-c z^YL=C8$E3kZ7X=fc0c$(%R$;5ghx!jwjxnNOKUku>m~3cOG>B~Ys`Md|CyIsPIHiD zl_=rX1D$g)b5;8@7# zgCn5jAnl|ca*z(8T8Lj7!LwQT^2y&%c+JteXUuD*dlH@9X0ksK1ie$i1OHLochMZ9>s|2xd zYagCOQ`;5`FQ+-kMJiE3_u^R&(&NktpN;X|N z_w~_7hkeiLtZkxgr8|r*2WfW@o+M9m*d1h6PYJbcIY{dz$U$~eLbcrU zgUI%k(;Va?l_=rX13Abr%|SYZYF&2o6l<$W4l*M;t3(LfEz4OgA*58DwNy$-2}_oP zw3^$#Q8^*0TGDPHcs7yG2Xc_Qzm+-Y>~88)fRf#L{0m+yJRj|koZ%4ibb0PBZ`nhy zJMHZR3RlaFp~zl$*pQxBlD_0gPvoBDN(r6b&WvJ3qJ%sJut6Vup=IRAjd22O;w2!;xoX8oJ4X6 z)pBbtCy_#xC?RKzU_;isC0Vihvi8lr144WQJ)z(b;sL-0Pd~6<@f?WOR<*Q*mV>mm z;x15?C?Q@LY>0Q~5UM3!9|-ZCopakth))edJTLP?x!PuaO+2sM8#a)G%)C4GiX1{b zJ=mb<$hJZbQavx8m9b|VEs#6&!}kENUm*t>YT1>L$OLS37;&LJgAZLb%OO-t&l@>s z`<#-=gwWlwzA;cPqc(i)PNbqN^O;pXaa1|*JN99|Em(J zr6sf+q(!{A|5YVQNL&jx=xcIK4d2rtR7+1<;r)pXN;bA{gOk!KQ9@#tupu!Sdz%K^ z3eO_<&|6z^kGPf)S(%OTD`pg}t?*mm;!abQC?T;$ z*ud^pYb)+%RYJAgnoE2)REZK2_k|6K4w|RSw!#?iOLQ>z?j4ChYUIu#BpL}D^iJ8Y zxMNmpt6Ew@%RyROAqN?%LEZd5EY?V+gEurNgt*yAnRwYVEwgxuj6t+XCmYmK8 z@!Q6e-p*S*l#m<}2;?BMyn($thW(2B;v|QVdvBEFSoAcYLr5kCHjsm~91G7XYHd|Z zOK3Sr%V2Rgt4frRY!+tb^MhHw zF85Y0WE3q+#`A+(b|q*p&9T7-Jz(}L?#fj{wX}qm?X!ICbi9d1B}$+T<-{S+2eYk^ zQFI8^lH4{*_0QO;_LhP|hmS**C?Wd*K)m1ig!sqvH+Z`pyP5NzZGD6GJNu80wz+AN zx27ZCn%(|`7V-Lt8@xC;%y~;Q-q9FkZ;QNk^8Q9F+LLcE+pVyz9}nB$%^NbB@06{) zCsp5Py6y6#JldGpfN#2;+xG{5(2X0s`FEYpHxF0dvZ-&w+_(P@K8fA;<@=DQ4{99L zKW2k>z*l{o_gU(jDzBNmzY$5PM(!{o*m=wb@AP}FcHWGqZ?Id|<7Ok;&%Yk)cGNsb zYaa7$k*qDh3?eonu@PC#qqOGy!cmz7zvmIIVds@26&|vilLq{Q&XWb5%jd2bu(3uKhPEA9JqN@Xl^sqi+v7%O5a& zhBtn$A8oemGP}O~pVlBguK%(B@*c+rr%ryz(K__HQ~j0WW_b;tJvf@OaHw5(n%xq_ zbH8ovtvG&k@a-OfFMB39`gk0>crNwcmk;+ykE{P5pC^mY_3r6EI(U3lCtr4?IOiY_ zn|+@VeX1veXtCMdUg?<8!S2=j@!fWQHrL92AODmV-xzVusaJ!T`^C%N!@WlbPi?-3 zbE*w18Kb$9IVafG>M?2BXb>;;{K5O9$LL^LO*6jR&a{xDa894SG;%K^`qv!{V*k^& z@VD(cI+$FwwJ$pXxu!OnZ^@f^VhzS3_4RwUx?s)O0`LdT2H%n=_XEVz8}{?NR*w#P^qbFj!I>6Y8UDFl^DTM3 zULS9zdj7OcK>XFG?In?{$f8qQd}9Q92?+F(FzqFLx1AC6J!QQcof~W$u~g_K zAka&~w3qPRc1AFhCB8v~USb4#2?+F(DD5SY=DfsLi*7x!hY{!{Aka&qw3me92}j}y zN9ZL+@OiXe5~aO_@3ym2u>~Y*z^B%T)4c)5jShN!wZF5YO~#c-Mg|ZaP71vh7)!41(bn1hC*w*aBLj$u z?Y{C3=rcOl^PCpW-b&r2DI)`j-?!b=Kda~H;FZ%GIeT4YT#00405Rm;?fpR*ORCN; zIQxQST;V z{j{|obQ&Ezd138|^-YPmz_xo}!IoaOe`iT$Uzw6}umJ-MaSpAs)!h6-8ndQ%aZD?@$59d0BYW>yiCM(tZUvCa#v&Rqf zXEzufJoM+=WtAwQ=ceGRJbAzc?^CTZN zaNObk`TvXx9^Ii+XC+iiPuJm#>FwtDx1%26=ab7SQ9|sYbr+B7>0bdGYwFH%2-OnX zAf)DHl_()C0^*F#|F`IOjO`6~K7`&@Hnux&P?i;dZ?i!;oefB2>jdWw%CZ6gf!QET zX9LHVmGy%!D*zIEOb^r9z=L?wlop&zF`hn|2Bd`Jh zfl)L{M^R7K3BIf!d|3g2zz7$mBb<}Fk@bToD*!wn7~!IHgmWZH$oc^UMz|;);T%G> zn)jb#^}q-R0wY|Mj&M%)P1Y!$OJIbH(h<&)D1k91;#k7>J=+Kur6Zg}s1}|TD-}jK z5E$X2bc8FZL4l&@my-< zw^U0q;~+4?Md=7vR*4el1XHc%l@TsVN4P~wsFvpLZG?-`5w4^XCBz} zhe3SUaIxb%>pIBwwjUY2*1YYm+f8-+a3yrTf^5dU+XO7t{jc5Q5UO?Cbra2_Z`*RS z2p@2H=5MpH?9joHN|bQdC7b@+)ao(qsWA?rTBn>c*=%h1`c>3CSW-7&)Zm6-uSg|I z$h-?;M(-9@kKZpiz#&xYzP>k^4Yo9Pd9SHwHvWBnWvCJ*a5sI9iODLX<;d1nkMquY z*CABvxIWX&Msf##>{#DyoYb%sszeE$cMFAmFD{ymLEYDul~ApQeW#m^OtH%Xb&GA&CgtQw7^meNUdb>lYmb7|e zBj!E7@Txh^^P$fK>}6wOX!VHse4N#+6skmtt@}=o_;gj;%50#mxK6D6mTKuJVfVwH z+QHq|mQnhiXI4xw7^?0n@51L8F={N@+RZ6o>J@SPqvThtM; z(C~jp-D1}(@7^jb6yQfinIEN*0$DTATe22Oq6R&ePKox#>b1xC){aC8S(jkEy6W>^ zBlfE$-6lGOYGE9+nkOUN_)E67`?2Gh4{*GyNR+_1YyVH8ocFcs5Hl{i<%CxpLbYZc ze~r~V`0wT@)h{1)v9?-!@VAjll#u8-2zbI#<_XLCDv}jhE+%vJfC*7^wAHZ}9O6in zkX0XSjQMPpwbdIB&vFRW(h}mG98Ydy{p!yqOE`a2+C&LNhwcB24r4#VfHu}vTVMKL zhfpoI=G(T~&)Vw!gSL!Sq6DJR*1C*F7Yg%+?GRz+v6En9#}iKq4?*<2#k&VPu~6}f za&gh84xAajf5*_^oPX|iBua?q1siSpG_f2&5*>Y2W`^Giw+wWG(GEXMzAXq z@p0J-mT5pX1EpHH>@e>oj8`l6s2?k#T7%Y2DzUAWHJlEje)k7Gw$%tvY{pYOE3^BohbX+^g$&HOS*k zdp2+)w35fk)x6T&jogIgym&fKOIRp8ee{RkK3#_e>zdARBucn(>Nan;_t{n-Ppup4Z>g4+5F_=# z!9M%dR;zc4RieZXf3CK+`eU!_aL-TfaJ9A7yl1;Rglf4pzdO9g+G^OpN5?8rVp+Q% zt*xHf@_N{qGIFuE88UH89%$oyaY!<8xp@1ruk7u2IAB=N>%*%Zi4tzSebzxYTU)hw zd5uG;R>QvA`+TAW|4!CvDYti&!N}ENr!}5m&9f5XAbES6Ewp+Grn#P%X(+ zljyd=+G^AronnI;*;SEl;`!Vm9tsO$OutK(aBrD{hoAnJkVDwqs^ct?6D-tEthr=HF z2Tr$o+}v;nhfuA3`_HgnO1z?AYTx9Z_g`C5i4tPZ!}+LAiH&PpUE?XCT2fjNBl`3< z8~+>ex2F;%q}@Qko3MJooA8xTEopTSl9h3?(~^~81k&g13~$26TW*$4@l$WYktiXt z6A8@rDp5klO4xumk!40b$!$7&G_-`+ z@6&6DpL!FFt5@1Ya;dqU9PlQrt>8^Kgk*JnEunc6wvvH2;YgIIo^qtM6}$=51KxzS z6}*W+e@nI8n!}s0@e1BVpb{nEP1slhZvr-CCBuwKwt8`P^2q7~1iT3^^(K6k$U4ZE zwH*j}6V_JnCITf?OV%qO;7!=<3~wS(i4w9J1OactW@mU44xw7IUI77b!e(c96M;&U zkkudvcoXH+n{e`6n$2=^UhpQu)SK{Cq6F%c?RtR?coSjjO$17)7JPP>)vHxZ`Z zM4%ESP^ZlE0s(I#OuY$*P%Zcj<-EAP?O@yg8;biz^zYlwf z)EwSKn0gbAL<#XlVFTVon0ga|{+4QK3C)`@j~?Dcpb{m-dxZ^n6H)3-ID~4sHHSA5 zrQSrK5+%fYg$?oOov*{nPN!U+6W&CadJ~RB2{+FPZz4*)i9liN)0+lH7Ub`QyU%{Jz4R{k_>P>Jbpk=T) z`^%24T)r0GM3j0HjzkGJUkh)-+6vx;L#P&fhA8zWP%3y6Nn7>ZB2bAEPqf|%}i3}P3nL#P&J zyD0URK){c(s2cnz&Vv<+5?D*v|C7DWSnrw*tan3=g<~aaT3p>rd_S}`baDv_Ey zxe)At*kMG>o#bcSbG1WAJ;G0)xzTLktL(6`L)VMqYddZ5mcH^}bjFWUOoDI1J6cjF z5I5d>LA>YHWBs$fm`=YoYZHf1dxgT=M;&La+pocO4xw7oRdCCk=>?}AvWF$NQ+C#? z1*`c}&HFfnX2!JDk)uCk2g}Oz8hDM4I zf4!`i%>D9drpP!0IdbzK&rdusJ{dM1e{$bg zB}%jyG|=b)?GAyBsqc4;??FA9U%8t@sFutUAl{$dJzm;ngV$zxD<>jQ@3%>8z`YC2?~YFcdZ+*?zO>t^X3y{Jxin~hGhK+8*8@P zBKAj(^}jx?FXPlUsKWb0E&LLDw z_I1L>m_FZyyW^Bl`JX|WULS0T zKj@tKQ9?XD5dFH|8a{LM=-};(_jgVP$sS?HHoj5ieI9;-QeAY_ZH`0<@u^|s)7y`< zo_KlvIh0gyy!Fu~$gPS?6tAu#ru(89+8FmNzPweUts-?ZBP&n)To1?Yx zSWdpSpVLc}5HB1y_T1(1h%4kPjvVL^s-=Azv)Xqx5ohN|54+gu?Mj??*nE2mK7N#0 z{npKnj=0LWdH7IfU$YpJb8=GYLSfPFL!yhW+~D2$+ojGv06lBDyy}di@nY$I`<<-$li|+51mmy2jwL8j2`PBzvU&)eg@UT^Jx1SaAF-c z`j0u>|L&9xUiS?no!ufz$a!}Vg#+sOydVF0a)d*umbNtF?H4ciF28nzH}tkKyn~gy zri7fYhmAQ+ul2I=N(t4%J(oKuC+}l9ZO?UywGYptV>RG2s+OET$GXJN)+H)YLho#$ z@SnkN``phkAn4)jfKV;02KNC)c+kz^AfalI%}}cNb*dol2C@`XPRGLSxHX z4*0MQ{qxFisg`6gQIFN1)d?68zNJa)SS3p6E*to2zkFc5Wc-QiA|+HyGO@7n;O+CQ zmmGJ%N6uMYC9vwZTyb*J`}&`H`9HQD7JU8l2!~KD_y(4{Pu@=rZ^FyG36&_Jr;N=X z^u-^v-{PKEdFOy*yHI%Z(n0=`mcxSD&j&aXB_!vKnzyqDv;y%qb93KoFH`c%XvtOMZTdF0yFJJ@jlL`1fnca`wjL|5o2lu2Yal)Bn%*I#$ zaIe~vYYw-1oV`UOhfpnTX}mY;lOuxQstw*<-|fh#n%UrfI3*A-GaE@94w1V+B6k%+ zwcI=S%g~|0s_Qp+BOjO<=^fO2BX5d9)cO267g;?z-aIi zhGQKX+<1`)BFspnuN|UbDA1cL>#b zZPOX{OLcoRfQ@e5E(^FW>2UuYp-Pm{-D1cty*JkS?$f1R9YVGI`ZLW&lJgq>(Ph?F z>znN0sYD5}=OJ3#GqG{}Lw7iYYDsB9AdeHIc^qHb$CG>G>|wK9QP38-qQBckoj?1SASP`Ar=bA{MZgtWPTh%wY2wG=Er&oGCxi)Q9@=3-!eZoG9dHg z5UQnp+A=>un)z{hyAm?{zy>lu*~&7IwV^Nbt}iP95Xk)4=!48ppb{lyYzKkNkBvUa z{5XVa$-DwW<`3>1$mS1U37JbkAoCNXnIDHxEtwxdAoCNXnV&!VMEpo4xw7^9hA4E1>$q~dN*Z74jbYd1S(NN@2q8htnVW8 z;}EJPD{|OC=Ep`jWPSpbC?Ts?5Xk)4>J^zEUkTNc6*&lGer$z|%#W`UCB&Nmfy|Ge zW_}z(wdCzUAdvaVR{GBS$dr&ZJP7gb0`cN}@$P)_`amG_6Qr4+KqX4(eX`7t&s8`w zKMtW<;2PsyiraG@!>!q^OMEM0*P|@5-;&3t^qAq)eb<6x%Z%5|GX<%LH;}EK)y~i>?ewz7ldWjMeFGX7+^W&$P zABRva?bDX|@zczY)7zDhI4o=+^J8&QWPZ3)HjA7I1DPK$&HMx^Q9|oynIAiyiOi2fsFuX{VFQ^T zI{}K!5BF?mxdLAaWN7ScAI^+|K<39wGd~WYT9T&#fy|Gc&P3*id(X4Xh_3`PG}+l# z5Xk&^Y37If+be`>$=5wWWT#A#`SDevgq$A*fp<-o(sxZdgq+BAY~$_5+g)`qcipcZ zILndbh%CPY8_4{W(#(%jbJVG#rLAt6pK_Y{aauP=WcfDOK<1~EW_}z3zgyAL-eZ}c za+>*ZdP$DRGL5i-%ugxJ{5S-Dx1yze+A=@oH1p&1_8gJrKVd`mGw_YQVfx-$U-H1d z4J6O4EN?=^E`+@fh!v-=x zS*F?{R7SPrTHP`~ahmyYT2~3#y#*VxE6gEO zOZ$SeGc%CAmGtf+KJ(b6N&nnRm7FD$eSP${D-tENewO*Mz30gMID~4+ZaUNhnV&e# z`~)gdLiT%sK<3AK2{J#v5~?M;=|CX!W4#2KALqS%N?_G*ry!CyK_l}MrI{axP%YUN z1{<=E%y}oE60-9QgzN;QKNxWj12R9(`vKj0AoCNYnIETAvR}|SvtgMZt2r`14xy(+ zv<)ruW37wKkJGwJ=qV4&{Ma2t=Eu2%s-?ZhGCy&e`Eh!Q5{T7Ue?xWvZH3H_JyFQ~ zID~3xpSH|ToMwKU-mU~zw0AfW50zgl8-2kT_fA$%N}9aK;|b-Ge3?*39TR2)Kj|K z{lFUp9745ZS2=9pEd{n){hC*n^MtgG?byfeE1_p|>^*mO-r&C1?r{j!lHKvJfp_Uy z-^IK1c+%URPM#W9LeCi4n};L5d3e=UtsO$O-t@5=n!)LIvB_;XrU2|1wv z8+ZqVJ+*iTghQy7+pq8r2%SBVmG(h9@{buO}cbhvq(_nP`A`tYFF3@b|4OZU@Z}5oxV*-@MSXlBwnXBdr!NID_07Je5{P)M=keq{ zwea2`J9*D*X0=ZL{z8ugz84AN)2ivE_8{6`)xl%@iduWUJl^70yk=gCUtA=CuO@=P z_vlM4K^%I0JCCt2YVpe#9D#Vvc-gdnzcB*e4g@jhhp$TwK+NC0mB(l%wfKcJ#zJ|G z(T!gK^J#?PYHyh=X34RAPRRT3LRO*NpkGRY@e@wOn;W z7w>2gs~a6$Vy=-|%r)}P@fz<}^A_UHk>H)QZ~c0^(Z(%{?CsywI_I*w9(xC``L=O< zN7V@S7V9PDw3mcD-AygNU5f8+<27tW{DKp0@T;QMOUh|43F()mxMfjOfB>h`-TRuxdx^t36j=J z`2BPCk}~IQYVkYgEDf(&I+lh6OJ}`=-zH}-DRX|M7T?*=8uJ>xBw~$8pqGS|FLbk) z*jJ~i#V=p*G$60hORQB%B;O53FX30G*-Oeii%2cLH=idNdCfb?J4XV&1U6c&?jEMS z#NMDxE%Xw5$1|_FW13&vC6Rn}I{gk-%|gwL6^Uf@nSpOp;aiRI z$H$(v=&jTG`L~}tgJ0Uq2@lnUdU_I+`cAAA{nV4@fw7EuDl{%v+AAj$p$^WaQL*aMfdc)Ob~~e~PpxhKtmES=w|4#fidA}_yh33`{C0TbxGUmI z_T1iE*3LJrJLV0s-zE)P&i%)iFk9{!)`N|w+P>~R{NN*2lIivLkEB$QlnVFb)(KCQ z{(z00Zu!vTxAXYBC+&P_#4iZ)`r*&JM*KP->%lt<4|22F-nSs;|1s0!msF|s(1b=2 zzbDIUek)a48pLDC7YpNmhrefEETq^vFu*uKt6eqYT>h40ea ztWSFThkMvHOT}lVP^fO)o?qLH2ef_7zP3p%d{Now*Cct(`@t_VZoD5o&pW{@qaI^A zE_MjL=lqr_>0{fpfsGxX?dvsr^@{lBxpPC6D8VO;HrRVA-%E}A4u9GqREu9&r49B2 zd^h~AtF0c5k6K_~Sj{9#u!Z@5v^a?W4O?Wy{=c4Q-;kzc!pvtpem$Aj>{on>St>pS zXx;WtdR6&%Z8o2-T8%j#8yxAdZ_}KH0v*OY3~@ zl#m_+;-Iu&J^aT^hfpo)Zy@%*=Ob@F-19G*&n}~PSb6z1zN>n4v+Mn*w6ZU>(>6y8 z%xWJm_s&GkuYTbbXDm^I-*IQn`Tah`WP+IAGL4(P@sUHQmX1V)!d)$v+5PzH-1_zv za9Zaxrv$%?P8)nKD_=~H$KGA#5URy5rjzL3@h%We>Z~*yd`_A?+`}XsIdv437AY4B z__m?d1K&C8Fc| zAnJaz!eb94!B*z?GI{;Rwml;L5(&0AJmInS1<4p+kaP&0IoShAa|}jS|NeXVmCAU> z+UGr$D4}z3q0r@x<>hX;gWs(Az#&vi<}TQ1u-~L`SJb2Zqw_tqs88#B{sz_g%}UbY z?&guM3<`y|myQo7!p8maJ7oT%HK+7GM{&i zeM)9+*tost?V*QyY`W=aPbKJe6++it__l1i0;oH8qC=<_X93zq-O$^gy5ZTdDQbS= z5kokhS0qa8c+TGT|2?NI2GI~-n`T>WiLXy{&f{-!oxr(}*L=FTnqi$dZ{h1I^WF_x zg4i&)jL0j4Bx6#319Aw3)`(Li;rwyn&vv1-n_da`}n952B4omHZQv>}LR-?@a}!j6}&|37q{dAv>4|NoD97BWU9vrG|+d-gt&P^Oe7 z5>kmqgmSsZJZC2JJT#b9%H8X1GEGhxprf_uaLJcTw}1Z&aU2Wd!-(YYby}xC&XA!I= zx6Vt>We$hF_DV^o0ovXByY04ScTDgsEP2PeUv}05vRa$853Q$t2%>u?|%A5Qfi#@cJgwE7N9n2^W;DNR}Hy}8y`87sm} zuokTWf_STRRUL)@+F-3U=VV*)Y!YXlrEb*{Y%r_6_SaH^(tk6-X(KMf^wc)7 z{w>y`^+deY-&J#Z&;J?q7v-57W(gB^K7OeBf!6@GdVOn6hY8k_)jP43tod52oZ^8? zN@&G1!wO5K;#Iw8@m2#HPPN{O30mbu8XvzoMRUGy)e(>1inVB@52EV}MRcWT{VNe` z-G>R9O@Qcdrk|GJmY&lsg0*Na0-{QuDbBO_K5jX`P)C&Vc6SkGi>f|fH z|3I|rSVc>4O4h2@ssR)Hw%D7oY>U>CvZGgf{9CL=E89pT-|1JqM_{WZEBl98!i1fV z7uw`A#b7JbK9|D;Yss3s*h>5@)_S|dl_Vv!_MTzQvTE88FM_waC)CM$D<*hMgfgFh zNOOMctJ6GwE7r1Cif$X)Y)4?!UU}cfT;gLDU%u2{bR@#Wz{#a9v&=~FhM>G zl*i$3$9wm}x(6CIun5-TQ6}~@d|TQ44o^dqv)jWgVS+pxNaNREYN-EXEWBh)uon46 zkn_d=e&XDY@1xVQ(!54ujdAVOsNcfvwFIk_-R`l3t;=b{U%TV7){?AyBNoA0_Imr; z<}F)u+{3+xfa1%tYH^nBW;eC{$oeNaqHBt<3B(!CJBgF0D^|J#qiW*VVdD9KFX{9c03u zO}x-;vwk0yGQVvRtR*W)@)gKD3+q={g_4;UR;8>}P9}H_5ODy1hRrJRc@63!zSN|B z$miwo8-_wBZhFbWEU}22-ZPX(%iBNnvcS5}FI<|!1o_ykITcp6=QlKC@mBw>%p2y} z787y@sFbF7Vl7Wx3KOg)w}}cNeq4-wK8vq%7OmMioo&LllJz$!!T9|A-KXRJsFHiT z%ZxrLVS>}fdB~Ut%8Ui`!q1stE!%@NII_a~<9yV=@9le1Si*#zkLj}>GB3kcpZ)Dx z1Z&A%t&;P2KBnCy(pf@;&QxU_94F|l()q2Jpf|*P5OXxmxz5?hN5@)ZHxS|%6u+9x z*;v8^eNlL`Sx;?pN~49V(QK+ku$H~*Ol$hQ@^7s)^9r<86ZIb6pvLLFzw#{pVSYoa zwx_d%>TU)vGUjM%E19!d1o@gdPq+#5Vi&cQ%-L8%Usr~;@GOse+Lo+(^oB)HJ1>4O zZA)Yg(DF3MdQwut1ogEbs4elRHPF+0#a7~d=Qp(4U0z|a2x?uC23Cl)$B`8y{w>zx zH^h$hS@B*?W=AYxf_gZlajL;uwN)?7z?fhy8kc~O)n;jTS8RRGVF?rDF$3{k(5tOU zo$FB_WvEw^RWBWD$9?qFb8?Sk5!8z!4b1A)Rx-=u-(oF(L#)Zbn=jv>__$fZ1dZ*G zhOErX3O!cpd1S%kIbF+_J}SOWO&&$|J6Z&J{*VTZmOL8o#AvjXA@+ktWFEge6EwDq zVUNkGBWf#|7c#+GcFr*mR9nfskR?peoB?T&XVfBC%g#A@Mje(gK|W8ULE~MIMyxR! z`(}u&p}7ICi&_ND0FZ{PJW8)7Yp|SK*5WtBTrF!=wUx}kSi%I&!jJ~d?ks|}Xx0aU z=FV2E0TVRa20=3~jcSrMO6Hq1^U4snM6)}d6DI5MwwurC!)NA8T~i8OQ?;+Rx# z*z=29d*B_Dw*8jKcFQNs1g%*j4O)}YNH(#Re2cU`lOg7g*00!`VG*=Sg)~A~%a?CZ zyc(Qa*5WtB_fdAc+Dc}5EMbCH3Xw*xy0@vVZalosB3R4LIj!$HEMbCHgpmfV4r&aa z*h<=XS{=*~(MT(hymDs|v>J&tFgsOS$!wK#%Ub+~*e#35Ir#>^S=q&52@|w>jx=a3 z+#*=Z&iUFP(kawypTiO+$Zvo&Xw})!y0P9ZEOwJTrsYv&Z=dzMLP&aY zQ?wF^y#N-$T1YRkM*svOoHR~GBA&=oZTVPHhPQ$b(t0Z<*n_P;NX@y-Z~3iQi{b$AR+!IvVqKZvvV;jcCiRED$Gk@PKHkgX zTLf#_aZ9U$XxuYDe&eu&366o)wj?apg%47`kEDI%9>qkv!f&WPNZm04AEfRl2t0~0 zCeQ{eEv>e;)G1wHUHBk9{w>zxm;mh!!hsJ`cR5HJGRtE^c0$M-%1(ltyHenTvu72@`fcFgx|+`;gfx6Rc%Nl4ArA4t$Uv zOPH|pfl)>{@ImSx60w!c@>omunTV}q^kMDC(H$rW3C3`$CA%&-Z4AhYR}BX~Nb9Yb zz(`HwCuG*7K1j{E%su(HSc@WSKwz$Eld<+kSp;igZm5Lp zh(RP^uJLN!TZ@gfA_3V}CSbBW4K`c0S;P)LJ4lNhVm!-kX70YB=yg zdMshW&Ie|~PT+$yOt6;Ruq(Eb8M68y6Fb8UOXL<`(USc?{7dMa(}sitAEfnGOmK9P z`XDvuGB4!cVl9qt#Qh)RTd8$rUdR$A?1;t*8$U8N@qILz-IRA!Sn*JH)MVjSn@n?z zuX46%?XZM@SK{MjL?#iGx+dcUK1h#qEB8B#t;F-rZ>T;<-9-l_ zWH|6aS_ErxyqB)3Ie`z-V+j*z3pEXi!cZTiBYUvmgR}_N!uq8WvNtOf!pu>>51C1F zgelvK;uAq&cB&;PvsIQb!EdWRNUbF@%VUDI&@XDsfF1&AU?nvi_#kB^H7Q}j&If#u zPT+&I2-cD~A1O`QS7z-|^jJds6*a0+TBZ0~!3P-*e30qFVn3(H5+>kp(O(h|je2Fmfe$jB3D$z|Me72_s>la?kWS!( z^jN}#?ADVqmzk2aXH+~t$=_nF8=Lx1ic{DoY%9zIwFHwsNG(B`NwS0qPFsDD zT1zB0l?m3e_YcC`7Y=-o=`3Nw&If#uPT+&I2-cElP_b3g2bmyJSVDxuY2)Otn{SoE z5+>*k!|H?7oXZT13DzRJfsi;+8DGg>MV2r@-;INPUW>ob??ZN6Fu__JlO77icI-FP z(0?5N;8!bJoeA2(hcu`rhN&(&R1?L2o~Uog2R!bH+Abc&q=X6j3Xq1xiAq}nA0*e^ zFl+G}st;0aC37~GFhT7x(#ZCMF~!i=7JlliMX;8g^J6!6H5!&MLH!ESptdATt${=B zN`{@@)b4VuvqezriZmojU2G+>+nih0;x|+uq}mETNRK5C-BltaCm#K~ywk-3%Cb8?Sk5!8!?%UkZLRVAbEV{uok}|BH|H?D(#ib3t7Sh%^8r!^k64a_N=KE z!CJIK2}I+YyPd4P$V||D5CnXXiScfjMyxK4eKVW^L30D%p0_CRmH+&LHmGHP$Rb+x}aN53JoaOwevO5H$00 zXdWeJg=udo=X3BIYJ_QGcE__Ki=dev(vav?u@!ufJoA#hGWu;}RxA<5iB$s-vKwCN z6?~8yI~%MgSOl#W*WiB$vfC?<2u1g$0@9}@2>wt^2*yp~CVwfGIy2dOJwGWTQ&6SS^{G$h_t)@0y= zvzJ|SK?7jN|>NkDiH8Ns;%II zjaLX%Vbt=R9$)!Dn}WX;{Jpt?wcYS{;=A2KwDe z8&9i)R-SYhL}CS!SMDr=RwI#yM950Lf)A2c2dz_p_zl$uskVX-Qul<*H;8B?i=Z`f z$;ZvLaEo9qTJZ)!yMC>cDVX40d)BJ6L+i$}S0=HVZM~tjvK?ldFhMKccq@si6cN5!(y)XH@@658!)a^NOTborW^c6!*0OU>K1jn7CgeHrS|W{v2TRVyA%B!h9;^(f za>1jhUNYG~$nVaCq#-LT@F*e;iNY0IAu3l+<4Kg`j1?PQ$6!xAQ7!^G}> zq#fcwQp(}49v+7{4Wx}_q zr)ih1JIVA9O#l&`zeqPfR`DE>@ar{NQ+{vF@ex6V1^uU5{z z7ouhP(IA2|`+YgHpIZiQMdh4*AzplLD2U)*0Dt@Ym92BmxW|z@0)!YjDHTL;vxAR2 zy{&W3xIdR$9)yUW_Zr;I;p0|z>zp$lU&%ckLiA`ZJCT<4Eb9JvU#g$=@&Bw58INA& zwmc#7ua{HOaMq;TyLzgBy!l~=$Gbez$GMYA)SG`N2%I(P?k}6_XD_LK{<09LB_M)(!=;v3=bWLI#N@5S6DMa!3xQe!A~>;EYKe8u8ET0V;!%>*dxePK z2N|5$E49Qr=M1$(3Gw#GiM>LgmLLt(l2}kntk^-0vy_u{g+MI<5u8XWwM3)AClB_L2sVz@a=YKe8u8ET0V zvZ^X4hYEpOVzidTe$SmMwZuN>?B)&*bNdtTDuG%8;?6gpmV16;V@yw1?g?9P_b5|u z_XtPsCHrtpUsGfGD7`IBp5v#5zFoAJe_OxnrsKS!uAJmpXTh@uH!nJJ4x~KSYBSoA zGbj_Z-n-=E-X*iJWx4LQeA48>i%4P7~ZXrN1R-UCY_Q zLf|G;xfx2I*+bd2`xF%SbkS%IS*U@FDGb+LKQ*Ui?x>PyIrUgiB$b;N4Q^g^<*q)F;JjD88&IC5mT(S3YWn zO62xjxyejuxnWms9FynxJ)^;GX;QEBX3~Tf)2LTU!0Jc?^~w$El`l7u2!VPPle<#n z8TCr;jZf4P5W)QhQm=fu(?GQ3mTantdegjEJ$@Hy>|P$aSe#K7BbcIqP1uP_JTg`g>5XK%idv zxS3Syl`p4QiQ zZo-rkdxa1mgq+wbTJkI>>&kQTwoN(dHii>>ErPY=TweL5*e8j7yE{0_L1Y9+A`7jodBEHG_JF zn4Hosza)3gCQoBGl@FBmS;7SM1|XJPPVw8K|2T&GgqdJ1>PtXS{~;}drYj7{+8P#Bp>m6+=IIy%-0j2@ma!z+yx=@g|7zTt=?~S zHumz^>t^}vjuydM_E#I+$6^lP3~9NkMN;pYb-dLYa2tbq_2vQ7XZUp^ciwZ0Lw#aQ zZbXq^DpGhV-YU5H#JKPD_gTV(+X_VWm9PlLKJh!M)K)BEf_i7)kzwa9KDg4<7}1oigQpakVs0e$!24h?;lF{<_-ayPm39}ybqxm1_r{tvZC z{8kdGiE^7qQo;n)N~D4QBNFr<7QtFHW&}aw#0ZTI^;TUe1DUbV_W=U^MG54hZxgaywTdjYRL|vKIAMAkr(o9>X1n(tkv#A9Sg=bg4%Lf&L?gI}X)W zEMbC1;ULg|#De}q?>S=vkARxOVW_pC=)ck0ukK7 zBmIYbgZftTJ<}LYzWJEsFMewe`VT+oKdiL{8h`5jCXzP#52O*?+M}%xjb8QE9{F8q zacCq90{w>{^dHu5u@;Sx<87iJ^dHhDYCdG{%vvnyW->eY}2?lFmMiqDGVt+c&D ze`gUiqX+R;-sd8?y)L$FNDrscHC9OOS>oVdBNe1f}EUfqZBh$cINY&af8OO08F#2I^Iq zB}`Cy$Or0`AJi*{3D%;tL7=v48mR3KOPHYbb`Zf`Td}4ee`T$aQ14^4F`-a!pH~d` zd07%Bc0*q=)pYU3c36i(oA-C)~}^;ttLErB`dmSi%J518KBBokMee zfyh0_9bZzk~M<~c(c^A5s&iDwzhF>e%@67qsx0dCRhu8 zPbK0p+rgcBu^He06{B9?T6JW*q3*`-)QjOxJ!}1n*D2)=H?b~m&Wj~)Wb<(&n?ClZ?OD{iV=GCE!JYYC2uVBabsbOB}~|Uwcy@9fA2$GErPY!ZaC}y{3N*>(65s@ zQ;a1{upbZJjQ;gv?aHV61uDL4`RG`SPYO!jof*U3nLe*N@@gd8EqOm@%zdwzwaUqa z+|?=89r%F@>+af6R;~NM@Eg_|D{Haca2iRQY})P~%)c?l5+-av=gRnfkUs8%v zyCv^~^l=|#j3rF4UlltJAFdJmrADfsdCaGl&y=;`iPx4PzS}9dBR6)VYl`K~pjk?c z?G_5{dHPnZySO9QS`lVK?qn6~zP;foSogj?x2kok{#MW;Sc~n3eRth2#H8n3{>kwe zOPH|z&WCd!mOCf?=SF{I5v;{_3xzfe7!cb~sHeYu*8`SEnhExEBXZz)nOLM=s-Ny0 zGyGeu#itP=DhxL%ISWUkF(QYtcEd$oaoRzKdNN(?51?K?k4a`Z4z1vE7olfXAMVG_m{! zOvqi|V%<019Dp>gwL2PmC0)?&M1oVcxetZwa|ev5-ctq2+>I4&m?8dmjZQ@drVU**L+ zEP}Np3P!9eEd+K!Tw%^4+mlj_rol z=iYNh+THN?&-pB2qDhXHYTXC&PedA{8dX#4esEVai(oCb8|DUWOKY#Td-0t_B0ge*2e(PnJ7Q0TMP2hBYVdiqz3O^vaHf0yId5R+PIvU&E&RKNMp_gVyN z@i|P`&5<@gEY{s|wU19L&EgGBtY&BMjE>m#swb;B?e=!GJflp!e08KJEyLdYlVROl zBWD_Ecf0OrX%Vc&cEbr~jXpHe?w+{6tj`iA?6|&T`F=7oW_V$H4vSzdwi|Y(l$czb)I8IU^0QY=frKINaK|q z7rax?Ag=F3#3ERW&v&w-ievcQaN>O_o?6dElC~s%-cp&8tzD_@6W{7#`On$U&6W;@ zYF~fAmGbB^yPdQQ$x>qiHPn&vh_@xbR{q72+TL_c3yWYawsa_T_O0QLjF1bZmlf+K z%a#ewUnn$a#;ake?O8w4@<v%}k1 z(Fsg6EBB$6N4)3!VsC3#%A?xlrWV0kY-!}9#VxLUA8)>2TH2Ci*)qZT!#$&w=QvUx zrCQ{&2-adtW3P-`+}Vrr=>O;ftL`#k+iKO{EyI7J^?Bt~1B+lSuK6gzn-TFbihQ@u zTcTYaC=ZOnT^fZufnQBxe01ejVlmj#@L<*0q~FJw36EH@A55IR{JYvPK29upY^s*W z6GIwU1Z%OSL!p%OPiuM1?po4k2@{+@?3HPm-<9$>acg#qU@f*Z)_v-{=j=y$yzrm4 zSIN4|gl(&h7xOts5qth?C2g;g1Z#24M+{_xY0l@ZQ~hrcNlyC;tTUZx9|FqbbfKIP z2i~QV9a>p2EF7J}mJWr+|8ic-qsMVa<~YexV*(>*SK6!itZ2~IFSI;H^}Np_Sc@%< zK5FkcSK6yD3KaHP!UX3J=XlL%rseTY?o1ZJT5M^=={qN!BPfqI22Ho>E)%w`^1bqs zGY|Ve*8W(}B3O&|g21}8n%1*^c=z8Ik^bZM0Tq0TTak4?t@#p*#g-0*hF>qO z{-_F9OUe3`YDo+v6XoA+rWT2>cx^72DZNe)PjuXGM!te_i%U7QtFv^Ftxp zi4>z9M{;(weiO3CgmyI}jraFI6lveTe{9)|B386IN2s%CHv86GCeC>>uN7*7LV=Q5U^M_TnbL+G`{$8`&B3O$p zjoHNf$J}cuk6dTpvFa`pwym}_J?s44B-P)$sH8=(7T0{-6nk@@m%%!mejl<^hxU2J zXh%NE<5>MR`h9F{7xF2N%!&$ROT(*w=m9N{GxdKJ--MQj#IbYaA=b#XJmTJrDbH5c z^2pcwyhX4UTN>x$e41H(+n0-Mm-XFb*)qZT3x#ri^|h8qrawQk2-adtheFkwzwYLl z)x&qzbg=3!6Sl4H?U2(gh&9X6W%F4CYjMrDcG1ZivX+PJgQ8t@G1^^+^7wT1ixHWB z+*Kt#Mlpg0F*9muiMeD;BOh0qYk7R|(`Qy0FaeK{+A!|BTT->ImPf9^+bn{$*wQ#f zuzNoBpO<+4eeq@_%a#ewUntc7`yaJDzFINYB3O$pjhXPXgWcOv9*@1+P*#MKb(aa- zR%N>scmKOT)&IKfRjanM7T0`hkD_=?G!5Bh27i>cSF-zz_Aa74#!h=RQe|lW*z-S3 zw)W#tWQ|oe@R&UMq?SjUyd%W#oGdja+P5FAHjI0!a}0Yx%j5B5GcAI(*wUfUw+)MG zc{J}bOni6AvSotvhxy=%zqCBIJ~+f8Sc@%()ehG#OY%JSNGy%Y<#KVZ$o8 zpTi%u`{X{WwzC%3d}{}&p`D&`SBjR0?CqnSq41w)exj$wmppXm16EWq#eQViA2ndp zvyn5H4~D$EV_XJIP}CFBIMt}BmPeNRpS1|qVoRe<%yYYzN9Vc^#aO}w=PwkRyE7D# z`Nz83TUrEbv8B;}G@a@;MR~O87!vEl0M7r1nce(eQwo6CTPbo^6_uW zusZ>f19M9awg}eZdW^WGrcK>x*ZTUU>v`6hXMEZlB0RKY<1u#|`!;pc{_E?X&ayDf z5+?YhIkZ<*7rHZ$4|8I)MX(mfGlfE3q7S>TAdS^U>!q`V2}%z+|8>X$_x4YE__q{T zXvM0r7QHQqH*e-#VptM6G)&Mba3J2uJKybxd{pk+-in%IEiN0x2*3ZJyA*LU>HVr% zv2{$)K5?Y+V37yi)7U3m7W;(xw^)lyQ{$HO`#{{16`M~zvP*5gqj5|6eIRbhk}yFn z1_;D0>Gy%SC5vD!s?#74x1`?(;+Cx4%S=%IKp<{OzYoMMIs99!MdbtnaZ7Fxx8$&d z39=gq#4Wi&+>%ujS&PaB1mcz=J)-?3Zb@Q~le-;gl7s*x{J6aYsU!9sa&?3#x3bg7;#GxmM}r1L0A`YOKM%jEm^`yl6tTT<&HZpr#B)?&M9+>%-s zaZ4^sn4qy8(m>pjS{HFk7QtF%-saZ47#T5LCsThdid#4WijVS;8dNCR<8 zYF)%FSp;jb-862=4dRwumM}qc9HfD`B{zs$a+qK(njwKe+>*{Y5w~RR!J^gS3}+`G zZb{dW5w{d!i!wp$T1W$NOKM%jEm;I>vE4LoN!Mf$x8$;f37XL(4a6;}brH8@5v;{_ z)3_yf`<*={Zpmc{6Eveo8i-qRgSaJ&U@ck?0P*ilkBRI=N_b3M@{(lO;Wn=8p121q z(j>wbWrEgZkp|+HbVV3(OBTUeY&VTtQtKjaDZ&yaX#EOlAZ|&mi?}713D#n}Y21=~ z?(Uuvx8$;f30l8G8i-qRgSaJ&U@cnx0)et-FX@vQ8sm zf_xT8193~P_|FlyWD%^zcGI{ewJze8A}nEoR%?+4;+E99h+A@*U@f+r#x1!)+>*-@ zCTO)5X&`RN3F4M4g0*O^7X;##+#qhrI_rh}+?J&^Zb_|+xFu`nBopMJLmG%%(z=Vd zC5vD!wwuN+sdW*z6k!Py$##rKiL#xh!FVd=p3maZ64R zw`38lMV<{1h+EQF1H>&^dqyd$L(bkwL==EP+>*wAAZ{tb5+=wW4FYjXYF)%FSp;jb z-861Vdo{!@MOeZFdE$@;;+C}TB5uhdSc~nZaZ64Rx8$;f3G&1t4a6-uLEMr>uon68 zKp<|(3*wd{yx$eJO74SYyM;oCTM7qpOA(eZLD3gT193|l$$_{fi(oCbo5n3ULEKV= zB}|at8EGJHNh1dkw`38l#dg!UB`1hma#_Lz`JKhOH6L?=xFw5VE%I7}K-`iE;+Cv) zqfjf2?5LBoqS$U4x1=$5h+7g{CCh*bSRoM=hBOejEro-)C5vD!iqQapC?t(&L==*>3!7qV zGn~qWD5O{rg(Tm3vJ99&eKSE664F2vlE&O23dtf^i|wXSNG6Cv5?dupiV0XD5jli3 z5QXFgQAifST5LDe-9m%bi*rQRd<=NZG|W# z6GS0d1Z#24*C-?tL?O8pRqRp(wo5U>uoa?^{2&U+IthXHv}8DK0Z~X=9*9Dc8B4O% zn7}wV7DOQ-4MZVnc_0eOB3O$ptx-rCfsH7n2uqmY{Am=DmItDcEP}Pz(i(+if+!@b z?lNK93Q56r0RLdv~x;skI*uZ`zEkzpwHOt1Y02r$q%BCtg~3L%B_}`^FGMj$utq_G|f+!@5U@fls8ikZNN7%utntmU0sxf=APUJUH74NSQ5zx(327h-Ny`IK zNEX3bY-x=`@@4*kC?up@fTXdWp4i8r1-Pk;)w_k zEm=9UC=@~zQY?rA-_>7=pHqY=q*xGzWD%^zClF~AQY?riNUOJCdvQX z1WW!8A_YBXyDE#mUy-KiuvYM#j`TQ<3L^YB&0&3yx*aKIh%+=yRK&7CZ7B3T1kDo)SCn>gkJCLc&CjWdrs9 z?T?0`ySvdsC1x(@;j<(oA!)~n@v-$vJlg(six4`Y)%%rIn#Kn+Ye6^l{MSnKt<=qD zNk&5GIPpx^Q%V#p`GQ3VozTj4YfRI~Ji7*TYZN@E#MDL4E5TawELt|vGH-U2Ap9UD z+WIV!=LE6gkxTmg%%t1#>lc40sKlS`AF~M7l4r4coG5!oB_&4P(!gg46T40oib;A; zI608UvLUsU7})PVi(oBzmNeo-XvRZI%-LARX9*Ke-(6AD_~Es~1~ElVTPm@2dNGS& zEqRtS;zaq)?UcCGEQ`+)CZyzqC{#}FCja|*M?Hx@+z5w*KyWUh{ z#-8OdmSiM^juR{I>!n1e9Fr_U=!Dh}6B=k5*9$d58kslrR^sW-BVsJcNC+J#PVMQd z#HbuCEJEmn*0FMpHI1%Emf;rgs}1`rk*8yk7)zMwccZb=oqit-;`F&RC7N$uZG#MDR2%&Fk4Ja>Z6kgE;X*8VnANqt)=;;&D2*$oiNk&5GB!SlV|0je_ zXn_vj%m>~IUpv-+;%`L~o4EOgIhOySM3D0&A-|i@f)$*bFU4y+#_dXA+%B~} zDal9(9VhTbDS>gjMF^eH!q=t0l>BOyz_?w$+N2~SA#|KT%b*0t?G_<)LJO^g{t`yy z&_(N`1jg-3u$DZFmQA3ALk-k%yR=uy-;(D9f%Z|KF$%}8W8AI;#_bltTJkKlBu=2E zRs!R8X+@I~CeY5ik{(9kNCUlr5*W8z1Z&B&q!B03<0ye~yYvQ02@~kAG!5zDblk24 z#_bltTJkJu#0m7AN?_bBy;@Sjgp`~R$=+EBjN7GmPD(NolJhu$5r7gHw_AkJ2`!8U z^p}#O3?(pbmr+Jil93QPPGH=w1jg+aA#_3uqZ<7s`2uvbqy)z8GFnPXG7>_^35>{; zz_{HagidH-bf&))AN64@ssu*JG8R=W8Q03QSX7>+y%idx@c39%35>#JWSNvOVW)wy zs1m_gG)b_QJWCqMv8WQ5O~_a@DPe;1gflsQl{P&TTCwg2PgXyku2)-ECg`pB|5%xr zc0EqiY@atwL<$r1jGV8C#ffA4>N@`ip}+KIp~3ZKohcNmpBg7VZ$3zggoJ-ro+an; z*#zao`YqOyw1Z#5x)0?;bC{4YLC@#`DIbP^i?t|!NQ3gB1Y0+FcTeb`#vl!bDS7UG7^$Td<_6|93?Qvu?T7zv^NXdM5K{u z;V{REQJbi5lK5R}yFg%$qiF=IADRzYPuqyz;E_A7QtH76M>*!&1VS{)F*&i+WTLnB!EIgX}*IgUlph)h<5HEoP6kp|{CN(3vyNl8XR(ufn7<0v7k&iq^QoY0~% zHPWCtju1w^9QiG1>9ed^%d^n(914}|`UC2GDD++TG;3v>37Tan(MgF_v!WJZYbECi zal(-_grGSGB+1!}yp>uc`BqBETQR{}@_aKN$hj+NU~V99m6R~Sb_<2}mX5EH9sK@% z=f%r4+|{Y0OwlRzJb5mE%R)zyV%=3Nd;G7>_^iNS~CYkdtL z&+0NE&k3!??^M^cpC5M=X?%0EA95TDMZdk%WeF2+*Qus-&Z)Uk5{+)8Dv`5eZHr*7 zttYB!8mE81f;84W8z-jbZ0NFt33(Qa#M5ZwmDQ)DV@PhbT6|CFNDnUv^i9~6JLUp#siNgO>QX(N? zLY@;N1N*JGoLNiWR(=Ut{U13`NG#%J8W>+u&JF(-5h;{**vf}tEqP9i&TN8gr6m~T z+$uq`F4Cay!y;IVY9$EzJ`77T5>l`5eSo0vBgTY0C$!`%khjJ60fN4d7)zL-x{EUD zy)s_gXVpou2-c#S52Cua+}m|3>KFTHu-B*hZSLCUqfNK#e>wip-1=6_>l|^49?!4O z&urWc;`=jYyj=fA{kq%FrZd4>Z~j|Bf61FDMAsgxz3oV&!;AermN2p8uL7FJfs;Ex zOjh$)TwK#y_(>mN2n2R}nXL(J1pm z=`A28kIZg{d>QrozW<5G5+)8_Eu?RC_TnZGBaY`c4{eS5yUO?$!CK$ka*La(>?pHk z@kS6O+mABe8=bUi9;imHD zwIJRYG{l^#2wRP8YFNTVr^p}9lskr-wV{tejQMz=d8<~`U)`ahMX;9rR{M($Fm3LS z`h9+N4NI8F`t3!h)0p9=;XKL5sQ!ITn}$*U-cUV@U@f*tDD>yQCCvL?)Nj{ex5uUS zTJ#n-y&7&DI=9iWOR!PRil)My;ZGOPKiL*4*yqnIp~GEkaD|;+U7FMg0%H z&uo}rtraJ8xn*aJGzAw4aqx+U%%!pT&R@%ASi;29g|fLTbBr`)kEDaBw4;UTIV9>2 zd$E8;u-1k2tnT=0Bh2&#LLB_{DO0si)GvIzxM2ws+n>nd?)`d%x$EG15F-jdYhLai z^`iqzSp;j{S245u`H~Ul&%1;um)g-(c_r!}eZI6|2@{V@&*c6&X@t3Z|K}jqjC|2- z?i}@V{Z-B)Sc|_j?8h1VvT-{^{Tm-ww7x+m(m%i9lzVD~arb_PG;aCtRrBi8QU9@h zRV;$F_O2!og*|Ehp=fr$=Vk2-%(8*1*Jw*qN&TQkNypEc@tZ19{#uoky`q0pw`+r2FtqQ3h~ z5mT$rM(63iAN()sr_WrJE2hAmsNY57kZw8bwBG_%3J+U)W2{xm&Xz&#%C^~eQo;88z9yW zo9`7w8ke7Y&mvfB@Yh$>((*SH`X_rq?*P&mx2>SZ5+)91%cE(?U&QZjo8qM*jaysI zvk2Cb_m|R?w+@AN{F~ETg*2KqyWL|66Y~CIH%S*K03yd2?q+ z{k=QyH!NXdJ$jno=8QDI6&2!@3YpED(@}y0!WO|=Z*7e^bbC_EuMEw&B9<&J7DtOv+Zf`Ks6hA4q13&V2UNe4V z)ciG9+enD-M;12!^^f`|cRpqjtTp`TdgrU%Bg_-+CBFUpJ4={d zy`%m;Rh~AiRetAsXZM#QOu436T$}i3cxiK`ThyO5qoZL76P5CP?lgF5gxT6GgfvQi zTF%sd0YtqQErPY~{`xbg%9A6E`AELn@)xR@2IxP!6n)LGgo%_#*Eu!*8E$gU{Rc#@ zDfgH$kD|=acDD%D`rH51`D5R3^X%*^Ao~4S*Zlqv+N(})8up@JO`q3$EK!6rKmrz`w+ttCN3{rZiYI>Supk`NEQ^R&s44{c)h(H6m4O~$Qs z%6~u9ym#(<5c>|dHN|rwjh{ywmN0Rk_)2Gz8EXD|;W&s|4WBc8vPAt(rQWp&)+#-F zh0_)NdFz!&LBuw8Fqtz&{d4o)H7sFb)wC7P#`lJrmCJ-U{y|4G>PDL1@0?Ar*6Sly zIPE76HH}{u;?0iFn=h}W`889=8kR88x$knP;e$iX?fVac7?SlRQ}}Y4|KX%@7QtG_ zsxEWd9v@6S}%O_fm5Ku5VQ9FFF_2f*xT$op5}L+ zHp#GriAU$Y@BF@Pu$f&!=Cv0iZ<{km()>(UZGyE{EPUTtynV3wr>YPSP3>zo9!&FB zJTuv_go*6`E_HHG9&9rIE;He|FQuB57+JpFXR=|f2d*x4%0jE;nJtb@a##ZUKwk~f%tZVO|Vv`A7(nkM?_7T z4nnl9OWj5G#MQ3D)}MpPA0wX;D+`Ga*(z zHr8|mapvq;!xAPIUzzFDd@pLsuM#5Mc&vE@M9r+@EP}Om6`tjM{(jWtEjSy*-tbsc zAH>&%#~GF|(e92}&ioZoGqa`;4^|v&ih?Lo-zHdVO4C`+rR`C3=?ftS+&0!^26494 zIKvVq3N@PL6x$j#h1Lo&E;QC0*^uU+>}wOO^<2MMPRegl^Zi?MKzw=TUE_oJY{odl z5+>5d&2nzN6gAgB5u%d+t{DpAl^<+^wa))E%lWJD0JG}gToBJbINE&Vr}>rMpJ*Pg zJJ%Vxdw`K|>H=0uYOP+5~GYxowWqw)X&YTh>J& z4n97{Oak%8@(G3|Oyp=Y2Rk)mLeL?fO#;OPJXF{9>oz=0T=fP6J}} zdxOlsyVCsr584E4&AV-}^X;-h=9b(Zh+g*$Ht9Rl{68O>Vpzh&!byvqIfDk7nGeW{ z*UNtoHnn!3g^Sn(YuPy;ymW{;v@Ok_RA-7|2@^w5%kwuFWb(cvwkrDeQ1krOH2-<@ zYD};eTRjx|;NmFrCCWVQ=ZS_}94=>RPyW6#z%-il0n*4eVwAZREkl8-leDEtNSL_P zd7krK^?~LKjMC7nWg2B(k@jkcO|VwZ5%ZjW^#_{$ZI^*~wEswR2t?C8lMG9k*!j;q zXX0}M&6ppSgQ#C*q-lWO;7FFq7QtE-pPKI!?>EqN#>#yt^y?}LfADlKsCiVZY(oL!AH zy44wOrfx!S;MoLg@wbArinFiNwZ7WxZwpV{mB*Dey?Mh2dDXk+bHyL=^Q4j9!dEi8 zvYzTRz0reae!f>?BUqI$5#eR+SFB}|-7E$ND9t8R~NAli%?udC-pTG<3^#Wt37Wxc)1 znC&2LFK|FTiseU*OJT46^SvXwPMH>~WjLY$cV{+kqF&4AieIhI5+<5F{Gifz-ufxh zIQ`cF^^8`({8|bVtVNz!5K{-gtA2wk-R=wX`*J=;J$1YKCXNi;4dS=AN2_n*wv~0m zEMX$gf!o#pF>cp4Anq*$8^Hgu@ZmZZ!CGC;-l0C0y?wp|v7+2i^|5T&b8na>Ohjsx zRzFUpyu@XU=rlbra3k*gq%efpUC?mB&Wdzd9moS9o$J-jEkWj64{z1vv*gB2zgvk2CD zGw0pvU93Gj3y8<>t*buBNe|`^vxEuq*MrzFy^{K!_w2|PW(gDH3)fKJc9%{0L9A+b zr~0lxJNeJhBTi4`XlwxpJ_SRB3O&R zF04}zxW|a+r}nPbj9EHWb5XE;I_57U6v}`@K24TvrbLF2pu6Ta(oW33TST*LbdVZ#5x+8_#45Bp_ zOS~Bpi-mL5Dm|*6pPb`b*Qb~gkBN0&yuDie`x_u$d*GOQe%kGL(IQxjV~w!FGQWj- zew=DKKVu0KOJ+9GHZdOWGxxzG>iL<`{Pp!ruok^7Z1rc6N7eJQYR8M~S;7RR2cpD) zqw4u-^harqfeN!0*$~8+_cqsjRGztEJxiD%yMZ`T;edL6PW?0@oe9?BS{Vwx_tXOQ z{9Il*Je?&>*kyisbY3H#pX~0>7QtFvr$eD4wVpEK`C0Ck_PEAzP0ZeL@=6I;JU<0H#y~uJd6Ig5D($lg*7{&jaaTM)ZnO0ucD^%B zJwJavP|srt6H8YYb#ub=Go#BI5Up>_G~)T$f8lu6miA#)2^cIF{wOru6lm* zKY72$5+)v~SlAWM&wK7t5N~H+pq`)Gr{8B0td(oUt*&@}HWXP5Vqe-K_57^uQ`ch& z6K4w+a>eu0F6$f+pXXSjo}ZUz*6~=v#I;!kUGe->EjkNC>HQz5=V#`@S{A`t2M*t_70*xebK^mjJg`DNKV2$Uw+Plc>g039^V95` z5g-mWTcw_#GEY_YSi;1f5qVwl{QS0cD2S(?U8A0#^V2I^1ZzG0MIKi?KUrE00= zIb8Ale0JfvuuW_om9Cy2XKPW9B}_Cpoz)f3PqigYk;d?Ao_c;Rbt_~MtX0F!>Wb%Q z+3bcO&cEQR=O?r#x5pADMs~{Visz?t+gcz_zqCO;KhCe&ErPY$yqMV)&rk0ch4?0I zqk4Y6do8oa5+*XW&*X~d=lM33K@2^%Q9VEVw}(8|x&vC``Dxaza@ZzHw*EprKWBPf zPiF}eYf5Eu#q-m;c15JI?!7P6^K<_v|5yZTMaP6(@%;3tRt7}T;+xd-lXw25be1sT zt-PV0pYi!if%tUNCiVQhHRQZSuvWDPZm8#HK*8HUq*dRno}XTGeoJQw6U8cASI^In zrwV|mG7JPfKi7w!viH?2?}A0JR_9$u)$^07LoE>fKHQ<6pG8GVe9jUknjAi=o}ZuQ zHv}iOB&dYDD9*6!Dispn_Mb8A4<->^eHKj%K5_Bl(Km^S*DdVZG9{{qC*yLPDOCtsT{ zEP}OC3LIC@&)Kcn>f_wnZ+58XXUDF?pRRPrK)8fq3$l9qRencca*PmM~H8+;R2%)SllEM7}FK)bq3Ut_BvtTKzA7ub!V? zTZe+kTWzO$eu}lInEsRVt9pJe&uN&_ZSt?``RTB*pAz?8SkDqBR=)kSdVbbjE(oHLvs1k?gQkVjnP9D*xlgL+=Z^xVKx6?So}ULl z%$d#-CW^jzQawLuHOhc!TtA*h+g$}Mg0<{gvgy8^>iM}^uy{I4nCRE~7xnzOU8G)B zueDP>Kix~;Wf82!H5BnzleeqqXG*_0>A8EKSIDEMcP0tbf$=^U$VjARhW@i+X-ey5Cv^Yi<7Is(OBom`otbw%)3q zpGDKYOlJubhYDR$&rjEsOUOrqgIm?}Gja4Li(oA~=bKw@Q_oMM=IQAyVZs@CNj*R9 z&L2k_-tKMc`6+p3l|`@?TV2kl-l?9Ss_)&K&Mgj?bG<{S)blgs!gEODP_~`w`T2Ip zgXt_`;+;Q!SI^Jh*gz2Xp4_3HpT8ncSp;kCfBv+3exBMq6htSpLp?wJXLe0z2@?&s zpHa`xn}1IL;ZED3o}WGK`&a~Py?N%WdVbp9G7Chj*LJAq=Su#;=`3L)&-`=h`N>^< z0f_Rocc|xQNUPBn!CL$kV6RN>9qRdMeQCV)eK4`_o%8DXng8M%r19{!?dtjIm2DrobwGW2-cvG%^W@0U^@W&G(ZLrnk+aepT=uqvmb#CS&DpOZa}% zw!lJ-1^#eNDYx&`+0M{TBhAtZh26jME^wA$Eo03Ui6l>1aKT$NDC#$U=sCj@CVtE_ z)j4-`xOuZvP7wQ7P6`hm5cLoBe9Nrqd&ry8y0`hZ$O32O@p<0m-`+4~Prv32Khsj5 zb8nI}AP%2w?(9W0)v-qxn`3`HZ8ELuZ|c4CiL+wHTjtM615A%m8=dk48W_pP=myh4 z9D4Oprx>D;j#Xdk%zgvWGqZ7~;Vrw&`bk*fgnf<=I%2XO9BK}~I@sJ%<2cG=>VIvV z9>1sg9U9McF5mZ-Su|vT`Elt6L%(Y>zxaZtvBet$V(hN%;pUm6eue+%&;GVT?4`z|&GWgo z7+5$a>y)s#F-z{!=XTx3f>=2A_3)=xqW*i!A5Zx;bER14Vx!F3uEoudDQ-+6yX(wr zY@A$SecrX=MG(18E_A-dn0ou!woZ>xn@y|C1I^IBsisu5htAR~FL``h<>HFTTh#h=v z#K^HwE|?7uR-je`>W%9z%OhnrgZGjC(ntIpNRgUuh~E{0dN zx#mcjH~ro;x(&6l#ur6D!wxjpr?M*4231)NK1*xYqgE&O1|jnfad_4qv_F zEw$CIzh6NbO`5-H9vvL@uXLX2v4n|xUw=i3XMb4%V(h6krtYOQe^c&HJ$_%##}_#Z zxHU>)rRcFTc&izCr<*O|sK2t)ERQ8jOuVbCD_?Du6|#EXy-f&gNV6ATN zly>Et|D}qYjJH1b*Xp}#{AhlU?at+KWlDK1kN(+vgQ#`%kM)OcM1616l=WZEtE{Eg z_v@|BOK+EROEeg59v-vFIrUq0{r}hR%AUCI!moR!FGu~sBd?{igo%n3Zr3!rw3fJ~ z2bb5?b?WtBdKST2$DXUBX`BmB1u^Td?OqS;Q0QK#rpFQ{?0mev?*UC?!P>FuOt998 z7WZo!rB9DQ8UsEKdpWV6bHvcG=`3M_?S{G9()lLsG~)VJM-10EY31bWLaXO+4Mn{w zw8#|0H`r+e;;O0cGJ)^k3BG^4Rr&AdnGcSp`MFNCu?W^W+wy>ZD=%c50HW>POH50& zC6VcE3`>|myW#}x3W$A0-!r+*jP9JH)=Oxl9bXym*{jI2f zuuC?>5+<@?B{fe^#JbFo_{6pCA2h9IU|&)9(;gG7^8Nu`)fW4)llO1b#p+RdAx=R|CQ$N3omq7A}w@+C^atP^uOBIJoLhcASM=y znEycBjp$J(Sj&E^l)X*OGe2Sk&~Jgm5+>w33`QSFqh{*k<`H~@`SLEb2-aeYghDgZ z*Li<7i~5VFj(4Qrkp2Vxi1r)Of1p<|p_hh)rQglcs0Y&6+Ge5G82!hi+1_wiB0Wul z_++c6#N*z}ASQQT;EhCl`>4M>tFPt$^@o;Q!~K3lgy|>?OUj^v>vuL3C?5)h>X(HY{WW+VJldCZvy*z7~Bhi2eb+?YYRp z+YPL#*usS5Jo25RF9vb8P-;6XcG)C-Nwp#X+$=o)beH#7X-K)n9 zg1w>+jCNw|*_<21I((NsjyP`p`7e9a0LArM9!N`5q%$;fRsDVclG)l#2 zB4@3AT4BX+_ARrmC%5l7ebK(a!}g(v?^L-$p}Nhgf9zhF-m3E$-6r?9uy9 z2YD+G4YJt6M9m>S0WvD8(Q+b)+$qNDvUT0w;A@E#kBY`Oo9$%!zxt*zMo5@}+%imC zsA`-v{Gr8TCnnI#De3Ld>mkO;+|Big8E)_TvyleDUNklUk#Ch-7wnB41UetE*uq4T zjPul?dV}=X8M5+huJ07RzdkD5UhFUk_Tsya=P_-yPMy;2{r&Yx<9RTFv8~hZ%2?OO z=k7n-_3w{^yrbXkHwgCPaU$NUgG+T&jJ99=SXKS_dWkcRYSp{|=cT$?n|(_9sI(!& z@O`AawiNrcp&ln*6U7$FeL3R*Vm{6mcmf-+ed`#a-7nG5joNt$bs?t_un zj?h5G7A8)QkL!%Qs@0ngqIkMy`V?kA_BBeN{w^6OVA;{JI(d~1I&1yp0W*h=(?37l z?#!7;+m0C#5Yw7jdfzg)xAOi!EtyUEYGEQWI(2}I^!M%B1>$4xqI&mMv{&=?8U%Y$ zJ_q7LoRfBH%rgw1{Hw(lCTK(k;;##PoYkKTx708Q_M$uyM3eeSJTkgFb?CVtjb-#t zzxp|&yPqN~O=BMrKC6T5+!)<$DYMzd7A9zf1cF9h2Ekr5A_GCAJBuw$nAbrgNEZ|A zMPpIKXtcGov+gxI<1QClnBe<{3^}(~-@(j8>)Q)0Ze_Ujp|Lu?sDMja7X~r8%5I*& zFj~0PfBfrY=YP$Yb(ZtoEA&w0)OC+9HVF2j(LJu?p8^YX%kr3+=)c%vuU$ow2S|T) z{O7FNB$jUu*1Ir{YS3ho#TF(i4A1F|qxR;jiWq(+{dK=xZg1qT)eVBZGS4j;aCqH# zt(p}9v3EuheH<$qS9kx(Vha;7)AKsxs8(z0fmrg>Z96`)j6~f&yO>}ve#h{Zy#3;g zqvq7gX0e3{n&Uu>ykDN$@&3d*vOGBqg1z`1^YKYrdAX{L_UcHs1`1zjp%&RZwz(yFb+(LDq&L9$1VpW_S}n)jt=DV1L9o}Q4qKgjl|}`FSoUeR>VnGR zHH9`zYp@pYZ7G;?6tV*1}DausIwqWZQG_MqyI?z zewEBLe*5iwO)@5kow>u^jkvo`^}}vfH&RZs*un(Q?_*|r{#4blq1)R$a*9E)my9A} zXYLTgr)`Mph5Z@YXYOgSg^7x{b4N>m)%09S5I>y4j(C{;D4e&yL9kcv{JEm1fG9q_ z8i;m7+WLJ#Z;&E?S3k6U(K0uUxjxOa+(#alcK+QCl@WcN-Yu*|@7-S2`=E<0Oqg@w zwy(>&kG%b9;Ru6Zue<%qIx*HYo{boj(*I#i#@OJgmBnHU6Ec31aTG>PAWoO4V%)jiv!Yka~ zM|&GtY+-_*4Z2#taJ2@j4MRe+tG-1Z=_1=l>+&??STHd(!zvYM)#Yg@hSz5GwFY?{U_k&$% zk-JF_cQMXMi!Dq@ekge&@;VTbA4;Bxd{ME53G-LoNpaEYv)1j6epJRF*z4TjT{=tR z@%lwGiBaOOKdt9WvDZs4rP#s*-vtnpA6sWYoUZL}5bPycva~+Pfe~Zy_z!-PSx&i? z*d_Xw+!JJ&(UMV$Zh#&;`r?h@&cC}W`GbgQywa5mnPsvL!4_MXDEm`K=T5(Dk{`sY zDxt2E_|69msbUc9b)dp*Cx*9?%rh*inAhrvCwTtoF^ers@RLPt#)~aZi~t{hgJ7@2 zKdg0P)OD9cj0wlrxnv*6ek03SY+-`m1s|WKZ?$y;Bd-=Mb|}^zMU9hrN{qVxM}w@q ze!b<3Im^XUwPJOW2^mX^Zh)~hzNj{V%dBPSYez)b24Q&JK5xtH;GYRUgYahFU{ykY z-u|~3lDW4VYSB?1bYp;pHj;V%ln5i&lTMOd9TG5CZzxSKA*VlekSV^bc0b@o*M*v@tg1CQ?5oA z)e|+miC;!&*5yTemUl@sBTt&yx@u5}uJ!M3g%yoo8mqpT12|QE0junWs!xhLi1GLP zsr;zn?UQwx=D)=;cITe0tA&Q>lqDlU4-Z>v5bPzoxy%$nM+cGhg4gQQ2QTzE?~R;@!Zv11hzZiz&Juw&H>5d9M_vnHUuy0yu6 zMhjmp)Y@?y17gCV^;RLYS0zWs7zDLlqCnWOY6ghE$8NNmAj_!LWSgud_-^^$+R0qM zlVyk^5AAM8dn+&YZX49In||^!k?#2*TtCm6Ge9zK>HCns1z@h<$r(g>$KHm$n^-ba zwD?P7(cr&Xn2@y~k^vwq1QDlkGbaO3zg9E|_M$Hs#Ngd;T#{vsNb{G?7AB|<29Z0B zuXP0dV9tCe4T8O>WdL#F+8lrB&wt+eG>Uq!0O!fo2fT3oi2nRZqJB18 zn4mrp1ogEB!CusBgP{K0W(yPMbx_V=5bQ1L89Dj1QY?M=M;q; zyG>{R)0&94efn9;AlR$O%3V75KjZYSC807g$XDPPR}U{ImS_$ zr&$>sRhunL z6eF*`K|VZwH3%8i$>Q>_d92~_ zszn!f2WHM6{i5&$-J$FOMe`bpW-LG)$hKQeydUJPo@Iy4cT}=(>B*2=^9&NMeAnMv z6-5@FX=#Mb_nisJz9n-))(ql)E3I~;SF5mUxSs5f}8PW}{T5bPz{w`AeSxj{(wEm=6SahoknNcJsRII?CCl6^}Sj%?f@ z*h{i+$-dERFY$eaVwueu$PQf zoe^t<1!C^5RhA1o@NfTkz{3_MXa)&HhT(}_(sSl69XE;z_L7lt>`G7&U4A`hH_VQc zRq9|pS^Znqmka}R=H?S*Y-mYaB8nWXxdf5)`bqoYvmkGm#M^i^ra_#~eA=3kV}w50 zSoZ8cH+qe|5N}Dc);kP>y=dhKh?qHR?FZPS(YL3ES9vNX%@!u)ONt%WBF2dqi|hz|9|`jBF$ngO?;>`T3gX~` zB>Fz)!rkvt4U4ugcK%99TNpckrQ(OYbk^cje%=a1zQb1>{e1SiPMR%D(CQr!8*dJ> zvtT~4#I(CMDeeKZej-5H$k054PhVG!(vjMKReQBg4RO4ZLJvmf5!l_azLW?_O>S%3&@n#@^W65scxL9iFb zxX$Vn(RQ%b*)z>vhqk0}_h6^3h#k2H&^nm_jP9NF8fafY)T^=FZd4Pq276|RBKFO~ zM3ak|RMCoK^spW(yNoQ56tdhk)Lo`m9Adyo}p>^M1I^7A8pN1W_k)x4w_HABC%pH3;?!#JY@S z7;P7BIT3_!Mz2nceNsnWSZK3_310n;vD%qE`fsfLusZ}91bcBs1lIf1*r)5DEm_fX zw#^nMpc^@>6J)&{)*9UO>bL06&)4W>5bQ;3SU{|<>(!%i9j!aevf0AKmDA@{;0U)q zlgrr&q3Ld&ANT6-Ei(;*y=Wx|VqDp%wdXF@w};*KaQz3zTiI8udn1SH|91W=(0`XM zh&(Y}U>6Ttm`EhgBDSM{J`-R0F4uLOBB<{50P_hEw97h$x0d%sSP z-4Ls)xdy>r$eg~dHS+OUT*_Zh+3ogzI9t?Es*yi9>w;xAkKTOTulm#4>Y~U?^8ECZ zp@uVo498iyEc1=n1?t2&U9J<(|F{}r5bQ;7KJHcbGmCUiR>wwZ`)ZuQJvk*o#*!`1q7hHCVgaBkSv*S~72^RTBk(*T(Q_7$2V}S*Pen z$V+m5ENiTjVS-oLU_XGHll9W{nEj|x#UR)#!NSK%S|3k`Rk&As-_6w%aUCzKwNz|j zq5@{@q%HY)T`FIet;0Dn7(4%#?ia-tCf?MDbn2#F6%s}9hk6TjG*+?Rz1&{0g$Z7f zgf?;DJiQ9v`Qr+G4T8M}SNL7+%^s|i_n3wl74px}D=_1=byrWt7ABVeG|u@3moNVX z#PKSVw0#HjSJ7^RV6S?w!kq6M{{=BGN2q>_5#*`a!HO+Rq*yo5iLoS7h$2Zx>HZkw z98WObAlNJX@ISMl#JI~zs8ks$~axI zg$Z7n?c=jNZ%^G3&!c>tc?Q8=n5|W@^C%LddI$Xy_iEm}d5SGe@XB>uxo)o;VC6t| zf0JM@b1mm*R};M)#NGUh6kC|!we{HLe^Q`s`zgqq<@!8>U@uG##&A$ zr20X|QK)$UQN6_zy9!#kUoKZR2=?N&s>qfeH}*({+kzo|EX;*Dzg@;Ol*2`1Hd4jT za>{ia_O(Y`#;idxU&R(CC_4ku{dFCC6LOy{3!4}Odr8g{I}Z!Ob+v=t5xLLgX`zZO zOz;|U?2FU#o_`$loM-3nQdPV@PSv0PnC*Dud{#;SioQ{ozFycRJ!h_hJMiyy<2{SY zh28P*Y_XMT`A%f(+1Ayn&P$lO9ZZGW1o^G+U4BcoponhM_meT?RVP z_gQ(T&-+TqN?&Oi(7WMR{d0Vr6@W~ph|6OT>_r-aJdZx@tv$Go9mAqok8oBHfBn0X z^GNQ4yamLaUDd60_*Gkei82WGGT)vFN7GpQuoCc9?Y+i(#YDn$1?+$S2-b~!?<2-9 z7k0R!(8A>@8*LD#*Y|e}wE!v8s{p+1AFcL^wRoDjjg~%E`daj?h;bo#Ni_gjMw2sR z6kC{}d1?^uWX;qbTzSrf^9_Q%q*s==1bs1xsj+k6JF2cwY+-_Hd$HapS1^{oF z990e9U~S*t2Ekrty>r&{3su%z7~QRDt=Pf@uh_)C&V3_P_G3Zbw)oXjnW zvWz`B-mJE|KXH4X&#rDs?;Bh1$}`Z$+BodFT*yZqJC9Xie@!uJ!+B+uxtc0P@J;I~ zH2TMxdl>|K(X2XtRf#dlRY~;cSsH9GewFmyv6YO*FGNj4WS}aA{(SpSFN`%_Oh`3~ z%+{h`M~noYd#m%^QCGAtrQ+YtUc4d=t?2kLb=n`Q%!b0oS~Vu5UPfANRK_4iz7q@8 zhnGR#3o+FUg1w|>QD*K$)j~hGbiRs%cXv>nCWts~yd|en}=c9l3VD2?zv|5R;w#?0b zF19f7q2(og^Jb7PeCH;J)*qwP8hju5N~E!vU@y`WFuJ?bXpdTp>uA)wC~FWl6Vmg? z?hOGVX`5&@8(-ASIXw)5y+~;QQR>Hi&Tb2Z7Bx3k<1!&Vf9xy{i1?!;)ks`N@veOh zg1vZ;3uKm|n^m{?Zg2Ne!wua)dj8n4EdM3T$EVZuNYw~29(3$$s2NO1&o4bS`gjm6 zUwBk}JdYZk1{(x>(cJ|x;!Ly}hI_TINkc=GVM2QT*x3&di|$9McNpUwtW(G!*o&Sl zb|ZOTbg#;cC)j@D-yXIwv9b9j-3V_^ z2G2*rPZ0$UUvzNEbHwgBURi82{!dg!d&$j!kwHV`Eo&A^1 z7A9nUrHpZqLb5%{`jD}KxDm8aeZ)A*U9^Ki zuovYIAQF^Zu6kSw^45LTglj&e67AdHjVZT7hddvt3$JSdBFBP7$`{ofZ~pknAlQrQ zG(bE>p12Ts;uZge#+o}`8%OyZh_$hKVvDI$csCnkWgcaNASh2X2==1v3`Eku{>u}G z)e6;YVd60I#5>3n3ziQDv4870bqtl>xjPOq2=+4XZj)c8t31fzM$8#v+$$y|!iV*vouN-kg14?O%>n#ltHY>q{_~;jG`3T^?w>6M#AWLa(jD z$d($6uVk!YVM4Mb$(E4afG9UJqbiO0-HFA2H3;^i@eZyd$)u91E=FFxqQ)4jcbJeY zN%}-&Hz2y^YNqC*AN-thzCo~;xuP-DcY^h6U$=McKR7{>R-W;SHeSPq-Hl(&umVb9 z73=Lq#_BdEXcUfL)oXCD6;crE0D3Mr2=t7-%YiDuc$}gEkt0J!j7H&z^^LWE!28~x8$EyT6W6%ZXtr^ z06<(`Roj|`Z}7Bhk3q24#M=ezt|x-^>7@5TWU~XT;m80g?2XcFVS?rWKs1jX(WfsP zZ4jo{t$eZbOdx1BN@I_eZx$wK&I!bwxc|*Yt>0oB1bYQGYwJpn*{FCYj)J)0Ugyb( zHnH%L7|j+YFiT;@&VGPMa5%XwxzEyS9?^onS(u<%DiG%jR<(b|^LUZfYY^-uxm)aP z3!eG)_$}q1iLAScT?KEb?@;yAH?sZEijMGUtNHITAuEHV6%|zr zRoLCe*wv89)NeJ)AlS>iy9aKC*=wq~y{*>F)@)${bBk8&Od(?A%roBhNr;_Wnr|`) z_TqN|JJ95aXUoj?s$%tQnw2+Ja!BqbIh<5xqsp|wWII@9wiCRx*+TRC|FipE_lP_8 zZe)FF&%2yF@ax~AdHev$_9VBH3UlP`wLaNDW%4#=txHg|iQ zCL3Z9?1ec%M~M^N4d;JMDWEHqbbEKlnIPKSHwzQ8Ixn^c3%}}S%K*It^&j<;O*IJi z3eCJyoxy$?(>h{LR-gRwE9!~y+}^|)=4!SuA^D-?iOB0f^2SF^$(MroIy+QV3gJ3UGnn1j(R9D|ZzMC=4 za?KVdA{tgyXRi;_`L4;SZ^b_b=s@Ju*V`>N2=<~Kk3f*xr%B;s9Z!+Q2BHbnzJ5^q z-X|EZ*@7JItBR5vK zI+&2$Eq1mRG3LDPst2Lntx#;fL9mzk1ShIr^(Q>RT+n#s-;Y>37g3imV!LyjM)LEc?6a32i%d_i2c+8%niC@0>E)Z4m6m z@0gFz#rCgV9X`6fi!Qxz^^7=Z$$qHQ^IW!SU5K`1pVSSPqOEMtZaDvbB1a5nSh8=; zX_fte`lz&N4GR-Z4%xP=*Nh0;nhYb zMym$t41&EbPFv^1_>%P*h~1MPyX4B-{ay|k(RT|Io98WZV*I=EDu{nio^oQ8dg^Ns z?8Q$O%1`p7&fR^`IlsjgCT{<>(}@v0_z+@vU!}KX|J^3Jvl|3^@$-j1I6IfWJo8oe z3R}F-F7Lnl{KN*AJdaxAWR38^aU1>R${&tyZn1@l9BY=ixi2+^dGm6XH60T*wn8&tux{!WLVYsG72YN1jKsX=y<8E%PKwo=3{r%?yIQE_!Y_ zF?_1U2eD=7D<{U0K?NQePWyO4Y%lZFiIMi? zJC|Xhzgwo@StmxT&&NTOs*}@}=TR~B2-iMOGA;ML=3j-ac_ZFCf4A56de*wN37vnx zS-m%i1C?sp^0t30xZcGUCT4Yc>(D>GmiPN__YY2t8;@rg1bbEQ_R0BGf3BGYqDlWs zw!Bw&iXC&Yg^8{Q{&r&Y96Am}s%L3|!CuCb^|@EIi1VvNSNnJ;jq{{d4NdB?o+i}t-N`ys`giCbo%Xb_r8l^- z<&7U(nE3ktgR}d9*cn#XiP12@0RR7w5U(H3rE+3lb)5o{`cO0H%8MNR)1NK;cbg?n z;QYc7HM}5}g%xmOj2)WX_*?A7Zz%T5c-+v5(WiJ*aSCLGx z*Vq65Z*?@aR~~BBYk#@;O&t zt3WcFElkiC3?k@KQs?eYe0JEw1bb0C2EzBxvQCWb@1AHx z={e)IREC8K>QO^w$c1As(QK{*PD0~vpH?$wQe z1_r@il&OJe-YJ(8qg~hhHd~mWTnj|1Uy?X6wq9y#5bQ-6Cy24xmpgf4*)N4`wlG0C zBZzh9Dn!Y>s`pz9gJ3Veo9oL;e>Lz^LJKGQZ6hCTQ#f;`Z_}PK;zP>KO!k(O3j;`^s{Cofzjj^$`($CJ7zgRNR#TF(Wb&RLvnP>g{$%PT*umVnu+SO7R1bgXhX`C3({U?C9 zy|Aeh!%{mkdrjH4g%cw(AfG>5 zn26y%J|qCE%|E6`8;A=7`Wew5%v0a9vfIp9DiP5i1Cd8MgWMBug*m$M!=ZqHd~nB9YlP5M(xPlL>G>;7|_M))?Vnk>A%ZbrFRbQJe zOqjcoq;#ca$;=AHH=5Xyicx0 zqgQ;j883ZwVyH>)c_i%Ozk9j(5a)U5Z6y)oRAitN2Ekr5dPR)(esPq%yZwp< zd)UIniS5Ij7$=kU0dXdMH7CZM`z+I231ZXRa!!oLm1n#7 zZ?PABX&^RM{@aQ1W_~Y=Elkk20wTxpB2J7=BVu?4lK1-I76U}s)=N%|qWz~@)XEqH zee=kWXO_>3SBG(L_e4pICv~c_YN^?a$I%$wtv&6;NT2x&Ymf%PXIEinyRh;|jPxlg83cRr zI2z;HzIkl9j&(o0Wew6eEsJ*2!F7CTF~NzECYzr@uosVtF^6ooabmbuJz_OnGeNuf zAjZ!HcRDdnPA_f{?8T#Etlxbz&WZ8j&ugrP+e|#}kw(e$IFY=LTt|-^PKfSi-9;Y$nW;Nw1X7<-}-J z;U2HDFwQTfktN#pVe@V}F#zHSyVKijVS=7Hh_jhoPK@XV!5${qi{4!jf1G>j#HhQz zzReaU=p6$Qzf>tF#^?3xJWQ|`eS;vj-Mr<*xYIJ!W(yPa4JwQvkLGh?)LC-Q!vuR# zTY?xP_MUWN%uKY%W(yPa%_ByYWSN~9A+tVsm|!nz6A>dK%Hza%?cQ#)g$ZiA5MzD* z#7>O4p(zZ4y{K(RjDo2moEYnWJz}$k32K88qtp7QPTO9~&SntoMST4f2_XcquIg)<-Q>N8mDwg&hUD4Wt$21 zq7eXy!Z#CI663cC|JrO}f^v8em0I+4VuU`l41&FABm<&p??5NU?|-~tz1G-)oyH;{ zg2Tt^F>O$J@4H`4HF9=xl+#r|&z+^x_Zg^@7QfCX=ixiww0ndOLVc8{{63r8S|;d3 zJ`i-$pFyw}x2QNBIBAGZggv&Bgumg;!eT=9RF6H|3D?oKR2Q9S81~+I^wA*Li(6Fe zZ8$Pa*9gSvb+2=2wlHC?Dn8Y!v5tor*)wD|2=?L@6;E)(AnihoMkgw1wlHC?D$cU6 zk`v=x&XNYfUfiOh;xJzuC&q81T5Gm2!K>Jzc?~M$#Q3tYxOUe03JK>S#^2@2 zKx6=QKe{Bw$mbyj!Cu^ILos<#(~=mcv(49RVS+0hvF2{TT{=^aNrkV+wzeJ39*P1vnzRc=m5bR}Elh12f*ol$% zNj0N3oC%u0M2v@h{hSyzYYsOE_A<{Hc^a9tGP< zWo7`Ks}6N?hWo$Ywb{Z1&B@}Kr%JNS$x8~ZEn^VuW#%Qr>uvJL%7NSE((z2HVuDt0 zA;yBpKb&<-r4Cdy2=<~iWgt}Y5Y@S(+Z!|NvCX^gzo|7zd)5um?UR2nv?-iTesQ3R zI|wJ_Wj$-t%)iA1pGknMuX-zW4kyuUY5TiDuoo#C_*L5)k5xY+liAa7H!B#D$$UHO zfKM?%f4*^q^8^ds2{#D#BE1DMGF6`IyjLk^j%OvtI5)xExusZeh!f*}{Y(bIUZgZ( zo?&>c1x}3ldE?n^VS@K(!H#klM>#S6-h3~L3HG9Y$DGW`9~U|?)-4P3XA2Yb{~$)S z_%FuRS<$S%@xCvHnuWW2Y`zoYbAvn<-9?-KE?tw2UD6T;JJ-<$tKFGkFM8%6K2@LN z#8`G}K5Lu2;|-rf0pdf)S!zDo-Mx(?4T7Gz&F7Co$0@!^#b5_B`{E_zWKt&htWLBH zM}k!)WHN&~AGP>2QhF2loyM>FxNWeyh05Y%G3WTp;d44{^Ssmu-`1-A1e^z%+9cSE z+Iht2`ZPo(Z0h#@ppx>58phwHo=D^FCU4_Bj~FYNL9iFK^B}r633i^xi3cSWTbQ6e z3dH7zKRGcjcFAiH>_zQ7h=XT(I5CDMsIS<<1ocrMiasst#F$`N2Eks`&Vv}ZwZ0Rh zm|qXY7AB~V0&%@lb|=QsK0g}-dr>k#b4asWonqBUd%_ zeeCIFy5-SJcDKnx^x}l8L415W%X&HjXPKTIVi4>_`6GxCp83{}s@OaFKTlZh zFL`3-TniOjn4laU#Kx_`&S;{1#3+McFB-9c2+#7x8BGjqvVdo{G!rxy0g)lp<&27+ z91J!H!|VI_3dE69;m)XNZmYS9MqYeQ2cHW9qCl^W_Ii9D35#MU9{O7}@{+UNtk|>N zK%}pK!fy5~$h)%THpLbu`qVjT)#y4x_vp4CM3vNs>~NfSx3>Q%C9^lNC-3QGeQsHk z9`@I}SC8kBC5XNi584MXO6@nXKaXDxg2uQYPIup9Uq|la+pVcVuosQ!LDb&mqXUrp z+$`?4@71XXqZC`1pcw=Zck1VG zV$6@KZxHN7^C%!X`P6h`e7N$fVha;A69U58SI&vCqqoZ-*o)?aKs0~b(TUM^bW_C^ zCTKbu>gf+^b84{1sc6pqVKU+i#54ODns*`erVJV6Q$) z7Ax1;A$m~7ydYNeSfn3(3GyZ{T1v5n35+J4(_^GpzzM_;cjyJ^4X)w+;?o?E?>Jua z1(+v0G`l@ppTQS(x919*EljY|gws6g&U3E3Rp;IY!CrJag5~2A*fYeryQ}VJHO`x0 zf)z9DB4{sgVtAVE@bKSaFFxe~JN%u+4zqaM2Xsl`VG9$i{GpEi<9{)3)#~D6g1sm< z@~h2V|BEr9*$x+5n4oybsgot0?_9@;QFSaP*o*EuVwBGt>|966UQPH(8Hy|2HxLKf zVIL)2dD5H{41&FAZW%fh3PBG#x!M?$r>4&(cH{AWL17CWV1zcN*^g^3L-R;#)#Lv_Ar z=?y;59HDLO3Hbi`41-{=`Twj|r>2GKotF-PXjEdf&WF9i8YZ2t*uq4G4GUDe?rx3$ zf@mAqR(HgXq&>DyG_E7$$4#nBOqk9;=7w=i*mEF7bA37mGW|B=75{c7{5ot^88(d3 zN!C9=jDi(^)(Nv>FAHm|L9kcB{o9n4e5`KW?kR|2<7(>1`LT24sL_foOl{Ta*H!KN=FWd9$fOgn7 zYI1kQzn8D0(D_L9Vn(?BX?G1vxa$Sm2XHJCc!%gCWaED~o-TS${;pti{wlFboxkpX?7_MJ>;)6(cBa<#N z1ZUp=)yyE+EB958+LUOVZk{Fqh%sGK=>enN-U3JJDz-3@dS$fAJ%60ucrP)C480TU z*OQR}G^u6~?6vJcwA#M_rwOK&yZigixVr0Hw|8zgrP#v6A2HFY;*xPXaYiB1zWZWN zT8KSsw4Xt+*OI@ys`~kHx^seLAO@CsX%}0C^HT4YP;6o1K*SyuC--=LI%P@_)yv+o z^KEu}tCq}f5bRax=^o`NI$rm73(>0GNqdd$_P+QxvtkPqPhRbF-m6RR(||bkqt~v6 zlgz?zq)=>OqI1pzYWT|WdUfLTAcn2kVUIqJGsDIuGzj+M?*{wne^_YOz@BHvq8}Jv z6cb$+99ApiP0$76|9}{$CRDXk;vB^pTc;WXd-2zWN{bfh^??}ZoMR7Lu5Bp-nr9iW zOAXnhag_mbjvlT}-zuLbU~n(|`v}?P|H|&Hx^R@++qnB#i!GP^QwF5ZKVF}S-lO?1 zAx4}6y5%Ofw`JG6Mhqt2s$>D5u8h;+abgg|`m>1c{=3^7aQ%@%uvhM>$pSog#_2&7 zgzzj_>ACb7dlk>F??PJ#(_51LkI!pihiB0^*nH6YUXbOWp;q zvAE6Pwxsibzny3Pa;bcSFP|i~w|s!EHXy6T7A8CkzBujG)VT7@-?p7&r$&rzW0n~N zdxf5O@5I1=@vEjBN^M_6j1LJ@TWn$Ca)PAJHQ~RAk+%L)I|wln9hzkj?1kU&JWc#+ z#Hd|6o4pw^j{NIuv4sizekTUvf@qiLcRM9w)ZH@4AlM7-trG+H62zXKxt!}bVt;nA zg$aI6&~ch>AvEE4n+OHj_kG+q^m7h6UK`&W^wa$G$TWn$CL53s& z4;GKpQP@`#PcYchedj@g%okTN!CooSCkZHrR&?M&AwCTa(1qr>z0V@!DYh`-ADB2` z@z`;?aaAF1Ew7?ePIG(bKTl*3?3L+W!hmdn<8aa41&Fyw22q+$H{O#_F5E(5`~-VV}n8D$gJ2aPtAA% zCy$5gyeMNciG}mq>vx!^{xCMDVha-oYx@KQb`94Bl1C!OLccD$OlM@4JM$O>d+Bvw zRN6u&y^}<)%K%_c8N)IfC7H(rzgJ7@i zzE4$;gk$xi--TG(Z?rC6!0j#AzNTUe6TYJ!s!7pf^xG9%LA)IhrYq)gd%atKQfy(O zcGv^;dhHnfvWXDK?~T>1vbepqrv7XY?DcWr9d)kI7@cqSW)Q2(kJDGM?_lFojTBp$ z@OgblRW6IuYIg}yJK+SKD7o8PZD@0YV6Qn(Z>qdEu`X!JCW&!(g3go}YQ~k8%COMi z{ipK{HA9E#ik z)B0;_&zvy5d9Dy6o=(!^F~f3WZF_@Yuj<{esW#KYbf0h`N)Df_kADpE_HEx$v4x3j z=P#+sRl;U4jz3h!nxpkH^*dq&&X}&f*qyRg$9@LE zUfU`hSE=%i)}2qU1<`5l41Eq~FNfqGtk}ZDqI`$d!$YC^=Ot@E#CbnMKfa1ndn*2B z5bX7#$YB+6I8<+3A;iWOGxZ+qbzg1vFvS)o;yyf}lFSU%3I7!ppwEz*dK1RyOS%qM z?DfOr11dMXD!pH=O=8phnYtbJ*-qMRgklR5@7o?wjmP4o*i#Z?$cCAEI(DZlmUyH= zuvgt&`_;srI1h4=5Qk69)Y;Dkc~_MTQfy(O)ttR*aP?4~D2@`8K!p$R%~Hn?@6y}lOR;zD=EaNA3$Ia(^IESg1vrE zAEWLi4b^pP3SqCFtk>eisVTorRz(voRQ-N)>#T2g=%cLTgUlRh^Z$hYd44nohB=`FwyhZg=**ow?1-Dh)uUA>t8@z zZEh0mm2vk%wPdba-~S-Q<0q4Kdk~u&PF8GTBJbvfs^lEEj(8_T$@o+BPav%7Cc$3G zQZG`GYux%+x`iN4q?@AsL7cHBE4DDPpyVR8Y@=JZ$}U8D|0y~Hh${I_g1uhvU8G(g zcI#O+g?LgQr!9a8&N5lCg^4uV7O9K}-8xNGA?^*EqOZo_3Hq1>d)*v}S?33C-FAc! zyXQ~QUJ%D0Pf~1Q;uFp^O8eTagQf`4>(41V3`7C1NwC-EOH0&0>4Nq1J3_YI6BNENHST1vu2pV{9$tKns(2|_H*c^+Z#lL~P2Ux)4?S26Vs4VDx(i}_SusiR z-~D^{5|uVhuzqx9p*CYY{b{N$2V(k=Ns28@ob@bK5e0D~TRu6d>Cn)rIwOcKO-zEl z+}1MHvTU#ptt~|KwyF9RuA@|;Ns28@=;&oCFfdr}>nFsrM^p7h5c@t&Gzj*pw{*EW z(Wo`IgLVFD7G+B?T=Mz zFW#%`4<*L6@acLnh{rulg1z_+_38qkr*Wi;B@9x_Z9l`mdMU)Z-^1 z`X}#l9kgY;>h&c=cX_=WF&4#}r6(M~`BCq}6kC`W`gxZcRCknq^>_t{v&CoW9w&ml zEk=eYZjrgAzLqjtb-y-B58e_1qKyA6UH^|D@5g^b6kC`m>Z?`i{iF2$jzWyAGE4t^ zEXX@y&M1Rmuarq_b$0zIy)=suFRIPbo}<{4yhNyC3lj?}MXAN3M(GtZR)R=hah5KH za}>M3F$wlEuY5+?S^Dy!AaCgE(TXihBpbR*r3f6QNAH(=)e*f~$AdxM48MgL1bgva z#~yTdr|aW*=4)S#SKQ+8bFMmLt$On=SfjN-j8sKt=(K1V5`>ReY++*W)phDZu@L>b z(^3#~N6*l`Ks1PB66|%p<$5*3KScY63sLjb41F2I&m+evwlFdA&kbsN+Yo*9gAiBa z&D4SD4gAxa1bcOYhLCAQh|b?^8HnczO?I?$%PaC_gKD$*gl!^+c8^Kb2m3 z6kC|6v^1)AGR{gJ7>wSqs{t{8Vi$bK&duEOd$TGgeJ`qmMA|{Dy=mL_8Pb^!WQLc-ubj3o^~i_iSpB6-b%$5Caz3dZHw|# z#y=g1W&f17MESY#>r#VYua)b!*`oYx^~ngrFQS4a%8yT)#frUtjoE68@^kAzhG>(R z=<>5f`6={no?;6VMKfz#l%MN4Gb6^IKl)js{B-^}+aTC0diEY$l%F_7L@}9iyn-dl z&&s#c6af$MiE!9Qq z(ZhGP%o`uPRWv#%x|EiA*p7oMMt7WY&H49;p~XP7&Ggxp@-u26oa|JG5lg^7qI zFKkhM-Z;eLR=F)vei~nBV-W0B>8JO$C_j6y=0l7Q$Fo_Y{9NDJP_c!Hdxzp`QGOmT zDF`Cp^o*7$KXWHlHwgABvnZYx<)^Q2ArLdFq_9N!X;iwLVha<#vy*6fuYN0A6vU|` z2`o{5V&)Zq?)%-sM7Mn@v?xDQ)5)7Sw9;FbC_kH9$xtwMER+bCy8PU z6BT2!XiVx92~vKN0{=yA>^u|@fL7+gZ#i5FLi^7E-~!Dw8Q zqesZq7RZ`diSn~7qzGb^s+-CduZ~V zt96tZX?>DD%BDp5dH10#h`DjHyF~ffJn@RfZ3ed`8D{x8ZAq86@&tXSH1HSYM;G|n zVha;n9{%dISG#O!uUZ}H;xEci?@HGV!t@G`koW51iV`4HQQzI7{H$75*ODCqzFPj5 zkn3Bupel&@b^1h!^0TChoF(y{kpKVcg^v-pV!}TvoOKW2|N7V3HO{qjH~%B z8U%asTZuX36=OZ3{LE>#++qt8<}*(iaMvTs&)W&f41&G- zjecQ?@-sPu#MoIlpDoJI%X6I+TbS^x{?roXXMaO!+mBo-V2kpzVNg$lV6Q6rt|iJ( zXwe@*Oh{0~7Ud^%tNw~DOuVao+Y;r+o|_AVCtV3!l%Lz_gA9VbGS0qWiSkqDmGp!6 zelBH;^0RR2D8*jo8(y$P`8jnXd$dWc^($+O@-v`NxMB+vPnsXKMEUuWCo5vy`K_ES z%1`nd6AXgAviCh~iSpCZBbm(9iWTfY{2U!RSFweO`Q5f!qWrAhk^#i|mlbSLej0pPU=Zxp zD*t**l%JA6iSC@DX$4!9pMndPD7G*$Ct$TD%1@>IlJ91lSKb!o=eLAdbx(hby<*Zw zSfczS-Y7Zswjt$gQGU(^tyFAbqE-CGmMA|@Qp=i&?hDG=qWnZATBX>+M3D>&Em3|x zE|g4v!KG5RC_g#RuQdqv%6)r^CCbmm%d)1ZPxg|wC_kkhu2XDbqR!K)mMA}$(#YD6 zZUu|kqWt`Daic-7SMAf`mMA~hRB{kMHY;L_@^h*7X2ljJ9vlp_MEN-tE^Anx&nsw) z^3$yKR)b)#c=d7m5Jr8?_lm0j_@@H4C_ftlw<)$Tk)!b_OO&5WULi8|%WsSFGyAAX zu-Af^5KEMw2g`(5v^}pa%1`bi+Z9`wxL0wICCbmApJj#6&H1@(QGR?b?=%SZI+vo8 zCCbl-XNf>0O_j|SpG1QaMVo{=n86n1=iqpcVha;RSJkvc`3Za^ z>oQ*VOk<1kGxnox5bU*nQDsY%pW*>R_-svLi}LflvsbZ&iGnRlS)%-m>mZ|T^;be$ zl%GdkV+?}526riCiSpC9ix3xj$F)WIIUTe|v4x3_jSE_${KRP^qwVvDeQZ&F!mjU8 z>{YvGK}(dM?C>&)$Adn3MEUul!Cu7{CK{BT8z_BzsbtDh)8CwmL=G;(gFC_nx&M-*F_ zSiNkopC~_bCkT^C{cb+UN;H$YSp%szbHSew+eCYOU5WsewyAtq6`cD-7?E6`-}49_f&{& zxdNj^`APoHB-m@v!7zVOen!5%2_j?N{2oz$k`+Cw-Y%}}66NQP`b)Q4UDGAXPtTcu z>0+%*xkUMyU;jRcbhTSViSqL%&QZmGcVSG3zbHQ|uiVsTjL*^TC{ccrq&lkD!bEt9 z<^H1lBtLWuG3u3?93{$+PiB)~ugPt;`it_@(E1a^0|I6K$97^%v!5 z@HQbvoZ1p4%Fl$tCc$3AUfu8)#<k;KA9tgHD5mfv~mnc6Ox(LzoSZXImb$^p!FY_&VpE{FA zl%IX&k1Dn>5zwuaOO&4x4dlJ*mot|~l%HayOoF}m4fXMvHDa+xl%Jb3535!!x4K06 zNiz7kF2886OO&5Q4PWZ!5rBCryIA_^#trt2w1TqWq-J zc~o(W!_Rs2%eF32e*7-W>d&*It9V5Dxt!prVha;zqC;Gw{0x2e5X3(fn|Va}DUDVA zOt4q8{b4Rqe$ID%1Y+cZ9v)GCI_M*cEll)%GtDK+PvygpL7Zwc#3Ra2z+97HuQn+c zx4(e)>IMES{E#w6H_zXBhh2Ct`j zMEU8F1ib-$A51LkvehNZ&$*$`5o3_=JdY?pwGNqI6npWvf-^u->m$k!YJZf}`iSy_ z+8?LZN0c8_!#K4*qWqx32Qj49N0cAb{wS#e`f8Etps$3~`iSy_8XXW)>m$k!YJUuZ zy`?O56qWqv<2ZYr6i1LHlAH`l$>m$k!DtVmhpznm#`iSy_+8@P#iwUXq z5#Y`9Xyb2&wfExL}XqkbORrgZsBma&H9}rUOBgzkIe_U)~ z0_(ROTGsDljWB9`MEODOkHrLgNv)5>_;2mGQ|kle2em(ne=lE$)cT0>g9;zSkXj#6 zeo*_P*usR=`iSy_8XXW)>m$k!YJUuZy`gBl$W zQtKni4{Co5g1w~HN0c8__<)dFA5nf#`=i*xgw*m$k!YJV&y*h^}CMEOC54+yFC5#m$k!YJV)YFoCK9=e?3D7(BrnDU>Kb zsQr=Zfo~Qjq}E52AJpi8kXj#6eo*^k5bVX@4eE+e>m$k!YJZF`iV3Op5#=M9WpmS0vXawLYT!pc(>m08;BC$`5LP z6kDX$N0c8_@BIT zYJEicLG6!A+6rlLq*ahsNB&=~T55en`9XyT2&wfE9U%pwGkXj#!_g}4y)cT0>gW4a1U@xilkr@Bg{79{jC?=@=kqVw~7ABIUi?=2_(-jfC_kwEvDm_d z`OKx(N0cAb{ul&%@jH#20kuA&{Gj$n@f*i)qSX3`@`HLET)EWxi1LHlAH^0Xq}E52 zAJpi8kXj#6eo*^k5bPzjKBD}f!Uu%Z`iSy_+8@OhCZyI!lpoaSfRI`rQGQVSV-V~m zwLYT!puz`))cT0>gW4a(7ABwu72A5nf#`(qI7CAB`H{GeV(2-NzB@`KtR z#a>eDBgzjdd7@21YJEicLG6!X3lmc7BgzkIbPz*oeMI>|?Ty`F*N2rK7(O8A z`mpi?_s3{N3A#S4{J_xxLDz?sAGkjOp;>f&SowkB1A?v(D?f05j7F58>%+y0YTS?l^?i20ijuReOUQ{;RAxM z4=X=#e~dnnl-#l^+;BAn5wA@&otBXhaFRKCJw}*8xG- zhm{|=KLMdxbbVO)fv*FCt`93eaDR+u(e+{F2PTiRgN_k&eOUQ{`(yNHDM8nVl^-}d zI0juGR(|0A1cYYM^%+MJ zl^-}dI0juGR(|0A1cYYM^MlI;2gT_09{;OKy$>%+%+to*?60YTS? zl^?i2Mk7kl^%+!^#ibpMcOTx<0J@!0-V<*N2rKxIacC zO3?LTF_KbA3?xfujS0t`Cm^_a`7U zi$>V7PYGQgR(|0A7>y`F*N2rKSUorfT_09{;Qj=JX6Yvs{s&wiR(|0A7`i^J{J?r} zt`93euoIl?!^#g_6C8uC4=X=#e+(_4Y=m}DmZ0my$`3pj5OjT5`GNam^o*=$YPvqG z{J`)5LDz?sAGkk8BTCTqVdV#o4hXtFto*?J2?))i>%+No=;f$f#HK=(Dh;E2kwv2h!S*tSowjY1A?v(D?f050z$Ls`nbwZCz{@L zeOUQ{`(res1YI9ie&FbUpzFiR58R)C&@8$>to*?60YTS?l^?i2Mk7kl^%+H4tp1NSGf&SowkB1A?v(D?f055{)Q9*N2rK_&Ok* z>x0S<+@FBZEV@3dX3_OwfheD?c!NK+yGJ@UA69qDA-+&MXPeOUQ{ z`;$>Zv)FUaW3baaCx@;NogcVAiT=L&I_Uba@&m&M1YI9ie&GIKF2J#f5_El7`GKPY zg02rMKX88nLbK@lu<`@L2LxRoR(|0ABpOkIu8(tms`0&|>%+MwFoI!^#gF9T0SVSowkb6A+q3*N2rK7(O8A`rL!c58R(bBTCTqVdV#o z4hXtFto*?J2?))i>%+H#^5*VciF=4=X=#e}ZEuLDz?s zAD9sdDp+uRSowkb6A+q3*N2rKm>3{VhwH=258R)|ayCfh)jHRQl^+-$cpY?oSowkb zlhJdA&=DOOz66$aObl^?i20ijuReRvF9IjdoX z1+EV(CUAcmYD5XTK0L;M1YI9ie&GHzRzkDnx5ax!*N2rKxIc|GqJ$g|1YI9ie&GJ( zDxq2O9)h6j!`D%B>Z-;XQ9|A~5OjT5`GNbBtAu9B_Xe+?t`93eaDQ?&q6Gb}V}EnH zKCJw}{Rs%o($6&9SGYc`{J{N*^b@C_M7ln#{J`+R>!9ny$`9P1NFz$n^%+%+ZnwAF>Vcr^!^#ibpGF!{g02rMKX7zF z(Dh;E2kuWmXck=`R(@dkfS~Kc$`9P1MjBCqt`93eaCAV>^to*?60YTS?l^?i2jWwbK zT_09{;OKy$>%+AGkk_HKGJvA69f&SowkB1A?v(D?f058f!!ex<0J@z|jFg*N0UZxIei{Xck=`R(@dkfS~Kc$`9P1 zT#YE%(Kf{Rs%o3O^-ueOUQ{`;)5?CFuIF@&l^}$Dr%O$`9P1fY2=c zgrffnt`93eaDQ^?`mpi?w;@Bnialsx<0J@!2QY9h!S*tSowj~ zgJaP3VdV$zPe5pvzUw(TbbVO)f%}uIXB_=I)AeEH2fhxDLDz?sAGklc8c~9-4=X=# zbU@JcVdV$zPe5oET_09{VEBNb>%+fi}pYsEPu8*Jd<1CKK z0YTS?&JWz5fY2fheD?c!NK+yH^bAFr!l#M7s*T>KK0YTS?l^?i20ijuReOUQ{ zO9O(gkDv3CU|xyq@`l5ZlCJv{T_3lSy5r=OoAZ;)$`9P1L?cQ_|27D^K7P(mKxme9 zn1i6}!^#ibALk}ze_wqabbb7s9}skX{G1KK0YTS?l^?i2&H~Ctl%VUw$`2eJ z5OjT5`GNZr5Sm5T$ItlzLD%OVRDR(8I14BnQG%|IpYsEPu8*Jd6A+q3*T>KK0YTTt z&-rl{P&T3jT_09{VBCP9>*MGA1cYYM_3?9lK+yGJKK367xz zT_09{U`F5=bbb7spMcOTx;}o+4+y$Gto*?J$%unv#BefneOLv6;Q@lKkDv3C=s82r zC1S+j-KFc}=lmoZQ9_&+5OjU~oS%TuEHQiVThaAl#RTq8q7fy;&A~C~`mpi?_a`7U zOAI9(gRT!NKX88%jVK|G5eT|Ie$G!oXqI?WAn5w=b-?|}XhaG9JGnVOuJQx-Cs9JP z^i%2P{J6>w+@C}vN`!xNx;}o+Pe5pvex}`=A6NN-`;+J=PCtosef*psymGoeto*?J zNi?DaT^~Q^2LxRoR(|0AIBzKXvowpYkDv1cg07FB^W!X_Y(xpVK7P&*2)aJ3{J{MQ z2+gAF!^#f~9}skXSowkb<1CKK;cOlu==!ko1NX;yL)o9D1YI9L=Lg52>%+K234&1NX;S zK-q{AbbVO)fujS0u8*Jd6A+q3*T>KK0YTTt&-rl{P&T3jT_09{;OKy$>*MGA1cYYM z_3?9lK+yGJKK0YTS?&JWz5fY2K7P)Rvw*S@ zCFuJ2IX@ui`mpi?_a`7Ui>{BK^8RIR(@dea5j$+bbb7sALk8af0hz-ef*ps9D}ZppYszCnnl;g z&-npC*N2rKxIfMU%0`r+>*MGAfS~K+=lleOX3_QWbACY3_3?9loCTDPC_&eUl^^&z zAn5w|IX})c${wArkDv3y**rqf^%+{BK^8KCJw}{Rs%oqU+=5{D7eA zKK;nWRR`9UW>=d`%W58Mq9bbVO)f&1f3qwLYyf$!)1aGH-CgRYOC^W#jT z?9r8=>%+KK0YTTt&-rl{P&T3jT^~Q^2LxRoKj$YPG>fi} zpYsEPt`93eaDSWyl#M7s*T>KK0YTTt&-n=m&7$kW$`1@55OjU~oF8WaWg|+^_3?9l zK+yGJRR-=)Kxh_SA3x^@1YI9L=f_z<*@zO(_4#kk4+y$GJOQHd_d6k@pFEh1(b~_!Tw`9Kj@voE2rz@=lle( zgRYOC^Ao%#H|Hmz^8@$CnN8VOs{~yiKj#O(6KK zao$k&XDLC~$Itn}G3ffR@&orLAT*1v59>QHd_d6k@pFEh1(b~_LD$F6`2j)Khm{|= zKLMdxbbVM!flC8|u8*JdlhF0yS~whrluX)4(e>f~hpz*It`93eaDNhwC?PW&K+yH^ zbAAFsvt+6S2)aJ3{J{NjZc_I5)z?AShxHv8J|O7&_&Gn$0?I~|pzGu3{D7eAQHd_d6kVdV$z zkF$WX5hdvQu<`>(2LxRoR(|0A1cYYM^tna|^0YTTt&-rl{P&T3jT_09{VBCP9>*MGA1cYYM^g1pz_V$Itn377#zx@D5T+(Dm_ien8Om@pFCxLbLRHIwYA3x^@$Dr%O$`9P1;5(>U`t5Rae%x+vaDSZZ!^#ibpA=rLtI_f`(e+{F2Q~zb zLD$F6`EeFdHbU3O&-qEw8p{48H|NLg_6GMSIEE5*eOUQ{8G&Qa_3?9l0z$Ls`uI6N zAn5wA@&orLgR?<)HW<%7Zr3unKPkFCto*?6072Ks&-qF8oT29unP~%pu8*JdlW0T< znPUTju8*Jd6A)q6s_Oj9!q)-eTpv_S;QpW|=~yHrc2%eI14jo0T_09{;Qj;zR{M`; z;kQkA4EQ=A==!ko1NVo&l|+saI9_&M5eT|Ie$G!oXcpc>_mkl3fS~Kc$`9NhzPm>w zO6cFo&H2gobAAFsv-DHx=KSQ+`GNa`NqfgWuS$e}bGkl$&JVwXM?c}36@J?3`uI6N z&MwP-;`Eb9*N4>_7(RIAbbVO)f&1eupln15x;}o+4+zZpiCFo8`x6kFMc0S*9T+|! z==%6MKh6TmMwFoItna|^0YTS?l^?i2&H~Ctl%VUwY7KlH z5OjU~oS%TuEV@3d*1*>RLD$F6`ElM*_Gi)c@pFDsAwk!Nl^?i2&Kt`9EG6jr_&Gl~ z23;Rke&GHDgl5t8VSNXN4+y$Gto*?JaTZWEq6A$ZR({~QHd_d6kVdV$zkF$WX5hdvQ_&Gly z==%6MKLMdxbbVOgf#Cy!u8*Jd<1CK7P(mKxh_SAJ%tZ_<*46fhe>pL)fK+yH^bAFr!l#M7s z*T>KK!5RQvA3x_OAT*1v59>QHd_d6k@pFEh1(b~_LD$F6`2j)K$Itl*2+gAF!*xb< znuDP0!^#ibALsh8@&oq=kz?x@bbb7sAN+s1K7P(mKxh`G`7CFB2Zj#_x;}o+kJX40 zbbb7s9}skX{G6YF&@8$>tna|^0YTTt&-rl{P&T3jT^~Q^2LxRoKj$YPG>fhe>pL)f zK+yGJ?prJMeWt(Dm_iew+oAjVM9a$Itlz zLD$F6`3VTkqU*!@4h$a%-a$>>ChteOUQ{`x6kFMc0S57uYu- z==%6MKhE{xx;pyj4P76u!=e+Pb6PT7xre&}g02rMKX8AXX_P%WT^~Q^htquI7<7I7 zoF8WzWsj}|T_09{;OO8Obbb7spMcOTx<0J$!0-V<*T>KKaTZWEq6A$ZKj#MoT^~Q^ zCm=M7t`F-wFnmDJ^col>%%o~SPzD- z4=X>g6AWD+)_35V;23m$Sowkb<1CS_&Gl~23;RN=O-XEEBt%V_3?9loL!hbnx)?r)acQ%jP(y2xh3(Su1R~byJNL{?Tz@WF?uoM2# zHwp~;(eYccuN|wLG5XvSjVOT*+EleNvkm&(L13nZ#VTivKKFpoEX>wJvH#B+gmvsDlzxs(r^mzJ{uuIx|&nL(IkdFIJ`d^|ECBokdoy!T(s+fe!2h>u@nUu$9m(bYr_?@V~Ch zJHc9C%r0+@D1m-)!@nT^>pIEZ>tH9j5}L)|pYJq(2iL8hV9hdKJa|^35heKh^B6p? z>xfUVE*fJRMnGs*_}N9*eS)>u7!x-VjVQrS2amz`54#9Gvil zXXv2W$-%AZxa0i2iAI#*r<}*&rxWY#-Df0N9gNW*9uS&E`{Db43TQ)sz^s%6-b8FV zmUmu6HWCo46LFw=bsS^5=dVoEh{xkGVOi72OI9EE{}EFj2>%#uCG_Ni?Da zrt73$uUBAT+J%85 zLm+4%p&k`i>{&7(Gz)W#QdOqTGO(UN&~ie}D~9!CHKGJfs$!#O85mGJ#y1@->S{5} zs({ce%wtNmxMP-qy#<1{7HW4f>@BMiB`~!qRj2VR1Ct8`ra@WM2V)pw0iju#E0wyt z#w-I14Fo1mS=1oolD}598c_n%r%cgZ`36QB2xqq4mX2Y%1%zhN(98Qi-@w=dL8lKD z-WZObbN8|lCFl+Q`a-^eM+gEl!z`-EF+4(N6lNnzV1Af+e?Y#0QwU<};NG@K%XB=a zY=eN%EKD^spPZX-U^;>rvG7T|zbURCZ5r9BpZ;vN?3ro4Tep}~%}n2#`LrfY_*=c( zYN)MxYC2w0(9XG{TW_C1tCZ8(%&Yk`4eU>YnQ>-Y+Zpsoag28l46>`wOUHAEU1v3- zgdRI5=i+|{+p%Y-a?wl!^AyL})3C3-Bu>XA4mY+MQ6hYIF@?{fFC&JT8@vuo7Bt;! z&oG!Q$jNyo`yRUagBBerG3E~j@2(Owjc>bk8l7bPR&K2wDXS4BFsH@b*)89| z>HvWWE*5M0ankj1s}Ut=ip(CFZ(w+UC^6v@i@HI)Y5&6kp;?$WV`hGrZ(yf@ppAms zM0|IJo>n7DU@DDSayZ|>RKeBYEEq4Sf5b3g0z$JeH^(%+a~3Td5VUGgV~JteSk1yj z9nA-e7G@=xg}AE0tOD`l z@}d@XwHRiV)rb<9sAO&h0m}*mZ7tO9V%S>&p;?&uWHv_y1|Ap)8euc1r(+mmRwGJ; z*K=BDs6obQXM>@*w$)6x>u&tn*rRwGL2{R4J^dbznpK4x;S83yhT2+aAhsQkome*!|YFptNa&}N2#qXVMe6NSX+wGUF>>}vk@h*Yrgqz z*A#;uTM+l5zYnSWP?6c z5Dm*?FJ%zue+>xDVo&XX_a_^4(t>F7)KH5RmKZ&@RwGJaZ+&yko0ARtZAlzA%wiQM zp7cyeXcl{eyN{S`&?^iAa{(+?iemH%yRPAEL#+f$ zS?o)Gy~kvl5g;%t#bWh5hCkstma`Eh*zbP)wUg;jfM8!cRypJCL&jRo!b}Tu8M4sl z&RG{ioH1*-#Y$?7UV7I%pZ!@%V1|Zyr2b^~)#Dgl(Vvgi+8F)%0iju#@?q}0aI%3D z0OH_Z!!1^XV>kg;BT8Tvh*^H-WCK3{1U&;D1KvSEXck?DjU^`=xD6mM$HZb~JBHif zEQf4F3CuJx#fwcg@Eky3R*J>yc?^FdAT$e8S4@lV@(dge5PRWdV1+*Zu>KgU5hXC2 z#VpyJXW(mqz|0qmDnJYmBp@^k(__rWck&Ee6A+jyV^L|qhVY}UMwFnxQpx5Scqbq* zyT+oL5yNK*2+hJ29CPpdJUTNVFdxUFViLodaV|{uXJI~$d3J6dr&e$Zju8LA!$DOh zo^;}9&e}N|Q3A7h%s(UZ3_KtlgLV*VMKNrlfY2<=7&7ICnR{K3$v2UPmkppm{lM!MaiPB7Q?Kv8c_lhmCV}i zc?Omh2-;ex-NmrC0z$KBgl)Pv&%h7^K_d+H!5D^^bH%a|B`_Jvl)f#`z!n36iBlFe z$QTw{Kxh`twzojQbOV8@Ru*;67^a(Z-m(!TFyYG7?U-j^y@9~wEQ?xd44W<>Gz&Ah z%(4!72F4x;Oy{zw*TyjRtVWc;q%PB;ZJvR>2O`yDltoQA{%BQ5Xcm3Kms;l;%n}1Z z(-3v%80Mif4YLs?!Y3BYe6gqk#PC3zRg=A1V&;o^dh-+m4}`N|Tl6G5W^j{8c_lh=S;G3s)3&h0<-8Wx)Wmf zsa7LOU@o2ce%n+7R~1C{o6;5?5OJ4%;{!soFgefU{4>?Svju^fdKO(4F+5wV5hZwy zedmm62F@*r+9jW|=;VkWeJLa~i$-z38q??tgE$F(FuFxz_`=RL&PJ5LoIo=P1l(Z| z3-0P;U&r(LbG<`CvoOifRJvuFf%gnz>-Z-vx?bXII*qp)Q38_;O_$Eo3>;_>n4@UX zSrfyp4hYS{L`L(>@@WSCHVFFK=-!FpZ(EHhfw_%l_~&@9mb?$*nmZo0=n#sp7&kT` zG%LJ&#mq^IE~FS9x^vjG_q9sUT0f)HbOR?H$G}`mi%zE)u6saeR(Ma%j%8MU(80Wd zUCLaEXOA{^u6O@tcQHGbSrI~?Dvt3|)!E5-tc7oUtVc#8O3<+2%JzTLRd$swWxv^) zj#qs9K|p90JH1JuFBZpO&mh-J&_kGDH|`YIOVFVgu@{l+CFmjKuHY%Im!Rt~!ddj+ zsg~;{=u=EIq6B*%xn6=^ND$cf+^v@!Y|<#vh!X6tbi) zTrWXSCkXa%a=ipSory-2z+Ubtu9u*{69oH2xn8p8@yh~2v)H}L^%C@^f?zKy*Gryn z)F9C;>_ea8dI@?{x!b%D*z4Y{m+ZZv9{03A8c~8hwOlVj_biU_b@_g7y(Bs9l7P@G z_U&?21bw_9*tg5|67=yV8c_oK_oujCf}UOwFQYe@>m}$F4hYR+|1sA~(2oq_r_Fb| z^^zsEswWyz0&@sbTrWXyG6?oKyY-S2s|AE+v5%VTCFrXLF&ll1FNKxkI@X@BC(%dACZG-pF;PH;K;Jy3%71M55J56Ac8_u(g5 z){4+k&Iv9@3C+^)rrS^7t+1Rm`SRfV!9H59u%NFt(r=pEPv5PupvN}&4l2Q(TCT95 z#}=;~`{}zC7WCK#gl1vi`xIAL&AMvc^wAMvc^w=gEQGz|STwy_vEePzV?^amQV;c~fg?;Z+Twy^kEC}qU z?^amQW1DD13HH=-g#|sfAh4glTVX+uZ9r%i_PtMWg$2E^AlOsO6&Cc^CK^$KJ+)k6 zL60p6?5FQmSkPk|5SqoFTCSs@dlm%t(|0Q@=&?;Sq6B+tc_l)}EC}q_>sDCC_nnbp z*A7=$(7(XFc-;yMIz@8X!NYYF^c>{69edph3%Yo?ukX=_671UH3JZE!K(LR2D=g@1 z2ng(9>Q-3L*TB6^j~*NI?$9g26_y)+8y);sN?^}ax59!x3LFD_vAPu&^k)QwX0hjk z>nP{}0l}URuCSm7B%=`}u=lH5VL?9#2$T1&TVeU&*2e-uv#>j@TVX*j3kd96>sDCM z%aYNE64=Amt+1f41qAlSbt^3Bmk9{XVh;}2QP7hE0{ic}6&Cd5WHh1#dkMM1g8m#3 zr&M0=R#<9Hsvi)V#g0R+qo4y31ok9%D=g?!q6GG;b}KCCU&Arj2glV9^u+~)X0g|fD=g@} z15pIsd0b&Z?_EYCN?^}zx59!xJP_>X<1q&2>ch_SkO-h0(+9X6&Ca<283p@_mL|s=!I;IIwyJ`xx!Ml-McF^q6GFpcPlLDiv)qa z)!hn9pATOP2+d*-Cs$a|(+L9mx4RXV=T6ICp%Eq6C(2b3^ml^59`SC4rFFeg0ijv! zcjXETdQ(AQA9}aKg5J~>nuUGn-3kkOQ@Pu`5Wk_{l`AZ#UfYp-+8>Q5!7f~`u%O=- z$6yyOS6I-M8xWesPG7FDbna3QM2Efax)qjB{;jw|BT8V$f49PdzF`pWZ-3XVu%Np* zAT)~|%UoeW2QvsvD{w0;>)-oqxki-0TVX**`ErdYfk_f> zg$3Q^Af~_iu3KS2*Lpx`7CYg&!h-&H5SW7DR#?y(zg#0qU?PTFVL_KXh!^L+>sDCM zeZNcz&0^m^*HJLDqoJGT;Z|7C;lE5HN^o}q)`T%Db)MT>-L0^o-;#UUAH7;)Z*{lA zf__Wxxh~hiwXNQED=g^g%xFXj?B(uOSkT{zGXwUBcPlLD8x07}VlOJ!QP7*pdxkda z+zJbNQ!^S-0(;WC6&CcVf?&TZS6I;h8W5Vro?5Q3pvM*j_S1JOEaFm%KC&d*OI65FM|6;XUVd?d54(ItC z{aKntpNK0g@QXkc_FL^%Sgw1tNTLxX=qz!C1+EbY%qwy$EO3|tLbK>aafJn*6bO1z zTwytG(TRyhl)!wX6jxZ_Oo143BylS&aIpeHv%y%BJeUYmXCFoLf zO@;8HCX zm9A5k=DHG^MH`-LXSh3lJ|~AZd_Q!U(vH`N5;X344BYpCpmERFK?7e2&5~o|lZc6) zu2c3FSpFJOLXHOlQ$t;+EO!!6LbK#O1cAwfY2=NjlzCW z?3DuI9qf(5e$jyibs~)@ff>oJUljYMfEe2KY1c3M#C7!oLbLA09xv<{#hx!9Ucw$P z>=(tJFOf!+z^rH2FN*zNKwyTn>lekoG6A7k+^dHDqS(6z1m;w`e$lgDxh&F%5|~+? zV!tT%u>mmw`{7_;oEZD#1cYXBUmtdbVxJ!n+zE*Nq7_;+`$e%65r{|XOmh9AUsP!n5SoQq=qdJ#Vt*tMuT-7l`bB^Lq+wLK zNBI={MSouUV#3{+*e{B`mN>IqeyfLPzUcZz8$4N?bLUg+b;NF2oavrozbN*MN-$|Y z#ePxjK80g^bo}$KUvzo(`jJMI&|_oYk6H6wzv%oc>ji{nVbXkx{i4`?3dgvs)eP4! zI->dIkw%mVUq|sKGhM%^`RlTP&@Ap^#ePxjSA}ETbJbMWFS=l4!$>1agzxUTWf!@A zQS9dxypFN&l}fQ+H2>MB6MYYH*LVC<*DreMiZgdz6=4a+7 z(@@7b>6Rt-lS-SS)a;4ogPULrR9qSTJ`Q{HZhqN3dTM+3?|+-HZ|R@sUNaT{=og>A ze??N|oF#VAQxnXMzi*Caw13Hx_-Mt)(N@f^;lIn7{t+Ck9k5$agPeJ0XWQY{HTJ-x zlg+6Eo;2rNyu-H2nP!S@9b_6lwb7P8Wtus%omJ%1+D|tJ_xFpt^}WUn#cHIzY?Ary z^mewz$@sc1g~~hQIsw zOJ~@LZQ8nj-`aE>j?rw~4EqE6$hx<$XJ?j~Wj6gV-ps6Xq1pJ}Omop&;`Wn2B1GU@RxwGK0T-ZGMrpN`UPZz=xxbJim@2-+6QM$mi-(1FwJ+DfNzhSMH zS@W9Jbli$<|Du|4>d%c^j#y(xZiWr?c-6uuH?A|h>Tk%eS@_7O*8Th9I<@gSR{S){ zT)Dkpd~J!IrcB-Cc6o&M zy=>vZrZdgBXEsH@rT?`BxYM8Y(o+1*EA%Ou%hyq*evuW|JlLp^uj87zk=dP_D&*^E zkl(_Xl9BuOdoSOOS6<@$JCZAVrQ?0m2U`AY9s|cpJ-N4xsex>v8YYpX4{8d0KFrx6Lya82EBwR*$QDD`!}xK3^+ zAT(=S+X?P3JHFFvIL4m-w?}W`b+mq>&}u}90kc{pKb}6tWa{zVU9i4IR1v>b%N{EN zLbJk8PxI~NqIFmU=y%PV!RJbe5xXx)KI=N!Y$`>&|K=@Aa#wtXZmI@_0TE^$`;1|q z?Jp)Z=9%G!H-21!Go1BjxD?KC)}P^0@0_{7{rmcKUHk=imwF?LP_eDbFH0#?tmRO!k{wYnvZNZW!%mn-eJC1(NX39;p%gRnME&p0(irjsd zyDqIwMwnIy2U&g}@n5`GSN-0{l*PAp-}pgRBT9@o@o7gt+P5!=Qr`?RukPy?KiP6% zKxo!G=(XN^WP+)A`4A9AZ~Z5F182AgUz?INtyH7%?v=Am*9L3N^1`x(y!xzJy41+I z9mG$I8=D2VMtwft;g@=vi|&I5xv-30CyZvnQ->3Y7r~|Ga-!+(&(d(dI`$FQxk54xDeUgs< zoKZf}h!RbYR4&Y`gbvoaSMqf%=w$AknvQ3k)GHt~OMly(oEmoxFgL?v+0(CkqQARl z>9rkq8SBTI^R7?FKb$)z(TEaDYnLu8T5G1+aKl;ntsXz^WphJ`bUfpMu>ql3;XOmw z`Af~O=(@)`MNYAOi{1BN*Sjxda5Zz^BHTk)m;aAd=g%q>nz{H6Zr<^5Mk7kReDhX& zPEqu7ez+6Fg-2GH`8X$@d`Y=P3C#-cUQchg+B}a>$zz@BBpOiyS2K6t#j6ljqq-ED zu{cw2dgi`>(5Pp-1YoQ9se^}}vXG@=BqW`(?}@w$a+9%GlAws;-i-|SubSs^4>z=CpJ;WJvW55HnXJX@n-W~j3i-X`wMvei;9T;|a`P09amhUo>D^sG z;A&RLs~WFDcpm&YV~XML@zou@146UpJp@sHQ=#dH_o_;_8}+FnQ36*p%c~l%LfFZ3 z&kFO`_x=*t=E%V{xbbP@pNpKe~=U|JgTp_P^yz1rT96zipRyD9PQT0?)=Yf5ecgRiJ&a-`Q zF73`f(SgN!J_d2+@}{O9&R2`C`8m>`s|2oQ?tI0o8=i5t<(uw1`^ERqY-1j({e#WF zYPz}nv|;wFIy)@yMIYKf$R3BY=t7)DN0*omVq6cL8FuxHCr^7Uc>d7mvpTp&eS&M$ zAD0aQv2f8)^B&IazjS@fXhaFQ!h!f@?|;|9t}O=!gl5SV6@*-C^(t(Ykn1jpj{bUH zWAt+Yp;?trn`j%9n_^!3cNvJfQB6~&R61_kW~zCxL^)fx%Q!Qv!$jNp<_qi%FN`)+I!$A&kZ45HC3O-xCAcH5kQJ~4?Xap>|#?CGaZHoKo+1!CeqH!ZzPRsha}%nsZGW6=G@=Ba*WGhFpWiX7u~;ut z7F{o!E6oZB%{qADME9-z{VLoO=M?;Tm+1+j)PlK2BT7tv5W9X|GR5pF^B#zi=k+j$ z(X-uQaDG5&7FG+~ssXRkSOfUx%jiHp?93jRLWgl2`Wy!Ws_8}Xj{xm_i5 z@to=Isd=}7=S=ILGYdc6(Z~He-J~&I$7efRM-|?{s<o^T*_y+&y)JM=mJrJinE@ zr(QL-S|RRW-2E=^LNH;qd8?@RTwFhXyMgyMMS=fbr6eo-V@cpIz!IE8+d1Q zG@=CVo-EfKcprhz%++0^PNUQDOO3k)gl4_j=mb0J*;%H-%5y<{`sRpe7kW|$4H{%L z3-=(F_aeO82#K|`Cqxr!rQ;_a$u}BNLZ0F9_qb+b|ETE&>3I291p%R1Sg}a_iUoeF zgZ7m0s%#&5OZ z)`8LYxN>%$Z%q&pLY@;roIC#7XeiDMSDDoTp;^aoz94xJPj_ug>;+LHNkx5d_POfK z6-FaU$P*-p`~CA^)dqzD5oYDg^Q#mfWG%zs#_woE30biKaedMM)-t|&EeQzCI=g$9 z+ybm+RQq5(h$rX1kU0Y@6Gz@&Wi+A$?k*z#>TN1hZFmof@_8vu51+)+|Q?ClPG{=I018GFkf5QBG)viarl_qeK=`L^zH zsq$U&P3dMYSzM2de&q1^=F~v^Ddv&PJy}GV$mB8JF;kTCe6j&*04RZ&-)xVuXLbLSK zlaq5or3v;3R=kdz)hGB|Dbc&(LUY-oJX88UzVZ#tM%o15+Pa15fY2=cjOFCCYkgvd zSLYAkKF|nP<&<9ww_N?@)tOi6UDr2s|E~N4?~rSbIo*!jh<#XYzBIyB*;Vg(mBv*$ z#T74JK`Z6eO-1o+V>;9Z(dNxM_9N`jbbN(Ikw%n|N&|@edX4RK%hK`TkLv`4X5q@8 z@@p9&T94^s>)>gk>NVFy8c~9)^nN7-#DGT@*ndt;$ITvlFR6E6y5Sx2tR01lO7~gKC-H&hWyX|`?nl-Y*AycV5`nuLU7=^?&pRBScfjF+j zC5c9q;F_y{O2si656Rd{_^pNv+MQ8Cvj&(Y?ze))IyWb0_L+tDd3--^c=xu9MwH;X zKF@al_4QrQYpJb?^~BSf-kqz2X34RWoSZ9OwRS0vvHP~&xf)S|EAu>G@ty)6hx(eq{p0M;{Kg zm*c*D`;q~Pd|rb}+^aVoac8)z_x=i^^t$Objr;arCJah6qP06#0{q$ui0hUwvwQJ3 zuXW|K0ijvpZ}rr(b?u*pSckJUg8HEThWlQuo9a||wi*6(ZT#Jn1C8vQrRn&c^I9Yt zQKI`3l~a87*;}hQh@z{i+Pks0;XQXX4G7JWa}0=jU;MO!=c{DcgcYbgy7Lulkyy)c z=P1@9zy0na_wS7(SrfjXc}>fwiDJW7CR~~KYZh*0-d7jhsyWXkSZ4syv|&Tbr-^bC zcO+a-&qlbGpCzzL;m##k*8uUx=*aSEV#BUa5{)Q<3TDbzFhP`iw1e&ObUJ?eiQ-%% zIr_6StKe`>>ax4?P5*PbGeyn)PuMRz!Ki9{8mpm4f7Y7s|1o@;n107-6B2)y9Alq5 z9lJWNYiKp1gj^qSjAf@jXMZ{^9nYK4EFd%st2@T8?tsWIGTGjV&(+pWovcQbz?I+K z0q`1+8vVlQ_A)$8EUI)r>%d1NO5lFPeb0Fxfgbwnr`Zgywe@%2ZZ)EWT%AD-`QKz) zfTxLysfPkWvpO|cXm-4oXUcXP1EN}uadr;Q?W31=w;EAGuFfEq;aY2Ptu0fS4hYSX zYb^-5Pt#WT#9JNAHBSG|lq_x5yL zchF<@%2s2|>{n)*O~Z<$c9)uH?szEQJk+&BiZvp?UXp@&KliI-8J;Fi{Uq0FMEWvP ztV!{i0Tm|@)!K|o`txa`_%De@l#mVx5M$3Rn(%32{za_Lx&~rZ4;oi5l4ek>sR$dmI+m+bA5_Nj?vs|$KFs=s02F$ikoS%-5TQVac zG)vFgaP{#$UlU;$+9K0~Ym^dimN+HFcfIqC=i~43aJi>!gD2AQs|SY%gl6e^J}2jc zDmUAWu?k#(wKMy=>I1{#7^kr24fgbMv-?H~*ypC6w^|k#T z!j8R{uSqnb#6NixOd1uUQWtLraq_PF?8Pv0ulsFkKxo$Ca~^TWc<=WfAcpUqVbA;t z6_XR2TRn4P)!Fz}XMJYCEAMpSJlhISMKSJ*^&F){uVHVQH4`SAK~MGpQEg|wU4S)! zlDk4ev-C`aHRN)0Y{jkEnPLcb=aRl2B^o`k#5~$#lG*<2%{WHm=V#e|I8)bsEe;6H z(#|2Qmo)k_*|8-ZPyT&ua2?d^u3k}bPF&bCseC9M7g_mFMk7juSLYjFTb*EHVLY($ z)xp(Svuad7+g-KqZNoiln!R+H>k(eDA<1Y&iS1n)xI2I!BVIqI{rXPQ3&(i4LES_N z&H7_PHFu1sj_(cP@y$)#F$!KEmC=Y2@>B$3_oW+?4LHWG=A{!QG%LK5d8S>H1d|uz z<*RySG@^t&h2a=I7rd6V`w1Oe8`lSfX6bzw_Gs+!QL+}#IPV{~z&+dW83)fgmd`eP z#=(<|m2NuAnUfon4*0as>GZnx*#*P{*L@J>t($1>yZ0>+t>2iRoO%G3>Chzsp;@|W zglC+G3zDJOXJXi|iT3YVC3q*!J96A-;}~%=Fxi6dN6vAD0ijvC&V*?NGp8q`@E!c5 z-fE)}C3r66IT7bD9OJ38hb9TGYKwc@fY7XP{c6DEnaQ1~6`l9hV)XDGTiH@V*R}BO zzCScM?F4+I{&+bcGz+!Pi1+QReWJ7Gu0hF!7WkWAJCRk;qY)*-HL^Y>W+!v8gTUu? zZZkReJQMLOTC{mDyJTJB{@pg|W>0!xSClC+)+~E|7+(29@w#L!&eRW&=w&pb1kb%Z z2jk2NViTT#x8qD*;@`r*$rm>NB8_JclkoW7nJ7=8`_g6LYl2dYM6C<12 zE`Rrn&)7cMXhaFrQ{5Gg^;O)r=eDy2xFh?z#`J*DEV(-avE}+d8Cv50N?Y$D`y0RX30Gxh`N2++G}tfEPc}KV9inqUjKL<#FY+&`RHof zaW|@#eG39Yv$W?Ha{(sgC(T=><1eos6RcD7K8N=^xT6WytTD-~)9B;^e4_>p=xcPP zSqVM?^GO)@K=@p}esK+qLq|tS-YEg0S-Jv^SrD@;C6#u9_~B5b5hbuL=k`{|^##XB zpYm{qSDcl7ngoPqm3n8K;kw_Zx|e~ts_Ll;=0V24obrC85hYfvea0PQ^{ZT=UmNFT zj{J%J+xO%Kgl65+ZK6BI%VQdVc;U{=lVvzY-Ky&%jVOU019uGe9N?+QB$>Z(jQvyU z2ZUzncOHhq&PS6o@Lts&^L3;VCG;B%cgZeG)-6uQx1L_dXhaEg>>1zVhu`Ys#_uP^ zum*5pl{g?Y3*F1oGr#S@!73Y&pd!#56e9@-aHytv#8Cx6-ZXz<=zgT-AmTx z+xB=?`}zFlxXV7;%^eV^g1faWRA}g)xpwxhC~`sLY^Q& zy!iGqYq=ua?Ad_OEOspW9xo7QR9R`i!ZT;*-P0nCDDn39f0%_>7rk}fuOL?KSZ&u} zUG$14`UQk$g{!rdTduJNYp>_LHZjtO68m?5<*pxVn$nMYZu3fe3RXWJv^@esvvh44 z`@_}5dOM!BPaHTQSVLB#UY*Tm+v$0x&EO3<#!tD+Y;U|*3-ZPXgl0)~0K}p(iQR^4 z)IGbFX+qXYNb4%-U2rRf>_5=IKWvUy``e|Dpx3$G$VekfphF?$yC(7dxbV`cw)5rbc+86F z0ijv?_s2TJ$xG~>AF;>plS?CwC_#gO&(San@H$dkt*wR6)u?960z$L&?~kX{^FL0W z!S&t+U0G&ou11uQr!WxmbQjdTG)tcPK*$qhu11uQ zr%4dLY{RR1#^ zH?LKYpW*MwE~qaS*NEJ{bLoJF?C5EAkt4l+di6HO?z6ir$Zl$6g8I zzJ1R`&;5?7%=NQ#H4CdB?ssRUIwS@kDsH;t?{V*vGLc4G0JUgW2(2Za6m}G>fY@zOIU6w7kcf0^EzX>M=Ibh!SB3_N>2`nY;1K zIsd|!0z$KjRD0c4kKvf~*o ze51;4jx?gg>+#L*c*`F67snW~ZlL+7T{@mLu$WOov$z)H{ZSlaICk64N4NUkQeBO9 zT5AWkx}7;WCHKrWALCQ<&i+oW1BiE!v_6&Kv%g;p$1x5Km}XAHI^5opT?0b1v>O|H zH2yiuOu_wCqb}`@MwH;Qzh4W-F;2arz+8b(;=5$qb?H}eYa z;l`FO>Q;iX5hc`|#U1k3oy}BKUzaqW?RuYljm~Q4vUUPvXT1AwFcm>;zv%g(<5vkj z2l8Bk=QsRT2bR_~eNkOH^u?%v&@Am}#`WXV^UQiwmp0COHt1Ydg3p0GC*t`HPuuAS zikPN2ix&Un&VbM??X$)=>d=Jf$G)(HK7PzRyRTKk@8F4R9<`m;Z%yWR8gFJ`hk;ji zqxP!?if*W z2ad69mm8i&1{o++mE}{Q)wD*{I+`RL~y|sFtAXZj-DQbdm?d^|apKj^dRf11k{MO=0 z3B;{UXGOE{jp{oWeXl}jmUiZ%-{-{_qZ0Vm&KPZtMwH;w5Wlr}?!htg57}r3o{Bnl zToMqP#it>jukdsPqF;$}5i3|X_B<)*3)en$-ofxrhIb)&x_e=2E-P47Dh!A;qD0uO z{>e=zMDOBm>7gq=2nfw;aLpa=7{9cufnywOHZb=C+%5g@v1XA*lvvwvqU9ag%C=l1 zn;ut-?!YlVS^r)@Xx8sPPIAY%{c-l5fB*Aq?ii_@#*s#p5R( zWcqnCSijn}ILgI3oW)MD^4SdtRGJcB!2;3i_*v0#d_Q)*k_1GMb?kcsV))xHMi=5c zSoayYHWE<+m8Qg3ut1#Fd}36mBBpJ&pC1sKrOr6+mda0y>eNFY!2Qz$n_LO3S-bNt z>-PB8*6J7CiHdu%%)o%qEZ*n(&TJ67ai7ck-7_9}%4$RjtXVrFhW!A+Sya!+dbVQ? zDSO_<`7mu$abu6=pRBlhkZtSGEz<=b8LS>qO`3Bsapi5R_2W#pk0ycWcG4%&`B;;=Y;$DQ?#3#x z^GevoCD%c`@`AsMnKyAg?|19HRwGKFLgUWh>_y1Q>C?8lxeseH4L=$Z5Sk^|a}Z@V zH8BUUCiC*IGp$CHph?Fo13MPbzkA0G=5*Wvtg8EbKxo#z1!;R?gDGZ9srNwK+Iwj9 zz~|^_oU$)b$6cLzIb-0J4{!T#F4tuK8q_n}BpOkIPs6-^ur~lznKvuB z^KSod4h4i}h2O!Qx0iM2-G`q$!D>VaJ~Q*Yi)URNgHOPG62=p8KxmeJ|1qzq?O=0j zvvhp%J7)$SJ@4@R%K!h{4`6T6yGdp<~r5f}MI&+epf>>vG?>Tb< z*21Sh)yrx`iSQV=9++fW;_0qz(VhXJS?C#b<|I1>F_-M*>82zc-qvT{Lc8KQF19+{=LVeZ`jv;FUAZ8vJjF}s__jx%92+iVs zF7J17-wWc(ZA(mqJN^7_^Ap;Ie(m1f;rlgqb>Bg3*|N&qiMx#NhRs#OKH@V$mf#&e z@APqJ4q|U-YnI_ors2G?0ijv4+5%$fx7O6boqomqxxtlG;6pB4_t;$8?rX9_wO>|1x zB^AL7Z93-)fQLPXB8ejsmTI-NT#9E~W!>pQRWxZZ=14mvA6a7H@lv`-Gi>s`^obH25JY#oJjuHSU93BX1cYYs zO5;~pKs0GEG@+YOwzsvqQ(Q(*}XiyF~X)u-ltv=^m7r z+EaB{l5;#J*x&q0@XB?6K;1D9?^UmnNpfX6u3vXzu$P_^(k+Jfs?}8mN!zQ@N49!g zKxh_sG~#uhHFcO_nK8)=c!I3mt-sZX66ghRT}Z6-qxa+ZDVY*j#o72s<3!I(dcKnW zG7y!zoR)0DO3~M!ZwU4sR07W>?!1eu5QxnemQBvWy3a>d4+n&1>2HXMw+C-a)-Q&e zQ9KHELsSB$sq4RDzXNsx>+w}aqD1?5HaNOrpI1Tr zHn(`hV|-nGTSkADW-X|A&>dr1w>cm#?Q>Do5XYE%QjtU>N^HM;mpjI?;*&tM7+KaG zV^Gm$86`Ap;CDp~U*GsUxSQ@nTZg+>p1%F;j zjVQ7E@i*Kt`uFB8%_|Rz6(TEbW2cGO+`L%Zz0Wp8=)$ZMGw6tnK zXqJ9@up(S}^nb@_e|_+|Qld=#Yuz!@&-{sZckM}YbL-=k?_Aw7AT&!qW9a>O?dc5P z-640Kn>=y;QwiV2!CQ;jGNW20e1EF9J)HDCyB1&9Z zvyP)XoWxK2rV%aOF^bQx8W5Uw@QGhCJoc^su&RIVn$8*i1^11v;FkngO9%&C9fL$LKJo9Eb-l-M@mzC^NA`q7fxtF4@E#-B=$8ef|fCx8@vnf5Dnp)Jrs?#QN5w z-7(tb@we*J>J@j4-Itvf5Spc*(43s9%inj$sJAu_KD$cPAKc9yqg0uLIL4t`uV;An znK!pZKxmeJj$ue&S2^M5DlXeMvnF$rg{0knb`C>*RN=&%>kfYE4ts{tU(`UM4?ASLhAT+DRy??uR_sjVcK(y=CB;jZG ztBc;tXhey7)_&`b(fx^`AWm6O)*YkI3rhn+vqtax&K)B?p8L>`I<3At#@MS4Wi+D1 z8@sl+V>CRG*V;Afio0W!+OjnuG)q6BIXMmMS8>Pq;MX#VMwIyI&}w&#!Ph4^Mu&c9 zx_9@iHKzxJX6fe`Hu<1h?zg(J`2SWM`Kp}zOU-+tR3`fIc+2ly?{ji8XKp^l{r}H% zKg6DZW#8`LeyiH+zg(daB|4NW?&!W(tpqV^&;{-o&puH)_*t5zpC0rx?7Pt&j^hkQSRh!XN$ z0nz{WzukHF@RV717=hV2=YwNEGh&2@=o|v+W|_PR+NxWI1sDaEC_4t@X>CDFkM@}0f4yTvx0EX zd!5rf(dU&C@<|OM_nqN_CWjb8yYx8*L;8~g=kb&C@=Vi2z7@H)AI@sY_uZTRs_f)@ zm&4J)Rc%W74tMIU=OtQELcTeH7T?pUC?Vef zL7dyYZrHmQ|EHlLv`fArgIK)RwPB5QMW-iPQ9{1Sg1GL+Yr`6wZ>(zw?b2rtuGaJM znAdv`b$F_(ebI?(i%1wV%&5uMZ{Un?BZ9 zTj`eEZv#VUm%dgob$aVDnT#ASN#qxHBEQ@5c*yT_Q&B>GtAl9!`$u8#9({2|Lui*A ze*p1Fqn#2yf;-&XIMIp{as&ZH^Wh7^8b7?an<2DIpP@KUzt(5r5v6 zh8&YIgm&rk7{?i|Iw0Y5_u7*NX3`BiJN`Ck`{T*Ub=`hT_zt&Z)TxOaDZ(1ZZRi+| zc>P?XG@}(ICimSC=s!NW8N?~8Ylk)7tNpMcv`dasf!Keq!mxK|P5C&Z6(!_Y7Kqh9 z?-JJ7JbsBGv`e2ocrUrGNmyg|DwPwhC?QAKu!bD#GlX{Oa}4Io^dzjYXTf_}x!qLm zM=JX;HG4O!6(wX(gXp>S5j2E$$s-Hm#)c<_<5%~unUvLv5;d>-D?EZHADw{cu-74B z@80+O1%}YBqAI(GXV0Q`RYBam`m}J*H%`7Os}&`_>9&L8b8NrA|HAjgFK;_EtZ~vY zyBR{e{QlL$8XF3SfcRwMIbn_Yb@s?=MTvvkR1Ryru(Sk3?Y>RI8b5Woxl{@5s^6eS zSfl*=?(P?z7uJ|p)Sy%=O5mtRSfiZSctF#z#vN6rv{gd8WbF*D0a3ktjbA$4T&NW# zWIYhYXEY9LY#g)95ZWbsJ;BlQ(zC<;`1-9wGFnkW_8ZpdRkuM{W8I-G4WV7~?7Of-ac$+Hr~1Et5LZIMm1+|Lxe>Du2?-j9AS)Jn9Xgk13m#9Mo3!Ww0#_tCv;jAea~ z!7=1j--k6$nbk?(^$lTNv4T=*Q+&|%mT;yKKv-G@#*>f6M1hp#OPB_ z3y;U`r|jzSEn``Ou*S)gSLu6us$KF9j(dK`iz~w#qj#F5@6?89Q(P3*xbUY#u*T85 z?i1GNJLY%&mXT_ge9OQZGfJ~zjm;%<^*e(hnhb#HfoJ8er?$l!vl{Lk))Uvw+ zCEq2mMx#Augf(VeyHvk3q)L2yMfI@8ifSigjqbC)&+_$gLb|^pv`fBafGDXsG^|lF zWQ~4j@JdJ?4PxF?uY@(~mNhnncFA{Y5NkVh3u|;9`L%vS)|}g1jRx-w>nDXZE;+xY zAtb5x^354*OlsaJtkLS!pY zhU}I2>x`P=DmOKH+={Kb`@Sk+jd^c&Fobr=cWMx||L73b=gJ82y#%wM%}Bf|$H|bcSop{HVZbMG3WT@GbnT-7{Qc^IaYESE|=8`7MeyntWI} z;TpFN`9ptm8bUoCB<|;38P@3kbz%tZl3%G<u*TbeFVG`*sS>S@ zJSwcQ_J_l;#y;JvCVb4honFll+9gNZu*N$#EedOtZhlOU+@(r1oN`=PtFQ9U8-Gjd=6_gIQiYMM$z3P6RjvAXN7|3_iV$k#;WJv&?9$x?r2`dQnvpW zVU5f8xGs@ndWMj5N3lkYA6kSp+^9$N$enRU<%l?=zVm!A3I*P zL35mpcFAK7;^k}p3Xey@${#diNtBSs21Mz7MPZF|-#^n3+9l6W5RFFs6xR5p;*t8S zR+HJB#fc$6uAoYtY=TyaquW_-fOz##47J z(0nk_E_p8jF<|!Uutu{RMxc=ieG9zm}r;0Ct{5$do2!Yyt4bF zsaBMb_b#k)MwdOq8odswYzWh}_5B!Yyg&Epu*O@bn4COOLf(V1#++LV!WtvG*G}cV zJ<%@tjKUhbygN3map~GOQ>`c=pCwph@rX6y^P~B|dWO(0`K$%;`^-DT8i)7%G}Vd{ z@|g(Ypnd0rHHLIK+z{F&-x)xhSpC?r#>llBQmrT<-v&UetUD;IamaIR4WV7~4F|-E zxx0ilx_$Dyp2?vGuo}l8?(5wutkJn=J448KAN{5VV&IDphVNG=JyYQ2+nu>x`K|@x z!ZYWF?{HuD>8R&^IPH>eoFFFjA0ECZetU35uN5WaTPBD}uXTBWpXZ&H9g`}dU3xSc z?}$b+4WV7~n-j0|sy`17Yi#^@ZK@R|L!x|s&usqd@67m}tYs`7MLdwTuRL5F|&@MR!fHhwG zV_sOJ=;Y`0%*;dy`E`#qs@+vRtWo#F9Sxyfa>N2_v~erK8h2EhtVcN#CFCdt)_DKO zx?znjZPx3VnTdAEF&V6J+qe(I8twZJ&|}4hkYh3+&Y#jOtTFF4uSbLv?UEx%AdYzR zyRgP}9nMO%qJ$h<0`bMf)?tk%HAm?YVZDM~BFD%;beQ{VSYvemI;mFlcI8+Wh;fyQ z!y0u8Psu8wU2?1s->;6txq5sJe$m3~5#fvya!d}ys`*EUHRi1Pq*QN9yYx6Cjwf!a z5Z1Wi>PlIyD51v|F*p2~+kA3mN%4@|zvh)&a#t=-dES5Y{JiYxw4mUS-3I!W@IU&l z-N|W13B5jKLBXz@yZgg#$LyN#$QoFFms)LR&gm%d*7{o3O zE(~kj+V29V6(wYH0fHV$iSdGc68XqUVbf!OD+_F;`C2lRAWQ9|qy5D&eyXISIV z8_zR@cF8*`h!+|k64vNbZ-CQ^5@L^lcCNIny>Rejq&neKQpEV>ghMPut{pI5?O zVSKN-H>P}Etr^?f5ZWc5)L3K4hU-#3uU>0C&S^yn@jpOpsr_S?YgDV)&k))r-#9>Y zyf@8qjZ5ZE(C;GZf_R;;hu=82)@;i)ZuzXAA+$@rIbn@cR-cpM8dp`AsNcfO?doJf z97#Rp&kWbNb39-nZHH})T|-wnMIa>WV|cVx#W&vq;+K4|3_Lui*? z@doEvE?<(IT(P8hpU-AFttery!%}l`C3o(5xT1C1*Xea?bTX}c>&I3-*=#R&E}mBp zcJA-AqJ&(x0mS$7sypthV_!Sh5ZWcbUO;?(U0cU}b=>i{JFO_8Q)=-UbxxD8M*Z)O zF@$!>uQ05!!`idM8e7J6cUnGr2oE_F!TW@beXqWsd#%I*j$NGgeZv3;c(~1&etYeMC1`Kkq;Qi|U^Y=D{cG;_o z9d|gUNyAv*V@>OD4fx!3$CR*FWugP%@+>g$EMz~K;!ra$G z=IQYZPJjy*KHj%dy^b3`ah|**?5oC~4l;yx$&@MR|mBqQ|Crk)yjIX~#q7@}{o;a-Ecl(7kzI=Lpp%U69|Bi1|1eh&(Cb0SD-Bz9!<%=xees?+{jBO~#o?Y; zyD;pl1<9_4&@Oq$0CD-*eZsz4@zoJtD@w>~9>mjMpBUD7w?}v@+Uv`ap(uvOWaEy6wTTBDD-PLUFNpKuj(T*LG_T+QnBV<#9wyY#9`_^ibo_ldY_ z_WOks&GnX)$X37Kzp&?ccfubpV5?dm*TY?jIqo}evR7!*F3fBQ*O|a|8$sOj`Sq?L zrm|nN-&C&^B`_b($N9A&>aM-i^#jrN@fn8DE_x^y*N^ifYz!b#b-Ozt8V#t^%b5rj>*#=bScJP%yLc=A_AZcwYCkGlX_whDw;E z&KZa>c%Cauj>Ko}W8d^O&vt%d#@`0!h$pU7^v?XG`Qx44fXOxM<5eIS;; zJ}CTF8{1{9{!-MbO*$nC#N&;hPUqsYw#v@9_O#rV{JINQx7m8lfn7dWnSPC{-1OLa zj@PRZC}Cawcbj~lo{Q)1q0jX)*G|xDGRUuRY*lHGYJMZWCoU|!ThChwS82*!#X){Y zgQzm4lIOnqYrjhjpIa#z|p~ z4kh&rpF8y9-5C?Ut0K$Oh7Fsw1N{Vs;kE;-tU?^hcp4)jOk@mR2^ zjvk>)l;E`hcUIf!saBMbc@tQpb^Si!p6`Cu*@nTPM4JuZ6epA*6wADz&{oQjp+>b7o zUagN*s)Xz}5U;iy;mbO~ul;3)A+$?p%)r&ZZ>HaKcYM}vUYTe`3H-_k&qN++!MDB% z4`o;Xjky5#cgkG%M}s0>`!5~2(%*7eo$&XSfBonOjNPwj*T<&26?ZT7IP1RYpmg*m zeB$iw60Imvd);nDyn51k3s-{p?6R-YFIJZn@B8^=Lul9P->L`VyPsYHvARKDKLFok zZmZkgyHD2)oh#s}C_U+FtDXzb%iPMS_i%%*jdiJ*|?$B!UKum1g z!yk2NN%4Nq)iZ>4oqgdBMeVy!bpzLyk{I9B|BBD3-v=J#w5#6nI}{z=b*ihstkhfL z@FwT_+Dcv?`hA zmj6cL&1G%;hRP)qeh_!%B*u zf3l-_eax-$z58I?WcSTubG*LNa7N1YclqXr;@E4~>!bl+xhvdcx9MyWudW~HyVSw6WW;GsD@y!%)2HtEvIkv*`=16e zv-M#AeocI;y?&-4OxNa5-E&JGbX}e&aZ=?Wey3_B#mDr*G+U`C@xb>Vx^Xu==#Cry z6xaA{h~Il>OhkD9d_!p0kC(1A!pvi;o zph-`H_+jjpyLjEBU7c2xIQH_j?v45n zx@!iJIO6tU{?$Kw7hl)4n<2Do|F>7W=iZs*y5IH$h{r|^_cd`e>aHFCn8F$p_CkCj*GBp}Vzhr7zv$h9fo7|eIQxsI-155P-Q@eGVvUcl9_=p#@zDN*453}! z4}QuG-F>`k*qOw}Hluwhj!axVeUQ_N5<@?J!d2ch&Mo_W3Wzm3jP~t8w5c`N5Zd+j z`Lo=H*T%UjgGe0z`Y8Y2g5Jfa-#OT6MTr;JJnl|>ah%)Sox}rojq+EKsBn)Vw5#K& zN8Ob}$GI5m~!D@xq_%0q76zT@0ZXOX~+hp@(yMnesuU3GSR$gS9UoO`$q zi65T0&yT_ytIr(jw4%hYMbllS9mlx|RY=UZ@jgEd#Gt{J(5_RbOmoM6HP+Rf!-<8j zA9QTSB{@UOm}e_Q+Vb;nRsAzCUqi z-neY6TV9jIikicHA&57VVNNSb)PH)St9J2NH{;g{Adc8^xIYm@a;zn^Yp)k3x%M=J#G4C-`QadnuCj!7HLE<)J<(~b+wT<;>C9pN zQ4qs#9p<#6M4KljxQC7#>+oL?-S!>hyDjcrT>I7mPCxs0?e)Ctw`#n*YteLXKL6 zh>gdL@mX90yXWEkomP}+R>ivkohP_O-ALSd^cerga$Gh0fqsV2uC=?DxwY3$a5q0g z;;6zgzSC>Hi~sziuhWVWFRq;L-WWT@jt zay*HC*ty5?vm6(S7~i1h-R# znIJCucC>%)&ECZg&MGm4cAZjpkt_Ing8Q>4i6tvW`vX>Cdc+aEomQ0i?V^|6k~$Ol zsRyFx6Qlh|%(ZN~^PPs!u8Lp3?0Pqx=qmp~;;HeY{l&;wcD?Klrxhjk{q|+|0El+K zkr;mSXg>#2Fdn`1c0*{_?@gDueJ+^jo}7*uAq6L%KiV(Eby8Q4zRhVxiAfEXxQn_> zbf--wQQ@~y{@XS9x8coBD@y$K>}zhw znu%^I=EdTe%&3um{`%gNM->%Ly#+TK6SUHD?Pvc}&pbj=q| zb61z_UiR{gg|6pw)7%@o?_P$P_ZP2BAHnazjeqRpw4wx#lZ5M};`btmT2FT~cdiBEfP=H?1FzyJPG8J$lZp~gv|JO`m_MK@h##8Vn!OlD zicVScVg^Tr9FG*?m`@pw7KOiY^r-AV6PCEWADHeA-Em(KKleT|U5+C~Etd~Yw4&?j zE#c}(58Rkm_y*IOm(NVJqJ-V5rRm?N-_%EJUzgONf<^34`%ASVME^L2T16vJZ?%h++$}E z&@Mghhwmi^ewltbtEBjcYZ{x^hd%Qse=*;cUOvrTT4`78-J6culpgjl=G}dExYLRf zuPrEZb8y^e=e_vct?}!Y^xlcMVy|y&2<@8la+zz>e42Z)28l;MtmywUwxoFMWzK0u zi9H`Ga}P9|=AK-?Gl;#e-q~*+R#LqB>|+d}U5Bj6x~*E1mf-#!bt*9Y;)co3eZ+)?Bx@Z+Z*X_@c8Rw5#swQg>{(scy;HJAf$ZyPv=Odb~5# zyufKiiH&tjU9-Zeu609B$Xna(Am8MwlHz)|cQu4|HGX@Z>(OwkJ8@hE5Ig@^&o9Ef zyV-+#IISpg&eRv&4j)Z%_3HDvyJc=eUvx1hVGg_85ZYDr<_m7@*Hc_}9*HwnHSzz& zk<{J){;$)D5?xk4?|yuIircaMpCDE=ZSL2cQBwS6zw4Y)t*PYrORnhyzY<>%T+tGxV|B+*ga|x_8!3b`##+=$~2o zth=KTjx=}L>~-yef@i0l?d#RR)mu*;?1n%7lv~~PLHBs4k9?y=bKKKYCc6tR{@(Y+ zafbKKe9$$#dmYx8anH$qVO8*Avrcx`p3Oa1F{9f%tp$9X`dk zrQbG;a#~Sh{EstT$NCf9bE{tlapvK7`3CrAdB!dy4WV83x54)nW|cCP*?XDK^e$@= zKE1l#TwHcwjpq`6?jCo-(Pg`Qv%h01^Xu=N^ta-ctFlaGo~SoH(TWn?hObSS%FO6> z7>Lp@S7w>Yd{k{0r-XJ@xxZ@ojJmaDGZ4F-(f&Abx5G%L%E>vR-4I zR+QMYYgxin=D4f&0deT6HYrn?PQQ#YgmxWp-I9c<%=uY6aKnyZri12~(NMmyu}s-ofeQNjRf% z@&!&SN>ptBd%{%a+g&+3^NV}-N}0+$Qtfy{XqSDq7ra_6Wh&Ea-&Rg5N*uc1&W@?f z)V@uzM&+Wy)X?t(B*l*T;fdGZLmUJ3m>YOkZg*+-_-= zGL>1?`yulhRHDm{4<<}yzT1<(4KAP1GG!_=Z>NV1pv+ui4 zI;|*i(i?*krZQ_?H4q1PZkjTcS$)#ehS09B77s|6%Dg^^-xD{CYm_pT>3qR#d^&Hf zD6vDQehE{Vb6@25_HR!-G-WFDMEg00(5?f|>X$H;Sv{Y`-q$xwnabS1Y>v~45)&5m zO_<7jHI>Aqx%E?~GKVakYY6RHU)(ccD)aH*{AT&#__`@mnS%G8b6Qbi)o$GrrZT_( zuoH;UcRZM7D)Zs!C9cc)volO(s@}Z8pF3kohN;Z-Et`DnNiSxY%1kj(WnaZ5-iY2D@n4MuNv#QqyuWREw+~yHkrZQJn zU23*UiK>T9%P^JMW$O1>ZMLA zN?iBzeHo@Q9hQ6xV&#RmWSPpiv6j%T&Wi?Qn997}?HdqxPPih=ROS-D)M-VDH_Q5F zn9B6};cE~-7I)4vl{s>~CA90VO&4XD%Cvotzt!Hl>*y>~nfEF!b6Qd2mj^p!n96+W zz5vnWfg`g_W%fA8654g~%;PgmWv(1eVy{ygW|_+D+H9HAiV}xi&?3WBW_+j5LELaq z-7Hg?!&@wK+EsK}iwsklJ5K-HTjJL}_s%kvd8zd>rxhi7H$OPTRHk;1^;qNl<$GqC z${bs03GMn}kNq-CWtLSXar9$VvP@+vx@Ar)N<9C|o*AYxPu=<%i2h>>!Wtd(2<@8u za-|GYnO|T26vRG9ZYpIevm{yOw4%h9^DAVS${aV8#Q4kBm4;NNttGVUwx8A&GL>o2 z_Y)BH&R$x|RA%Ur%bZq}xM<3Yg-m5`p7Sw?+h2dCl&Q>+CYI2yVHeIWWGZt;LSlH$ zDWyzhu0Ld%(~1&<4xd)YRHoW1AA#u9Vpu6tnSy;Rpa#4#yrZO{UlX!c}UZqTBI)9G$5~(Oru&_cQQ<)VNNHlt>QYllJ*FLa>c73xv{i*1?8j2-d;h-zoOIFG5!xyvn~T}v;T-Il4$ z%Bx9yKX2?jrZR;KmO8B{an!=TZJEk+t3_hr>37d#DpN0O3GHh7%7C^^WybACqSK%* z^O(vUK6k0piV~kr?a-E~%yI9p1##8a9p*8Wne?AsxAL$&sq$5iHy z$Cf&+DA8$Qg|$BC|Qe zROY?vzhaG%Lte@PgrZVYMByPHELzbz`bE94|gm&G~?BIl{Ov%s!d|TRe>gFs{nc925 z&PJOWu^cGZ-r%!W(nJFO_u?BU}RrZVlnA+h<& z>M2v1L4T%(&@TJ!)h(`_GL>0;Pu6Kgi5E6qlrWXqsVBeh?y|@JDN`9&W1b5YLDzn=Shn5{RX$Q|#=DI44%htbA(KD6#c5)-EG3w~u5~ea| z9@)xiMG5>)^gO~+e!S%MrIiwX9cKLc5;%`r5Fy&!RJIaW zFC2#}zaLeGpI*vT#vdB)$3KL2=}|nK<5l5+EK`}MhrZ9f8wef|R08`gtWo|fIqa9K zvrJ{a`SD#tXqO)M!@0Ff_eq$_Y#x20d41?Jzuk$yrA%cOu4#aM)%Df=6Q(jBJa>lE ziV`y>Z%moW{2Y$^eB0%agsIF~?_6jI?P_1LF=Z;#H4vMJ)=!wqjJ&m*(~1($zqcV} zD)af5JbtzQhDHffnUkLTuOYOn<~1LrOl8jMe-McN)0!nrWtL33#c4%};`(b-rZUAX zNc1|nMZ#2O@Fo2WpQvENgz5~ea=-8#f+MTu57ypl4N`Q~;W7yb3h)(KOY zG5zl~gmyI9 ziDvuwl&Q=I2l4ps+C$nVOl59r_JAR@>)HjgQ>HQ>y<8i_&u_O$n94j=Z@k<1{H&Cz z%t2SxDtl%;C7Q>HSrp5$@3 zp&eT%Ol2-T^+BfaZ7$}p8V|Eq;gD@yd+uTjcWrsG-sM)vr^ zi5aFc!~7yc*e?BTKu3nD44jz^9T~ps^Q;FtGW?roL(q|7Duc7{u?8I(rZRA560Imf zM~0szNX0?WkzpzWXT}iPMMs82`MDo-WSGjpnF)>zQyHAe@9D@em4VOV>BumZff?fq z3h2l%m4P!8?3r9e2|6-NWnjjDpd-Un2F^^dXL1!K=*TdYf!hLtjto;7I5UROE;=$y zWnjjDpd-Un2F^^dXL1!K=*TdYf#-sKMMs9I44fH5XcrwBrZVtcK+ut4Dg$RG_%^xQ zq9emp1_n%-CFsa7m4P!8e4E^DDM3eusSMl}tU*VHsSKPMLueNr8KyEYV?fZ6VJZV> zCfGB%iV}2Wn99Iy0YOKGsSKPMLueNr8KyEYV?fZ6VJZV>CfGB%iV}2Wn99Iy0YOKG zsSKPMLueNr8KyEYV?fZ6nT%8h&P=dpaup@$$S{?G+X8})3{x36GltME`)sEp!&C;& zjMIt|bYz&yz=pvZbYz&yz?n&u&@O##78KBtVJZV>#=Ji0$S{?G0pn?-kWQyDlj!Jf%g zl%ONSR0eJf2s$!MW#G&hLc8e5gjD8ynn-kHn99JJ3HD5`q68forZR9_NWhU{Dg$T6 z5ZVPVz%!MB83Tfj3{x36Gr^w8Rg|D3!&IjH{9QUSOl9EA7(%<~$S{?G8G|+G$S{?G zGZXBYTtx{wGE8OQxqzS}!&C;&OfYnEtJ9HTDgy(?TY`=ZQyDlj!MDlXmJ)Pin99Iy z!5VaAn99JJF@$!}kzpzWGX?}58KyFDW`aGFt0+N7hN%qP77%n~xCWdVLueNr8KyEY zV?fZ6VJZV>CfGB%iV}2Wn99Iy0YOKGsSKPMLueNr8KyEYV?fZ6VJZV>CfGB%iV}2W zn99Iy0YOKGsSKPMLueNr8KyEYV?fZ6VJZV>CfGB%iV}2Wn99I&0YOKGsSKPMLueNr z8KyGuTtLu~VJZV>CiphF+oB`GREE!VOVE*FDg$RG_%^xQQi6^QQyI7|Sc8rXQyDlj zhR`lLGE8M)#( zCfGB%iV}2Wn99Iy0YOKGsSKPMLueNr8KyEYV?fZ6VJZV>CfGB%iV}2Wn99Iy0YOKG zsSKPMLueNr8KyEYV?fZ6VJZV>CfGB%iV}2Wn99Iy0YOKGsSKPMLueNr8KyEYV?fZ6 zVJZV>CfGB%iV}2Wn99Iy0YOKGsSKPMLueNr8KyEYV?fZ6VJZV>CfGB%iV}2Wwz@KO zWSGjpnF&T|?$eTv3{x2xFy4L+(ve{*17{{!q`6N>CFsa7m4VxWt)e5tR0htBA+(E* z3{x4HF(By3FqMHb6YQB>MF~1GOl9D zMF~1GOl4rIfS@B2QkmwK&@MVMOl4rkfS@D8R0hsWuxD}=CFsa7m4O)pf{qMR88|b+ zp2<~|pd-Un25t)oIxl%ONSHOegrIx9?_9uDg!eH zYtWHlDg$Q*GtakHbUnQ#OoM_W!&C;&3{8uF)=@V?sxU zsSKPM8YBNyl%ONSdtUCC(2-#(182q%+C@i(Ym~b(bYz&yz?q@>@=rwxIx<|N+?Amt z!}|ee#t_=Y?dKZYYFwEDjto;7I5RYO{;4Rz?dKX?7gq#=Bg0e%&Ws_nOON6e6wr}j zDg$SRCelAg1eM^kgKKdA;ruH&GE8OQ%oswu^tc}!EI2YuW#G)1*M~my>BumZffbYz&yz?m_GcF~bxDg&zn1RWWsGH_;sBg0e%eu<|e!&C;&jJI1w zM~0~koSERrFqMJt;pxaQm4N}{>BumZff<7}=*TdYfin~AnOsE)`Z>9^F^>g~3{x36 zGltMEIxCfGB%iV}2Wn99J00YOKGsSKPMLui-%Z9qqcsSKQ%LZ0ow zcYU7yz(kyX^Na;LGE8M~_C401Bg0e%&P+xtO3;zvJ2g`A6vy=8$S{?GGh+zt;yE8A zc&-MH2*Z(KDg$RGp(Dd%#W<5cr6a>s20lwlM~2x8%owaeM~0~koS8%`O3;yE_5w2o z1RWWsGH_-Rttdf9hN%qP77%n~n99JJF@$!}kzw`%GX?}58KyFDW)iI^K}Uv33OpAO zbYz&yz?m_GcF~bxk^;{K1RWWsGH_-R?V=;YR0al2Y6&_rOl9EABwA5|jto;7xGh+N zjto;7I5UROE;=&IUSP(6pd-Un2F^^P6(#7%FqMJZ0)mbVQyDljhR`lLGR$6J#(EPwM`rRQoKy7P!HHIspd-Un z25t)oIx=_jto;7I5Wtfx4sUPpd-Un1~v>{A9Q4x%D|b)D4|{Y+AJub zBg0e%&Ww3|(2-#(0|O@2R~oVjI5JFS;LMoUpb~Usn99Iy!9AxV!&C;&j3Km(jtsLG zm@y#e$S{?GGm~gV2|6-NW#G1epd-Un2F{Ejw2O`mvlo~#An3?2m4P#pXhjJ+GE8OQ zwt%1`!&C;&j3Km(jtsLGm@y#e$S{?GGm~gV2|6-NW#G1epd-Un2F{Ejw2O`mvlo~# zAn3?2m4P#pXhjJ+GE8OQwt%1`!&C;&j3Km(jtsLGoZkn6jto;7I5UY>l%ONSU#~c~ z5Ck0=rZRA5GIV5^jKEvT(vjhDCY%MFr6a@a1!fGc7D`8ksSKQ%j8>GOBg11(I3pMY z9T}!FaApiaM~0~k44AC0T~I(rhN%pk8M9SN(2-#(1Gfch(2-#(182q%+C@i(*$d1V z5Oidi%D|b)XhjJ+GE8OQwt%1`!&C;&j3Km(jtsLGm@y#e$S{?GGn3JZ5_Dvk%D`;_ zK}UwE44fH5XcrwBW-l;fK+ut4Dg$RGqZK9S$S@aywE}{U3{x36GltMEIx@^&V8(!; zBg0e%&P+xtO3;yEk^;{K1RWWsGH_-x+C@i(sSFI5tR?8kFqMHblhKM2bYz&yz-_@A zbYz&Az?m_GcF~bx_5w2o1RWWsGH_-xT2X?I3{x4nEg;K(qQfiqL66(#7%FqMJZ z0)mbVQyDljhR`lLGR$6J#(rcf(N(2-#(1Gfch(2-#(182q%+C@i(*$d1V z5Oidi%D|Z^)QS>xWSGjph5?p8KyFDX4)vBU36ray}*olp`d_{3{x36Gi|h@1RWWsGB~c(0B5VikzpzWXC|Yc zeRO1)%D{lh+Rs5cGE8OQ%w)8p1RWWsGH_e)&Ok?osSKPMLueNr8D=jqWB8o`jto_?hN%pk8AE6n9T{dXFk?W_kzpzWXC|W+CFsa7m4T@Of{qMR z88|bB&@MVM%wAx|fS@D8R0hsWMk`9tkzw`%GX?}58KyFDW-?k)f{qMR8MrMV=*TdY zfiq(W?Fx_?hN%pk8AE6n9T{dXFk?W_kzpzW zXC|W+CFsa7m4Vv=f{qMR88|bE652&ahS>|u7!Y)1n99JJNwlH_9T}!Fa9cpokzpzW zXT}iPMMs9&3(Oc0bYz&yz?n(3q68forZR9_K+ut4Dg$T65ZYzGz0#3kDg$RG(TWmu zWSGjphQS)akwGd0XT}iPrQe+Kz6(c&sSKQ%l#UEj88|b+kzpzW112~!Ol5GkKi(ba z$S{?GGn3Mu$yI38CQExJSJCzKmSCU3kzpzWXC|u^CG1ww zkztzAXu<-sRoX?jgvYXIlwkTP92urEaAvYvQG#v>?>U_iq-1bpn99JJDOEzd=*Vyl zytmgcD4-+5R0hsWsaBMrBf~ZDy$AoJBg6ZFsQU#av`f~;Gm(xAQyDljg<4TU)&mh7 z8LRUuXqO)MgW(28hN%pk8T0zkXFeSn zrZO;N5*$f|Bg0e%&P=KmCFsa7m4Vv=f{qMR88|bB&@MVM%wAx|fS@D8R0hsWsud;Z z$S{?G+X8})3{x36GltMEIx@^&V8(!;Bg0e%&P=KmCFsZmSEl}25Oidi%D|a1gm%%9 zVfF$u1_T`$rZRA5QmrUKM~0~k+!hdYWSGjpnK6WR(UD>H0y72#9T}!FaAq)Xd22-p zIxBulqfbWsekzpzW116y(!|VlS4A!6{!&C;&OsW+nbZuM#6OIg188|bB&@MVM z%wFKRU=2DlOl9EAq*_tJ-VZu5Ol9EA7(%<~$S`|>8G|+G$S{?GGm~mX3A=ac$S{?G zGh^-t9T}!FFklkhhxpb9M~0~koEfusm7pWTR0eJfwu+7nQyDljhR`lLGR$6J#($yI38+#t_=2 zugx%5CZsZOX3Xn@j!c{@6Kpi*pM0f-xiTS@fiq)XgG$hmiF0K@(2@lWSGjpnE^pZCeD@dv}bY^CFsa7m4VyB zHQ>m^xiW^(E;=$yW#G(!pd%CK%6P3PK}ROel>tFVCeD>Hgm%%9VJZV>1_T`$rZRA5 zyjGN;BNOM!fS@B2=gJsDyXeR;mBIOaAn3@%xiVfWO3;yEDuc5QLC}$5Dg$T6(~)5+ z18*fbGE8M)zywEzsSKPM5OieXTp3S$CRd?VlOyQJFqOf%!XW6#FqMHbV+cAjajs18 zb8>5kxiTS@fiq*aN(nkLajp#3pd-Un2F{Ejw2O`mQyDljAn3?2m4P$kwW0(anK)Ml z1Ra?;SH=+9h3PRNm4Pz@f{sj_E914I1Ra?;R|W(fnK)O*5ZXmYhN%op0uXd$;#?W8 z6(x9{EmIk|Eg2XcrwBrZRA5K+utib7j0%l%OLM z=gNSfBf~Y|%oswu=*TdYfinYwj!c{@gnK)O*YZo1vI9DcEHCqWfGE8OQ%y8n&Kewd>9ho>+25ZofVJZV> z#t_;?M~0~koEZ>wWa3;IuN5UQ|E1iO=}3Z(Oq?rY2<@UH!&C;&3{ajuNliV}2W;#?UJbY$XO8AE6n z9T}!FaArWzkzpzWXU1zq2{|7Q1Ra?;SH|mSA03%ES0=ckTR#Ws$i%raUOyp~pd%CK z%3uvTGI6eqA+(E*3{x36Ga%^5FqMHb+#t_;?M~0~kyb};~Wa3;IuN5W4Zva6@CeD?~iZ@XtS6C^cBg5+Ce?}(;(~ynBg0e% z&Ws_nONB#U{G0x;K zq9enM1wKm=9T{dXFk?W_kzpzWXU1zq2|6-NWnjjDpd%CK%6P3PK}ROel>tFVCeD>H zgm%%9VJZVN1_T|MI9JANMF~1GOl9D?fS@D8R0htBA+(E*3^NvZE+FX0FqMHblBoGatCq68h8I9CP)=E@{YW#G&hLc8e5FqNr%8P}jA z!&C;&jMs`1bY$XO84z@2n99JJF@$#6XFDAkrZRA5yjGN;BNOM!U=2DlajuLZv`b%U zVXjOP=gOGZ2OXI>SEfi`X<@ER66ea8*Ps$~Wa3;IY!w}uI9J9H+C@i(sSL~*5OieX zTp6zwCFsb+xiTQ=$i%rahR`lLGR$6J#(+1_T|MI9J9H+C@i(sSL~*5OieXTp6zwCFsb+xiTQ= z$i%rahR`lLGE8M~ejf-rGI6eq*NPH!WSGj}+(Hm^WSGjpnc-}gERzvpW9M`j!c{@gEi>LFfoBMV+ie{Bg0e%W(){AGI6eq*NPH!Wa3;I5Oid?2Aml~ zXcrwBrZO;NK+utib7j0%l%ONSR0eJf2s$z$m1(=o5ZXmYhN%q97!Y)1;#?W86(#7% z#JMsc=*YymGKSDDIxHt_%n|GI6eq*UvsWGI6dEPwM<&jd@mf)Wjto;7m@y#e$i%raUMot_k%@ClBoGW7p?V=;YR0d`Y2s$!MW#G(sttdf9CeD=sK}ROel`({N(UD;)12YB$ z9ho>+#%o0hIxep5;8Xh1Ra?;SH=*w z>!SwT3-DY((2-#(17{}1`KJF=EU};gA3?Y+An3^Oe!!VA1RSM*y0En=*MJ!Vf{sj_ zE5ogl%2opF<>upnpd%CK${0es^eA4KE0c+HWw>|48gOQcl)!!qYruxV8kj4SiF0KP zp+#%o218E|CcTp18_WSGjpnK6WR(UD;) z12YB$9ho>+#%o0hIx=yt3+#t_;?M~0~k%oq@KWa3;I zuN5We$i%raAn3?2m4P#32<@UH!&C-l3M<&jdDbjry=E|gT zu8i5chJYi(R0eJfwu+7nQyDljhM-B4>!KsWR0d`Y2s$!xu8h};5_DwZTp18_Wa3;I zL)b3;ZE#W5v*y#F?0Mbp^KqVj(KEN-<8i)(d-%sa!r$-WiYWYdetz)ZVYt;eBM|*g zsUC=2MG2(gfi8DtzOB|N5c>|TZ3yi`mLAr?84FnB#m`O*#4h{oH(x9H1h=-FIIjA! zfoRnHU_+43bs^yoYv7CptZ~*^M+f4^UiIf|C7&Q&PMowf3B)B|G&Kb2To=w%2;Y|Y zU(Em5)Fu#TR5)V3R`Lnb<5oShq-QbDKH~RXoQ)K2k6pYKo{7ZozBtbakB1Uk(PzGWwkx4) z@T?7fPr$hvW<9%x-mVfnA0u9=G;gbv&@OImw%I-Yf8UQ>MG3BV?AwERZb;r5$You; zzPaPy7hhiD`Cn$ieD^^DoJVLSpE%|G{!D&xy>nP!53?qiG=o?6q1)mxJ;cSSBv@lxgmz(8jvIMVUk?u`kHE|i zSEG6#PqzoNIb4m+B_7^E_&d)3$RjX=#T_%KkB46pe3JXF>*L{pY-g)XYkKnz{-9x?S)nQn~sU&#>Cfv9ZK`$y!^VtreT|DRf_)LGEH=ajmMF~E8;!LFN5Zc9a&WB#v zpXZI|5xN(3@9I9Z&qS>#!N+Mvqdv56^43s7yYv}q*U;_N`@!?ttB&r^bJO$I(25d# zeZ(16+aa`z=e5sR(x2z1=Mh>_0yD8(oVB$bLc4fg`yLJM;<@R01kK2Azw1l8(P5sK zt6SFB!&Us3uR$faUgu$bJuJk$HTbCI-et6F+wUcO_T}EA_-udi`92;t-M`!_CHP7! zn9|3?liSW#X_vk$*=LEqYW4Lc`qA*oTSE!$(&w99gYTAmEiUo!$Q))Oxv5WNLwn_=@;=kv9S=cr7@laatpCz=S1lNnx zpz^j#3GLFy$*$3}%>tMG6yJnL>{_J1KU>_g(4AZ79-o=B8-AtgHyN!c!N0fuN>zf_ zUx<@Qi@09%Tc$a#$7?^dnmm}-Z^&B%QzP9KV+VK`@!_f`S|L=REK1=x7&is_0`dmBCW6E2DM4WOOo=ZF@k$7cWbgL##xyuGW0 zcG<_{`3r6j$7JrW(xHr3A?5cEo?)^0qw>GM`TAF#j)8mLaZ5Q-rR!0F;F0)zg4del zEg?rwaILVlcZ4JK0BTFEC!^Q;J5$7?}3G5YBv4M95Bwe>onydr64Lpd?(={c!Z z@(I%A*Dw_#QG$Qxx@2opvsF$j`9$185OU8AAzPKoJ_I3q*J&l6;2J!SV(TN=;mjS2 zl#sof^3mk8hi6-CeU_BGbzqTJl#pjA_Sel%l|K_Fw#*npyZCo}hJrZooS)11n7jXW zozLs~GXLN?OG1RdbIz8_lAt8Ch9 zP3k>YLc4Sy+O5)SvFbHbd2Lf3*)G58sji_{p(VkrfM<~KmY7YHU+-0k{M*f4O?BIA zXoY|02)#z9y&pGRDJy5IHj;4_~|6VIKo zgjST$tKM##&@O##T0$#I=oM+VO=y?Cf(=p32{%lBXzy^w43DbPpV0{=+a|P&^LUv2 zl+XE*XGt;ViZJ=1Gr{>EOn&G#=qwPs2Issm`JuzYc`VFv=$hzyme5K*!Ayr1$+ij7 zxh|cdVhOD%p>tC#q4!YlxlSmtgig`XsXaJL-80`QpX{J}S1U^B#2~wd657Ry4@`c_ zXF=#1T2VshBiS{S&@N7VVDeKw3qse>y{LOv_n}=wD@yQjV)9cyQAgKMLc8=CYS+;1 z)%(F25lnu{=S}DuT2VshRoOL^&@N7uVDeKwZ$j75iV`|^%dVk>c5$i%kCBzno6t2l zmyF2|olDLPWAZ~El6#tI&GuhWN^m_UKjl-#bPc^N?b`NxiM~hi+0NvL#-84iz2{m{ zg0D0tKjm|t4rrqSwbsHa25=cpYka&x>ZVOm(HuQYiLCY&a`3j zQ$FoR*HA*cbRXI^w4wxO^Dy}-pI)bHD4|{Ye6wrt-IB=3-a{D^6JF&(X}eWgQG&BtnH7~!an;8| z3GE`ibtbD4oPNo4iDtjf{pI9MW=Q1|J(bXk5;_Ce-VY_TixWh7q?lJnu!Mff=*-D& zf8uCG37wE>*HA*cILC{0h7vlT)e^eBeBaGYFVp*H39Tr>Pll~?$@G3Gp?HWpG7q^h946o*539TrhQ?<8EXczA}Q9PVus+QltoDpNkqTBysSJOg=_}2y zp%o=`*50-W?b7G8CA6Xhf5~i}!l(B`3GLE%RJ(?L-s$I{?l((lMF~DOOl8Wavg=kU zphD2qnv>E5eRr7h9I5mf?E>SfD?i>;Fbge zc1^KX@(I%A1pJjiz-KW8>0B3_7SBDx{{}}U5O8LSwUSSeE+^Q@+yHisAz00Iacj5+ zZzb3@f#B9@C7&Q&PQb1S1owav{5#jhy~;JXH-cSLzE#-ETFEC!mlJ&Cct7|^D#5>V zU3_+M4L+*41_YiRB)-A3MJr11c}AMgNL+vS!#x7A+a6~cLc91k*C;1&K6nw=z!^{T z;j4sHhS&GiXTE*5Z;#;Z^7i3ugj9xCMGfbi|FZ_p1Pc>k`CtA&o^9q~kA!O*@=Au5 z&`LfL4V64XSJ!Qafe}&}UPslgp%o>#N1}a_Pm3GL$FOlAHrp%o=ycHp;QFh=s$ z(8rd~vFMU{efHR`(n>y&+lSjGbWg+V38@UP&ua;-D6##=BloB&q5IITp%o>#b~LK; zwn_=@(&w99L-)Hr9(?9U|0iz^tti1;inh~s2<_6>rrj#7C;{sxTxFM6rrkE7UHS?x zf4}AXF5gXY&UVN=IQ0Z)N{4KM(@FSuJX0QP@Etlwz%d9p4rk-w?D&x5a5~MuBeV-= z-G>~9lYHzN`CFCS5}d^z(i+Zzv4n0rOp9<-p3_itz5h$(ZdVDo86iXBG?Z-<+J$q6 zL(;_ACYHdN%jFYJFzJL{(ai~eM=L3hz?uDFIuEDmz#a&5emK1c=S+oEhI1V38d_0; zk4^M(wnJza&a4Wl3@1O>HMF7xp9|5)*$$yyIJ3$}A19B{{lmQ*4X5qwE8Xu(@X?G$ z)&E!{x8JpE+s_i+UcDbU-^)iICvOd{D8XlY^l`RBXcx{S^U=r2BebFf&QA{Wyf}Z$ zK7vYU7tU4n@yz8s0%sD3REG1(aOQGIWjH%*+xto@N^rgC87bGhyr_sDyU$y)ybZd4yJ! zz?sq^mEmj~yM_|lrH_*(w4wyg>Jy!xw zOGsrni^;B``%1g?_l_m>@laatpCz=S1lNl`PTp22pF-SVA3pjx z_?4>PWVE6L|K9q$Rta4L=kogKv6%Jj8hX1*;4EDq4W7KMQbM~(M;9oMz3l;Ar< zbY=3^P(r)lQ21z!VEAub+l@eS#x-xld=-$;X{(J6mvinN+JA9Kc-gxSKJ7`$yl zyY%&F34N{UYmnmJiLka$! z>yqndf`B6v2$~~W$tOtD3BlBbr;iK-of#$g_tvgHGq|s4s^FTkPxB1)oHMhvl24HS zhd@61e+lfx8M!Xd3D@{%tMGg*cV=wG5?i;Bb`Xhp&;PkC(z!0|h4AnH?A<`bz57ok zpCDaMz>&fIFL!42w)l6h3y)^FrSfM99GO7yS)vss@a%D<%b$sGWCB5FMhWfW-&>!% zaAZP`!}Jo4jHfF@_k+*M-0kx3e@EoH;K-zOW#|V459gmXumc{B*BU4#3Ii30Z`2_E044Z~YvDnlE>68X2wjD@$m?KQN*zjFkPmo#2kHE#_iw2OZ; zm7z;vw@NEYz>!Ir%Fv9kgg&->j>Rhhm+7;|5?aY8a{F-GgzjlLGAUgddMB39iW1v@ zJaUhk61ornA7keMZ%I)l?h7WO2rCGRnP33-WgPfQw;81Vmg=!7M1ShX48McHjA`?(6I2_uHNJo%8jn&|O_s z=blr!4NFX5yU8P5l*)v){JiBh-0toVo_xGA#G2%UB__C2ll68CVJ*L#xeZH9L`K?~ zCd+PN!-Tc`1}7WI$HKT95hx3YMB!J`@$2`ki5TJ6%v|HM;5sKFs%8PvHN*i#RLugS zYxo8GWQ4UMs%8PvHT*I@w^5d=ElI@AEFgx4-;L*l%N{WjTN5imG=%Mq6779WL`2Wl zMD`Fr(M?z@;(oSfub*E8=S2Lvd+X+e6QYB*ZcbE5*Ygwc%l!q-={&>$ENIU8Ax373 zSQ&mhmD{ky1bx$-S2TvOR{REQidY$bVU^pk#01YmbMDd@!dej{Glf?s{lY3m$uciV zGXS*@t=pVkGp4QF?k4EX=0u&MR3@y|{gk-8u1CbkOyQN`cVBs1Sz>~xy*US~D3u9o zMU2c8UKxH*mfNtzL`0)3XwLI0Y?!cC#K=tHmEkw5xs8aCSwO4|zbK9vnFYkk@C)Yd zwz9+o_VCK^>*?Hv32Swa3?6ZK+VRQ|0pmM$+c3eKhF2ymQ?`5s-(Z_GC-$w|% zGNa>_B_<+9W{OxDercT7!-TaME1Pq$3c?Z-5hF82tPH=H&TW{mmRlqzEHM!=G7E^6 z;Wypggth#<;M#+_z(iB_<+9W-DT4h(XD1LmIbn$j>@_D&6*f#{TKY;9HdJ0ph*ySa5!Wv#EHM!=GFuTVL)=L>k!vkq z?-Ydk!}eUioX91;;VKM!&52V*sZ3bQ{gm5?7?~-&GQ_jQI%>Gij2M}eC5_0KoUp_M z*X{Z@AXE5omKy9sMSH)paIM8wEU;g#X{$niV#spdrB z*@(}W!Yf1cMQ+0q6Y-n#spfRxF@&`uMrI1H48P;gZTKt0*PuD2lBmp%FODT97#W%q zGK;6ggta0@W(uziu@rf!EHS}I)SNO_*l_Fe6>Uy{n#DH$gwZc2M03h%>H~Z%^nve` zm&y|QrX^_I=G@n!9xgBAZgYAW(Loc`+yq~S=3KI(=DwG;B1UEkuMEG+&+B1{3BGX6 zxnzY6w<7kMQ&lHyD-+mm&V4OP<<_;9`zf!7+dU#srkeA8CoGkTh%K3F&K4e1Dr@3~??wVTp-|mzZi!=pI8@i#p+zAu=YnVTlPw?dF8;F@&`!Azm3`G;$k$ zb6ABnXZ6*7({jQR6Rc$L%8ahOOjyhBO>V;y6Rc$L%8agxOjye!YHq{dJAVh=ZaHCz z3Hk=F4AC&%gthYi-~^hO=k$n~iQi15xdFeQ=L8z&3B=6scXpupd#}d{G!StjO(I%} ziHLPb^e_q{5yZ^+Ue=0;h-70JX_1H~(qbqn2}(GO=12rFGrkwstyV;Kq&p2FMmT|n zdNdIuLrF=O9B4)-C6Y&HlnqT+ydJ!X&2x4YTSc_}gYCy!Vkfy0QzuD%@8qTgE zCV;1sQt^ay)(gG~VnUKP9qi6Sta6PB3ZR26o%`R#r;VJ%9F z*J=KGv=S58!@EQYa~tt%v-a#7el=IMF+ZF@gLjGOl$@}nB=E|NC!kv`PN2an!|(WW z8g@10tZQ{1#8lTr_e^_FIvtHQKCzc|&VZvIR+=35@h>M)y zEEIex#4~Va37#0@C%DFs!*xzrVuI61@B$I-F-o-eMGLPLTHS;tCO91izX(x8xeXK6 zqUQL#Mr-aifxxfEecgt+4NFYeb~j-y`UYRoXb)OqqPret54OF=lZaPl^hvbDy~&;M z%J3}Y^)O*AKlwRfiHV4jNhbpl4bx3nD}SS6yp5huf(bJhz! z3w{foM(BA7YjI``J{ErGo)er|gP((V2F|R(AHi>7xyDbybxv^B1Kt;YAI_OI_>K4- zx9#PGB_)BUX|x_DxNfyL@q|5nVkvSPmYAS^_z5c5oX>z)hTn8| z6V~$cmJ^JYDOM&%OU|spD?_Y_=fOE)i3v`l!7D=yN=|Sh3|<*xG0?&*gO*3_oUp_M z_VCJ3!fwJ^-CqNjmlEQYp@gnqZo?82oLPfchPab%!dl#^U0LLW`@{C!A~|7+3GCsO z87-9wYq_6t8=N77SB7{NuQNF#g;*IPV{*b06I`?YjMZO3*am04;FaMwy{2;;mYCp_ z8@w|7TDP097BpTN?BxXK;^39x_sHp7oH!qcUzc;130@hZFLJ^X6P(Y0SBBq>cN5m) zTpV_a`5k{w_$$NL0Iv++kM1vyB_ZNUUQ4&HY_oLZM-t0r7~eH{@(Ue zZo}=)X)SnVh$8Wwa>5c5oWp`whWL_#_X zElP-2X0#rbnBa^QyfVZc{!7DS`=O(O`_s15$x+Cp=9Q*b6%Kk@$~nrzWVHb?9l)FcN6jab>25;Nl8Eth-Y4NaU%Zr;=MBh zy48B<)E$$JE%$v+*m&$;&P&9eD|~3ql9GTP5a)gC!)b^9f)_68A9V5=)ls`0SD(Mp z6SI1_ei67ZhG37Kn%}+Z$<=RfKc?Pix0Rw)CVVgKJ^a8~752IbOG@G$`z)zOZJ6M? z)q2@$PN+6p|Csug<5w(7Wl2e#{guVlcmlfBdi1SFRkywW$ogrU-C5-|x1=Oq(_2)H zC!kxce>wc1>X5r*FJqT$3LBP`#P9bzwHgp#c-F?L&)@s2ZKn5LX{~DWT~Dlzf78j; zhEqSA`tq%xs~-9NG3ok)$A75iy4N#-Rx5!%@TC1B3gYC-cghJ%OuY5Ylm>?8HF z9$Z}5FkvmOU-!k&SEGa_CeD4sboKo^4yrf0{l5wuCalHvt}C8gjS`laaI5DvH(@QV zm-okRdkjudI_kRPt8)&xd1}8sPpOW6?02ebwz+ZYnv+hgeslNF)AegtJiO*QJc%OE zY9-JseD$L>wC|J?mYDeAdbdoS`1C{S@9xNRWg8}}#dZJeldDm}5)+T!{YO(D-t8mx z;%9xSuwlYlT)*Jj&sU>_B_=-h+PkLyvCfC<_1^r6!iEWJas9y4PN+r+OHBAJ$lJ<< zwfuJVdUHprG7+UZB@ zR%d3oid}p`mrF_l8$+Uv`ppRF zRx9WkYz#{k@9wZvlH|nldMJ9CdJGA!Tdin?^!H)wCL2xb4kaZ4Js>#ej#4!}I3&1l zs};SO{yun0IOh(6r^FHy@g&yJJa4@o=iEU=3~xqQi|h6Y&3;YQj~K=DYmtaQO;31x zU(Ua4B3a|^`kj8?65ffH;QF82h^WS?CJr*Qm)r1tO++l=R1*hTl*)v)C~Xs?To9I+ zz+MxJToAq9OE+p_k>fcyY{MoNxr%7nsU{Y=AaY4gG%>tm2m%Bd!XxBrtkwXTWb?b8ZPymLXgP25)9ge4{-wsWe904;2ou$D`kKP4`E#E(uj zQNLsAVH+kQ8g#0O6CP74Yf-``zP2DNF%i+AQ%#iV7{XfAyor!52un;v{OD8@Wjcni z7H!zX_7()sRr~xzEb3GfQ``6RmiLDxCMaPOAw7?c_NlfObQAAh5SEyrrTJA)#BGlu ztmRh7>tTrro|q=ay|7`zS|hESX0H)B*^gh!&NPuBjDy3`nd^2$O{E$V5$Cn6iTbS~ zg6oPV>Nj0CF|jc!DOSH9k&MflsNX7L@Rl`EzY`MJXzv@beao7t-@-;&s+Nezw`EP# zZ$WT+QWIZWMa0k*O?+*-ZsKbT!nKVE&?}la;W71a*-b>m=@m_!@H{r!vRjK1&R?pC zA6(W%{ZV|;GfmWQVZ#y=^i31>JBF}U{6>7HiTW)FOHA-AG*Q1}2y4Y} z#AlkQ-@(&9d=lMjv{e)JJEjNSiYDlrChE5+l?iLPXY;4s<#j#cm+Lc4)NfG_OHA;z zH&MSusZ3Zaei1*@MEw>vEHM$0R?C{G-@=9oYem$}OcV86*oc^@Wlhv?6){-LnyB9i z-wzYmYodOOQn}r&)jcwJ#NlagqJAeVl?mRoChB)gsjSsK`uMH&`v}oQ{T4PXF%hv+ zGfmX*7{XeNmHfUW@-`HNB_<-~Yo>|%9Ya{l{gl5SmY9gBv}H}yZ(+lPwfwy0HX_pV z@+Km;;%vJnB6q@(!9>K`Ufx9H7NzpYkZI|=l9!4vP7{kM1F-7vEgF~YjF}|6J=fyE-y2uCQ`3* z{qoke#00aCCQ`4kVZvJUe-i;-5SEx=_R&P@jUlYXX@5;Lc|llWg4stCEj@;?7AGz? z5v~Pci3#4#CJK8DVXcUXooS+F3&Ii;Jkw2F@)*Ke-EXZWCg|BFdbzM+!diak^XJME z`lg8{?{|+3mYAT`oA~phR3@wyF|jjEv}{3GVuDt0;;Y9H){5xNnI>AcAgo2ZHIdi- zZo(21jIK={g~EmjYeoF%OcP~V5SEyr4V!EWV+d<8jx|{$3c?Z-w0aZiJ%+Fr^=sm` z3&LX`V{nuGqVLf)e-bSziSBx|W4P-?8#ZyY%9SvULa(8oS@P;M(rOmNK(J#n20QoeRk+$r?qHZ6V{@%?9k6&k5*y=d+g9t!n{432Q|j%Ram6u{T=~kr^`f_>QS#zjB8CN%kpYUol;?>&$gt542i|iO7Q4X9qI& z7{?IS;+lQ&QNj`vk(;y6j&ST<7B);+i<+}fJz8_O2?U-7?&~(pYi@}N+wLZ;Mc=SP zKiY$qnCPxY*@JE0FeHb3lO`~g$)zd z^5~k`n2U^&DXKB{#}-7!$Q0EWJ39*^$7G6Kiamm@y9sMW#>f=a7&}G_aw4)erl`i) z8QePZF{Y@-SnH;1c89sniO9{Cq8ejwW&yh??2E@9%9v8QBqhO4`e;2&aNTM}hRPJx z7`u{1sVp%;{n#U=etA8pZCgXvJhG;xs7A7=5c5^d`H`^kz3eS~1wnQ<&9 zEHM!|CR0>n?79^FVZvIBcI-McKIS$oF%dZ?Q&eN@9u+oBSj%mg+pxq$&YtV4^Z-GsHE z@!exDx8Wzz?dE48CoC~ROXCF??GF>y@)Mfd@OaL+%YHi}b@$kAi3#38_S+fra~meC z71UT4cFAL}WGeE__1SNay_u=Vq1k62KK9TG88^>!=hA{nBdF6e*5UG z&oz%cmVNdUW0!EsZJ5`?5)+Xnw9kHG?Ee*|GGVRAy4PnvF?Og5!V(ja1+mY5V(bNu zA*>Zy_fni!>=+e<+k{yrd-}{+-G+J1Eiu8|jy?U+xu^+i(dz8!&;KO05);hr*wY`K zC;DF2qHoyKr#JI@SYm>?9eett^F$NYqHoyKAMJBXOz{4*r$0JRG+`}zlRf>>KDWdK z?+ttUqhpB)YjwZpmYASt+0!3=2TfSZZ(80TeqN#3*=EG)es(P}!Pv#lHltl`!-TaW zZ(@qni=Ebju*3v!GdtUiuDJ~p*77$oCoD0+`_Iny=*VEgTGWr7?a}w#5=zKUGqv@d zx=U3O>|c-00DLd5TdjNs&_DIv>9N^!K;E@6$1p zdB)#&PsGIs-a2bZNk9*XwSKl&BA)!Obw)t9S`nL=Y!KVf>mB_34<_Q~WnY}Nq$HpR zL_{;rvfobRp-bXAMbzOe(TBto_If5FO0Fh4izqFwiM8W8BJ^rv@QAF-2}??XXu$CV zbgNb0dVjrmhcl`}Uvhk5!x9q_n>b7KAu)xcrSg5Bf7!=t?%PdRf;|&NPLA3z!F8+E z-MW^P1ktCX{b7RZR?9ux>qRu<9DPo#;*~GDq(1!jAFZGN#kXWV=$_4qh+wRVgCz1W zq6=%{5{VGxnutTLbHWl6w%tuwi|b21aY{vLbHWl6-Svog&6*faqRqG_Qj_aHzv5H% z8}>M%di&~+#F*%|vZN%IeeuKfcmlfBavSD0EGY@%M``tL0=m_5OZR#aF5c5ToXAtYQqu}?*H6|32SlPK5r3qcIkb|Ye`ffBXv6>M>N|k zQEkMqc?2IN_~I~zo7m>B&zRld=;P|%<}Ztm&7pU zL`3_|67@&KUPKqp5@kq)AO!J|ql9hvzTJc+Ca_1WCHC@CnXr~in-i9l1hJOXubY5w zwcOGwYGfaJCcn*?zC~}p3u8A5jU>0 z_najq0X-n@`tp)QY`Er!GXlERil;x>i1#FPcYoU%iTL2@A10&2P*M`m1LD9l-kH9G zx4-ee*`K}U`Wa?2-@oMUifd*vTtDZIhi8}>{AP|g;V!~jTr>9>B`h)V);Bz>W;Ss3 zN>7Ly*oFyfam`F-l(59az0cpaW;XD?1Bny14HMSlnpxi{VTlR1dTzsnwYXm1A4k55 zSkcI0{*hC%K5*Y`zVrXgFyq*62~qJTEGY@*C8I=q?Prw5VW!R1aMmTa%`n5+;`hvV zZNn016MT0^2};#kzv!SJ&rHvpSbcx(rIkyY+pxrhZFdvaf``6gZ2}?|Hy}TZ~ z|HpIEYT}SPUpjr^Y5UfHI5F})9)DGJ$DiJu<_TLJcu95CK?kS#!-tN)Hf)%%!~}PG z_r{TstPP2@gzeR=(*TaOhxMt2UN?2mz ze^yw#zId-T=|l){DyYjORWZ=P6<5|)_oQ<>Mpgthz@^m^Ca{^8W;U%c`3zI)Jp zu=~s7Wqt@@u;IX&9Mk54jZ&56}!V-UR{O!sK zm&zsK`sA|?uSZK|iHUuFb5xqitiLH4Xk022*5aC(%qU@ri8J2u*_wIDHTV6!uwlYl zTr+bTB`h&Pt25)E)$@9ou$KENCoC~RKQT`n?LiaPa&Pu}nwLyVGOK=`)ofrko0m*m zQWDIZV_p)3<|P>c-D+tz5QOF>)0UJ3bj(YF(7Yrgpj$0{)q>ExWZIIFfM&*@_F~dI z$WBY_rlcJf*0EeS*^KHl_CB;e_5Yn#-L(eUA7b}rNLW%58=i4^J)VGWwPG(O?c%V9 zlH0JvMC^K`c?r7}IpJP&|HmFinwPL!krS4bM3W0^3<2G0QK}}JRY6!%5>1|}F@$SN zi!e`|zpYw{3AbC?i%C7me#2j0yl;KZ#}BLTKL5(B&;2aqMC=NrJsH;jvHz0xWLW=m z-DH7^9*q5-p$$t+*mgHzEw0yH_tc8g=7c3Cy6d5D5qmN1{Hp%??CSNFo19o3@UhPq zHY_QL!#Cfr9#25GT5iL<9+s2@vn5)+n}BY$+|p?;W{&wTdo!{BGSg(RO4m)!B6e10 znk-jgBX)0wgeA}>nANan(@j9PTCwXf)8vhshp<+YkBYsR4#E z?wqj11lP;QcH3~Tx&LFIWTwe%Rg}tvwYY9FP!)tFCSso?%}dzd$m?OkT3k1IqYAP>E{!iEWJxo>(s`EmN%B_}Io>(i;_J&D$pAE$3gNwBUB zKTZ(x<75PMtHqa}r-agFew@A~B>_DkVh^LwSi;JFuZ^EM`mXriv>QNgexNfy#*CTmP*ty6{Wl2f!Js(d% zw_34#lfLKdz~nY8DGBy{#uL!3R_rgO`5e0yxeZH7f?cWs5&I-j|G~;$yUR1$b)JbG zi8M1{WuJCdhJ+<0!S`yEpj55(6*s)N-e~%y>bZOVV8*4*ZCGL=_F~e!guRY#!dlSp zeA9t7_Hx1!6Rux3VJ&F(mPSiui3zTkw^i(ur0)m22eAv0_DI-0h<%H+f5FO?YrfQ6 z_j)EQf#$ml?K|a!B_@vh=Ee2rw)<%P;JP~%HcVKH>-t5fRHK9?CSunk?U%4~k(bJZ zwYX-MF-lls;$0Vgy1r%eeWM<|!iEWJalOlzPKbJxge4~Y1; zoxvK~-;Y=)CqE7=Vt*M%3C3F1Hzr~wpFAn7t-A?pLGvBNUQSqIf@{9cqc$ut5jzrT z2EeXDZo`DNxMufblZVl=tzUoiw`a(G-TdBTCOq*~ z^E;6Es+q9F1b6!Jx(h4r)J<56J2k&MDTuOE%zfCQu)W-dC0w^e{Q9D5el1eiFkvmO zo8NvEge4|cdD5xX4X@d+KIX*R#}L-y`qr&atVRh-O!%qHYi`0?T(@sQ`mI5lm$2Uu zdl>!ZcNwe)ha+n2Vf35dn#6NOer=u-2un6U zXEbMX+;j2X)0UJ3be!f9gwFrS2%XJ=-zeFRFLn?*V+8NgP*M`u7!a{flD<*wX~fP$ zI?aO}1DDG6OFJt=BG%tie92hfa^3t|q>i=!6kk!+>^WgcNi@GN8ACv~T1$SuUiI_a z&a7Vd`&Fanu1Bf0_x4BEXmt~oaNQEIPm<36V1FaGVZvHmGe;REEHU9$&uy5n7T3(R z=%<{p#6;eM@k@@>gY27p;8ow9+WtL<)O+lHZPtVC*|f7VBw{~gs`*t2I|NhBuTau; z^9zsYLEAv9m6)*YZo*nzFTDQbiqhtUB__J-5qsY4*(K@suFY>)>eW7Q*VM9=PN*(B zpB0PiVF|Q}Pu=&SdOQK$YPk(_8#L+n6MVt%q#~){K_Kr2m2}=B_Q* z&F@Q!npuJA)c${{Rgnm!+U7ir_QdHS~$*d(M!P67_B|&JvBqN|(E$vbSq5YCsOG*Md z_Dh1$eo00^w_2Ko2ci8EVt(5Bc~uh7d=HbSA=-HG1&tX@T9fm=;F_5X*H>-waJ5&= zEPwZz2c~kul9G7%xkuLH3FuZUW=Uz!fq6@A!x9rQyGT1B%n)+IHRrmmZOj$Yz7Mm4 zoUo)M8c)+00=m_rRP6hVmdcWnXgp1Y4HK>{Ey4_N{)5&dEQWA}?s32V4#cP~ZUH;WLA#Ky=rFyjW%Wb&kCTzQ#uomxJuj6dCTR7>uU6PF zVJ-JfueaYmYos@7*Hw0$<3x0Nic`&hbk9xc`n*3qq0is>Uh(%{?}%5gm53Mq%Nr8W zN=&@vs_!OxojV^N#8W=GP9lE2`fD@7T3_DsC&|X#QL6;8>iX*^;_Cl><(wrYL1_oX zb2ocdBDP;^yNrNtwchpNUnU!WT*3)he>!l(MC`cZzt34x63_!;w_j|Mh#hX4$_VII z>&TlQPB!A-=#Mw7u=$`=e|*WDB_#npAh!SGOA--eMnJb(QJPs=J?;`VqBMz!(#=^? z63_!8YMh8a9=KsfK(|`as>w#QM%ai}O+>WvoFydzJs_gz5)nO_5zwtxJRQkK^lI3+ zfA!ZUBA%8xOH9NQnCN&SgLwQC-k6AQ{qzYLVJ)s{s{!$~8~2-Igj;)y&&*zY-E2+% z&8z=qmHy&i%++M?eAi=EE1q@}eh*AM@3&XgLRSgooI!@8)f1pUp~F& zJg@kd|EtMn#PyfYKEEbI>_)TKM$JuFQW9i{9VJ{3N=3$2%I+4)ZCGOB&ik&c$pgE~ z)tn&dQkk$8?M5b7S~@2_^Tn^!XPUPa{ zPPq*e)^Z!>gv(2v$Ro=Wy0}-svy30 z(->?Ss`@zk6v-_SQ#l^Vf7u9#F3HQlZsKO!U8ZSxxrVWtabB3}G#<$=*6j zSYqONKfF9*vyQD_dFl#9Jxo}Onv=bCwB~LT2(q_wU$oR0PGoQ8S?DIL%U%;z4i1T{h_d7!diYG z(|8*_pKMLX$?vmdD*M*Mv&<-lqq9ftoVfZYU#vMZ?7??N&fxz(zvj%aSG;I(RnMMP zlZo+~$iLG~SnHEN`*O{hVc&dYNkRPbvc)y0aNU2~qUvv#oLO_e*2g|GxF#Da*SU@T zZ#bvsG_l9+cxLtKYtOF9_j>wDXO1bAOHvYKaviOQ39ehM?=M?Yb4JyhHY#gwi3#dQ zzE|p(*Mr)&HFV9_y7-KmGtt)Cwj_4_=D9VejD0Bl{xAE^c{Qhu-ErTU)dg!`S#!$R zt6zRzVZ#y=^d|XU>CL=UCaiVPQ?9N#Wo(0=mNqOg!P7&&SDv2Sh6!uE`kB|(w2ts-*q+lULX5^Wj!o0!TUkJ*U|UG zgtZ>o3rPb4Z^R=2&#`b+qWI^m487wh@J@UPdmdb>+y2lcaQ9SMBd*%J`o$`8E zVuCk~e6PG|-GsF~D&>UVTEATo2cgtZv$$oI&*ubl^;TkH!>=x?InV3dhfXg_^}fAB@|K0wP4}E$p+&w|v^;9( zHY_oLJ@UO$!fwJ^-CqNjmlBfil@hvsxeZH9T=;@THRpN#_IqW`O<0S+w=1OFhWo>` zTO=neF@Zg@o{pBvgtgpHxebqMj6P&NWxVPh;Vd!1lStN6M!wvJ32W{2x*ybJJ-uTS zGE?|zx5NZbK3Pvk-;Z(*$6A&Z_T$%HWtMz&`(8g=*s#Piy#*IPewO^ZTO4rJ7{Xf5 z{_JYAoSe1aORg*kmzVdPJgJNyu3vY}O)wIXCv|j$^S!LK-Ft7Z$&>nlV=pX9Wr+z! zRPv;b&X)f3jE8D+%Kmxo8`XiI`9n=k*?YhC_3HIsxxFT*>@&_NZCGOB>nr`XCa3KE z7hGJF%ET$Z{b@}u*6ly@mCCmBwz9;;U-$iaO)l1rPX20P!-Tc!FaDz@7whwGzN{cD zF|pDS_toTL{ma=GjUlYH(=Lyi1>mi(IUub2#72TJ#OMSn18Y9+sG3-bF6f(K(z6Ytc94Vjb;sOH42- zk&AV74rjtz^d`AjNBi6o6TF+`VjUgfOjxV?{jkIYJxeau(f8bhwfv^#{o&^onp~{B zsol@6B_??1$;HYjk=rm~t#$8t>@25@t$F`UL0Dpfx0zh5j7qr;6V_tP=X9?5zXq+u z1n)n&SVu<&-^*Imk6f&y@43Gde6KiVj6DZ`iSl|_QW9-xy9t+&79scR{H@zcOyu=o zucX&IEbVR|bo2G~jz2%Q`u39N_FwbBQRzDVP4g@M9&?rGkHLQfVuu|*KZWFu4YupY z^-OymcifQcCtkRHT64h+h>y)~Q6YK9{?oGuthQgeUhUdyc9jDjm9Fo3VB6WoL_>sD zDhXP{>;Kq#cFQH(rN7_3pkENS;rqUJ^L4fD2&9;|5H=)qZfj%#|7p5vO?W=^d9FSALq;u)LG&YbYwbiL32 zZ8Ur3D<4ePZ#nU)g$+wg92_C!*m(bfwZ{Pv{uJS}IjRSYkrY^cccgYLSA_*PySFns0j=+xa)Ixg{nvj*TI# zrE#SoEHR;xuOQk!pa)I2f2TL|dRSuOpWEPG*3ws^uwjV_eY^U3sbb7a?auS{xGx=^ zu6Mb8s=xo9UrpDPIwyQzeWUu_HY_oruV`VzgthdYF9=Ia_=(BuVZvIPeH1nhsUD0FIiWdj zU$bTA@M(t3d_E^EF`;?z7{XflI$>aCxSB{aWUQNr>vrZmYQw}(OS9#Iu*CP(oO%pl zt!U|*rzF-T1rbkTlEj>vaW`G_CdXTlu47JJ5SEx=p4-f+#}L+vw>c3pr!ELfOvEUW z2;Stp&rMh>M!rPEoO*Oj97;???bF|RlXDxsm$l;EOT_5d9^Z`AihMibdzG&FZkf() zSYjf+49N!Xem7yQ?owGYAHism+c42yqZPA(RH~R$7lb7y;(L+^MvL5r32VjtArXug zIbn&3n6FGgSSw~{iHJFMVS{xmPc`F6j7{m9v8t_8%&7~)_chUN!x9s=o!8uiwPG|% zCEVjDoIW)8Z!lh2VuH0l^%3GZ+H17b3I(CnMD|>1olra_ zmiW11Pm!AQRme+a!djFJB1&2imYAT8{y9-Cn<{LP1z!B1WZDs?jmggtfHCQP{A=M2x}7#%K?kuvUB}5`ot#uel{A;>(bT z(OHHGYsL2}5q!OK844xZ%Lz+N@B~8eR(BKDqE#Vy%W}e! z`3S~=Zla~p;%&u7jMN+Dge4{z5e7u7-#+aotku%IWi2y!KP;J#;H~Z^S{g02LP2=P zYxsV|&W+yxes04O6MBQk5Z0n(v{jU}AS^MVk!TE2Xl;y*XuqQ7QLCXOC+^w^BKm6# z5$AjiwW74C&*!a&B+H4gr@s%{cQ{fHCD!7-pj6S5Ma?ZS!Mg_$Z`>HdTG5+{7~Q$E zWL{#vz1QKrhID9Y23VBJ5)+y~jv=h2nPov(VnVa!F@&`=pDzeYOlS^2hOm}a76oC6 z39WbI*?s@F_e;NDIe6XAq~9=XeAn5@hja7MH&v@$aCUXn!u2!%*C@gB6W@uxi7gJf zrn>L%ORKwHOe}I~qb01R??+K8OH6!k_NwZ*DfhgfR<*&)iS0AtdtGtmY_&`Lp7vMktkSpboUp{i zj@!;wYdvLYwe>bD7dA{-%O%WhxV+C<{qpLPhnG~>@6emDR3;X@?$YY)Pc5ldTKveE z{;<|ACtgw=vi_3l8|OVx5SA=@;Nt403l~?nt^GUZ3Kh=+|K|0u#Ka$Wx~STtT3qdL z)UU=6)_UuuU#-4zW5hE&`169WzxOEx%$TcoKZdXhqo4lC4c?N7po`ld`5M^%f3HhsZ5+zT~K}ECyT0wFZoVk z!=lS~Z+V!oAsxvmau^=pY>BHw&r^IhvpYrSLCM=bSh`On6d~%d(*Xs%!E|s+& zx5D|=eLp_Edh01y7lbAEY<^yK%fi#EtG_!pVW~`9`;K#~quz9SwdqQH&%1iiT4$el zPPNuLr&p)HlwU5Ju;k;{o?RXBgVU zR{t8&3V-<3*NReo>xql1TXtVqt+wVF)xD3LUR@heDNnjAMZR>rgC=b6q?a$Mes{pa z>cOjtYILc5-xYp#dUe^G7FN%C+c+D(uZi_L}`u%rKt$w&Ou^C;ZvQ|U`R`2`dsnxb85))^_k~hD8 zadq*Yr&b4V_Js*cW#Wckomo9LVmrU~En+Qg!);})7aehC_0H#=THU)ls}>WMocH82 ztD9FowR-ZS&zZ1PCZ2fl8P#^bT3Eei3BEhqaH*_yZkh>;bt2ym9_Gx{jm#QHOEZ+&Y!L~7kkrb7ZBes z^B=xstd0+O!IS&UqTctnKZT7SK7YqV{Gq?boFyi>hJfz%o_6TAiMV8)4Km`hE3Tci zmYx0&ekVG#9os=G^b>LKXP%#x%EXT!vudLGH?pccddo!cukU3o>P4N9_j;6{no}Rj z+0GNWZs&8ocK^sBPW|o-9ZBSzfTEK+0s695QTdzlrA!q?hOt?;QCQ{6EA?SPe z`S~la-T&Q-BU{TeuFHPIloReX6VG|{Q~K+ka(4Be)A@4Rh6!useQx59%O2f-^k>hi zPF=dJy6~Qr`=@NWv|96=+2Uz8VXc*)6j?7~F8ZCAle&I+sVp&Z%NlF+_xr}u>bi4@ z^Rf*S)^aQ4L_Kw5^|oCWRac#xk80nz^}1@?4Hs3X{fT&I+pxs;xL!WCo3M?yU4MJ^ zzD>@op10(}32Sa*7ae*DHWtHa~VkeA9OvDPYI`c-xOOBYvL?RHT?tnk-|tM44X zq`Ki5msT5W_>byQcP**@|ue@aapce_L|Nm{M8GEz;|Kbgw_hyW8u1|J`q&X0L+xnH>tQ z8B4hS@8kY8y;0LwKDo{bOH8n{0?kfKH({;MK5?`3&hLKB;|pSXi)W;FaC*brXYT#w z2I(EV^vA!SVTTAC1FwwhVM#`;ygc{wyt*FefZA@$1FUO>gZzH>_CH z!-TcEYku~gEB1M7|M#LTvf6ID;|hJ=+9TF~Zcz_QvN}au@z##Em2I5xtyTNHwM&jU zBD0s*-1jx{&?&3+d20_@`RJllCam?P3)k%P*8cRJiwfe7XRO!ft=)9JdglIvpVH^8 zebI+*n6OkPR{haa(_8zQZ{1SZaH*{2=Pj?f%lofeKe5kSd)w#EpRiOW?z(QBK5y;b zS6(!xRMv8fWTl$ZbCq@*o42-l=#ee^>>90l|5Kyi^?uA*qPI5D&HG;vx5hicuF8gs z|1jlt`}JxY_u0i+ahpe`avPSIaA~^SijFs(Qn@T z%?V3oV*5SU>$6j|=G$ir8!nZ#&i~pveRhgY+x?<~u;itYmyw;KQ~KvmSSk~LU9@JO zouW#xvfr|9+nx^ZE{rLxw{SN@T9iaz`J^$Wt1 zCvEh%v{Q8VFP|`BsZ1QO=#jKj^s;LnQ`m5+to7ry9!fh!dn|ZxLH-U}QXThT+9`VL z@9$jTJLQBWCeHrHAJb0Jo6o(muwlYltL*>#v{Urfoi8eg@9uR++9|qe*Ne6~b^SZi zPSGYe9JQ72l$XkcwH7?#&a_kXo9iF5bx!!c@BG&7X{Ts~w{0=ThVN@)lY?$gJ4H`> z+eI(QZJ4kYf1h_=GUqng=hweUJ4L&!v1r2nF!958+@E%e-gNCzMeDj$*4paFzf3zt zAOGX71!2kiKL3lfQ}nj;Up`@}Oq}-Gd(%$Q3;uJ9!iGy_t#7V!PueN^-4oU?2umKi z?&oQzXz_KAnXptQHah(7v{Q7@19uiriA!azH%$F3?G$}_mx~I*l8^r7r)j5Xzw3|M z+IQ-HN=%%8(Vc0h=&ieMQP}Xktd&3Q7a#c1v@=ofyGB2LBb-(y#7t=JQ*Zx@e@|sw-i>vpx&>;2-Pk0s*FH(pwqxO8T4->==b_l#}#diPu~ zIQjkfFTKt&l`|&JJAK<^qt|=F`K;0oOE$Rjy{x6b$C#*k%&NTEJW-_$LTxo`iE8fB z2BDg}6{lPh)hP(oytc%I>lD@9>a?^P87>#U=6g)gRw~^Y%-tU%rF2b7`X`tQEf(PHRs7%?V3P9P;MX`y0ou(bVtBGhrK+ zEPc4wf6=>^REItN%fy0AV8g_wANX~3_5Yk%z4VRjI@^ZtWv%T#dULhu6Bbn~+{vE4 z2}{=4{PODZbxx};d-ll_mdeD=TV7Dz`L%`Bn(zHwVZ)`e7JuLU4JRdAz242$+tSm1 z-zksGy3e_8`{tLwdO>;?ZvGV6dOrM~!Fj3AfA0OWmY8VQ3H&Cj*E{YLgY#1NdeZ-7 zgthM2b<1Sqw^Kx={CSr>Q>h+#`%SZ!n26t~r4sVnvR>~SU*9Vcr>`}e5!Slv)h|gl zo^k)NL9DgnJ_8$1zi8GH6Y=}~WFvlg5yaFF2WRkH|CiGUgz<{s=k$8NdG-Fu z#urZb#H=MHK}!#aCvEcUv|GF5v)?(*Z*7pUpTIS}#`Ur-epCH+-P5YW&)P2Da}%c> z^!Wal;*7IbEWLhe`tE1K|Ir1J0c?+T!)6y@t+sFY z)lg1YV&d0d+PuH>=4V%*IAW7AgtchH`P<5pl33m!u7_LkQ|tVtT5s*st5dGod&(`6 z*TWJM+Z@pAuO09C^LPGa(H|zP<$lU+%ZDg(pXm1K=_Y*N+fUpejnrR#*_w4uSYkpwJBF~;tn9#E@hOidb%~MhkZqb)VKQo?hzw;-@w65F7#GdQ^rFum? zV{iG^-ZOdYny{9ig>0nmYpf;mC6%3DJZU_RdT6B12y3X+(bDc_-KU z?$-Oii_=bg7DMlr}FaIHPiRwnoBP&2un=Zc3uw?)>{9ytEVsA z>+bt{VZ#y=c|Dlth9&xC_ShRgS?#dXDb@KWoSs^=nIRReYl3+$V@A|rmYFd#sCEyoDd@FL-*=0-IjM#F!bnf4lnXM7-vz_h*E)R=x4WWaF02Ulh9A z-2RP3T=CSsr!6tTJQo`=W`^$6;-!gr_w0uAX~KUFNoYabgxbVa-ik^w83&_icDab>uG|Gp6R&a;v9O zrIDIGXP(Qb7W3Y$B+ObFMPsfyurVZZ$?{%{7OAt=otLl{b5O?ln0Xd9EHM$Sn`{i9 z-JuN=*5W#Q+J}T|e)U$5t3Q3rS=BmoPtRH*Z!14nCRiUZw#V$YsD}w_G3RB}ju~x1 zSi-7>(K%+W+56aCDie?W!ErPUwaRNAn_L|zYijt-<>HeLTy^$-7gQuWY_j!iAv_JQd^U$+Er4DTIv;F@=W z>odN;(d=zMKD&Cy%GWVU$c81%rJG&nM7MX!3EMEiT)NqHE^L^vR(CzD#az1CX)c~C z*TeTR!Cbo8LoP~X!dfdl`n&Z7>o2N4yAtQP+lD2~rJJ4R2}@;yxpcDwUD$A`tmS8+ z*L%-pA53rU%8S0x|KAU8nfm#QJDyxKHqmR0Db>nT>F?jV@ZDkK=r;~xu%7qo6Z)2z z;EM^(sMqWL_M7`B8(Ti{*o?3i*F0kb;*KxwmWU@U`vbclNzy)v?Xz^#uV0w{K6B)m zVdI4tzB>^gdivdcOZ>zz!-r<1>-8>J^u9zK@Y8Q+gtgovz1~hSdh&k!`kgmrZDoS- z78{JLai(mH&=6a$c3DPP%k4Ip8AHT;agLdBvscWXRT_6=4|$_UcD}WK*P|9z&;R*P zm*s>dCb;IEht3JxV1C%_g=Y40!uK`79J|@Sp6Mp6b=9-ioPAIHx^26Q`Q;h&!?xy@ zFkf%>!i(r-6E2kr=IhN~c=SgXVXd||nF;2EB_{G`*EUR8%TIo0W15*UV^qu+(|U$y ziC$x7%$OMS;rQROF>Q%kLAJ*b)?#LyX2|DG6@(=wRF5%)wbTj);hG<_?wYd?Y_qsJ z@#D8lxlVb_Eiu8&xYL#qk%(&SdE(lAQ88g<#ym!JjC0(g+^Jif0T)>bvgv_N*l)+NUzc_8{~%$OvocyAs6vo7d2X;+YI{vIRM^106(bIoQ~Hq9a#uVOY<=^I=SmN4&Z31*ax zS1~IbLs&~+xPq|6#5U_~Jp1msv#Z^8`JXZCU%zORXMVn((!W@Oi_L^PmFWx`tS*=*k4XFk%b z6#KCwoc0#@wFQ6YDTy|V@0nIbnZ(2<=UiH!a`e*b(#30zA*|)n<~A%b5qryNhb892 zg$+w$4>|46@XHI|soRE$*iTL~WPV4{O;{^-htu4b-&Ev;C9xx%#$A3pFOP3)y#4a{|GnP%XMG?etfd``(4A^_Cib{%pE*lRXwM;tqn7V}WQ4Vt z;q%_aS15@1bww%_K0HfGf;VbFFf*ne@dcfYUCx|gFc{Y+y-u;}J+hRBBmR0YK zznjP<%L!=uJifUFVH>e8I>YG0?*VKtw_%Bi*cY8?cB6xKsZ3bwH-CLxedi%(Rli^V z83kcU>{F-x3w{IQJ9XPI5j)UnFC%8Og$>`!TG}Hm2un=3XY*2-uol-@pQm*ceZI|` zc3p62_y-L*}3c?Z- z%-5Tp?J-2I)m0B`u|8;a(&N5ege4|ocX+DVLoP~X!dkES5J)AV|*0m(| zlc$=U<_Sw>f_Zhb13h>LhyCGFSu1}QFXoIMh z`_(eSTJq2ZA>ZAcB_?7-O*Udi8$|0LeDziD&j@SD(-?$&kaL!pU}nr)FnD(5=gbIe z$zvKeJ+Qpva7x5Pwz z&r_-Rx0|pQbN6OPxUgY~iP%q0zsum47r6~)#?9_IvzK8>o_fH>nIKY~i1mm`AJZS!^3#*o+~p-wo!HliL!YozCWurg_BCSCi<-NwtmPKT;^^nd z@?jUlY%`gPaC1R2`!T5k2+hTDW(XGF3_ zCbJ3q!vwj`h-8hdW@AcaEpnX^$r>5X3c?a{oe{|znan0El?ig45y=`^%?cZCt4!;` zpQoH>k>RW$$bv?UD-v>@5y={v%qA?A338ng$r@SB3L7q!wa9fwBx__iD+o)-bw(s> zWHOtuR3^xEMkH%wH7jhmRMsNb8Ii1!;jADmA=ep^tS^1|{0U2Cf?Q`rvPM?3!bVmq zX_4!UoM(~YtRO5Q*BLp_B9qyKr7}UTGjg6qRz*l?+=MXob)o<*Lof*{u!InN@KSxv4pa-KzwvN5GHVSD5{Bj;IU zgDPzJzT`S1=UHSj8)L)wH9@X3a-OY!0~wUNz6RFfPRnN*Cfp|EIwR*iTi8&x zw`ogExK4vSOY~sm|ClAW673$bwdtA}AlKwsVm%nym7?ZkW@-sblt+428Lh_<)*{am zE7r(9R1%SAi4|nz!I>q`5-Z5aq7+)OGZrO`nCqyyOJ#`(@+`5MjQmK24HMRK33D5k zm>|y*YtCOUCZ@rqGGVRmnv-XVHD}~R%4$oVCDxpgU8%5iP*G9ggthVG?Vyzb0l?ofVWcicm(&jcy zSc^PMtT`jQQendq6Ruxw!}TD~66^EGqLkGsC;XI{AkPx(^T?=Fl*)v)$g{-yJhCel zgeBxzVwDyCQX`{MVZ&`@E%Gd}N{#GF z1z`z!mRO}m7NrSGWr93QtWqPRQenfTvKD!kSfxgGrGl`8JWH%nBa706r7}UDC041C zQK_)uQduj1+R3woX5gWoS%QdsMbnmejl=cw*%En{AR_xv zMv!L-t;j1hYumjZd6pm|`%qRY6CpkiISH7Pop?-Y z%Fe&|H=E4dcr#Kg06vSHu*3xZ%_cMV7{XfIiMATGfq%2f%w6N(Y%+7RCo?QhUMk<$1pZCdoZ-nVN@c=Y_&1x(+y#Muv&qa|Qd!N1v@?KEMjOyJ*a&UPwnxK!4{zuBDaR1lWn z-)zoyny^$R@NYI}I~6uuDr@22Y|eHn2utv9HfK9cSSl0vH=DDa3L7q!weW8?XFC;y zCHOa+vz;a^l?nWt&DlM|j|7P+#ZFu_>{!Lbp;k_geeVV;e`rL*k z84+F@R+HhEoa!d1ih5Y$ zR^Xbi!Dw6A2L8?FT$#*XUUT2q1pZCdoZ-nVN@c=Y_&1w#WeNiSW^=C06#mWTT$u?= zWdi>uYtHaw7B*ZeYx#N0Ywq&m-)zp6nXptQ@NYKf%8V(MwcH|EsiyT@)p`eO{F}|W zGIdT^VuI`D{Vxdoo6Wg0Gj2Eho6Wg0Gr0{*Ot`e>hQ*vgQo0W>G3jOt^lz4c7zz zW^=AgR;QeB*-hZzY|fP_YHq?>_&1w#WeUO){F}|WG82}{1pdwDT$#d#OJyzmo2*j9 zt6311;NNV{m6@d^kmf+uHl^Wj52}@-H|0b){@MIP?TqPS^ z+2g+W^K5(I--HN%XKjfI{F~5mqRfWq9+qryWx`tedyI+rH_^s#tMX>^M3puOwG}7o zB4+>$>%s86 zRS}(;)=}ZTEJ}q(l+h=idd>}RJ)jv8k(y~86`sr}RTp8ch+Uj*;yDXK`-WA-bEegA zcrTORlQBQu-g$^tVgmnW6VEw@u$JrBT@MoxshQT!;mIs)_+Hj>tLHY{CJ~*PR*>Pn zoUlJkM5Jc&bA~5#OsT9DQJcxn8D7nTuq2{0lbDiaZ@nf#pL$t-NRRMv{9&E)3{uVz75649B-&l%p! z2}@-nA~lnrGd!7v4VTJV5w)58oZ;0h2umV5Gx<5gdpTjLOhi0q@^gkKv#^nsN?H-M znO2bD)hq~0B04jzAj5k(VW~_+q-I({h9|SI;Zj*EqBheCGQ64vVM#=1rWIs(FDERO ziHOupE6DI<7B*ZeYenp0T0w?yuOK2iGp!)Qds#)?Wm-XoUvf;TOxRvTxTO_jcz_BU zzAygGw1WKEI2*pNiHOupE6DI<7B);+i@z_QW%&EyHi_uWw1N!p<(Qh=hKY#OOe@In zWR5A7wIXUWtsujzSrC>)bY@yXhWB#9QkjTI&9s6HPiA4m^{`e%ZKf4ucr^>cl8DYs zE6DI(PFN}v5viG0km1QJY`9d`im1)Bf()-_L0E!+vx(=Nuv8`@QZua}!;@LqaH*`7 zKkaxcnaL2{=+%VR1M<+ttOrjb1QC?-xb@|!>>s?`qZkA}R0!fBZNvA?3Hb--EHNQ3 zVA#MTiVfl+O<2pN&HS} z8NSG@wh^^C)x>iaHgbvEr?)X*gVDCKjfl>iYT`LFdwI>>RwnRoHu0QAsZ3Za;v=V; zc+P@|=*6ifp0gj(nNv+X=Y*v)fq%1!=PYcvRMv`k&f)Wx*WBfe=*+1mo^!%dnTSZu zsV1ItOsTBp7D=T_?>TR6JXdK28J<4g+H}oZ8&Qqv7p>v-8`u~UmYCqWegAVC8%88_ z6VI8|HexVmnt0B_MlM>(ybMSQ@jy{&)-)!PJLu>gc(ftmZz`xnVa~3vyFKgl7Y~nc!!V>(OO+4p> zr80qkvx(;{Y`9d`!oS(Xa~1^t%_g2R`8S(*&M~DjVSD&Dn|RK`27c4_z7d^yIjhw0 zUXHQh`>(yb4;nMg@3b&=PU?I@NYKp zoD-JH1pdt?p0lvwwz3xf%_g3+AS}VZ*~D{BSSl0vH=B6Q!iGy_E&Q8JJZC{zf`7A# z=bW%qCh%`I@tlPXm&#iC(~h??H1Yb)d6mL-JKs_4BID!mzr*Hwy(>3DD?D%g@Q%)~ z<_I4i*KOov5Q>A$Z1}!8p*YAnOH3%*F>K%wrC<>UnGw0x^3rB;sg!CsyW_fD-QmTg ze&N*|)FahD{GD@_m~bm3&n|t6zcVAOg?|$p;qM&OBN5cY5)*E9?#_SoMX$HR4xgX7 z>$RV%@7Q3weq2wr*Z6|De&U7Ory49L$X1VJwQH;X@H+BEM;__)_d(`*^jjON9Pp?l zx#xjx)0`TbIkjyM^jpFb+Nvd}6W2U3-GsIBIt`d%&4;x$5!dPO^V%>m)Qb95l#2T0 zrLx5LjXEWQR_G?IMFwqb(CRtyv(Ifai{x)>ZJRvqT+?QU{A0WH_ucM0awaD%i4r6& z2z=?#v_>~!E!}CVlSscvXzwd}GGa>gOV2rW20h5xKHQfK=Bh_J$A-U?r#>$gzu#;n z^AWM`8AG%*TAWwJod&0j4Xg}GWr+!XMKU1TGPU(EVXc)s6H(80EEz*sOYh1k(Y|*fS$t7!olH8(znA70-0CG4J~^l$eO;IQ@Oz_hU#{E8ed3_tEzpPYgZ9D8rd* zTr*nW3*$QeEyfZ{OvGsniQrU*!86i+IZap#&lWZq!*aqB6H&563{LYHFoUNg#@$qQ z#_$*)(=}tQ>zCWG#6F; z2Zs_9ZuQ)T?`5s{GNe24Ey)Q>Omz3432SvfyOx-UZ&xbS=+kb(THWuUXTqL~cF%V$ zG2wY|-c}~8b=xjg>hpN_i#N&=6P$6$8#SJ=)`_>jC=uV@lixE8{u{hemYCp-OKk8h z?k23|cO@q*nU7!=(oM89THWv9d~YIYF#Dt!OF@&|$ zHw9sd2|Yby2y3Zt3c?Z-dV0nX)@oat_j3OJKr$Z@BXvROY2fRUo>xX8eM<_$5)=A% zjUlY1k!Uurheo)RZ>Rb8&1!Tl2un1IlFK{Qi7!NM!-Tc;T`34lOz7(~hOm~tqD5O- zV!|z**TaOh+NWf+&n+?GXCb#?!dmU$N1sIZv-_jF&n+?GXCW_@32RXro)}7(6PB3J z*KQ19EqwCn;&pdc(Up*j2*!dhCF6oe%v zv=$jd6k6xe=j=V@HIM%_loUh{g0EgTfuz-n(pK|7SEZyS!rlagwW8G%!B;OYl_e&k z-4emKv74|~^kyPrtyU10nD9PRZX=%XVGZN$8eTK!p%wV*<;2iNJk`VNC`mVAiHUgf zlZ{y26*f#*%cadr6=Ox8@-kYs*Nhf1+NHlU*5pL|C0S=YjPWX6Gn&TtF{TQTHU3x#6*-V)q{~Ww_(CsZ7Ym^Kito5QMX8L!x9rQ2B(_Gs;KBe6V`IO zHcVJ6?wttc5qUie#q2y0@$MIdB_?8i zJpo~@7;h87S1)hf7*~^o?^CP|(lx%RSnsCmQSXu^Ch$oz#_aKvFBSeM6V}q-3-6Nd zi?66HVI{gCEHTk-!|fw`_*Rm=(YCV0gzOcqYr8CC>TGV~$Jb*qY95n6Or4B(A>u z?PF_BV9g2Nm$>R*oq1f%39hDd!V(ii6#wnE<7&==?Ix_%U2~#(S32&PnzLDn3Eu3H zV`@%wwe4;jCWuGg<~_&OoF3avSgX6Oi0b{fEsw4_o0XX02mkBnn$uh-E0qc2k#~B^ zF*T>hc9+UpZjqcIUiZA~KVEaXDiOZ__U}j4oYUG}DihWscK1my|9H)*tGNx|m$>7r zPC2UP#8}fgVTlQ1o=>cgN@v=36V`I8=L9jj`)_w-%}J|7`0jYjku@i{+IBZ#E#i20 zdCZYDr>^FN?@J8wvp;`i&55z5bHWl6#5v!0!;v+o)pirs>h2FBd>_Bf5jE$r5)*vp z5l7UV>}uQHHcSwMyymq>)SMpMO<1eDt%!47_mIPDP9-HK_{#e5n)6L3E0qaikoWw@ z;Weknc9+UpZjn*qZSOs_rW8c@e()oQ)||~cS*c7!Zsh8iV-Kx43wG27-wf_)En=P* zFFZ7zX`2(o&z^AUVKpb85{Wx~>tQwLrgoRgT15E%`JuyV&S~u?EHObu@gZ9uUUL>~ zUMdsTa?j=j5x3vl>9Cr!Qi5c5#0UTG{wvTD zmw(~VniGRrYq_5Wvm|Cq%xIYBFhgP%Lr$V|9`%VjvJdflhBPDN@1q1ydr6QF z>ELsYuOrXT7{XevUv9$^6J#4&;n~O6kyog&VZvHuH=162TphWK#t?BTN%ih4kE$bU zPeoRsKQBD0j+{RQVF|g4?!W2CI`Rq?J;)riZC#hj1R0I~`*TOuk;ka8VZvJcy&cE$ zwsH;Q9Gm{LPdl!TJWmsr$^?0&KKs{W>&Of=rc~C7b5r`4pLc8>d4&qX5;7Wn=2gem zk*{dNQkft((p!FeOdXkl3L9=KYmseew@)5ZM_!?Vu!M|8Cq3<$I`S1wSSl0ba$4uh zN7s=nsj%TvS=&)sY0X)wOhk-(8Zr1cJFPh*tff8KAaq(Y(fz~G$0H6krXG|! zJFS^m{h`D}ZbPRvXN0w=JvOM@AUgqV)kOCXB_>>_K~z6PM8{8SuZLf6B$^%1cF$q3 zt42g|OITtevYV$dnA4nd8z!t3xxCZ3%h|;_VM%2FP9rC$9s5o>VTlQ%`WZzd8h@sn zu$K4da>A0x%-v_)jmY(x$m`u_+~pkOoUnv=ea2nRO7@*{!V(jatGv&+%h}A`gtfR6 z>_gM#lFv?sCGlZFk!+5!t`fxXWqB-GsFwcX%3iIV(9QEQy@tea2nRV4kd0 zCL;THpK+Jdj&mEnm$f2yc%N~XvyyYdlE_KkXWZosX5T3%EHM%J(EE(Lod4WSSj*2? z$~BqB-6k(*n&S{(pf@;0YcVnqEjEa3IF_sXm1<~Z?91=umabIG} zymvN;I)iBPat=#nf*3jIUhfI#qdWNZ99O=Vwe#z)S;?z20{$=5kyiHR+5cy6D)z85_0Q3Vm%*!%3zar$)R zZ|}43$9dI$3vwIQiX8EMb_Y2VyPL4YMC7OMv+o!A8{%nqTbZzy>y#6gn25~$eRc;q zSG=3BR(D%Pj`%*igPe&SS>^le4swdNOPkxU#6)DV@3T9|somX#wcJlR5jo=f><)4! zc4U?BvpdKs+P0k&mY9ev_I-8-Ikmf+u$EgSCnC#xpWQ)DwT^u8eRc;qAKSLO32R06 z_ddIWoOYcPzHel%@3T9|N!_M%!V(jaDZkI|ASZ)&6V`I8=R{MoUu$YP&%2RXI7o3K`QTSa#Cv^&UY(2-|7?G8pBf(c7yBC^=0 z-9b+6?k<(J+#;hyJG+Y<@o9IEGqERYD-&dOV0Vx+xJPZYUTlNB;J-I~e&5#WLC)aLOXYi6%RQSDk+VJR4su3y zWPDG%gPd^fJLQBWCL-H>+8yL{?QX(aZo`~#yMK4DJJRl8WcJv~wsXP~6Or*f?GAFn zbvI$H$QPe>2P2bpY!^uxkQOuZo-*+Q2BZqW|*DqrnPe(QULXpSc@AFxE z?eF)!*4X=X&p&g&zSs5M*R|H#d+l}YYp-kjyW6x~Z-azt;D@J!{^oZ*K`oAxmU}yW zFGQ)GjZPdgxBcc?Yj>Z#d2aE{jGyNjcM#0DlbHFn4|g}*<$_|*3xBD#4{ea3mjCY6 zpmX0TL9hJ#sWVRT8~1AU^_?R>IJ=m5_$3)Z$vWFD?Cdt@tYX1t^Ey0Iy$uq(pK)(z z;puaV36DApz;^Ih)Y|%(6`kq3o?CospZ~}RO0IsT)xG^U=M}RzzF|bKNSwa^THTv3 zpIfy5?2JjBSJdLzv|1i(ae?H!2LA0a@L2rv)>}J=uK$f<;b5Z9k2-={?2(k9gv4k6 z__NNpPnlb6wD($>4HDE^bcky3?s0Ch+7&C*a(ZQ=Ix|R5T6$sUz2}@!ocV3HPNlUoS41@l-Z~w87(&czxLwovUN5HFqb z&j~@TgASh;Y}|N>E90GV$kIUk{tHJ9DItNkjYYh1`|W|4zWC^bpw>H=d@IwWxufDVAuiBoecRy_HjNo|e zao~k*-vK^-vfn8gr&F&eAu;`htJ@D@J+*r4!C{XeU0QQ8o-Vvbb^IRM@scNtuhiSny0h@?;}s_9 zl%Rx!)}V!FIIleG32JFYS$G!p+A$?4QA|*HKKH7Uwo`%<5>u|Zwb<;%xy7yXGlvJA2*BBc%i-B(z>H zJZpQUTu)GoBim}tT=3O!Ca!tKb%Q6rxPf0BM;UR%of6?;;o>x4Vmado@ zi2fYEg*5fX!vb;q#*YsuA)z~e@X9OmR_ppJjts=f%kN1DYOzOJt$n|6R3KIyx-{u4 z5}I#=4X?~wt$%*vm_Y3Ct_2A}E%sYj8SC0D*I8N_hk4g4Gw)jUwc_e)H}3y%vCr}| zi+BBIxtdjrqAUdxeAZBRl&E6RcAU9aWp32L3U!NkGr z8_zAib&kIwO|N)1@GQ}KeGt~|TEC|RB_yh`@jAPnpqAF_1JCnbbEgC)B-kVM1huqY zANY>rReDNLLZY^>hFTeiSk5@=HcK`o3^Mo^LyK99W~O1)w` z7H>9j@WPK2rQCdfpB|t5PU2}(%3 zdf>ywa$U8PpIE-Ao}iYGG=9|{Ik}t@XMFd?E@m}9w+i#1@8wlbdo7pDiCs!aV6GIg z%9Z7u_}H?05`tQoyF^@gS2-u1cidfFN=RT96@fW1A*h8pQ3UQ$T}nvcP9y^NsDz*v zW(g6vM|CO5iFl6^f%|#y%K!SvVCL=@6f@SmGZ_z#Q%Y!c8dj-Zhics!W&^J_ai7m@ zP(niM(J)_mwVB!=L9KePC?TO0Wtexpc1&%MpcZ>1B@{)3yPBg4dbqV#oQt*M{M(M_ zXErDy;oosxnh~_2C?Z4?juA+wUQt3~g4S?5Y7KYs8dqjENKlI-o23mNj*gIp)QJh)UyR5Z}sju_Gns^-7SGD$nM{w8oESfM@%*Z* zm2p2lL-y4fuY2e#YtA1S6|!yU0t<~BK&u+rc#0u5?XzSjH1`v^+c*w=M}ZI+7DSoubSC!sSQd{Lg9`L5bGS?f9g5M6XC_UEPjPpv!A;Y&_@{wbGGAKFTxo z*r;(dk=c@m$a(cBA>k(=9&@ieb;lXct0e@rkf9TS++B|n5`J1>8(u+==Lh#%d~`xk z3zpSUa1PB}0NX{GLaA-k#V?ZSc4x{%!qhIv41j zfJ+a0D)Wj2wK%f6vd7=7>G_?A_=Gm`L@VQNd?M@_90Vn_r!%nYvt7O1Kv2uSeI~9< z(5q**o6x=L?(>SZcD*6-F!hR_knkHE@fmXF6$xtjU5WT~I3pm-LPGOx zu;CSSt98rIz7mM8eONodWZIVh|IhFZ^tk@DUiziHul#VcC>-9)+P zCnqWiiK8}nx%1#zXBP+j+It#E&@2D0Jn`EV@oBB>kf4M_H8x&5))Um)@Vnb}m;CS> zMQ6V$89@mNzmE~0?`8xgB$c8!zn=V=4=XS4d>j`SH zeJMdLzcJ!_iPydL1SKT=c13)K+)izfpqAgRh|iESf|85g_j2c2T}7Au^4K9>J{EzQ zIw7cq8C3*k>H#GrFdvJ+Oq~$a!i*{cGxdNH61)nMnK~h;#j7i+YY=ut`&!eE-+`+W zxJrSl6(p5IS0+5y=7g&gxJrSl3V7W?Ry)ZUhv z^%Jj1V6VQ${KZvw2!#Gm2x{rrVa``OMWEV34^sJtK>u1?_9t9qbE2?@3-sT4B&`gb=9yJA%#FVwfI#(-nfOn3}D zYOaXqy|1c+rx8TOlOZKMF3-1mf?BSK=iRcZ6PMX=MLh42RlU1V5zl*HRmm>9KIjz* z+HgfY@4Hpix6H;TcUd#+sr7MP5zjkhRqw9B29Ha^74f|HRkiOj8ziVz-*Q*P^WIn0 zg9{b$y!Tc0?nd;=HS{XN74f|HRkiOLyrNcpU%4Wl_r9uDTd0WVy|1cwH=3QXfc;5S}dUv5Bp7*}0l3jyWBsey%i08eps>qgk3IsrFrFgG8c*UQb)@ig>P!rwVz6E8==Q<{dl+{o-5<29$cu1=gN4hcQ>L} zuAx^Eu88N#c&dHZ;1#v%`^pvZTp3Sw)Ivo(SH@GlyAi!|4ZVtRMLbu=Q|-G3uc*Zy zNzW4ZZnai(MLbu=+vu+EkLVQ%SHuf@U;o?BUODe_1gW+Df-Az_S5<1u2v@{&Wjs}P z3l;HP8BewE8oYAdyh_Uz@mv{C_3j!7dPTw&@mv{CweK>oNKlI-o3`8)@mv{CmDfT= zJXgk3y}J>;at*zTa78><##8OP2Ct~aK1{u0zq=ydLRH37y}J>;BH@a7u8gPJcMV=q z%N6ll8BcZaGJ+CU#B*gl)w>(fD-y1V=gN4heV5tb2vUpVRMv9x`bt$W2Cj|b^^U59 zgx_8*`L}C1`R|I~wIXx%r;4D&bVaz9lOtADZE7H>;#y9QQdM_n;95?OMODEmvq6b#IXOyI zr6y^OAF1933Dl3M)Zn=YdJYeRn?}<2K$OyuI1z?RTZ2vf)dwqa+In{O(S|m z!nK?nrK)OEW`kZ)i|1HbnaP@}aMaUv7oOe6t2X3M{o56rd_Ag;QSi|E{x@4!@9b+W zQI(+qzgeArb=vi!tgo6#i47h%C0zZq>%gKb>K?w==La1WZG2wQQpq6VnCG7}=+d&Bl_IkL^LtGo@ z-LX;QXu6h@YdZbyRlf(I*=LNPgoJB3B{TI~64Y`nC&#s_;FQ^*goJB3IZ9Q%qKt4Y zC&!km88mP$Cr7NR+9a)Ph8y#WTCU~fxK@>#8VDYXgljoDVpR>M%qtSqVw=+5rG$iQ zIXSLX)uzk_32N2%m1{XUu2m(YfonNAN>!z%5nE2ewVWK+s%lf_6sn5ZYgMVK!3K{@!nK@S(@9mEG8-hQ#a>Ta?pjWcYgOAR)N*oMs~SuV zUXh?Z*K%@Pt9nJ6aXFW`MpSiN*K%@Pt4d7`Hh5eTuI1#oR#lrCT28I{@o+6C$F-_t zRJfLtqf}LD3U`ZY-Icb3UXgGuC&#s_+LX1N1hwk>%C(#v*Qx?g;aX0PQdOyGM6XD= zmXqUJRc&hUidyWEm0Mn|?p({sajhyfjp!8#*K%@PtEx>6UQx@noLuo;HHI?6wVWK+ zsxDFCT278wRkf+XD{6&WPKs+)si}eB2$FCur%>^I#-B2;NKlI-oA$12IXSLX&7i`y zoE)X9QqzcDk#H?1$F-{3)Zi7h*oUcC?0464a$KuQO(S|m!nK?n*Q#n$gICmYEhopd zs^F9nl(?3Y<62c}8qq5fuI1#oR#lra8yrDuah$?4fUY%_?{v-Of!At&j_(|5toR-> zrJhUt_mzoCLc%%JSn<7qpq8TW5Ig(-)CMIaoI{Nj-x~;OIfoi6zBdrgp~i~uA&2TH zRhiR_aCWtlIENZ5zWd3<2<;%@9BQoip4s5BsO7(V9`pZcU$KSGp~i~uBYH)`In-G3 zJ+nctsO21LtoWW0lsJd#C{-EK5xpYe9BQoip4p&R)N&3rR(#J0N}NM=l&TErh+dI! z4mDPM&uq{uYVjNk8O5HjL1jptQ4HsguSNg%_2}Qq8;0M?oNCSBY^4eRudH6UYW=@6 zl)fI7^~=7{tsG<^oP(qd9@muVGS8_TWFVY_q=bYrjlnDBSLKznuJ+0~ND|bdw`Ge> zD5vW0O^nSx{$0&0Zn1m8c0=Ad*l>F&A;De!;tJtU}Q|82vbmj2r-w}%oEX*)c7 zn$Q#Ou5+mID`UwBve(P`wvKSi-5%#q<5$MiyR<ifz$)cBRLkVAFMsSN3eUODSp5ze8;uZ-zz zuWJXj*dr<79BTZ^SjeF|=2Y&p!7CE%H|J2}SH?20oSUtV>l|wQ%21m3FlDbSH?20NKlI-oA$1AsPQXfA%_~jGB%=D&bn5F zbExqvV+~$Wi+z}S#eR1V)iI|sq$7Go!a3CVm9Yk|sO21L{K{BHP~seF{L0vfUXgGP zHGX9*v%wLh7RRZ~p?dA(r)$o@c)jDN^ZxBsn14Hm>c9JmaY|4^!Z}n&tjd-)5Y%!G z)lsT4rx`(sbEu9pl_4F`D-zD3#_!|k-E(I#s+O}I)N=08Ew^4uP~seF{60?GIaJ4@ z%A964C~*!oejmqm=trL^ti(hB$`l$)L)4iBb)^_?VKTPml;tL%8+&_A>sV3Y3uo)GrQ$K64b)q)mP4;THoLK zfxltCs^%_uE5bQc6V44&f|k=;5okGku}x3VCK1k|+D7;?(0KnO1lyEcgZ?gA=o8Jg z;oX(kj*vr*-^WpZVZQ1)yIM)mj_|fioT(cK%yuD%8o!T|5zekw5)#g##_!`~gmb9z z`#62)P~-P;`aGx8c2LVX)cAdz27<>T;T&rGK2ATiL4sOrQ%X=m!a3CVeVoh&32N2% zm2;@hr7DBicMjE2sxqV_ww#1>sPX$anOAH%wKz^`%bi1w-^b}Yhw3O*8PXBGBHDSJYyUq+U6P8o!UzcMjF@r*fYSUXfrgIENa)kCS=D<2r{LzmL;kgU2P|9BTYN zPG*Aywb<)v%bi1YT&oOe-#JvrpUQnUctwKtoI`b7t2|-m6_4v2YWzM+gmb9z z`#6~m64a_659d%F*D8a!$T?I;smhQp;*rw6qJ)HVsE%uuEp70MTJ?S99IE45W!@G! zhw3O*8PXBGBHbO?H311(2@}CgeKN{ZnRqnHapcbO=PHKY^654SZ-WT@wvFizHY1d{E z_oX%v+A|n(ss6&TbEu9|{jKcO1|`~M8gi-rCN{lI2}($4$7#r=`uo`R1hsr5&tv*O zBiKUiGA$gX`kUCaU2lVgcAOS*Uur{NQA@i|i?}Z}BPekWHSS9tv9CyI$7#r=`uo`R z?Vy%+pN3qjzm=U5lsJbP_oa^L6$$M)4Y^c*A3L?dey0}Cu_Qk@M82+z{9p%JK-qBC z)p3;fby7mYza2s9>J{OPs0r`VB!OIEhqjZ9V&WAEWE3^#$nYivwUA>K;T)>H@;+P7 zGWOSV31=MSZbcv`?5}`V`Q?O2Z6GI{5Y$4pS2mCn9#TSrZA#u}=xJYSh&h#0?Qje@ zHqC@*RF9f=pN7a%nNy9R^R(_O<-U59@VGqR>IrITcV>uEm08SeXqRb-OqC(+X#Z%4 zIhFg&t`B-ef;P0*GQ_*e6J|DeTsWp8uz7U1SQU)#(k-Y?Ru|B zXb)yP?n}*Vu!X5s>!V%)Dt=e*vgKO*jY+g;upRfMcAZ0Yl&Z{WW`h##GHu6wsnQxh zQoRil+Hu;B`%*I-JXWgpi;sBbTe%%v4$e6KZLQeyYDcaJ?5}k@#v~+C8`xi) z5Y$qe!jY6yl@08#9a2JqZ3@?Uh_;m>4Wm}|yT_nvhjyQaH-VKol?}~4V+186G>-*Z zxxEI0TH1XY-Vs*jG$SY>p}m&jjbG&nGeY|v`*B}tS36GoabK#mvKely9n{h;(|+8S z+CcDFB(#6DANQqZUXh>{+m!Y$B_y=tv>*4SW;RGrtG=(CLv>uM3}V+gRL8Z-kdD}L z654UvkNZ+Huh?>Gah%eYYlmb%?n~`Dhw8Xi8PXBGBB33p{kSi+!7FO9M^dk}%d{W& zrFNY|bzH05XM2P~*PTawRi%4f43!W!jJXQX6dWxFodWv>*4SHnf~t_2c0j zYTTFFaSk=^OO@|+a|tCRoI{QKQnQwmpjLffIfokerFNV{jr&qZ^ooRYsBvFvgICmI zkECab+fl9VoI{QKQb+WPgm#=RjQdg>yrPzKsBvFvMmUEW_oa56Lv>uMY-xj6)CxIN zJ|Il zIaJ5B%8-ue6$$51RFuPz(^u<6?ZaqN?43@OP8(iVH+jUJ*9j@{DebO!gQsz@pbcewv9V}yqawM zdQ0y@S3Ax)b4W=}m@bL6-`yLSm~@t6P8`d>E3JQ@vv%7yK6B_Qvhn;)GXwF_qfQx8 zk`ty&;@AVruV?@DeJ3V_=}K#zshklc( z3DYI9&3y+1V*WX+Cxq!rYyMe(4mMtU{3Q3)Uk?t%yDxujKuJ!RE{P2uo*9U>_g$6{ zrYo)EX1o$?Ecw=S**O1>BLZ>hO}`mXk`ty&;b=cf9;(Q3WF ze^o)kzbh@@o7@iFk+imW@}7#=G~Bf+NlutviRkcH{#|LowpIY}szXUmL=Q!vU=T}pDoHgsNzz?qm3I7|At3Pj*+?^2Qz zwxR1o#ChXaR6^iv@8fC~QC+p~-gjA-lAN#&UFRY&Gb9AA+CF9_5!LMTZ|AJuqa-J6 zL-Umg%y0>T*{6@$RRm_y9wj+p8=7}TR5SJQk4#Po%%XkVB}CwE(4!UlCu~FO5)oL*Bm`C&eXOEHY&yPL>QRytwxRWviSZR#LSVJj$7)anR((B6 za>6#WP85NaWkO)p*TbMJBEtJfYSIbj=G?~1?*IU%rmEwI)WfmL{qlAN#&t=mOl zrJoR3g%^l2L?D{zQIZq3q4+}tB9??eG*LKu@tsIfkqAUZJxWM8zOoJ7Q$!&0N(gEp z>Jx$Ju9r&2kBhiX1R}_UpcbN65l@UqsXa<^!tGF8D*};lLLf>l5L1glwB4g5Cu~EJ zw}=(D-q;PX+SSJ;1fuO?oqwI)_jr6{A74>Fj^Dz*NZ-PyBqwa6B$mJTo?zqBB}XQN z=}K$rxrYZE?_B3EvN37O1A&8^;yuRCWfw*PfjD#>?03P&w0B%1 z8$aK6w?J&V%Vs@Fa>8^;?C>xDD-Z{6^PYq-U1`m{^O<1d$W!LZ#$l883&d_q-_fHa zCrp>bUWXkLh-Hgk=#ud7O6xm^y&P&2W zLYS_!EVk~Xda5jfii zl;nhM==u?)#~MGx5KJwr-z!ZtMTioi^r5ST^VxJ!t@-C#&bPS}R-A0k$bcbo&K zO-%^g4cfTdiNIZLNJ&oEhVFwRaOX@2+|}B+Ym30$c}Pi4*oN-sBCrBT2;809Sbd1V zDq~1VPS}RlB_gnrNeHYm+E_)2z-nnoNlw^?)>k61B1;IYmfBbiiomLGNJ&oEhSrH9 cu(C`Dtoqtm)oLci>NUwO<%DfG)6{DHe@U_kI{*Lx literal 0 HcmV?d00001 From c8327ae27812647fafcead9c2e804b4b9782b664 Mon Sep 17 00:00:00 2001 From: gem Date: Tue, 5 Mar 2024 19:53:21 -0600 Subject: [PATCH 133/232] Added ability to read from both GEM e2 and e4 sensors --- GEMstack/knowledge/defaults/current.yaml | 14 +--- GEMstack/knowledge/vehicle/gem_e2.yaml | 13 ++++ .../knowledge/vehicle/gem_e2_geometry.yaml | 2 +- .../vehicle/gem_e2_sensor_environment.yaml | 6 ++ GEMstack/knowledge/vehicle/gem_e4.yaml | 13 ++++ .../knowledge/vehicle/gem_e4_geometry.yaml | 2 +- .../vehicle/gem_e4_sensor_environment.yaml | 6 ++ GEMstack/knowledge/vehicle/model/gem_e4.urdf | 8 +-- GEMstack/onboard/interface/gem_hardware.py | 70 ++++++++++++++++--- .../onboard/perception/state_estimation.py | 17 ++--- .../visualization/klampt_visualization.py | 4 +- 11 files changed, 111 insertions(+), 44 deletions(-) create mode 100644 GEMstack/knowledge/vehicle/gem_e2.yaml create mode 100644 GEMstack/knowledge/vehicle/gem_e2_sensor_environment.yaml create mode 100644 GEMstack/knowledge/vehicle/gem_e4.yaml create mode 100644 GEMstack/knowledge/vehicle/gem_e4_sensor_environment.yaml diff --git a/GEMstack/knowledge/defaults/current.yaml b/GEMstack/knowledge/defaults/current.yaml index a09532ba6..c886288be 100644 --- a/GEMstack/knowledge/defaults/current.yaml +++ b/GEMstack/knowledge/defaults/current.yaml @@ -1,19 +1,7 @@ # ********* Main settings entry point for behavior stack *********** # Configure settings for the vehicle / vehicle model -vehicle: - name: GEM - version: e2 - max_gear : 1 - num_wiper_settings : 1 - enable_through_joystick : true #turn this to false to have GEMstack enable control - max_command_rate : 10.0 #for hardware, max rate of commands to send to vehicle over Pacmod - #using !include directives helps maintain reuse of common settings - geometry: !include ../vehicle/gem_e2_geometry.yaml - dynamics: !include ../vehicle/gem_e2_dynamics.yaml - limits: !include ../vehicle/gem_e2_slow_limits.yaml - control_defaults: !include ../vehicle/gem_e2_control_defaults.yaml - calibration: !include ../calibration/gem_e2.yaml +vehicle: !include ../vehicle/gem_e4.yaml #arguments for algorithm components here model_predictive_controller: diff --git a/GEMstack/knowledge/vehicle/gem_e2.yaml b/GEMstack/knowledge/vehicle/gem_e2.yaml new file mode 100644 index 000000000..4544313b9 --- /dev/null +++ b/GEMstack/knowledge/vehicle/gem_e2.yaml @@ -0,0 +1,13 @@ +name: GEM +version: e2 +max_gear : 1 +num_wiper_settings : 1 +enable_through_joystick : true #turn this to false to have GEMstack enable control +max_command_rate : 10.0 #for hardware, max rate of commands to send to vehicle over Pacmod +#using !include directives helps maintain reuse of common settings +geometry: !include gem_e2_geometry.yaml +dynamics: !include gem_e2_dynamics.yaml +limits: !include gem_e2_slow_limits.yaml +control_defaults: !include gem_e2_control_defaults.yaml +calibration: !include ../calibration/gem_e2.yaml +sensors: !include gem_e2_sensor_environment.yaml diff --git a/GEMstack/knowledge/vehicle/gem_e2_geometry.yaml b/GEMstack/knowledge/vehicle/gem_e2_geometry.yaml index 11e3fca1f..ae6e3b3ba 100644 --- a/GEMstack/knowledge/vehicle/gem_e2_geometry.yaml +++ b/GEMstack/knowledge/vehicle/gem_e2_geometry.yaml @@ -8,4 +8,4 @@ min_wheel_angle: -0.6108 #radians, 35 degrees max_wheel_angle: 0.6108 #radians, 35 degrees min_steering_angle: -11.0 #radians, 630 degrees max_steering_angle: 11.0 #radians, 630 degrees - +urdf_model: !relative_path model/gem_e2.urdf diff --git a/GEMstack/knowledge/vehicle/gem_e2_sensor_environment.yaml b/GEMstack/knowledge/vehicle/gem_e2_sensor_environment.yaml new file mode 100644 index 000000000..7649b4431 --- /dev/null +++ b/GEMstack/knowledge/vehicle/gem_e2_sensor_environment.yaml @@ -0,0 +1,6 @@ +ros_topics: + top_lidar: /lidar1/velodyne_points + front_camera: /zed2/zed_node/rgb/image_rect_color + front_depth: /zed2/zed_node/depth/depth_registered + gnss: /novatel/inspva + \ No newline at end of file diff --git a/GEMstack/knowledge/vehicle/gem_e4.yaml b/GEMstack/knowledge/vehicle/gem_e4.yaml new file mode 100644 index 000000000..78785ab03 --- /dev/null +++ b/GEMstack/knowledge/vehicle/gem_e4.yaml @@ -0,0 +1,13 @@ +name: GEM +version: e4 +max_gear : 1 +num_wiper_settings : 1 +enable_through_joystick : true #turn this to false to have GEMstack enable control +max_command_rate : 10.0 #for hardware, max rate of commands to send to vehicle over Pacmod +#using !include directives helps maintain reuse of common settings +geometry: !include gem_e4_geometry.yaml +dynamics: !include gem_e4_dynamics.yaml +limits: !include gem_e2_slow_limits.yaml +control_defaults: !include gem_e2_control_defaults.yaml +calibration: !include ../calibration/gem_e4.yaml +sensors: !include gem_e4_sensor_environment.yaml diff --git a/GEMstack/knowledge/vehicle/gem_e4_geometry.yaml b/GEMstack/knowledge/vehicle/gem_e4_geometry.yaml index 1d671864b..ec4a5c506 100644 --- a/GEMstack/knowledge/vehicle/gem_e4_geometry.yaml +++ b/GEMstack/knowledge/vehicle/gem_e4_geometry.yaml @@ -8,4 +8,4 @@ min_wheel_angle: -0.6108 #radians, 35 degrees max_wheel_angle: 0.6108 #radians, 35 degrees min_steering_angle: -11.0 #radians, 630 degrees max_steering_angle: 11.0 #radians, 630 degrees - +urdf_model: !relative_path model/gem_e4.urdf \ No newline at end of file diff --git a/GEMstack/knowledge/vehicle/gem_e4_sensor_environment.yaml b/GEMstack/knowledge/vehicle/gem_e4_sensor_environment.yaml new file mode 100644 index 000000000..a0c611b37 --- /dev/null +++ b/GEMstack/knowledge/vehicle/gem_e4_sensor_environment.yaml @@ -0,0 +1,6 @@ +ros_topics: + top_lidar: /ouster/points + front_camera: /oak/rgb/image_raw + front_depth: /oak/stereo/image_raw + gnss: /septentrio_gnss/insnavgeod + \ No newline at end of file diff --git a/GEMstack/knowledge/vehicle/model/gem_e4.urdf b/GEMstack/knowledge/vehicle/model/gem_e4.urdf index c2b1bb728..5ddb5a0eb 100644 --- a/GEMstack/knowledge/vehicle/model/gem_e4.urdf +++ b/GEMstack/knowledge/vehicle/model/gem_e4.urdf @@ -286,7 +286,7 @@ - + @@ -312,11 +312,11 @@ - + - + @@ -342,7 +342,7 @@ - + diff --git a/GEMstack/onboard/interface/gem_hardware.py b/GEMstack/onboard/interface/gem_hardware.py index 2242e4498..65596e3b8 100644 --- a/GEMstack/onboard/interface/gem_hardware.py +++ b/GEMstack/onboard/interface/gem_hardware.py @@ -6,7 +6,15 @@ import rospy from std_msgs.msg import String, Bool, Float32, Float64 from sensor_msgs.msg import Image,PointCloud2 -from novatel_gps_msgs.msg import NovatelPosition, NovatelXYZ, Inspva +try: + from novatel_gps_msgs.msg import NovatelPosition, NovatelXYZ, Inspva +except ImportError: + pass +try: + from septentrio_gnss_driver.msg import INSNavGeod +except ImportError: + pass + from radar_msgs.msg import RadarTracks from tf.transformations import euler_from_quaternion, quaternion_from_euler @@ -18,12 +26,17 @@ import numpy as np from ...utils import conversions +@dataclass +class GNSSReading: + pose : ObjectPose + status : str class GEMHardwareInterface(GEMInterface): """Interface for connnecting to the physical GEM e2 vehicle.""" def __init__(self): GEMInterface.__init__(self) self.max_send_rate = settings.get('vehicle.max_command_rate',10.0) + self.ros_sensor_topics = settings.get('vehicle.sensors.ros_topics') self.last_command_time = 0.0 self.last_reading = GEMVehicleReading() self.last_reading.speed = 0.0 @@ -138,47 +151,82 @@ def get_reading(self) -> GEMVehicleReading: def subscribe_sensor(self, name, callback, type = None): if name == 'gnss': - if type is not None and type is not Inspva: - raise ValueError("GEMHardwareInterface only supports Inspva for GNSS") - self.gnss_sub = rospy.Subscriber("/novatel/inspva", Inspva, callback) + topic = self.ros_sensor_topics[name] + if topic.endswith('inspva'): + if type is not None and (type is not Inspva and type is not GNSSReading): + raise ValueError("GEMHardwareInterface GEM e2 only supports Inspva/GNSSReading for GNSS") + if type is Inspva: + self.gnss_sub = rospy.Subscriber(topic, Inspva, callback) + else: + def callback_with_gnss_reading(inspva_msg: Inspva): + pose = ObjectPose(ObjectFrameEnum.GLOBAL, + x=inspva_msg.longitude, + y=inspva_msg.latitude, + z=inspva_msg.height, + yaw=math.radians(inspva_msg.azimuth), #heading from north in degrees + roll=math.radians(inspva_msg.roll), + pitch=math.radians(inspva_msg.pitch), + ) + callback(GNSSReading(pose,inspva_msg.status)) + self.gnss_sub = rospy.Subscriber(topic, Inspva, callback_with_gnss_reading) + else: + #assume it's septentrio + if type is not None and (type is not INSNavGeod and type is not GNSSReading): + raise ValueError("GEMHardwareInterface GEM e4 only supports INSNavGeod/GNSSReading for GNSS") + if type is INSNavGeod: + self.gnss_sub = rospy.Subscriber(topic, INSNavGeod, callback) + else: + def callback_with_gnss_reading(msg: INSNavGeod): + pose = ObjectPose(ObjectFrameEnum.GLOBAL, + x=msg.longitude, + y=msg.latitude, + z=msg.height, + yaw=math.radians(msg.heading), #heading from north in degrees (TODO: maybe?? check this) + roll=math.radians(msg.roll), + pitch=math.radians(msg.pitch), + ) + callback(GNSSReading(pose,'error' if msg.error else 'ok')) + self.gnss_sub = rospy.Subscriber(topic, Inspva, callback_with_gnss_reading) elif name == 'top_lidar': + topic = self.ros_sensor_topics[name] if type is not None and (type is not PointCloud2 and type is not np.ndarray): raise ValueError("GEMHardwareInterface only supports PointCloud2 or numpy array for top lidar") if type is None or type is PointCloud2: - self.top_lidar_sub = rospy.Subscriber("/lidar1/velodyne_points", PointCloud2, callback) + self.top_lidar_sub = rospy.Subscriber(topic, PointCloud2, callback) else: def callback_with_numpy(msg : Image): #print("received image with size",msg.width,msg.height,"encoding",msg.encoding) points = conversions.ros_PointCloud2_to_numpy(msg, want_rgb=False) callback(points) - self.top_lidar_sub = rospy.Subscriber("/lidar1/velodyne_points", PointCloud2, callback_with_numpy) + self.top_lidar_sub = rospy.Subscriber(topic, PointCloud2, callback_with_numpy) elif name == 'front_radar': if type is not None and type is not RadarTracks: raise ValueError("GEMHardwareInterface only supports RadarTracks for front radar") self.front_radar_sub = rospy.Subscriber("/front_radar/front_radar/radar_tracks", RadarTracks, callback) elif name == 'front_camera': + topic = self.ros_sensor_topics[name] if type is not None and (type is not Image and type is not cv2.Mat): raise ValueError("GEMHardwareInterface only supports Image or OpenCV for front camera") if type is None or type is Image: - self.front_camera_sub = rospy.Subscriber("/zed2/zed_node/rgb/image_rect_color", Image, callback) + self.front_camera_sub = rospy.Subscriber(topic, Image, callback) else: def callback_with_cv2(msg : Image): #print("received image with size",msg.width,msg.height,"encoding",msg.encoding) cv_image = conversions.ros_Image_to_cv2(msg, desired_encoding="bgr8") callback(cv_image) - self.front_camera_sub = rospy.Subscriber("/zed2/zed_node/rgb/image_rect_color", Image, callback_with_cv2) + self.front_camera_sub = rospy.Subscriber(topic, Image, callback_with_cv2) elif name == 'front_depth': + topic = self.ros_sensor_topics[name] if type is not None and (type is not Image and type is not cv2.Mat): raise ValueError("GEMHardwareInterface only supports Image or OpenCV for front depth") if type is None or type is Image: - self.front_depth_sub = rospy.Subscriber("/zed2/zed_node/depth/depth_registered", Image, callback) + self.front_depth_sub = rospy.Subscriber(topic, Image, callback) else: - self.bridge = CvBridge() def callback_with_cv2(msg : Image): #print("received image with size",msg.width,msg.height,"encoding",msg.encoding) cv_image = conversions.ros_Image_to_cv2(msg, desired_encoding="passthrough") callback(cv_image) - self.front_depth_sub = rospy.Subscriber("/zed2/zed_node/depth/depth_registered", Image, callback_with_cv2) + self.front_depth_sub = rospy.Subscriber(topic, Image, callback_with_cv2) # PACMod enable callback function diff --git a/GEMstack/onboard/perception/state_estimation.py b/GEMstack/onboard/perception/state_estimation.py index de48d069f..c0f613ac6 100644 --- a/GEMstack/onboard/perception/state_estimation.py +++ b/GEMstack/onboard/perception/state_estimation.py @@ -9,6 +9,7 @@ from ...mathutils.signal import OnlineLowPassFilter from ..interface.gem import GEMInterface from ..component import Component +from ..interface.gem_hardware import GNSSReading class GNSSStateEstimator(Component): """Just looks at the GNSS reading to estimate the vehicle state""" @@ -16,7 +17,7 @@ def __init__(self, vehicle_interface : GEMInterface): self.vehicle_interface = vehicle_interface if 'gnss' not in vehicle_interface.sensors(): raise RuntimeError("GNSS sensor not available") - vehicle_interface.subscribe_sensor('gnss',self.inspva_callback) + vehicle_interface.subscribe_sensor('gnss',self.c,ObjectPose) self.gnss_pose = None self.location = settings.get('vehicle.calibration.gnss_location')[:2] self.yaw_offset = settings.get('vehicle.calibration.gnss_yaw') @@ -24,17 +25,9 @@ def __init__(self, vehicle_interface : GEMInterface): self.status = None # Get GNSS information - def inspva_callback(self, inspva_msg): - self.gnss_pose = ObjectPose(ObjectFrameEnum.GLOBAL, - t=self.vehicle_interface.time(), - x=inspva_msg.longitude, - y=inspva_msg.latitude, - z=inspva_msg.height, - yaw=math.radians(inspva_msg.azimuth), #heading from north in degrees - roll=math.radians(inspva_msg.roll), - pitch=math.radians(inspva_msg.pitch), - ) - self.status = inspva_msg.status + def gnss_callback(self, reading : GNSSReading): + self.gnss_pose = reading.pose + self.status = reading.status def rate(self): return 10.0 diff --git a/GEMstack/onboard/visualization/klampt_visualization.py b/GEMstack/onboard/visualization/klampt_visualization.py index ad9578f9e..3e07aed23 100644 --- a/GEMstack/onboard/visualization/klampt_visualization.py +++ b/GEMstack/onboard/visualization/klampt_visualization.py @@ -4,7 +4,7 @@ from klampt import * from ...state import AllState,ObjectFrameEnum,VehicleState from ...mathutils.signal import OnlineLowPassFilter -from ...utils import klampt_visualization +from ...utils import klampt_visualization, settings import time import os import math @@ -27,7 +27,7 @@ def __init__(self, vehicle_interface, rate : float = 20.0, save_as : str = None) self.last_v = 0.0 self.world = WorldModel() - fn = os.path.abspath(os.path.join(__file__,"../../../knowledge/vehicle/model/gem_e2.urdf")) + fn = os.path.abspath(os.path.join(__file__,settings.get('vehicle.geometry.urdf_model'))) if not self.world.loadFile(fn): print("Warning, could not load vehicle model from",fn) input("Press enter to continue.") From 7d1c737d886d5f1bfe1734e8934e424c525f1ac0 Mon Sep 17 00:00:00 2001 From: krishauser Date: Tue, 19 Mar 2024 18:26:14 -0400 Subject: [PATCH 134/232] Added speed to GNSS reading, using it for velocity estimation --- GEMstack/onboard/interface/gem_hardware.py | 7 +++++-- GEMstack/onboard/perception/state_estimation.py | 6 ++++-- 2 files changed, 9 insertions(+), 4 deletions(-) diff --git a/GEMstack/onboard/interface/gem_hardware.py b/GEMstack/onboard/interface/gem_hardware.py index 65596e3b8..925b480b7 100644 --- a/GEMstack/onboard/interface/gem_hardware.py +++ b/GEMstack/onboard/interface/gem_hardware.py @@ -29,6 +29,7 @@ @dataclass class GNSSReading: pose : ObjectPose + speed : float status : str class GEMHardwareInterface(GEMInterface): @@ -167,7 +168,8 @@ def callback_with_gnss_reading(inspva_msg: Inspva): roll=math.radians(inspva_msg.roll), pitch=math.radians(inspva_msg.pitch), ) - callback(GNSSReading(pose,inspva_msg.status)) + speed = np.sqrt(inspva_msg.east_velocity**2 + inspva_msg.north_velocity**2) + callback(GNSSReading(pose,speed,inspva_msg.status)) self.gnss_sub = rospy.Subscriber(topic, Inspva, callback_with_gnss_reading) else: #assume it's septentrio @@ -185,7 +187,8 @@ def callback_with_gnss_reading(msg: INSNavGeod): roll=math.radians(msg.roll), pitch=math.radians(msg.pitch), ) - callback(GNSSReading(pose,'error' if msg.error else 'ok')) + speed = np.sqrt(msg.ve**2 + msg.vn**2) + callback(GNSSReading(pose,speed,('error' if msg.error else 'ok'))) self.gnss_sub = rospy.Subscriber(topic, Inspva, callback_with_gnss_reading) elif name == 'top_lidar': topic = self.ros_sensor_topics[name] diff --git a/GEMstack/onboard/perception/state_estimation.py b/GEMstack/onboard/perception/state_estimation.py index c0f613ac6..495aebad0 100644 --- a/GEMstack/onboard/perception/state_estimation.py +++ b/GEMstack/onboard/perception/state_estimation.py @@ -27,6 +27,7 @@ def __init__(self, vehicle_interface : GEMInterface): # Get GNSS information def gnss_callback(self, reading : GNSSReading): self.gnss_pose = reading.pose + self.gnss_speed = reading.speed self.status = reading.status def rate(self): @@ -60,8 +61,9 @@ def update(self) -> VehicleState: raw = readings.to_state(vehicle_pose_global) #filtering speed - filt_vel = self.speed_filter(raw.v) - raw.v = filt_vel + raw.v = self.gnss_speed + #filt_vel = self.speed_filter(raw.v) + #raw.v = filt_vel return raw From a5ffdf356e61535cda9e05d90f8d965d0245c209 Mon Sep 17 00:00:00 2001 From: krishauser Date: Mon, 1 Apr 2024 15:27:11 -0400 Subject: [PATCH 135/232] Fixed typos --- GEMstack/onboard/perception/state_estimation.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/GEMstack/onboard/perception/state_estimation.py b/GEMstack/onboard/perception/state_estimation.py index 495aebad0..44be5baa0 100644 --- a/GEMstack/onboard/perception/state_estimation.py +++ b/GEMstack/onboard/perception/state_estimation.py @@ -17,7 +17,7 @@ def __init__(self, vehicle_interface : GEMInterface): self.vehicle_interface = vehicle_interface if 'gnss' not in vehicle_interface.sensors(): raise RuntimeError("GNSS sensor not available") - vehicle_interface.subscribe_sensor('gnss',self.c,ObjectPose) + vehicle_interface.subscribe_sensor('gnss',self.gnss_callback,GNSSReading) self.gnss_pose = None self.location = settings.get('vehicle.calibration.gnss_location')[:2] self.yaw_offset = settings.get('vehicle.calibration.gnss_yaw') From 25b4ac46183bbcff5f14a2d6a717e42e879ba271 Mon Sep 17 00:00:00 2001 From: krishauser Date: Tue, 2 Apr 2024 17:50:28 -0400 Subject: [PATCH 136/232] Changed subscribers to go last in case subscriber callback is called immediately --- GEMstack/onboard/interface/gem_hardware.py | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/GEMstack/onboard/interface/gem_hardware.py b/GEMstack/onboard/interface/gem_hardware.py index 925b480b7..e98efcae4 100644 --- a/GEMstack/onboard/interface/gem_hardware.py +++ b/GEMstack/onboard/interface/gem_hardware.py @@ -65,7 +65,6 @@ def __init__(self): # -------------------- PACMod setup -------------------- # GEM vehicle enable - self.enable_sub = rospy.Subscriber('/pacmod/as_tx/enable', Bool, self.pacmod_enable_callback) self.enable_pub = rospy.Publisher('/pacmod/as_rx/enable', Bool, queue_size=1) self.pacmod_enable = False @@ -107,6 +106,10 @@ def __init__(self): """ #TODO: publish TwistStamped to /front_radar/front_radar/vehicle_motion to get better radar tracks + + #subscribers should go last because the callback might be called before the object is initialized + self.enable_sub = rospy.Subscriber('/pacmod/as_tx/enable', Bool, self.pacmod_enable_callback) + def start(self): if settings.get('vehicle.enable_through_joystick',True): From 18bf800b23ce3cdc6779902418a12299f3ec7fb0 Mon Sep 17 00:00:00 2001 From: onemaple Date: Mon, 22 Apr 2024 21:44:26 -0500 Subject: [PATCH 137/232] convert coordinate demo --- api-service/main.py | 64 +++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 64 insertions(+) create mode 100644 api-service/main.py diff --git a/api-service/main.py b/api-service/main.py new file mode 100644 index 000000000..7710147ca --- /dev/null +++ b/api-service/main.py @@ -0,0 +1,64 @@ +import googlemaps +from datetime import datetime +import sys +import os +sys.path.append(os.getcwd()) +from GEMstack.state import PhysicalObject,ObjectPose,ObjectFrameEnum +from GEMstack.state.physical_object import _get_frame_chain +from GEMstack.mathutils import transforms +import math +import time +def find_place_coordinates(place_name): + # Search for places based on the input name + places_result = gmaps.places(query=place_name) + if places_result['status'] == 'OK' and len(places_result['results']) > 0: + # Get the first (best-matched) place from the search results + place = places_result['results'][0] + # Extract the place ID + place_id = place['place_id'] + # Retrieve the details of the place using the place ID + place_details = gmaps.place(place_id=place_id) + if place_details['status'] == 'OK': + # Extract the latitude and longitude coordinates + lat = place_details['result']['geometry']['location']['lat'] + lng = place_details['result']['geometry']['location']['lng'] + # Create an ObjectPose for the current pose in the global frame + current_pose_global = ObjectPose(frame=ObjectFrameEnum.GLOBAL, t=time.time(), y=lat, x=lng, yaw=math.radians(90.0)) + # Transform the current pose to the car frame (START frame) + current_pose_car = current_pose_global.to_frame(ObjectFrameEnum.START, start_pose_abs=start_pose_global) + # Return the coordinates in the car frame as JSON + return {'x': current_pose_car.x, 'y': current_pose_car.y, 'yaw': current_pose_car.yaw} + # # Return the coordinates as a dictionary + # return {'lat': lat, 'lng': lng} + else: + return None + else: + return None +if __name__ == "__main__": + gmaps = googlemaps.Client(key='REPLACE_WITH_YOUR_API_KEY') + # Define the start pose of the car in the global frame + start_pose_global = ObjectPose(frame=ObjectFrameEnum.GLOBAL, t=time.time(), y=40.09286250064475, x=-88.23565755734872, yaw=math.radians(90.0)) + place_name = "Highbay" + coordinates = find_place_coordinates(place_name) + if coordinates: + print(f"Coordinates for the best-matched place: {coordinates}") + else: + print(f"No coordinates found for '{place_name}'") + # Geocoding an address + # geocode_result = gmaps.geocode('201 St Marys Rd, Champaign, IL') + # print(geocode_result) + # geocode_result = gmaps.geocode('UIUC IRL - The Highbay Facility') + # print(geocode_result) + # # Look up an address with reverse geocoding + # reverse_geocode_result = gmaps.reverse_geocode((40.714224, -73.961452)) + # # Request directions via public transit + # now = datetime.now() + # directions_result = gmaps.directions("UIUC IRL - The Highbay Facility", "Champaign, IL", + # mode="transit", + # departure_time=now) + # # print(directions_result) + # # Validate an address with address validation + # addressvalidation_result = gmaps.addressvalidation(['1600 Amphitheatre Pk'], + # regionCode='US', + # locality='Mountain View', + # enableUspsCass=True) \ No newline at end of file From 885ba44591792eac76809cd2814cec2b13519e54 Mon Sep 17 00:00:00 2001 From: Akshay Sivaraman Date: Tue, 23 Apr 2024 21:53:08 -0500 Subject: [PATCH 138/232] Adds Kalman Tracker class --- .../perception/2D_bounding_box_config.py | 104 ++++++++++ GEMstack/onboard/perception/kalman_tracker.py | 182 ++++++++++++++++++ requirements.txt | 1 + 3 files changed, 287 insertions(+) create mode 100644 GEMstack/onboard/perception/2D_bounding_box_config.py create mode 100644 GEMstack/onboard/perception/kalman_tracker.py diff --git a/GEMstack/onboard/perception/2D_bounding_box_config.py b/GEMstack/onboard/perception/2D_bounding_box_config.py new file mode 100644 index 000000000..1ba621bc7 --- /dev/null +++ b/GEMstack/onboard/perception/2D_bounding_box_config.py @@ -0,0 +1,104 @@ +import numpy as np + +## Config file for Kalman filtering for 2D bounding box prediction +## State has 6 dimensions (x,y,length,width, vel_x, vel_y) +## Observation/measurement is 2D bounding box [4 dimensions: x, y, length, width] + +''' +CONFIG FILE for Kalman filter + +MUST PROVIDE: +1: dim_x = the dimensions for state) + +2: dim_z = the dimensions for measurement + +3: F = state transition matrix. Must be shape (dim_x, dim_x) + +4: H = measurement matrix. Must be shape (dim_z, dim_x) + +5: P = Covariance matrix for initial observation. Represents uncertainty of initial state. + Must be matrix of shape (dim_x, dim_x) + +6: Q = Process Covariance Matrix. Represents uncertainty of process + Must be matrix of shape (dim_x, dim_x) + +7: R = Measurement Covariance Matrix. Represents uncertainty of measurement + Must be matrix of shape (dim_z, dim_z) + +8: max_age = After how many time_steps with no observation should we delete a kalman tracker. + Must be positive int + +9: cost_function(predicted_state, observation) = + function which calculates cost (or dissimilarity) between a + predicted state (size dim_x) and an observation (size dim_z) + +10: threshold = max limit for whether we consider a predicted state and new observation a match + +11: initial_state(measurement) = + function which provides initial state, given just the first observation + measurement is vector of size (dim_z). Output is vector of size (dim_x) +''' + + +# state is vector with [x,y,l,w,vel_x, vel_y] +dim_x = 6 +# measurements (sensor observations/bounding boxes) are just [x,y,l,w] +dim_z = 4 + +F = np.array([[1, 0, 0, 0, 1, 0], + [0, 1, 0, 0, 0, 1], + [0, 0, 1, 0, 0, 0], + [0, 0, 0, 1, 0, 0], + [0, 0, 0, 0, 1, 0], + [0, 0, 0, 0, 0, 1]]) + +H = np.array([[1, 0, 0, 0, 0, 0], + [0, 1, 0, 0, 0, 0], + [0, 0, 1, 0, 0, 0], + [0, 0, 0, 1, 0, 0]]) + +P = np.eye(dim_x) * 100 + +Q = np.eye(dim_x) * 0.01 + +R = np.eye(dim_z) * 1 + +max_age = 4 + +# IoU must be at least 0.3 or higher to be considered a match +threshold = -0.6 + +# This cost function is IoU (intersection over Union) of 2D bounding boxes +# Higher the IoU (overlapping region), higher is the similarity +# Since this is a cost function (measurement of dissimilarity), we negate the IoU +def cost_function(predicted_state, measurement): + rect1 = predicted_state[0:4] + rect2 = measurement + rect1_x1, rect1_y1 = rect1[0] - rect1[2]/2, rect1[1] - rect1[3]/2 + rect1_x2, rect1_y2 = rect1[0] + rect1[2]/2, rect1[1] + rect1[3]/2 + rect2_x1, rect2_y1 = rect2[0] - rect2[2]/2, rect2[1] - rect2[3]/2 + rect2_x2, rect2_y2 = rect2[0] + rect2[2]/2, rect2[1] + rect2[3]/2 + + # Calculate the coordinates of the intersection rectangle + inter_x1 = max(rect1_x1, rect2_x1) + inter_y1 = max(rect1_y1, rect2_y1) + inter_x2 = min(rect1_x2, rect2_x2) + inter_y2 = min(rect1_y2, rect2_y2) + + # Calculate the area of intersection + inter_area = max(0, inter_x2 - inter_x1) * max(0, inter_y2 - inter_y1) + + # Calculate the area of union + rect1_area = rect1[2] * rect1[3] + rect2_area = rect2[2] * rect2[3] + union_area = rect1_area + rect2_area - inter_area + + # Calculate the IoU + iou = inter_area / union_area if union_area > 0 else 0 + return -iou + +# given measurement of [x,y,l,w], set state to [x,y,l,w,0,0] +def initial_state(measurement): + state = np.zeros(dim_x) + state[0:dim_z] = measurement + return state \ No newline at end of file diff --git a/GEMstack/onboard/perception/kalman_tracker.py b/GEMstack/onboard/perception/kalman_tracker.py new file mode 100644 index 000000000..4cdaff811 --- /dev/null +++ b/GEMstack/onboard/perception/kalman_tracker.py @@ -0,0 +1,182 @@ +from filterpy.kalman import KalmanFilter +from scipy.optimize import linear_sum_assignment +import numpy as np +import importlib.util + + +''' +CONFIG FILE/PRARAMETERS for KalmanTracker: +(some examples for configs are provided/set as defaults. ) + +MUST PROVIDE: +1: dim_x = the dimensions for state +2: dim_z = the dimensions for measurement +3: F = state transition matrix. Must be shape (dim_x, dim_x) +4: H = measurement matrix. Must be shape (dim_z, dim_x) +5: P = Covariance matrix for initial observation. Represents uncertainty of initial state. + Must be matrix of shape (dim_x, dim_x) +6: Q = Process Covariance Matrix. Represents uncertainty of process + Must be matrix of shape (dim_x, dim_x) +7: R = Measurement Covariance Matrix. Represents uncertainty of measurement + Must be matrix of shape (dim_z, dim_z) +8: max_age = After how many time_steps with no observation should we delete a kalman tracker. + Must be positive int +9: cost_function(predicted_state, observation) = + function which calculates cost (or dissimilarity) between a + predicted state (size dim_x) and an observation (size dim_z) +10: threshold = max limit for whether we consider a predicted state and new observation a match +11: initial_state(measurement) = + function which provides initial state, given just the first observation + measurement is vector of size (dim_z). Output is vector of size (dim_x) +''' + +class KalmanTracker: + def __init__(self, config_file_path=None, \ + dim_x=4, dim_z=2, F=None, H=None, P= None, Q=None, R=None, \ + max_age=6, cost_function=None, threshold=10, initial_state=None): + + def default_cost_fn(predicted_state, measurement): + return np.linalg.norm(predicted_state[0:2] - measurement) + + def default_initial_state(measurement): + state = np.zeros(dim_x) + state[0:dim_z] = measurement + return state + + + if config_file_path is not None: + spec = importlib.util.spec_from_file_location("config", config_file_path) + config = importlib.util.module_from_spec(spec) + spec.loader.exec_module(config) + + self.kalman_filters = {} + self.max_id = 0 + + self.dim_x = config.dim_x + self.dim_z = config.dim_z + self.F = config.F + self.H = config.H + self.P = config.P + self.Q = config.Q + self.R = config.R + self.max_age = config.max_age + self.threshold = config.threshold + self.cost_function = config.cost_function + self.initial_state = config.initial_state + + else: # if no config file is provided, use the parameters provided OR defaults. + self.kalman_filters = {} + self.max_id = 0 + + self.dim_x = dim_x + self.dim_z = dim_z + self.F = np.array([[1, 0, 1, 0], + [0, 1, 0, 1], + [0, 0, 1, 0], + [0, 0, 0, 1]]) if F is None else F + self.H = np.array([[1, 0, 0, 0], + [0, 1, 0, 0]]) if H is None else H + self.P = np.eye(dim_x) * 100 if P is None else P + self.Q = np.eye(dim_x) * 0.01 if Q is None else Q + self.R = np.eye(dim_z) * 1 if R is None else R + self.max_age = max_age + self.threshold = threshold + self.cost_function = default_cost_fn if cost_function is None else cost_function + self.initial_state = default_initial_state if initial_state else initial_state + + + # Must be called in loop to continuously update all tracked objects + # bounding_boxes are just the list of measurements/observations/sensor readings + def update_pedestrian_tracking(self, bounding_boxes): + + # Predict the next state for each pedestrian using past state + predicted_states = {} + for pedestrian_id, kalman_filter in self.kalman_filters.items(): + kalman_filter.predict() + # kalman_filter.x now stores the prediction for the future state. + predicted_states[pedestrian_id] = kalman_filter.x + + # Match observed bounding boxes with predicted future states + cost_matrix, pedestrian_id_list = self.compute_cost_matrix(predicted_states, bounding_boxes) + matches = self.compute_matching(cost_matrix, pedestrian_id_list) + + # Update matched pedestrians + matched_pedestrians = set() + matched_bboxes = set() + for pedestrian_id, bbox_idx in matches.items(): + self.kalman_filters[pedestrian_id].update(bounding_boxes[bbox_idx]) + self.kalman_filters[pedestrian_id].time_since_update = 0 + matched_pedestrians.add(pedestrian_id) + matched_bboxes.add(bbox_idx) + + # For unmatched Kalman filters, increase time since last update by 1 + for pedestrian_id in (set(self.kalman_filters.keys()) - matched_pedestrians): + self.kalman_filters[pedestrian_id].time_since_update += 1 + self.delete_old_tracks() + + # For unmatched bboxes, create a new kalman filter + for col_idx in (set(range(len(bounding_boxes))) - matched_bboxes): + pedestrian_id = self.generate_new_pedestrian_id() + self.kalman_filters[pedestrian_id] = self.create_kalman_filter(bounding_boxes[col_idx]) + matches[pedestrian_id]= col_idx + # Return the tracked pedestrians (mapping pedestrian ID to state) + tracked_pedestrians = { + pedestrian_id: kalman_filter.x for pedestrian_id, kalman_filter in self.kalman_filters.items() + } + return tracked_pedestrians, matches + + ### HELPER FUNCTIONS + def generate_new_pedestrian_id(self): + self.max_id += 1 + return str(self.max_id) + + def delete_old_tracks(self): + to_delete = [] + for pedestrian_id, kalman_filter in self.kalman_filters.items(): + if kalman_filter.time_since_update > self.max_age: + to_delete.append(pedestrian_id) + for pedestrian_id in to_delete: + del self.kalman_filters[pedestrian_id] + + def compute_cost_matrix(self,predicted_states, bounding_boxes): + cost_matrix = np.zeros((len(predicted_states), len(bounding_boxes))) + ped_id_list = [] + for i, (ped_id, predicted_state) in enumerate(predicted_states.items()): + ped_id_list.append(ped_id) + for j, bounding_box in enumerate(bounding_boxes): + cost_matrix[i, j] = self.cost_function(predicted_state, bounding_box) + return cost_matrix, ped_id_list + + def compute_matching(self, cost_matrix, ped_id_list): + row_indices, col_indices = linear_sum_assignment(cost_matrix) + # Maps pedestrian ID to observed box index + matching = {} + for i in range(len(row_indices)): + # row_indices[i], col_indices[i] is matched according to the linear solver + # but, only include matches that have enough similarity (less than threshold) + if cost_matrix[row_indices[i], col_indices[i]] <= self.threshold: + matching[ped_id_list[i]] = col_indices[i] + return matching + + def create_kalman_filter(self, bounding_box): + kalman_filter = KalmanFilter(dim_x=self.dim_x, dim_z=self.dim_z) + # Initialize the state with the bounding box + kalman_filter.x = self.initial_state(bounding_box) + + # State transition matrix + kalman_filter.F = self.F.copy() + + # Measurement matrix + kalman_filter.H = self.H.copy() + + # Initial state uncertainty + kalman_filter.P = self.P.copy() + + # Process noise (uncertainty of process) + kalman_filter.Q = self.Q.copy() + + # Measurement noise covariance (uncertainty of obtained measurements/bounding boxes) + kalman_filter.R = self.R.copy() + + kalman_filter.time_since_update = 0 + return kalman_filter diff --git a/requirements.txt b/requirements.txt index 94db8ba43..f516e388b 100644 --- a/requirements.txt +++ b/requirements.txt @@ -7,3 +7,4 @@ shapely klampt pyyaml dacite +filterpy \ No newline at end of file From d9bdc416aa5f74e9f4ecee97fe7e9ab049c05540 Mon Sep 17 00:00:00 2001 From: Akshay Sivaraman Date: Thu, 25 Apr 2024 19:12:04 -0500 Subject: [PATCH 139/232] Moved config file to knowledge directory --- .../perception => knowledge/prediction}/2D_bounding_box_config.py | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename GEMstack/{onboard/perception => knowledge/prediction}/2D_bounding_box_config.py (100%) diff --git a/GEMstack/onboard/perception/2D_bounding_box_config.py b/GEMstack/knowledge/prediction/2D_bounding_box_config.py similarity index 100% rename from GEMstack/onboard/perception/2D_bounding_box_config.py rename to GEMstack/knowledge/prediction/2D_bounding_box_config.py From 52aba584c1af08e5865705784cc562e1687c70bf Mon Sep 17 00:00:00 2001 From: Apramey <54759777+AprameyH@users.noreply.github.com> Date: Wed, 1 May 2024 01:36:54 -0500 Subject: [PATCH 140/232] Top Down Multi class detection and tracking --- .../knowledge/defaults/computation_graph.yaml | 5 +- .../perception/td_multi_class_detector.py | 250 ++++++++++++++++++ .../perception/td_multi_class_tracker.py | 195 ++++++++++++++ GEMstack/state/all.py | 7 + launch/detect_and_track.yaml | 45 ++++ 5 files changed, 501 insertions(+), 1 deletion(-) create mode 100644 GEMstack/onboard/perception/td_multi_class_detector.py create mode 100644 GEMstack/onboard/perception/td_multi_class_tracker.py create mode 100644 launch/detect_and_track.yaml diff --git a/GEMstack/knowledge/defaults/computation_graph.yaml b/GEMstack/knowledge/defaults/computation_graph.yaml index d7a606326..b0d3bb9a5 100644 --- a/GEMstack/knowledge/defaults/computation_graph.yaml +++ b/GEMstack/knowledge/defaults/computation_graph.yaml @@ -17,7 +17,10 @@ components: outputs: obstacles - agent_detection: inputs: vehicle - outputs: agents + outputs: detected_agents + - agent_tracking: + inputs: detected_agents + outputs: tracking_frames - lane_detection: inputs: [vehicle, roadgraph] outputs: vehicle_lane diff --git a/GEMstack/onboard/perception/td_multi_class_detector.py b/GEMstack/onboard/perception/td_multi_class_detector.py new file mode 100644 index 000000000..0cc8c145e --- /dev/null +++ b/GEMstack/onboard/perception/td_multi_class_detector.py @@ -0,0 +1,250 @@ +from ...state import AllState,VehicleState,ObjectPose,ObjectFrameEnum,AgentState,AgentEnum,AgentActivityEnum +from ...utils import settings +from ...mathutils import transforms +from ..interface.gem import GEMInterface +from ..component import Component +from ultralytics import YOLO +import cv2 +try: + from sensor_msgs.msg import CameraInfo + from image_geometry import PinholeCameraModel + import rospy +except ImportError: + pass +import numpy as np +from typing import Dict,Tuple, List +import time +from numpy.linalg import inv + + +def Pmatrix(fx,fy,cx,cy): + """Returns a projection matrix for a given set of camera intrinsics.""" + return np.array([[fx,0,cx,0], + [0,fy,cy,0], + [0,0,1,0]]) + +def project_point_cloud(point_cloud : np.ndarray, P : np.ndarray, xrange : Tuple[int,int], yrange : Tuple[int,int]) -> Tuple[np.ndarray,np.ndarray]: + """Projects a point cloud into a 2D image using a camera intrinsic projection matrix P. + + Returns: + - point_cloud_image: an Nx2 array of (u,v) visible image coordinates + - image_indices: an array of N indices of visible points into the original point cloud + """ + + pc_with_ids = np.hstack((point_cloud,np.arange(len(point_cloud)).reshape(-1,1))) + pc_fwd = pc_with_ids[pc_with_ids[:,2] > 0] + pxform = pc_fwd[:,:3].dot(P[:3,:3].T) + P[:3,3] + uv = (pxform[:,0:2].T/pxform[:,2]).T + inds = np.logical_and(np.logical_and(uv[:,0] >= xrange[0],uv[:,0] < xrange[1]), + np.logical_and(uv[:,1] >= yrange[0],uv[:,1] < yrange[1])) + point_cloud_image = uv[inds] + image_indices = pc_fwd[inds,3].astype(int) + return point_cloud_image, image_indices + +def lidar_to_image(point_cloud_lidar: np.ndarray, extrinsic : np.ndarray, intrinsic : np.ndarray): + + homo_point_cloud_lidar = np.hstack((point_cloud_lidar, np.ones((point_cloud_lidar.shape[0], 1)))) # (N, 4) + pointcloud_pixel = (intrinsic @ extrinsic @ (homo_point_cloud_lidar).T) # (3, N) + pointcloud_pixel = pointcloud_pixel.T # (N, 3) + + # normalize + pointcloud_pixel[:, 0] /= pointcloud_pixel[:, 2] # normalize + pointcloud_pixel[:, 1] /= pointcloud_pixel[:, 2] # normalize + point_cloud_image = pointcloud_pixel[:,:2] # (N, 2) + return point_cloud_image + +def lidar_to_vehicle(point_cloud_lidar: np.ndarray, T_lidar2_Gem: np.ndarray): + ones = np.ones((point_cloud_lidar.shape[0], 1)) + pcd_homogeneous = np.hstack((point_cloud_lidar, ones)) # (N, 4) + pointcloud_trans = np.dot(T_lidar2_Gem, pcd_homogeneous.T) # (4, N) + pointcloud_trans = pointcloud_trans.T # (N, 4) + point_cloud_image_world = pointcloud_trans[:, :3] # (N, 3) + return point_cloud_image_world + +def filter_lidar_by_range(point_cloud, xrange: Tuple[float, float], yrange: Tuple[float, float]): + xmin, xmax = xrange + ymin, ymax = yrange + idxs = np.where((point_cloud[:, 0] > xmin) & (point_cloud[:, 0] < xmax) & + (point_cloud[:, 1] > ymin) & (point_cloud[:, 1] < ymax) ) + return point_cloud[idxs] + +class TDMultiClassDetector(Component): + """Detects and tracks pedestrians.""" + def __init__(self,vehicle_interface : GEMInterface, extrinsic=None): + # State Estimation + self.vehicle_interface = vehicle_interface + + self.detector = YOLO('GEMstack/knowledge/detection/yolov8n.pt') + self.camera_info_sub = None + self.camera_info = None + self.zed_image = None + + + + self.point_cloud = None + self.point_cloud_zed = None + assert(settings.get('vehicle.calibration.top_lidar.reference') == 'rear_axle_center') + assert(settings.get('vehicle.calibration.front_camera.reference') == 'rear_axle_center') + + + if extrinsic is None: + extrinsic = np.loadtxt("GEMstack/knowledge/calibration/gem_e4_lidar2oak.txt") + self.extrinsic = np.array(extrinsic) + + intrinsic = np.loadtxt("GEMstack/knowledge/calibration/gem_e4_intrinsic.txt") + self.intrinsic = np.concatenate([intrinsic, np.zeros((3, 1))], axis=1) + + T_lidar2_Gem = np.loadtxt("GEMstack/knowledge/calibration/gem_e4_lidar2vehicle.txt") + self.T_lidar2_Gem = np.asarray(T_lidar2_Gem) + + # Hardcode the roi area for agents + self.xrange = (1, 20) + self.yrange = (-10, 10) + + + def rate(self): + return 2.5 + + def state_inputs(self): + return ['vehicle'] + + def state_outputs(self): + return ['detected_agents'] + + def test_set_data(self, zed_image, point_cloud, camera_info='dummy'): + self.zed_image = zed_image + self.point_cloud = point_cloud + self.camera_info = camera_info + + # def initialize(self): + # print("INITIALIZE PED DETECT") + # # tell the vehicle to use image_callback whenever 'front_camera' gets a reading, and it expects images of type cv2.Mat + # self.vehicle_interface.subscribe_sensor('front_camera',self.image_callback,cv2.Mat) + # # tell the vehicle to use lidar_callback whenever 'top_lidar' gets a reading, and it expects numpy arrays + # self.vehicle_interface.subscribe_sensor('top_lidar',self.lidar_callback,np.ndarray) + # # subscribe to the Zed CameraInfo topic + # self.camera_info_sub = rospy.Subscriber("/oak/rgb/camera_info", CameraInfo, self.camera_info_callback) + + # def image_callback(self, image : cv2.Mat): + # self.zed_image = image + + # def camera_info_callback(self, info : CameraInfo): + # self.camera_info = info + + # def lidar_callback(self, point_cloud: np.ndarray): + # self.point_cloud = point_cloud + + def update(self, vehicle : VehicleState) -> Dict[str,AgentState]: + print("0PED DETECT UPDATE", self.zed_image is None, self.point_cloud is None, self.camera_info is None) + if self.zed_image is None: + # no image data yet + print("zed") + return {} + if self.point_cloud is None: + # no lidar data yet + print("pc") + return {} + if self.camera_info is None: + # no camera info yet + print("camera") + return {} + + detected_agents = self.detect_agents() # TODO: to ask SE to output detected_agents only + + + print("Pedestrian Detection detected agents: ", detected_agents) + return detected_agents + + + def box_to_agent(self, box, point_cloud_image, point_cloud_image_world): + """Creates a 3D agent state from an (x,y,w,h) bounding box. + """ + + # print ('Detect a pedestrian!') + + # get the idxs of point cloud that belongs to the agent + x,y,w,h = box + xmin, xmax = x - w/2, x + w/2 + ymin, ymax = y - h/2, y + h/2 + + + # enlarge bbox in case inaccuracy calibration + enlarge_factor = 3 + xmin *= enlarge_factor + xmax *= enlarge_factor + ymin *= enlarge_factor + ymax *= enlarge_factor + + agent_world_pc = point_cloud_image_world + + + # Find the point_cloud that is closest to the center of our bounding box + center_x = x + w / 2 + center_y = y + h / 2 + distances = np.linalg.norm(point_cloud_image - [center_x, center_y], axis=1) + closest_point_cloud_idx = np.argmin(distances) + closest_point_cloud = point_cloud_image_world[closest_point_cloud_idx] + + x, y, _ = closest_point_cloud + pose = ObjectPose(t=0, x=x, y=y, z=0, yaw=0, pitch=0, roll=0, frame=ObjectFrameEnum.CURRENT) + + # Specify AgentState. + l = np.max(agent_world_pc[:, 0]) - np.min(agent_world_pc[:, 0]) + w = np.max(agent_world_pc[:, 1]) - np.min(agent_world_pc[:, 1]) + h = np.max(agent_world_pc[:, 2]) - np.min(agent_world_pc[:, 2]) + + dims = (w, h, l) + + return AgentState(pose=pose,dimensions=dims,outline=None,type=AgentEnum.PEDESTRIAN,activity=AgentActivityEnum.MOVING,velocity=(0,0,0),yaw_rate=0) + + # Behavior Prediction added test argument to return matchings + def detect_agents(self, test=False): + detection_result = self.detector(self.zed_image,verbose=False) + + # TODO: create boxes from detection result + pedestrian_boxes = [] + car_boxes = [] # add car objects + + for box in detection_result[0].boxes: # only one image, so use index 0 of result + class_id = int(box.cls[0].item()) + if class_id == 0: # class 0 stands for pedestrian + bbox = box.xywh[0].tolist() + pedestrian_boxes.append(bbox) + + if class_id == 2: # class 2 stands for car + bbox = box.xywh[0].tolist() + car_boxes.append(bbox) + + + # Only keep lidar point cloud that lies in roi area for agents + point_cloud_lidar = filter_lidar_by_range(self.point_cloud, self.xrange, self.yrange) + + # Tansfer lidar point cloud to camera frame + point_cloud_image = lidar_to_image(point_cloud_lidar, self.extrinsic, self.intrinsic) + + # Tansfer lidar point cloud to vehicle frame + point_cloud_image_world = lidar_to_vehicle(point_cloud_lidar, self.T_lidar2_Gem) + + + + # Find agents + detected_agents = [] + for i,b in enumerate(pedestrian_boxes): + agent = self.box_to_agent(b, point_cloud_image, point_cloud_image_world) + agent.type = AgentEnum.PEDESTRIAN + if agent is not None: + detected_agents.append(agent) + + for i,b in enumerate(car_boxes): + agent = self.box_to_agent(b, point_cloud_image, point_cloud_image_world) + agent.type = AgentEnum.CAR + if agent is not None: + detected_agents.append(agent) + + + if test: # Behavior Prediction + return detected_agents, detection_result + return detected_agents + + + \ No newline at end of file diff --git a/GEMstack/onboard/perception/td_multi_class_tracker.py b/GEMstack/onboard/perception/td_multi_class_tracker.py new file mode 100644 index 000000000..808eb9994 --- /dev/null +++ b/GEMstack/onboard/perception/td_multi_class_tracker.py @@ -0,0 +1,195 @@ +from ...state import ( + ObjectPose, + ObjectFrameEnum, + AgentState, + AgentEnum, + AgentActivityEnum, +) +from ...utils import settings +from ...mathutils import transforms +from ..interface.gem import GEMInterface +from ..component import Component +from ultralytics import YOLO +import cv2 + +try: + from sensor_msgs.msg import CameraInfo + from image_geometry import PinholeCameraModel + import rospy +except ImportError: + pass + +import numpy as np +from typing import Dict, List +from .kalman_tracker import KalmanTracker # Behavior Prediction Team + +# TOP DOWN 2D BOUNDING BOX TRACKER FOR MULTIPLE OBJECTS/AGENTS +class TDMultiClassTracker(Component): + def __init__( + self, + kalman_config_files=["GEMstack/onboard/perception/2D_bounding_box_config.py"], + kalman_classes = [AgentEnum.PEDESTRIAN], + detection_file_name="GEMstack/onboard/prediction/tracking_results.txt", + test=False, + write_all=False, + write_limit=8, + velocity_threshold=0.1 + ): + self.velocity_threshold = velocity_threshold ** 2 + self.kalman_trackers = [KalmanTracker(config_file_path=kalman_config_file) for kalman_config_file in kalman_config_files] + self.kalman_classes = kalman_classes + self.tracking_results = {ag_class:{} for ag_class in kalman_classes} + self.current_frame = 0 + self.write_limit= write_limit + + self.detection_file_name = detection_file_name + self.write_all = write_all + + f = open(self.detection_file_name, "w") + f.close() + + + # For Testing + self.test = test + if self.test: + self.detection_file_name = detection_file_name + self.write_all = write_all + f = open(self.detection_file_name, "w") + f.close() + + """Base class for top-level components in the execution stack.""" + + def rate(self) -> float: + """Returns the rate in Hz at which this component should be updated.""" + return 2.5 + + def state_inputs(self) -> List[str]: + """Returns the list of AllState inputs this component requires.""" + return ["detected_agents"] + + def state_outputs(self) -> List[str]: + """Returns the list of AllState outputs this component generates.""" + return ["tracking_frames"] + + def healthy(self): + """Returns True if the element is in a stable state.""" + return True + + def initialize(self): + """Initialize the component. This is called once before the first + update.""" + pass + + def cleanup(self): + """Cleans up resources used by the component. This is called once after + the last update.""" + pass + + def update(self, detected_agents: List[AgentState]): + print("Updating with detected, ", detected_agents) + """Update the component.""" + self.track_agents(detected_agents=detected_agents) + return self.tracking_results + + def debug(self, item, value): + """Debugs a streaming value within this component""" + if hasattr(self, "debugger"): + self.debugger.debug(item, value) + + def debug_event(self, label): + """Debugs an event within this component""" + if hasattr(self, "debugger"): + self.debugger.debug_event(label) + + def track_agents(self, detected_agents: List[AgentState]): + """Given a list of detected agents, updates the state of the agents using a Kalman Tracker.""" + all_tracked_objects = {} + for i, kalman_tracker in enumerate(self.kalman_trackers): + detections = [] + for agent in detected_agents: + if agent.type == self.kalman_classes[i]: + x, y, z = agent.pose.x, agent.pose.y, agent.pose.z + w, h, l = agent.dimensions + detections.append(np.array([x, y, w, l])) + + kalman_agent_states, matches = kalman_tracker.update_pedestrian_tracking( + detections + ) + tracking_results = {} + for pid in kalman_agent_states: + ag_state = kalman_agent_states[pid] + curr_activity = AgentActivityEnum.MOVING + v2 = (ag_state[4] ** 2 + ag_state[5] ** 2) + if (v2 <= self.velocity_threshold): + curr_activity = AgentActivityEnum.STOPPED + tracking_results[pid] = AgentState( + pose=ObjectPose( + t=0, + x=ag_state[0], + y=ag_state[1], + z=0, + yaw=0, + pitch=0, + roll=0, + frame=ObjectFrameEnum.CURRENT, + ), + dimensions=(ag_state[2], ag_state[3], 1.5), + velocity=(ag_state[4], ag_state[5], 0), + type=self.kalman_classes[i], + activity=curr_activity, + yaw_rate=0, + outline=None, + ) + all_tracked_objects[self.kalman_classes[i]] = tracking_results + + self.update_track_history(all_tracked_objects) + + if self.test: + return tracking_results, matches + + + def update_track_history( + self, all_ag_dict: Dict[AgentEnum, Dict[int, AgentState]] + ): + for ag_class, ag_dict in all_ag_dict.items(): + for pid in sorted(ag_dict): + if self.current_frame in self.tracking_results[ag_class]: + self.tracking_results[ag_class][self.current_frame][pid] = ag_dict[pid] + else: + self.tracking_results[ag_class][self.current_frame] = {pid: ag_dict[pid]} + if not self.write_all: + # Remove old tracking information + self.tracking_results[ag_class].pop(self.current_frame - self.write_limit, None) + + self.current_frame += 1 + + def get_stationary_pedestrians(tracking_frames): + epsilon = 0.1 #hyperparam + num_past_frames = 3 #hyperparam + pedestrian_frames = tracking_frames[AgentEnum.Pedestrian] + latest_frames = sorted(list(pedestrian_frames.keys()))[-num_past_frames:] + all_peds_set = set() # all pedestrians + non_stat_peds = set() # pedestrians that are not stationary + + prev_frame_peds = set() # pedestrians that were seen in the prev frame. + for frame in latest_frames: + frame_peds = set() + for pid,ag_state in pedestrian_frames[frame].items(): + # if the velocity of the pedestrians are more than 0, + # then add the pedestrian to the set of non-stationary pedestrians + if ag_state.activity == AgentActivityEnum.STOPPED: + non_stat_peds.add(pid) + else: # ped velocity is 0 + # if this frame is the first time a pedestrian shows up, it's not stationary + if pid not in prev_frame_peds: + non_stat_peds.add(pid) + + all_peds_set.add(pid) + frame_peds.add(pid) + + + all_peds_set = all_peds_set.intersect(frame_peds) + prev_frame_peds = frame_peds + + stationary_pedestrians = all_peds_set - non_stat_peds + return stationary_pedestrians \ No newline at end of file diff --git a/GEMstack/state/all.py b/GEMstack/state/all.py index fc976fe24..060821345 100644 --- a/GEMstack/state/all.py +++ b/GEMstack/state/all.py @@ -11,6 +11,8 @@ from .trajectory import Trajectory from .predicates import PredicateValues from typing import Dict,List,Optional +from .agent import AgentState +from .agent import AgentEnum @dataclass @register @@ -46,6 +48,11 @@ class AllState(SceneState): intent_update_time : float = 0 route_update_time : float = 0 trajectory_update_time : float = 0 + + # pedestrian detection and tracking items + detected_agents : List[AgentState] = None + tracking_frames : Dict[AgentEnum, Dict[int, Dict[int, AgentState]]] = None + predicted_trajectories : List[Dict[List[AgentState]]] = None @staticmethod def zero(): diff --git a/launch/detect_and_track.yaml b/launch/detect_and_track.yaml new file mode 100644 index 000000000..5a4d4e3e8 --- /dev/null +++ b/launch/detect_and_track.yaml @@ -0,0 +1,45 @@ +description: "Detect the peds" +mode: hardware +vehicle_interface: gem_hardware.GEMHardwareInterface +mission_execution: StandardExecutor + +# Recovery behavior after a component failure +recovery: + planning: + trajectory_tracking : recovery.StopTrajectoryTracker + +# Driving behavior for the GEM vehicle. Runs detection and tracking on real vehicle. +drive: + perception: + state_estimation : GNSSStateEstimator + agent_detection : td_multi_class_detector.TDMultiClassDetector + agent_tracking : td_multi_class_tracker.TDMultiClassTracker + perception_normalization : StandardPerceptionNormalizer + +log: + # Specify the top-level folder to save the log files. Default is 'logs' + folder : 'logs' + # If prefix is specified, then the log folder will be named with the prefix followed by the date and time. Default no prefix + prefix : 'detect_and_track_' + # If suffix is specified, then logs will output to folder/prefix+suffix. Default uses date and time as the suffix + #suffix : 'test3' + # Specify which ros topics to record to vehicle.bag. Default records nothing. This records the "standard" ROS topics. + ros_topics : + # Specify options to pass to rosbag record. Default is no options. + #rosbag_options : '--split --size=1024' + # If True, then record all readings / commands of the vehicle interface. Default False + vehicle_interface : True + # Specify which components to record to behavior.json. Default records nothing + # components : ['state_estimation','agent_detection', 'agent_tracking'] + # Specify which components of state to record to state.json. Default records nothing + # state: ['all'] + # Specify the rate in Hz at which to record state to state.json. Default records at the pipeline's rate + # state_rate: 10 +replay: # Add items here to set certain topics / inputs to be replayed from logs + # Specify which log folder to replay from + log: + ros_topics : [] + components : [] + +#usually can keep this constant +computation_graph: !include "../GEMstack/knowledge/defaults/computation_graph.yaml" \ No newline at end of file From 91bda35004f1e7a877bf0190118acf2d22d3959f Mon Sep 17 00:00:00 2001 From: Apramey <54759777+AprameyH@users.noreply.github.com> Date: Wed, 1 May 2024 02:06:38 -0500 Subject: [PATCH 141/232] Add calibration files from State Estimation --- .../calibration/gem_e4_intrinsic.txt | 3 ++ .../calibration/gem_e4_lidar2oak.txt | 4 +++ .../calibration/gem_e4_lidar2vehicle.txt | 4 +++ .../perception/td_multi_class_detector.py | 34 +++++++++---------- .../perception/td_multi_class_tracker.py | 2 +- 5 files changed, 29 insertions(+), 18 deletions(-) create mode 100644 GEMstack/knowledge/calibration/gem_e4_intrinsic.txt create mode 100644 GEMstack/knowledge/calibration/gem_e4_lidar2oak.txt create mode 100644 GEMstack/knowledge/calibration/gem_e4_lidar2vehicle.txt diff --git a/GEMstack/knowledge/calibration/gem_e4_intrinsic.txt b/GEMstack/knowledge/calibration/gem_e4_intrinsic.txt new file mode 100644 index 000000000..b2509ef74 --- /dev/null +++ b/GEMstack/knowledge/calibration/gem_e4_intrinsic.txt @@ -0,0 +1,3 @@ +684.83331299 0. 573.37109375 +0. 684.60968018 363.70092773 +0. 0. 1. \ No newline at end of file diff --git a/GEMstack/knowledge/calibration/gem_e4_lidar2oak.txt b/GEMstack/knowledge/calibration/gem_e4_lidar2oak.txt new file mode 100644 index 000000000..fedf4d5bd --- /dev/null +++ b/GEMstack/knowledge/calibration/gem_e4_lidar2oak.txt @@ -0,0 +1,4 @@ +-0.00519 -0.99997 0.005352 0.1627 +-0.0675 -0.00499 -0.9977 -0.03123 +0.99771 -0.00554 -0.06743 -0.7284 +0 0 0 1 \ No newline at end of file diff --git a/GEMstack/knowledge/calibration/gem_e4_lidar2vehicle.txt b/GEMstack/knowledge/calibration/gem_e4_lidar2vehicle.txt new file mode 100644 index 000000000..5dff05e15 --- /dev/null +++ b/GEMstack/knowledge/calibration/gem_e4_lidar2vehicle.txt @@ -0,0 +1,4 @@ +0.998621 -0.052503 0.000000 1.10000 +0.052503 0.998621 0.000000 0.000000 +0.000000 0.000000 1.000000 2.030000 +0.000000 0.000000 0.000000 1.000000 diff --git a/GEMstack/onboard/perception/td_multi_class_detector.py b/GEMstack/onboard/perception/td_multi_class_detector.py index 0cc8c145e..57cd0ab86 100644 --- a/GEMstack/onboard/perception/td_multi_class_detector.py +++ b/GEMstack/onboard/perception/td_multi_class_detector.py @@ -116,23 +116,23 @@ def test_set_data(self, zed_image, point_cloud, camera_info='dummy'): self.point_cloud = point_cloud self.camera_info = camera_info - # def initialize(self): - # print("INITIALIZE PED DETECT") - # # tell the vehicle to use image_callback whenever 'front_camera' gets a reading, and it expects images of type cv2.Mat - # self.vehicle_interface.subscribe_sensor('front_camera',self.image_callback,cv2.Mat) - # # tell the vehicle to use lidar_callback whenever 'top_lidar' gets a reading, and it expects numpy arrays - # self.vehicle_interface.subscribe_sensor('top_lidar',self.lidar_callback,np.ndarray) - # # subscribe to the Zed CameraInfo topic - # self.camera_info_sub = rospy.Subscriber("/oak/rgb/camera_info", CameraInfo, self.camera_info_callback) - - # def image_callback(self, image : cv2.Mat): - # self.zed_image = image - - # def camera_info_callback(self, info : CameraInfo): - # self.camera_info = info - - # def lidar_callback(self, point_cloud: np.ndarray): - # self.point_cloud = point_cloud + def initialize(self): + print("INITIALIZE PED DETECT") + # tell the vehicle to use image_callback whenever 'front_camera' gets a reading, and it expects images of type cv2.Mat + self.vehicle_interface.subscribe_sensor('front_camera',self.image_callback,cv2.Mat) + # tell the vehicle to use lidar_callback whenever 'top_lidar' gets a reading, and it expects numpy arrays + self.vehicle_interface.subscribe_sensor('top_lidar',self.lidar_callback,np.ndarray) + # subscribe to the Zed CameraInfo topic + self.camera_info_sub = rospy.Subscriber("/oak/rgb/camera_info", CameraInfo, self.camera_info_callback) + + def image_callback(self, image : cv2.Mat): + self.zed_image = image + + def camera_info_callback(self, info : CameraInfo): + self.camera_info = info + + def lidar_callback(self, point_cloud: np.ndarray): + self.point_cloud = point_cloud def update(self, vehicle : VehicleState) -> Dict[str,AgentState]: print("0PED DETECT UPDATE", self.zed_image is None, self.point_cloud is None, self.camera_info is None) diff --git a/GEMstack/onboard/perception/td_multi_class_tracker.py b/GEMstack/onboard/perception/td_multi_class_tracker.py index 808eb9994..dcbd7a117 100644 --- a/GEMstack/onboard/perception/td_multi_class_tracker.py +++ b/GEMstack/onboard/perception/td_multi_class_tracker.py @@ -27,7 +27,7 @@ class TDMultiClassTracker(Component): def __init__( self, - kalman_config_files=["GEMstack/onboard/perception/2D_bounding_box_config.py"], + kalman_config_files=["GEMstack/knowledge/prediction/2D_bounding_box_config.py"], kalman_classes = [AgentEnum.PEDESTRIAN], detection_file_name="GEMstack/onboard/prediction/tracking_results.txt", test=False, From 83c0022eb28a18880cb7a559a8fa600202840843 Mon Sep 17 00:00:00 2001 From: Ananya Y <14322650+anan-ya-y@users.noreply.github.com> Date: Wed, 1 May 2024 18:16:13 -0500 Subject: [PATCH 142/232] Revert "S2024 Integrate Kalman Filter with Detection/Tracking" --- .../calibration/gem_e4_intrinsic.txt | 3 - .../calibration/gem_e4_lidar2oak.txt | 4 - .../calibration/gem_e4_lidar2vehicle.txt | 4 - .../knowledge/defaults/computation_graph.yaml | 5 +- .../perception/td_multi_class_detector.py | 250 ------------------ .../perception/td_multi_class_tracker.py | 195 -------------- GEMstack/state/all.py | 7 - launch/detect_and_track.yaml | 45 ---- 8 files changed, 1 insertion(+), 512 deletions(-) delete mode 100644 GEMstack/knowledge/calibration/gem_e4_intrinsic.txt delete mode 100644 GEMstack/knowledge/calibration/gem_e4_lidar2oak.txt delete mode 100644 GEMstack/knowledge/calibration/gem_e4_lidar2vehicle.txt delete mode 100644 GEMstack/onboard/perception/td_multi_class_detector.py delete mode 100644 GEMstack/onboard/perception/td_multi_class_tracker.py delete mode 100644 launch/detect_and_track.yaml diff --git a/GEMstack/knowledge/calibration/gem_e4_intrinsic.txt b/GEMstack/knowledge/calibration/gem_e4_intrinsic.txt deleted file mode 100644 index b2509ef74..000000000 --- a/GEMstack/knowledge/calibration/gem_e4_intrinsic.txt +++ /dev/null @@ -1,3 +0,0 @@ -684.83331299 0. 573.37109375 -0. 684.60968018 363.70092773 -0. 0. 1. \ No newline at end of file diff --git a/GEMstack/knowledge/calibration/gem_e4_lidar2oak.txt b/GEMstack/knowledge/calibration/gem_e4_lidar2oak.txt deleted file mode 100644 index fedf4d5bd..000000000 --- a/GEMstack/knowledge/calibration/gem_e4_lidar2oak.txt +++ /dev/null @@ -1,4 +0,0 @@ --0.00519 -0.99997 0.005352 0.1627 --0.0675 -0.00499 -0.9977 -0.03123 -0.99771 -0.00554 -0.06743 -0.7284 -0 0 0 1 \ No newline at end of file diff --git a/GEMstack/knowledge/calibration/gem_e4_lidar2vehicle.txt b/GEMstack/knowledge/calibration/gem_e4_lidar2vehicle.txt deleted file mode 100644 index 5dff05e15..000000000 --- a/GEMstack/knowledge/calibration/gem_e4_lidar2vehicle.txt +++ /dev/null @@ -1,4 +0,0 @@ -0.998621 -0.052503 0.000000 1.10000 -0.052503 0.998621 0.000000 0.000000 -0.000000 0.000000 1.000000 2.030000 -0.000000 0.000000 0.000000 1.000000 diff --git a/GEMstack/knowledge/defaults/computation_graph.yaml b/GEMstack/knowledge/defaults/computation_graph.yaml index b0d3bb9a5..d7a606326 100644 --- a/GEMstack/knowledge/defaults/computation_graph.yaml +++ b/GEMstack/knowledge/defaults/computation_graph.yaml @@ -17,10 +17,7 @@ components: outputs: obstacles - agent_detection: inputs: vehicle - outputs: detected_agents - - agent_tracking: - inputs: detected_agents - outputs: tracking_frames + outputs: agents - lane_detection: inputs: [vehicle, roadgraph] outputs: vehicle_lane diff --git a/GEMstack/onboard/perception/td_multi_class_detector.py b/GEMstack/onboard/perception/td_multi_class_detector.py deleted file mode 100644 index 57cd0ab86..000000000 --- a/GEMstack/onboard/perception/td_multi_class_detector.py +++ /dev/null @@ -1,250 +0,0 @@ -from ...state import AllState,VehicleState,ObjectPose,ObjectFrameEnum,AgentState,AgentEnum,AgentActivityEnum -from ...utils import settings -from ...mathutils import transforms -from ..interface.gem import GEMInterface -from ..component import Component -from ultralytics import YOLO -import cv2 -try: - from sensor_msgs.msg import CameraInfo - from image_geometry import PinholeCameraModel - import rospy -except ImportError: - pass -import numpy as np -from typing import Dict,Tuple, List -import time -from numpy.linalg import inv - - -def Pmatrix(fx,fy,cx,cy): - """Returns a projection matrix for a given set of camera intrinsics.""" - return np.array([[fx,0,cx,0], - [0,fy,cy,0], - [0,0,1,0]]) - -def project_point_cloud(point_cloud : np.ndarray, P : np.ndarray, xrange : Tuple[int,int], yrange : Tuple[int,int]) -> Tuple[np.ndarray,np.ndarray]: - """Projects a point cloud into a 2D image using a camera intrinsic projection matrix P. - - Returns: - - point_cloud_image: an Nx2 array of (u,v) visible image coordinates - - image_indices: an array of N indices of visible points into the original point cloud - """ - - pc_with_ids = np.hstack((point_cloud,np.arange(len(point_cloud)).reshape(-1,1))) - pc_fwd = pc_with_ids[pc_with_ids[:,2] > 0] - pxform = pc_fwd[:,:3].dot(P[:3,:3].T) + P[:3,3] - uv = (pxform[:,0:2].T/pxform[:,2]).T - inds = np.logical_and(np.logical_and(uv[:,0] >= xrange[0],uv[:,0] < xrange[1]), - np.logical_and(uv[:,1] >= yrange[0],uv[:,1] < yrange[1])) - point_cloud_image = uv[inds] - image_indices = pc_fwd[inds,3].astype(int) - return point_cloud_image, image_indices - -def lidar_to_image(point_cloud_lidar: np.ndarray, extrinsic : np.ndarray, intrinsic : np.ndarray): - - homo_point_cloud_lidar = np.hstack((point_cloud_lidar, np.ones((point_cloud_lidar.shape[0], 1)))) # (N, 4) - pointcloud_pixel = (intrinsic @ extrinsic @ (homo_point_cloud_lidar).T) # (3, N) - pointcloud_pixel = pointcloud_pixel.T # (N, 3) - - # normalize - pointcloud_pixel[:, 0] /= pointcloud_pixel[:, 2] # normalize - pointcloud_pixel[:, 1] /= pointcloud_pixel[:, 2] # normalize - point_cloud_image = pointcloud_pixel[:,:2] # (N, 2) - return point_cloud_image - -def lidar_to_vehicle(point_cloud_lidar: np.ndarray, T_lidar2_Gem: np.ndarray): - ones = np.ones((point_cloud_lidar.shape[0], 1)) - pcd_homogeneous = np.hstack((point_cloud_lidar, ones)) # (N, 4) - pointcloud_trans = np.dot(T_lidar2_Gem, pcd_homogeneous.T) # (4, N) - pointcloud_trans = pointcloud_trans.T # (N, 4) - point_cloud_image_world = pointcloud_trans[:, :3] # (N, 3) - return point_cloud_image_world - -def filter_lidar_by_range(point_cloud, xrange: Tuple[float, float], yrange: Tuple[float, float]): - xmin, xmax = xrange - ymin, ymax = yrange - idxs = np.where((point_cloud[:, 0] > xmin) & (point_cloud[:, 0] < xmax) & - (point_cloud[:, 1] > ymin) & (point_cloud[:, 1] < ymax) ) - return point_cloud[idxs] - -class TDMultiClassDetector(Component): - """Detects and tracks pedestrians.""" - def __init__(self,vehicle_interface : GEMInterface, extrinsic=None): - # State Estimation - self.vehicle_interface = vehicle_interface - - self.detector = YOLO('GEMstack/knowledge/detection/yolov8n.pt') - self.camera_info_sub = None - self.camera_info = None - self.zed_image = None - - - - self.point_cloud = None - self.point_cloud_zed = None - assert(settings.get('vehicle.calibration.top_lidar.reference') == 'rear_axle_center') - assert(settings.get('vehicle.calibration.front_camera.reference') == 'rear_axle_center') - - - if extrinsic is None: - extrinsic = np.loadtxt("GEMstack/knowledge/calibration/gem_e4_lidar2oak.txt") - self.extrinsic = np.array(extrinsic) - - intrinsic = np.loadtxt("GEMstack/knowledge/calibration/gem_e4_intrinsic.txt") - self.intrinsic = np.concatenate([intrinsic, np.zeros((3, 1))], axis=1) - - T_lidar2_Gem = np.loadtxt("GEMstack/knowledge/calibration/gem_e4_lidar2vehicle.txt") - self.T_lidar2_Gem = np.asarray(T_lidar2_Gem) - - # Hardcode the roi area for agents - self.xrange = (1, 20) - self.yrange = (-10, 10) - - - def rate(self): - return 2.5 - - def state_inputs(self): - return ['vehicle'] - - def state_outputs(self): - return ['detected_agents'] - - def test_set_data(self, zed_image, point_cloud, camera_info='dummy'): - self.zed_image = zed_image - self.point_cloud = point_cloud - self.camera_info = camera_info - - def initialize(self): - print("INITIALIZE PED DETECT") - # tell the vehicle to use image_callback whenever 'front_camera' gets a reading, and it expects images of type cv2.Mat - self.vehicle_interface.subscribe_sensor('front_camera',self.image_callback,cv2.Mat) - # tell the vehicle to use lidar_callback whenever 'top_lidar' gets a reading, and it expects numpy arrays - self.vehicle_interface.subscribe_sensor('top_lidar',self.lidar_callback,np.ndarray) - # subscribe to the Zed CameraInfo topic - self.camera_info_sub = rospy.Subscriber("/oak/rgb/camera_info", CameraInfo, self.camera_info_callback) - - def image_callback(self, image : cv2.Mat): - self.zed_image = image - - def camera_info_callback(self, info : CameraInfo): - self.camera_info = info - - def lidar_callback(self, point_cloud: np.ndarray): - self.point_cloud = point_cloud - - def update(self, vehicle : VehicleState) -> Dict[str,AgentState]: - print("0PED DETECT UPDATE", self.zed_image is None, self.point_cloud is None, self.camera_info is None) - if self.zed_image is None: - # no image data yet - print("zed") - return {} - if self.point_cloud is None: - # no lidar data yet - print("pc") - return {} - if self.camera_info is None: - # no camera info yet - print("camera") - return {} - - detected_agents = self.detect_agents() # TODO: to ask SE to output detected_agents only - - - print("Pedestrian Detection detected agents: ", detected_agents) - return detected_agents - - - def box_to_agent(self, box, point_cloud_image, point_cloud_image_world): - """Creates a 3D agent state from an (x,y,w,h) bounding box. - """ - - # print ('Detect a pedestrian!') - - # get the idxs of point cloud that belongs to the agent - x,y,w,h = box - xmin, xmax = x - w/2, x + w/2 - ymin, ymax = y - h/2, y + h/2 - - - # enlarge bbox in case inaccuracy calibration - enlarge_factor = 3 - xmin *= enlarge_factor - xmax *= enlarge_factor - ymin *= enlarge_factor - ymax *= enlarge_factor - - agent_world_pc = point_cloud_image_world - - - # Find the point_cloud that is closest to the center of our bounding box - center_x = x + w / 2 - center_y = y + h / 2 - distances = np.linalg.norm(point_cloud_image - [center_x, center_y], axis=1) - closest_point_cloud_idx = np.argmin(distances) - closest_point_cloud = point_cloud_image_world[closest_point_cloud_idx] - - x, y, _ = closest_point_cloud - pose = ObjectPose(t=0, x=x, y=y, z=0, yaw=0, pitch=0, roll=0, frame=ObjectFrameEnum.CURRENT) - - # Specify AgentState. - l = np.max(agent_world_pc[:, 0]) - np.min(agent_world_pc[:, 0]) - w = np.max(agent_world_pc[:, 1]) - np.min(agent_world_pc[:, 1]) - h = np.max(agent_world_pc[:, 2]) - np.min(agent_world_pc[:, 2]) - - dims = (w, h, l) - - return AgentState(pose=pose,dimensions=dims,outline=None,type=AgentEnum.PEDESTRIAN,activity=AgentActivityEnum.MOVING,velocity=(0,0,0),yaw_rate=0) - - # Behavior Prediction added test argument to return matchings - def detect_agents(self, test=False): - detection_result = self.detector(self.zed_image,verbose=False) - - # TODO: create boxes from detection result - pedestrian_boxes = [] - car_boxes = [] # add car objects - - for box in detection_result[0].boxes: # only one image, so use index 0 of result - class_id = int(box.cls[0].item()) - if class_id == 0: # class 0 stands for pedestrian - bbox = box.xywh[0].tolist() - pedestrian_boxes.append(bbox) - - if class_id == 2: # class 2 stands for car - bbox = box.xywh[0].tolist() - car_boxes.append(bbox) - - - # Only keep lidar point cloud that lies in roi area for agents - point_cloud_lidar = filter_lidar_by_range(self.point_cloud, self.xrange, self.yrange) - - # Tansfer lidar point cloud to camera frame - point_cloud_image = lidar_to_image(point_cloud_lidar, self.extrinsic, self.intrinsic) - - # Tansfer lidar point cloud to vehicle frame - point_cloud_image_world = lidar_to_vehicle(point_cloud_lidar, self.T_lidar2_Gem) - - - - # Find agents - detected_agents = [] - for i,b in enumerate(pedestrian_boxes): - agent = self.box_to_agent(b, point_cloud_image, point_cloud_image_world) - agent.type = AgentEnum.PEDESTRIAN - if agent is not None: - detected_agents.append(agent) - - for i,b in enumerate(car_boxes): - agent = self.box_to_agent(b, point_cloud_image, point_cloud_image_world) - agent.type = AgentEnum.CAR - if agent is not None: - detected_agents.append(agent) - - - if test: # Behavior Prediction - return detected_agents, detection_result - return detected_agents - - - \ No newline at end of file diff --git a/GEMstack/onboard/perception/td_multi_class_tracker.py b/GEMstack/onboard/perception/td_multi_class_tracker.py deleted file mode 100644 index dcbd7a117..000000000 --- a/GEMstack/onboard/perception/td_multi_class_tracker.py +++ /dev/null @@ -1,195 +0,0 @@ -from ...state import ( - ObjectPose, - ObjectFrameEnum, - AgentState, - AgentEnum, - AgentActivityEnum, -) -from ...utils import settings -from ...mathutils import transforms -from ..interface.gem import GEMInterface -from ..component import Component -from ultralytics import YOLO -import cv2 - -try: - from sensor_msgs.msg import CameraInfo - from image_geometry import PinholeCameraModel - import rospy -except ImportError: - pass - -import numpy as np -from typing import Dict, List -from .kalman_tracker import KalmanTracker # Behavior Prediction Team - -# TOP DOWN 2D BOUNDING BOX TRACKER FOR MULTIPLE OBJECTS/AGENTS -class TDMultiClassTracker(Component): - def __init__( - self, - kalman_config_files=["GEMstack/knowledge/prediction/2D_bounding_box_config.py"], - kalman_classes = [AgentEnum.PEDESTRIAN], - detection_file_name="GEMstack/onboard/prediction/tracking_results.txt", - test=False, - write_all=False, - write_limit=8, - velocity_threshold=0.1 - ): - self.velocity_threshold = velocity_threshold ** 2 - self.kalman_trackers = [KalmanTracker(config_file_path=kalman_config_file) for kalman_config_file in kalman_config_files] - self.kalman_classes = kalman_classes - self.tracking_results = {ag_class:{} for ag_class in kalman_classes} - self.current_frame = 0 - self.write_limit= write_limit - - self.detection_file_name = detection_file_name - self.write_all = write_all - - f = open(self.detection_file_name, "w") - f.close() - - - # For Testing - self.test = test - if self.test: - self.detection_file_name = detection_file_name - self.write_all = write_all - f = open(self.detection_file_name, "w") - f.close() - - """Base class for top-level components in the execution stack.""" - - def rate(self) -> float: - """Returns the rate in Hz at which this component should be updated.""" - return 2.5 - - def state_inputs(self) -> List[str]: - """Returns the list of AllState inputs this component requires.""" - return ["detected_agents"] - - def state_outputs(self) -> List[str]: - """Returns the list of AllState outputs this component generates.""" - return ["tracking_frames"] - - def healthy(self): - """Returns True if the element is in a stable state.""" - return True - - def initialize(self): - """Initialize the component. This is called once before the first - update.""" - pass - - def cleanup(self): - """Cleans up resources used by the component. This is called once after - the last update.""" - pass - - def update(self, detected_agents: List[AgentState]): - print("Updating with detected, ", detected_agents) - """Update the component.""" - self.track_agents(detected_agents=detected_agents) - return self.tracking_results - - def debug(self, item, value): - """Debugs a streaming value within this component""" - if hasattr(self, "debugger"): - self.debugger.debug(item, value) - - def debug_event(self, label): - """Debugs an event within this component""" - if hasattr(self, "debugger"): - self.debugger.debug_event(label) - - def track_agents(self, detected_agents: List[AgentState]): - """Given a list of detected agents, updates the state of the agents using a Kalman Tracker.""" - all_tracked_objects = {} - for i, kalman_tracker in enumerate(self.kalman_trackers): - detections = [] - for agent in detected_agents: - if agent.type == self.kalman_classes[i]: - x, y, z = agent.pose.x, agent.pose.y, agent.pose.z - w, h, l = agent.dimensions - detections.append(np.array([x, y, w, l])) - - kalman_agent_states, matches = kalman_tracker.update_pedestrian_tracking( - detections - ) - tracking_results = {} - for pid in kalman_agent_states: - ag_state = kalman_agent_states[pid] - curr_activity = AgentActivityEnum.MOVING - v2 = (ag_state[4] ** 2 + ag_state[5] ** 2) - if (v2 <= self.velocity_threshold): - curr_activity = AgentActivityEnum.STOPPED - tracking_results[pid] = AgentState( - pose=ObjectPose( - t=0, - x=ag_state[0], - y=ag_state[1], - z=0, - yaw=0, - pitch=0, - roll=0, - frame=ObjectFrameEnum.CURRENT, - ), - dimensions=(ag_state[2], ag_state[3], 1.5), - velocity=(ag_state[4], ag_state[5], 0), - type=self.kalman_classes[i], - activity=curr_activity, - yaw_rate=0, - outline=None, - ) - all_tracked_objects[self.kalman_classes[i]] = tracking_results - - self.update_track_history(all_tracked_objects) - - if self.test: - return tracking_results, matches - - - def update_track_history( - self, all_ag_dict: Dict[AgentEnum, Dict[int, AgentState]] - ): - for ag_class, ag_dict in all_ag_dict.items(): - for pid in sorted(ag_dict): - if self.current_frame in self.tracking_results[ag_class]: - self.tracking_results[ag_class][self.current_frame][pid] = ag_dict[pid] - else: - self.tracking_results[ag_class][self.current_frame] = {pid: ag_dict[pid]} - if not self.write_all: - # Remove old tracking information - self.tracking_results[ag_class].pop(self.current_frame - self.write_limit, None) - - self.current_frame += 1 - - def get_stationary_pedestrians(tracking_frames): - epsilon = 0.1 #hyperparam - num_past_frames = 3 #hyperparam - pedestrian_frames = tracking_frames[AgentEnum.Pedestrian] - latest_frames = sorted(list(pedestrian_frames.keys()))[-num_past_frames:] - all_peds_set = set() # all pedestrians - non_stat_peds = set() # pedestrians that are not stationary - - prev_frame_peds = set() # pedestrians that were seen in the prev frame. - for frame in latest_frames: - frame_peds = set() - for pid,ag_state in pedestrian_frames[frame].items(): - # if the velocity of the pedestrians are more than 0, - # then add the pedestrian to the set of non-stationary pedestrians - if ag_state.activity == AgentActivityEnum.STOPPED: - non_stat_peds.add(pid) - else: # ped velocity is 0 - # if this frame is the first time a pedestrian shows up, it's not stationary - if pid not in prev_frame_peds: - non_stat_peds.add(pid) - - all_peds_set.add(pid) - frame_peds.add(pid) - - - all_peds_set = all_peds_set.intersect(frame_peds) - prev_frame_peds = frame_peds - - stationary_pedestrians = all_peds_set - non_stat_peds - return stationary_pedestrians \ No newline at end of file diff --git a/GEMstack/state/all.py b/GEMstack/state/all.py index 060821345..fc976fe24 100644 --- a/GEMstack/state/all.py +++ b/GEMstack/state/all.py @@ -11,8 +11,6 @@ from .trajectory import Trajectory from .predicates import PredicateValues from typing import Dict,List,Optional -from .agent import AgentState -from .agent import AgentEnum @dataclass @register @@ -48,11 +46,6 @@ class AllState(SceneState): intent_update_time : float = 0 route_update_time : float = 0 trajectory_update_time : float = 0 - - # pedestrian detection and tracking items - detected_agents : List[AgentState] = None - tracking_frames : Dict[AgentEnum, Dict[int, Dict[int, AgentState]]] = None - predicted_trajectories : List[Dict[List[AgentState]]] = None @staticmethod def zero(): diff --git a/launch/detect_and_track.yaml b/launch/detect_and_track.yaml deleted file mode 100644 index 5a4d4e3e8..000000000 --- a/launch/detect_and_track.yaml +++ /dev/null @@ -1,45 +0,0 @@ -description: "Detect the peds" -mode: hardware -vehicle_interface: gem_hardware.GEMHardwareInterface -mission_execution: StandardExecutor - -# Recovery behavior after a component failure -recovery: - planning: - trajectory_tracking : recovery.StopTrajectoryTracker - -# Driving behavior for the GEM vehicle. Runs detection and tracking on real vehicle. -drive: - perception: - state_estimation : GNSSStateEstimator - agent_detection : td_multi_class_detector.TDMultiClassDetector - agent_tracking : td_multi_class_tracker.TDMultiClassTracker - perception_normalization : StandardPerceptionNormalizer - -log: - # Specify the top-level folder to save the log files. Default is 'logs' - folder : 'logs' - # If prefix is specified, then the log folder will be named with the prefix followed by the date and time. Default no prefix - prefix : 'detect_and_track_' - # If suffix is specified, then logs will output to folder/prefix+suffix. Default uses date and time as the suffix - #suffix : 'test3' - # Specify which ros topics to record to vehicle.bag. Default records nothing. This records the "standard" ROS topics. - ros_topics : - # Specify options to pass to rosbag record. Default is no options. - #rosbag_options : '--split --size=1024' - # If True, then record all readings / commands of the vehicle interface. Default False - vehicle_interface : True - # Specify which components to record to behavior.json. Default records nothing - # components : ['state_estimation','agent_detection', 'agent_tracking'] - # Specify which components of state to record to state.json. Default records nothing - # state: ['all'] - # Specify the rate in Hz at which to record state to state.json. Default records at the pipeline's rate - # state_rate: 10 -replay: # Add items here to set certain topics / inputs to be replayed from logs - # Specify which log folder to replay from - log: - ros_topics : [] - components : [] - -#usually can keep this constant -computation_graph: !include "../GEMstack/knowledge/defaults/computation_graph.yaml" \ No newline at end of file From 0ee8810df6417a5ab84e91d51ee8b5e93dc71003 Mon Sep 17 00:00:00 2001 From: Kris Hauser Date: Wed, 1 May 2024 18:16:43 -0500 Subject: [PATCH 143/232] Revert "Adds Kalman Tracker class" --- .../prediction/2D_bounding_box_config.py | 104 ---------- GEMstack/onboard/perception/kalman_tracker.py | 182 ------------------ requirements.txt | 1 - 3 files changed, 287 deletions(-) delete mode 100644 GEMstack/knowledge/prediction/2D_bounding_box_config.py delete mode 100644 GEMstack/onboard/perception/kalman_tracker.py diff --git a/GEMstack/knowledge/prediction/2D_bounding_box_config.py b/GEMstack/knowledge/prediction/2D_bounding_box_config.py deleted file mode 100644 index 1ba621bc7..000000000 --- a/GEMstack/knowledge/prediction/2D_bounding_box_config.py +++ /dev/null @@ -1,104 +0,0 @@ -import numpy as np - -## Config file for Kalman filtering for 2D bounding box prediction -## State has 6 dimensions (x,y,length,width, vel_x, vel_y) -## Observation/measurement is 2D bounding box [4 dimensions: x, y, length, width] - -''' -CONFIG FILE for Kalman filter - -MUST PROVIDE: -1: dim_x = the dimensions for state) - -2: dim_z = the dimensions for measurement - -3: F = state transition matrix. Must be shape (dim_x, dim_x) - -4: H = measurement matrix. Must be shape (dim_z, dim_x) - -5: P = Covariance matrix for initial observation. Represents uncertainty of initial state. - Must be matrix of shape (dim_x, dim_x) - -6: Q = Process Covariance Matrix. Represents uncertainty of process - Must be matrix of shape (dim_x, dim_x) - -7: R = Measurement Covariance Matrix. Represents uncertainty of measurement - Must be matrix of shape (dim_z, dim_z) - -8: max_age = After how many time_steps with no observation should we delete a kalman tracker. - Must be positive int - -9: cost_function(predicted_state, observation) = - function which calculates cost (or dissimilarity) between a - predicted state (size dim_x) and an observation (size dim_z) - -10: threshold = max limit for whether we consider a predicted state and new observation a match - -11: initial_state(measurement) = - function which provides initial state, given just the first observation - measurement is vector of size (dim_z). Output is vector of size (dim_x) -''' - - -# state is vector with [x,y,l,w,vel_x, vel_y] -dim_x = 6 -# measurements (sensor observations/bounding boxes) are just [x,y,l,w] -dim_z = 4 - -F = np.array([[1, 0, 0, 0, 1, 0], - [0, 1, 0, 0, 0, 1], - [0, 0, 1, 0, 0, 0], - [0, 0, 0, 1, 0, 0], - [0, 0, 0, 0, 1, 0], - [0, 0, 0, 0, 0, 1]]) - -H = np.array([[1, 0, 0, 0, 0, 0], - [0, 1, 0, 0, 0, 0], - [0, 0, 1, 0, 0, 0], - [0, 0, 0, 1, 0, 0]]) - -P = np.eye(dim_x) * 100 - -Q = np.eye(dim_x) * 0.01 - -R = np.eye(dim_z) * 1 - -max_age = 4 - -# IoU must be at least 0.3 or higher to be considered a match -threshold = -0.6 - -# This cost function is IoU (intersection over Union) of 2D bounding boxes -# Higher the IoU (overlapping region), higher is the similarity -# Since this is a cost function (measurement of dissimilarity), we negate the IoU -def cost_function(predicted_state, measurement): - rect1 = predicted_state[0:4] - rect2 = measurement - rect1_x1, rect1_y1 = rect1[0] - rect1[2]/2, rect1[1] - rect1[3]/2 - rect1_x2, rect1_y2 = rect1[0] + rect1[2]/2, rect1[1] + rect1[3]/2 - rect2_x1, rect2_y1 = rect2[0] - rect2[2]/2, rect2[1] - rect2[3]/2 - rect2_x2, rect2_y2 = rect2[0] + rect2[2]/2, rect2[1] + rect2[3]/2 - - # Calculate the coordinates of the intersection rectangle - inter_x1 = max(rect1_x1, rect2_x1) - inter_y1 = max(rect1_y1, rect2_y1) - inter_x2 = min(rect1_x2, rect2_x2) - inter_y2 = min(rect1_y2, rect2_y2) - - # Calculate the area of intersection - inter_area = max(0, inter_x2 - inter_x1) * max(0, inter_y2 - inter_y1) - - # Calculate the area of union - rect1_area = rect1[2] * rect1[3] - rect2_area = rect2[2] * rect2[3] - union_area = rect1_area + rect2_area - inter_area - - # Calculate the IoU - iou = inter_area / union_area if union_area > 0 else 0 - return -iou - -# given measurement of [x,y,l,w], set state to [x,y,l,w,0,0] -def initial_state(measurement): - state = np.zeros(dim_x) - state[0:dim_z] = measurement - return state \ No newline at end of file diff --git a/GEMstack/onboard/perception/kalman_tracker.py b/GEMstack/onboard/perception/kalman_tracker.py deleted file mode 100644 index 4cdaff811..000000000 --- a/GEMstack/onboard/perception/kalman_tracker.py +++ /dev/null @@ -1,182 +0,0 @@ -from filterpy.kalman import KalmanFilter -from scipy.optimize import linear_sum_assignment -import numpy as np -import importlib.util - - -''' -CONFIG FILE/PRARAMETERS for KalmanTracker: -(some examples for configs are provided/set as defaults. ) - -MUST PROVIDE: -1: dim_x = the dimensions for state -2: dim_z = the dimensions for measurement -3: F = state transition matrix. Must be shape (dim_x, dim_x) -4: H = measurement matrix. Must be shape (dim_z, dim_x) -5: P = Covariance matrix for initial observation. Represents uncertainty of initial state. - Must be matrix of shape (dim_x, dim_x) -6: Q = Process Covariance Matrix. Represents uncertainty of process - Must be matrix of shape (dim_x, dim_x) -7: R = Measurement Covariance Matrix. Represents uncertainty of measurement - Must be matrix of shape (dim_z, dim_z) -8: max_age = After how many time_steps with no observation should we delete a kalman tracker. - Must be positive int -9: cost_function(predicted_state, observation) = - function which calculates cost (or dissimilarity) between a - predicted state (size dim_x) and an observation (size dim_z) -10: threshold = max limit for whether we consider a predicted state and new observation a match -11: initial_state(measurement) = - function which provides initial state, given just the first observation - measurement is vector of size (dim_z). Output is vector of size (dim_x) -''' - -class KalmanTracker: - def __init__(self, config_file_path=None, \ - dim_x=4, dim_z=2, F=None, H=None, P= None, Q=None, R=None, \ - max_age=6, cost_function=None, threshold=10, initial_state=None): - - def default_cost_fn(predicted_state, measurement): - return np.linalg.norm(predicted_state[0:2] - measurement) - - def default_initial_state(measurement): - state = np.zeros(dim_x) - state[0:dim_z] = measurement - return state - - - if config_file_path is not None: - spec = importlib.util.spec_from_file_location("config", config_file_path) - config = importlib.util.module_from_spec(spec) - spec.loader.exec_module(config) - - self.kalman_filters = {} - self.max_id = 0 - - self.dim_x = config.dim_x - self.dim_z = config.dim_z - self.F = config.F - self.H = config.H - self.P = config.P - self.Q = config.Q - self.R = config.R - self.max_age = config.max_age - self.threshold = config.threshold - self.cost_function = config.cost_function - self.initial_state = config.initial_state - - else: # if no config file is provided, use the parameters provided OR defaults. - self.kalman_filters = {} - self.max_id = 0 - - self.dim_x = dim_x - self.dim_z = dim_z - self.F = np.array([[1, 0, 1, 0], - [0, 1, 0, 1], - [0, 0, 1, 0], - [0, 0, 0, 1]]) if F is None else F - self.H = np.array([[1, 0, 0, 0], - [0, 1, 0, 0]]) if H is None else H - self.P = np.eye(dim_x) * 100 if P is None else P - self.Q = np.eye(dim_x) * 0.01 if Q is None else Q - self.R = np.eye(dim_z) * 1 if R is None else R - self.max_age = max_age - self.threshold = threshold - self.cost_function = default_cost_fn if cost_function is None else cost_function - self.initial_state = default_initial_state if initial_state else initial_state - - - # Must be called in loop to continuously update all tracked objects - # bounding_boxes are just the list of measurements/observations/sensor readings - def update_pedestrian_tracking(self, bounding_boxes): - - # Predict the next state for each pedestrian using past state - predicted_states = {} - for pedestrian_id, kalman_filter in self.kalman_filters.items(): - kalman_filter.predict() - # kalman_filter.x now stores the prediction for the future state. - predicted_states[pedestrian_id] = kalman_filter.x - - # Match observed bounding boxes with predicted future states - cost_matrix, pedestrian_id_list = self.compute_cost_matrix(predicted_states, bounding_boxes) - matches = self.compute_matching(cost_matrix, pedestrian_id_list) - - # Update matched pedestrians - matched_pedestrians = set() - matched_bboxes = set() - for pedestrian_id, bbox_idx in matches.items(): - self.kalman_filters[pedestrian_id].update(bounding_boxes[bbox_idx]) - self.kalman_filters[pedestrian_id].time_since_update = 0 - matched_pedestrians.add(pedestrian_id) - matched_bboxes.add(bbox_idx) - - # For unmatched Kalman filters, increase time since last update by 1 - for pedestrian_id in (set(self.kalman_filters.keys()) - matched_pedestrians): - self.kalman_filters[pedestrian_id].time_since_update += 1 - self.delete_old_tracks() - - # For unmatched bboxes, create a new kalman filter - for col_idx in (set(range(len(bounding_boxes))) - matched_bboxes): - pedestrian_id = self.generate_new_pedestrian_id() - self.kalman_filters[pedestrian_id] = self.create_kalman_filter(bounding_boxes[col_idx]) - matches[pedestrian_id]= col_idx - # Return the tracked pedestrians (mapping pedestrian ID to state) - tracked_pedestrians = { - pedestrian_id: kalman_filter.x for pedestrian_id, kalman_filter in self.kalman_filters.items() - } - return tracked_pedestrians, matches - - ### HELPER FUNCTIONS - def generate_new_pedestrian_id(self): - self.max_id += 1 - return str(self.max_id) - - def delete_old_tracks(self): - to_delete = [] - for pedestrian_id, kalman_filter in self.kalman_filters.items(): - if kalman_filter.time_since_update > self.max_age: - to_delete.append(pedestrian_id) - for pedestrian_id in to_delete: - del self.kalman_filters[pedestrian_id] - - def compute_cost_matrix(self,predicted_states, bounding_boxes): - cost_matrix = np.zeros((len(predicted_states), len(bounding_boxes))) - ped_id_list = [] - for i, (ped_id, predicted_state) in enumerate(predicted_states.items()): - ped_id_list.append(ped_id) - for j, bounding_box in enumerate(bounding_boxes): - cost_matrix[i, j] = self.cost_function(predicted_state, bounding_box) - return cost_matrix, ped_id_list - - def compute_matching(self, cost_matrix, ped_id_list): - row_indices, col_indices = linear_sum_assignment(cost_matrix) - # Maps pedestrian ID to observed box index - matching = {} - for i in range(len(row_indices)): - # row_indices[i], col_indices[i] is matched according to the linear solver - # but, only include matches that have enough similarity (less than threshold) - if cost_matrix[row_indices[i], col_indices[i]] <= self.threshold: - matching[ped_id_list[i]] = col_indices[i] - return matching - - def create_kalman_filter(self, bounding_box): - kalman_filter = KalmanFilter(dim_x=self.dim_x, dim_z=self.dim_z) - # Initialize the state with the bounding box - kalman_filter.x = self.initial_state(bounding_box) - - # State transition matrix - kalman_filter.F = self.F.copy() - - # Measurement matrix - kalman_filter.H = self.H.copy() - - # Initial state uncertainty - kalman_filter.P = self.P.copy() - - # Process noise (uncertainty of process) - kalman_filter.Q = self.Q.copy() - - # Measurement noise covariance (uncertainty of obtained measurements/bounding boxes) - kalman_filter.R = self.R.copy() - - kalman_filter.time_since_update = 0 - return kalman_filter diff --git a/requirements.txt b/requirements.txt index f516e388b..94db8ba43 100644 --- a/requirements.txt +++ b/requirements.txt @@ -7,4 +7,3 @@ shapely klampt pyyaml dacite -filterpy \ No newline at end of file From e6c0f6e0557e6e7d85ff1458215e1f3d1474a498 Mon Sep 17 00:00:00 2001 From: onemaple Date: Wed, 1 May 2024 19:32:45 -0500 Subject: [PATCH 144/232] refactor --- app/api-service/.gitignore | 1 + app/api-service/app.py | 48 +++++++++++++++ app/api-service/templates/index.html | 61 +++++++++++++++++++ .../main.py => app/api-service/test.py | 15 +++-- 4 files changed, 121 insertions(+), 4 deletions(-) create mode 100644 app/api-service/.gitignore create mode 100644 app/api-service/app.py create mode 100644 app/api-service/templates/index.html rename api-service/main.py => app/api-service/test.py (89%) diff --git a/app/api-service/.gitignore b/app/api-service/.gitignore new file mode 100644 index 000000000..2eea525d8 --- /dev/null +++ b/app/api-service/.gitignore @@ -0,0 +1 @@ +.env \ No newline at end of file diff --git a/app/api-service/app.py b/app/api-service/app.py new file mode 100644 index 000000000..798f84882 --- /dev/null +++ b/app/api-service/app.py @@ -0,0 +1,48 @@ +from flask import Flask, render_template, request, jsonify +import googlemaps +from dotenv import load_dotenv +import os +# Load the environment variables from the .env file +load_dotenv() +api_key = os.getenv('GOOGLE_MAPS_API_KEY') + +app = Flask(__name__) + + +gmaps = googlemaps.Client(key=api_key) + +@app.route('/') +def index(): + return render_template('index.html', api_key=api_key) + +@app.route('/find_place', methods=['POST']) +def find_place(): + place_name = request.form['place_name'] + + # Search for places based on the input name + places_result = gmaps.places(query=place_name) + + if places_result['status'] == 'OK' and len(places_result['results']) > 0: + # Get the first (best-matched) place from the search results + place = places_result['results'][0] + + # Extract the place ID + place_id = place['place_id'] + + # Retrieve the details of the place using the place ID + place_details = gmaps.place(place_id=place_id) + + if place_details['status'] == 'OK': + # Extract the latitude and longitude coordinates + lat = place_details['result']['geometry']['location']['lat'] + lng = place_details['result']['geometry']['location']['lng'] + print(lat, lng) + # Return the coordinates as JSON + return jsonify({'lat': lat, 'lng': lng}) + else: + return jsonify({'error': 'Unable to retrieve place details'}) + else: + return jsonify({'error': 'No places found'}) + +if __name__ == '__main__': + app.run(debug=True) \ No newline at end of file diff --git a/app/api-service/templates/index.html b/app/api-service/templates/index.html new file mode 100644 index 000000000..89d75f474 --- /dev/null +++ b/app/api-service/templates/index.html @@ -0,0 +1,61 @@ + + + + Place Finder + + + + + +

Place Finder

+
+ + +
+
+
+ + \ No newline at end of file diff --git a/api-service/main.py b/app/api-service/test.py similarity index 89% rename from api-service/main.py rename to app/api-service/test.py index 7710147ca..b2190a528 100644 --- a/api-service/main.py +++ b/app/api-service/test.py @@ -8,6 +8,12 @@ from GEMstack.mathutils import transforms import math import time +from dotenv import load_dotenv + +# Load the environment variables from the .env file +load_dotenv() +api_key = os.getenv('GOOGLE_MAPS_API_KEY') + def find_place_coordinates(place_name): # Search for places based on the input name places_result = gmaps.places(query=place_name) @@ -27,15 +33,15 @@ def find_place_coordinates(place_name): # Transform the current pose to the car frame (START frame) current_pose_car = current_pose_global.to_frame(ObjectFrameEnum.START, start_pose_abs=start_pose_global) # Return the coordinates in the car frame as JSON - return {'x': current_pose_car.x, 'y': current_pose_car.y, 'yaw': current_pose_car.yaw} - # # Return the coordinates as a dictionary - # return {'lat': lat, 'lng': lng} + return {'global':{'lat': lat, 'lng': lng}, + 'car_frame':{'x': current_pose_car.x, 'y': current_pose_car.y, 'yaw': current_pose_car.yaw}} else: return None else: return None + if __name__ == "__main__": - gmaps = googlemaps.Client(key='REPLACE_WITH_YOUR_API_KEY') + gmaps = googlemaps.Client(key=api_key) # Define the start pose of the car in the global frame start_pose_global = ObjectPose(frame=ObjectFrameEnum.GLOBAL, t=time.time(), y=40.09286250064475, x=-88.23565755734872, yaw=math.radians(90.0)) place_name = "Highbay" @@ -44,6 +50,7 @@ def find_place_coordinates(place_name): print(f"Coordinates for the best-matched place: {coordinates}") else: print(f"No coordinates found for '{place_name}'") + # Geocoding an address # geocode_result = gmaps.geocode('201 St Marys Rd, Champaign, IL') # print(geocode_result) From a4b4c14e5a90dc2dce59ec6dc4d7f00e17630781 Mon Sep 17 00:00:00 2001 From: onemaple Date: Wed, 1 May 2024 20:14:05 -0500 Subject: [PATCH 145/232] add unittest --- app/api-service/test_app.py | 72 +++++++++++++++++++++++++++++++++++++ 1 file changed, 72 insertions(+) create mode 100644 app/api-service/test_app.py diff --git a/app/api-service/test_app.py b/app/api-service/test_app.py new file mode 100644 index 000000000..8b18ebec1 --- /dev/null +++ b/app/api-service/test_app.py @@ -0,0 +1,72 @@ +from flask import Flask +import pytest +from app import app, find_place +from unittest.mock import MagicMock, patch + +# Create a test client +@pytest.fixture +def client(): + app.config['TESTING'] = True + with app.test_client() as client: + yield client + +# Mock the googlemaps.Client class +@pytest.fixture +def mock_gmaps(): + with patch('googlemaps.Client') as mock_client: + yield mock_client + +def test_find_place_success(client, mock_gmaps): + # Mock the places API response + mock_place_result = { + 'status': 'OK', + 'results': [ + { + 'place_id': 'abc123', + 'geometry': { + 'location': { + 'lat': 40.0930404, + 'lng': -88.2356592 + } + } + } + ] + } + mock_gmaps.return_value.places.return_value = mock_place_result + + # Mock the place details API response + mock_place_details = { + 'status': 'OK', + 'result': { + 'geometry': { + 'location': { + 'lat': 40.0930404, + 'lng': -88.2356592 + } + } + } + } + mock_gmaps.return_value.place.return_value = mock_place_details + + # Send a request to the find_place endpoint + response = client.post('/find_place', data={'place_name': 'Highbay'}) + + # Assert the response + assert response.status_code == 200 + assert response.json == { 'lat': 40.0930404, + 'lng': -88.2356592} + +def test_find_place_no_results(client, mock_gmaps): + # Mock the places API response with no results + mock_place_result = { + 'status': 'OK', + 'results': [] + } + mock_gmaps.return_value.places.return_value = mock_place_result + + # Send a request to the find_place endpoint + response = client.post('/find_place', data={'place_name': 'InvalidPlace'}) + + # Assert the response + assert response.status_code == 200 + assert response.json == {'error': 'No places found'} From a6556416fc46fd505fbdb41bee02925fe360bbe1 Mon Sep 17 00:00:00 2001 From: onemaple Date: Wed, 1 May 2024 20:14:21 -0500 Subject: [PATCH 146/232] refactor end to end test --- app/E2E_test.py | 48 ++++++++++++++++++++++++++++ app/api-service/test.py | 71 ----------------------------------------- 2 files changed, 48 insertions(+), 71 deletions(-) create mode 100644 app/E2E_test.py delete mode 100644 app/api-service/test.py diff --git a/app/E2E_test.py b/app/E2E_test.py new file mode 100644 index 000000000..f003bf251 --- /dev/null +++ b/app/E2E_test.py @@ -0,0 +1,48 @@ +import requests +from datetime import datetime +import sys +import os +sys.path.append(os.path.join(os.getcwd(), '..')) +from GEMstack.state import PhysicalObject,ObjectPose,ObjectFrameEnum +from GEMstack.state.physical_object import _get_frame_chain +from GEMstack.mathutils import transforms +import math +import time + +# Replace with your actual API endpoint +API_ENDPOINT = 'http://localhost:5000/find_place' + +# Define the start pose of the car in the global frame +start_pose_global = ObjectPose(frame=ObjectFrameEnum.GLOBAL, t=time.time(), y=40.09286250064475, x=-88.23565755734872, yaw=math.radians(90.0)) + +def test_find_place(): + # Test case 1: Valid place name + place_name = 'Highbay' + response = requests.post(API_ENDPOINT, data={'place_name': place_name}) + assert response.status_code == 200 + data = response.json() + assert 'lat' in data + assert 'lng' in data + print(f"Latitude: {data['lat']}") + print(f"Longitude: {data['lng']}") + + # Convert coordinates to car frame + current_pose_global = ObjectPose(frame=ObjectFrameEnum.GLOBAL, t=time.time(), y=data['lat'], x=data['lng'], yaw=math.radians(90.0)) + current_pose_car = current_pose_global.to_frame(ObjectFrameEnum.START, start_pose_abs=start_pose_global) + + print(f"Place: {place_name}") + print(f"Car Frame - X: {current_pose_car.x}, Y: {current_pose_car.y}, Yaw: {current_pose_car.yaw}") + + # Test case 2: Invalid place name + place_name = 'InvalidPlace' + response = requests.post(API_ENDPOINT, data={'place_name': place_name}) + assert response.status_code == 200 + data = response.json() + assert 'error' in data + assert data['error'] == 'No places found' + + print(f"Place: {place_name}") + print(f"Error: {data['error']}") + +if __name__ == '__main__': + test_find_place() \ No newline at end of file diff --git a/app/api-service/test.py b/app/api-service/test.py deleted file mode 100644 index b2190a528..000000000 --- a/app/api-service/test.py +++ /dev/null @@ -1,71 +0,0 @@ -import googlemaps -from datetime import datetime -import sys -import os -sys.path.append(os.getcwd()) -from GEMstack.state import PhysicalObject,ObjectPose,ObjectFrameEnum -from GEMstack.state.physical_object import _get_frame_chain -from GEMstack.mathutils import transforms -import math -import time -from dotenv import load_dotenv - -# Load the environment variables from the .env file -load_dotenv() -api_key = os.getenv('GOOGLE_MAPS_API_KEY') - -def find_place_coordinates(place_name): - # Search for places based on the input name - places_result = gmaps.places(query=place_name) - if places_result['status'] == 'OK' and len(places_result['results']) > 0: - # Get the first (best-matched) place from the search results - place = places_result['results'][0] - # Extract the place ID - place_id = place['place_id'] - # Retrieve the details of the place using the place ID - place_details = gmaps.place(place_id=place_id) - if place_details['status'] == 'OK': - # Extract the latitude and longitude coordinates - lat = place_details['result']['geometry']['location']['lat'] - lng = place_details['result']['geometry']['location']['lng'] - # Create an ObjectPose for the current pose in the global frame - current_pose_global = ObjectPose(frame=ObjectFrameEnum.GLOBAL, t=time.time(), y=lat, x=lng, yaw=math.radians(90.0)) - # Transform the current pose to the car frame (START frame) - current_pose_car = current_pose_global.to_frame(ObjectFrameEnum.START, start_pose_abs=start_pose_global) - # Return the coordinates in the car frame as JSON - return {'global':{'lat': lat, 'lng': lng}, - 'car_frame':{'x': current_pose_car.x, 'y': current_pose_car.y, 'yaw': current_pose_car.yaw}} - else: - return None - else: - return None - -if __name__ == "__main__": - gmaps = googlemaps.Client(key=api_key) - # Define the start pose of the car in the global frame - start_pose_global = ObjectPose(frame=ObjectFrameEnum.GLOBAL, t=time.time(), y=40.09286250064475, x=-88.23565755734872, yaw=math.radians(90.0)) - place_name = "Highbay" - coordinates = find_place_coordinates(place_name) - if coordinates: - print(f"Coordinates for the best-matched place: {coordinates}") - else: - print(f"No coordinates found for '{place_name}'") - - # Geocoding an address - # geocode_result = gmaps.geocode('201 St Marys Rd, Champaign, IL') - # print(geocode_result) - # geocode_result = gmaps.geocode('UIUC IRL - The Highbay Facility') - # print(geocode_result) - # # Look up an address with reverse geocoding - # reverse_geocode_result = gmaps.reverse_geocode((40.714224, -73.961452)) - # # Request directions via public transit - # now = datetime.now() - # directions_result = gmaps.directions("UIUC IRL - The Highbay Facility", "Champaign, IL", - # mode="transit", - # departure_time=now) - # # print(directions_result) - # # Validate an address with address validation - # addressvalidation_result = gmaps.addressvalidation(['1600 Amphitheatre Pk'], - # regionCode='US', - # locality='Mountain View', - # enableUspsCass=True) \ No newline at end of file From b78a83c5edbf3fcb40343d0c12961c6faf1d445a Mon Sep 17 00:00:00 2001 From: onemaple Date: Tue, 7 May 2024 17:42:34 -0500 Subject: [PATCH 147/232] integrate conversion samples into onboard --- GEMstack/onboard/googlemaps/conversion.py | 50 +++++++++++++++++++++++ testing/test_googlemaps.py | 7 ++++ 2 files changed, 57 insertions(+) create mode 100644 GEMstack/onboard/googlemaps/conversion.py create mode 100644 testing/test_googlemaps.py diff --git a/GEMstack/onboard/googlemaps/conversion.py b/GEMstack/onboard/googlemaps/conversion.py new file mode 100644 index 000000000..97cfe4d82 --- /dev/null +++ b/GEMstack/onboard/googlemaps/conversion.py @@ -0,0 +1,50 @@ +import requests +from datetime import datetime +import sys +import os +# sys.path.append(os.path.join(os.getcwd(), '...')) +# sys.path.append(os.getcwd()) +# sys.path.append(os.path.dirname('/home/sam/Documents/GEMstack/GEMstack')) +from ...state import PhysicalObject,ObjectPose,ObjectFrameEnum +from ...state.physical_object import _get_frame_chain + +from ...mathutils import transforms +import math +import time + +# Replace with your actual API endpoint +API_ENDPOINT = 'http://localhost:5000/find_place' + +# Define the start pose of the car in the global frame +start_pose_global = ObjectPose(frame=ObjectFrameEnum.GLOBAL, t=time.time(), y=40.09286250064475, x=-88.23565755734872, yaw=math.radians(90.0)) + +def test_find_place(end_place): + + response = requests.post(API_ENDPOINT, data={'place_name': end_place}) + + assert response.status_code == 200 + data = response.json() + if 'error' in data: + print('No places found') + # print(f"Place: {end_place}") + # print(f"Error: {data['error']}") + else: + # Test case 1: Valid place name + assert response.status_code == 200 + data = response.json() + assert 'lat' in data + assert 'lng' in data + print(f"Latitude: {data['lat']}") + print(f"Longitude: {data['lng']}") + + # Convert coordinates to car frame + current_pose_global = ObjectPose(frame=ObjectFrameEnum.GLOBAL, t=time.time(), y=data['lat'], x=data['lng'], yaw=math.radians(90.0)) + current_pose_car = current_pose_global.to_frame(ObjectFrameEnum.START, start_pose_abs=start_pose_global) + + print(f"Place: {end_place}") + print(f"Car Frame - X: {current_pose_car.x}, Y: {current_pose_car.y}, Yaw: {current_pose_car.yaw}") + + + +# if __name__ == '__main__': +# test_find_place() \ No newline at end of file diff --git a/testing/test_googlemaps.py b/testing/test_googlemaps.py new file mode 100644 index 000000000..e1830b0f5 --- /dev/null +++ b/testing/test_googlemaps.py @@ -0,0 +1,7 @@ +import sys +import os +sys.path.append(os.getcwd()) +from GEMstack.onboard.googlemaps import conversion + +Location = input("Where would you like to go? ") +conversion.test_find_place(Location) \ No newline at end of file From f06178c4cd8453d67908969336bab762b2f802d9 Mon Sep 17 00:00:00 2001 From: OneMaple <37830933+onemapl3@users.noreply.github.com> Date: Wed, 8 May 2024 16:59:48 -0500 Subject: [PATCH 148/232] Revert "S2024 curbside googlemap" --- GEMstack/onboard/googlemaps/conversion.py | 50 ---------------- app/E2E_test.py | 48 --------------- app/api-service/.gitignore | 1 - app/api-service/app.py | 48 --------------- app/api-service/templates/index.html | 61 ------------------- app/api-service/test_app.py | 72 ----------------------- testing/test_googlemaps.py | 7 --- 7 files changed, 287 deletions(-) delete mode 100644 GEMstack/onboard/googlemaps/conversion.py delete mode 100644 app/E2E_test.py delete mode 100644 app/api-service/.gitignore delete mode 100644 app/api-service/app.py delete mode 100644 app/api-service/templates/index.html delete mode 100644 app/api-service/test_app.py delete mode 100644 testing/test_googlemaps.py diff --git a/GEMstack/onboard/googlemaps/conversion.py b/GEMstack/onboard/googlemaps/conversion.py deleted file mode 100644 index 97cfe4d82..000000000 --- a/GEMstack/onboard/googlemaps/conversion.py +++ /dev/null @@ -1,50 +0,0 @@ -import requests -from datetime import datetime -import sys -import os -# sys.path.append(os.path.join(os.getcwd(), '...')) -# sys.path.append(os.getcwd()) -# sys.path.append(os.path.dirname('/home/sam/Documents/GEMstack/GEMstack')) -from ...state import PhysicalObject,ObjectPose,ObjectFrameEnum -from ...state.physical_object import _get_frame_chain - -from ...mathutils import transforms -import math -import time - -# Replace with your actual API endpoint -API_ENDPOINT = 'http://localhost:5000/find_place' - -# Define the start pose of the car in the global frame -start_pose_global = ObjectPose(frame=ObjectFrameEnum.GLOBAL, t=time.time(), y=40.09286250064475, x=-88.23565755734872, yaw=math.radians(90.0)) - -def test_find_place(end_place): - - response = requests.post(API_ENDPOINT, data={'place_name': end_place}) - - assert response.status_code == 200 - data = response.json() - if 'error' in data: - print('No places found') - # print(f"Place: {end_place}") - # print(f"Error: {data['error']}") - else: - # Test case 1: Valid place name - assert response.status_code == 200 - data = response.json() - assert 'lat' in data - assert 'lng' in data - print(f"Latitude: {data['lat']}") - print(f"Longitude: {data['lng']}") - - # Convert coordinates to car frame - current_pose_global = ObjectPose(frame=ObjectFrameEnum.GLOBAL, t=time.time(), y=data['lat'], x=data['lng'], yaw=math.radians(90.0)) - current_pose_car = current_pose_global.to_frame(ObjectFrameEnum.START, start_pose_abs=start_pose_global) - - print(f"Place: {end_place}") - print(f"Car Frame - X: {current_pose_car.x}, Y: {current_pose_car.y}, Yaw: {current_pose_car.yaw}") - - - -# if __name__ == '__main__': -# test_find_place() \ No newline at end of file diff --git a/app/E2E_test.py b/app/E2E_test.py deleted file mode 100644 index f003bf251..000000000 --- a/app/E2E_test.py +++ /dev/null @@ -1,48 +0,0 @@ -import requests -from datetime import datetime -import sys -import os -sys.path.append(os.path.join(os.getcwd(), '..')) -from GEMstack.state import PhysicalObject,ObjectPose,ObjectFrameEnum -from GEMstack.state.physical_object import _get_frame_chain -from GEMstack.mathutils import transforms -import math -import time - -# Replace with your actual API endpoint -API_ENDPOINT = 'http://localhost:5000/find_place' - -# Define the start pose of the car in the global frame -start_pose_global = ObjectPose(frame=ObjectFrameEnum.GLOBAL, t=time.time(), y=40.09286250064475, x=-88.23565755734872, yaw=math.radians(90.0)) - -def test_find_place(): - # Test case 1: Valid place name - place_name = 'Highbay' - response = requests.post(API_ENDPOINT, data={'place_name': place_name}) - assert response.status_code == 200 - data = response.json() - assert 'lat' in data - assert 'lng' in data - print(f"Latitude: {data['lat']}") - print(f"Longitude: {data['lng']}") - - # Convert coordinates to car frame - current_pose_global = ObjectPose(frame=ObjectFrameEnum.GLOBAL, t=time.time(), y=data['lat'], x=data['lng'], yaw=math.radians(90.0)) - current_pose_car = current_pose_global.to_frame(ObjectFrameEnum.START, start_pose_abs=start_pose_global) - - print(f"Place: {place_name}") - print(f"Car Frame - X: {current_pose_car.x}, Y: {current_pose_car.y}, Yaw: {current_pose_car.yaw}") - - # Test case 2: Invalid place name - place_name = 'InvalidPlace' - response = requests.post(API_ENDPOINT, data={'place_name': place_name}) - assert response.status_code == 200 - data = response.json() - assert 'error' in data - assert data['error'] == 'No places found' - - print(f"Place: {place_name}") - print(f"Error: {data['error']}") - -if __name__ == '__main__': - test_find_place() \ No newline at end of file diff --git a/app/api-service/.gitignore b/app/api-service/.gitignore deleted file mode 100644 index 2eea525d8..000000000 --- a/app/api-service/.gitignore +++ /dev/null @@ -1 +0,0 @@ -.env \ No newline at end of file diff --git a/app/api-service/app.py b/app/api-service/app.py deleted file mode 100644 index 798f84882..000000000 --- a/app/api-service/app.py +++ /dev/null @@ -1,48 +0,0 @@ -from flask import Flask, render_template, request, jsonify -import googlemaps -from dotenv import load_dotenv -import os -# Load the environment variables from the .env file -load_dotenv() -api_key = os.getenv('GOOGLE_MAPS_API_KEY') - -app = Flask(__name__) - - -gmaps = googlemaps.Client(key=api_key) - -@app.route('/') -def index(): - return render_template('index.html', api_key=api_key) - -@app.route('/find_place', methods=['POST']) -def find_place(): - place_name = request.form['place_name'] - - # Search for places based on the input name - places_result = gmaps.places(query=place_name) - - if places_result['status'] == 'OK' and len(places_result['results']) > 0: - # Get the first (best-matched) place from the search results - place = places_result['results'][0] - - # Extract the place ID - place_id = place['place_id'] - - # Retrieve the details of the place using the place ID - place_details = gmaps.place(place_id=place_id) - - if place_details['status'] == 'OK': - # Extract the latitude and longitude coordinates - lat = place_details['result']['geometry']['location']['lat'] - lng = place_details['result']['geometry']['location']['lng'] - print(lat, lng) - # Return the coordinates as JSON - return jsonify({'lat': lat, 'lng': lng}) - else: - return jsonify({'error': 'Unable to retrieve place details'}) - else: - return jsonify({'error': 'No places found'}) - -if __name__ == '__main__': - app.run(debug=True) \ No newline at end of file diff --git a/app/api-service/templates/index.html b/app/api-service/templates/index.html deleted file mode 100644 index 89d75f474..000000000 --- a/app/api-service/templates/index.html +++ /dev/null @@ -1,61 +0,0 @@ - - - - Place Finder - - - - - -

Place Finder

-
- - -
-
-
- - \ No newline at end of file diff --git a/app/api-service/test_app.py b/app/api-service/test_app.py deleted file mode 100644 index 8b18ebec1..000000000 --- a/app/api-service/test_app.py +++ /dev/null @@ -1,72 +0,0 @@ -from flask import Flask -import pytest -from app import app, find_place -from unittest.mock import MagicMock, patch - -# Create a test client -@pytest.fixture -def client(): - app.config['TESTING'] = True - with app.test_client() as client: - yield client - -# Mock the googlemaps.Client class -@pytest.fixture -def mock_gmaps(): - with patch('googlemaps.Client') as mock_client: - yield mock_client - -def test_find_place_success(client, mock_gmaps): - # Mock the places API response - mock_place_result = { - 'status': 'OK', - 'results': [ - { - 'place_id': 'abc123', - 'geometry': { - 'location': { - 'lat': 40.0930404, - 'lng': -88.2356592 - } - } - } - ] - } - mock_gmaps.return_value.places.return_value = mock_place_result - - # Mock the place details API response - mock_place_details = { - 'status': 'OK', - 'result': { - 'geometry': { - 'location': { - 'lat': 40.0930404, - 'lng': -88.2356592 - } - } - } - } - mock_gmaps.return_value.place.return_value = mock_place_details - - # Send a request to the find_place endpoint - response = client.post('/find_place', data={'place_name': 'Highbay'}) - - # Assert the response - assert response.status_code == 200 - assert response.json == { 'lat': 40.0930404, - 'lng': -88.2356592} - -def test_find_place_no_results(client, mock_gmaps): - # Mock the places API response with no results - mock_place_result = { - 'status': 'OK', - 'results': [] - } - mock_gmaps.return_value.places.return_value = mock_place_result - - # Send a request to the find_place endpoint - response = client.post('/find_place', data={'place_name': 'InvalidPlace'}) - - # Assert the response - assert response.status_code == 200 - assert response.json == {'error': 'No places found'} diff --git a/testing/test_googlemaps.py b/testing/test_googlemaps.py deleted file mode 100644 index e1830b0f5..000000000 --- a/testing/test_googlemaps.py +++ /dev/null @@ -1,7 +0,0 @@ -import sys -import os -sys.path.append(os.getcwd()) -from GEMstack.onboard.googlemaps import conversion - -Location = input("Where would you like to go? ") -conversion.test_find_place(Location) \ No newline at end of file From 1960c9999831adc8a5894356be46baab599a3926 Mon Sep 17 00:00:00 2001 From: Kris Hauser Date: Tue, 28 Jan 2025 17:04:38 -0600 Subject: [PATCH 149/232] Fixed Klampt drawing problem onboard... still mysterious --- GEMstack/utils/klampt_visualization.py | 14 ++++++++++---- 1 file changed, 10 insertions(+), 4 deletions(-) diff --git a/GEMstack/utils/klampt_visualization.py b/GEMstack/utils/klampt_visualization.py index 0e9219e76..5a73fe95d 100644 --- a/GEMstack/utils/klampt_visualization.py +++ b/GEMstack/utils/klampt_visualization.py @@ -198,7 +198,10 @@ def plot_vehicle(vehicle : VehicleState, vehicle_model=None, axis_len=1.0): vehicle_model.link('rear_left_stop_light_link').appearance().setColor(0.3,0,0,1) def plot_path(name : str, path : Path, color=(0,0,0), width=1): - vis.add(name,[list(p) for p in path.points],color=color,width=width) + if len(path.points) > 50: + vis.add(name,[list(p) for p in path.points[::len(path.points)//50]],color=color,width=width) + else: + vis.add(name,[list(p) for p in path.points],color=color,width=width) def plot_curve(name : str, curve : RoadgraphCurve, color=None, width=None): style = CURVE_TO_STYLE.get(curve.type,CURVE_TO_STYLE[None]) @@ -211,7 +214,10 @@ def plot_curve(name : str, curve : RoadgraphCurve, color=None, width=None): if width is not None: style['width'] = width for i,seg in enumerate(curve.segments): - vis.add(name+"_%d" % i,seg,**style) + if len(seg) > 50: + vis.add(name+"_%d" % i,seg[::len(seg)//50],**style) + else: + vis.add(name+"_%d" % i,seg,**style) def plot_lane(name : str, lane : RoadgraphLane, on_route=False): if lane.surface != RoadgraphSurfaceEnum.PAVEMENT: @@ -284,6 +290,6 @@ def plot_scene(scene : SceneState, ground_truth_vehicle=None, vehicle_model = No def plot(state : AllState, ground_truth_vehicle = None, vehicle_model=None, title=None, show=True): plot_scene(state, ground_truth_vehicle=ground_truth_vehicle, vehicle_model=vehicle_model, title=title, show=show) if state.route is not None: - plot_path("route",state.route,color=(1,0.5,0,1)) + plot_path("route",state.route,color=(1,0.5,0,1),width=2) if state.trajectory is not None: - plot_path("trajectory",state.trajectory,color=(1,0,0,1),width=2) + plot_path("trajectory",state.trajectory,color=(1,0,0,1),width=3) From 6c94fae52cfbf2b0ca0288912aafefab3021eac5 Mon Sep 17 00:00:00 2001 From: krishauser Date: Wed, 29 Jan 2025 00:19:53 -0500 Subject: [PATCH 150/232] Moved GNSSReading to gem.py to avoid reliance on rospy --- GEMstack/onboard/interface/gem.py | 7 +++++++ GEMstack/onboard/interface/gem_hardware.py | 6 ------ GEMstack/onboard/perception/state_estimation.py | 2 +- 3 files changed, 8 insertions(+), 7 deletions(-) diff --git a/GEMstack/onboard/interface/gem.py b/GEMstack/onboard/interface/gem.py index c5482de19..9abcd1b6b 100644 --- a/GEMstack/onboard/interface/gem.py +++ b/GEMstack/onboard/interface/gem.py @@ -82,6 +82,13 @@ class GEMVehicleCommand: wiper_level : int = 0 +@dataclass +class GNSSReading: + pose : ObjectPose + speed : float + status : str + + class GEMInterface: """Base class for simulated / physical GEM vehicle. """ diff --git a/GEMstack/onboard/interface/gem_hardware.py b/GEMstack/onboard/interface/gem_hardware.py index e98efcae4..3f2f26994 100644 --- a/GEMstack/onboard/interface/gem_hardware.py +++ b/GEMstack/onboard/interface/gem_hardware.py @@ -26,12 +26,6 @@ import numpy as np from ...utils import conversions -@dataclass -class GNSSReading: - pose : ObjectPose - speed : float - status : str - class GEMHardwareInterface(GEMInterface): """Interface for connnecting to the physical GEM e2 vehicle.""" def __init__(self): diff --git a/GEMstack/onboard/perception/state_estimation.py b/GEMstack/onboard/perception/state_estimation.py index 44be5baa0..4aef25659 100644 --- a/GEMstack/onboard/perception/state_estimation.py +++ b/GEMstack/onboard/perception/state_estimation.py @@ -9,7 +9,7 @@ from ...mathutils.signal import OnlineLowPassFilter from ..interface.gem import GEMInterface from ..component import Component -from ..interface.gem_hardware import GNSSReading +from ..interface.gem import GNSSReading class GNSSStateEstimator(Component): """Just looks at the GNSS reading to estimate the vehicle state""" From a8a897d0117734caf83d86330d359ae0cc4192ce Mon Sep 17 00:00:00 2001 From: animesh Date: Sun, 2 Feb 2025 14:50:45 -0600 Subject: [PATCH 151/232] Adding github action for linting and documentation --- .github/workflows/python-app.yml | 59 ++++++++++++++++++++++++++++++++ 1 file changed, 59 insertions(+) create mode 100644 .github/workflows/python-app.yml diff --git a/.github/workflows/python-app.yml b/.github/workflows/python-app.yml new file mode 100644 index 000000000..165bd6c09 --- /dev/null +++ b/.github/workflows/python-app.yml @@ -0,0 +1,59 @@ +# This workflow will install Python dependencies, run tests and lint with a single version of Python +# For more information see: https://docs.github.com/en/actions/automating-builds-and-tests/building-and-testing-python + +name: Python application + + +permissions: + contents: read + +jobs: + PEP-Guidelines: + + runs-on: ubuntu-latest + + steps: + - uses: actions/checkout@v3 + - name: Set up Python 3.10 + uses: actions/setup-python@v3 + with: + python-version: "3.10" + - name: Install dependencies + run: | + python -m pip install --upgrade pip + pip install flake8 flake8-docstrings pep8-naming + if [ -f requirements.txt ]; then pip install -r requirements.txt; fi + - name: Lint with flake8 + run: | + # stop the build if there are Python syntax errors or undefined names + flake8 ./GEMstack --count --select=E9,F63,F7,F82 --show-source --statistics --exclude=__init__.py || exit 1 + # to enable more advanced checks on the repo, uncomment the lines below (There are around 3000 violations) + # flake8 ./GEMstack --ignore=D,C901,E402,E231 --count --max-complexity=10 --max-line-length=127 --statistics --exclude=__init__.py || exit 1 + # if we want to enable documentation checks, uncomment the line below + # flake8 ./GEMstack --ignore=E128,E402,E501,F401 --docstring-convention pep257 --max-line-length=120 --exclude=__init__.py || exit 1 + continue-on-error: false + + Documentation: + + runs-on: ubuntu-latest + + steps: + - uses: actions/checkout@v3 + - name: Set up Python 3.10 + uses: actions/setup-python@v3 + with: + python-version: "3.10" + - name: Install dependencies + run: | + python -m pip install --upgrade pip + pip install sphinx sphinx-rtd-theme + if [ -f requirements.txt ]; then pip install -r requirements.txt; fi + - name: Generate Documentation + run: | + # stop the build if there are Python syntax errors or undefined names + sphinx-build -b html docs docs/build + - name: Save Documentation as Artifact + uses: actions/upload-artifact@v2 + with: + name: documentation + path: documents/build From ee9ed62769d9c72587c638c9e51c7fa044b35a53 Mon Sep 17 00:00:00 2001 From: animesh Date: Sun, 2 Feb 2025 14:56:01 -0600 Subject: [PATCH 152/232] Adding github action trigger on all commits --- .github/workflows/python-app.yml | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/.github/workflows/python-app.yml b/.github/workflows/python-app.yml index 165bd6c09..ab65f49b8 100644 --- a/.github/workflows/python-app.yml +++ b/.github/workflows/python-app.yml @@ -3,6 +3,12 @@ name: Python application +on: + push: + branches: + - '**' + pull_request: + permissions: contents: read From b12a0e24b432a4c18f7cd035973155f7e31aecdc Mon Sep 17 00:00:00 2001 From: animesh Date: Sun, 2 Feb 2025 14:57:09 -0600 Subject: [PATCH 153/232] Upgrading version of upload artifact --- .github/workflows/python-app.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/python-app.yml b/.github/workflows/python-app.yml index ab65f49b8..5966ffbd7 100644 --- a/.github/workflows/python-app.yml +++ b/.github/workflows/python-app.yml @@ -59,7 +59,7 @@ jobs: # stop the build if there are Python syntax errors or undefined names sphinx-build -b html docs docs/build - name: Save Documentation as Artifact - uses: actions/upload-artifact@v2 + uses: actions/upload-artifact@v4 with: name: documentation path: documents/build From 97577d6f7ebe58580330c1842b5fd6619afc9095 Mon Sep 17 00:00:00 2001 From: animesh Date: Sun, 2 Feb 2025 15:03:47 -0600 Subject: [PATCH 154/232] Optimizing the workflow yaml --- .github/workflows/python-app.yml | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/.github/workflows/python-app.yml b/.github/workflows/python-app.yml index 5966ffbd7..19f573309 100644 --- a/.github/workflows/python-app.yml +++ b/.github/workflows/python-app.yml @@ -28,7 +28,6 @@ jobs: run: | python -m pip install --upgrade pip pip install flake8 flake8-docstrings pep8-naming - if [ -f requirements.txt ]; then pip install -r requirements.txt; fi - name: Lint with flake8 run: | # stop the build if there are Python syntax errors or undefined names @@ -49,6 +48,13 @@ jobs: uses: actions/setup-python@v3 with: python-version: "3.10" + - name: Cache dependencies + - uses: actions/cache@v2 + - with: + path: ~/.cache/pip + keys: ${{ runner.os}}-python-${{hashFiles('**/requirements.txt')}} + restore-keys: | + ${{runner.os}}-python- - name: Install dependencies run: | python -m pip install --upgrade pip From 3374b79f5a60d7127519ff009589cda9b8bcfc40 Mon Sep 17 00:00:00 2001 From: animesh Date: Sun, 2 Feb 2025 15:06:04 -0600 Subject: [PATCH 155/232] Optimizing the workflow yaml --- .github/workflows/python-app.yml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/workflows/python-app.yml b/.github/workflows/python-app.yml index 19f573309..c95cb087c 100644 --- a/.github/workflows/python-app.yml +++ b/.github/workflows/python-app.yml @@ -49,8 +49,8 @@ jobs: with: python-version: "3.10" - name: Cache dependencies - - uses: actions/cache@v2 - - with: + uses: actions/cache@v2 + with: path: ~/.cache/pip keys: ${{ runner.os}}-python-${{hashFiles('**/requirements.txt')}} restore-keys: | From 7faab511b903824d44e6ee1e7a62efcaac775382 Mon Sep 17 00:00:00 2001 From: animesh Date: Sun, 2 Feb 2025 15:07:57 -0600 Subject: [PATCH 156/232] Correcting in the key names --- .github/workflows/python-app.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/python-app.yml b/.github/workflows/python-app.yml index c95cb087c..fa040db13 100644 --- a/.github/workflows/python-app.yml +++ b/.github/workflows/python-app.yml @@ -52,7 +52,7 @@ jobs: uses: actions/cache@v2 with: path: ~/.cache/pip - keys: ${{ runner.os}}-python-${{hashFiles('**/requirements.txt')}} + key: ${{ runner.os}}-python-${{hashFiles('**/requirements.txt')}} restore-keys: | ${{runner.os}}-python- - name: Install dependencies From 766ac70d4848684e64f8321badc47435aa2deaea Mon Sep 17 00:00:00 2001 From: animesh Date: Sun, 2 Feb 2025 15:13:52 -0600 Subject: [PATCH 157/232] Removing requirements.txt installation in documentation --- .github/workflows/python-app.yml | 8 -------- 1 file changed, 8 deletions(-) diff --git a/.github/workflows/python-app.yml b/.github/workflows/python-app.yml index fa040db13..b452f3c51 100644 --- a/.github/workflows/python-app.yml +++ b/.github/workflows/python-app.yml @@ -48,18 +48,10 @@ jobs: uses: actions/setup-python@v3 with: python-version: "3.10" - - name: Cache dependencies - uses: actions/cache@v2 - with: - path: ~/.cache/pip - key: ${{ runner.os}}-python-${{hashFiles('**/requirements.txt')}} - restore-keys: | - ${{runner.os}}-python- - name: Install dependencies run: | python -m pip install --upgrade pip pip install sphinx sphinx-rtd-theme - if [ -f requirements.txt ]; then pip install -r requirements.txt; fi - name: Generate Documentation run: | # stop the build if there are Python syntax errors or undefined names From 5437cac611f1f09f5c709c5bea614a77440bda6d Mon Sep 17 00:00:00 2001 From: animesh Date: Sun, 2 Feb 2025 15:15:07 -0600 Subject: [PATCH 158/232] Correcting name of build artifact for documentation folder --- .github/workflows/python-app.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/python-app.yml b/.github/workflows/python-app.yml index b452f3c51..541b071a7 100644 --- a/.github/workflows/python-app.yml +++ b/.github/workflows/python-app.yml @@ -60,4 +60,4 @@ jobs: uses: actions/upload-artifact@v4 with: name: documentation - path: documents/build + path: docs/build From 1eacdb9ed425fe46671b8d1511d2ad487aa912b7 Mon Sep 17 00:00:00 2001 From: Animesh Singh Date: Sun, 2 Feb 2025 15:18:35 -0600 Subject: [PATCH 159/232] Removing action trigger on PR --- .github/workflows/python-app.yml | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/.github/workflows/python-app.yml b/.github/workflows/python-app.yml index 541b071a7..3de575d8e 100644 --- a/.github/workflows/python-app.yml +++ b/.github/workflows/python-app.yml @@ -7,8 +7,7 @@ on: push: branches: - '**' - pull_request: - + permissions: contents: read From 5290b701e6c77c60c98f458b1e74233506e185a9 Mon Sep 17 00:00:00 2001 From: Kris Hauser Date: Mon, 3 Feb 2025 12:31:56 -0500 Subject: [PATCH 160/232] Better docstring --- GEMstack/utils/config.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/GEMstack/utils/config.py b/GEMstack/utils/config.py index 9112107e9..ac7fbbaa7 100644 --- a/GEMstack/utils/config.py +++ b/GEMstack/utils/config.py @@ -18,7 +18,7 @@ def save_config(fn : str, config : dict) -> None: def load_config_recursive(fn : str) -> dict: - """Loads a configuration file with !include directives.""" + """Loads a configuration file with !include and !relative_path directives.""" if fn.endswith('yaml') or fn.endswith('yml'): with open(fn,'r') as f: res = yaml.load(f,_Loader) @@ -35,7 +35,7 @@ def load_config_recursive(fn : str) -> dict: class _Loader(yaml.SafeLoader): - """YAML Loader with `!include` constructor.""" + """YAML Loader with `!include` and `!relative_path` directives.""" def __init__(self, stream: IO) -> None: """Initialise Loader.""" @@ -60,7 +60,7 @@ def _construct_relative_path(loader: _Loader, node: yaml.Node) -> Any: yaml.add_constructor('!relative_path', _construct_relative_path, _Loader) def _load_config_or_text_recursive(fn : str) -> dict: - """Loads a configuration file with !include directives.""" + """Loads a configuration file with !include and !relative_path directives.""" if fn.endswith('yaml') or fn.endswith('yml'): with open(fn,'r') as f: res = yaml.load(f,_Loader) From 6ca5300b6593fa1d95ae116b0b94aeb67839a5d2 Mon Sep 17 00:00:00 2001 From: Kris Hauser Date: Mon, 3 Feb 2025 12:56:54 -0500 Subject: [PATCH 161/232] Fixed to work with Klampt 0.10 --- .../visualization/klampt_visualization.py | 40 +++++++++++++------ 1 file changed, 28 insertions(+), 12 deletions(-) diff --git a/GEMstack/onboard/visualization/klampt_visualization.py b/GEMstack/onboard/visualization/klampt_visualization.py index 3e07aed23..762a747b4 100644 --- a/GEMstack/onboard/visualization/klampt_visualization.py +++ b/GEMstack/onboard/visualization/klampt_visualization.py @@ -1,4 +1,5 @@ from ..component import Component +from klampt import __version__ as klampt_version from klampt import vis from klampt.math import se3 from klampt import * @@ -11,14 +12,16 @@ import numpy as np class KlamptVisualization(Component): - """Runs a matplotlib visualization at 10Hz. - - If save_as is not None, saves the visualization to a file. + """Runs a Klampt visualization. + + Runs at 20Hz by default. """ def __init__(self, vehicle_interface, rate : float = 20.0, save_as : str = None): self.vehicle_interface = vehicle_interface self._rate = rate self.save_as = save_as + if save_as is not None: + print("WARNING: automatic saving of KlamptVisualization to movie is not supported yet. You can use Ctrl+M to start / stop saving the movie") self.num_updates = 0 self.last_yaw = None self.plot_values = {} @@ -57,12 +60,20 @@ def state_inputs(self): def initialize(self): vis.setWindowTitle("GEMstack visualization") vp = vis.getViewport() - vp.camera.rot[1] = -0.15 - vp.camera.rot[2] = -math.pi/2 - vp.camera.dist = 30.0 - vp.w = 1280 - vp.h = 720 - vp.clippingplanes = (0.1,1000) + if klampt_version == '0.10.0': + vp.controller.rot[1] = -0.15 + vp.controller.rot[2] = -math.pi/2 + vp.controller.dist = 30.0 + vp.resize(1280,720) + vp.n = 0.1 + vp.f = 1000 + else: + vp.camera.rot[1] = -0.15 + vp.camera.rot[2] = -math.pi/2 + vp.camera.dist = 30.0 + vp.w = 1280 + vp.h = 720 + vp.clippingplanes = (0.1,1000) vis.setViewport(vp) vis.add("vehicle_plane",self.world.terrain(0),hide_label=True) #note: show() takes over the interrupt handler and sets it to default, so we restore it @@ -121,9 +132,14 @@ def update(self, state): center_offset = 1.0 lookahead = 4.0*v dx,dy = math.cos(tracked_vehicle.pose.yaw)*(lookahead+center_offset),math.sin(tracked_vehicle.pose.yaw)*(lookahead+center_offset) - vp.camera.tgt = [tracked_vehicle.pose.x+dx,tracked_vehicle.pose.y+dy,1.5] - vp.camera.rot[2] += tracked_vehicle.pose.yaw - self.last_yaw - vp.camera.dist += 5.0*(v - self.last_v) + if klampt_version == '0.10.0': + vp.controller.tgt = [tracked_vehicle.pose.x+dx,tracked_vehicle.pose.y+dy,1.5] + vp.controller.rot[2] += tracked_vehicle.pose.yaw - self.last_yaw + vp.controller.dist += 5.0*(v - self.last_v) + else: + vp.camera.tgt = [tracked_vehicle.pose.x+dx,tracked_vehicle.pose.y+dy,1.5] + vp.camera.rot[2] += tracked_vehicle.pose.yaw - self.last_yaw + vp.camera.dist += 5.0*(v - self.last_v) self.last_v = v vis.setViewport(vp) From 49a74768fac073db18ad2db29fd586f9fcb4c62a Mon Sep 17 00:00:00 2001 From: Kris Hauser Date: Mon, 3 Feb 2025 12:31:56 -0500 Subject: [PATCH 162/232] Better docstring --- GEMstack/utils/config.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/GEMstack/utils/config.py b/GEMstack/utils/config.py index 9112107e9..ac7fbbaa7 100644 --- a/GEMstack/utils/config.py +++ b/GEMstack/utils/config.py @@ -18,7 +18,7 @@ def save_config(fn : str, config : dict) -> None: def load_config_recursive(fn : str) -> dict: - """Loads a configuration file with !include directives.""" + """Loads a configuration file with !include and !relative_path directives.""" if fn.endswith('yaml') or fn.endswith('yml'): with open(fn,'r') as f: res = yaml.load(f,_Loader) @@ -35,7 +35,7 @@ def load_config_recursive(fn : str) -> dict: class _Loader(yaml.SafeLoader): - """YAML Loader with `!include` constructor.""" + """YAML Loader with `!include` and `!relative_path` directives.""" def __init__(self, stream: IO) -> None: """Initialise Loader.""" @@ -60,7 +60,7 @@ def _construct_relative_path(loader: _Loader, node: yaml.Node) -> Any: yaml.add_constructor('!relative_path', _construct_relative_path, _Loader) def _load_config_or_text_recursive(fn : str) -> dict: - """Loads a configuration file with !include directives.""" + """Loads a configuration file with !include and !relative_path directives.""" if fn.endswith('yaml') or fn.endswith('yml'): with open(fn,'r') as f: res = yaml.load(f,_Loader) From 4fd94dc532167f56b830ffb75a835c20bac8a784 Mon Sep 17 00:00:00 2001 From: Kris Hauser Date: Mon, 3 Feb 2025 12:56:54 -0500 Subject: [PATCH 163/232] Fixed to work with Klampt 0.10 --- .../visualization/klampt_visualization.py | 40 +++++++++++++------ 1 file changed, 28 insertions(+), 12 deletions(-) diff --git a/GEMstack/onboard/visualization/klampt_visualization.py b/GEMstack/onboard/visualization/klampt_visualization.py index 3e07aed23..762a747b4 100644 --- a/GEMstack/onboard/visualization/klampt_visualization.py +++ b/GEMstack/onboard/visualization/klampt_visualization.py @@ -1,4 +1,5 @@ from ..component import Component +from klampt import __version__ as klampt_version from klampt import vis from klampt.math import se3 from klampt import * @@ -11,14 +12,16 @@ import numpy as np class KlamptVisualization(Component): - """Runs a matplotlib visualization at 10Hz. - - If save_as is not None, saves the visualization to a file. + """Runs a Klampt visualization. + + Runs at 20Hz by default. """ def __init__(self, vehicle_interface, rate : float = 20.0, save_as : str = None): self.vehicle_interface = vehicle_interface self._rate = rate self.save_as = save_as + if save_as is not None: + print("WARNING: automatic saving of KlamptVisualization to movie is not supported yet. You can use Ctrl+M to start / stop saving the movie") self.num_updates = 0 self.last_yaw = None self.plot_values = {} @@ -57,12 +60,20 @@ def state_inputs(self): def initialize(self): vis.setWindowTitle("GEMstack visualization") vp = vis.getViewport() - vp.camera.rot[1] = -0.15 - vp.camera.rot[2] = -math.pi/2 - vp.camera.dist = 30.0 - vp.w = 1280 - vp.h = 720 - vp.clippingplanes = (0.1,1000) + if klampt_version == '0.10.0': + vp.controller.rot[1] = -0.15 + vp.controller.rot[2] = -math.pi/2 + vp.controller.dist = 30.0 + vp.resize(1280,720) + vp.n = 0.1 + vp.f = 1000 + else: + vp.camera.rot[1] = -0.15 + vp.camera.rot[2] = -math.pi/2 + vp.camera.dist = 30.0 + vp.w = 1280 + vp.h = 720 + vp.clippingplanes = (0.1,1000) vis.setViewport(vp) vis.add("vehicle_plane",self.world.terrain(0),hide_label=True) #note: show() takes over the interrupt handler and sets it to default, so we restore it @@ -121,9 +132,14 @@ def update(self, state): center_offset = 1.0 lookahead = 4.0*v dx,dy = math.cos(tracked_vehicle.pose.yaw)*(lookahead+center_offset),math.sin(tracked_vehicle.pose.yaw)*(lookahead+center_offset) - vp.camera.tgt = [tracked_vehicle.pose.x+dx,tracked_vehicle.pose.y+dy,1.5] - vp.camera.rot[2] += tracked_vehicle.pose.yaw - self.last_yaw - vp.camera.dist += 5.0*(v - self.last_v) + if klampt_version == '0.10.0': + vp.controller.tgt = [tracked_vehicle.pose.x+dx,tracked_vehicle.pose.y+dy,1.5] + vp.controller.rot[2] += tracked_vehicle.pose.yaw - self.last_yaw + vp.controller.dist += 5.0*(v - self.last_v) + else: + vp.camera.tgt = [tracked_vehicle.pose.x+dx,tracked_vehicle.pose.y+dy,1.5] + vp.camera.rot[2] += tracked_vehicle.pose.yaw - self.last_yaw + vp.camera.dist += 5.0*(v - self.last_v) self.last_v = v vis.setViewport(vp) From a90e361e5f1506c1f90e525461b52181a32a954d Mon Sep 17 00:00:00 2001 From: Kris Hauser Date: Mon, 3 Feb 2025 12:46:58 -0500 Subject: [PATCH 164/232] Fixed diff that was somehow committed --- GEMstack/utils/klampt_visualization.py | 12 ++++++++---- 1 file changed, 8 insertions(+), 4 deletions(-) diff --git a/GEMstack/utils/klampt_visualization.py b/GEMstack/utils/klampt_visualization.py index 5a73fe95d..063f690c7 100644 --- a/GEMstack/utils/klampt_visualization.py +++ b/GEMstack/utils/klampt_visualization.py @@ -6,6 +6,10 @@ from . import settings from ..state import ObjectFrameEnum,ObjectPose,PhysicalObject,VehicleState,VehicleGearEnum,Path,Obstacle,AgentState,AgentEnum,Roadgraph,RoadgraphLane,RoadgraphLaneEnum,RoadgraphCurve,RoadgraphCurveEnum,RoadgraphRegion,RoadgraphRegionEnum,RoadgraphSurfaceEnum,Trajectory,Route,SceneState,AllState +#KH: there is a bug on some system where the visualization crashes with an OpenGL error when drawing curves +#this is a workaround. We really should find the source of the bug! +MAX_POINTS_IN_CURVE = 50 + OBJECT_COLORS = { AgentEnum.CAR : (1,1,0,1), AgentEnum.PEDESTRIAN : (0,1,0,1), @@ -198,8 +202,8 @@ def plot_vehicle(vehicle : VehicleState, vehicle_model=None, axis_len=1.0): vehicle_model.link('rear_left_stop_light_link').appearance().setColor(0.3,0,0,1) def plot_path(name : str, path : Path, color=(0,0,0), width=1): - if len(path.points) > 50: - vis.add(name,[list(p) for p in path.points[::len(path.points)//50]],color=color,width=width) + if len(path.points) > MAX_POINTS_IN_CURVE: # downsample due to OpenGL error? + vis.add(name,[list(p) for p in path.points[::len(path.points)//MAX_POINTS_IN_CURVE]],color=color,width=width) else: vis.add(name,[list(p) for p in path.points],color=color,width=width) @@ -214,8 +218,8 @@ def plot_curve(name : str, curve : RoadgraphCurve, color=None, width=None): if width is not None: style['width'] = width for i,seg in enumerate(curve.segments): - if len(seg) > 50: - vis.add(name+"_%d" % i,seg[::len(seg)//50],**style) + if len(seg) > MAX_POINTS_IN_CURVE: # downsample due to OpenGL error? + vis.add(name+"_%d" % i,seg[::len(seg)//MAX_POINTS_IN_CURVE],**style) else: vis.add(name+"_%d" % i,seg,**style) From df1ee24b83b9e86220c300e84e2da061d2ad4d6d Mon Sep 17 00:00:00 2001 From: Kris Hauser Date: Mon, 17 Feb 2025 09:39:38 -0600 Subject: [PATCH 165/232] Fixed ROS type typo --- GEMstack/onboard/interface/gem_hardware.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/GEMstack/onboard/interface/gem_hardware.py b/GEMstack/onboard/interface/gem_hardware.py index 3f2f26994..e13ff817e 100644 --- a/GEMstack/onboard/interface/gem_hardware.py +++ b/GEMstack/onboard/interface/gem_hardware.py @@ -186,7 +186,7 @@ def callback_with_gnss_reading(msg: INSNavGeod): ) speed = np.sqrt(msg.ve**2 + msg.vn**2) callback(GNSSReading(pose,speed,('error' if msg.error else 'ok'))) - self.gnss_sub = rospy.Subscriber(topic, Inspva, callback_with_gnss_reading) + self.gnss_sub = rospy.Subscriber(topic, INSNavGeod, callback_with_gnss_reading) elif name == 'top_lidar': topic = self.ros_sensor_topics[name] if type is not None and (type is not PointCloud2 and type is not np.ndarray): From c1fb33ddef71b1d2d3ad2fc415b6c609f1ffd9ed Mon Sep 17 00:00:00 2001 From: Kris Hauser Date: Mon, 17 Feb 2025 09:39:38 -0600 Subject: [PATCH 166/232] Fixed ROS type typo --- GEMstack/onboard/interface/gem_hardware.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/GEMstack/onboard/interface/gem_hardware.py b/GEMstack/onboard/interface/gem_hardware.py index 3f2f26994..e13ff817e 100644 --- a/GEMstack/onboard/interface/gem_hardware.py +++ b/GEMstack/onboard/interface/gem_hardware.py @@ -186,7 +186,7 @@ def callback_with_gnss_reading(msg: INSNavGeod): ) speed = np.sqrt(msg.ve**2 + msg.vn**2) callback(GNSSReading(pose,speed,('error' if msg.error else 'ok'))) - self.gnss_sub = rospy.Subscriber(topic, Inspva, callback_with_gnss_reading) + self.gnss_sub = rospy.Subscriber(topic, INSNavGeod, callback_with_gnss_reading) elif name == 'top_lidar': topic = self.ros_sensor_topics[name] if type is not None and (type is not PointCloud2 and type is not np.ndarray): From b9ab89b0be6ff35d9f597521dc8e1e2a95beae63 Mon Sep 17 00:00:00 2001 From: Kris Hauser Date: Mon, 17 Feb 2025 22:22:08 -0500 Subject: [PATCH 167/232] Typo --- GEMstack/knowledge/calibration/gem_e4.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/GEMstack/knowledge/calibration/gem_e4.yaml b/GEMstack/knowledge/calibration/gem_e4.yaml index da971c253..d0954dc06 100644 --- a/GEMstack/knowledge/calibration/gem_e4.yaml +++ b/GEMstack/knowledge/calibration/gem_e4.yaml @@ -1,7 +1,7 @@ calibration_date: "2024-03-05" # Date of calibration YYYY-MM-DD reference: rear_axle_center # rear axle center rear_axle_height: 0.33 # height of rear axle center above flat ground -gnss_location: [1.10,0.1.62] # meters, taken from https://github.com/hangcui1201/POLARIS_GEM_e2_Real/blob/main/vehicle_drivers/gem_gnss_control/scripts/gem_gnss_tracker_stanley_rtk.py. Note conflict with pure pursuit location? +gnss_location: [1.10,0,1.62] # meters, taken from https://github.com/hangcui1201/POLARIS_GEM_e2_Real/blob/main/vehicle_drivers/gem_gnss_control/scripts/gem_gnss_tracker_stanley_rtk.py. Note conflict with pure pursuit location? gnss_yaw: 0.0 # radians top_lidar: !include "gem_e4_ouster.yaml" front_camera: !include "gem_e4_oak.yaml" From 88c65bbb0db3981314cbf2a89f1c6ec8526966e0 Mon Sep 17 00:00:00 2001 From: krishauser Date: Mon, 24 Feb 2025 11:01:11 -0500 Subject: [PATCH 168/232] Added items committed to s2024 --- GEMstack/mathutils/dubins.py | 2 +- GEMstack/mathutils/transforms.py | 21 +++++++++++++++++++++ GEMstack/onboard/interface/gem_hardware.py | 9 ++++++--- 3 files changed, 28 insertions(+), 4 deletions(-) diff --git a/GEMstack/mathutils/dubins.py b/GEMstack/mathutils/dubins.py index cdb4655ab..b840201d9 100644 --- a/GEMstack/mathutils/dubins.py +++ b/GEMstack/mathutils/dubins.py @@ -44,7 +44,7 @@ def derivative(self,x,u): right = [-fwd[1],fwd[0]] phi = u[1] d = u[0] - return np.array([fwd[0]*d,fwd[1]*d,phi]) + return np.array([fwd[0]*d,fwd[1]*d,phi*d]) class DubinsCarIntegrator(ControlSpace): diff --git a/GEMstack/mathutils/transforms.py b/GEMstack/mathutils/transforms.py index 833ecc80d..a29ec48e2 100644 --- a/GEMstack/mathutils/transforms.py +++ b/GEMstack/mathutils/transforms.py @@ -36,6 +36,14 @@ def vector_dist(v1, v2) -> float: """Euclidean distance between two vectors""" return vo.distance(v1,v2) +def vector_dot(v1, v2) -> float: + """Dot product between two vectors""" + return vo.dot(v1,v2) + +def vector_cross(v1, v2) -> float: + """Cross product between two 2D vectors""" + return vo.cross(v1,v2) + def vector2_angle(v1, v2 = None) -> float: """find the ccw angle bewtween two 2d vectors""" if v2 is None: @@ -123,3 +131,16 @@ def xy_to_lat_lon(x_east : float, y_north : float, lat_reference : float, lon_re # convert GNSS waypoints into local fixed frame reprented in x and y lat, lon = axy.xy2ll(x_east, y_north, lat_reference, lon_reference) return lat, lon + +def quaternion_to_euler(x : float, y : float, z : float, w : float): + t0 = +2.0 * (w * x + y * z) + t1 = +1.0 - 2.0 * (x * x + y * y) + roll = np.arctan2(t0, t1) + t2 = +2.0 * (w * y - z * x) + t2 = +1.0 if t2 > +1.0 else t2 + t2 = -1.0 if t2 < -1.0 else t2 + pitch = np.arcsin(t2) + t3 = +2.0 * (w * z + x * y) + t4 = +1.0 - 2.0 * (y * y + z * z) + yaw = np.arctan2(t3, t4) + return [roll, pitch, yaw] diff --git a/GEMstack/onboard/interface/gem_hardware.py b/GEMstack/onboard/interface/gem_hardware.py index e13ff817e..4fb95d4fc 100644 --- a/GEMstack/onboard/interface/gem_hardware.py +++ b/GEMstack/onboard/interface/gem_hardware.py @@ -1,6 +1,7 @@ from .gem import * from ...utils import settings import math +import time # ROS Headers import rospy @@ -151,6 +152,7 @@ def subscribe_sensor(self, name, callback, type = None): if name == 'gnss': topic = self.ros_sensor_topics[name] if topic.endswith('inspva'): + #GEM e2 uses Novatel GNSS if type is not None and (type is not Inspva and type is not GNSSReading): raise ValueError("GEMHardwareInterface GEM e2 only supports Inspva/GNSSReading for GNSS") if type is Inspva: @@ -169,7 +171,7 @@ def callback_with_gnss_reading(inspva_msg: Inspva): callback(GNSSReading(pose,speed,inspva_msg.status)) self.gnss_sub = rospy.Subscriber(topic, Inspva, callback_with_gnss_reading) else: - #assume it's septentrio + #assume it's septentrio on GEM e4 if type is not None and (type is not INSNavGeod and type is not GNSSReading): raise ValueError("GEMHardwareInterface GEM e4 only supports INSNavGeod/GNSSReading for GNSS") if type is INSNavGeod: @@ -177,8 +179,9 @@ def callback_with_gnss_reading(inspva_msg: Inspva): else: def callback_with_gnss_reading(msg: INSNavGeod): pose = ObjectPose(ObjectFrameEnum.GLOBAL, - x=msg.longitude, - y=msg.latitude, + t=time.time(), + x=math.degrees(msg.longitude), #Septentrio GNSS uses radians rather than degrees + y=math.degrees(msg.latitude), z=msg.height, yaw=math.radians(msg.heading), #heading from north in degrees (TODO: maybe?? check this) roll=math.radians(msg.roll), From 308ba556dc94eafee40837bba3415a57e13d7df0 Mon Sep 17 00:00:00 2001 From: krishauser Date: Mon, 24 Feb 2025 11:04:02 -0500 Subject: [PATCH 169/232] Changed time.time to self.time --- GEMstack/onboard/interface/gem_hardware.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/GEMstack/onboard/interface/gem_hardware.py b/GEMstack/onboard/interface/gem_hardware.py index 4fb95d4fc..836d7ef71 100644 --- a/GEMstack/onboard/interface/gem_hardware.py +++ b/GEMstack/onboard/interface/gem_hardware.py @@ -179,7 +179,7 @@ def callback_with_gnss_reading(inspva_msg: Inspva): else: def callback_with_gnss_reading(msg: INSNavGeod): pose = ObjectPose(ObjectFrameEnum.GLOBAL, - t=time.time(), + t=self.time(), x=math.degrees(msg.longitude), #Septentrio GNSS uses radians rather than degrees y=math.degrees(msg.latitude), z=msg.height, From 5cdfb6b90a71d397f8e02e16e12c217a6e3794f6 Mon Sep 17 00:00:00 2001 From: michalj1 Date: Wed, 12 Mar 2025 22:47:29 -0500 Subject: [PATCH 170/232] Include data capture code --- .../calibration/capture_ouster_oak.py | 102 ++++++++++++++++++ 1 file changed, 102 insertions(+) create mode 100644 GEMstack/offboard/calibration/capture_ouster_oak.py diff --git a/GEMstack/offboard/calibration/capture_ouster_oak.py b/GEMstack/offboard/calibration/capture_ouster_oak.py new file mode 100644 index 000000000..3c9e1e6af --- /dev/null +++ b/GEMstack/offboard/calibration/capture_ouster_oak.py @@ -0,0 +1,102 @@ +# ROS Headers +import rospy +from sensor_msgs.msg import Image,PointCloud2 +import sensor_msgs.point_cloud2 as pc2 +import ctypes +import struct + +# OpenCV and cv2 bridge +import cv2 +from cv_bridge import CvBridge +import numpy as np +import os +import time + +lidar_points = None +camera_image = None +depth = None +depth_image = None +bridge = CvBridge() + +def lidar_callback(lidar : PointCloud2): + global lidar_points + lidar_points = lidar + +def camera_callback(img : Image): + global camera_image + camera_image = img + +def depth_callback(img : Image): + global depth_image + depth_image = img + +def pc2_to_numpy(pc2_msg, want_rgb = False): + gen = pc2.read_points(pc2_msg, skip_nans=True) + if want_rgb: + xyzpack = np.array(list(gen),dtype=np.float32) + if xyzpack.shape[1] != 4: + raise ValueError("PointCloud2 does not have points") + xyzrgb = np.empty((xyzpack.shape[0],6)) + xyzrgb[:,:3] = xyzpack[:,:3] + for i,x in enumerate(xyzpack): + rgb = x[3] + # cast float32 to int so that bitwise operations are possible + s = struct.pack('>f' ,rgb) + i = struct.unpack('>l',s)[0] + # you can get back the float value by the inverse operations + pack = ctypes.c_uint32(i).value + r = (pack & 0x00FF0000)>> 16 + g = (pack & 0x0000FF00)>> 8 + b = (pack & 0x000000FF) + #r,g,b values in the 0-255 range + xyzrgb[i,3:] = (r,g,b) + return xyzrgb + else: + return np.array(list(gen),dtype=np.float32)[:,:3] + +def save_scan(lidar_fn,color_fn,depth_fn): + print("Saving scan to",lidar_fn,color_fn) + + pc = pc2_to_numpy(lidar_points,want_rgb=False) # convert lidar feed to numpy + np.savez(lidar_fn,pc) + cv2.imwrite(color_fn,bridge.imgmsg_to_cv2(camera_image)) + + dimage = bridge.imgmsg_to_cv2(depth_image) + dimage_non_nan = dimage[np.isfinite(dimage)] + print("Depth range",np.min(dimage_non_nan),np.max(dimage_non_nan)) + dimage = np.nan_to_num(dimage,nan=0,posinf=0,neginf=0) + dimage = (dimage/4000*0xffff) + print("Depth pixel range",np.min(dimage),np.max(dimage)) + dimage = dimage.astype(np.uint16) + cv2.imwrite(depth_fn,dimage) + +def main(folder='data',start_index=1): + rospy.init_node("capture_ouster_oak",disable_signals=True) + lidar_sub = rospy.Subscriber("/ouster/points", PointCloud2, lidar_callback) + camera_sub = rospy.Subscriber("/oak/rgb/image_raw", Image, camera_callback) + depth_sub = rospy.Subscriber("/oak/stereo/image_raw", Image, depth_callback) + index = 0 + print(" Storing lidar point clouds as npz") + print(" Storing color images as png") + print(" Storing depth images as tif") + print(" Ctrl+C to quit") + while True: + if camera_image and depth_image: + cv2.imshow("result",bridge.imgmsg_to_cv2(camera_image)) + time.sleep(.5) + files = [ + os.path.join(folder,'lidar{}.npz'.format(index)), + os.path.join(folder,'color{}.png'.format(index)), + os.path.join(folder,'depth{}.tif'.format(index))] + save_scan(*files) + index += 1 + +if __name__ == '__main__': + import sys + folder = 'data' + start_index = 1 + if len(sys.argv) >= 2: + folder = sys.argv[1] + if len(sys.argv) >= 3: + start_index = int(sys.argv[2]) + main(folder,start_index) From 08fa470623bce33bb70ac70f00892cb2a4730984 Mon Sep 17 00:00:00 2001 From: michalj1 Date: Wed, 12 Mar 2025 22:47:29 -0500 Subject: [PATCH 171/232] Include data capture code --- .../calibration/capture_ouster_oak.py | 102 ++++++++++++++++++ 1 file changed, 102 insertions(+) create mode 100644 GEMstack/offboard/calibration/capture_ouster_oak.py diff --git a/GEMstack/offboard/calibration/capture_ouster_oak.py b/GEMstack/offboard/calibration/capture_ouster_oak.py new file mode 100644 index 000000000..3c9e1e6af --- /dev/null +++ b/GEMstack/offboard/calibration/capture_ouster_oak.py @@ -0,0 +1,102 @@ +# ROS Headers +import rospy +from sensor_msgs.msg import Image,PointCloud2 +import sensor_msgs.point_cloud2 as pc2 +import ctypes +import struct + +# OpenCV and cv2 bridge +import cv2 +from cv_bridge import CvBridge +import numpy as np +import os +import time + +lidar_points = None +camera_image = None +depth = None +depth_image = None +bridge = CvBridge() + +def lidar_callback(lidar : PointCloud2): + global lidar_points + lidar_points = lidar + +def camera_callback(img : Image): + global camera_image + camera_image = img + +def depth_callback(img : Image): + global depth_image + depth_image = img + +def pc2_to_numpy(pc2_msg, want_rgb = False): + gen = pc2.read_points(pc2_msg, skip_nans=True) + if want_rgb: + xyzpack = np.array(list(gen),dtype=np.float32) + if xyzpack.shape[1] != 4: + raise ValueError("PointCloud2 does not have points") + xyzrgb = np.empty((xyzpack.shape[0],6)) + xyzrgb[:,:3] = xyzpack[:,:3] + for i,x in enumerate(xyzpack): + rgb = x[3] + # cast float32 to int so that bitwise operations are possible + s = struct.pack('>f' ,rgb) + i = struct.unpack('>l',s)[0] + # you can get back the float value by the inverse operations + pack = ctypes.c_uint32(i).value + r = (pack & 0x00FF0000)>> 16 + g = (pack & 0x0000FF00)>> 8 + b = (pack & 0x000000FF) + #r,g,b values in the 0-255 range + xyzrgb[i,3:] = (r,g,b) + return xyzrgb + else: + return np.array(list(gen),dtype=np.float32)[:,:3] + +def save_scan(lidar_fn,color_fn,depth_fn): + print("Saving scan to",lidar_fn,color_fn) + + pc = pc2_to_numpy(lidar_points,want_rgb=False) # convert lidar feed to numpy + np.savez(lidar_fn,pc) + cv2.imwrite(color_fn,bridge.imgmsg_to_cv2(camera_image)) + + dimage = bridge.imgmsg_to_cv2(depth_image) + dimage_non_nan = dimage[np.isfinite(dimage)] + print("Depth range",np.min(dimage_non_nan),np.max(dimage_non_nan)) + dimage = np.nan_to_num(dimage,nan=0,posinf=0,neginf=0) + dimage = (dimage/4000*0xffff) + print("Depth pixel range",np.min(dimage),np.max(dimage)) + dimage = dimage.astype(np.uint16) + cv2.imwrite(depth_fn,dimage) + +def main(folder='data',start_index=1): + rospy.init_node("capture_ouster_oak",disable_signals=True) + lidar_sub = rospy.Subscriber("/ouster/points", PointCloud2, lidar_callback) + camera_sub = rospy.Subscriber("/oak/rgb/image_raw", Image, camera_callback) + depth_sub = rospy.Subscriber("/oak/stereo/image_raw", Image, depth_callback) + index = 0 + print(" Storing lidar point clouds as npz") + print(" Storing color images as png") + print(" Storing depth images as tif") + print(" Ctrl+C to quit") + while True: + if camera_image and depth_image: + cv2.imshow("result",bridge.imgmsg_to_cv2(camera_image)) + time.sleep(.5) + files = [ + os.path.join(folder,'lidar{}.npz'.format(index)), + os.path.join(folder,'color{}.png'.format(index)), + os.path.join(folder,'depth{}.tif'.format(index))] + save_scan(*files) + index += 1 + +if __name__ == '__main__': + import sys + folder = 'data' + start_index = 1 + if len(sys.argv) >= 2: + folder = sys.argv[1] + if len(sys.argv) >= 3: + start_index = int(sys.argv[2]) + main(folder,start_index) From 073bf49043ae057f6c9bef3fb3d5d5635271833d Mon Sep 17 00:00:00 2001 From: michalj1 Date: Wed, 12 Mar 2025 23:16:38 -0500 Subject: [PATCH 172/232] Add collection from additional sensors --- .../calibration/capture_ouster_oak.py | 104 ++++++++++++------ 1 file changed, 68 insertions(+), 36 deletions(-) diff --git a/GEMstack/offboard/calibration/capture_ouster_oak.py b/GEMstack/offboard/calibration/capture_ouster_oak.py index 3c9e1e6af..3cd912145 100644 --- a/GEMstack/offboard/calibration/capture_ouster_oak.py +++ b/GEMstack/offboard/calibration/capture_ouster_oak.py @@ -12,23 +12,25 @@ import os import time -lidar_points = None -camera_image = None -depth = None -depth_image = None +lidar_points = [] +camera_images = [] +depth_images = [] +lidar_filetype = ".npz" +camera_filetype = ".png" +depth_filetype = ".tif" bridge = CvBridge() def lidar_callback(lidar : PointCloud2): global lidar_points - lidar_points = lidar + lidar_points.append(lidar) def camera_callback(img : Image): - global camera_image - camera_image = img + global camera_images + camera_images.append(img) def depth_callback(img : Image): - global depth_image - depth_image = img + global depth_images + depth_images.append(img) def pc2_to_numpy(pc2_msg, want_rgb = False): gen = pc2.read_points(pc2_msg, skip_nans=True) @@ -54,41 +56,71 @@ def pc2_to_numpy(pc2_msg, want_rgb = False): else: return np.array(list(gen),dtype=np.float32)[:,:3] -def save_scan(lidar_fn,color_fn,depth_fn): - print("Saving scan to",lidar_fn,color_fn) +def clear_scan(): + global lidar_points + lidar_points = [] + global camera_images + camera_images = [] + global depth_images + depth_images = [] + +def save_scan(lidar_filenames, camera_filenames, depth_filenames, index): + if len(lidar_filenames) != len(lidar_points) or len(camera_filenames) != len(camera_images) or len(depth_filenames) != len(depth_images): + print("Missing data, scan", index, "cannot be saved") + return + print("Saving scan", index) - pc = pc2_to_numpy(lidar_points,want_rgb=False) # convert lidar feed to numpy - np.savez(lidar_fn,pc) - cv2.imwrite(color_fn,bridge.imgmsg_to_cv2(camera_image)) + for i in range(len(lidar_points)): + current_lidar = lidar_points[i] + lidar_fn = lidar_filenames[i] + str(index) + lidar_filetype + pc = pc2_to_numpy(current_lidar,want_rgb=False) # convert lidar feed to numpy + np.savez(lidar_fn,pc) - dimage = bridge.imgmsg_to_cv2(depth_image) - dimage_non_nan = dimage[np.isfinite(dimage)] - print("Depth range",np.min(dimage_non_nan),np.max(dimage_non_nan)) - dimage = np.nan_to_num(dimage,nan=0,posinf=0,neginf=0) - dimage = (dimage/4000*0xffff) - print("Depth pixel range",np.min(dimage),np.max(dimage)) - dimage = dimage.astype(np.uint16) - cv2.imwrite(depth_fn,dimage) + for i in range(len(camera_images)): + current_camera = camera_images[i] + camera_fn = camera_filenames[i] + str(index) + camera_filetype + cv2.imwrite(camera_fn,bridge.imgmsg_to_cv2(current_camera)) -def main(folder='data',start_index=1): + for i in range(len(depth_images)): + dimage = bridge.imgmsg_to_cv2(depth_images[i]) + depth_fn = depth_filenames[i] + str(index) + depth_filetype + dimage_non_nan = dimage[np.isfinite(dimage)] + # print("Depth range",np.min(dimage_non_nan),np.max(dimage_non_nan)) + dimage = np.nan_to_num(dimage,nan=0,posinf=0,neginf=0) + dimage = (dimage/4000*0xffff) + # print("Depth pixel range",np.min(dimage),np.max(dimage)) + dimage = dimage.astype(np.uint16) + cv2.imwrite(depth_fn,dimage) + +def main(folder='data',start_index=0): + # Initialize node and establish subscribers rospy.init_node("capture_ouster_oak",disable_signals=True) - lidar_sub = rospy.Subscriber("/ouster/points", PointCloud2, lidar_callback) - camera_sub = rospy.Subscriber("/oak/rgb/image_raw", Image, camera_callback) + ouster_sub = rospy.Subscriber("/ouster/points", PointCloud2, lidar_callback) + livox_sub = rospy.Subscriber("/livox/lidar", PointCloud2, lidar_callback) + oak_sub = rospy.Subscriber("/oak/rgb/image_raw", Image, camera_callback) + cam_fl_sub = rospy.Subscriber("/camera_fl/arena_camera_node/image_raw", Image, camera_callback) + cam_fr_sub = rospy.Subscriber("/camera_fr/arena_camera_node/image_raw", Image, camera_callback) + cam_rl_sub = rospy.Subscriber("/camera_rl/arena_camera_node/image_raw", Image, camera_callback) + cam_rr_sub = rospy.Subscriber("/camera_rr/arena_camera_node/image_raw", Image, camera_callback) depth_sub = rospy.Subscriber("/oak/stereo/image_raw", Image, depth_callback) - index = 0 - print(" Storing lidar point clouds as npz") - print(" Storing color images as png") - print(" Storing depth images as tif") + + # Store scans + index = start_index + print(" Storing lidar point clouds as", lidar_filetype) + print(" Storing color images as", camera_filetype) + print(" Storing depth images as", depth_filetype) print(" Ctrl+C to quit") while True: - if camera_image and depth_image: - cv2.imshow("result",bridge.imgmsg_to_cv2(camera_image)) + if len(camera_images) > 0: + cv2.imshow("result",bridge.imgmsg_to_cv2(camera_images[0])) time.sleep(.5) - files = [ - os.path.join(folder,'lidar{}.npz'.format(index)), - os.path.join(folder,'color{}.png'.format(index)), - os.path.join(folder,'depth{}.tif'.format(index))] - save_scan(*files) + lidar_files = [os.path.join(folder, 'ouster'), os.path.join(folder, 'livox')] + camera_files = [os.path.join(folder, 'oak'), + os.path.join(folder, 'fl'), os.path.join(folder, 'fr'), + os.path.join(folder, 'rl'), os.path.join(folder, 'rr')] + depth_files = [os.path.join(folder, 'depth')] + save_scan(lidar_files, camera_files, depth_files, index) + clear_scan() index += 1 if __name__ == '__main__': From c67909e535d3b5cbf691218fb1b3fae839d2a6fd Mon Sep 17 00:00:00 2001 From: michalj1 Date: Wed, 12 Mar 2025 23:16:38 -0500 Subject: [PATCH 173/232] Add collection from additional sensors --- .../calibration/capture_ouster_oak.py | 104 ++++++++++++------ 1 file changed, 68 insertions(+), 36 deletions(-) diff --git a/GEMstack/offboard/calibration/capture_ouster_oak.py b/GEMstack/offboard/calibration/capture_ouster_oak.py index 3c9e1e6af..3cd912145 100644 --- a/GEMstack/offboard/calibration/capture_ouster_oak.py +++ b/GEMstack/offboard/calibration/capture_ouster_oak.py @@ -12,23 +12,25 @@ import os import time -lidar_points = None -camera_image = None -depth = None -depth_image = None +lidar_points = [] +camera_images = [] +depth_images = [] +lidar_filetype = ".npz" +camera_filetype = ".png" +depth_filetype = ".tif" bridge = CvBridge() def lidar_callback(lidar : PointCloud2): global lidar_points - lidar_points = lidar + lidar_points.append(lidar) def camera_callback(img : Image): - global camera_image - camera_image = img + global camera_images + camera_images.append(img) def depth_callback(img : Image): - global depth_image - depth_image = img + global depth_images + depth_images.append(img) def pc2_to_numpy(pc2_msg, want_rgb = False): gen = pc2.read_points(pc2_msg, skip_nans=True) @@ -54,41 +56,71 @@ def pc2_to_numpy(pc2_msg, want_rgb = False): else: return np.array(list(gen),dtype=np.float32)[:,:3] -def save_scan(lidar_fn,color_fn,depth_fn): - print("Saving scan to",lidar_fn,color_fn) +def clear_scan(): + global lidar_points + lidar_points = [] + global camera_images + camera_images = [] + global depth_images + depth_images = [] + +def save_scan(lidar_filenames, camera_filenames, depth_filenames, index): + if len(lidar_filenames) != len(lidar_points) or len(camera_filenames) != len(camera_images) or len(depth_filenames) != len(depth_images): + print("Missing data, scan", index, "cannot be saved") + return + print("Saving scan", index) - pc = pc2_to_numpy(lidar_points,want_rgb=False) # convert lidar feed to numpy - np.savez(lidar_fn,pc) - cv2.imwrite(color_fn,bridge.imgmsg_to_cv2(camera_image)) + for i in range(len(lidar_points)): + current_lidar = lidar_points[i] + lidar_fn = lidar_filenames[i] + str(index) + lidar_filetype + pc = pc2_to_numpy(current_lidar,want_rgb=False) # convert lidar feed to numpy + np.savez(lidar_fn,pc) - dimage = bridge.imgmsg_to_cv2(depth_image) - dimage_non_nan = dimage[np.isfinite(dimage)] - print("Depth range",np.min(dimage_non_nan),np.max(dimage_non_nan)) - dimage = np.nan_to_num(dimage,nan=0,posinf=0,neginf=0) - dimage = (dimage/4000*0xffff) - print("Depth pixel range",np.min(dimage),np.max(dimage)) - dimage = dimage.astype(np.uint16) - cv2.imwrite(depth_fn,dimage) + for i in range(len(camera_images)): + current_camera = camera_images[i] + camera_fn = camera_filenames[i] + str(index) + camera_filetype + cv2.imwrite(camera_fn,bridge.imgmsg_to_cv2(current_camera)) -def main(folder='data',start_index=1): + for i in range(len(depth_images)): + dimage = bridge.imgmsg_to_cv2(depth_images[i]) + depth_fn = depth_filenames[i] + str(index) + depth_filetype + dimage_non_nan = dimage[np.isfinite(dimage)] + # print("Depth range",np.min(dimage_non_nan),np.max(dimage_non_nan)) + dimage = np.nan_to_num(dimage,nan=0,posinf=0,neginf=0) + dimage = (dimage/4000*0xffff) + # print("Depth pixel range",np.min(dimage),np.max(dimage)) + dimage = dimage.astype(np.uint16) + cv2.imwrite(depth_fn,dimage) + +def main(folder='data',start_index=0): + # Initialize node and establish subscribers rospy.init_node("capture_ouster_oak",disable_signals=True) - lidar_sub = rospy.Subscriber("/ouster/points", PointCloud2, lidar_callback) - camera_sub = rospy.Subscriber("/oak/rgb/image_raw", Image, camera_callback) + ouster_sub = rospy.Subscriber("/ouster/points", PointCloud2, lidar_callback) + livox_sub = rospy.Subscriber("/livox/lidar", PointCloud2, lidar_callback) + oak_sub = rospy.Subscriber("/oak/rgb/image_raw", Image, camera_callback) + cam_fl_sub = rospy.Subscriber("/camera_fl/arena_camera_node/image_raw", Image, camera_callback) + cam_fr_sub = rospy.Subscriber("/camera_fr/arena_camera_node/image_raw", Image, camera_callback) + cam_rl_sub = rospy.Subscriber("/camera_rl/arena_camera_node/image_raw", Image, camera_callback) + cam_rr_sub = rospy.Subscriber("/camera_rr/arena_camera_node/image_raw", Image, camera_callback) depth_sub = rospy.Subscriber("/oak/stereo/image_raw", Image, depth_callback) - index = 0 - print(" Storing lidar point clouds as npz") - print(" Storing color images as png") - print(" Storing depth images as tif") + + # Store scans + index = start_index + print(" Storing lidar point clouds as", lidar_filetype) + print(" Storing color images as", camera_filetype) + print(" Storing depth images as", depth_filetype) print(" Ctrl+C to quit") while True: - if camera_image and depth_image: - cv2.imshow("result",bridge.imgmsg_to_cv2(camera_image)) + if len(camera_images) > 0: + cv2.imshow("result",bridge.imgmsg_to_cv2(camera_images[0])) time.sleep(.5) - files = [ - os.path.join(folder,'lidar{}.npz'.format(index)), - os.path.join(folder,'color{}.png'.format(index)), - os.path.join(folder,'depth{}.tif'.format(index))] - save_scan(*files) + lidar_files = [os.path.join(folder, 'ouster'), os.path.join(folder, 'livox')] + camera_files = [os.path.join(folder, 'oak'), + os.path.join(folder, 'fl'), os.path.join(folder, 'fr'), + os.path.join(folder, 'rl'), os.path.join(folder, 'rr')] + depth_files = [os.path.join(folder, 'depth')] + save_scan(lidar_files, camera_files, depth_files, index) + clear_scan() index += 1 if __name__ == '__main__': From e2a689bc535f4024df0130342f3d7a9c85ef4e04 Mon Sep 17 00:00:00 2001 From: michalj1 Date: Thu, 13 Mar 2025 11:47:23 -0500 Subject: [PATCH 174/232] Collect GNSS latitude and longitude from septentrio --- .../calibration/capture_ouster_oak.py | 24 ++++++++++++++++--- 1 file changed, 21 insertions(+), 3 deletions(-) diff --git a/GEMstack/offboard/calibration/capture_ouster_oak.py b/GEMstack/offboard/calibration/capture_ouster_oak.py index 3cd912145..403153a14 100644 --- a/GEMstack/offboard/calibration/capture_ouster_oak.py +++ b/GEMstack/offboard/calibration/capture_ouster_oak.py @@ -1,6 +1,6 @@ # ROS Headers import rospy -from sensor_msgs.msg import Image,PointCloud2 +from sensor_msgs.msg import Image,PointCloud2,NavSatFix import sensor_msgs.point_cloud2 as pc2 import ctypes import struct @@ -12,12 +12,15 @@ import os import time +# TODO: change these arrays to use dictionaries, format eg. {filename: data} lidar_points = [] camera_images = [] depth_images = [] +gnss_locations = [] lidar_filetype = ".npz" camera_filetype = ".png" depth_filetype = ".tif" +gnss_filetype = ".npy" bridge = CvBridge() def lidar_callback(lidar : PointCloud2): @@ -32,6 +35,10 @@ def depth_callback(img : Image): global depth_images depth_images.append(img) +def gnss_callback(sat_fix : NavSatFix): + global gnss_locations + gnss_locations.append(sat_fix) + def pc2_to_numpy(pc2_msg, want_rgb = False): gen = pc2.read_points(pc2_msg, skip_nans=True) if want_rgb: @@ -63,8 +70,11 @@ def clear_scan(): camera_images = [] global depth_images depth_images = [] + global gnss_locations + gnss_locations = [] -def save_scan(lidar_filenames, camera_filenames, depth_filenames, index): +# TODO: when data is stored in dictionaries, change to only save files which exist and change error checking +def save_scan(lidar_filenames, camera_filenames, depth_filenames, gnss_filenames, index): if len(lidar_filenames) != len(lidar_points) or len(camera_filenames) != len(camera_images) or len(depth_filenames) != len(depth_images): print("Missing data, scan", index, "cannot be saved") return @@ -91,6 +101,12 @@ def save_scan(lidar_filenames, camera_filenames, depth_filenames, index): # print("Depth pixel range",np.min(dimage),np.max(dimage)) dimage = dimage.astype(np.uint16) cv2.imwrite(depth_fn,dimage) + + for i in range(len(gnss_locations)): + sat_fix = gnss_locations[i] + gnss_fn = gnss_filenames + str(index) + gnss_filetype + coordinates = np.array(sat_fix.latitude, sat_fix.longitude) + np.save(gnss_fn, coordinates) def main(folder='data',start_index=0): # Initialize node and establish subscribers @@ -103,6 +119,7 @@ def main(folder='data',start_index=0): cam_rl_sub = rospy.Subscriber("/camera_rl/arena_camera_node/image_raw", Image, camera_callback) cam_rr_sub = rospy.Subscriber("/camera_rr/arena_camera_node/image_raw", Image, camera_callback) depth_sub = rospy.Subscriber("/oak/stereo/image_raw", Image, depth_callback) + gnss_sub = rospy.Subscriber("/septentrio_gnss/navsatfix", NavSatFix, gnss_callback) # Store scans index = start_index @@ -119,7 +136,8 @@ def main(folder='data',start_index=0): os.path.join(folder, 'fl'), os.path.join(folder, 'fr'), os.path.join(folder, 'rl'), os.path.join(folder, 'rr')] depth_files = [os.path.join(folder, 'depth')] - save_scan(lidar_files, camera_files, depth_files, index) + gnss_files = [os.path.join(folder, 'septentrio')] + save_scan(lidar_files, camera_files, depth_files, gnss_files, index) clear_scan() index += 1 From d8dceb9de61a2dd96f2091760f48ac0a2a4db1b6 Mon Sep 17 00:00:00 2001 From: michalj1 Date: Thu, 13 Mar 2025 11:47:23 -0500 Subject: [PATCH 175/232] Collect GNSS latitude and longitude from septentrio --- .../calibration/capture_ouster_oak.py | 24 ++++++++++++++++--- 1 file changed, 21 insertions(+), 3 deletions(-) diff --git a/GEMstack/offboard/calibration/capture_ouster_oak.py b/GEMstack/offboard/calibration/capture_ouster_oak.py index 3cd912145..403153a14 100644 --- a/GEMstack/offboard/calibration/capture_ouster_oak.py +++ b/GEMstack/offboard/calibration/capture_ouster_oak.py @@ -1,6 +1,6 @@ # ROS Headers import rospy -from sensor_msgs.msg import Image,PointCloud2 +from sensor_msgs.msg import Image,PointCloud2,NavSatFix import sensor_msgs.point_cloud2 as pc2 import ctypes import struct @@ -12,12 +12,15 @@ import os import time +# TODO: change these arrays to use dictionaries, format eg. {filename: data} lidar_points = [] camera_images = [] depth_images = [] +gnss_locations = [] lidar_filetype = ".npz" camera_filetype = ".png" depth_filetype = ".tif" +gnss_filetype = ".npy" bridge = CvBridge() def lidar_callback(lidar : PointCloud2): @@ -32,6 +35,10 @@ def depth_callback(img : Image): global depth_images depth_images.append(img) +def gnss_callback(sat_fix : NavSatFix): + global gnss_locations + gnss_locations.append(sat_fix) + def pc2_to_numpy(pc2_msg, want_rgb = False): gen = pc2.read_points(pc2_msg, skip_nans=True) if want_rgb: @@ -63,8 +70,11 @@ def clear_scan(): camera_images = [] global depth_images depth_images = [] + global gnss_locations + gnss_locations = [] -def save_scan(lidar_filenames, camera_filenames, depth_filenames, index): +# TODO: when data is stored in dictionaries, change to only save files which exist and change error checking +def save_scan(lidar_filenames, camera_filenames, depth_filenames, gnss_filenames, index): if len(lidar_filenames) != len(lidar_points) or len(camera_filenames) != len(camera_images) or len(depth_filenames) != len(depth_images): print("Missing data, scan", index, "cannot be saved") return @@ -91,6 +101,12 @@ def save_scan(lidar_filenames, camera_filenames, depth_filenames, index): # print("Depth pixel range",np.min(dimage),np.max(dimage)) dimage = dimage.astype(np.uint16) cv2.imwrite(depth_fn,dimage) + + for i in range(len(gnss_locations)): + sat_fix = gnss_locations[i] + gnss_fn = gnss_filenames + str(index) + gnss_filetype + coordinates = np.array(sat_fix.latitude, sat_fix.longitude) + np.save(gnss_fn, coordinates) def main(folder='data',start_index=0): # Initialize node and establish subscribers @@ -103,6 +119,7 @@ def main(folder='data',start_index=0): cam_rl_sub = rospy.Subscriber("/camera_rl/arena_camera_node/image_raw", Image, camera_callback) cam_rr_sub = rospy.Subscriber("/camera_rr/arena_camera_node/image_raw", Image, camera_callback) depth_sub = rospy.Subscriber("/oak/stereo/image_raw", Image, depth_callback) + gnss_sub = rospy.Subscriber("/septentrio_gnss/navsatfix", NavSatFix, gnss_callback) # Store scans index = start_index @@ -119,7 +136,8 @@ def main(folder='data',start_index=0): os.path.join(folder, 'fl'), os.path.join(folder, 'fr'), os.path.join(folder, 'rl'), os.path.join(folder, 'rr')] depth_files = [os.path.join(folder, 'depth')] - save_scan(lidar_files, camera_files, depth_files, index) + gnss_files = [os.path.join(folder, 'septentrio')] + save_scan(lidar_files, camera_files, depth_files, gnss_files, index) clear_scan() index += 1 From f1ef0860cfdc42a318bd786ea0f64caa9bc33e48 Mon Sep 17 00:00:00 2001 From: michalj1 Date: Thu, 13 Mar 2025 13:26:43 -0500 Subject: [PATCH 176/232] Attempt to add component to track state in local frame --- .../offboard/calibration/capture_ouster_oak.py | 18 ++++++++++++++++++ 1 file changed, 18 insertions(+) diff --git a/GEMstack/offboard/calibration/capture_ouster_oak.py b/GEMstack/offboard/calibration/capture_ouster_oak.py index 403153a14..78c34e449 100644 --- a/GEMstack/offboard/calibration/capture_ouster_oak.py +++ b/GEMstack/offboard/calibration/capture_ouster_oak.py @@ -5,6 +5,9 @@ import ctypes import struct +from ...state import VehicleState, ObjectPose +from ...onboard import Component + # OpenCV and cv2 bridge import cv2 from cv_bridge import CvBridge @@ -17,6 +20,7 @@ camera_images = [] depth_images = [] gnss_locations = [] +frame_position = None lidar_filetype = ".npz" camera_filetype = ".png" depth_filetype = ".tif" @@ -80,6 +84,11 @@ def save_scan(lidar_filenames, camera_filenames, depth_filenames, gnss_filenames return print("Saving scan", index) + if frame_position != None: + np.save("state" + str(index), frame_position) + else: + print("No state found") + for i in range(len(lidar_points)): current_lidar = lidar_points[i] lidar_fn = lidar_filenames[i] + str(index) + lidar_filetype @@ -141,6 +150,15 @@ def main(folder='data',start_index=0): clear_scan() index += 1 +class StateTracker(Component): + def rate(self): + return 4.0 # Hz + def state_inputs(self): + return ['vehicle'] + def update(self, vehicle : VehicleState): + global frame_position + frame_position = np.array(vehicle.pose.frame, vehicle.pose.t, vehicle.pose.x, vehicle.pose.y) + if __name__ == '__main__': import sys folder = 'data' From da593171ba44eb77545ca2c2877abfb8f59b7da5 Mon Sep 17 00:00:00 2001 From: michalj1 Date: Thu, 13 Mar 2025 13:26:43 -0500 Subject: [PATCH 177/232] Attempt to add component to track state in local frame --- .../offboard/calibration/capture_ouster_oak.py | 18 ++++++++++++++++++ 1 file changed, 18 insertions(+) diff --git a/GEMstack/offboard/calibration/capture_ouster_oak.py b/GEMstack/offboard/calibration/capture_ouster_oak.py index 403153a14..78c34e449 100644 --- a/GEMstack/offboard/calibration/capture_ouster_oak.py +++ b/GEMstack/offboard/calibration/capture_ouster_oak.py @@ -5,6 +5,9 @@ import ctypes import struct +from ...state import VehicleState, ObjectPose +from ...onboard import Component + # OpenCV and cv2 bridge import cv2 from cv_bridge import CvBridge @@ -17,6 +20,7 @@ camera_images = [] depth_images = [] gnss_locations = [] +frame_position = None lidar_filetype = ".npz" camera_filetype = ".png" depth_filetype = ".tif" @@ -80,6 +84,11 @@ def save_scan(lidar_filenames, camera_filenames, depth_filenames, gnss_filenames return print("Saving scan", index) + if frame_position != None: + np.save("state" + str(index), frame_position) + else: + print("No state found") + for i in range(len(lidar_points)): current_lidar = lidar_points[i] lidar_fn = lidar_filenames[i] + str(index) + lidar_filetype @@ -141,6 +150,15 @@ def main(folder='data',start_index=0): clear_scan() index += 1 +class StateTracker(Component): + def rate(self): + return 4.0 # Hz + def state_inputs(self): + return ['vehicle'] + def update(self, vehicle : VehicleState): + global frame_position + frame_position = np.array(vehicle.pose.frame, vehicle.pose.t, vehicle.pose.x, vehicle.pose.y) + if __name__ == '__main__': import sys folder = 'data' From 1798d5bf9a55f0b3d05fc4e228d3c01f8bff9149 Mon Sep 17 00:00:00 2001 From: rjsun-KA <92330153+rjsun06@users.noreply.github.com> Date: Mon, 24 Mar 2025 17:41:31 +0000 Subject: [PATCH 178/232] calibration scripts --- GEMstack/offboard/calibration/.gitignore | 2 + .../calibration/camera_to_vehicle_manual.py | 104 +++++++++ .../offboard/calibration/lidar_to_camera.py | 20 ++ .../offboard/calibration/lidar_to_vehicle.py | 216 ++++++++++++++++++ .../offboard/calibration/output/.gitignore | 4 + .../offboard/calibration/run_calibration.bash | 9 + .../offboard/calibration/tools/.gitignore | 2 + .../offboard/calibration/tools/save_cali.py | 79 +++++++ .../offboard/calibration/tools/visualizer.py | 44 ++++ 9 files changed, 480 insertions(+) create mode 100644 GEMstack/offboard/calibration/.gitignore create mode 100644 GEMstack/offboard/calibration/camera_to_vehicle_manual.py create mode 100644 GEMstack/offboard/calibration/lidar_to_camera.py create mode 100644 GEMstack/offboard/calibration/lidar_to_vehicle.py create mode 100644 GEMstack/offboard/calibration/output/.gitignore create mode 100644 GEMstack/offboard/calibration/run_calibration.bash create mode 100644 GEMstack/offboard/calibration/tools/.gitignore create mode 100644 GEMstack/offboard/calibration/tools/save_cali.py create mode 100644 GEMstack/offboard/calibration/tools/visualizer.py diff --git a/GEMstack/offboard/calibration/.gitignore b/GEMstack/offboard/calibration/.gitignore new file mode 100644 index 000000000..c20c2ab73 --- /dev/null +++ b/GEMstack/offboard/calibration/.gitignore @@ -0,0 +1,2 @@ +__pycache__ + diff --git a/GEMstack/offboard/calibration/camera_to_vehicle_manual.py b/GEMstack/offboard/calibration/camera_to_vehicle_manual.py new file mode 100644 index 000000000..abc1efa44 --- /dev/null +++ b/GEMstack/offboard/calibration/camera_to_vehicle_manual.py @@ -0,0 +1,104 @@ +#%% +import pyvista as pv +import argparse +import cv2 +from scipy.spatial.transform import Rotation as R +import matplotlib.pyplot as plt +import numpy as np +from tools.save_cali import load_ex,save_ex,load_in,save_in +from tools.visualizer import visualizer +#%% +def pick_n_img(img,n=4): + corners = [] # Reset the corners list + def click_event(event, x, y, flags, param): + if event == cv2.EVENT_LBUTTONDOWN: + corners.append((x, y)) + cv2.circle(param, (x, y), 5, (0, 255, 0), -1) + cv2.imshow('Image', param) + + cv2.imshow('Image', img) + cv2.setMouseCallback('Image', click_event, img) + + while True: + if len(corners) == n: + break + if cv2.waitKey(1) & 0xFF == ord('q'): + return None + + cv2.destroyAllWindows() + + return corners + +#%% +def pick_n_pc(point_cloud,n=4): + points = [] + def cb(pt,*args): + points.append(pt) + while len(points)!=n: + points = [] + cloud = pv.PolyData(point_cloud) + plotter = pv.Plotter(notebook=False) + plotter.camera.position = (-20,0,20) + plotter.camera.focal_point = (0,0,0) + plotter.add_mesh(cloud, color='lightblue', point_size=5, render_points_as_spheres=True) + plotter.enable_point_picking(cb) + plotter.show() + return points + +#%% +def main(): + parser = argparse.ArgumentParser(description='register image into point cloud using manual feature selection', + formatter_class=argparse.ArgumentDefaultsHelpFormatter) + parser.add_argument('--img_path', type=str, required=True, + help='Path to PNG image') + parser.add_argument('--pc_path', type=str, required=True, + help='Path to NPZ point cloud file') + parser.add_argument('--pc_transform_path', type=str, required=False, + help='Path to ymal file for lidar calibration') + parser.add_argument('--img_intrinsics_path', type=str, required=True, + help='Path to ymal file for image intrinsics') + parser.add_argument('--out_path', type=str, required=False, + help='Path to output ymal file for image extrinsics') + parser.add_argument('--n_features', type=int, required=False, default=8, + help='number of features to select and math') + + + args = parser.parse_args() + + # Load data + N = args.n_features + img = cv2.imread(args.img_path, cv2.IMREAD_UNCHANGED) + pc = np.load(args.pc_path)['arr_0'] + pc = pc[~np.all(pc == 0, axis=1)] # remove (0,0,0)'s + + camera_in = load_in(args.img_intrinsics_path,mode='matrix') + + if args.pc_transform_path is not None: + lidar_ex = load_ex(args.pc_transform_path,mode='matrix') + pc = np.pad(pc,((0,0),(0,1)),constant_values=1) @ lidar_ex.T[:,:3] + + cpoints = np.array(pick_n_img(img,N)).astype(float) + print(cpoints) + + lpoints = np.array(pick_n_pc(pc,N)) + print(lpoints) + + success, rvec, tvec = cv2.solvePnP(lpoints, cpoints, camera_in, None) + R, _ = cv2.Rodrigues(rvec) + + T=np.eye(4) + T[:3, :3] = R + T[:3, 3] = tvec.flatten() + print(T) + + v2c = T + print('vehicle->camera:',v2c) + c2v = np.linalg.inv(v2c) + print('camera->vehicle:',c2v) + + if args.out_path is not None: + save_ex(args.out_path,matrix=c2v) + + +if __name__ == "__main__": + main() \ No newline at end of file diff --git a/GEMstack/offboard/calibration/lidar_to_camera.py b/GEMstack/offboard/calibration/lidar_to_camera.py new file mode 100644 index 000000000..d45b7ab3d --- /dev/null +++ b/GEMstack/offboard/calibration/lidar_to_camera.py @@ -0,0 +1,20 @@ +import numpy as np + +T_lidar_vehicle = np.array([[ 0.99939639, 0.02547917, 0.023615, 1.1 ], + [-0.02530848, 0.99965156, -0.00749882, 0.03773583], + [-0.02379784, 0.00689664, 0.999693, 1.95320223], + [ 0., 0., 0., 1. ]]) + +T_camera_vehicle = np.array([[-0.025131, -0.0304479, 0.99922038, 1.78251567], + [-0.99892897, 0.0396095, -0.0239167, 0.18649424], + [-0.0388504, -0.99875123, -0.03141071, 1.5399846 ], + [ 0., 0., 0., 1. ]]) + +# Invert Camera->Vehicle transformation +T_vehicle_camera = np.linalg.inv(T_camera_vehicle) + +T_lidar_camera = T_vehicle_camera @ T_lidar_vehicle + +# Print result +print("Lidar to Camera Transformation Matrix:") +print(T_lidar_camera) diff --git a/GEMstack/offboard/calibration/lidar_to_vehicle.py b/GEMstack/offboard/calibration/lidar_to_vehicle.py new file mode 100644 index 000000000..235a53488 --- /dev/null +++ b/GEMstack/offboard/calibration/lidar_to_vehicle.py @@ -0,0 +1,216 @@ +#%% +import sys +import math +import numpy as np +from scipy.spatial.transform import Rotation as R +import pyvista as pv +import matplotlib.pyplot as plt +from visualizer import visualizer + +VIS = False # True to show visuals +VIS = True # True to show visuals + +#%% things to extract +tx,ty,tz,rx,ry,rz = [None] * 6 + +#%%============================================================== +#======================= util functions ========================= +#================================================================ +def vis(title='', ratio=1): + print(title) + pv.set_jupyter_backend('client') + return visualizer().set_cam() +def load_scene(path): + sc = np.load(path)['arr_0'] + sc = sc[~np.all(sc == 0, axis=1)] # remove (0,0,0)'s + return sc +def crop(pc,ix=None,iy=None,iz=None): + # crop a subrectangle in a pointcloud + # usage: crop(pc, ix = (x_min,x_max), ...) + # return: array(N,3) + mask = True + for dim,intervel in zip([0,1,2],[ix,iy,iz]): + if not intervel: continue + d,u = intervel + mask &= pc[:,dim] >= d + mask &= pc[:,dim] <= u + print(f'points left after cropping {dim}\'th dim',mask.sum()) + return pc[mask] + +from sklearn.linear_model import RANSACRegressor +from sklearn.linear_model import LinearRegression +def fit_plane_ransac(pc,tol=0.01): + # fit a line/plane/hyperplane in a pointcloud + # pc: np array (N,D). the pointcloud + # tol: the tolerance. default 0.01 + model = RANSACRegressor(LinearRegression(), residual_threshold=tol) + model.fit(pc[:,:-1], pc[:,-1]) + a = model.estimator_.coef_ + inter = model.estimator_.intercept_ + class visual: + def plot(self): + inliers = pc[model.inlier_mask_] + if pc.shape[1] == 2: + plt.title('ransac fitting line') + plt.scatter(pc[:,0], pc[:,1], color='blue', marker='o', s=1) + plt.scatter(inliers[:,0], inliers[:,1], color='red', marker='o', s=1) + x_line = np.linspace(0, max(pc[:,0]), 100).reshape(-1,1) + plt.plot(x_line, x_line * a[0] + inter, color='red', label='Fitted Line') + elif pc.shape[1] == 3: + vis('ransac fitting a plane').add_pc(pc).add_pc(inliers,color='red').show() + return self + + def results(self): + # return: array(D-1), float, array(N,3) + # ^: , coeffs, intercept toward the plane, inliers of the fit + return a,inter + return visual() + +from scipy.spatial import cKDTree +def pc_diff(pc0,pc1,tol=0.1): + # remove points in pc0 from pc1 s.t. euclidian distance is within tolerance + # return: array(N,3) + tree = cKDTree(pc0) + diff = [] + for i, point in enumerate(pc1): + _, idx = tree.query(point) + distance = np.linalg.norm(point - pc0[idx]) # Compute the distance + if distance > tol: + diff.append(point) + tree = cKDTree(pc1) + for i, point in enumerate(pc0): + _, idx = tree.query(point) + distance = np.linalg.norm(point - pc1[idx]) # Compute the distance + if distance > tol: + diff.append(point) + return np.array(diff) + + + + + + +#%%============================================================== +#========================= tz rx ry ============================= +#================================================================ + +#%% load scene for ground plane +# Update depending on where data is stored +sc = load_scene('./data/lidar1.npz') + +# %% we crop to keep the ground +cropped_sc = crop(sc,iz = (-3,-2)) +if VIS: + vis('ground points cropped').add_pc(cropped_sc,color='blue').show() + +#%% +from math import sqrt +fit = fit_plane_ransac(cropped_sc,tol=0.01) # small tol because the ground is very flat +c, inter = fit.results() +normv = np.array([c[0], c[1], -1]) +normv /= np.linalg.norm(normv) +nx,ny,nz = normv +height = nz * inter +# TODO MAGIC NUMBER WARNING +height_axel = 0.2794 # 11 inches that we measured +tz = height - height_axel +if VIS: + fit.plot() +rx = -math.atan2(ny,-nz) +ry = -math.atan2(-nx,-nz) + + +if VIS: + from scipy.spatial.transform import Rotation as R + rot = R.from_euler('xyz',[rx,ry,0]).as_matrix() + cal_sc = sc @ rot.T + [0,0,tz] + vis('yz projection').add_pc(cal_sc*[0,1,1],color='blue').show() + vis('xz projection').add_pc(cal_sc*[1,0,1],color='blue').show() + +#%%============================================================== +#========================== tx ty rz ============================ +#================================================================ + +rot = R.from_euler('xyz',[rx,ry,0]).as_matrix() + +if False: # True to use the diff method to extract object. + # load data: update depending on where data is stored + sc0 = load_scene('./data/lidar70.npz') + sc1 = load_scene('./data/lidar78.npz') + + sc0 = sc0 @ rot.T + [0,0,tz] + sc1 = sc1 @ rot.T + [0,0,tz] + + # crop to only keep a frontal box area + area = (-0,7),(-1,1),(-3,1) + cropped0 = crop(sc0,*area) + cropped1 = crop(sc1,*area) + print(cropped0.shape) + print(cropped1.shape) + + # Take difference to only keep added object + objects = pc_diff(cropped0,cropped1) + +else: #False to use only cropping + # Update depending on where data is stored + sc1 = load_scene('./data/lidar1.npz') + + objects = sc1 @ rot.T + [0,0,tz] + + # crop to only keep a frontal box area + area = (-0,20),(-1,1),(0,1) + objects = crop(objects,*area) + print(objects.shape) + + +#%% +if VIS: + vis().add_pc(objects,color='blue').show() #visualize diff, hopefully the added objects + +# %% use the added objects to find rz. +# TODO after dataset retake +# right now we assume tx = ty = 0 and \ +# just use median to find a headding direction +fit = fit_plane_ransac(objects[:,:2],tol=1) # tol=1 because 1m^3 foam boxes +c,inter = fit.results() +if VIS: + fit.plot() +# tx = ty = 0 +# hx,hy = np.median(diff,axis=0)[:2] +# rz = -np.arctan2(hy,hx) +rz = - math.atan(c) +tx = 2.56 - 1.46 # https://publish.illinois.edu/robotics-autonomy-resources/gem-e4/hardware/ +ty = - inter * math.cos(rz) + +if VIS: + p1 = (0,inter,0) + p2 = max(objects[:,0])*np.array([1,c[0],0])+np.array([0,inter,0]) + vis().add_pc(sc1*np.array([1,1,0]),color='blue').add_line(p1,p2,color='red').show() + + from scipy.spatial.transform import Rotation as R + rot = R.from_euler('xyz',[0,0,rz]).as_matrix() + cal_sc1 = sc1 @ rot.T + [tx,ty,0] + vis().add_pc(cal_sc1,color='blue').show() + + +#%% visualize calibrated pointcloud +if VIS: + rot = R.from_euler('xyz',[rx,ry,rz]).as_matrix() + + cal_sc1 = sc1 @ rot.T + [tx,ty,tz] + v = vis(ratio=100) + proj = [1,1,1] + v.add_pc(cal_sc1*proj,color='blue') + v.add_box((2.56,.61*2,2.03+height_axel),[2.56/2,0,(2.03+height_axel)/2]) + v.show() + # the yellow box should be 11 inches above the ground + # rear-axel center should be at (0,0,0) +# %% +print(f""" +translation: ({tx,ty,tz}) +rotation: ({rx,ry,rz}) +""") + + + +# %% diff --git a/GEMstack/offboard/calibration/output/.gitignore b/GEMstack/offboard/calibration/output/.gitignore new file mode 100644 index 000000000..fd0c7757f --- /dev/null +++ b/GEMstack/offboard/calibration/output/.gitignore @@ -0,0 +1,4 @@ +* + +# track just these files +!.gitignore diff --git a/GEMstack/offboard/calibration/run_calibration.bash b/GEMstack/offboard/calibration/run_calibration.bash new file mode 100644 index 000000000..d3073b7ba --- /dev/null +++ b/GEMstack/offboard/calibration/run_calibration.bash @@ -0,0 +1,9 @@ +root='/mnt/GEMstack' + +python3 $root/GEMstack/offboard/calibration/camera_to_vehicle_manual.py \ + --img_path $root/data/color32.png \ + --pc_path $root/data/lidar32.npz \ + --pc_transform_path $root/GEMstack/knowledge/calibration/gem_e4_ouster.yaml \ + --img_intrinsics_path $root/GEMstack/knowledge/calibration/gem_e4_oak_in.yaml \ + --n_features 4 \ + --out_path /tmp/test.yaml \ \ No newline at end of file diff --git a/GEMstack/offboard/calibration/tools/.gitignore b/GEMstack/offboard/calibration/tools/.gitignore new file mode 100644 index 000000000..c20c2ab73 --- /dev/null +++ b/GEMstack/offboard/calibration/tools/.gitignore @@ -0,0 +1,2 @@ +__pycache__ + diff --git a/GEMstack/offboard/calibration/tools/save_cali.py b/GEMstack/offboard/calibration/tools/save_cali.py new file mode 100644 index 000000000..29e341459 --- /dev/null +++ b/GEMstack/offboard/calibration/tools/save_cali.py @@ -0,0 +1,79 @@ +#%% +import yaml +from yaml import SafeDumper +import numpy as np +def represent_flow_style_list(dumper, data): + return dumper.represent_sequence(yaml.resolver.BaseResolver.DEFAULT_SEQUENCE_TAG, data, flow_style=True) +SafeDumper.add_representer(list, represent_flow_style_list) +#%% +class FlowListDumper(yaml.Dumper): + def represent_list(self, data): + return self.represent_sequence('tag:yaml.org,2002:seq', data, flow_style=True) + +def load_ex(path,mode,ref='rear_axle_center'): + with open(path) as stream: + y = yaml.safe_load(stream) + assert y['reference'] == ref + if mode == 'matrix': + ret = np.zeros((3,4)) + ret[0:3,0:3] = y['rotation'] + ret[:,3] = y['position'] + return ret + elif mode == 'tuple': + return np.array(y['rotation']),np.array(y['position']) + + +def save_ex(path,rotation=None,translation=None,matrix=None,ref='rear_axle_center'): + if matrix is not None: + rot = matrix[0:3,0:3] + trans = matrix[0:3,3] + save_ex(path,rot,trans,ref=ref) + return + ret = {} + ret['reference'] = ref + ret['rotation'] = rotation + ret['translation'] = translation + for i in ret: + if type(ret[i]) == np.ndarray: + ret[i] = ret[i].tolist() + print(yaml.dump(ret,Dumper=SafeDumper,default_flow_style=False)) + with open(path,'w') as stream: + yaml.dump(ret,stream,Dumper=SafeDumper,default_flow_style=False) + +def load_in(path,mode='matrix'): + with open(path) as stream: + y = yaml.safe_load(stream) + if mode == 'matrix': + ret = np.diag(y['focal']) + ret[0:2,2] = y['center'] + return ret + elif mode == 'tuple': + return np.array(y['focal']),np.array(y['center']) + +def save_in(path,focal=None,center=None,matrix=None): + if matrix is not None: + focal = matrix.diagonal() + center = matrix[0:2,2] + save_in(path,focal,center) + return + ret = {} + ret['focal'] = focal + ret['center'] = center + for i in ret: + if type(ret[i]) == np.ndarray: + ret[i] = ret[i].tolist() + print(yaml.dump(ret,Dumper=SafeDumper,default_flow_style=False)) + with open(path,'w') as stream: + yaml.dump(ret,stream,Dumper=SafeDumper,default_flow_style=False) + + +#%% +if __name__ == "__main__": + #%% + rot, trans = load_ex('/mnt/GEMstack/GEMstack/knowledge/calibration/gem_e4_ouster.yaml',mode='tuple') + save_ex('/tmp/test.yaml',rot,trans) + #%% + focal = [1,2,3] + center = [400,500] + save_in('/tmp/test.yaml',focal,center) + load_in('/tmp/test.yaml',mode='tuple') diff --git a/GEMstack/offboard/calibration/tools/visualizer.py b/GEMstack/offboard/calibration/tools/visualizer.py new file mode 100644 index 000000000..c01a711a6 --- /dev/null +++ b/GEMstack/offboard/calibration/tools/visualizer.py @@ -0,0 +1,44 @@ +import pyvista as pv +import os +os.environ['DISPLAY'] = ':0' +class visualizer: + def __init__(self): + self.plotter = pv.Plotter(notebook=False) + self.plotter.show_axes() + + def set_cam(self, pos=(-20, 0, 20), foc=(0, 0, 0)): + self.plotter.camera.position = pos + self.plotter.camera.focal_point = foc + return self + + def add_pc(self, pc, **kargs): + self.plotter.add_mesh( + pv.PolyData(pc), + render_points_as_spheres=True, + point_size=2, + **kargs + ) + return self + + def add_line(self, p1, p2, **kargs): + self.plotter.add_mesh( + pv.Line(p1 , p2), + **kargs, + line_width=1 + ) + return self + + def add_box(self, bound, trans, ratio=1): + l, w, h = map(lambda x: x * ratio, bound) + box = pv.Box(bounds=(-l/2, l/2, -w/2, w/2, -h/2, h/2)) + box = box.translate(list(map(lambda x: x * ratio, trans))) + self.plotter.add_mesh(box, color='yellow') + return self + + def show(self): + self.plotter.show() + return self + + def close(self): + self.plotter.close() + return None From 84105befa04fd8a8142146af58024fe9dee0ffab Mon Sep 17 00:00:00 2001 From: rjsun-KA <92330153+rjsun06@users.noreply.github.com> Date: Mon, 24 Mar 2025 17:41:31 +0000 Subject: [PATCH 179/232] calibration scripts --- GEMstack/offboard/calibration/.gitignore | 2 + .../calibration/camera_to_vehicle_manual.py | 104 +++++++++ .../offboard/calibration/lidar_to_camera.py | 20 ++ .../offboard/calibration/lidar_to_vehicle.py | 216 ++++++++++++++++++ .../offboard/calibration/output/.gitignore | 4 + .../offboard/calibration/run_calibration.bash | 9 + .../offboard/calibration/tools/.gitignore | 2 + .../offboard/calibration/tools/save_cali.py | 79 +++++++ .../offboard/calibration/tools/visualizer.py | 44 ++++ 9 files changed, 480 insertions(+) create mode 100644 GEMstack/offboard/calibration/.gitignore create mode 100644 GEMstack/offboard/calibration/camera_to_vehicle_manual.py create mode 100644 GEMstack/offboard/calibration/lidar_to_camera.py create mode 100644 GEMstack/offboard/calibration/lidar_to_vehicle.py create mode 100644 GEMstack/offboard/calibration/output/.gitignore create mode 100644 GEMstack/offboard/calibration/run_calibration.bash create mode 100644 GEMstack/offboard/calibration/tools/.gitignore create mode 100644 GEMstack/offboard/calibration/tools/save_cali.py create mode 100644 GEMstack/offboard/calibration/tools/visualizer.py diff --git a/GEMstack/offboard/calibration/.gitignore b/GEMstack/offboard/calibration/.gitignore new file mode 100644 index 000000000..c20c2ab73 --- /dev/null +++ b/GEMstack/offboard/calibration/.gitignore @@ -0,0 +1,2 @@ +__pycache__ + diff --git a/GEMstack/offboard/calibration/camera_to_vehicle_manual.py b/GEMstack/offboard/calibration/camera_to_vehicle_manual.py new file mode 100644 index 000000000..abc1efa44 --- /dev/null +++ b/GEMstack/offboard/calibration/camera_to_vehicle_manual.py @@ -0,0 +1,104 @@ +#%% +import pyvista as pv +import argparse +import cv2 +from scipy.spatial.transform import Rotation as R +import matplotlib.pyplot as plt +import numpy as np +from tools.save_cali import load_ex,save_ex,load_in,save_in +from tools.visualizer import visualizer +#%% +def pick_n_img(img,n=4): + corners = [] # Reset the corners list + def click_event(event, x, y, flags, param): + if event == cv2.EVENT_LBUTTONDOWN: + corners.append((x, y)) + cv2.circle(param, (x, y), 5, (0, 255, 0), -1) + cv2.imshow('Image', param) + + cv2.imshow('Image', img) + cv2.setMouseCallback('Image', click_event, img) + + while True: + if len(corners) == n: + break + if cv2.waitKey(1) & 0xFF == ord('q'): + return None + + cv2.destroyAllWindows() + + return corners + +#%% +def pick_n_pc(point_cloud,n=4): + points = [] + def cb(pt,*args): + points.append(pt) + while len(points)!=n: + points = [] + cloud = pv.PolyData(point_cloud) + plotter = pv.Plotter(notebook=False) + plotter.camera.position = (-20,0,20) + plotter.camera.focal_point = (0,0,0) + plotter.add_mesh(cloud, color='lightblue', point_size=5, render_points_as_spheres=True) + plotter.enable_point_picking(cb) + plotter.show() + return points + +#%% +def main(): + parser = argparse.ArgumentParser(description='register image into point cloud using manual feature selection', + formatter_class=argparse.ArgumentDefaultsHelpFormatter) + parser.add_argument('--img_path', type=str, required=True, + help='Path to PNG image') + parser.add_argument('--pc_path', type=str, required=True, + help='Path to NPZ point cloud file') + parser.add_argument('--pc_transform_path', type=str, required=False, + help='Path to ymal file for lidar calibration') + parser.add_argument('--img_intrinsics_path', type=str, required=True, + help='Path to ymal file for image intrinsics') + parser.add_argument('--out_path', type=str, required=False, + help='Path to output ymal file for image extrinsics') + parser.add_argument('--n_features', type=int, required=False, default=8, + help='number of features to select and math') + + + args = parser.parse_args() + + # Load data + N = args.n_features + img = cv2.imread(args.img_path, cv2.IMREAD_UNCHANGED) + pc = np.load(args.pc_path)['arr_0'] + pc = pc[~np.all(pc == 0, axis=1)] # remove (0,0,0)'s + + camera_in = load_in(args.img_intrinsics_path,mode='matrix') + + if args.pc_transform_path is not None: + lidar_ex = load_ex(args.pc_transform_path,mode='matrix') + pc = np.pad(pc,((0,0),(0,1)),constant_values=1) @ lidar_ex.T[:,:3] + + cpoints = np.array(pick_n_img(img,N)).astype(float) + print(cpoints) + + lpoints = np.array(pick_n_pc(pc,N)) + print(lpoints) + + success, rvec, tvec = cv2.solvePnP(lpoints, cpoints, camera_in, None) + R, _ = cv2.Rodrigues(rvec) + + T=np.eye(4) + T[:3, :3] = R + T[:3, 3] = tvec.flatten() + print(T) + + v2c = T + print('vehicle->camera:',v2c) + c2v = np.linalg.inv(v2c) + print('camera->vehicle:',c2v) + + if args.out_path is not None: + save_ex(args.out_path,matrix=c2v) + + +if __name__ == "__main__": + main() \ No newline at end of file diff --git a/GEMstack/offboard/calibration/lidar_to_camera.py b/GEMstack/offboard/calibration/lidar_to_camera.py new file mode 100644 index 000000000..d45b7ab3d --- /dev/null +++ b/GEMstack/offboard/calibration/lidar_to_camera.py @@ -0,0 +1,20 @@ +import numpy as np + +T_lidar_vehicle = np.array([[ 0.99939639, 0.02547917, 0.023615, 1.1 ], + [-0.02530848, 0.99965156, -0.00749882, 0.03773583], + [-0.02379784, 0.00689664, 0.999693, 1.95320223], + [ 0., 0., 0., 1. ]]) + +T_camera_vehicle = np.array([[-0.025131, -0.0304479, 0.99922038, 1.78251567], + [-0.99892897, 0.0396095, -0.0239167, 0.18649424], + [-0.0388504, -0.99875123, -0.03141071, 1.5399846 ], + [ 0., 0., 0., 1. ]]) + +# Invert Camera->Vehicle transformation +T_vehicle_camera = np.linalg.inv(T_camera_vehicle) + +T_lidar_camera = T_vehicle_camera @ T_lidar_vehicle + +# Print result +print("Lidar to Camera Transformation Matrix:") +print(T_lidar_camera) diff --git a/GEMstack/offboard/calibration/lidar_to_vehicle.py b/GEMstack/offboard/calibration/lidar_to_vehicle.py new file mode 100644 index 000000000..235a53488 --- /dev/null +++ b/GEMstack/offboard/calibration/lidar_to_vehicle.py @@ -0,0 +1,216 @@ +#%% +import sys +import math +import numpy as np +from scipy.spatial.transform import Rotation as R +import pyvista as pv +import matplotlib.pyplot as plt +from visualizer import visualizer + +VIS = False # True to show visuals +VIS = True # True to show visuals + +#%% things to extract +tx,ty,tz,rx,ry,rz = [None] * 6 + +#%%============================================================== +#======================= util functions ========================= +#================================================================ +def vis(title='', ratio=1): + print(title) + pv.set_jupyter_backend('client') + return visualizer().set_cam() +def load_scene(path): + sc = np.load(path)['arr_0'] + sc = sc[~np.all(sc == 0, axis=1)] # remove (0,0,0)'s + return sc +def crop(pc,ix=None,iy=None,iz=None): + # crop a subrectangle in a pointcloud + # usage: crop(pc, ix = (x_min,x_max), ...) + # return: array(N,3) + mask = True + for dim,intervel in zip([0,1,2],[ix,iy,iz]): + if not intervel: continue + d,u = intervel + mask &= pc[:,dim] >= d + mask &= pc[:,dim] <= u + print(f'points left after cropping {dim}\'th dim',mask.sum()) + return pc[mask] + +from sklearn.linear_model import RANSACRegressor +from sklearn.linear_model import LinearRegression +def fit_plane_ransac(pc,tol=0.01): + # fit a line/plane/hyperplane in a pointcloud + # pc: np array (N,D). the pointcloud + # tol: the tolerance. default 0.01 + model = RANSACRegressor(LinearRegression(), residual_threshold=tol) + model.fit(pc[:,:-1], pc[:,-1]) + a = model.estimator_.coef_ + inter = model.estimator_.intercept_ + class visual: + def plot(self): + inliers = pc[model.inlier_mask_] + if pc.shape[1] == 2: + plt.title('ransac fitting line') + plt.scatter(pc[:,0], pc[:,1], color='blue', marker='o', s=1) + plt.scatter(inliers[:,0], inliers[:,1], color='red', marker='o', s=1) + x_line = np.linspace(0, max(pc[:,0]), 100).reshape(-1,1) + plt.plot(x_line, x_line * a[0] + inter, color='red', label='Fitted Line') + elif pc.shape[1] == 3: + vis('ransac fitting a plane').add_pc(pc).add_pc(inliers,color='red').show() + return self + + def results(self): + # return: array(D-1), float, array(N,3) + # ^: , coeffs, intercept toward the plane, inliers of the fit + return a,inter + return visual() + +from scipy.spatial import cKDTree +def pc_diff(pc0,pc1,tol=0.1): + # remove points in pc0 from pc1 s.t. euclidian distance is within tolerance + # return: array(N,3) + tree = cKDTree(pc0) + diff = [] + for i, point in enumerate(pc1): + _, idx = tree.query(point) + distance = np.linalg.norm(point - pc0[idx]) # Compute the distance + if distance > tol: + diff.append(point) + tree = cKDTree(pc1) + for i, point in enumerate(pc0): + _, idx = tree.query(point) + distance = np.linalg.norm(point - pc1[idx]) # Compute the distance + if distance > tol: + diff.append(point) + return np.array(diff) + + + + + + +#%%============================================================== +#========================= tz rx ry ============================= +#================================================================ + +#%% load scene for ground plane +# Update depending on where data is stored +sc = load_scene('./data/lidar1.npz') + +# %% we crop to keep the ground +cropped_sc = crop(sc,iz = (-3,-2)) +if VIS: + vis('ground points cropped').add_pc(cropped_sc,color='blue').show() + +#%% +from math import sqrt +fit = fit_plane_ransac(cropped_sc,tol=0.01) # small tol because the ground is very flat +c, inter = fit.results() +normv = np.array([c[0], c[1], -1]) +normv /= np.linalg.norm(normv) +nx,ny,nz = normv +height = nz * inter +# TODO MAGIC NUMBER WARNING +height_axel = 0.2794 # 11 inches that we measured +tz = height - height_axel +if VIS: + fit.plot() +rx = -math.atan2(ny,-nz) +ry = -math.atan2(-nx,-nz) + + +if VIS: + from scipy.spatial.transform import Rotation as R + rot = R.from_euler('xyz',[rx,ry,0]).as_matrix() + cal_sc = sc @ rot.T + [0,0,tz] + vis('yz projection').add_pc(cal_sc*[0,1,1],color='blue').show() + vis('xz projection').add_pc(cal_sc*[1,0,1],color='blue').show() + +#%%============================================================== +#========================== tx ty rz ============================ +#================================================================ + +rot = R.from_euler('xyz',[rx,ry,0]).as_matrix() + +if False: # True to use the diff method to extract object. + # load data: update depending on where data is stored + sc0 = load_scene('./data/lidar70.npz') + sc1 = load_scene('./data/lidar78.npz') + + sc0 = sc0 @ rot.T + [0,0,tz] + sc1 = sc1 @ rot.T + [0,0,tz] + + # crop to only keep a frontal box area + area = (-0,7),(-1,1),(-3,1) + cropped0 = crop(sc0,*area) + cropped1 = crop(sc1,*area) + print(cropped0.shape) + print(cropped1.shape) + + # Take difference to only keep added object + objects = pc_diff(cropped0,cropped1) + +else: #False to use only cropping + # Update depending on where data is stored + sc1 = load_scene('./data/lidar1.npz') + + objects = sc1 @ rot.T + [0,0,tz] + + # crop to only keep a frontal box area + area = (-0,20),(-1,1),(0,1) + objects = crop(objects,*area) + print(objects.shape) + + +#%% +if VIS: + vis().add_pc(objects,color='blue').show() #visualize diff, hopefully the added objects + +# %% use the added objects to find rz. +# TODO after dataset retake +# right now we assume tx = ty = 0 and \ +# just use median to find a headding direction +fit = fit_plane_ransac(objects[:,:2],tol=1) # tol=1 because 1m^3 foam boxes +c,inter = fit.results() +if VIS: + fit.plot() +# tx = ty = 0 +# hx,hy = np.median(diff,axis=0)[:2] +# rz = -np.arctan2(hy,hx) +rz = - math.atan(c) +tx = 2.56 - 1.46 # https://publish.illinois.edu/robotics-autonomy-resources/gem-e4/hardware/ +ty = - inter * math.cos(rz) + +if VIS: + p1 = (0,inter,0) + p2 = max(objects[:,0])*np.array([1,c[0],0])+np.array([0,inter,0]) + vis().add_pc(sc1*np.array([1,1,0]),color='blue').add_line(p1,p2,color='red').show() + + from scipy.spatial.transform import Rotation as R + rot = R.from_euler('xyz',[0,0,rz]).as_matrix() + cal_sc1 = sc1 @ rot.T + [tx,ty,0] + vis().add_pc(cal_sc1,color='blue').show() + + +#%% visualize calibrated pointcloud +if VIS: + rot = R.from_euler('xyz',[rx,ry,rz]).as_matrix() + + cal_sc1 = sc1 @ rot.T + [tx,ty,tz] + v = vis(ratio=100) + proj = [1,1,1] + v.add_pc(cal_sc1*proj,color='blue') + v.add_box((2.56,.61*2,2.03+height_axel),[2.56/2,0,(2.03+height_axel)/2]) + v.show() + # the yellow box should be 11 inches above the ground + # rear-axel center should be at (0,0,0) +# %% +print(f""" +translation: ({tx,ty,tz}) +rotation: ({rx,ry,rz}) +""") + + + +# %% diff --git a/GEMstack/offboard/calibration/output/.gitignore b/GEMstack/offboard/calibration/output/.gitignore new file mode 100644 index 000000000..fd0c7757f --- /dev/null +++ b/GEMstack/offboard/calibration/output/.gitignore @@ -0,0 +1,4 @@ +* + +# track just these files +!.gitignore diff --git a/GEMstack/offboard/calibration/run_calibration.bash b/GEMstack/offboard/calibration/run_calibration.bash new file mode 100644 index 000000000..d3073b7ba --- /dev/null +++ b/GEMstack/offboard/calibration/run_calibration.bash @@ -0,0 +1,9 @@ +root='/mnt/GEMstack' + +python3 $root/GEMstack/offboard/calibration/camera_to_vehicle_manual.py \ + --img_path $root/data/color32.png \ + --pc_path $root/data/lidar32.npz \ + --pc_transform_path $root/GEMstack/knowledge/calibration/gem_e4_ouster.yaml \ + --img_intrinsics_path $root/GEMstack/knowledge/calibration/gem_e4_oak_in.yaml \ + --n_features 4 \ + --out_path /tmp/test.yaml \ \ No newline at end of file diff --git a/GEMstack/offboard/calibration/tools/.gitignore b/GEMstack/offboard/calibration/tools/.gitignore new file mode 100644 index 000000000..c20c2ab73 --- /dev/null +++ b/GEMstack/offboard/calibration/tools/.gitignore @@ -0,0 +1,2 @@ +__pycache__ + diff --git a/GEMstack/offboard/calibration/tools/save_cali.py b/GEMstack/offboard/calibration/tools/save_cali.py new file mode 100644 index 000000000..29e341459 --- /dev/null +++ b/GEMstack/offboard/calibration/tools/save_cali.py @@ -0,0 +1,79 @@ +#%% +import yaml +from yaml import SafeDumper +import numpy as np +def represent_flow_style_list(dumper, data): + return dumper.represent_sequence(yaml.resolver.BaseResolver.DEFAULT_SEQUENCE_TAG, data, flow_style=True) +SafeDumper.add_representer(list, represent_flow_style_list) +#%% +class FlowListDumper(yaml.Dumper): + def represent_list(self, data): + return self.represent_sequence('tag:yaml.org,2002:seq', data, flow_style=True) + +def load_ex(path,mode,ref='rear_axle_center'): + with open(path) as stream: + y = yaml.safe_load(stream) + assert y['reference'] == ref + if mode == 'matrix': + ret = np.zeros((3,4)) + ret[0:3,0:3] = y['rotation'] + ret[:,3] = y['position'] + return ret + elif mode == 'tuple': + return np.array(y['rotation']),np.array(y['position']) + + +def save_ex(path,rotation=None,translation=None,matrix=None,ref='rear_axle_center'): + if matrix is not None: + rot = matrix[0:3,0:3] + trans = matrix[0:3,3] + save_ex(path,rot,trans,ref=ref) + return + ret = {} + ret['reference'] = ref + ret['rotation'] = rotation + ret['translation'] = translation + for i in ret: + if type(ret[i]) == np.ndarray: + ret[i] = ret[i].tolist() + print(yaml.dump(ret,Dumper=SafeDumper,default_flow_style=False)) + with open(path,'w') as stream: + yaml.dump(ret,stream,Dumper=SafeDumper,default_flow_style=False) + +def load_in(path,mode='matrix'): + with open(path) as stream: + y = yaml.safe_load(stream) + if mode == 'matrix': + ret = np.diag(y['focal']) + ret[0:2,2] = y['center'] + return ret + elif mode == 'tuple': + return np.array(y['focal']),np.array(y['center']) + +def save_in(path,focal=None,center=None,matrix=None): + if matrix is not None: + focal = matrix.diagonal() + center = matrix[0:2,2] + save_in(path,focal,center) + return + ret = {} + ret['focal'] = focal + ret['center'] = center + for i in ret: + if type(ret[i]) == np.ndarray: + ret[i] = ret[i].tolist() + print(yaml.dump(ret,Dumper=SafeDumper,default_flow_style=False)) + with open(path,'w') as stream: + yaml.dump(ret,stream,Dumper=SafeDumper,default_flow_style=False) + + +#%% +if __name__ == "__main__": + #%% + rot, trans = load_ex('/mnt/GEMstack/GEMstack/knowledge/calibration/gem_e4_ouster.yaml',mode='tuple') + save_ex('/tmp/test.yaml',rot,trans) + #%% + focal = [1,2,3] + center = [400,500] + save_in('/tmp/test.yaml',focal,center) + load_in('/tmp/test.yaml',mode='tuple') diff --git a/GEMstack/offboard/calibration/tools/visualizer.py b/GEMstack/offboard/calibration/tools/visualizer.py new file mode 100644 index 000000000..c01a711a6 --- /dev/null +++ b/GEMstack/offboard/calibration/tools/visualizer.py @@ -0,0 +1,44 @@ +import pyvista as pv +import os +os.environ['DISPLAY'] = ':0' +class visualizer: + def __init__(self): + self.plotter = pv.Plotter(notebook=False) + self.plotter.show_axes() + + def set_cam(self, pos=(-20, 0, 20), foc=(0, 0, 0)): + self.plotter.camera.position = pos + self.plotter.camera.focal_point = foc + return self + + def add_pc(self, pc, **kargs): + self.plotter.add_mesh( + pv.PolyData(pc), + render_points_as_spheres=True, + point_size=2, + **kargs + ) + return self + + def add_line(self, p1, p2, **kargs): + self.plotter.add_mesh( + pv.Line(p1 , p2), + **kargs, + line_width=1 + ) + return self + + def add_box(self, bound, trans, ratio=1): + l, w, h = map(lambda x: x * ratio, bound) + box = pv.Box(bounds=(-l/2, l/2, -w/2, w/2, -h/2, h/2)) + box = box.translate(list(map(lambda x: x * ratio, trans))) + self.plotter.add_mesh(box, color='yellow') + return self + + def show(self): + self.plotter.show() + return self + + def close(self): + self.plotter.close() + return None From b041270ee88305c758d5ae3d68ee460fe7c652d7 Mon Sep 17 00:00:00 2001 From: michalj1 Date: Mon, 24 Mar 2025 12:46:39 -0500 Subject: [PATCH 180/232] Collect all camera intrinsics and write to files --- GEMstack/offboard/calibration/camera_info.py | 102 +++++++++++++++++++ 1 file changed, 102 insertions(+) create mode 100644 GEMstack/offboard/calibration/camera_info.py diff --git a/GEMstack/offboard/calibration/camera_info.py b/GEMstack/offboard/calibration/camera_info.py new file mode 100644 index 000000000..a1fa4429b --- /dev/null +++ b/GEMstack/offboard/calibration/camera_info.py @@ -0,0 +1,102 @@ +# ROS Headers +import rospy +from sensor_msgs.msg import Image,PointCloud2, CameraInfo +import sensor_msgs.point_cloud2 as pc2 +import ctypes +import struct +import pickle +import image_geometry + +import numpy as np +import os +import time + +oak_info = None +stereo_info = None +right_info = None +left_info = None +fl_info = None +fr_info = None +rl_info = None +rr_info = None + +def oak_callback(info : CameraInfo): + global oak_info + oak_info = info + +def stereo_callback(info : CameraInfo): + global stereo_info + stereo_info = info + +def right_callback(info : CameraInfo): + global right_info + right_info = info + +def left_callback(info : CameraInfo): + global left_info + left_info = info + +def fl_callback(info : CameraInfo): + global fl_info + fl_info = info + +def fr_callback(info : CameraInfo): + global fr_info + fr_info = info + +def rl_callback(info : CameraInfo): + global rl_info + rl_info = info + +def rr_callback(info : CameraInfo): + global rr_info + rr_info = info + +def get_intrinsics(folder): + model = image_geometry.PinholeCameraModel() + model.fromCameraInfo(oak_info) + with open(os.path.join(folder, "oak.txt"), "w") as f: + f.write(model.intrinsicMatrix()) + model.fromCameraInfo(stereo_info) + with open(os.path.join(folder, "stereo.txt"), "w") as f: + f.write(model.intrinsicMatrix()) + model.fromCameraInfo(right_info) + with open(os.path.join(folder, "right.txt"), "w") as f: + f.write(model.intrinsicMatrix()) + model.fromCameraInfo(left_info) + with open(os.path.join(folder, "left.txt"), "w") as f: + f.write(model.intrinsicMatrix()) + model.fromCameraInfo(fl_info) + with open(os.path.join(folder, "fl.txt"), "w") as f: + f.write(model.intrinsicMatrix()) + model.fromCameraInfo(fr_info) + with open(os.path.join(folder, "fr.txt"), "w") as f: + f.write(model.intrinsicMatrix()) + model.fromCameraInfo(rl_info) + with open(os.path.join(folder, "rl.txt"), "w") as f: + f.write(model.intrinsicMatrix()) + model.fromCameraInfo(rr_info) + with open(os.path.join(folder, "rr.txt"), "w") as f: + f.write(model.intrinsicMatrix()) + +def main(folder='data'): + rospy.init_node("capture_cam_info",disable_signals=True) + caminfo_sub = rospy.Subscriber("/oak/rgb/camera_info", CameraInfo, oak_callback) + stereoinfo_sub = rospy.Subscriber("/oak/stereo/camera_info", CameraInfo, stereo_callback) + rightinfo_sub = rospy.Subscriber("/oak/right/camera_info", CameraInfo, right_callback) + leftinfo_sub = rospy.Subscriber("/oak/left/camera_info", CameraInfo, left_callback) + flinfo_sub = rospy.Subscriber("/camera_fl/arena_camera_node/camera_info", CameraInfo, fl_callback) + frinfo_sub = rospy.Subscriber("/camera_fr/arena_camera_node/camera_info", CameraInfo, fr_callback) + rlinfo_sub = rospy.Subscriber("/camera_rl/arena_camera_node/camera_info", CameraInfo, rl_callback) + rrinfo_sub = rospy.Subscriber("/camera_rr/arena_camera_node/camera_info", CameraInfo, rr_callback) + while True: + if oak_info and fl_info and fr_info and rl_info and rr_info: + time.sleep(1) + get_intrinsics(folder) + +if __name__ == '__main__': + import sys + folder = 'data' + if len(sys.argv) >= 2: + folder = sys.argv[1] + main(folder) From b75d59f2092d75672056c2080c4b345f3e656eea Mon Sep 17 00:00:00 2001 From: michalj1 Date: Mon, 24 Mar 2025 12:46:39 -0500 Subject: [PATCH 181/232] Collect all camera intrinsics and write to files --- GEMstack/offboard/calibration/camera_info.py | 102 +++++++++++++++++++ 1 file changed, 102 insertions(+) create mode 100644 GEMstack/offboard/calibration/camera_info.py diff --git a/GEMstack/offboard/calibration/camera_info.py b/GEMstack/offboard/calibration/camera_info.py new file mode 100644 index 000000000..a1fa4429b --- /dev/null +++ b/GEMstack/offboard/calibration/camera_info.py @@ -0,0 +1,102 @@ +# ROS Headers +import rospy +from sensor_msgs.msg import Image,PointCloud2, CameraInfo +import sensor_msgs.point_cloud2 as pc2 +import ctypes +import struct +import pickle +import image_geometry + +import numpy as np +import os +import time + +oak_info = None +stereo_info = None +right_info = None +left_info = None +fl_info = None +fr_info = None +rl_info = None +rr_info = None + +def oak_callback(info : CameraInfo): + global oak_info + oak_info = info + +def stereo_callback(info : CameraInfo): + global stereo_info + stereo_info = info + +def right_callback(info : CameraInfo): + global right_info + right_info = info + +def left_callback(info : CameraInfo): + global left_info + left_info = info + +def fl_callback(info : CameraInfo): + global fl_info + fl_info = info + +def fr_callback(info : CameraInfo): + global fr_info + fr_info = info + +def rl_callback(info : CameraInfo): + global rl_info + rl_info = info + +def rr_callback(info : CameraInfo): + global rr_info + rr_info = info + +def get_intrinsics(folder): + model = image_geometry.PinholeCameraModel() + model.fromCameraInfo(oak_info) + with open(os.path.join(folder, "oak.txt"), "w") as f: + f.write(model.intrinsicMatrix()) + model.fromCameraInfo(stereo_info) + with open(os.path.join(folder, "stereo.txt"), "w") as f: + f.write(model.intrinsicMatrix()) + model.fromCameraInfo(right_info) + with open(os.path.join(folder, "right.txt"), "w") as f: + f.write(model.intrinsicMatrix()) + model.fromCameraInfo(left_info) + with open(os.path.join(folder, "left.txt"), "w") as f: + f.write(model.intrinsicMatrix()) + model.fromCameraInfo(fl_info) + with open(os.path.join(folder, "fl.txt"), "w") as f: + f.write(model.intrinsicMatrix()) + model.fromCameraInfo(fr_info) + with open(os.path.join(folder, "fr.txt"), "w") as f: + f.write(model.intrinsicMatrix()) + model.fromCameraInfo(rl_info) + with open(os.path.join(folder, "rl.txt"), "w") as f: + f.write(model.intrinsicMatrix()) + model.fromCameraInfo(rr_info) + with open(os.path.join(folder, "rr.txt"), "w") as f: + f.write(model.intrinsicMatrix()) + +def main(folder='data'): + rospy.init_node("capture_cam_info",disable_signals=True) + caminfo_sub = rospy.Subscriber("/oak/rgb/camera_info", CameraInfo, oak_callback) + stereoinfo_sub = rospy.Subscriber("/oak/stereo/camera_info", CameraInfo, stereo_callback) + rightinfo_sub = rospy.Subscriber("/oak/right/camera_info", CameraInfo, right_callback) + leftinfo_sub = rospy.Subscriber("/oak/left/camera_info", CameraInfo, left_callback) + flinfo_sub = rospy.Subscriber("/camera_fl/arena_camera_node/camera_info", CameraInfo, fl_callback) + frinfo_sub = rospy.Subscriber("/camera_fr/arena_camera_node/camera_info", CameraInfo, fr_callback) + rlinfo_sub = rospy.Subscriber("/camera_rl/arena_camera_node/camera_info", CameraInfo, rl_callback) + rrinfo_sub = rospy.Subscriber("/camera_rr/arena_camera_node/camera_info", CameraInfo, rr_callback) + while True: + if oak_info and fl_info and fr_info and rl_info and rr_info: + time.sleep(1) + get_intrinsics(folder) + +if __name__ == '__main__': + import sys + folder = 'data' + if len(sys.argv) >= 2: + folder = sys.argv[1] + main(folder) From e88e42204247cd7bbccd45c01a5818046935d54a Mon Sep 17 00:00:00 2001 From: rjsun-KA <92330153+rjsun06@users.noreply.github.com> Date: Mon, 24 Mar 2025 17:56:03 +0000 Subject: [PATCH 182/232] file rename and play with pycolmap --- .../knowledge/calibration/gem_e4_oak_in.yaml | 2 + ...{camera_to_vehicle_manual.py => img2pc.py} | 3 - .../calibration/play_with_pycolmap.py | 164 ++++++++++++++++++ .../{run_calibration.bash => run_img2pc.bash} | 4 +- 4 files changed, 168 insertions(+), 5 deletions(-) create mode 100644 GEMstack/knowledge/calibration/gem_e4_oak_in.yaml rename GEMstack/offboard/calibration/{camera_to_vehicle_manual.py => img2pc.py} (93%) create mode 100644 GEMstack/offboard/calibration/play_with_pycolmap.py rename GEMstack/offboard/calibration/{run_calibration.bash => run_img2pc.bash} (69%) diff --git a/GEMstack/knowledge/calibration/gem_e4_oak_in.yaml b/GEMstack/knowledge/calibration/gem_e4_oak_in.yaml new file mode 100644 index 000000000..bf30a36b2 --- /dev/null +++ b/GEMstack/knowledge/calibration/gem_e4_oak_in.yaml @@ -0,0 +1,2 @@ +center: [573.37109375, 363.700927734375] +focal: [684.8333129882812, 684.6096801757812, 1.0] diff --git a/GEMstack/offboard/calibration/camera_to_vehicle_manual.py b/GEMstack/offboard/calibration/img2pc.py similarity index 93% rename from GEMstack/offboard/calibration/camera_to_vehicle_manual.py rename to GEMstack/offboard/calibration/img2pc.py index abc1efa44..846bc4902 100644 --- a/GEMstack/offboard/calibration/camera_to_vehicle_manual.py +++ b/GEMstack/offboard/calibration/img2pc.py @@ -2,11 +2,8 @@ import pyvista as pv import argparse import cv2 -from scipy.spatial.transform import Rotation as R -import matplotlib.pyplot as plt import numpy as np from tools.save_cali import load_ex,save_ex,load_in,save_in -from tools.visualizer import visualizer #%% def pick_n_img(img,n=4): corners = [] # Reset the corners list diff --git a/GEMstack/offboard/calibration/play_with_pycolmap.py b/GEMstack/offboard/calibration/play_with_pycolmap.py new file mode 100644 index 000000000..9061c97cb --- /dev/null +++ b/GEMstack/offboard/calibration/play_with_pycolmap.py @@ -0,0 +1,164 @@ +#%% +root = '/mnt/GEMstack' +#%% +import numpy as np +import pycolmap +import open3d as o3d +from pathlib import Path +from scipy.spatial.transform import Rotation as R +from tools.save_cali import load_ex, save_ex, load_in, save_in +from tools.visualizer import visualizer as vis +def pc_relative(pc0,pc1): + #get relative translation and rotation from pc0 to pc1 + #in: Nx3 array, Nx3 array + #out: 3 array, 3 array + # Load point clouds + source = o3d.geometry.PointCloud() + source.points = o3d.utility.Vector3dVector(pc0) + target = o3d.geometry.PointCloud() + target.points = o3d.utility.Vector3dVector(pc1) + + # Run ICP + reg_result = o3d.pipelines.registration.registration_icp( + source, target, max_distance=0.1, + estimation_method=o3d.pipelines.registration.TransformationEstimationPointToPoint() + ) + print("Transformation Matrix:\n", reg_result.transformation) + return(reg_result.transformation) + +#%% +img_dir = root + "/data/calib1/img" +# img_dir = root + "/data/test" +output_dir = root + '/GEMstack/offboard/calibration/output' +output_path = Path(output_dir) +output_path.mkdir(exist_ok=True, parents=True) + +# 1. Feature extraction. google 'sift' to know what it does. +extract_options = pycolmap.SiftExtractionOptions() +extract_options.num_threads = 2 +pycolmap.extract_features( + database_path=output_path/"database.db", + image_path=img_dir, + camera_mode=pycolmap.CameraMode.PER_FOLDER, + sift_options=extract_options, + # device=pycolmap._core.Device.cuda +) + +# 2. Feature matching. match_sequential tries matching only on pairs close in filename ordering +match_options = pycolmap.SequentialMatchingOptions() +match_options.overlap = 3 # how many subsequent images should be tried matching. + # 3 is too small actually. do larger if you figured out pycolmap+cuda +pycolmap.match_sequential( + database_path=output_path/"database.db", + matching_options=match_options +) + +# vocabtree matching. alternative to sequantial matching. +# requires a vocab tree from https://demuc.de/colmap/ +# match_options = pycolmap.VocabTreeMatchingOptions() +# match_options.vocab_tree_path = "/mnt/GEMstack/GEMstack/offboard/calibration/output/vocab_tree_flickr100K_words32K.bin" +# pycolmap.match_vocabtree( +# database_path=output_path/"database.db", +# matching_options=match_options +# ) + +# 3. Sparse reconstruction. ba_refine = 0 so it don't mess with the intrinsics we got in feature extraction stage. +mapper_options = pycolmap.IncrementalPipelineOptions() +mapper_options.ba_refine_focal_length = 0 +mapper_options.ba_refine_principal_point = 0 +mapper_options.ba_refine_extra_params = 0 +reconstructions = pycolmap.incremental_mapping( + database_path=output_path/"database.db", + image_path=img_dir, + output_path=output_path, + options=mapper_options +) + +#%% +#%% +# this part tries 3d reconstruction with stereo depth given the images registered in the previous part. +# but patch_match_stereo needs cuda and compiling pycolmap from source so haven't managed to run it. + +# dense_dir = output_path +# dense_dir.mkdir(exist_ok=True) + +# pycolmap.patch_match_stereo( +# input_path=output_path, +# output_path=dense_dir, +# output_type="TXT", +# ) + +# pycolmap.stereo_fusion( +# output_path=dense_dir, +# workspace_path=dense_dir, +# workspace_format="COLMAP", +# max_image_size=2000, +# gpu_index="0", +# ) + +# 4. Depth Map Fusion (Global Registration) +# fused_pc = pycolmap.dense_fusion( +# workspace_path=dense_dir, +# output_path=dense_dir/"fused.ply", +# max_image_size=2000, +# gpu_index="0", +# ) + +#%% +#%% +# get correspondence between image registrations and filenames, +# and find image142 is from oak +[(id,reconstructions[0].image(id).name) for id in reconstructions[0].reg_image_ids()] + +#%% +#make a copy because I was in jupyter lab trying to test different stuff with it +rec = reconstructions[0].__copy__() + +#%% +# anchor the coordination system to image #142 +# because I found #142 is the first registered images from the front camera +trans = rec.image(142).cam_from_world +rec.transform(pycolmap.Sim3d(rotation=trans.rotation,translation=trans.translation)) +print(rec.image(142).viewing_direction()) # shoud be a trivial direction + +#%% +#%% +pc = np.array([p.xyz for p in rec.points3D.values()]) +################################################################################## +#so far we have got pointcloud reconstructed from camera images +################################################################################# +# tranform to vehicle coordination just for visualization +camera_ex = load_ex(root + "/GEMstack/knowledge/calibration/gem_e4_oak.yaml",mode='matrix') +pc = np.pad(pc,((0,0),(0,1)),constant_values=1) @ camera_ex.T[:,:3] + +#%% +def load_scene(path): + sc = np.load(path)['arr_0'] + sc = sc[~np.all(sc == 0, axis=1)] # remove (0,0,0)'s + return sc + +#%% +#%% +# get lidar pointcloud +from save_cali import load_ex +sc = load_scene(root + f"/data/calib1/pc/ouster1.npz") +lidar_ex = load_ex(root + "/GEMstack/knowledge/calibration/gem_e4_ouster.yaml",mode='matrix') +sc = np.pad(sc,((0,0),(0,1)),constant_values=1) @ lidar_ex.T[:,:3] + +#%% +pc = np.array([p.xyz for p in rec.points3D.values()]) +#%% +from visualizer import visualizer as vis +#import os +#os.environ['DISPLAY'] = ':0' +#%% +v = vis() +v.add_pc(pc,color='red') +v.add_pc(sc,color='blue') +v.show() +v.close() + + + +# %% +pc.shape \ No newline at end of file diff --git a/GEMstack/offboard/calibration/run_calibration.bash b/GEMstack/offboard/calibration/run_img2pc.bash similarity index 69% rename from GEMstack/offboard/calibration/run_calibration.bash rename to GEMstack/offboard/calibration/run_img2pc.bash index d3073b7ba..70db81967 100644 --- a/GEMstack/offboard/calibration/run_calibration.bash +++ b/GEMstack/offboard/calibration/run_img2pc.bash @@ -1,9 +1,9 @@ root='/mnt/GEMstack' -python3 $root/GEMstack/offboard/calibration/camera_to_vehicle_manual.py \ +python3 $root/GEMstack/offboard/calibration/img2pc.py \ --img_path $root/data/color32.png \ --pc_path $root/data/lidar32.npz \ --pc_transform_path $root/GEMstack/knowledge/calibration/gem_e4_ouster.yaml \ --img_intrinsics_path $root/GEMstack/knowledge/calibration/gem_e4_oak_in.yaml \ --n_features 4 \ - --out_path /tmp/test.yaml \ \ No newline at end of file + --out_path $root/GEMstack/knowledge/calibration/gem_e4_oak.yaml \ No newline at end of file From b26982911db1ae8aced589bc408afd94ffcc0cb8 Mon Sep 17 00:00:00 2001 From: rjsun-KA <92330153+rjsun06@users.noreply.github.com> Date: Mon, 24 Mar 2025 17:56:03 +0000 Subject: [PATCH 183/232] file rename and play with pycolmap --- .../knowledge/calibration/gem_e4_oak_in.yaml | 2 + ...{camera_to_vehicle_manual.py => img2pc.py} | 3 - .../calibration/play_with_pycolmap.py | 164 ++++++++++++++++++ .../{run_calibration.bash => run_img2pc.bash} | 4 +- 4 files changed, 168 insertions(+), 5 deletions(-) create mode 100644 GEMstack/knowledge/calibration/gem_e4_oak_in.yaml rename GEMstack/offboard/calibration/{camera_to_vehicle_manual.py => img2pc.py} (93%) create mode 100644 GEMstack/offboard/calibration/play_with_pycolmap.py rename GEMstack/offboard/calibration/{run_calibration.bash => run_img2pc.bash} (69%) diff --git a/GEMstack/knowledge/calibration/gem_e4_oak_in.yaml b/GEMstack/knowledge/calibration/gem_e4_oak_in.yaml new file mode 100644 index 000000000..bf30a36b2 --- /dev/null +++ b/GEMstack/knowledge/calibration/gem_e4_oak_in.yaml @@ -0,0 +1,2 @@ +center: [573.37109375, 363.700927734375] +focal: [684.8333129882812, 684.6096801757812, 1.0] diff --git a/GEMstack/offboard/calibration/camera_to_vehicle_manual.py b/GEMstack/offboard/calibration/img2pc.py similarity index 93% rename from GEMstack/offboard/calibration/camera_to_vehicle_manual.py rename to GEMstack/offboard/calibration/img2pc.py index abc1efa44..846bc4902 100644 --- a/GEMstack/offboard/calibration/camera_to_vehicle_manual.py +++ b/GEMstack/offboard/calibration/img2pc.py @@ -2,11 +2,8 @@ import pyvista as pv import argparse import cv2 -from scipy.spatial.transform import Rotation as R -import matplotlib.pyplot as plt import numpy as np from tools.save_cali import load_ex,save_ex,load_in,save_in -from tools.visualizer import visualizer #%% def pick_n_img(img,n=4): corners = [] # Reset the corners list diff --git a/GEMstack/offboard/calibration/play_with_pycolmap.py b/GEMstack/offboard/calibration/play_with_pycolmap.py new file mode 100644 index 000000000..9061c97cb --- /dev/null +++ b/GEMstack/offboard/calibration/play_with_pycolmap.py @@ -0,0 +1,164 @@ +#%% +root = '/mnt/GEMstack' +#%% +import numpy as np +import pycolmap +import open3d as o3d +from pathlib import Path +from scipy.spatial.transform import Rotation as R +from tools.save_cali import load_ex, save_ex, load_in, save_in +from tools.visualizer import visualizer as vis +def pc_relative(pc0,pc1): + #get relative translation and rotation from pc0 to pc1 + #in: Nx3 array, Nx3 array + #out: 3 array, 3 array + # Load point clouds + source = o3d.geometry.PointCloud() + source.points = o3d.utility.Vector3dVector(pc0) + target = o3d.geometry.PointCloud() + target.points = o3d.utility.Vector3dVector(pc1) + + # Run ICP + reg_result = o3d.pipelines.registration.registration_icp( + source, target, max_distance=0.1, + estimation_method=o3d.pipelines.registration.TransformationEstimationPointToPoint() + ) + print("Transformation Matrix:\n", reg_result.transformation) + return(reg_result.transformation) + +#%% +img_dir = root + "/data/calib1/img" +# img_dir = root + "/data/test" +output_dir = root + '/GEMstack/offboard/calibration/output' +output_path = Path(output_dir) +output_path.mkdir(exist_ok=True, parents=True) + +# 1. Feature extraction. google 'sift' to know what it does. +extract_options = pycolmap.SiftExtractionOptions() +extract_options.num_threads = 2 +pycolmap.extract_features( + database_path=output_path/"database.db", + image_path=img_dir, + camera_mode=pycolmap.CameraMode.PER_FOLDER, + sift_options=extract_options, + # device=pycolmap._core.Device.cuda +) + +# 2. Feature matching. match_sequential tries matching only on pairs close in filename ordering +match_options = pycolmap.SequentialMatchingOptions() +match_options.overlap = 3 # how many subsequent images should be tried matching. + # 3 is too small actually. do larger if you figured out pycolmap+cuda +pycolmap.match_sequential( + database_path=output_path/"database.db", + matching_options=match_options +) + +# vocabtree matching. alternative to sequantial matching. +# requires a vocab tree from https://demuc.de/colmap/ +# match_options = pycolmap.VocabTreeMatchingOptions() +# match_options.vocab_tree_path = "/mnt/GEMstack/GEMstack/offboard/calibration/output/vocab_tree_flickr100K_words32K.bin" +# pycolmap.match_vocabtree( +# database_path=output_path/"database.db", +# matching_options=match_options +# ) + +# 3. Sparse reconstruction. ba_refine = 0 so it don't mess with the intrinsics we got in feature extraction stage. +mapper_options = pycolmap.IncrementalPipelineOptions() +mapper_options.ba_refine_focal_length = 0 +mapper_options.ba_refine_principal_point = 0 +mapper_options.ba_refine_extra_params = 0 +reconstructions = pycolmap.incremental_mapping( + database_path=output_path/"database.db", + image_path=img_dir, + output_path=output_path, + options=mapper_options +) + +#%% +#%% +# this part tries 3d reconstruction with stereo depth given the images registered in the previous part. +# but patch_match_stereo needs cuda and compiling pycolmap from source so haven't managed to run it. + +# dense_dir = output_path +# dense_dir.mkdir(exist_ok=True) + +# pycolmap.patch_match_stereo( +# input_path=output_path, +# output_path=dense_dir, +# output_type="TXT", +# ) + +# pycolmap.stereo_fusion( +# output_path=dense_dir, +# workspace_path=dense_dir, +# workspace_format="COLMAP", +# max_image_size=2000, +# gpu_index="0", +# ) + +# 4. Depth Map Fusion (Global Registration) +# fused_pc = pycolmap.dense_fusion( +# workspace_path=dense_dir, +# output_path=dense_dir/"fused.ply", +# max_image_size=2000, +# gpu_index="0", +# ) + +#%% +#%% +# get correspondence between image registrations and filenames, +# and find image142 is from oak +[(id,reconstructions[0].image(id).name) for id in reconstructions[0].reg_image_ids()] + +#%% +#make a copy because I was in jupyter lab trying to test different stuff with it +rec = reconstructions[0].__copy__() + +#%% +# anchor the coordination system to image #142 +# because I found #142 is the first registered images from the front camera +trans = rec.image(142).cam_from_world +rec.transform(pycolmap.Sim3d(rotation=trans.rotation,translation=trans.translation)) +print(rec.image(142).viewing_direction()) # shoud be a trivial direction + +#%% +#%% +pc = np.array([p.xyz for p in rec.points3D.values()]) +################################################################################## +#so far we have got pointcloud reconstructed from camera images +################################################################################# +# tranform to vehicle coordination just for visualization +camera_ex = load_ex(root + "/GEMstack/knowledge/calibration/gem_e4_oak.yaml",mode='matrix') +pc = np.pad(pc,((0,0),(0,1)),constant_values=1) @ camera_ex.T[:,:3] + +#%% +def load_scene(path): + sc = np.load(path)['arr_0'] + sc = sc[~np.all(sc == 0, axis=1)] # remove (0,0,0)'s + return sc + +#%% +#%% +# get lidar pointcloud +from save_cali import load_ex +sc = load_scene(root + f"/data/calib1/pc/ouster1.npz") +lidar_ex = load_ex(root + "/GEMstack/knowledge/calibration/gem_e4_ouster.yaml",mode='matrix') +sc = np.pad(sc,((0,0),(0,1)),constant_values=1) @ lidar_ex.T[:,:3] + +#%% +pc = np.array([p.xyz for p in rec.points3D.values()]) +#%% +from visualizer import visualizer as vis +#import os +#os.environ['DISPLAY'] = ':0' +#%% +v = vis() +v.add_pc(pc,color='red') +v.add_pc(sc,color='blue') +v.show() +v.close() + + + +# %% +pc.shape \ No newline at end of file diff --git a/GEMstack/offboard/calibration/run_calibration.bash b/GEMstack/offboard/calibration/run_img2pc.bash similarity index 69% rename from GEMstack/offboard/calibration/run_calibration.bash rename to GEMstack/offboard/calibration/run_img2pc.bash index d3073b7ba..70db81967 100644 --- a/GEMstack/offboard/calibration/run_calibration.bash +++ b/GEMstack/offboard/calibration/run_img2pc.bash @@ -1,9 +1,9 @@ root='/mnt/GEMstack' -python3 $root/GEMstack/offboard/calibration/camera_to_vehicle_manual.py \ +python3 $root/GEMstack/offboard/calibration/img2pc.py \ --img_path $root/data/color32.png \ --pc_path $root/data/lidar32.npz \ --pc_transform_path $root/GEMstack/knowledge/calibration/gem_e4_ouster.yaml \ --img_intrinsics_path $root/GEMstack/knowledge/calibration/gem_e4_oak_in.yaml \ --n_features 4 \ - --out_path /tmp/test.yaml \ \ No newline at end of file + --out_path $root/GEMstack/knowledge/calibration/gem_e4_oak.yaml \ No newline at end of file From 2e6b44419963428f40e260c9acf50dc66b08a3e2 Mon Sep 17 00:00:00 2001 From: rjsun-KA <92330153+rjsun06@users.noreply.github.com> Date: Mon, 24 Mar 2025 18:12:12 +0000 Subject: [PATCH 184/232] typo --- GEMstack/offboard/calibration/tools/visualizer.py | 2 -- 1 file changed, 2 deletions(-) diff --git a/GEMstack/offboard/calibration/tools/visualizer.py b/GEMstack/offboard/calibration/tools/visualizer.py index c01a711a6..2139a020c 100644 --- a/GEMstack/offboard/calibration/tools/visualizer.py +++ b/GEMstack/offboard/calibration/tools/visualizer.py @@ -1,6 +1,4 @@ import pyvista as pv -import os -os.environ['DISPLAY'] = ':0' class visualizer: def __init__(self): self.plotter = pv.Plotter(notebook=False) From f9cf542988f4a55bdde4a665546c1e5854cf907d Mon Sep 17 00:00:00 2001 From: rjsun-KA <92330153+rjsun06@users.noreply.github.com> Date: Mon, 24 Mar 2025 18:12:12 +0000 Subject: [PATCH 185/232] typo --- GEMstack/offboard/calibration/tools/visualizer.py | 2 -- 1 file changed, 2 deletions(-) diff --git a/GEMstack/offboard/calibration/tools/visualizer.py b/GEMstack/offboard/calibration/tools/visualizer.py index c01a711a6..2139a020c 100644 --- a/GEMstack/offboard/calibration/tools/visualizer.py +++ b/GEMstack/offboard/calibration/tools/visualizer.py @@ -1,6 +1,4 @@ import pyvista as pv -import os -os.environ['DISPLAY'] = ':0' class visualizer: def __init__(self): self.plotter = pv.Plotter(notebook=False) From f242fa731dcf522e3efd0c8a94c156f9426833e0 Mon Sep 17 00:00:00 2001 From: rjsun-KA <92330153+rjsun06@users.noreply.github.com> Date: Mon, 24 Mar 2025 18:59:09 +0000 Subject: [PATCH 186/232] typo --- GEMstack/offboard/calibration/play_with_pycolmap.py | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/GEMstack/offboard/calibration/play_with_pycolmap.py b/GEMstack/offboard/calibration/play_with_pycolmap.py index 9061c97cb..03a419b7d 100644 --- a/GEMstack/offboard/calibration/play_with_pycolmap.py +++ b/GEMstack/offboard/calibration/play_with_pycolmap.py @@ -8,6 +8,7 @@ from scipy.spatial.transform import Rotation as R from tools.save_cali import load_ex, save_ex, load_in, save_in from tools.visualizer import visualizer as vis + def pc_relative(pc0,pc1): #get relative translation and rotation from pc0 to pc1 #in: Nx3 array, Nx3 array @@ -140,7 +141,6 @@ def load_scene(path): #%% #%% # get lidar pointcloud -from save_cali import load_ex sc = load_scene(root + f"/data/calib1/pc/ouster1.npz") lidar_ex = load_ex(root + "/GEMstack/knowledge/calibration/gem_e4_ouster.yaml",mode='matrix') sc = np.pad(sc,((0,0),(0,1)),constant_values=1) @ lidar_ex.T[:,:3] @@ -148,7 +148,6 @@ def load_scene(path): #%% pc = np.array([p.xyz for p in rec.points3D.values()]) #%% -from visualizer import visualizer as vis #import os #os.environ['DISPLAY'] = ':0' #%% From 09011b0eeddd5f7cc3c45562594da6dcfd2560ba Mon Sep 17 00:00:00 2001 From: rjsun-KA <92330153+rjsun06@users.noreply.github.com> Date: Mon, 24 Mar 2025 18:59:09 +0000 Subject: [PATCH 187/232] typo --- GEMstack/offboard/calibration/play_with_pycolmap.py | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/GEMstack/offboard/calibration/play_with_pycolmap.py b/GEMstack/offboard/calibration/play_with_pycolmap.py index 9061c97cb..03a419b7d 100644 --- a/GEMstack/offboard/calibration/play_with_pycolmap.py +++ b/GEMstack/offboard/calibration/play_with_pycolmap.py @@ -8,6 +8,7 @@ from scipy.spatial.transform import Rotation as R from tools.save_cali import load_ex, save_ex, load_in, save_in from tools.visualizer import visualizer as vis + def pc_relative(pc0,pc1): #get relative translation and rotation from pc0 to pc1 #in: Nx3 array, Nx3 array @@ -140,7 +141,6 @@ def load_scene(path): #%% #%% # get lidar pointcloud -from save_cali import load_ex sc = load_scene(root + f"/data/calib1/pc/ouster1.npz") lidar_ex = load_ex(root + "/GEMstack/knowledge/calibration/gem_e4_ouster.yaml",mode='matrix') sc = np.pad(sc,((0,0),(0,1)),constant_values=1) @ lidar_ex.T[:,:3] @@ -148,7 +148,6 @@ def load_scene(path): #%% pc = np.array([p.xyz for p in rec.points3D.values()]) #%% -from visualizer import visualizer as vis #import os #os.environ['DISPLAY'] = ':0' #%% From 65784dcd02329e2e69139bd11c1bac1559d98a32 Mon Sep 17 00:00:00 2001 From: michalj1 Date: Wed, 26 Mar 2025 13:30:19 -0500 Subject: [PATCH 188/232] Versions working on GEM --- GEMstack/offboard/calibration/camera_info.py | 16 +- .../calibration/capture_ouster_oak.py | 174 ++++++++++-------- 2 files changed, 110 insertions(+), 80 deletions(-) diff --git a/GEMstack/offboard/calibration/camera_info.py b/GEMstack/offboard/calibration/camera_info.py index a1fa4429b..339f5f9be 100644 --- a/GEMstack/offboard/calibration/camera_info.py +++ b/GEMstack/offboard/calibration/camera_info.py @@ -56,28 +56,28 @@ def get_intrinsics(folder): model = image_geometry.PinholeCameraModel() model.fromCameraInfo(oak_info) with open(os.path.join(folder, "oak.txt"), "w") as f: - f.write(model.intrinsicMatrix()) + f.write(str(model.intrinsicMatrix())) model.fromCameraInfo(stereo_info) with open(os.path.join(folder, "stereo.txt"), "w") as f: - f.write(model.intrinsicMatrix()) + f.write(str(model.intrinsicMatrix())) model.fromCameraInfo(right_info) with open(os.path.join(folder, "right.txt"), "w") as f: - f.write(model.intrinsicMatrix()) + f.write(str(model.intrinsicMatrix())) model.fromCameraInfo(left_info) with open(os.path.join(folder, "left.txt"), "w") as f: - f.write(model.intrinsicMatrix()) + f.write(str(model.intrinsicMatrix())) model.fromCameraInfo(fl_info) with open(os.path.join(folder, "fl.txt"), "w") as f: - f.write(model.intrinsicMatrix()) + f.write(str(model.intrinsicMatrix())) model.fromCameraInfo(fr_info) with open(os.path.join(folder, "fr.txt"), "w") as f: - f.write(model.intrinsicMatrix()) + f.write(str(model.intrinsicMatrix())) model.fromCameraInfo(rl_info) with open(os.path.join(folder, "rl.txt"), "w") as f: - f.write(model.intrinsicMatrix()) + f.write(str(model.intrinsicMatrix())) model.fromCameraInfo(rr_info) with open(os.path.join(folder, "rr.txt"), "w") as f: - f.write(model.intrinsicMatrix()) + f.write(str(model.intrinsicMatrix())) def main(folder='data'): rospy.init_node("capture_cam_info",disable_signals=True) diff --git a/GEMstack/offboard/calibration/capture_ouster_oak.py b/GEMstack/offboard/calibration/capture_ouster_oak.py index 78c34e449..baee8985b 100644 --- a/GEMstack/offboard/calibration/capture_ouster_oak.py +++ b/GEMstack/offboard/calibration/capture_ouster_oak.py @@ -5,8 +5,8 @@ import ctypes import struct -from ...state import VehicleState, ObjectPose -from ...onboard import Component +# from ...state import VehicleState, ObjectPose +# from ...onboard import Component # OpenCV and cv2 bridge import cv2 @@ -16,10 +16,14 @@ import time # TODO: change these arrays to use dictionaries, format eg. {filename: data} -lidar_points = [] -camera_images = [] -depth_images = [] -gnss_locations = [] +lidar_points = None +camera_image = None +fl_image = None +fr_image = None +rl_image = None +rr_image = None +depth_images = None +gnss_locations = None frame_position = None lidar_filetype = ".npz" camera_filetype = ".png" @@ -29,19 +33,35 @@ def lidar_callback(lidar : PointCloud2): global lidar_points - lidar_points.append(lidar) + lidar_points = (lidar) def camera_callback(img : Image): - global camera_images - camera_images.append(img) + global camera_image + camera_image = (img) + +def fl_camera_callback(img : Image): + global fl_image + fl_image = (img) + +def fr_camera_callback(img : Image): + global fr_image + fr_image = (img) + +def rl_camera_callback(img : Image): + global rl_image + rl_image = (img) + +def rr_camera_callback(img : Image): + global rr_image + rr_image = (img) def depth_callback(img : Image): global depth_images - depth_images.append(img) + depth_images = (img) def gnss_callback(sat_fix : NavSatFix): global gnss_locations - gnss_locations.append(sat_fix) + gnss_locations = (sat_fix) def pc2_to_numpy(pc2_msg, want_rgb = False): gen = pc2.read_points(pc2_msg, skip_nans=True) @@ -67,21 +87,22 @@ def pc2_to_numpy(pc2_msg, want_rgb = False): else: return np.array(list(gen),dtype=np.float32)[:,:3] -def clear_scan(): - global lidar_points - lidar_points = [] - global camera_images - camera_images = [] - global depth_images - depth_images = [] - global gnss_locations - gnss_locations = [] +# def clear_scan(): +# global lidar_points +# lidar_points = [] +# global camera_image +# camera_image = [] +# global depth_images +# depth_images = [] +# global gnss_locations +# gnss_locations = [] # TODO: when data is stored in dictionaries, change to only save files which exist and change error checking -def save_scan(lidar_filenames, camera_filenames, depth_filenames, gnss_filenames, index): - if len(lidar_filenames) != len(lidar_points) or len(camera_filenames) != len(camera_images) or len(depth_filenames) != len(depth_images): - print("Missing data, scan", index, "cannot be saved") - return +def save_scan(lidar_fn, camera_fn, fl_fn, fr_fn, rl_fn, rr_fn, depth_fn, gnss_fn, index): + # if len(lidar_filenames) != len(lidar_points) or len(camera_filenames) != len(camera_image) or len(depth_filenames) != len(depth_images): + # print("Missing data, scan", index, "cannot be saved") + # print(len(lidar_filenames), len(lidar_points), len(camera_filenames), len(camera_image), len(depth_filenames), len(depth_images)) + # return print("Saving scan", index) if frame_position != None: @@ -89,44 +110,49 @@ def save_scan(lidar_filenames, camera_filenames, depth_filenames, gnss_filenames else: print("No state found") - for i in range(len(lidar_points)): - current_lidar = lidar_points[i] - lidar_fn = lidar_filenames[i] + str(index) + lidar_filetype - pc = pc2_to_numpy(current_lidar,want_rgb=False) # convert lidar feed to numpy - np.savez(lidar_fn,pc) - - for i in range(len(camera_images)): - current_camera = camera_images[i] - camera_fn = camera_filenames[i] + str(index) + camera_filetype - cv2.imwrite(camera_fn,bridge.imgmsg_to_cv2(current_camera)) - - for i in range(len(depth_images)): - dimage = bridge.imgmsg_to_cv2(depth_images[i]) - depth_fn = depth_filenames[i] + str(index) + depth_filetype - dimage_non_nan = dimage[np.isfinite(dimage)] - # print("Depth range",np.min(dimage_non_nan),np.max(dimage_non_nan)) - dimage = np.nan_to_num(dimage,nan=0,posinf=0,neginf=0) - dimage = (dimage/4000*0xffff) - # print("Depth pixel range",np.min(dimage),np.max(dimage)) - dimage = dimage.astype(np.uint16) - cv2.imwrite(depth_fn,dimage) + # for i in range(len(lidar_points)): + # current_lidar = lidar_points[i] + # lidar_fn = lidar_filename + str(index) + lidar_filetype + pc = pc2_to_numpy(lidar_points,want_rgb=False) # convert lidar feed to numpy + np.savez(lidar_fn + str(index) + lidar_filetype,pc) + + # for i in range(len(camera_image)): + # current_camera = camera_image[i] + # camera_fn = camera_filenames[i] + str(index) + camera_filetype + cv2.imwrite(camera_fn + str(index) + camera_filetype,bridge.imgmsg_to_cv2(camera_image)) + cv2.imwrite(fl_fn + str(index) + camera_filetype,bridge.imgmsg_to_cv2(fl_image)) + cv2.imwrite(fr_fn + str(index) + camera_filetype,bridge.imgmsg_to_cv2(fr_image)) + cv2.imwrite(rl_fn + str(index) + camera_filetype,bridge.imgmsg_to_cv2(rl_image)) + cv2.imwrite(rr_fn + str(index) + camera_filetype,bridge.imgmsg_to_cv2(rr_image)) + + # for i in range(len(depth_images)): + dimage = bridge.imgmsg_to_cv2(depth_images) + # depth_fn = depth_filenames[i] + str(index) + depth_filetype + dimage_non_nan = dimage[np.isfinite(dimage)] + # print("Depth range",np.min(dimage_non_nan),np.max(dimage_non_nan)) + dimage = np.nan_to_num(dimage,nan=0,posinf=0,neginf=0) + dimage = (dimage/4000*0xffff) + # print("Depth pixel range",np.min(dimage),np.max(dimage)) + dimage = dimage.astype(np.uint16) + cv2.imwrite(depth_fn + str(index) + depth_filetype,dimage) - for i in range(len(gnss_locations)): - sat_fix = gnss_locations[i] - gnss_fn = gnss_filenames + str(index) + gnss_filetype - coordinates = np.array(sat_fix.latitude, sat_fix.longitude) - np.save(gnss_fn, coordinates) + # for i in range(len(gnss_locations)): + # sat_fix = gnss_locations[i] + # gnss_fn = gnss_filenames + str(index) + gnss_filetype + if gnss_locations: + coordinates = np.array([gnss_locations.latitude, gnss_locations.longitude]) + np.save(gnss_fn + str(index) + gnss_filetype, coordinates) def main(folder='data',start_index=0): # Initialize node and establish subscribers rospy.init_node("capture_ouster_oak",disable_signals=True) ouster_sub = rospy.Subscriber("/ouster/points", PointCloud2, lidar_callback) - livox_sub = rospy.Subscriber("/livox/lidar", PointCloud2, lidar_callback) + # livox_sub = rospy.Subscriber("/livox/lidar", PointCloud2, lidar_callback) oak_sub = rospy.Subscriber("/oak/rgb/image_raw", Image, camera_callback) - cam_fl_sub = rospy.Subscriber("/camera_fl/arena_camera_node/image_raw", Image, camera_callback) - cam_fr_sub = rospy.Subscriber("/camera_fr/arena_camera_node/image_raw", Image, camera_callback) - cam_rl_sub = rospy.Subscriber("/camera_rl/arena_camera_node/image_raw", Image, camera_callback) - cam_rr_sub = rospy.Subscriber("/camera_rr/arena_camera_node/image_raw", Image, camera_callback) + cam_fl_sub = rospy.Subscriber("/camera_fl/arena_camera_node/image_raw", Image, fl_camera_callback) + cam_fr_sub = rospy.Subscriber("/camera_fr/arena_camera_node/image_raw", Image, fr_camera_callback) + cam_rl_sub = rospy.Subscriber("/camera_rl/arena_camera_node/image_raw", Image, rl_camera_callback) + cam_rr_sub = rospy.Subscriber("/camera_rr/arena_camera_node/image_raw", Image, rr_camera_callback) depth_sub = rospy.Subscriber("/oak/stereo/image_raw", Image, depth_callback) gnss_sub = rospy.Subscriber("/septentrio_gnss/navsatfix", NavSatFix, gnss_callback) @@ -137,27 +163,31 @@ def main(folder='data',start_index=0): print(" Storing depth images as", depth_filetype) print(" Ctrl+C to quit") while True: - if len(camera_images) > 0: - cv2.imshow("result",bridge.imgmsg_to_cv2(camera_images[0])) + if camera_image: + cv2.imshow("result",bridge.imgmsg_to_cv2(camera_image)) time.sleep(.5) - lidar_files = [os.path.join(folder, 'ouster'), os.path.join(folder, 'livox')] - camera_files = [os.path.join(folder, 'oak'), + files = [os.path.join(folder, 'ouster'),os.path.join(folder, 'oak'), os.path.join(folder, 'fl'), os.path.join(folder, 'fr'), - os.path.join(folder, 'rl'), os.path.join(folder, 'rr')] - depth_files = [os.path.join(folder, 'depth')] - gnss_files = [os.path.join(folder, 'septentrio')] - save_scan(lidar_files, camera_files, depth_files, gnss_files, index) - clear_scan() + os.path.join(folder, 'rl'), os.path.join(folder, 'rr'), + os.path.join(folder, 'depth'), os.path.join(folder, 'septentrio')] + # lidar_files = [os.path.join(folder, 'ouster')] + # camera_files = [os.path.join(folder, 'oak'), + # os.path.join(folder, 'fl'), os.path.join(folder, 'fr'), + # os.path.join(folder, 'rl'), os.path.join(folder, 'rr')] + # depth_files = [os.path.join(folder, 'depth')] + # gnss_files = [os.path.join(folder, 'septentrio')] + save_scan(*files, index) + # clear_scan() index += 1 -class StateTracker(Component): - def rate(self): - return 4.0 # Hz - def state_inputs(self): - return ['vehicle'] - def update(self, vehicle : VehicleState): - global frame_position - frame_position = np.array(vehicle.pose.frame, vehicle.pose.t, vehicle.pose.x, vehicle.pose.y) +# class StateTracker(Component): +# def rate(self): +# return 4.0 # Hz +# def state_inputs(self): +# return ['vehicle'] +# def update(self, vehicle : VehicleState): +# global frame_position +# frame_position = np.array(vehicle.pose.frame, vehicle.pose.t, vehicle.pose.x, vehicle.pose.y) if __name__ == '__main__': import sys From 10a5b928990c5b4106f4252b3df702ce9ff688df Mon Sep 17 00:00:00 2001 From: michalj1 Date: Wed, 26 Mar 2025 13:30:19 -0500 Subject: [PATCH 189/232] Versions working on GEM --- GEMstack/offboard/calibration/camera_info.py | 16 +- .../calibration/capture_ouster_oak.py | 174 ++++++++++-------- 2 files changed, 110 insertions(+), 80 deletions(-) diff --git a/GEMstack/offboard/calibration/camera_info.py b/GEMstack/offboard/calibration/camera_info.py index a1fa4429b..339f5f9be 100644 --- a/GEMstack/offboard/calibration/camera_info.py +++ b/GEMstack/offboard/calibration/camera_info.py @@ -56,28 +56,28 @@ def get_intrinsics(folder): model = image_geometry.PinholeCameraModel() model.fromCameraInfo(oak_info) with open(os.path.join(folder, "oak.txt"), "w") as f: - f.write(model.intrinsicMatrix()) + f.write(str(model.intrinsicMatrix())) model.fromCameraInfo(stereo_info) with open(os.path.join(folder, "stereo.txt"), "w") as f: - f.write(model.intrinsicMatrix()) + f.write(str(model.intrinsicMatrix())) model.fromCameraInfo(right_info) with open(os.path.join(folder, "right.txt"), "w") as f: - f.write(model.intrinsicMatrix()) + f.write(str(model.intrinsicMatrix())) model.fromCameraInfo(left_info) with open(os.path.join(folder, "left.txt"), "w") as f: - f.write(model.intrinsicMatrix()) + f.write(str(model.intrinsicMatrix())) model.fromCameraInfo(fl_info) with open(os.path.join(folder, "fl.txt"), "w") as f: - f.write(model.intrinsicMatrix()) + f.write(str(model.intrinsicMatrix())) model.fromCameraInfo(fr_info) with open(os.path.join(folder, "fr.txt"), "w") as f: - f.write(model.intrinsicMatrix()) + f.write(str(model.intrinsicMatrix())) model.fromCameraInfo(rl_info) with open(os.path.join(folder, "rl.txt"), "w") as f: - f.write(model.intrinsicMatrix()) + f.write(str(model.intrinsicMatrix())) model.fromCameraInfo(rr_info) with open(os.path.join(folder, "rr.txt"), "w") as f: - f.write(model.intrinsicMatrix()) + f.write(str(model.intrinsicMatrix())) def main(folder='data'): rospy.init_node("capture_cam_info",disable_signals=True) diff --git a/GEMstack/offboard/calibration/capture_ouster_oak.py b/GEMstack/offboard/calibration/capture_ouster_oak.py index 78c34e449..baee8985b 100644 --- a/GEMstack/offboard/calibration/capture_ouster_oak.py +++ b/GEMstack/offboard/calibration/capture_ouster_oak.py @@ -5,8 +5,8 @@ import ctypes import struct -from ...state import VehicleState, ObjectPose -from ...onboard import Component +# from ...state import VehicleState, ObjectPose +# from ...onboard import Component # OpenCV and cv2 bridge import cv2 @@ -16,10 +16,14 @@ import time # TODO: change these arrays to use dictionaries, format eg. {filename: data} -lidar_points = [] -camera_images = [] -depth_images = [] -gnss_locations = [] +lidar_points = None +camera_image = None +fl_image = None +fr_image = None +rl_image = None +rr_image = None +depth_images = None +gnss_locations = None frame_position = None lidar_filetype = ".npz" camera_filetype = ".png" @@ -29,19 +33,35 @@ def lidar_callback(lidar : PointCloud2): global lidar_points - lidar_points.append(lidar) + lidar_points = (lidar) def camera_callback(img : Image): - global camera_images - camera_images.append(img) + global camera_image + camera_image = (img) + +def fl_camera_callback(img : Image): + global fl_image + fl_image = (img) + +def fr_camera_callback(img : Image): + global fr_image + fr_image = (img) + +def rl_camera_callback(img : Image): + global rl_image + rl_image = (img) + +def rr_camera_callback(img : Image): + global rr_image + rr_image = (img) def depth_callback(img : Image): global depth_images - depth_images.append(img) + depth_images = (img) def gnss_callback(sat_fix : NavSatFix): global gnss_locations - gnss_locations.append(sat_fix) + gnss_locations = (sat_fix) def pc2_to_numpy(pc2_msg, want_rgb = False): gen = pc2.read_points(pc2_msg, skip_nans=True) @@ -67,21 +87,22 @@ def pc2_to_numpy(pc2_msg, want_rgb = False): else: return np.array(list(gen),dtype=np.float32)[:,:3] -def clear_scan(): - global lidar_points - lidar_points = [] - global camera_images - camera_images = [] - global depth_images - depth_images = [] - global gnss_locations - gnss_locations = [] +# def clear_scan(): +# global lidar_points +# lidar_points = [] +# global camera_image +# camera_image = [] +# global depth_images +# depth_images = [] +# global gnss_locations +# gnss_locations = [] # TODO: when data is stored in dictionaries, change to only save files which exist and change error checking -def save_scan(lidar_filenames, camera_filenames, depth_filenames, gnss_filenames, index): - if len(lidar_filenames) != len(lidar_points) or len(camera_filenames) != len(camera_images) or len(depth_filenames) != len(depth_images): - print("Missing data, scan", index, "cannot be saved") - return +def save_scan(lidar_fn, camera_fn, fl_fn, fr_fn, rl_fn, rr_fn, depth_fn, gnss_fn, index): + # if len(lidar_filenames) != len(lidar_points) or len(camera_filenames) != len(camera_image) or len(depth_filenames) != len(depth_images): + # print("Missing data, scan", index, "cannot be saved") + # print(len(lidar_filenames), len(lidar_points), len(camera_filenames), len(camera_image), len(depth_filenames), len(depth_images)) + # return print("Saving scan", index) if frame_position != None: @@ -89,44 +110,49 @@ def save_scan(lidar_filenames, camera_filenames, depth_filenames, gnss_filenames else: print("No state found") - for i in range(len(lidar_points)): - current_lidar = lidar_points[i] - lidar_fn = lidar_filenames[i] + str(index) + lidar_filetype - pc = pc2_to_numpy(current_lidar,want_rgb=False) # convert lidar feed to numpy - np.savez(lidar_fn,pc) - - for i in range(len(camera_images)): - current_camera = camera_images[i] - camera_fn = camera_filenames[i] + str(index) + camera_filetype - cv2.imwrite(camera_fn,bridge.imgmsg_to_cv2(current_camera)) - - for i in range(len(depth_images)): - dimage = bridge.imgmsg_to_cv2(depth_images[i]) - depth_fn = depth_filenames[i] + str(index) + depth_filetype - dimage_non_nan = dimage[np.isfinite(dimage)] - # print("Depth range",np.min(dimage_non_nan),np.max(dimage_non_nan)) - dimage = np.nan_to_num(dimage,nan=0,posinf=0,neginf=0) - dimage = (dimage/4000*0xffff) - # print("Depth pixel range",np.min(dimage),np.max(dimage)) - dimage = dimage.astype(np.uint16) - cv2.imwrite(depth_fn,dimage) + # for i in range(len(lidar_points)): + # current_lidar = lidar_points[i] + # lidar_fn = lidar_filename + str(index) + lidar_filetype + pc = pc2_to_numpy(lidar_points,want_rgb=False) # convert lidar feed to numpy + np.savez(lidar_fn + str(index) + lidar_filetype,pc) + + # for i in range(len(camera_image)): + # current_camera = camera_image[i] + # camera_fn = camera_filenames[i] + str(index) + camera_filetype + cv2.imwrite(camera_fn + str(index) + camera_filetype,bridge.imgmsg_to_cv2(camera_image)) + cv2.imwrite(fl_fn + str(index) + camera_filetype,bridge.imgmsg_to_cv2(fl_image)) + cv2.imwrite(fr_fn + str(index) + camera_filetype,bridge.imgmsg_to_cv2(fr_image)) + cv2.imwrite(rl_fn + str(index) + camera_filetype,bridge.imgmsg_to_cv2(rl_image)) + cv2.imwrite(rr_fn + str(index) + camera_filetype,bridge.imgmsg_to_cv2(rr_image)) + + # for i in range(len(depth_images)): + dimage = bridge.imgmsg_to_cv2(depth_images) + # depth_fn = depth_filenames[i] + str(index) + depth_filetype + dimage_non_nan = dimage[np.isfinite(dimage)] + # print("Depth range",np.min(dimage_non_nan),np.max(dimage_non_nan)) + dimage = np.nan_to_num(dimage,nan=0,posinf=0,neginf=0) + dimage = (dimage/4000*0xffff) + # print("Depth pixel range",np.min(dimage),np.max(dimage)) + dimage = dimage.astype(np.uint16) + cv2.imwrite(depth_fn + str(index) + depth_filetype,dimage) - for i in range(len(gnss_locations)): - sat_fix = gnss_locations[i] - gnss_fn = gnss_filenames + str(index) + gnss_filetype - coordinates = np.array(sat_fix.latitude, sat_fix.longitude) - np.save(gnss_fn, coordinates) + # for i in range(len(gnss_locations)): + # sat_fix = gnss_locations[i] + # gnss_fn = gnss_filenames + str(index) + gnss_filetype + if gnss_locations: + coordinates = np.array([gnss_locations.latitude, gnss_locations.longitude]) + np.save(gnss_fn + str(index) + gnss_filetype, coordinates) def main(folder='data',start_index=0): # Initialize node and establish subscribers rospy.init_node("capture_ouster_oak",disable_signals=True) ouster_sub = rospy.Subscriber("/ouster/points", PointCloud2, lidar_callback) - livox_sub = rospy.Subscriber("/livox/lidar", PointCloud2, lidar_callback) + # livox_sub = rospy.Subscriber("/livox/lidar", PointCloud2, lidar_callback) oak_sub = rospy.Subscriber("/oak/rgb/image_raw", Image, camera_callback) - cam_fl_sub = rospy.Subscriber("/camera_fl/arena_camera_node/image_raw", Image, camera_callback) - cam_fr_sub = rospy.Subscriber("/camera_fr/arena_camera_node/image_raw", Image, camera_callback) - cam_rl_sub = rospy.Subscriber("/camera_rl/arena_camera_node/image_raw", Image, camera_callback) - cam_rr_sub = rospy.Subscriber("/camera_rr/arena_camera_node/image_raw", Image, camera_callback) + cam_fl_sub = rospy.Subscriber("/camera_fl/arena_camera_node/image_raw", Image, fl_camera_callback) + cam_fr_sub = rospy.Subscriber("/camera_fr/arena_camera_node/image_raw", Image, fr_camera_callback) + cam_rl_sub = rospy.Subscriber("/camera_rl/arena_camera_node/image_raw", Image, rl_camera_callback) + cam_rr_sub = rospy.Subscriber("/camera_rr/arena_camera_node/image_raw", Image, rr_camera_callback) depth_sub = rospy.Subscriber("/oak/stereo/image_raw", Image, depth_callback) gnss_sub = rospy.Subscriber("/septentrio_gnss/navsatfix", NavSatFix, gnss_callback) @@ -137,27 +163,31 @@ def main(folder='data',start_index=0): print(" Storing depth images as", depth_filetype) print(" Ctrl+C to quit") while True: - if len(camera_images) > 0: - cv2.imshow("result",bridge.imgmsg_to_cv2(camera_images[0])) + if camera_image: + cv2.imshow("result",bridge.imgmsg_to_cv2(camera_image)) time.sleep(.5) - lidar_files = [os.path.join(folder, 'ouster'), os.path.join(folder, 'livox')] - camera_files = [os.path.join(folder, 'oak'), + files = [os.path.join(folder, 'ouster'),os.path.join(folder, 'oak'), os.path.join(folder, 'fl'), os.path.join(folder, 'fr'), - os.path.join(folder, 'rl'), os.path.join(folder, 'rr')] - depth_files = [os.path.join(folder, 'depth')] - gnss_files = [os.path.join(folder, 'septentrio')] - save_scan(lidar_files, camera_files, depth_files, gnss_files, index) - clear_scan() + os.path.join(folder, 'rl'), os.path.join(folder, 'rr'), + os.path.join(folder, 'depth'), os.path.join(folder, 'septentrio')] + # lidar_files = [os.path.join(folder, 'ouster')] + # camera_files = [os.path.join(folder, 'oak'), + # os.path.join(folder, 'fl'), os.path.join(folder, 'fr'), + # os.path.join(folder, 'rl'), os.path.join(folder, 'rr')] + # depth_files = [os.path.join(folder, 'depth')] + # gnss_files = [os.path.join(folder, 'septentrio')] + save_scan(*files, index) + # clear_scan() index += 1 -class StateTracker(Component): - def rate(self): - return 4.0 # Hz - def state_inputs(self): - return ['vehicle'] - def update(self, vehicle : VehicleState): - global frame_position - frame_position = np.array(vehicle.pose.frame, vehicle.pose.t, vehicle.pose.x, vehicle.pose.y) +# class StateTracker(Component): +# def rate(self): +# return 4.0 # Hz +# def state_inputs(self): +# return ['vehicle'] +# def update(self, vehicle : VehicleState): +# global frame_position +# frame_position = np.array(vehicle.pose.frame, vehicle.pose.t, vehicle.pose.x, vehicle.pose.y) if __name__ == '__main__': import sys From b4a68ef07541fc84fc86396245bec85b64221b16 Mon Sep 17 00:00:00 2001 From: rjsun-KA <92330153+rjsun06@users.noreply.github.com> Date: Wed, 2 Apr 2025 22:24:48 +0000 Subject: [PATCH 190/232] ok --- GEMstack/knowledge/calibration/gem_e4_oak_in.yaml | 2 +- GEMstack/offboard/calibration/play_with_pycolmap.py | 2 -- GEMstack/offboard/calibration/tools/save_cali.py | 5 +++-- 3 files changed, 4 insertions(+), 5 deletions(-) diff --git a/GEMstack/knowledge/calibration/gem_e4_oak_in.yaml b/GEMstack/knowledge/calibration/gem_e4_oak_in.yaml index bf30a36b2..df84385be 100644 --- a/GEMstack/knowledge/calibration/gem_e4_oak_in.yaml +++ b/GEMstack/knowledge/calibration/gem_e4_oak_in.yaml @@ -1,2 +1,2 @@ center: [573.37109375, 363.700927734375] -focal: [684.8333129882812, 684.6096801757812, 1.0] +focal: [684.8333129882812, 684.6096801757812] diff --git a/GEMstack/offboard/calibration/play_with_pycolmap.py b/GEMstack/offboard/calibration/play_with_pycolmap.py index 03a419b7d..8406490fd 100644 --- a/GEMstack/offboard/calibration/play_with_pycolmap.py +++ b/GEMstack/offboard/calibration/play_with_pycolmap.py @@ -44,7 +44,6 @@ def pc_relative(pc0,pc1): sift_options=extract_options, # device=pycolmap._core.Device.cuda ) - # 2. Feature matching. match_sequential tries matching only on pairs close in filename ordering match_options = pycolmap.SequentialMatchingOptions() match_options.overlap = 3 # how many subsequent images should be tried matching. @@ -138,7 +137,6 @@ def load_scene(path): sc = sc[~np.all(sc == 0, axis=1)] # remove (0,0,0)'s return sc -#%% #%% # get lidar pointcloud sc = load_scene(root + f"/data/calib1/pc/ouster1.npz") diff --git a/GEMstack/offboard/calibration/tools/save_cali.py b/GEMstack/offboard/calibration/tools/save_cali.py index 29e341459..fa147aff2 100644 --- a/GEMstack/offboard/calibration/tools/save_cali.py +++ b/GEMstack/offboard/calibration/tools/save_cali.py @@ -44,7 +44,8 @@ def load_in(path,mode='matrix'): with open(path) as stream: y = yaml.safe_load(stream) if mode == 'matrix': - ret = np.diag(y['focal']) + ret = np.zeros((3,3)) + ret[0,0],ret[1,1] = y['focal'] ret[0:2,2] = y['center'] return ret elif mode == 'tuple': @@ -52,7 +53,7 @@ def load_in(path,mode='matrix'): def save_in(path,focal=None,center=None,matrix=None): if matrix is not None: - focal = matrix.diagonal() + focal = matrix.diagonal()[0,-1] center = matrix[0:2,2] save_in(path,focal,center) return From 880f08ef7275c92f038ac2d4803f1846f749f7ee Mon Sep 17 00:00:00 2001 From: rjsun-KA <92330153+rjsun06@users.noreply.github.com> Date: Wed, 2 Apr 2025 22:24:48 +0000 Subject: [PATCH 191/232] ok --- GEMstack/knowledge/calibration/gem_e4_oak_in.yaml | 2 +- GEMstack/offboard/calibration/play_with_pycolmap.py | 2 -- GEMstack/offboard/calibration/tools/save_cali.py | 5 +++-- 3 files changed, 4 insertions(+), 5 deletions(-) diff --git a/GEMstack/knowledge/calibration/gem_e4_oak_in.yaml b/GEMstack/knowledge/calibration/gem_e4_oak_in.yaml index bf30a36b2..df84385be 100644 --- a/GEMstack/knowledge/calibration/gem_e4_oak_in.yaml +++ b/GEMstack/knowledge/calibration/gem_e4_oak_in.yaml @@ -1,2 +1,2 @@ center: [573.37109375, 363.700927734375] -focal: [684.8333129882812, 684.6096801757812, 1.0] +focal: [684.8333129882812, 684.6096801757812] diff --git a/GEMstack/offboard/calibration/play_with_pycolmap.py b/GEMstack/offboard/calibration/play_with_pycolmap.py index 03a419b7d..8406490fd 100644 --- a/GEMstack/offboard/calibration/play_with_pycolmap.py +++ b/GEMstack/offboard/calibration/play_with_pycolmap.py @@ -44,7 +44,6 @@ def pc_relative(pc0,pc1): sift_options=extract_options, # device=pycolmap._core.Device.cuda ) - # 2. Feature matching. match_sequential tries matching only on pairs close in filename ordering match_options = pycolmap.SequentialMatchingOptions() match_options.overlap = 3 # how many subsequent images should be tried matching. @@ -138,7 +137,6 @@ def load_scene(path): sc = sc[~np.all(sc == 0, axis=1)] # remove (0,0,0)'s return sc -#%% #%% # get lidar pointcloud sc = load_scene(root + f"/data/calib1/pc/ouster1.npz") diff --git a/GEMstack/offboard/calibration/tools/save_cali.py b/GEMstack/offboard/calibration/tools/save_cali.py index 29e341459..fa147aff2 100644 --- a/GEMstack/offboard/calibration/tools/save_cali.py +++ b/GEMstack/offboard/calibration/tools/save_cali.py @@ -44,7 +44,8 @@ def load_in(path,mode='matrix'): with open(path) as stream: y = yaml.safe_load(stream) if mode == 'matrix': - ret = np.diag(y['focal']) + ret = np.zeros((3,3)) + ret[0,0],ret[1,1] = y['focal'] ret[0:2,2] = y['center'] return ret elif mode == 'tuple': @@ -52,7 +53,7 @@ def load_in(path,mode='matrix'): def save_in(path,focal=None,center=None,matrix=None): if matrix is not None: - focal = matrix.diagonal() + focal = matrix.diagonal()[0,-1] center = matrix[0:2,2] save_in(path,focal,center) return From d6b2c02b66d305f8f6f008ec6a3607a1ea178cb1 Mon Sep 17 00:00:00 2001 From: rjsun-KA <92330153+rjsun06@users.noreply.github.com> Date: Thu, 3 Apr 2025 00:16:49 +0000 Subject: [PATCH 192/232] ok --- .../calibration_by_segmentation/.gitignore | 3 + .../calibration_by_segmentation/CalibAnything | 1 + .../calibration_by_segmentation/calib.bash | 12 ++++ .../data/fl/calib.json | 58 +++++++++++++++++++ .../data/fl/images/.gitignore | 3 + .../data/fl/masks/.gitignore | 3 + .../data/fl/pc/.gitignore | 3 + .../calibration_by_segmentation/npz_to_pcd.py | 58 +++++++++++++++++++ .../segment-anything | 1 + GEMstack/offboard/calibration/run_img2pc.bash | 4 +- 10 files changed, 144 insertions(+), 2 deletions(-) create mode 100644 GEMstack/offboard/calibration/calibration_by_segmentation/.gitignore create mode 160000 GEMstack/offboard/calibration/calibration_by_segmentation/CalibAnything create mode 100644 GEMstack/offboard/calibration/calibration_by_segmentation/calib.bash create mode 100644 GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/calib.json create mode 100644 GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/images/.gitignore create mode 100644 GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/masks/.gitignore create mode 100644 GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/pc/.gitignore create mode 100644 GEMstack/offboard/calibration/calibration_by_segmentation/npz_to_pcd.py create mode 160000 GEMstack/offboard/calibration/calibration_by_segmentation/segment-anything diff --git a/GEMstack/offboard/calibration/calibration_by_segmentation/.gitignore b/GEMstack/offboard/calibration/calibration_by_segmentation/.gitignore new file mode 100644 index 000000000..591eb2709 --- /dev/null +++ b/GEMstack/offboard/calibration/calibration_by_segmentation/.gitignore @@ -0,0 +1,3 @@ +sam_vit_h.pth + +!.gitignore diff --git a/GEMstack/offboard/calibration/calibration_by_segmentation/CalibAnything b/GEMstack/offboard/calibration/calibration_by_segmentation/CalibAnything new file mode 160000 index 000000000..4122ea18a --- /dev/null +++ b/GEMstack/offboard/calibration/calibration_by_segmentation/CalibAnything @@ -0,0 +1 @@ +Subproject commit 4122ea18abe1831b99abbadce91362571a9b5158 diff --git a/GEMstack/offboard/calibration/calibration_by_segmentation/calib.bash b/GEMstack/offboard/calibration/calibration_by_segmentation/calib.bash new file mode 100644 index 000000000..73d785d6b --- /dev/null +++ b/GEMstack/offboard/calibration/calibration_by_segmentation/calib.bash @@ -0,0 +1,12 @@ +data=$1 + +wget -c -O sam_vit_h.pth https://dl.fbaipublicfiles.com/segment_anything/sam_vit_h_4b8939.pth + +echo 'running segmentation...' +python3 segment-anything scripts/amg.py --checkpoint sam_vit_h.pth --model-type vit_h --input $data/images --output $data/masks/ --stability-score-thresh 0.9 --box-nms-thresh 0.5 --stability-score-offset 0.9 + +echo 'reprocess segmentation...' +python3 CalibAnything/processed_mask.py -i $data/masks -o $data/processed_masks/ + +echo 'running calibration...' +CalibAnything/bin/run_lidar2camera $data/calib.json \ No newline at end of file diff --git a/GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/calib.json b/GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/calib.json new file mode 100644 index 000000000..22f6e1bbf --- /dev/null +++ b/GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/calib.json @@ -0,0 +1,58 @@ +{ + "cam_K": { + "rows": 3, + "cols": 3, + "data": [ + [1180.753804, 0.000000, 934.859447], + [0.000000, 1177.034929, 607.266974], + [0.000000, 0.000000 , 1.000000 ] + ] + }, + "cam_dist": { + "cols": 5, + "data": [-0.244851, 0.082024, 0.000429, -0.001245, 0.000000] + }, + "T_lidar_to_cam":{ + "rows": 4, + "cols": 4, + "data": [ + [ 0.72 , -0.694, 0.014, 0.12], + [-0.166, -0.191, -0.967, 0.09], + [ 0.673, 0.694, -0.253, -1.17], + [ 0.0 , 0.0 , 0.0 , 1.0 ] + ] + }, + "img_folder": "images", + "mask_folder": "processed_masks", + "pc_folder": "pc", + "img_format": ".png", + "pc_format": ".pcd", + "file_name": [ + "000000", + "000001", + "000002", + "000003", + "000004" + ], + "params": { + "min_plane_point_num": 2000, + "cluster_tolerance": 0.25, + "search_num": 4000, + "search_range": { + "rot_deg": 5, + "trans_m": 0.5 + }, + "point_range":{ + "top": 0.4, + "bottom": 1.0 + }, + "down_sample":{ + "is_valid": true, + "voxel_m": 0.05 + }, + "thread": { + "is_multi_thread": true, + "num_thread": 4 + } + } +} diff --git a/GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/images/.gitignore b/GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/images/.gitignore new file mode 100644 index 000000000..cec9082b6 --- /dev/null +++ b/GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/images/.gitignore @@ -0,0 +1,3 @@ +* + +!.gitignore diff --git a/GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/masks/.gitignore b/GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/masks/.gitignore new file mode 100644 index 000000000..cec9082b6 --- /dev/null +++ b/GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/masks/.gitignore @@ -0,0 +1,3 @@ +* + +!.gitignore diff --git a/GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/pc/.gitignore b/GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/pc/.gitignore new file mode 100644 index 000000000..cec9082b6 --- /dev/null +++ b/GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/pc/.gitignore @@ -0,0 +1,3 @@ +* + +!.gitignore diff --git a/GEMstack/offboard/calibration/calibration_by_segmentation/npz_to_pcd.py b/GEMstack/offboard/calibration/calibration_by_segmentation/npz_to_pcd.py new file mode 100644 index 000000000..e4a7bcbbd --- /dev/null +++ b/GEMstack/offboard/calibration/calibration_by_segmentation/npz_to_pcd.py @@ -0,0 +1,58 @@ +#%% +#%% +import numpy as np +import open3d as o3d +import os +import argparse + +def npz_to_pcd(input_dir, output_dir, data_key='arr_0'): + # Create output directory if it doesn't exist + os.makedirs(output_dir, exist_ok=True) + + # Iterate over all .npz files in the input directory + for npz_file in os.listdir(input_dir): + if npz_file.endswith(".npz"): + npz_path = os.path.join(input_dir, npz_file) + output_pcd_path = os.path.join(output_dir, npz_file.replace('.npz', '.pcd')) + + try: + # Load data from .npz file + data = np.load(npz_path) + if data_key not in data: + print(f"Skipping {npz_file}: Key '{data_key}' not found.") + continue + + point_cloud_np = data[data_key] + + # Validate shape (Nx3 for XYZ, Nx6 for XYZRGB, etc.) + if point_cloud_np.ndim != 2 or point_cloud_np.shape[1] < 3: + print(f"Skipping {npz_file}: Invalid shape {point_cloud_np.shape}.") + continue + + # Create Open3D point cloud object + pcd = o3d.geometry.PointCloud() + + # Assign points (required: Nx3 array) + pcd.points = o3d.utility.Vector3dVector(point_cloud_np[:, :3]) + + # Optionally assign colors (if available, e.g., Nx6 array with RGB) + if point_cloud_np.shape[1] >= 6: + # RGB values (assuming they are stored as 0-255 integers) + colors = point_cloud_np[:, 3:6] / 255.0 # Normalize to [0, 1] for Open3D + pcd.colors = o3d.utility.Vector3dVector(colors) + + # Save to .pcd (supports ASCII or binary) + o3d.io.write_point_cloud(output_pcd_path, pcd, write_ascii=True) + print(f"Converted: {npz_file} -> {output_pcd_path}") + + except Exception as e: + print(f"Failed to convert {npz_file}: {str(e)}") + +if __name__ == "__main__": + parser = argparse.ArgumentParser(description="Convert .npz to .pcd using Open3D") + parser.add_argument("--input_dir", type=str, required=True, help="Input directory with .npz files") + parser.add_argument("--output_dir", type=str, required=True, help="Output directory for .pcd files") + parser.add_argument("--data_key", type=str, default='points', help="Key for point cloud data in .npz files") + args = parser.parse_args() + + npz_to_pcd(args.input_dir, args.output_dir, args.data_key) \ No newline at end of file diff --git a/GEMstack/offboard/calibration/calibration_by_segmentation/segment-anything b/GEMstack/offboard/calibration/calibration_by_segmentation/segment-anything new file mode 160000 index 000000000..dca509fe7 --- /dev/null +++ b/GEMstack/offboard/calibration/calibration_by_segmentation/segment-anything @@ -0,0 +1 @@ +Subproject commit dca509fe793f601edb92606367a655c15ac00fdf diff --git a/GEMstack/offboard/calibration/run_img2pc.bash b/GEMstack/offboard/calibration/run_img2pc.bash index 70db81967..d0a1ed520 100644 --- a/GEMstack/offboard/calibration/run_img2pc.bash +++ b/GEMstack/offboard/calibration/run_img2pc.bash @@ -1,8 +1,8 @@ root='/mnt/GEMstack' python3 $root/GEMstack/offboard/calibration/img2pc.py \ - --img_path $root/data/color32.png \ - --pc_path $root/data/lidar32.npz \ + --img_path $root/data/calib1/img/fl/fl11.png \ + --pc_path $root/data/calib1/pc/ouster11.npz \ --pc_transform_path $root/GEMstack/knowledge/calibration/gem_e4_ouster.yaml \ --img_intrinsics_path $root/GEMstack/knowledge/calibration/gem_e4_oak_in.yaml \ --n_features 4 \ From 69675a9160155e75cd92eb108815e7aae4dfdff6 Mon Sep 17 00:00:00 2001 From: rjsun-KA <92330153+rjsun06@users.noreply.github.com> Date: Thu, 3 Apr 2025 00:16:49 +0000 Subject: [PATCH 193/232] ok --- .../calibration_by_segmentation/.gitignore | 3 + .../calibration_by_segmentation/CalibAnything | 1 + .../calibration_by_segmentation/calib.bash | 12 ++++ .../data/fl/calib.json | 58 +++++++++++++++++++ .../data/fl/images/.gitignore | 3 + .../data/fl/masks/.gitignore | 3 + .../data/fl/pc/.gitignore | 3 + .../calibration_by_segmentation/npz_to_pcd.py | 58 +++++++++++++++++++ .../segment-anything | 1 + GEMstack/offboard/calibration/run_img2pc.bash | 4 +- 10 files changed, 144 insertions(+), 2 deletions(-) create mode 100644 GEMstack/offboard/calibration/calibration_by_segmentation/.gitignore create mode 160000 GEMstack/offboard/calibration/calibration_by_segmentation/CalibAnything create mode 100644 GEMstack/offboard/calibration/calibration_by_segmentation/calib.bash create mode 100644 GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/calib.json create mode 100644 GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/images/.gitignore create mode 100644 GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/masks/.gitignore create mode 100644 GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/pc/.gitignore create mode 100644 GEMstack/offboard/calibration/calibration_by_segmentation/npz_to_pcd.py create mode 160000 GEMstack/offboard/calibration/calibration_by_segmentation/segment-anything diff --git a/GEMstack/offboard/calibration/calibration_by_segmentation/.gitignore b/GEMstack/offboard/calibration/calibration_by_segmentation/.gitignore new file mode 100644 index 000000000..591eb2709 --- /dev/null +++ b/GEMstack/offboard/calibration/calibration_by_segmentation/.gitignore @@ -0,0 +1,3 @@ +sam_vit_h.pth + +!.gitignore diff --git a/GEMstack/offboard/calibration/calibration_by_segmentation/CalibAnything b/GEMstack/offboard/calibration/calibration_by_segmentation/CalibAnything new file mode 160000 index 000000000..4122ea18a --- /dev/null +++ b/GEMstack/offboard/calibration/calibration_by_segmentation/CalibAnything @@ -0,0 +1 @@ +Subproject commit 4122ea18abe1831b99abbadce91362571a9b5158 diff --git a/GEMstack/offboard/calibration/calibration_by_segmentation/calib.bash b/GEMstack/offboard/calibration/calibration_by_segmentation/calib.bash new file mode 100644 index 000000000..73d785d6b --- /dev/null +++ b/GEMstack/offboard/calibration/calibration_by_segmentation/calib.bash @@ -0,0 +1,12 @@ +data=$1 + +wget -c -O sam_vit_h.pth https://dl.fbaipublicfiles.com/segment_anything/sam_vit_h_4b8939.pth + +echo 'running segmentation...' +python3 segment-anything scripts/amg.py --checkpoint sam_vit_h.pth --model-type vit_h --input $data/images --output $data/masks/ --stability-score-thresh 0.9 --box-nms-thresh 0.5 --stability-score-offset 0.9 + +echo 'reprocess segmentation...' +python3 CalibAnything/processed_mask.py -i $data/masks -o $data/processed_masks/ + +echo 'running calibration...' +CalibAnything/bin/run_lidar2camera $data/calib.json \ No newline at end of file diff --git a/GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/calib.json b/GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/calib.json new file mode 100644 index 000000000..22f6e1bbf --- /dev/null +++ b/GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/calib.json @@ -0,0 +1,58 @@ +{ + "cam_K": { + "rows": 3, + "cols": 3, + "data": [ + [1180.753804, 0.000000, 934.859447], + [0.000000, 1177.034929, 607.266974], + [0.000000, 0.000000 , 1.000000 ] + ] + }, + "cam_dist": { + "cols": 5, + "data": [-0.244851, 0.082024, 0.000429, -0.001245, 0.000000] + }, + "T_lidar_to_cam":{ + "rows": 4, + "cols": 4, + "data": [ + [ 0.72 , -0.694, 0.014, 0.12], + [-0.166, -0.191, -0.967, 0.09], + [ 0.673, 0.694, -0.253, -1.17], + [ 0.0 , 0.0 , 0.0 , 1.0 ] + ] + }, + "img_folder": "images", + "mask_folder": "processed_masks", + "pc_folder": "pc", + "img_format": ".png", + "pc_format": ".pcd", + "file_name": [ + "000000", + "000001", + "000002", + "000003", + "000004" + ], + "params": { + "min_plane_point_num": 2000, + "cluster_tolerance": 0.25, + "search_num": 4000, + "search_range": { + "rot_deg": 5, + "trans_m": 0.5 + }, + "point_range":{ + "top": 0.4, + "bottom": 1.0 + }, + "down_sample":{ + "is_valid": true, + "voxel_m": 0.05 + }, + "thread": { + "is_multi_thread": true, + "num_thread": 4 + } + } +} diff --git a/GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/images/.gitignore b/GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/images/.gitignore new file mode 100644 index 000000000..cec9082b6 --- /dev/null +++ b/GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/images/.gitignore @@ -0,0 +1,3 @@ +* + +!.gitignore diff --git a/GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/masks/.gitignore b/GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/masks/.gitignore new file mode 100644 index 000000000..cec9082b6 --- /dev/null +++ b/GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/masks/.gitignore @@ -0,0 +1,3 @@ +* + +!.gitignore diff --git a/GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/pc/.gitignore b/GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/pc/.gitignore new file mode 100644 index 000000000..cec9082b6 --- /dev/null +++ b/GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/pc/.gitignore @@ -0,0 +1,3 @@ +* + +!.gitignore diff --git a/GEMstack/offboard/calibration/calibration_by_segmentation/npz_to_pcd.py b/GEMstack/offboard/calibration/calibration_by_segmentation/npz_to_pcd.py new file mode 100644 index 000000000..e4a7bcbbd --- /dev/null +++ b/GEMstack/offboard/calibration/calibration_by_segmentation/npz_to_pcd.py @@ -0,0 +1,58 @@ +#%% +#%% +import numpy as np +import open3d as o3d +import os +import argparse + +def npz_to_pcd(input_dir, output_dir, data_key='arr_0'): + # Create output directory if it doesn't exist + os.makedirs(output_dir, exist_ok=True) + + # Iterate over all .npz files in the input directory + for npz_file in os.listdir(input_dir): + if npz_file.endswith(".npz"): + npz_path = os.path.join(input_dir, npz_file) + output_pcd_path = os.path.join(output_dir, npz_file.replace('.npz', '.pcd')) + + try: + # Load data from .npz file + data = np.load(npz_path) + if data_key not in data: + print(f"Skipping {npz_file}: Key '{data_key}' not found.") + continue + + point_cloud_np = data[data_key] + + # Validate shape (Nx3 for XYZ, Nx6 for XYZRGB, etc.) + if point_cloud_np.ndim != 2 or point_cloud_np.shape[1] < 3: + print(f"Skipping {npz_file}: Invalid shape {point_cloud_np.shape}.") + continue + + # Create Open3D point cloud object + pcd = o3d.geometry.PointCloud() + + # Assign points (required: Nx3 array) + pcd.points = o3d.utility.Vector3dVector(point_cloud_np[:, :3]) + + # Optionally assign colors (if available, e.g., Nx6 array with RGB) + if point_cloud_np.shape[1] >= 6: + # RGB values (assuming they are stored as 0-255 integers) + colors = point_cloud_np[:, 3:6] / 255.0 # Normalize to [0, 1] for Open3D + pcd.colors = o3d.utility.Vector3dVector(colors) + + # Save to .pcd (supports ASCII or binary) + o3d.io.write_point_cloud(output_pcd_path, pcd, write_ascii=True) + print(f"Converted: {npz_file} -> {output_pcd_path}") + + except Exception as e: + print(f"Failed to convert {npz_file}: {str(e)}") + +if __name__ == "__main__": + parser = argparse.ArgumentParser(description="Convert .npz to .pcd using Open3D") + parser.add_argument("--input_dir", type=str, required=True, help="Input directory with .npz files") + parser.add_argument("--output_dir", type=str, required=True, help="Output directory for .pcd files") + parser.add_argument("--data_key", type=str, default='points', help="Key for point cloud data in .npz files") + args = parser.parse_args() + + npz_to_pcd(args.input_dir, args.output_dir, args.data_key) \ No newline at end of file diff --git a/GEMstack/offboard/calibration/calibration_by_segmentation/segment-anything b/GEMstack/offboard/calibration/calibration_by_segmentation/segment-anything new file mode 160000 index 000000000..dca509fe7 --- /dev/null +++ b/GEMstack/offboard/calibration/calibration_by_segmentation/segment-anything @@ -0,0 +1 @@ +Subproject commit dca509fe793f601edb92606367a655c15ac00fdf diff --git a/GEMstack/offboard/calibration/run_img2pc.bash b/GEMstack/offboard/calibration/run_img2pc.bash index 70db81967..d0a1ed520 100644 --- a/GEMstack/offboard/calibration/run_img2pc.bash +++ b/GEMstack/offboard/calibration/run_img2pc.bash @@ -1,8 +1,8 @@ root='/mnt/GEMstack' python3 $root/GEMstack/offboard/calibration/img2pc.py \ - --img_path $root/data/color32.png \ - --pc_path $root/data/lidar32.npz \ + --img_path $root/data/calib1/img/fl/fl11.png \ + --pc_path $root/data/calib1/pc/ouster11.npz \ --pc_transform_path $root/GEMstack/knowledge/calibration/gem_e4_ouster.yaml \ --img_intrinsics_path $root/GEMstack/knowledge/calibration/gem_e4_oak_in.yaml \ --n_features 4 \ From 5a50c759e9cd23635285f72a2a6450f3606c87c0 Mon Sep 17 00:00:00 2001 From: Michal Juscinski Date: Sun, 6 Apr 2025 21:04:16 -0700 Subject: [PATCH 194/232] Add code to manually tune calibration --- .../offboard/calibration/test_transforms.py | 207 ++++++++++++++++++ 1 file changed, 207 insertions(+) create mode 100644 GEMstack/offboard/calibration/test_transforms.py diff --git a/GEMstack/offboard/calibration/test_transforms.py b/GEMstack/offboard/calibration/test_transforms.py new file mode 100644 index 000000000..4ed0894f1 --- /dev/null +++ b/GEMstack/offboard/calibration/test_transforms.py @@ -0,0 +1,207 @@ +import numpy as np +import cv2 +import matplotlib.pyplot as plt +from scipy.spatial.transform import Rotation as R +from matplotlib.widgets import Slider + +keep_running = True + +# Load LiDAR points +lidar_data = np.load("./data/ouster32.npz") # Update filename if needed +lidar_points = lidar_data['arr_0'] # Ensure the correct key + +# Load Camera Image +image = cv2.imread("./data/fr_rect32.png") # Update filename if needed +image = cv2.cvtColor(image, cv2.COLOR_BGR2RGB) # Convert BGR to RGB + +# Transformation Matrix +T_lidar_camera = np.array( + [[-0.65266466, -0.75745371, -0.01710912, -0.54157703], + [-0.08467423, 0.09536332, -0.99183472, -0.37038288], + [ 0.75290047, -0.64588677, -0.12637708, 0.0245309 ], + [ 0. , 0. , 0. , 1. ]] +) + +# Convert LiDAR points to homogeneous coordinates +num_points = lidar_points.shape[0] +lidar_homogeneous = np.hstack((lidar_points, np.ones((num_points, 1)))) # (N, 4) + +# Transform LiDAR points to Camera Frame +lidar_points_camera = (T_lidar_camera @ lidar_homogeneous.T).T # (N, 4) + + +# intrinsic matrix +K = np.array([ + [1180.753804, 0. , 934.859447], + [ 0. , 1177.034929, 607.266974], + [ 0. , 0. , 1. ] +], dtype=np.float32) + +# Extract 3D points in camera frame +X_c = lidar_points_camera[:, 0] +Y_c = lidar_points_camera[:, 1] +Z_c = lidar_points_camera[:, 2] # Depth + +# Avoid division by zero +valid = Z_c > 0 +X_c, Y_c, Z_c = X_c[valid], Y_c[valid], Z_c[valid] + +# Project points onto image plane +u = (K[0, 0] * X_c / Z_c) + K[0, 2] +v = (K[1, 1] * Y_c / Z_c) + K[1, 2] + +# Filter points within image bounds +img_h, img_w, _ = image.shape +valid_pts = (u >= 0) & (u < img_w) & (v >= 0) & (v < img_h) +u, v = u[valid_pts], v[valid_pts] + +# Create space for sliders +plt.ion() +fig, ax = plt.subplots() +fig.subplots_adjust(bottom=0.4) +scale_ax = fig.add_axes([0.25, 0.35, 0.65, 0.03]) +x_rot_ax = fig.add_axes([0.25, 0.3, 0.65, 0.03]) +y_rot_ax = fig.add_axes([0.25, 0.25, 0.65, 0.03]) +z_rot_ax = fig.add_axes([0.25, 0.2, 0.65, 0.03]) +x_trans_ax = fig.add_axes([0.25, 0.15, 0.65, 0.03]) +y_trans_ax = fig.add_axes([0.25, 0.1, 0.65, 0.03]) +z_trans_ax = fig.add_axes([0.25, 0.05, 0.65, 0.03]) + +# Plot projected points on camera image +ax.imshow(image) +dots = ax.scatter(u, v, s=2, c='cyan', alpha=0.2) # Dots for projected points +ax.set_title("Projected LiDAR Points on Camera Image", pad=0) + +# Make a slider to control the scale +scale = Slider( + ax=scale_ax, + label="Scale", + valmin=0.75, + valmax=1.25, + valinit=1, + orientation="horizontal" +) + +# Make sliders to control the rotation +x_rot = Slider( + ax=x_rot_ax, + label="X Rotation", + valmin=-30, + valmax=30, + valinit=0, + orientation="horizontal" +) + +y_rot = Slider( + ax=y_rot_ax, + label="Y Rotation", + valmin=-30, + valmax=30, + valinit=0, + orientation="horizontal" +) + +z_rot = Slider( + ax=z_rot_ax, + label="Z Rotation", + valmin=-30, + valmax=30, + valinit=0, + orientation="horizontal" +) + +# Make sliders to control the scale +x_trans = Slider( + ax=x_trans_ax, + label="X Translation", + valmin=-10, + valmax=10, + valinit=0, + orientation="horizontal" +) + +y_trans = Slider( + ax=y_trans_ax, + label="Y Translation", + valmin=-10, + valmax=10, + valinit=0, + orientation="horizontal" +) + +z_trans = Slider( + ax=z_trans_ax, + label="Z Translation", + valmin=-10, + valmax=10, + valinit=0, + orientation="horizontal" +) + +def update(val): + global T_lidar_camera + modified = np.copy(T_lidar_camera) + rotation_mat = R.from_euler('xyz', [x_rot.val, y_rot.val, z_rot.val], degrees=True).as_matrix() + scale_mat = np.array([[scale.val, 0, 0], [0, scale.val, 0], [0, 0, scale.val]]) + translation_vec = np.array([x_trans.val, y_trans.val, z_trans.val]) + modified[:3, :3] = T_lidar_camera[:3, :3] @ rotation_mat @ scale_mat + modified[:3, 3] = T_lidar_camera[:3, 3] + translation_vec + + # Transform LiDAR points to Camera Frame + lidar_points_camera = (modified @ lidar_homogeneous.T).T # (N, 4) + + + # intrinsic matrix + K = np.array([ + [1180.753804, 0. , 934.859447], + [ 0. , 1177.034929, 607.266974], + [ 0. , 0. , 1. ] + ], dtype=np.float32) + + # Extract 3D points in camera frame + X_c = lidar_points_camera[:, 0] + Y_c = lidar_points_camera[:, 1] + Z_c = lidar_points_camera[:, 2] # Depth + + # Avoid division by zero + valid = Z_c > 0 + X_c, Y_c, Z_c = X_c[valid], Y_c[valid], Z_c[valid] + + # Project points onto image plane + u = (K[0, 0] * X_c / Z_c) + K[0, 2] + v = (K[1, 1] * Y_c / Z_c) + K[1, 2] + + # Filter points within image bounds + img_h, img_w, _ = image.shape + valid_pts = (u >= 0) & (u < img_w) & (v >= 0) & (v < img_h) + u, v = u[valid_pts], v[valid_pts] + dots.set_offsets(np.c_[u, v]) + plt.draw() + + +# register the update function with each slider +scale.on_changed(update) +x_rot.on_changed(update) +y_rot.on_changed(update) +z_rot.on_changed(update) +x_trans.on_changed(update) +y_trans.on_changed(update) +z_trans.on_changed(update) + +plt.draw() +while keep_running: + try: + if plt.get_fignums(): + plt.pause(0.1) + else: + keep_running = False + except: + keep_running = False + +modified = np.copy(T_lidar_camera) +rotation_mat = R.from_euler('xyz', [x_rot.val, y_rot.val, z_rot.val], degrees=True).as_matrix() +scale_mat = np.array([[scale.val, 0, 0], [0, scale.val, 0], [0, 0, scale.val]]) +translation_vec = np.array([x_trans.val, y_trans.val, z_trans.val]) +modified[:3, :3] = T_lidar_camera[:3, :3] @ rotation_mat @ scale_mat +modified[:3, 3] = T_lidar_camera[:3, 3] + translation_vec +print(modified) \ No newline at end of file From a5423d989de0416d230ecf1fe00fc2f81e339834 Mon Sep 17 00:00:00 2001 From: Michal Juscinski Date: Sun, 6 Apr 2025 21:04:16 -0700 Subject: [PATCH 195/232] Add code to manually tune calibration --- .../offboard/calibration/test_transforms.py | 207 ++++++++++++++++++ 1 file changed, 207 insertions(+) create mode 100644 GEMstack/offboard/calibration/test_transforms.py diff --git a/GEMstack/offboard/calibration/test_transforms.py b/GEMstack/offboard/calibration/test_transforms.py new file mode 100644 index 000000000..4ed0894f1 --- /dev/null +++ b/GEMstack/offboard/calibration/test_transforms.py @@ -0,0 +1,207 @@ +import numpy as np +import cv2 +import matplotlib.pyplot as plt +from scipy.spatial.transform import Rotation as R +from matplotlib.widgets import Slider + +keep_running = True + +# Load LiDAR points +lidar_data = np.load("./data/ouster32.npz") # Update filename if needed +lidar_points = lidar_data['arr_0'] # Ensure the correct key + +# Load Camera Image +image = cv2.imread("./data/fr_rect32.png") # Update filename if needed +image = cv2.cvtColor(image, cv2.COLOR_BGR2RGB) # Convert BGR to RGB + +# Transformation Matrix +T_lidar_camera = np.array( + [[-0.65266466, -0.75745371, -0.01710912, -0.54157703], + [-0.08467423, 0.09536332, -0.99183472, -0.37038288], + [ 0.75290047, -0.64588677, -0.12637708, 0.0245309 ], + [ 0. , 0. , 0. , 1. ]] +) + +# Convert LiDAR points to homogeneous coordinates +num_points = lidar_points.shape[0] +lidar_homogeneous = np.hstack((lidar_points, np.ones((num_points, 1)))) # (N, 4) + +# Transform LiDAR points to Camera Frame +lidar_points_camera = (T_lidar_camera @ lidar_homogeneous.T).T # (N, 4) + + +# intrinsic matrix +K = np.array([ + [1180.753804, 0. , 934.859447], + [ 0. , 1177.034929, 607.266974], + [ 0. , 0. , 1. ] +], dtype=np.float32) + +# Extract 3D points in camera frame +X_c = lidar_points_camera[:, 0] +Y_c = lidar_points_camera[:, 1] +Z_c = lidar_points_camera[:, 2] # Depth + +# Avoid division by zero +valid = Z_c > 0 +X_c, Y_c, Z_c = X_c[valid], Y_c[valid], Z_c[valid] + +# Project points onto image plane +u = (K[0, 0] * X_c / Z_c) + K[0, 2] +v = (K[1, 1] * Y_c / Z_c) + K[1, 2] + +# Filter points within image bounds +img_h, img_w, _ = image.shape +valid_pts = (u >= 0) & (u < img_w) & (v >= 0) & (v < img_h) +u, v = u[valid_pts], v[valid_pts] + +# Create space for sliders +plt.ion() +fig, ax = plt.subplots() +fig.subplots_adjust(bottom=0.4) +scale_ax = fig.add_axes([0.25, 0.35, 0.65, 0.03]) +x_rot_ax = fig.add_axes([0.25, 0.3, 0.65, 0.03]) +y_rot_ax = fig.add_axes([0.25, 0.25, 0.65, 0.03]) +z_rot_ax = fig.add_axes([0.25, 0.2, 0.65, 0.03]) +x_trans_ax = fig.add_axes([0.25, 0.15, 0.65, 0.03]) +y_trans_ax = fig.add_axes([0.25, 0.1, 0.65, 0.03]) +z_trans_ax = fig.add_axes([0.25, 0.05, 0.65, 0.03]) + +# Plot projected points on camera image +ax.imshow(image) +dots = ax.scatter(u, v, s=2, c='cyan', alpha=0.2) # Dots for projected points +ax.set_title("Projected LiDAR Points on Camera Image", pad=0) + +# Make a slider to control the scale +scale = Slider( + ax=scale_ax, + label="Scale", + valmin=0.75, + valmax=1.25, + valinit=1, + orientation="horizontal" +) + +# Make sliders to control the rotation +x_rot = Slider( + ax=x_rot_ax, + label="X Rotation", + valmin=-30, + valmax=30, + valinit=0, + orientation="horizontal" +) + +y_rot = Slider( + ax=y_rot_ax, + label="Y Rotation", + valmin=-30, + valmax=30, + valinit=0, + orientation="horizontal" +) + +z_rot = Slider( + ax=z_rot_ax, + label="Z Rotation", + valmin=-30, + valmax=30, + valinit=0, + orientation="horizontal" +) + +# Make sliders to control the scale +x_trans = Slider( + ax=x_trans_ax, + label="X Translation", + valmin=-10, + valmax=10, + valinit=0, + orientation="horizontal" +) + +y_trans = Slider( + ax=y_trans_ax, + label="Y Translation", + valmin=-10, + valmax=10, + valinit=0, + orientation="horizontal" +) + +z_trans = Slider( + ax=z_trans_ax, + label="Z Translation", + valmin=-10, + valmax=10, + valinit=0, + orientation="horizontal" +) + +def update(val): + global T_lidar_camera + modified = np.copy(T_lidar_camera) + rotation_mat = R.from_euler('xyz', [x_rot.val, y_rot.val, z_rot.val], degrees=True).as_matrix() + scale_mat = np.array([[scale.val, 0, 0], [0, scale.val, 0], [0, 0, scale.val]]) + translation_vec = np.array([x_trans.val, y_trans.val, z_trans.val]) + modified[:3, :3] = T_lidar_camera[:3, :3] @ rotation_mat @ scale_mat + modified[:3, 3] = T_lidar_camera[:3, 3] + translation_vec + + # Transform LiDAR points to Camera Frame + lidar_points_camera = (modified @ lidar_homogeneous.T).T # (N, 4) + + + # intrinsic matrix + K = np.array([ + [1180.753804, 0. , 934.859447], + [ 0. , 1177.034929, 607.266974], + [ 0. , 0. , 1. ] + ], dtype=np.float32) + + # Extract 3D points in camera frame + X_c = lidar_points_camera[:, 0] + Y_c = lidar_points_camera[:, 1] + Z_c = lidar_points_camera[:, 2] # Depth + + # Avoid division by zero + valid = Z_c > 0 + X_c, Y_c, Z_c = X_c[valid], Y_c[valid], Z_c[valid] + + # Project points onto image plane + u = (K[0, 0] * X_c / Z_c) + K[0, 2] + v = (K[1, 1] * Y_c / Z_c) + K[1, 2] + + # Filter points within image bounds + img_h, img_w, _ = image.shape + valid_pts = (u >= 0) & (u < img_w) & (v >= 0) & (v < img_h) + u, v = u[valid_pts], v[valid_pts] + dots.set_offsets(np.c_[u, v]) + plt.draw() + + +# register the update function with each slider +scale.on_changed(update) +x_rot.on_changed(update) +y_rot.on_changed(update) +z_rot.on_changed(update) +x_trans.on_changed(update) +y_trans.on_changed(update) +z_trans.on_changed(update) + +plt.draw() +while keep_running: + try: + if plt.get_fignums(): + plt.pause(0.1) + else: + keep_running = False + except: + keep_running = False + +modified = np.copy(T_lidar_camera) +rotation_mat = R.from_euler('xyz', [x_rot.val, y_rot.val, z_rot.val], degrees=True).as_matrix() +scale_mat = np.array([[scale.val, 0, 0], [0, scale.val, 0], [0, 0, scale.val]]) +translation_vec = np.array([x_trans.val, y_trans.val, z_trans.val]) +modified[:3, :3] = T_lidar_camera[:3, :3] @ rotation_mat @ scale_mat +modified[:3, 3] = T_lidar_camera[:3, 3] + translation_vec +print(modified) \ No newline at end of file From 1f5c1205a501bf4f8be8fea8f6e5141e1600e6ef Mon Sep 17 00:00:00 2001 From: Michal Juscinski Date: Mon, 7 Apr 2025 07:07:22 -0700 Subject: [PATCH 196/232] Add script to rectify images --- .../offboard/calibration/undistort_images.py | 35 +++++++++++++++++++ 1 file changed, 35 insertions(+) create mode 100644 GEMstack/offboard/calibration/undistort_images.py diff --git a/GEMstack/offboard/calibration/undistort_images.py b/GEMstack/offboard/calibration/undistort_images.py new file mode 100644 index 000000000..a970f177d --- /dev/null +++ b/GEMstack/offboard/calibration/undistort_images.py @@ -0,0 +1,35 @@ +import numpy as np +import cv2 as cv +import glob +import os + +camera_matrix = np.array( + [[1180.753804, 0.000000 , 934.859447], + [0.000000 , 1177.034929, 607.266974], + [0.000000 , 0.000000 , 1.000000 ]] +) + +distortion_coefficients = np.array([-0.2448506795091457, 0.08202383880344215, 0.0004294271518916802, -0.0012454354245869965, 0.0]) + +def main(folder, camera): + image_files = glob.glob(os.path.join(folder, camera + '*.png')) + + for fn in image_files: + image = cv.imread(fn) + h, w = image.shape[:2] + new_camera_matrix, roi = cv.getOptimalNewCameraMatrix(camera_matrix, distortion_coefficients, (w,h), 1, (w,h)) + + # undistort + dst = cv.undistort(image, camera_matrix, distortion_coefficients, None, new_camera_matrix) + cv.imwrite(fn.replace(camera, camera + "_rect"), dst) + + +if __name__ == '__main__': + import sys + folder = 'data' + camera = 'fr' + if len(sys.argv) >= 2: + folder = sys.argv[1] + if len(sys.argv) >= 3: + camera = int(sys.argv[2]) + main(folder,camera) \ No newline at end of file From 4431f7f5013d021e1a809da1686fe4dc97a8a831 Mon Sep 17 00:00:00 2001 From: Michal Juscinski Date: Mon, 7 Apr 2025 07:07:22 -0700 Subject: [PATCH 197/232] Add script to rectify images --- .../offboard/calibration/undistort_images.py | 35 +++++++++++++++++++ 1 file changed, 35 insertions(+) create mode 100644 GEMstack/offboard/calibration/undistort_images.py diff --git a/GEMstack/offboard/calibration/undistort_images.py b/GEMstack/offboard/calibration/undistort_images.py new file mode 100644 index 000000000..a970f177d --- /dev/null +++ b/GEMstack/offboard/calibration/undistort_images.py @@ -0,0 +1,35 @@ +import numpy as np +import cv2 as cv +import glob +import os + +camera_matrix = np.array( + [[1180.753804, 0.000000 , 934.859447], + [0.000000 , 1177.034929, 607.266974], + [0.000000 , 0.000000 , 1.000000 ]] +) + +distortion_coefficients = np.array([-0.2448506795091457, 0.08202383880344215, 0.0004294271518916802, -0.0012454354245869965, 0.0]) + +def main(folder, camera): + image_files = glob.glob(os.path.join(folder, camera + '*.png')) + + for fn in image_files: + image = cv.imread(fn) + h, w = image.shape[:2] + new_camera_matrix, roi = cv.getOptimalNewCameraMatrix(camera_matrix, distortion_coefficients, (w,h), 1, (w,h)) + + # undistort + dst = cv.undistort(image, camera_matrix, distortion_coefficients, None, new_camera_matrix) + cv.imwrite(fn.replace(camera, camera + "_rect"), dst) + + +if __name__ == '__main__': + import sys + folder = 'data' + camera = 'fr' + if len(sys.argv) >= 2: + folder = sys.argv[1] + if len(sys.argv) >= 3: + camera = int(sys.argv[2]) + main(folder,camera) \ No newline at end of file From 3e354a3e7f02744a66b66b7d8e5ded0bd2660c3a Mon Sep 17 00:00:00 2001 From: rjsun-KA <92330153+rjsun06@users.noreply.github.com> Date: Mon, 7 Apr 2025 17:08:15 +0000 Subject: [PATCH 198/232] cali by segmentation --- .gitignore | 7 + .../knowledge/calibration/gem_e4_fl_in.yaml | 4 + .../calibration_by_segmentation/.gitignore | 1 - .../calibration_by_segmentation/calib.bash | 10 +- .../data/.gitignore | 3 + .../data/fl/calib.json | 24 ++-- .../data/fl/images/.gitignore | 3 - .../data/fl/masks/.gitignore | 3 - .../make_dataset.py | 123 ++++++++++++++++++ .../calibration_by_segmentation/setup.bash | 2 + GEMstack/offboard/calibration/img2pc.py | 1 + GEMstack/offboard/calibration/run_img2pc.bash | 4 +- .../offboard/calibration/tools/save_cali.py | 14 +- 13 files changed, 173 insertions(+), 26 deletions(-) create mode 100644 GEMstack/knowledge/calibration/gem_e4_fl_in.yaml create mode 100644 GEMstack/offboard/calibration/calibration_by_segmentation/data/.gitignore delete mode 100644 GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/images/.gitignore delete mode 100644 GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/masks/.gitignore create mode 100644 GEMstack/offboard/calibration/calibration_by_segmentation/make_dataset.py create mode 100644 GEMstack/offboard/calibration/calibration_by_segmentation/setup.bash diff --git a/.gitignore b/.gitignore index 0c36d682f..90ca50fe0 100644 --- a/.gitignore +++ b/.gitignore @@ -165,3 +165,10 @@ cython_debug/ # and can be added to the global gitignore or merged into this file. For a more nuclear # option (not recommended) you can uncomment the following to ignore the entire idea folder. #.idea/ +GEMstack/offboard/calibration/calibration_by_segmentation/init_proj_seg.png +GEMstack/offboard/calibration/calibration_by_segmentation/init_proj.png +.gitignore +.gitignore +GEMstack/offboard/calibration/calibration_by_segmentation/refined_proj_seg.png +GEMstack/offboard/calibration/calibration_by_segmentation/refined_proj.png +GEMstack/offboard/calibration/calibration_by_segmentation/extrinsic.txt diff --git a/GEMstack/knowledge/calibration/gem_e4_fl_in.yaml b/GEMstack/knowledge/calibration/gem_e4_fl_in.yaml new file mode 100644 index 000000000..d6677bc5e --- /dev/null +++ b/GEMstack/knowledge/calibration/gem_e4_fl_in.yaml @@ -0,0 +1,4 @@ +center: [980, 605] +focal: [1230, 1230] +distort: [-0.23751890570984993, 0.08452214195986749, -0.00035324203850054794, -0.0003762498910536819, 0.0] +skew: 0.0 diff --git a/GEMstack/offboard/calibration/calibration_by_segmentation/.gitignore b/GEMstack/offboard/calibration/calibration_by_segmentation/.gitignore index 591eb2709..4d776b98f 100644 --- a/GEMstack/offboard/calibration/calibration_by_segmentation/.gitignore +++ b/GEMstack/offboard/calibration/calibration_by_segmentation/.gitignore @@ -1,3 +1,2 @@ sam_vit_h.pth - !.gitignore diff --git a/GEMstack/offboard/calibration/calibration_by_segmentation/calib.bash b/GEMstack/offboard/calibration/calibration_by_segmentation/calib.bash index 73d785d6b..10d55d950 100644 --- a/GEMstack/offboard/calibration/calibration_by_segmentation/calib.bash +++ b/GEMstack/offboard/calibration/calibration_by_segmentation/calib.bash @@ -1,12 +1,16 @@ data=$1 -wget -c -O sam_vit_h.pth https://dl.fbaipublicfiles.com/segment_anything/sam_vit_h_4b8939.pth +wget -c -O sam_vit_b.pth https://dl.fbaipublicfiles.com/segment_anything/sam_vit_b_01ec64.pth +# wget -c -O sam_vit_h.pth https://dl.fbaipublicfiles.com/segment_anything/sam_vit_h_4b8939.pth +cd segment-anything; pip install -e .; cd .. echo 'running segmentation...' -python3 segment-anything scripts/amg.py --checkpoint sam_vit_h.pth --model-type vit_h --input $data/images --output $data/masks/ --stability-score-thresh 0.9 --box-nms-thresh 0.5 --stability-score-offset 0.9 +python3 segment-anything/scripts/amg.py --checkpoint sam_vit_b.pth --model-type vit_b --input $data/images --output $data/masks/ --stability-score-thresh 0.9 --box-nms-thresh 0.5 --stability-score-offset 0.9 +# python3 segment-anything/scripts/amg.py --checkpoint sam_vit_h.pth --model-type vit_h --input $data/images --output $data/masks/ --stability-score-thresh 0.9 --box-nms-thresh 0.5 --stability-score-offset 0.9 echo 'reprocess segmentation...' python3 CalibAnything/processed_mask.py -i $data/masks -o $data/processed_masks/ echo 'running calibration...' -CalibAnything/bin/run_lidar2camera $data/calib.json \ No newline at end of file +CalibAnything/bin/run_lidar2camera $data/calib.json + diff --git a/GEMstack/offboard/calibration/calibration_by_segmentation/data/.gitignore b/GEMstack/offboard/calibration/calibration_by_segmentation/data/.gitignore new file mode 100644 index 000000000..6982f8410 --- /dev/null +++ b/GEMstack/offboard/calibration/calibration_by_segmentation/data/.gitignore @@ -0,0 +1,3 @@ +*/*/* +pc/* +!.gitignore \ No newline at end of file diff --git a/GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/calib.json b/GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/calib.json index 22f6e1bbf..939da7abd 100644 --- a/GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/calib.json +++ b/GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/calib.json @@ -3,28 +3,26 @@ "rows": 3, "cols": 3, "data": [ - [1180.753804, 0.000000, 934.859447], - [0.000000, 1177.034929, 607.266974], + [1230.1440959825889, 0.0, 978.8285075011214], + [0.0, 1230.6304235898162, 605.7940335714893], [0.000000, 0.000000 , 1.000000 ] ] }, "cam_dist": { "cols": 5, - "data": [-0.244851, 0.082024, 0.000429, -0.001245, 0.000000] + "data": [-0.237519, 0.084522, -0.000353, -0.000376, 0.000000] }, "T_lidar_to_cam":{ "rows": 4, "cols": 4, - "data": [ - [ 0.72 , -0.694, 0.014, 0.12], - [-0.166, -0.191, -0.967, 0.09], - [ 0.673, 0.694, -0.253, -1.17], - [ 0.0 , 0.0 , 0.0 , 1.0 ] - ] + "data": [[ 0.72 , -0.694, 0.014, 0.12 ], + [-0.166, -0.191, -0.967, 0.09 ], + [ 0.673, 0.694, -0.253, -1.17 ], + [ 0 , 0 , 0 , 1 ]] }, "img_folder": "images", "mask_folder": "processed_masks", - "pc_folder": "pc", + "pc_folder": "../pc", "img_format": ".png", "pc_format": ".pcd", "file_name": [ @@ -32,7 +30,11 @@ "000001", "000002", "000003", - "000004" + "000004", + "000005", + "000006", + "000007", + "000008" ], "params": { "min_plane_point_num": 2000, diff --git a/GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/images/.gitignore b/GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/images/.gitignore deleted file mode 100644 index cec9082b6..000000000 --- a/GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/images/.gitignore +++ /dev/null @@ -1,3 +0,0 @@ -* - -!.gitignore diff --git a/GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/masks/.gitignore b/GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/masks/.gitignore deleted file mode 100644 index cec9082b6..000000000 --- a/GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/masks/.gitignore +++ /dev/null @@ -1,3 +0,0 @@ -* - -!.gitignore diff --git a/GEMstack/offboard/calibration/calibration_by_segmentation/make_dataset.py b/GEMstack/offboard/calibration/calibration_by_segmentation/make_dataset.py new file mode 100644 index 000000000..9e0224c59 --- /dev/null +++ b/GEMstack/offboard/calibration/calibration_by_segmentation/make_dataset.py @@ -0,0 +1,123 @@ +#%% +import rosbag +import os +import bisect +from sensor_msgs.msg import Image, PointCloud2 +from sensor_msgs import point_cloud2 +import cv2 +from cv_bridge import CvBridge +import numpy as np + +def write_pcd(pc_msg, filename): + # Read points from PointCloud2 message + points = list(point_cloud2.read_points(pc_msg, field_names=("x", "y", "z"), skip_nans=True)) + # Write PCD header + header = f"""VERSION .7 +FIELDS x y z +SIZE 4 4 4 +TYPE F F F +COUNT 1 1 1 +WIDTH {len(points)} +HEIGHT 1 +VIEWPOINT 0 0 0 1 0 0 0 +POINTS {len(points)} +DATA ascii +""" + + # Write to file + with open(filename, 'w') as f: + f.write(header) + for p in points: + f.write(f"{p[0]} {p[1]} {p[2]}\n") + +def process_bag(bag_path, output_dir='sync_dataset', time_threshold=0.05): + bag = rosbag.Bag(bag_path) + bridge = CvBridge() + + # Topic configuration + topic_map = { + '/camera_fl/arena_camera_node/image_raw': 'fl/images', + '/camera_rl/arena_camera_node/image_raw': 'rl/images', + '/camera_rr/arena_camera_node/image_raw': 'rr/images', + '/oak/rgb/image_raw': 'oak/images', + '/ouster/points': 'pc' + } + + # Create output directories + for d in ['fl', 'rl', 'rr', 'oak', 'pc']: + os.makedirs(os.path.join(output_dir, d), exist_ok=True) + + # Load and sort all messages + messages = {topic: [] for topic in topic_map.keys()} + for topic, msg, t in bag.read_messages(topics=topic_map.keys()): + stamp = msg.header.stamp.to_sec() if hasattr(msg, 'header') else t.to_sec() + messages[topic].append((stamp, msg)) + + # Sort each topic by timestamp + for topic in messages: + messages[topic].sort(key=lambda x: x[0]) + + # Reference topic (point cloud) + ref_topic = '/ouster/points' + group_index = 0 + + for pc_stamp, pc_msg in messages[ref_topic]: + timestamps = {'pc': pc_stamp} + entry = {} + + # Find closest camera messages + for cam_topic in topic_map: + if cam_topic == ref_topic: + continue + cam_msgs = messages.get(cam_topic, []) + if not cam_msgs: + continue + stamps = [s for s, m in cam_msgs] + idx = bisect.bisect_left(stamps, pc_stamp) + + closest = None + closest_stamp = None + + # Check next message + if idx < len(stamps): + if abs(stamps[idx] - pc_stamp) < time_threshold: + closest = cam_msgs[idx][1] + closest_stamp = stamps[idx] + + # Check previous message if not found + if not closest and idx > 0: + if abs(stamps[idx-1] - pc_stamp) < time_threshold: + closest = cam_msgs[idx-1][1] + closest_stamp = stamps[idx-1] + + if closest: + entry[cam_topic] = (closest_stamp, closest) + timestamps[topic_map[cam_topic]] = closest_stamp + + # Save only if we have all sensors + if len(entry) == 4: # 4 camera topics + point cloud + # Save images and point cloud + frame_id = f"{group_index:06d}" + + # Print timestamps + print(f"Saved group {group_index} with timestamps:") + for sensor, ts in timestamps.items(): + print(f" {sensor}: {ts:.6f}") + + # Save images + for topic, (stamp, msg) in entry.items(): + output_subdir = topic_map[topic] + output_path = os.path.join(output_dir, output_subdir, f"{frame_id}.png") + cv_img = bridge.imgmsg_to_cv2(msg, desired_encoding='passthrough') + cv2.imwrite(output_path, cv_img) + + # Save point cloud + pc_path = os.path.join(output_dir, 'pc', f"{frame_id}.pcd") + write_pcd(pc_msg, pc_path) + + group_index += 1 + + bag.close() + +# Example usage +process_bag('/mnt/GEMstack/data/mybag_2025-04-01-17-41-55.bag','/mnt/GEMstack/GEMstack/offboard/calibration/calibration_by_segmentation/data') \ No newline at end of file diff --git a/GEMstack/offboard/calibration/calibration_by_segmentation/setup.bash b/GEMstack/offboard/calibration/calibration_by_segmentation/setup.bash new file mode 100644 index 000000000..a3ffa9e26 --- /dev/null +++ b/GEMstack/offboard/calibration/calibration_by_segmentation/setup.bash @@ -0,0 +1,2 @@ + +cd segment-anything; pip install -e .; cd .. \ No newline at end of file diff --git a/GEMstack/offboard/calibration/img2pc.py b/GEMstack/offboard/calibration/img2pc.py index 846bc4902..5eaf1a4cc 100644 --- a/GEMstack/offboard/calibration/img2pc.py +++ b/GEMstack/offboard/calibration/img2pc.py @@ -74,6 +74,7 @@ def main(): lidar_ex = load_ex(args.pc_transform_path,mode='matrix') pc = np.pad(pc,((0,0),(0,1)),constant_values=1) @ lidar_ex.T[:,:3] + cpoints = np.array(pick_n_img(img,N)).astype(float) print(cpoints) diff --git a/GEMstack/offboard/calibration/run_img2pc.bash b/GEMstack/offboard/calibration/run_img2pc.bash index d0a1ed520..116d02291 100644 --- a/GEMstack/offboard/calibration/run_img2pc.bash +++ b/GEMstack/offboard/calibration/run_img2pc.bash @@ -1,8 +1,8 @@ root='/mnt/GEMstack' python3 $root/GEMstack/offboard/calibration/img2pc.py \ - --img_path $root/data/calib1/img/fl/fl11.png \ - --pc_path $root/data/calib1/pc/ouster11.npz \ + --img_path $root/data/calib1/img/fl/fl16.png \ + --pc_path $root/data/calib1/pc/ouster16.npz \ --pc_transform_path $root/GEMstack/knowledge/calibration/gem_e4_ouster.yaml \ --img_intrinsics_path $root/GEMstack/knowledge/calibration/gem_e4_oak_in.yaml \ --n_features 4 \ diff --git a/GEMstack/offboard/calibration/tools/save_cali.py b/GEMstack/offboard/calibration/tools/save_cali.py index fa147aff2..f49dca5a9 100644 --- a/GEMstack/offboard/calibration/tools/save_cali.py +++ b/GEMstack/offboard/calibration/tools/save_cali.py @@ -40,7 +40,7 @@ def save_ex(path,rotation=None,translation=None,matrix=None,ref='rear_axle_cente with open(path,'w') as stream: yaml.dump(ret,stream,Dumper=SafeDumper,default_flow_style=False) -def load_in(path,mode='matrix'): +def load_in(path,mode='matrix',return_distort=False): with open(path) as stream: y = yaml.safe_load(stream) if mode == 'matrix': @@ -48,18 +48,26 @@ def load_in(path,mode='matrix'): ret[0,0],ret[1,1] = y['focal'] ret[0:2,2] = y['center'] return ret + if 'skew' not in y: y['skew'] = 0 + if 'distort' not in y: y['distort'] = [0,0,0,0,0] elif mode == 'tuple': - return np.array(y['focal']),np.array(y['center']) + return {'focal':np.array(y['focal']), + 'center':np.array(y['center']), + 'skew':np.array(y['skew']), + 'distort':np.array(y['distort'])} -def save_in(path,focal=None,center=None,matrix=None): +def save_in(path,focal=None,center=None,skew=None,distort=None,matrix=None): if matrix is not None: focal = matrix.diagonal()[0,-1] + skew = matrix[0,1] center = matrix[0:2,2] save_in(path,focal,center) return ret = {} ret['focal'] = focal ret['center'] = center + ret['skew'] = skew or 0 + ret['distort'] = distort or [0,0,0,0,0] for i in ret: if type(ret[i]) == np.ndarray: ret[i] = ret[i].tolist() From 974f368da9f84051910f46cc5ce3be175b1ec218 Mon Sep 17 00:00:00 2001 From: michalj1 Date: Mon, 7 Apr 2025 14:04:15 -0500 Subject: [PATCH 199/232] Clean code and allow it to collect scans when not all sensors are working --- .../calibration/capture_ouster_oak.py | 197 +++++++----------- 1 file changed, 75 insertions(+), 122 deletions(-) diff --git a/GEMstack/offboard/calibration/capture_ouster_oak.py b/GEMstack/offboard/calibration/capture_ouster_oak.py index baee8985b..62cc72910 100644 --- a/GEMstack/offboard/calibration/capture_ouster_oak.py +++ b/GEMstack/offboard/calibration/capture_ouster_oak.py @@ -5,63 +5,39 @@ import ctypes import struct -# from ...state import VehicleState, ObjectPose -# from ...onboard import Component - # OpenCV and cv2 bridge import cv2 from cv_bridge import CvBridge import numpy as np import os import time +from functools import partial -# TODO: change these arrays to use dictionaries, format eg. {filename: data} -lidar_points = None -camera_image = None -fl_image = None -fr_image = None -rl_image = None -rr_image = None -depth_images = None -gnss_locations = None -frame_position = None +camera_images = {"oak": None, "fr": None, "fl": None, "rr": None, "rl": None, "fr_rect": None, "fl_rect": None, "rr_rect": None, "rl_rect": None} +lidar_clouds = {"ouster": None, "livox": None} +depth_images = {"depth": None} +gnss_locations = {"nav_fix": None} lidar_filetype = ".npz" camera_filetype = ".png" depth_filetype = ".tif" gnss_filetype = ".npy" bridge = CvBridge() -def lidar_callback(lidar : PointCloud2): - global lidar_points - lidar_points = (lidar) - -def camera_callback(img : Image): - global camera_image - camera_image = (img) - -def fl_camera_callback(img : Image): - global fl_image - fl_image = (img) - -def fr_camera_callback(img : Image): - global fr_image - fr_image = (img) +def lidar_callback(scanner, lidar : PointCloud2): + global lidar_clouds + lidar_clouds[scanner] = lidar -def rl_camera_callback(img : Image): - global rl_image - rl_image = (img) +def camera_callback(camera, img : Image): + global camera_images + camera_images[camera] = img -def rr_camera_callback(img : Image): - global rr_image - rr_image = (img) - -def depth_callback(img : Image): +def depth_callback(camera, img : Image): global depth_images - depth_images = (img) + depth_images[camera] = img -def gnss_callback(sat_fix : NavSatFix): +def gnss_callback(gnss, sat_fix : NavSatFix): global gnss_locations - gnss_locations = (sat_fix) + gnss_locations[gnss] = sat_fix def pc2_to_numpy(pc2_msg, want_rgb = False): gen = pc2.read_points(pc2_msg, skip_nans=True) @@ -87,74 +63,70 @@ def pc2_to_numpy(pc2_msg, want_rgb = False): else: return np.array(list(gen),dtype=np.float32)[:,:3] -# def clear_scan(): -# global lidar_points -# lidar_points = [] -# global camera_image -# camera_image = [] -# global depth_images -# depth_images = [] -# global gnss_locations -# gnss_locations = [] +def clear_scan(): + global camera_images + for camera in camera_images: + camera_images[camera] = None + global lidar_clouds + for lidar in lidar_clouds: + lidar_clouds[lidar] = None + global depth_images + for camera in depth_images: + depth_images[camera] = None + global gnss_locations + for gnss in gnss_locations: + gnss_locations[gnss] = None -# TODO: when data is stored in dictionaries, change to only save files which exist and change error checking -def save_scan(lidar_fn, camera_fn, fl_fn, fr_fn, rl_fn, rr_fn, depth_fn, gnss_fn, index): - # if len(lidar_filenames) != len(lidar_points) or len(camera_filenames) != len(camera_image) or len(depth_filenames) != len(depth_images): - # print("Missing data, scan", index, "cannot be saved") - # print(len(lidar_filenames), len(lidar_points), len(camera_filenames), len(camera_image), len(depth_filenames), len(depth_images)) - # return +def save_scan(folder, index): print("Saving scan", index) - if frame_position != None: - np.save("state" + str(index), frame_position) - else: - print("No state found") - - # for i in range(len(lidar_points)): - # current_lidar = lidar_points[i] - # lidar_fn = lidar_filename + str(index) + lidar_filetype - pc = pc2_to_numpy(lidar_points,want_rgb=False) # convert lidar feed to numpy - np.savez(lidar_fn + str(index) + lidar_filetype,pc) - - # for i in range(len(camera_image)): - # current_camera = camera_image[i] - # camera_fn = camera_filenames[i] + str(index) + camera_filetype - cv2.imwrite(camera_fn + str(index) + camera_filetype,bridge.imgmsg_to_cv2(camera_image)) - cv2.imwrite(fl_fn + str(index) + camera_filetype,bridge.imgmsg_to_cv2(fl_image)) - cv2.imwrite(fr_fn + str(index) + camera_filetype,bridge.imgmsg_to_cv2(fr_image)) - cv2.imwrite(rl_fn + str(index) + camera_filetype,bridge.imgmsg_to_cv2(rl_image)) - cv2.imwrite(rr_fn + str(index) + camera_filetype,bridge.imgmsg_to_cv2(rr_image)) - - # for i in range(len(depth_images)): - dimage = bridge.imgmsg_to_cv2(depth_images) - # depth_fn = depth_filenames[i] + str(index) + depth_filetype - dimage_non_nan = dimage[np.isfinite(dimage)] - # print("Depth range",np.min(dimage_non_nan),np.max(dimage_non_nan)) - dimage = np.nan_to_num(dimage,nan=0,posinf=0,neginf=0) - dimage = (dimage/4000*0xffff) - # print("Depth pixel range",np.min(dimage),np.max(dimage)) - dimage = dimage.astype(np.uint16) - cv2.imwrite(depth_fn + str(index) + depth_filetype,dimage) + for lidar in lidar_clouds: + lidar_points = lidar_clouds[lidar] + if lidar_points != None: + lidar_fn = os.path.join(folder, lidar + str(index) + lidar_filetype) + pc = pc2_to_numpy(lidar_points, want_rgb=False) # convert lidar feed to numpy + np.savez(lidar_fn, pc) + + for camera in camera_images: + camera_image = camera_images[camera] + if camera_image != None: + camera_fn = os.path.join(folder, camera + str(index) + camera_filetype) + cv2.imwrite(camera_fn, bridge.imgmsg_to_cv2(camera_image)) + + for camera in depth_images: + depth_image = depth_images[camera] + if depth_image != None: + depth_fn = os.path.join(folder, camera + str(index) + depth_filetype) + dimage = bridge.imgmsg_to_cv2(depth_image) + dimage_non_nan = dimage[np.isfinite(dimage)] + dimage = np.nan_to_num(dimage,nan=0,posinf=0,neginf=0) + dimage = (dimage/4000*0xffff) + dimage = dimage.astype(np.uint16) + cv2.imwrite(depth_fn, dimage) - # for i in range(len(gnss_locations)): - # sat_fix = gnss_locations[i] - # gnss_fn = gnss_filenames + str(index) + gnss_filetype - if gnss_locations: - coordinates = np.array([gnss_locations.latitude, gnss_locations.longitude]) - np.save(gnss_fn + str(index) + gnss_filetype, coordinates) + for gnss in gnss_locations: + location = gnss_locations[gnss] + if location != None: + gnss_fn = os.path.join(folder, gnss + str(index) + gnss_filetype) + coordinates = np.array([location.latitude, location.longitude]) + np.save(gnss_fn + str(index) + gnss_filetype, coordinates) def main(folder='data',start_index=0): # Initialize node and establish subscribers rospy.init_node("capture_ouster_oak",disable_signals=True) - ouster_sub = rospy.Subscriber("/ouster/points", PointCloud2, lidar_callback) - # livox_sub = rospy.Subscriber("/livox/lidar", PointCloud2, lidar_callback) - oak_sub = rospy.Subscriber("/oak/rgb/image_raw", Image, camera_callback) - cam_fl_sub = rospy.Subscriber("/camera_fl/arena_camera_node/image_raw", Image, fl_camera_callback) - cam_fr_sub = rospy.Subscriber("/camera_fr/arena_camera_node/image_raw", Image, fr_camera_callback) - cam_rl_sub = rospy.Subscriber("/camera_rl/arena_camera_node/image_raw", Image, rl_camera_callback) - cam_rr_sub = rospy.Subscriber("/camera_rr/arena_camera_node/image_raw", Image, rr_camera_callback) - depth_sub = rospy.Subscriber("/oak/stereo/image_raw", Image, depth_callback) - gnss_sub = rospy.Subscriber("/septentrio_gnss/navsatfix", NavSatFix, gnss_callback) + ouster_sub = rospy.Subscriber("/ouster/points", PointCloud2, partial(lidar_callback, "ouster")) + livox_sub = rospy.Subscriber("/livox/lidar", PointCloud2, partial(lidar_callback, "livox")) + oak_sub = rospy.Subscriber("/oak/rgb/image_raw", Image, partial(camera_callback, "oak")) + cam_fl_sub = rospy.Subscriber("/camera_fl/arena_camera_node/image_raw", Image, partial(camera_callback, "fl")) + cam_fr_sub = rospy.Subscriber("/camera_fr/arena_camera_node/image_raw", Image, partial(camera_callback, "fr")) + cam_rl_sub = rospy.Subscriber("/camera_rl/arena_camera_node/image_raw", Image, partial(camera_callback, "rl")) + cam_rr_sub = rospy.Subscriber("/camera_rr/arena_camera_node/image_raw", Image, partial(camera_callback, "rr")) + cam_fl_rect_sub = rospy.Subscriber("/camera_fl/arena_camera_node/image_rect_color", Image, partial(camera_callback, "fl_rect")) + cam_fr_rect_sub = rospy.Subscriber("/camera_fr/arena_camera_node/image_rect_color", Image, partial(camera_callback, "fr_rect")) + cam_rl_rect_sub = rospy.Subscriber("/camera_rl/arena_camera_node/image_rect_color", Image, partial(camera_callback, "rl_rect")) + cam_rr_rect_sub = rospy.Subscriber("/camera_rr/arena_camera_node/image_rect_color", Image, partial(camera_callback, "rr_rect")) + depth_sub = rospy.Subscriber("/oak/stereo/image_raw", Image, partial(depth_callback, "depth")) + gnss_sub = rospy.Subscriber("/septentrio_gnss/navsatfix", NavSatFix, partial(gnss_callback, "nav_fix")) # Store scans index = start_index @@ -163,32 +135,13 @@ def main(folder='data',start_index=0): print(" Storing depth images as", depth_filetype) print(" Ctrl+C to quit") while True: - if camera_image: - cv2.imshow("result",bridge.imgmsg_to_cv2(camera_image)) + if camera_images["oak"]: + cv2.imshow("result",bridge.imgmsg_to_cv2(camera_images["oak"])) time.sleep(.5) - files = [os.path.join(folder, 'ouster'),os.path.join(folder, 'oak'), - os.path.join(folder, 'fl'), os.path.join(folder, 'fr'), - os.path.join(folder, 'rl'), os.path.join(folder, 'rr'), - os.path.join(folder, 'depth'), os.path.join(folder, 'septentrio')] - # lidar_files = [os.path.join(folder, 'ouster')] - # camera_files = [os.path.join(folder, 'oak'), - # os.path.join(folder, 'fl'), os.path.join(folder, 'fr'), - # os.path.join(folder, 'rl'), os.path.join(folder, 'rr')] - # depth_files = [os.path.join(folder, 'depth')] - # gnss_files = [os.path.join(folder, 'septentrio')] - save_scan(*files, index) - # clear_scan() + save_scan(folder, index) + clear_scan() index += 1 -# class StateTracker(Component): -# def rate(self): -# return 4.0 # Hz -# def state_inputs(self): -# return ['vehicle'] -# def update(self, vehicle : VehicleState): -# global frame_position -# frame_position = np.array(vehicle.pose.frame, vehicle.pose.t, vehicle.pose.x, vehicle.pose.y) - if __name__ == '__main__': import sys folder = 'data' From 577d49e07c475c32fd54e98cd56149eafe9e9059 Mon Sep 17 00:00:00 2001 From: michalj1 Date: Mon, 7 Apr 2025 14:04:15 -0500 Subject: [PATCH 200/232] Clean code and allow it to collect scans when not all sensors are working --- .../calibration/capture_ouster_oak.py | 197 +++++++----------- 1 file changed, 75 insertions(+), 122 deletions(-) diff --git a/GEMstack/offboard/calibration/capture_ouster_oak.py b/GEMstack/offboard/calibration/capture_ouster_oak.py index baee8985b..62cc72910 100644 --- a/GEMstack/offboard/calibration/capture_ouster_oak.py +++ b/GEMstack/offboard/calibration/capture_ouster_oak.py @@ -5,63 +5,39 @@ import ctypes import struct -# from ...state import VehicleState, ObjectPose -# from ...onboard import Component - # OpenCV and cv2 bridge import cv2 from cv_bridge import CvBridge import numpy as np import os import time +from functools import partial -# TODO: change these arrays to use dictionaries, format eg. {filename: data} -lidar_points = None -camera_image = None -fl_image = None -fr_image = None -rl_image = None -rr_image = None -depth_images = None -gnss_locations = None -frame_position = None +camera_images = {"oak": None, "fr": None, "fl": None, "rr": None, "rl": None, "fr_rect": None, "fl_rect": None, "rr_rect": None, "rl_rect": None} +lidar_clouds = {"ouster": None, "livox": None} +depth_images = {"depth": None} +gnss_locations = {"nav_fix": None} lidar_filetype = ".npz" camera_filetype = ".png" depth_filetype = ".tif" gnss_filetype = ".npy" bridge = CvBridge() -def lidar_callback(lidar : PointCloud2): - global lidar_points - lidar_points = (lidar) - -def camera_callback(img : Image): - global camera_image - camera_image = (img) - -def fl_camera_callback(img : Image): - global fl_image - fl_image = (img) - -def fr_camera_callback(img : Image): - global fr_image - fr_image = (img) +def lidar_callback(scanner, lidar : PointCloud2): + global lidar_clouds + lidar_clouds[scanner] = lidar -def rl_camera_callback(img : Image): - global rl_image - rl_image = (img) +def camera_callback(camera, img : Image): + global camera_images + camera_images[camera] = img -def rr_camera_callback(img : Image): - global rr_image - rr_image = (img) - -def depth_callback(img : Image): +def depth_callback(camera, img : Image): global depth_images - depth_images = (img) + depth_images[camera] = img -def gnss_callback(sat_fix : NavSatFix): +def gnss_callback(gnss, sat_fix : NavSatFix): global gnss_locations - gnss_locations = (sat_fix) + gnss_locations[gnss] = sat_fix def pc2_to_numpy(pc2_msg, want_rgb = False): gen = pc2.read_points(pc2_msg, skip_nans=True) @@ -87,74 +63,70 @@ def pc2_to_numpy(pc2_msg, want_rgb = False): else: return np.array(list(gen),dtype=np.float32)[:,:3] -# def clear_scan(): -# global lidar_points -# lidar_points = [] -# global camera_image -# camera_image = [] -# global depth_images -# depth_images = [] -# global gnss_locations -# gnss_locations = [] +def clear_scan(): + global camera_images + for camera in camera_images: + camera_images[camera] = None + global lidar_clouds + for lidar in lidar_clouds: + lidar_clouds[lidar] = None + global depth_images + for camera in depth_images: + depth_images[camera] = None + global gnss_locations + for gnss in gnss_locations: + gnss_locations[gnss] = None -# TODO: when data is stored in dictionaries, change to only save files which exist and change error checking -def save_scan(lidar_fn, camera_fn, fl_fn, fr_fn, rl_fn, rr_fn, depth_fn, gnss_fn, index): - # if len(lidar_filenames) != len(lidar_points) or len(camera_filenames) != len(camera_image) or len(depth_filenames) != len(depth_images): - # print("Missing data, scan", index, "cannot be saved") - # print(len(lidar_filenames), len(lidar_points), len(camera_filenames), len(camera_image), len(depth_filenames), len(depth_images)) - # return +def save_scan(folder, index): print("Saving scan", index) - if frame_position != None: - np.save("state" + str(index), frame_position) - else: - print("No state found") - - # for i in range(len(lidar_points)): - # current_lidar = lidar_points[i] - # lidar_fn = lidar_filename + str(index) + lidar_filetype - pc = pc2_to_numpy(lidar_points,want_rgb=False) # convert lidar feed to numpy - np.savez(lidar_fn + str(index) + lidar_filetype,pc) - - # for i in range(len(camera_image)): - # current_camera = camera_image[i] - # camera_fn = camera_filenames[i] + str(index) + camera_filetype - cv2.imwrite(camera_fn + str(index) + camera_filetype,bridge.imgmsg_to_cv2(camera_image)) - cv2.imwrite(fl_fn + str(index) + camera_filetype,bridge.imgmsg_to_cv2(fl_image)) - cv2.imwrite(fr_fn + str(index) + camera_filetype,bridge.imgmsg_to_cv2(fr_image)) - cv2.imwrite(rl_fn + str(index) + camera_filetype,bridge.imgmsg_to_cv2(rl_image)) - cv2.imwrite(rr_fn + str(index) + camera_filetype,bridge.imgmsg_to_cv2(rr_image)) - - # for i in range(len(depth_images)): - dimage = bridge.imgmsg_to_cv2(depth_images) - # depth_fn = depth_filenames[i] + str(index) + depth_filetype - dimage_non_nan = dimage[np.isfinite(dimage)] - # print("Depth range",np.min(dimage_non_nan),np.max(dimage_non_nan)) - dimage = np.nan_to_num(dimage,nan=0,posinf=0,neginf=0) - dimage = (dimage/4000*0xffff) - # print("Depth pixel range",np.min(dimage),np.max(dimage)) - dimage = dimage.astype(np.uint16) - cv2.imwrite(depth_fn + str(index) + depth_filetype,dimage) + for lidar in lidar_clouds: + lidar_points = lidar_clouds[lidar] + if lidar_points != None: + lidar_fn = os.path.join(folder, lidar + str(index) + lidar_filetype) + pc = pc2_to_numpy(lidar_points, want_rgb=False) # convert lidar feed to numpy + np.savez(lidar_fn, pc) + + for camera in camera_images: + camera_image = camera_images[camera] + if camera_image != None: + camera_fn = os.path.join(folder, camera + str(index) + camera_filetype) + cv2.imwrite(camera_fn, bridge.imgmsg_to_cv2(camera_image)) + + for camera in depth_images: + depth_image = depth_images[camera] + if depth_image != None: + depth_fn = os.path.join(folder, camera + str(index) + depth_filetype) + dimage = bridge.imgmsg_to_cv2(depth_image) + dimage_non_nan = dimage[np.isfinite(dimage)] + dimage = np.nan_to_num(dimage,nan=0,posinf=0,neginf=0) + dimage = (dimage/4000*0xffff) + dimage = dimage.astype(np.uint16) + cv2.imwrite(depth_fn, dimage) - # for i in range(len(gnss_locations)): - # sat_fix = gnss_locations[i] - # gnss_fn = gnss_filenames + str(index) + gnss_filetype - if gnss_locations: - coordinates = np.array([gnss_locations.latitude, gnss_locations.longitude]) - np.save(gnss_fn + str(index) + gnss_filetype, coordinates) + for gnss in gnss_locations: + location = gnss_locations[gnss] + if location != None: + gnss_fn = os.path.join(folder, gnss + str(index) + gnss_filetype) + coordinates = np.array([location.latitude, location.longitude]) + np.save(gnss_fn + str(index) + gnss_filetype, coordinates) def main(folder='data',start_index=0): # Initialize node and establish subscribers rospy.init_node("capture_ouster_oak",disable_signals=True) - ouster_sub = rospy.Subscriber("/ouster/points", PointCloud2, lidar_callback) - # livox_sub = rospy.Subscriber("/livox/lidar", PointCloud2, lidar_callback) - oak_sub = rospy.Subscriber("/oak/rgb/image_raw", Image, camera_callback) - cam_fl_sub = rospy.Subscriber("/camera_fl/arena_camera_node/image_raw", Image, fl_camera_callback) - cam_fr_sub = rospy.Subscriber("/camera_fr/arena_camera_node/image_raw", Image, fr_camera_callback) - cam_rl_sub = rospy.Subscriber("/camera_rl/arena_camera_node/image_raw", Image, rl_camera_callback) - cam_rr_sub = rospy.Subscriber("/camera_rr/arena_camera_node/image_raw", Image, rr_camera_callback) - depth_sub = rospy.Subscriber("/oak/stereo/image_raw", Image, depth_callback) - gnss_sub = rospy.Subscriber("/septentrio_gnss/navsatfix", NavSatFix, gnss_callback) + ouster_sub = rospy.Subscriber("/ouster/points", PointCloud2, partial(lidar_callback, "ouster")) + livox_sub = rospy.Subscriber("/livox/lidar", PointCloud2, partial(lidar_callback, "livox")) + oak_sub = rospy.Subscriber("/oak/rgb/image_raw", Image, partial(camera_callback, "oak")) + cam_fl_sub = rospy.Subscriber("/camera_fl/arena_camera_node/image_raw", Image, partial(camera_callback, "fl")) + cam_fr_sub = rospy.Subscriber("/camera_fr/arena_camera_node/image_raw", Image, partial(camera_callback, "fr")) + cam_rl_sub = rospy.Subscriber("/camera_rl/arena_camera_node/image_raw", Image, partial(camera_callback, "rl")) + cam_rr_sub = rospy.Subscriber("/camera_rr/arena_camera_node/image_raw", Image, partial(camera_callback, "rr")) + cam_fl_rect_sub = rospy.Subscriber("/camera_fl/arena_camera_node/image_rect_color", Image, partial(camera_callback, "fl_rect")) + cam_fr_rect_sub = rospy.Subscriber("/camera_fr/arena_camera_node/image_rect_color", Image, partial(camera_callback, "fr_rect")) + cam_rl_rect_sub = rospy.Subscriber("/camera_rl/arena_camera_node/image_rect_color", Image, partial(camera_callback, "rl_rect")) + cam_rr_rect_sub = rospy.Subscriber("/camera_rr/arena_camera_node/image_rect_color", Image, partial(camera_callback, "rr_rect")) + depth_sub = rospy.Subscriber("/oak/stereo/image_raw", Image, partial(depth_callback, "depth")) + gnss_sub = rospy.Subscriber("/septentrio_gnss/navsatfix", NavSatFix, partial(gnss_callback, "nav_fix")) # Store scans index = start_index @@ -163,32 +135,13 @@ def main(folder='data',start_index=0): print(" Storing depth images as", depth_filetype) print(" Ctrl+C to quit") while True: - if camera_image: - cv2.imshow("result",bridge.imgmsg_to_cv2(camera_image)) + if camera_images["oak"]: + cv2.imshow("result",bridge.imgmsg_to_cv2(camera_images["oak"])) time.sleep(.5) - files = [os.path.join(folder, 'ouster'),os.path.join(folder, 'oak'), - os.path.join(folder, 'fl'), os.path.join(folder, 'fr'), - os.path.join(folder, 'rl'), os.path.join(folder, 'rr'), - os.path.join(folder, 'depth'), os.path.join(folder, 'septentrio')] - # lidar_files = [os.path.join(folder, 'ouster')] - # camera_files = [os.path.join(folder, 'oak'), - # os.path.join(folder, 'fl'), os.path.join(folder, 'fr'), - # os.path.join(folder, 'rl'), os.path.join(folder, 'rr')] - # depth_files = [os.path.join(folder, 'depth')] - # gnss_files = [os.path.join(folder, 'septentrio')] - save_scan(*files, index) - # clear_scan() + save_scan(folder, index) + clear_scan() index += 1 -# class StateTracker(Component): -# def rate(self): -# return 4.0 # Hz -# def state_inputs(self): -# return ['vehicle'] -# def update(self, vehicle : VehicleState): -# global frame_position -# frame_position = np.array(vehicle.pose.frame, vehicle.pose.t, vehicle.pose.x, vehicle.pose.y) - if __name__ == '__main__': import sys folder = 'data' From 19f7521c72d9a87d9f5ae5c967253d6b112af41d Mon Sep 17 00:00:00 2001 From: Michal Juscinski Date: Mon, 7 Apr 2025 20:25:19 -0700 Subject: [PATCH 201/232] Add camera intrinsics and minor changes in some calibration scripts --- .../camera_intrinsics/calibrated_fl.txt | 37 +++++++++++++++++++ .../camera_intrinsics/calibrated_fr.txt | 37 +++++++++++++++++++ .../camera_intrinsics/calibrated_rl.txt | 37 +++++++++++++++++++ .../camera_intrinsics/calibrated_rr.txt | 37 +++++++++++++++++++ .../knowledge/calibration/gem_e4_fl_in.yaml | 2 + .../knowledge/calibration/gem_e4_fr_in.yaml | 2 + .../knowledge/calibration/gem_e4_rl_in.yaml | 2 + .../knowledge/calibration/gem_e4_rr_in.yaml | 2 + GEMstack/offboard/calibration/img2pc.py | 2 +- 9 files changed, 157 insertions(+), 1 deletion(-) create mode 100755 GEMstack/knowledge/calibration/camera_intrinsics/calibrated_fl.txt create mode 100755 GEMstack/knowledge/calibration/camera_intrinsics/calibrated_fr.txt create mode 100755 GEMstack/knowledge/calibration/camera_intrinsics/calibrated_rl.txt create mode 100755 GEMstack/knowledge/calibration/camera_intrinsics/calibrated_rr.txt create mode 100644 GEMstack/knowledge/calibration/gem_e4_fl_in.yaml create mode 100644 GEMstack/knowledge/calibration/gem_e4_fr_in.yaml create mode 100644 GEMstack/knowledge/calibration/gem_e4_rl_in.yaml create mode 100644 GEMstack/knowledge/calibration/gem_e4_rr_in.yaml diff --git a/GEMstack/knowledge/calibration/camera_intrinsics/calibrated_fl.txt b/GEMstack/knowledge/calibration/camera_intrinsics/calibrated_fl.txt new file mode 100755 index 000000000..4ac9fb31e --- /dev/null +++ b/GEMstack/knowledge/calibration/camera_intrinsics/calibrated_fl.txt @@ -0,0 +1,37 @@ +**** Calibrating **** +mono pinhole calibration... +D = [-0.23751890570984993, 0.08452214195986749, -0.00035324203850054794, -0.0003762498910536819, 0.0] +K = [1230.1440959825889, 0.0, 978.8285075011214, 0.0, 1230.6304235898162, 605.7940335714893, 0.0, 0.0, 1.0] +R = [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0] +P = [1060.7667306621374, 0.0, 981.9084026840044, 0.0, 0.0, 1159.9175090232534, 606.1729100950629, 0.0, 0.0, 0.0, 1.0, 0.0] +None +# oST version 5.0 parameters + + +[image] + +width +1920 + +height +1200 + +[narrow_stereo] + +camera matrix +1230.144096 0.000000 978.828508 +0.000000 1230.630424 605.794034 +0.000000 0.000000 1.000000 + +distortion +-0.237519 0.084522 -0.000353 -0.000376 0.000000 + +rectification +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 1.000000 + +projection +1060.766731 0.000000 981.908403 0.000000 +0.000000 1159.917509 606.172910 0.000000 +0.000000 0.000000 1.000000 0.000000 \ No newline at end of file diff --git a/GEMstack/knowledge/calibration/camera_intrinsics/calibrated_fr.txt b/GEMstack/knowledge/calibration/camera_intrinsics/calibrated_fr.txt new file mode 100755 index 000000000..31e4e111d --- /dev/null +++ b/GEMstack/knowledge/calibration/camera_intrinsics/calibrated_fr.txt @@ -0,0 +1,37 @@ +**** Calibrating **** +mono pinhole calibration... +D = [-0.2448506795091457, 0.08202383880344215, 0.0004294271518916802, -0.0012454354245869965, 0.0] +K = [1180.753803927752, 0.0, 934.8594468810093, 0.0, 1177.034929104844, 607.2669740236552, 0.0, 0.0, 1.0] +R = [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0] +P = [995.519995797456, 0.0, 923.4562756312389, 0.0, 0.0, 1099.6556283728762, 608.8885739196182, 0.0, 0.0, 0.0, 1.0, 0.0] +None +# oST version 5.0 parameters + + +[image] + +width +1920 + +height +1200 + +[narrow_stereo] + +camera matrix +1180.753804 0.000000 934.859447 +0.000000 1177.034929 607.266974 +0.000000 0.000000 1.000000 + +distortion +-0.244851 0.082024 0.000429 -0.001245 0.000000 + +rectification +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 1.000000 + +projection +995.519996 0.000000 923.456276 0.000000 +0.000000 1099.655628 608.888574 0.000000 +0.000000 0.000000 1.000000 0.000000 diff --git a/GEMstack/knowledge/calibration/camera_intrinsics/calibrated_rl.txt b/GEMstack/knowledge/calibration/camera_intrinsics/calibrated_rl.txt new file mode 100755 index 000000000..c019d274b --- /dev/null +++ b/GEMstack/knowledge/calibration/camera_intrinsics/calibrated_rl.txt @@ -0,0 +1,37 @@ +**** Calibrating **** +mono pinhole calibration... +D = [-0.24343640079788503, 0.09125282937288573, 5.21454371097206e-06, -2.2750254391060847e-05, 0.0] +K = [1216.836137433559, 0.0, 955.7290895142494, 0.0, 1216.0457208793944, 599.3150429290699, 0.0, 0.0, 1.0] +R = [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0] +P = [1046.2719621718043, 0.0, 954.838848203849, 0.0, 0.0, 1143.0056282011747, 599.2973574785816, 0.0, 0.0, 0.0, 1.0, 0.0] +None +# oST version 5.0 parameters + + +[image] + +width +1920 + +height +1200 + +[narrow_stereo] + +camera matrix +1216.836137 0.000000 955.729090 +0.000000 1216.045721 599.315043 +0.000000 0.000000 1.000000 + +distortion +-0.243436 0.091253 0.000005 -0.000023 0.000000 + +rectification +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 1.000000 + +projection +1046.271962 0.000000 954.838848 0.000000 +0.000000 1143.005628 599.297357 0.000000 +0.000000 0.000000 1.000000 0.000000 diff --git a/GEMstack/knowledge/calibration/camera_intrinsics/calibrated_rr.txt b/GEMstack/knowledge/calibration/camera_intrinsics/calibrated_rr.txt new file mode 100755 index 000000000..d1bb29ee1 --- /dev/null +++ b/GEMstack/knowledge/calibration/camera_intrinsics/calibrated_rr.txt @@ -0,0 +1,37 @@ +**** Calibrating **** +mono pinhole calibration... +D = [-0.24754745389508612, 0.09944435338953724, -3.455420573094537e-05, -0.00022029168609146265, 0.0] +K = [1210.2941870955246, 0.0, 951.3029561113208, 0.0, 1211.035575904068, 600.5637386855253, 0.0, 0.0, 1.0] +R = [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0] +P = [1042.941578923699, 0.0, 948.9910317286675, 0.0, 0.0, 1136.9823670862872, 600.6610182272711, 0.0, 0.0, 0.0, 1.0, 0.0] +None +# oST version 5.0 parameters + + +[image] + +width +1920 + +height +1200 + +[narrow_stereo] + +camera matrix +1210.294187 0.000000 951.302956 +0.000000 1211.035576 600.563739 +0.000000 0.000000 1.000000 + +distortion +-0.247547 0.099444 -0.000035 -0.000220 0.000000 + +rectification +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 1.000000 + +projection +1042.941579 0.000000 948.991032 0.000000 +0.000000 1136.982367 600.661018 0.000000 +0.000000 0.000000 1.000000 0.000000 \ No newline at end of file diff --git a/GEMstack/knowledge/calibration/gem_e4_fl_in.yaml b/GEMstack/knowledge/calibration/gem_e4_fl_in.yaml new file mode 100644 index 000000000..5fbbf0d45 --- /dev/null +++ b/GEMstack/knowledge/calibration/gem_e4_fl_in.yaml @@ -0,0 +1,2 @@ +center: [978.828508, 605.794034] +focal: [1230.144096, 1230.630424] diff --git a/GEMstack/knowledge/calibration/gem_e4_fr_in.yaml b/GEMstack/knowledge/calibration/gem_e4_fr_in.yaml new file mode 100644 index 000000000..55b5e2ab6 --- /dev/null +++ b/GEMstack/knowledge/calibration/gem_e4_fr_in.yaml @@ -0,0 +1,2 @@ +center: [934.859447, 607.266974] +focal: [1180.753804, 1177.034929] diff --git a/GEMstack/knowledge/calibration/gem_e4_rl_in.yaml b/GEMstack/knowledge/calibration/gem_e4_rl_in.yaml new file mode 100644 index 000000000..b0c50960c --- /dev/null +++ b/GEMstack/knowledge/calibration/gem_e4_rl_in.yaml @@ -0,0 +1,2 @@ +center: [955.729090, 599.315043] +focal: [1216.836137, 1216.045721] diff --git a/GEMstack/knowledge/calibration/gem_e4_rr_in.yaml b/GEMstack/knowledge/calibration/gem_e4_rr_in.yaml new file mode 100644 index 000000000..12ae4f9ce --- /dev/null +++ b/GEMstack/knowledge/calibration/gem_e4_rr_in.yaml @@ -0,0 +1,2 @@ +center: [951.302956, 600.563739] +focal: [1210.294187, 1211.035576] diff --git a/GEMstack/offboard/calibration/img2pc.py b/GEMstack/offboard/calibration/img2pc.py index 846bc4902..de56d881d 100644 --- a/GEMstack/offboard/calibration/img2pc.py +++ b/GEMstack/offboard/calibration/img2pc.py @@ -86,7 +86,7 @@ def main(): T=np.eye(4) T[:3, :3] = R T[:3, 3] = tvec.flatten() - print(T) + print(repr(T)) v2c = T print('vehicle->camera:',v2c) From d8c79db98464a143b8af22ef7d23bf8d588f26a5 Mon Sep 17 00:00:00 2001 From: Michal Juscinski Date: Mon, 7 Apr 2025 20:25:19 -0700 Subject: [PATCH 202/232] Add camera intrinsics and minor changes in some calibration scripts --- .../camera_intrinsics/calibrated_fl.txt | 37 +++++++++++++++++++ .../camera_intrinsics/calibrated_fr.txt | 37 +++++++++++++++++++ .../camera_intrinsics/calibrated_rl.txt | 37 +++++++++++++++++++ .../camera_intrinsics/calibrated_rr.txt | 37 +++++++++++++++++++ .../knowledge/calibration/gem_e4_fl_in.yaml | 2 + .../knowledge/calibration/gem_e4_fr_in.yaml | 2 + .../knowledge/calibration/gem_e4_rl_in.yaml | 2 + .../knowledge/calibration/gem_e4_rr_in.yaml | 2 + GEMstack/offboard/calibration/img2pc.py | 2 +- 9 files changed, 157 insertions(+), 1 deletion(-) create mode 100755 GEMstack/knowledge/calibration/camera_intrinsics/calibrated_fl.txt create mode 100755 GEMstack/knowledge/calibration/camera_intrinsics/calibrated_fr.txt create mode 100755 GEMstack/knowledge/calibration/camera_intrinsics/calibrated_rl.txt create mode 100755 GEMstack/knowledge/calibration/camera_intrinsics/calibrated_rr.txt create mode 100644 GEMstack/knowledge/calibration/gem_e4_fl_in.yaml create mode 100644 GEMstack/knowledge/calibration/gem_e4_fr_in.yaml create mode 100644 GEMstack/knowledge/calibration/gem_e4_rl_in.yaml create mode 100644 GEMstack/knowledge/calibration/gem_e4_rr_in.yaml diff --git a/GEMstack/knowledge/calibration/camera_intrinsics/calibrated_fl.txt b/GEMstack/knowledge/calibration/camera_intrinsics/calibrated_fl.txt new file mode 100755 index 000000000..4ac9fb31e --- /dev/null +++ b/GEMstack/knowledge/calibration/camera_intrinsics/calibrated_fl.txt @@ -0,0 +1,37 @@ +**** Calibrating **** +mono pinhole calibration... +D = [-0.23751890570984993, 0.08452214195986749, -0.00035324203850054794, -0.0003762498910536819, 0.0] +K = [1230.1440959825889, 0.0, 978.8285075011214, 0.0, 1230.6304235898162, 605.7940335714893, 0.0, 0.0, 1.0] +R = [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0] +P = [1060.7667306621374, 0.0, 981.9084026840044, 0.0, 0.0, 1159.9175090232534, 606.1729100950629, 0.0, 0.0, 0.0, 1.0, 0.0] +None +# oST version 5.0 parameters + + +[image] + +width +1920 + +height +1200 + +[narrow_stereo] + +camera matrix +1230.144096 0.000000 978.828508 +0.000000 1230.630424 605.794034 +0.000000 0.000000 1.000000 + +distortion +-0.237519 0.084522 -0.000353 -0.000376 0.000000 + +rectification +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 1.000000 + +projection +1060.766731 0.000000 981.908403 0.000000 +0.000000 1159.917509 606.172910 0.000000 +0.000000 0.000000 1.000000 0.000000 \ No newline at end of file diff --git a/GEMstack/knowledge/calibration/camera_intrinsics/calibrated_fr.txt b/GEMstack/knowledge/calibration/camera_intrinsics/calibrated_fr.txt new file mode 100755 index 000000000..31e4e111d --- /dev/null +++ b/GEMstack/knowledge/calibration/camera_intrinsics/calibrated_fr.txt @@ -0,0 +1,37 @@ +**** Calibrating **** +mono pinhole calibration... +D = [-0.2448506795091457, 0.08202383880344215, 0.0004294271518916802, -0.0012454354245869965, 0.0] +K = [1180.753803927752, 0.0, 934.8594468810093, 0.0, 1177.034929104844, 607.2669740236552, 0.0, 0.0, 1.0] +R = [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0] +P = [995.519995797456, 0.0, 923.4562756312389, 0.0, 0.0, 1099.6556283728762, 608.8885739196182, 0.0, 0.0, 0.0, 1.0, 0.0] +None +# oST version 5.0 parameters + + +[image] + +width +1920 + +height +1200 + +[narrow_stereo] + +camera matrix +1180.753804 0.000000 934.859447 +0.000000 1177.034929 607.266974 +0.000000 0.000000 1.000000 + +distortion +-0.244851 0.082024 0.000429 -0.001245 0.000000 + +rectification +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 1.000000 + +projection +995.519996 0.000000 923.456276 0.000000 +0.000000 1099.655628 608.888574 0.000000 +0.000000 0.000000 1.000000 0.000000 diff --git a/GEMstack/knowledge/calibration/camera_intrinsics/calibrated_rl.txt b/GEMstack/knowledge/calibration/camera_intrinsics/calibrated_rl.txt new file mode 100755 index 000000000..c019d274b --- /dev/null +++ b/GEMstack/knowledge/calibration/camera_intrinsics/calibrated_rl.txt @@ -0,0 +1,37 @@ +**** Calibrating **** +mono pinhole calibration... +D = [-0.24343640079788503, 0.09125282937288573, 5.21454371097206e-06, -2.2750254391060847e-05, 0.0] +K = [1216.836137433559, 0.0, 955.7290895142494, 0.0, 1216.0457208793944, 599.3150429290699, 0.0, 0.0, 1.0] +R = [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0] +P = [1046.2719621718043, 0.0, 954.838848203849, 0.0, 0.0, 1143.0056282011747, 599.2973574785816, 0.0, 0.0, 0.0, 1.0, 0.0] +None +# oST version 5.0 parameters + + +[image] + +width +1920 + +height +1200 + +[narrow_stereo] + +camera matrix +1216.836137 0.000000 955.729090 +0.000000 1216.045721 599.315043 +0.000000 0.000000 1.000000 + +distortion +-0.243436 0.091253 0.000005 -0.000023 0.000000 + +rectification +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 1.000000 + +projection +1046.271962 0.000000 954.838848 0.000000 +0.000000 1143.005628 599.297357 0.000000 +0.000000 0.000000 1.000000 0.000000 diff --git a/GEMstack/knowledge/calibration/camera_intrinsics/calibrated_rr.txt b/GEMstack/knowledge/calibration/camera_intrinsics/calibrated_rr.txt new file mode 100755 index 000000000..d1bb29ee1 --- /dev/null +++ b/GEMstack/knowledge/calibration/camera_intrinsics/calibrated_rr.txt @@ -0,0 +1,37 @@ +**** Calibrating **** +mono pinhole calibration... +D = [-0.24754745389508612, 0.09944435338953724, -3.455420573094537e-05, -0.00022029168609146265, 0.0] +K = [1210.2941870955246, 0.0, 951.3029561113208, 0.0, 1211.035575904068, 600.5637386855253, 0.0, 0.0, 1.0] +R = [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0] +P = [1042.941578923699, 0.0, 948.9910317286675, 0.0, 0.0, 1136.9823670862872, 600.6610182272711, 0.0, 0.0, 0.0, 1.0, 0.0] +None +# oST version 5.0 parameters + + +[image] + +width +1920 + +height +1200 + +[narrow_stereo] + +camera matrix +1210.294187 0.000000 951.302956 +0.000000 1211.035576 600.563739 +0.000000 0.000000 1.000000 + +distortion +-0.247547 0.099444 -0.000035 -0.000220 0.000000 + +rectification +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 1.000000 + +projection +1042.941579 0.000000 948.991032 0.000000 +0.000000 1136.982367 600.661018 0.000000 +0.000000 0.000000 1.000000 0.000000 \ No newline at end of file diff --git a/GEMstack/knowledge/calibration/gem_e4_fl_in.yaml b/GEMstack/knowledge/calibration/gem_e4_fl_in.yaml new file mode 100644 index 000000000..5fbbf0d45 --- /dev/null +++ b/GEMstack/knowledge/calibration/gem_e4_fl_in.yaml @@ -0,0 +1,2 @@ +center: [978.828508, 605.794034] +focal: [1230.144096, 1230.630424] diff --git a/GEMstack/knowledge/calibration/gem_e4_fr_in.yaml b/GEMstack/knowledge/calibration/gem_e4_fr_in.yaml new file mode 100644 index 000000000..55b5e2ab6 --- /dev/null +++ b/GEMstack/knowledge/calibration/gem_e4_fr_in.yaml @@ -0,0 +1,2 @@ +center: [934.859447, 607.266974] +focal: [1180.753804, 1177.034929] diff --git a/GEMstack/knowledge/calibration/gem_e4_rl_in.yaml b/GEMstack/knowledge/calibration/gem_e4_rl_in.yaml new file mode 100644 index 000000000..b0c50960c --- /dev/null +++ b/GEMstack/knowledge/calibration/gem_e4_rl_in.yaml @@ -0,0 +1,2 @@ +center: [955.729090, 599.315043] +focal: [1216.836137, 1216.045721] diff --git a/GEMstack/knowledge/calibration/gem_e4_rr_in.yaml b/GEMstack/knowledge/calibration/gem_e4_rr_in.yaml new file mode 100644 index 000000000..12ae4f9ce --- /dev/null +++ b/GEMstack/knowledge/calibration/gem_e4_rr_in.yaml @@ -0,0 +1,2 @@ +center: [951.302956, 600.563739] +focal: [1210.294187, 1211.035576] diff --git a/GEMstack/offboard/calibration/img2pc.py b/GEMstack/offboard/calibration/img2pc.py index 846bc4902..de56d881d 100644 --- a/GEMstack/offboard/calibration/img2pc.py +++ b/GEMstack/offboard/calibration/img2pc.py @@ -86,7 +86,7 @@ def main(): T=np.eye(4) T[:3, :3] = R T[:3, 3] = tvec.flatten() - print(T) + print(repr(T)) v2c = T print('vehicle->camera:',v2c) From a316c63c4b0212c16a0b1e7919739fc5cf207079 Mon Sep 17 00:00:00 2001 From: rjsun-KA <92330153+rjsun06@users.noreply.github.com> Date: Sun, 13 Apr 2025 05:25:10 +0000 Subject: [PATCH 203/232] SfM with hand-eye calibration --- .../knowledge/calibration/gem_e4_rr_in.yaml | 4 + .../calibration/calibration_by_SfM/README.md | 10 + .../calibration_by_SfM/SfM_handeye.py | 191 ++++++++++++++++++ .../data/.gitignore | 3 +- .../calibration_by_segmentation/.gitignore | 5 + .../calibration_by_segmentation/calib.bash | 3 +- .../data/fl/calib.json | 25 +-- .../make_dataset.py | 3 +- .../calibration_by_segmentation/npz_to_pcd.py | 5 +- GEMstack/offboard/calibration/img2pc.py | 99 +++++++-- .../offboard/calibration/lidar_to_vehicle.py | 2 +- .../offboard/calibration/manual_fine_tune.py | 144 +++++++++++++ .../offboard/calibration/test_transforms.py | 22 +- .../offboard/calibration/tools/__init__.py | 0 .../offboard/calibration/tools/save_cali.py | 17 +- 15 files changed, 476 insertions(+), 57 deletions(-) create mode 100644 GEMstack/knowledge/calibration/gem_e4_rr_in.yaml create mode 100644 GEMstack/offboard/calibration/calibration_by_SfM/README.md create mode 100644 GEMstack/offboard/calibration/calibration_by_SfM/SfM_handeye.py rename GEMstack/offboard/calibration/{calibration_by_segmentation => calibration_by_SfM}/data/.gitignore (50%) create mode 100644 GEMstack/offboard/calibration/manual_fine_tune.py create mode 100644 GEMstack/offboard/calibration/tools/__init__.py diff --git a/GEMstack/knowledge/calibration/gem_e4_rr_in.yaml b/GEMstack/knowledge/calibration/gem_e4_rr_in.yaml new file mode 100644 index 000000000..f55460559 --- /dev/null +++ b/GEMstack/knowledge/calibration/gem_e4_rr_in.yaml @@ -0,0 +1,4 @@ +center: [950, 600] +focal: [1210,1210] +distort: [-0.24754745389508612, 0.09944435338953724, -3.455420573094537e-05, -0.00022029168609146265, 0.0] +skew: 0.0 diff --git a/GEMstack/offboard/calibration/calibration_by_SfM/README.md b/GEMstack/offboard/calibration/calibration_by_SfM/README.md new file mode 100644 index 000000000..2f3937738 --- /dev/null +++ b/GEMstack/offboard/calibration/calibration_by_SfM/README.md @@ -0,0 +1,10 @@ +data directory looks like +|-data +||-fl +|||-images +||||-000001.png +||-oak +||-rl +||-... +||-pc +|||-000001.pcd diff --git a/GEMstack/offboard/calibration/calibration_by_SfM/SfM_handeye.py b/GEMstack/offboard/calibration/calibration_by_SfM/SfM_handeye.py new file mode 100644 index 000000000..c215084ed --- /dev/null +++ b/GEMstack/offboard/calibration/calibration_by_SfM/SfM_handeye.py @@ -0,0 +1,191 @@ +#%% +import cv2 +import open3d as o3d +import numpy as np +import pyvista as pv +from typing import Literal +from tqdm import tqdm +#%% +import os +os.chdir('/mnt/GEMstack/GEMstack/offboard/calibration') +from tools.save_cali import * +#%% +N_PAIRS = 20 +STEP = 3 +cam = 'rr' + +#%% +def get_shape(): + return 1920,1200 + +def getK(): + K_path = f"/mnt/GEMstack/GEMstack/knowledge/calibration/gem_e4_{cam}_in.yaml" + K, distort = load_in(K_path,mode='matrix',return_distort=True) + w,h = get_shape() + newK, roi = cv2.getOptimalNewCameraMatrix(K, distort, (w,h), 1, (w,h)) + return newK + +def get_img_np(img_path): + K_path = f"/mnt/GEMstack/GEMstack/knowledge/calibration/gem_e4_{cam}_in.yaml" + K, distort = load_in(K_path,mode='matrix',return_distort=True) + img = cv2.imread(img_path, cv2.IMREAD_GRAYSCALE) + undistorted = cv2.undistort(img, K, distort) + return np.asarray(undistorted) + +def get_pc_np(pcd_path): + pcd = o3d.io.read_point_cloud(pcd_path) + pc = np.asarray(pcd.points) + pc = pc[~np.all(pc == 0, axis=1)] # remove (0,0,0)'s + return pc + +def vis(pc): + plotter = pv.Plotter(notebook=False) + # plotter = pv.Plotter() + plotter.add_mesh( + pv.PolyData(pc), + render_points_as_spheres=True, + point_size=2, + color='red' + ) + plotter.show() + +#%% +def pcd_paths(): + img_root = '/mnt/GEMstack/GEMstack/offboard/calibration/calibration_by_SfM/data/pc/' + img_format = '.pcd' + for id in range(0,N_PAIRS*STEP+1): + path = img_root + str(id).zfill(6) + img_format + print(path) + yield path + +def img_paths(): + img_root = f'/mnt/GEMstack/GEMstack/offboard/calibration/calibration_by_SfM/data/{cam}/images/' + img_format = '.png' + for id in range(0,N_PAIRS*STEP+1): + path = img_root + str(id).zfill(6) + img_format + print(path) + yield path + +def pcs(): + for path in pcd_paths(): + yield get_pc_np(path) + +def imgs(): + for path in img_paths(): + yield get_img_np(path) + +def iterpair(iter,step): + pre = None + for i in iter: + pre = i + break + for i,v in enumerate(iter): + if i%step == step-1: + yield pre,v + pre = v + +#%% +def findE_img(img1,img2,K): + sift = cv2.SIFT.create() + kp1,des1 = sift.detectAndCompute(img1,None) + kp2,des2 = sift.detectAndCompute(img2,None) + + if des1 is None or des2 is None or len(des1) < 5 or len(des2) < 5: + return None #insufficient features + + FLANN_INDEX_KDTREE = 1 + index_params = dict(algorithm=FLANN_INDEX_KDTREE, trees=5) + search_params = dict(checks=50) + flann = cv2.FlannBasedMatcher(index_params, search_params) + matches = flann.knnMatch(des1, des2, k=2) + good_matches = [m for m,n in matches if m.distance < 0.8 * n.distance] + + pts1 = np.float32([kp1[m.queryIdx].pt for m in good_matches]).reshape(-1, 2) + pts2 = np.float32([kp2[m.trainIdx].pt for m in good_matches]).reshape(-1, 2) + + E, mask = cv2.findEssentialMat(pts1, pts2, K, method=cv2.RANSAC, prob=0.999, threshold=1.0) + if E is None or mask.sum() < 5: + return None #Essential matrix computation failed + _, R_rel, t_rel, mask = cv2.recoverPose(E, pts1, pts2, K, mask=mask) + ret = np.eye(4) + ret[:3, :3] = R_rel + ret[:3, 3] = t_rel.flatten() + return ret + +def findE_pc(pc1,pc2,mode:Literal['icp','kp','svd']): + if mode == 'icp': + source = o3d.geometry.PointCloud() + source.points = o3d.utility.Vector3dVector(pc1) + + target = o3d.geometry.PointCloud() + target.points = o3d.utility.Vector3dVector(pc2) + + source.estimate_normals( + search_param=o3d.geometry.KDTreeSearchParamHybrid(radius=0.1, max_nn=30) + ) + target.estimate_normals( + search_param=o3d.geometry.KDTreeSearchParamHybrid(radius=0.1, max_nn=30) + ) + init_pose = np.eye(4) #assume continuous movement + # Robust configuration + reg = o3d.pipelines.registration.registration_icp( + source, target, + 0.1, + init_pose, + o3d.pipelines.registration.TransformationEstimationPointToPoint(), + o3d.pipelines.registration.ICPConvergenceCriteria( + max_iteration=30, + relative_rmse=1e-6 + ) + ) + return reg.transformation + else: + print(mode,'no imp') + return None + +#%% +rcam, tcam = [],[] +rlidar, tlidar = [],[] +#%% +for i,((img1,img2),(pc1,pc2)) in tqdm(enumerate(zip( + iterpair(map(get_img_np,img_paths()),STEP), + iterpair(map(get_pc_np,pcd_paths()),STEP))),total=N_PAIRS): + K = getK() + E_cam = findE_img(img1,img2,K) + print(E_cam) + E_lidar = findE_pc(pc1,pc2,mode='icp') + print(E_lidar) + if E_cam is None or E_lidar is None: + continue #unsolved + if np.isnan(E_cam).any() or np.isnan(E_lidar).any(): + continue #has nan + if np.linalg.norm(E_lidar[:3,3]) > 0.1*STEP: + continue #too large to be possible + rcam.append(E_cam[:3, :3]) + tcam.append(E_cam[:3, 3]) + rlidar.append(E_lidar[:3, :3]) + tlidar.append(E_lidar[:3, 3]) + +#%% +rt2cam = [] +tt2cam = [] +for r,t in zip(rlidar,tlidar): + B = np.eye(4) + B[:3,:3] = r + B[:3,3] = t + B = np.linalg.inv(B) + rt2cam.append(B[:3,:3]) + tt2cam.append(B[:3,3]) + +X = cv2.calibrateHandEye( + R_gripper2base=rcam, t_gripper2base=tcam, + R_target2cam=rt2cam, t_target2cam=tt2cam, + # R_target2cam=rlidar, t_target2cam=tlidar, + # method=cv2.CALIB_HAND_EYE_TSAI + method=cv2.CALIB_HAND_EYE_PARK +) +#%% +# Result is 4x4 transformation matrix: T_cam_lidar +T_cam_lidar = np.eye(4) +T_cam_lidar[:3, :3] = X[0] +T_cam_lidar[:3, 3] = X[1].flatten() diff --git a/GEMstack/offboard/calibration/calibration_by_segmentation/data/.gitignore b/GEMstack/offboard/calibration/calibration_by_SfM/data/.gitignore similarity index 50% rename from GEMstack/offboard/calibration/calibration_by_segmentation/data/.gitignore rename to GEMstack/offboard/calibration/calibration_by_SfM/data/.gitignore index 6982f8410..c96a04f00 100644 --- a/GEMstack/offboard/calibration/calibration_by_segmentation/data/.gitignore +++ b/GEMstack/offboard/calibration/calibration_by_SfM/data/.gitignore @@ -1,3 +1,2 @@ -*/*/* -pc/* +* !.gitignore \ No newline at end of file diff --git a/GEMstack/offboard/calibration/calibration_by_segmentation/.gitignore b/GEMstack/offboard/calibration/calibration_by_segmentation/.gitignore index 4d776b98f..0197c8cd8 100644 --- a/GEMstack/offboard/calibration/calibration_by_segmentation/.gitignore +++ b/GEMstack/offboard/calibration/calibration_by_segmentation/.gitignore @@ -1,2 +1,7 @@ sam_vit_h.pth +sam_vit_b.pth +init_proj* +refined_proj* +data/* +extrinsic.txt !.gitignore diff --git a/GEMstack/offboard/calibration/calibration_by_segmentation/calib.bash b/GEMstack/offboard/calibration/calibration_by_segmentation/calib.bash index 10d55d950..dbbd230ae 100644 --- a/GEMstack/offboard/calibration/calibration_by_segmentation/calib.bash +++ b/GEMstack/offboard/calibration/calibration_by_segmentation/calib.bash @@ -3,9 +3,8 @@ data=$1 wget -c -O sam_vit_b.pth https://dl.fbaipublicfiles.com/segment_anything/sam_vit_b_01ec64.pth # wget -c -O sam_vit_h.pth https://dl.fbaipublicfiles.com/segment_anything/sam_vit_h_4b8939.pth -cd segment-anything; pip install -e .; cd .. echo 'running segmentation...' -python3 segment-anything/scripts/amg.py --checkpoint sam_vit_b.pth --model-type vit_b --input $data/images --output $data/masks/ --stability-score-thresh 0.9 --box-nms-thresh 0.5 --stability-score-offset 0.9 +python3 segment-anything/scripts/amg.py --checkpoint sam_vit_b.pth --model-type vit_b --input $data/selected --output $data/masks/ --stability-score-thresh 0.9 --box-nms-thresh 0.5 --stability-score-offset 0.9 # python3 segment-anything/scripts/amg.py --checkpoint sam_vit_h.pth --model-type vit_h --input $data/images --output $data/masks/ --stability-score-thresh 0.9 --box-nms-thresh 0.5 --stability-score-offset 0.9 echo 'reprocess segmentation...' diff --git a/GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/calib.json b/GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/calib.json index 939da7abd..e3f633280 100644 --- a/GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/calib.json +++ b/GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/calib.json @@ -15,26 +15,23 @@ "T_lidar_to_cam":{ "rows": 4, "cols": 4, - "data": [[ 0.72 , -0.694, 0.014, 0.12 ], - [-0.166, -0.191, -0.967, 0.09 ], - [ 0.673, 0.694, -0.253, -1.17 ], - [ 0 , 0 , 0 , 1 ]] + "data": [[ 0.62707208, -0.77887383, -0.0116692 , 0.63835046], + [-0.10590946, -0.07040732, -0.99188003, -0.67206479], + [ 0.7717278 , 0.62321615, -0.12664056, -1.06795501], + [ 0 , 0 , 0 , 1 ]] }, - "img_folder": "images", + "img_folder": "selected", "mask_folder": "processed_masks", "pc_folder": "../pc", + "img_prefix": "fl", "img_format": ".png", + "pc_prefix": "ouster", "pc_format": ".pcd", "file_name": [ - "000000", - "000001", - "000002", - "000003", - "000004", - "000005", - "000006", - "000007", - "000008" + "b9", + "33", + "37", + "38" ], "params": { "min_plane_point_num": 2000, diff --git a/GEMstack/offboard/calibration/calibration_by_segmentation/make_dataset.py b/GEMstack/offboard/calibration/calibration_by_segmentation/make_dataset.py index 9e0224c59..15d742184 100644 --- a/GEMstack/offboard/calibration/calibration_by_segmentation/make_dataset.py +++ b/GEMstack/offboard/calibration/calibration_by_segmentation/make_dataset.py @@ -28,6 +28,7 @@ def write_pcd(pc_msg, filename): with open(filename, 'w') as f: f.write(header) for p in points: + if p[0] == 0 and p[1] == 0 and p[2] == 0: continue f.write(f"{p[0]} {p[1]} {p[2]}\n") def process_bag(bag_path, output_dir='sync_dataset', time_threshold=0.05): @@ -120,4 +121,4 @@ def process_bag(bag_path, output_dir='sync_dataset', time_threshold=0.05): bag.close() # Example usage -process_bag('/mnt/GEMstack/data/mybag_2025-04-01-17-41-55.bag','/mnt/GEMstack/GEMstack/offboard/calibration/calibration_by_segmentation/data') \ No newline at end of file +process_bag('/mnt/GEMstack/data/mybag_2025-04-01-17-41-55.bag','/mnt/GEMstack/GEMstack/offboard/calibration/calibration_by_SfM/data') \ No newline at end of file diff --git a/GEMstack/offboard/calibration/calibration_by_segmentation/npz_to_pcd.py b/GEMstack/offboard/calibration/calibration_by_segmentation/npz_to_pcd.py index e4a7bcbbd..ddbc89e29 100644 --- a/GEMstack/offboard/calibration/calibration_by_segmentation/npz_to_pcd.py +++ b/GEMstack/offboard/calibration/calibration_by_segmentation/npz_to_pcd.py @@ -23,7 +23,8 @@ def npz_to_pcd(input_dir, output_dir, data_key='arr_0'): continue point_cloud_np = data[data_key] - + mask = ~(np.all(point_cloud_np == [0, 0, 0], axis=1)) + point_cloud_np = point_cloud_np[mask] # Validate shape (Nx3 for XYZ, Nx6 for XYZRGB, etc.) if point_cloud_np.ndim != 2 or point_cloud_np.shape[1] < 3: print(f"Skipping {npz_file}: Invalid shape {point_cloud_np.shape}.") @@ -34,7 +35,7 @@ def npz_to_pcd(input_dir, output_dir, data_key='arr_0'): # Assign points (required: Nx3 array) pcd.points = o3d.utility.Vector3dVector(point_cloud_np[:, :3]) - + # Optionally assign colors (if available, e.g., Nx6 array with RGB) if point_cloud_np.shape[1] >= 6: # RGB values (assuming they are stored as 0-255 integers) diff --git a/GEMstack/offboard/calibration/img2pc.py b/GEMstack/offboard/calibration/img2pc.py index 5eaf1a4cc..adca936db 100644 --- a/GEMstack/offboard/calibration/img2pc.py +++ b/GEMstack/offboard/calibration/img2pc.py @@ -4,6 +4,8 @@ import cv2 import numpy as np from tools.save_cali import load_ex,save_ex,load_in,save_in +from scipy.spatial.transform import Rotation as R +from transform3d import Transform #%% def pick_n_img(img,n=4): corners = [] # Reset the corners list @@ -42,6 +44,52 @@ def cb(pt,*args): plotter.show() return points +#%% +def pc_projection(pc,T:Transform,K,img_shape) -> np.ndarray: + mask = ~(np.all(pc == 0, axis=1)) + pc = pc[mask] + + pc = T @ pc + if pc.shape[1] == 4: + pc = pc[:,:-1]/pc[:,[-1]] + + assert pc.shape[1] == 3 + x,y,z = pc.T + u = (K[0, 0] * x / z) + K[0, 2] + v = (K[1, 1] * y / z) + K[1, 2] + + img_h, img_w, _ = img_shape + valid_pts = (u >= 0) & (u < img_w) & (v >= 0) & (v < img_h) + return u[valid_pts],v[valid_pts] + + + + + +def calib(args,pc,img,K,N): + cpoints = np.array(pick_n_img(img,N)).astype(float) + print(cpoints) + + lpoints = np.array(pick_n_pc(pc,N)) + print(lpoints) + + success, rvec, tvec = cv2.solvePnP(lpoints, cpoints, K, None) + R, _ = cv2.Rodrigues(rvec) + + T=np.eye(4) + T[:3, :3] = R + T[:3, 3] = tvec.flatten() + print(T) + + v2c = T + print('vehicle->camera:',v2c) + c2v = np.linalg.inv(v2c) + print('camera->vehicle:',c2v) + + if args.out_path is not None: + save_ex(args.out_path,matrix=c2v) + + #%% def main(): parser = argparse.ArgumentParser(description='register image into point cloud using manual feature selection', @@ -58,6 +106,12 @@ def main(): help='Path to output ymal file for image extrinsics') parser.add_argument('--n_features', type=int, required=False, default=8, help='number of features to select and math') + parser.add_argument('-u','--undistort', action='store_true', + help='whether to use distortion parameters') + parser.add_argument('--fine_tune', choices=['manual'], required=False, + help='how to fine tune after first guess') + parser.add_argument('--just_projection', action='store_true', + help='just show the projection. No calibration') args = parser.parse_args() @@ -68,35 +122,40 @@ def main(): pc = np.load(args.pc_path)['arr_0'] pc = pc[~np.all(pc == 0, axis=1)] # remove (0,0,0)'s - camera_in = load_in(args.img_intrinsics_path,mode='matrix') + if args.undistort: + K, distort = load_in(args.img_intrinsics_path,mode='matrix',return_distort=True) + print('applying distortion coeffs', distort) + h, w = img.shape[:2] + newK, roi = cv2.getOptimalNewCameraMatrix(K, distort, (w,h), 1, (w,h)) + img = cv2.undistort(img, K, distort, None, newK) + K = newK + else: + K = load_in(args.img_intrinsics_path,mode='matrix') if args.pc_transform_path is not None: lidar_ex = load_ex(args.pc_transform_path,mode='matrix') pc = np.pad(pc,((0,0),(0,1)),constant_values=1) @ lidar_ex.T[:,:3] - cpoints = np.array(pick_n_img(img,N)).astype(float) - print(cpoints) + if not args.just_projection: + calib(args,pc,img,K,N) - lpoints = np.array(pick_n_pc(pc,N)) - print(lpoints) - - success, rvec, tvec = cv2.solvePnP(lpoints, cpoints, camera_in, None) - R, _ = cv2.Rodrigues(rvec) - - T=np.eye(4) - T[:3, :3] = R - T[:3, 3] = tvec.flatten() + c2v = load_ex(args.out_path,mode='matrix') + T = np.linalg.inv(c2v) print(T) - v2c = T - print('vehicle->camera:',v2c) - c2v = np.linalg.inv(v2c) - print('camera->vehicle:',c2v) - - if args.out_path is not None: - save_ex(args.out_path,matrix=c2v) - + u,v = pc_projection(pc,Transform(T),K,img.shape) + show_img = img.copy() + for uu,vv in zip(u.astype(int),v.astype(int)): + cv2.circle(show_img, (uu, vv), radius=1, color=(0, 0, 255), thickness=-1) + cv2.imshow("projection", show_img) + cv2.waitKey(0) + + if not args.fine_tune: + return + + if args.fine_tune == 'manual': + pass if __name__ == "__main__": main() \ No newline at end of file diff --git a/GEMstack/offboard/calibration/lidar_to_vehicle.py b/GEMstack/offboard/calibration/lidar_to_vehicle.py index 235a53488..4647e341c 100644 --- a/GEMstack/offboard/calibration/lidar_to_vehicle.py +++ b/GEMstack/offboard/calibration/lidar_to_vehicle.py @@ -5,7 +5,7 @@ from scipy.spatial.transform import Rotation as R import pyvista as pv import matplotlib.pyplot as plt -from visualizer import visualizer +from tools.visualizer import visualizer VIS = False # True to show visuals VIS = True # True to show visuals diff --git a/GEMstack/offboard/calibration/manual_fine_tune.py b/GEMstack/offboard/calibration/manual_fine_tune.py new file mode 100644 index 000000000..17a52d96f --- /dev/null +++ b/GEMstack/offboard/calibration/manual_fine_tune.py @@ -0,0 +1,144 @@ +from transform3d import Transform +import cv2 +import pyvista as pv +import numpy as np + +class Scene3D: + def __init__(self,pc,T:Transform,K,img,on_key_pressed): + self.pc = pc + self.Ti = T.inv + self.img = img + self.plotter : pv.Plotter = pv.Plotter(notebook=False) + self.plotter.add_axes() + self.plotter.camera.position = (-20,0,20) + self.plotter.camera.focal_point = (0,0,0) + + self.plotter.add_mesh(pv.PolyData(pc)) + self.camera_actor = self.plotter.add_mesh(self.make_camera(K,img.shape)) + self.plotter.add_key_event('a',lambda:on_key_pressed('a')) + self.plotter.add_key_event('s',lambda:on_key_pressed('s')) + self.plotter.add_key_event('d',lambda:on_key_pressed('d')) + self.plotter.add_key_event('w',lambda:on_key_pressed('w')) + self.plotter.add_key_event('c',lambda:on_key_pressed('c')) + self.plotter.add_key_event('z',lambda:on_key_pressed('z')) + self.plotter.add_key_event('j',lambda:on_key_pressed('j')) + self.plotter.add_key_event('k',lambda:on_key_pressed('k')) + self.plotter.add_key_event('l',lambda:on_key_pressed('l')) + self.plotter.add_key_event('i',lambda:on_key_pressed('i')) + self.plotter.add_key_event('u',lambda:on_key_pressed('i')) + self.plotter.add_key_event('o',lambda:on_key_pressed('i')) + #consts + def make_camera(self,K,img_shape) -> pv.PolyData: + h,w,_ = img_shape + Ki = np.linalg.inv(K) + rec_c = pv.Rectangle((Ki@[0,0,1],Ki@[w,0,1],Ki@[0,h,1])) + o_c = pv.Sphere(0.1) + c = pv.merge((rec_c,o_c)) + return c + + #statefuls + + def show(self): + self.plotter.show(interactive_update=True) + self.camera_actor.user_matrix = self.Ti.matrix + + def stop(self): + self.plotter.close() + + def update_T(self,T): + self.Ti = T.inv + self.camera_actor.user_matrix = self.Ti.matrix + + def update_Ti(self,Ti): + self.Ti = Ti + self.camera_actor.user_matrix = self.Ti.matrix + + def loop(self): + self.plotter.update() + +class Scene2D: + def __init__(self,pc,T:Transform,K,img,on_key_pressed): + self.pc = pc + self.img = img + self.img_shape = img.shape + self.T = T + self.K = K + self.scatter = None + cv2.startWindowThread() + self.window = cv2.namedWindow("projection") + def handle_event(event): + on_key_pressed(event.key) + self.overlay = np.zeros_like(img) + #statefuls + def _update(self): + self.overlay*=0 + u,v = pc_projection(self.pc,self.T,self.K,self.img_shape) + for uu,vv in zip(u.astype(int),v.astype(int)): + cv2.circle(self.overlay, (uu, vv), radius=1, color=(0, 0, 255), thickness=-1) + display = cv2.add(self.img, self.overlay) + cv2.imshow("projection", display) + + def show(self): + self._update() + + def stop(self): + cv2.destroyAllWindows() + + def update_T(self,T): + self.T = T + self._update() + + def loop(self): + pass + +#%% +def manual_fine_tune(pc,img,T,K): + on = True + tu = 0.1 + ru = 0.1 + T = Transform(T) + def on_key_pressed(key): + nonlocal on + nonlocal T + print(key) + if key == 'c': + T @= Transform(p=(0,0,tu)) + if key == 'z': + T @= Transform(p=(0,0,-tu)) + if key == 'a': + T @= Transform(p=(-tu,0,0)) + if key == 'd': + T @= Transform(p=(tu,0,0)) + if key == 'w': + T @= Transform(p=(0,-tu,0)) + if key == 's': + T @= Transform(p=(0,tu,0)) + + if key == 'j': + T = Transform(rpy=(0,ru,0)) @ T + if key == 'l': + T = Transform(rpy=(0,-ru,0)) @ T + if key == 'i': + T = Transform(rpy=(ru,0,0)) @ T + if key == 'k': + T = Transform(rpy=(-ru,0,0)) @ T + if key == 'u': + T = Transform(rpy=(0,0,-ru)) @ T + if key == 'o': + T = Transform(rpy=(0,0,ru)) @ T + + if key == 'p': + on = False + s3d.update_T(T) + s2d.update_T(T) + + s2d = Scene2D(pc,T,K,img,on_key_pressed) + s3d = Scene3D(pc,T,K,img,on_key_pressed) + + s2d.show() + s3d.show() + while on : + s3d.loop() + s2d.loop() + s3d.stop() + s2d.stop() \ No newline at end of file diff --git a/GEMstack/offboard/calibration/test_transforms.py b/GEMstack/offboard/calibration/test_transforms.py index 4ed0894f1..d7e233052 100644 --- a/GEMstack/offboard/calibration/test_transforms.py +++ b/GEMstack/offboard/calibration/test_transforms.py @@ -1,3 +1,4 @@ +#%% import numpy as np import cv2 import matplotlib.pyplot as plt @@ -7,20 +8,23 @@ keep_running = True # Load LiDAR points -lidar_data = np.load("./data/ouster32.npz") # Update filename if needed -lidar_points = lidar_data['arr_0'] # Ensure the correct key +import open3d as o3d +pcd = o3d.io.read_point_cloud("/mnt/GEMstack/GEMstack/offboard/calibration/calibration_by_SfM/data/pc/000038.pcd") +lidar_points = np.asarray(pcd.points) +# lidar_data = np.load("/mnt/GEMstack/data/calib2/ouster9.npz") +# lidar_points = lidar_data['arr_0'] # Ensure the correct key # Load Camera Image -image = cv2.imread("./data/fr_rect32.png") # Update filename if needed +image = cv2.imread("/mnt/GEMstack/GEMstack/offboard/calibration/calibration_by_SfM/data/rr/images/000038.png") image = cv2.cvtColor(image, cv2.COLOR_BGR2RGB) # Convert BGR to RGB # Transformation Matrix -T_lidar_camera = np.array( - [[-0.65266466, -0.75745371, -0.01710912, -0.54157703], - [-0.08467423, 0.09536332, -0.99183472, -0.37038288], - [ 0.75290047, -0.64588677, -0.12637708, 0.0245309 ], - [ 0. , 0. , 0. , 1. ]] -) +T_lidar_camera = np.array([[ 0.04129275, 0.999105 , -0.00917122, -0.0210888 ], + [ 0.85913152, -0.0401908 , -0.51017422, -4.33950475], + [-0.51008622, 0.01318721, -0.86002218, -1.29820361], + [ 0. , 0. , 0. , 1. ]]) +T_lidar_camera = np.linalg.inv(T_lidar_camera) + # Convert LiDAR points to homogeneous coordinates num_points = lidar_points.shape[0] diff --git a/GEMstack/offboard/calibration/tools/__init__.py b/GEMstack/offboard/calibration/tools/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/GEMstack/offboard/calibration/tools/save_cali.py b/GEMstack/offboard/calibration/tools/save_cali.py index f49dca5a9..dfd0da8a1 100644 --- a/GEMstack/offboard/calibration/tools/save_cali.py +++ b/GEMstack/offboard/calibration/tools/save_cali.py @@ -15,9 +15,9 @@ def load_ex(path,mode,ref='rear_axle_center'): y = yaml.safe_load(stream) assert y['reference'] == ref if mode == 'matrix': - ret = np.zeros((3,4)) + ret = np.eye(4) ret[0:3,0:3] = y['rotation'] - ret[:,3] = y['position'] + ret[:-1,3] = y['position'] return ret elif mode == 'tuple': return np.array(y['rotation']),np.array(y['position']) @@ -32,7 +32,7 @@ def save_ex(path,rotation=None,translation=None,matrix=None,ref='rear_axle_cente ret = {} ret['reference'] = ref ret['rotation'] = rotation - ret['translation'] = translation + ret['position'] = translation for i in ret: if type(ret[i]) == np.ndarray: ret[i] = ret[i].tolist() @@ -43,13 +43,18 @@ def save_ex(path,rotation=None,translation=None,matrix=None,ref='rear_axle_cente def load_in(path,mode='matrix',return_distort=False): with open(path) as stream: y = yaml.safe_load(stream) + if 'skew' not in y: y['skew'] = 0 + if 'distort' not in y: y['distort'] = [0,0,0,0,0] if mode == 'matrix': ret = np.zeros((3,3)) ret[0,0],ret[1,1] = y['focal'] + ret[2,2] = 1. ret[0:2,2] = y['center'] - return ret - if 'skew' not in y: y['skew'] = 0 - if 'distort' not in y: y['distort'] = [0,0,0,0,0] + ret[0,1] = y['skew'] + if return_distort: + return ret,np.array(y['distort']) + else: + return ret elif mode == 'tuple': return {'focal':np.array(y['focal']), 'center':np.array(y['center']), From 19aebf6fc2157ba3c2db1a577d3dbb022495a002 Mon Sep 17 00:00:00 2001 From: rjsun-KA <92330153+rjsun06@users.noreply.github.com> Date: Sun, 13 Apr 2025 05:29:15 +0000 Subject: [PATCH 204/232] include distortion and skew in xxx_in.yaml --- GEMstack/knowledge/calibration/gem_e4_fr_in.yaml | 2 ++ GEMstack/knowledge/calibration/gem_e4_rl_in.yaml | 2 ++ 2 files changed, 4 insertions(+) diff --git a/GEMstack/knowledge/calibration/gem_e4_fr_in.yaml b/GEMstack/knowledge/calibration/gem_e4_fr_in.yaml index 55b5e2ab6..0d7a90a52 100644 --- a/GEMstack/knowledge/calibration/gem_e4_fr_in.yaml +++ b/GEMstack/knowledge/calibration/gem_e4_fr_in.yaml @@ -1,2 +1,4 @@ center: [934.859447, 607.266974] focal: [1180.753804, 1177.034929] +distort: [-0.2448506795091457, 0.08202383880344215, 0.0004294271518916802, -0.0012454354245869965, 0.0] +skew: 0.0 \ No newline at end of file diff --git a/GEMstack/knowledge/calibration/gem_e4_rl_in.yaml b/GEMstack/knowledge/calibration/gem_e4_rl_in.yaml index b0c50960c..feea4eb78 100644 --- a/GEMstack/knowledge/calibration/gem_e4_rl_in.yaml +++ b/GEMstack/knowledge/calibration/gem_e4_rl_in.yaml @@ -1,2 +1,4 @@ center: [955.729090, 599.315043] focal: [1216.836137, 1216.045721] +distort: [-0.24343640079788503, 0.09125282937288573, 5.21454371097206e-06, -2.2750254391060847e-05, 0.0] +skew: 0.0 \ No newline at end of file From 8be544d4a607faeb03c1752c8a7bdd618b6cbf69 Mon Sep 17 00:00:00 2001 From: rjsun-KA <92330153+rjsun06@users.noreply.github.com> Date: Sun, 13 Apr 2025 06:06:30 +0000 Subject: [PATCH 205/232] removed accidentally added large file --- .../calibration/calibration_by_segmentation/.gitignore | 3 +-- .../calibration/calibration_by_segmentation/calib.bash | 4 ++-- 2 files changed, 3 insertions(+), 4 deletions(-) diff --git a/GEMstack/offboard/calibration/calibration_by_segmentation/.gitignore b/GEMstack/offboard/calibration/calibration_by_segmentation/.gitignore index 0197c8cd8..d86c77005 100644 --- a/GEMstack/offboard/calibration/calibration_by_segmentation/.gitignore +++ b/GEMstack/offboard/calibration/calibration_by_segmentation/.gitignore @@ -1,5 +1,4 @@ -sam_vit_h.pth -sam_vit_b.pth +weights/* init_proj* refined_proj* data/* diff --git a/GEMstack/offboard/calibration/calibration_by_segmentation/calib.bash b/GEMstack/offboard/calibration/calibration_by_segmentation/calib.bash index dbbd230ae..d80424546 100644 --- a/GEMstack/offboard/calibration/calibration_by_segmentation/calib.bash +++ b/GEMstack/offboard/calibration/calibration_by_segmentation/calib.bash @@ -1,10 +1,10 @@ data=$1 -wget -c -O sam_vit_b.pth https://dl.fbaipublicfiles.com/segment_anything/sam_vit_b_01ec64.pth +wget -c -O weights/sam_vit_b.pth https://dl.fbaipublicfiles.com/segment_anything/sam_vit_b_01ec64.pth # wget -c -O sam_vit_h.pth https://dl.fbaipublicfiles.com/segment_anything/sam_vit_h_4b8939.pth echo 'running segmentation...' -python3 segment-anything/scripts/amg.py --checkpoint sam_vit_b.pth --model-type vit_b --input $data/selected --output $data/masks/ --stability-score-thresh 0.9 --box-nms-thresh 0.5 --stability-score-offset 0.9 +python3 segment-anything/scripts/amg.py --checkpoint weights/sam_vit_b.pth --model-type vit_b --input $data/selected --output $data/masks/ --stability-score-thresh 0.9 --box-nms-thresh 0.5 --stability-score-offset 0.9 # python3 segment-anything/scripts/amg.py --checkpoint sam_vit_h.pth --model-type vit_h --input $data/images --output $data/masks/ --stability-score-thresh 0.9 --box-nms-thresh 0.5 --stability-score-offset 0.9 echo 'reprocess segmentation...' From cd28d1317732316a9d18ad875b3b4b9dee0d9b9e Mon Sep 17 00:00:00 2001 From: Michal Juscinski Date: Wed, 16 Apr 2025 09:05:36 -0700 Subject: [PATCH 206/232] Add script for intrinsic calibration --- .../calibration/intrinsic_calibration.py | 56 +++++++++++++++++++ 1 file changed, 56 insertions(+) create mode 100644 GEMstack/offboard/calibration/intrinsic_calibration.py diff --git a/GEMstack/offboard/calibration/intrinsic_calibration.py b/GEMstack/offboard/calibration/intrinsic_calibration.py new file mode 100644 index 000000000..a68eef14b --- /dev/null +++ b/GEMstack/offboard/calibration/intrinsic_calibration.py @@ -0,0 +1,56 @@ +import numpy as np +import cv2 as cv +import glob +import os + +def main(folder, camera): + image_files = glob.glob(os.path.join(folder, camera + '*.png')) + + # The following code is derived from https://docs.opencv.org/4.x/dc/dbb/tutorial_py_calibration.html + + # termination criteria + criteria = (cv.TERM_CRITERIA_EPS + cv.TERM_CRITERIA_MAX_ITER, 30, 0.001) + + # prepare object points, like (0,0,0), (1,0,0), (2,0,0) ....,(7,5,0) + objp = np.zeros((6*8,3), np.float32) + objp[:,:2] = np.mgrid[0:8,0:6].T.reshape(-1,2) + + # Arrays to store object points and image points from all the images. + objpoints = [] # 3d point in real world space + imgpoints = [] # 2d points in image plane. + + for fname in image_files: + img = cv.imread(fname) + gray = cv.cvtColor(img, cv.COLOR_BGR2GRAY) + + # Find the chess board corners + ret, corners = cv.findChessboardCorners(gray, (8,6), None) + + # If found, add object points, image points (after refining them) + if ret == True: + objpoints.append(objp) + + corners2 = cv.cornerSubPix(gray,corners, (11,11), (-1,-1), criteria) + imgpoints.append(corners2) + + # Draw and display the corners + cv.drawChessboardCorners(img, (8,6), corners2, ret) + cv.imshow('img', img) + cv.waitKey(500) + + cv.destroyAllWindows() + + ret, mtx, dist, rvecs, tvecs = cv.calibrateCamera(objpoints, imgpoints, gray.shape[::-1], None, None) + print(repr(mtx)) + print(dist) + + +if __name__ == '__main__': + import sys + folder = 'data/fr_calib' + camera = '' + if len(sys.argv) >= 2: + folder = sys.argv[1] + if len(sys.argv) >= 3: + camera = int(sys.argv[2]) + main(folder,camera) \ No newline at end of file From 2951536d9d2d9a1e956ad35b6705a687cf8be180 Mon Sep 17 00:00:00 2001 From: michalj1 Date: Fri, 25 Apr 2025 00:06:46 -0500 Subject: [PATCH 207/232] Standardize interface for scripts and clean messy code --- GEMstack/offboard/calibration/camera_info.py | 112 ++---- .../calibration/capture_ouster_oak.py | 2 +- .../calibration/intrinsic_calibration.py | 37 +- .../offboard/calibration/test_transforms.py | 366 +++++++++--------- .../offboard/calibration/undistort_images.py | 40 +- 5 files changed, 275 insertions(+), 282 deletions(-) diff --git a/GEMstack/offboard/calibration/camera_info.py b/GEMstack/offboard/calibration/camera_info.py index 339f5f9be..c37c994e6 100644 --- a/GEMstack/offboard/calibration/camera_info.py +++ b/GEMstack/offboard/calibration/camera_info.py @@ -10,93 +10,51 @@ import numpy as np import os import time +from functools import partial +from tools.save_cali import save_in -oak_info = None -stereo_info = None -right_info = None -left_info = None -fl_info = None -fr_info = None -rl_info = None -rr_info = None +camera_info = {"oak": None, "fr": None, "fl": None, "rr": None, "rl": None, "oak_stereo": None, "oak_right": None, "oak_left": None} -def oak_callback(info : CameraInfo): - global oak_info - oak_info = info - -def stereo_callback(info : CameraInfo): - global stereo_info - stereo_info = info - -def right_callback(info : CameraInfo): - global right_info - right_info = info - -def left_callback(info : CameraInfo): - global left_info - left_info = info - -def fl_callback(info : CameraInfo): - global fl_info - fl_info = info - -def fr_callback(info : CameraInfo): - global fr_info - fr_info = info - -def rl_callback(info : CameraInfo): - global rl_info - rl_info = info - -def rr_callback(info : CameraInfo): - global rr_info - rr_info = info +def info_callback(camera, info : CameraInfo): + global camera_info + camera_info[camera] = info def get_intrinsics(folder): model = image_geometry.PinholeCameraModel() - model.fromCameraInfo(oak_info) - with open(os.path.join(folder, "oak.txt"), "w") as f: - f.write(str(model.intrinsicMatrix())) - model.fromCameraInfo(stereo_info) - with open(os.path.join(folder, "stereo.txt"), "w") as f: - f.write(str(model.intrinsicMatrix())) - model.fromCameraInfo(right_info) - with open(os.path.join(folder, "right.txt"), "w") as f: - f.write(str(model.intrinsicMatrix())) - model.fromCameraInfo(left_info) - with open(os.path.join(folder, "left.txt"), "w") as f: - f.write(str(model.intrinsicMatrix())) - model.fromCameraInfo(fl_info) - with open(os.path.join(folder, "fl.txt"), "w") as f: - f.write(str(model.intrinsicMatrix())) - model.fromCameraInfo(fr_info) - with open(os.path.join(folder, "fr.txt"), "w") as f: - f.write(str(model.intrinsicMatrix())) - model.fromCameraInfo(rl_info) - with open(os.path.join(folder, "rl.txt"), "w") as f: - f.write(str(model.intrinsicMatrix())) - model.fromCameraInfo(rr_info) - with open(os.path.join(folder, "rr.txt"), "w") as f: - f.write(str(model.intrinsicMatrix())) + for camera in camera_info: + model.fromCameraInfo(camera_info[camera]) + print(f"Camera: {camera}\nFocal: [{model.fx()}, {model.fy()}]\nCenter: [{model.cx()}, {model.cy()}]\nDistortion: {str(model.distortionCoeffs())}") + save_file = input("Save this file?") + if save_file.lower() == 'y' or save_file.lower() == 'yes': + print("Saving") + save_in(path=folder, distort=model.distortionCoeffs(), matrix=model.intrinsicMatrix()) + else: + print("Not saved") def main(folder='data'): rospy.init_node("capture_cam_info",disable_signals=True) - caminfo_sub = rospy.Subscriber("/oak/rgb/camera_info", CameraInfo, oak_callback) - stereoinfo_sub = rospy.Subscriber("/oak/stereo/camera_info", CameraInfo, stereo_callback) - rightinfo_sub = rospy.Subscriber("/oak/right/camera_info", CameraInfo, right_callback) - leftinfo_sub = rospy.Subscriber("/oak/left/camera_info", CameraInfo, left_callback) - flinfo_sub = rospy.Subscriber("/camera_fl/arena_camera_node/camera_info", CameraInfo, fl_callback) - frinfo_sub = rospy.Subscriber("/camera_fr/arena_camera_node/camera_info", CameraInfo, fr_callback) - rlinfo_sub = rospy.Subscriber("/camera_rl/arena_camera_node/camera_info", CameraInfo, rl_callback) - rrinfo_sub = rospy.Subscriber("/camera_rr/arena_camera_node/camera_info", CameraInfo, rr_callback) - while True: - if oak_info and fl_info and fr_info and rl_info and rr_info: - time.sleep(1) - get_intrinsics(folder) - + caminfo_sub = rospy.Subscriber("/oak/rgb/camera_info", CameraInfo, partial(info_callback, "oak")) + stereoinfo_sub = rospy.Subscriber("/oak/stereo/camera_info", CameraInfo, partial(info_callback, "oak_stereo")) + rightinfo_sub = rospy.Subscriber("/oak/right/camera_info", CameraInfo, partial(info_callback, "oak_right")) + leftinfo_sub = rospy.Subscriber("/oak/left/camera_info", CameraInfo, partial(info_callback, "oak_left")) + flinfo_sub = rospy.Subscriber("/camera_fl/arena_camera_node/camera_info", CameraInfo, partial(info_callback, "fl")) + frinfo_sub = rospy.Subscriber("/camera_fr/arena_camera_node/camera_info", CameraInfo, partial(info_callback, "fr")) + rlinfo_sub = rospy.Subscriber("/camera_rl/arena_camera_node/camera_info", CameraInfo, partial(info_callback, "rl")) + rrinfo_sub = rospy.Subscriber("/camera_rr/arena_camera_node/camera_info", CameraInfo, partial(info_callback, "rr")) + + have_all = False + while not have_all: + have_all = True + for camera in camera_info: + if camera_info[camera] == None: + have_all = False + time.sleep(0.5) + break + get_intrinsics(folder) + if __name__ == '__main__': import sys - folder = 'data' + folder = 'GEMstack/knowledge/calibration' if len(sys.argv) >= 2: folder = sys.argv[1] main(folder) diff --git a/GEMstack/offboard/calibration/capture_ouster_oak.py b/GEMstack/offboard/calibration/capture_ouster_oak.py index 62cc72910..4e38b4c0d 100644 --- a/GEMstack/offboard/calibration/capture_ouster_oak.py +++ b/GEMstack/offboard/calibration/capture_ouster_oak.py @@ -137,10 +137,10 @@ def main(folder='data',start_index=0): while True: if camera_images["oak"]: cv2.imshow("result",bridge.imgmsg_to_cv2(camera_images["oak"])) - time.sleep(.5) save_scan(folder, index) clear_scan() index += 1 + time.sleep(.5) if __name__ == '__main__': import sys diff --git a/GEMstack/offboard/calibration/intrinsic_calibration.py b/GEMstack/offboard/calibration/intrinsic_calibration.py index a68eef14b..611165cd8 100644 --- a/GEMstack/offboard/calibration/intrinsic_calibration.py +++ b/GEMstack/offboard/calibration/intrinsic_calibration.py @@ -2,8 +2,28 @@ import cv2 as cv import glob import os - -def main(folder, camera): +import argparse + +from tools.save_cali import save_in + +def main(): + # Collect arguments + parser = argparse.ArgumentParser(description='calculate intrinsics from checkerboard images', + formatter_class=argparse.ArgumentDefaultsHelpFormatter) + parser.add_argument('-f', '--img_folder_path', type=str, required=True, + help='Path to folder containing PNG images') + parser.add_argument('-c', '--camera_name', type=str, required=False, + help='Name of the camera used to identify the correct images') + parser.add_argument('-o', '--out_path', type=str, required=False, + help='Path to output ymal file for camera intrinsics') + + args = parser.parse_args() + + # Find image files + folder = args.img_folder_path + camera = '' + if args.camera_name: + camera = args.camera_name image_files = glob.glob(os.path.join(folder, camera + '*.png')) # The following code is derived from https://docs.opencv.org/4.x/dc/dbb/tutorial_py_calibration.html @@ -40,17 +60,14 @@ def main(folder, camera): cv.destroyAllWindows() + # Calibrate camera ret, mtx, dist, rvecs, tvecs = cv.calibrateCamera(objpoints, imgpoints, gray.shape[::-1], None, None) print(repr(mtx)) print(dist) + if args.out_path: + save_in(args.out_path, distort=dist, matrix=mtx) + if __name__ == '__main__': - import sys - folder = 'data/fr_calib' - camera = '' - if len(sys.argv) >= 2: - folder = sys.argv[1] - if len(sys.argv) >= 3: - camera = int(sys.argv[2]) - main(folder,camera) \ No newline at end of file + main() \ No newline at end of file diff --git a/GEMstack/offboard/calibration/test_transforms.py b/GEMstack/offboard/calibration/test_transforms.py index 4ed0894f1..1740fdc69 100644 --- a/GEMstack/offboard/calibration/test_transforms.py +++ b/GEMstack/offboard/calibration/test_transforms.py @@ -1,162 +1,17 @@ import numpy as np import cv2 import matplotlib.pyplot as plt +import argparse from scipy.spatial.transform import Rotation as R from matplotlib.widgets import Slider +from tools.save_cali import load_ex, load_in, save_ex keep_running = True +scale, x_rot, y_rot, z_rot, x_trans, y_trans, z_trans = None -# Load LiDAR points -lidar_data = np.load("./data/ouster32.npz") # Update filename if needed -lidar_points = lidar_data['arr_0'] # Ensure the correct key - -# Load Camera Image -image = cv2.imread("./data/fr_rect32.png") # Update filename if needed -image = cv2.cvtColor(image, cv2.COLOR_BGR2RGB) # Convert BGR to RGB - -# Transformation Matrix -T_lidar_camera = np.array( - [[-0.65266466, -0.75745371, -0.01710912, -0.54157703], - [-0.08467423, 0.09536332, -0.99183472, -0.37038288], - [ 0.75290047, -0.64588677, -0.12637708, 0.0245309 ], - [ 0. , 0. , 0. , 1. ]] -) - -# Convert LiDAR points to homogeneous coordinates -num_points = lidar_points.shape[0] -lidar_homogeneous = np.hstack((lidar_points, np.ones((num_points, 1)))) # (N, 4) - -# Transform LiDAR points to Camera Frame -lidar_points_camera = (T_lidar_camera @ lidar_homogeneous.T).T # (N, 4) - - -# intrinsic matrix -K = np.array([ - [1180.753804, 0. , 934.859447], - [ 0. , 1177.034929, 607.266974], - [ 0. , 0. , 1. ] -], dtype=np.float32) - -# Extract 3D points in camera frame -X_c = lidar_points_camera[:, 0] -Y_c = lidar_points_camera[:, 1] -Z_c = lidar_points_camera[:, 2] # Depth - -# Avoid division by zero -valid = Z_c > 0 -X_c, Y_c, Z_c = X_c[valid], Y_c[valid], Z_c[valid] - -# Project points onto image plane -u = (K[0, 0] * X_c / Z_c) + K[0, 2] -v = (K[1, 1] * Y_c / Z_c) + K[1, 2] - -# Filter points within image bounds -img_h, img_w, _ = image.shape -valid_pts = (u >= 0) & (u < img_w) & (v >= 0) & (v < img_h) -u, v = u[valid_pts], v[valid_pts] - -# Create space for sliders -plt.ion() -fig, ax = plt.subplots() -fig.subplots_adjust(bottom=0.4) -scale_ax = fig.add_axes([0.25, 0.35, 0.65, 0.03]) -x_rot_ax = fig.add_axes([0.25, 0.3, 0.65, 0.03]) -y_rot_ax = fig.add_axes([0.25, 0.25, 0.65, 0.03]) -z_rot_ax = fig.add_axes([0.25, 0.2, 0.65, 0.03]) -x_trans_ax = fig.add_axes([0.25, 0.15, 0.65, 0.03]) -y_trans_ax = fig.add_axes([0.25, 0.1, 0.65, 0.03]) -z_trans_ax = fig.add_axes([0.25, 0.05, 0.65, 0.03]) - -# Plot projected points on camera image -ax.imshow(image) -dots = ax.scatter(u, v, s=2, c='cyan', alpha=0.2) # Dots for projected points -ax.set_title("Projected LiDAR Points on Camera Image", pad=0) - -# Make a slider to control the scale -scale = Slider( - ax=scale_ax, - label="Scale", - valmin=0.75, - valmax=1.25, - valinit=1, - orientation="horizontal" -) - -# Make sliders to control the rotation -x_rot = Slider( - ax=x_rot_ax, - label="X Rotation", - valmin=-30, - valmax=30, - valinit=0, - orientation="horizontal" -) - -y_rot = Slider( - ax=y_rot_ax, - label="Y Rotation", - valmin=-30, - valmax=30, - valinit=0, - orientation="horizontal" -) - -z_rot = Slider( - ax=z_rot_ax, - label="Z Rotation", - valmin=-30, - valmax=30, - valinit=0, - orientation="horizontal" -) - -# Make sliders to control the scale -x_trans = Slider( - ax=x_trans_ax, - label="X Translation", - valmin=-10, - valmax=10, - valinit=0, - orientation="horizontal" -) - -y_trans = Slider( - ax=y_trans_ax, - label="Y Translation", - valmin=-10, - valmax=10, - valinit=0, - orientation="horizontal" -) - -z_trans = Slider( - ax=z_trans_ax, - label="Z Translation", - valmin=-10, - valmax=10, - valinit=0, - orientation="horizontal" -) - -def update(val): - global T_lidar_camera - modified = np.copy(T_lidar_camera) - rotation_mat = R.from_euler('xyz', [x_rot.val, y_rot.val, z_rot.val], degrees=True).as_matrix() - scale_mat = np.array([[scale.val, 0, 0], [0, scale.val, 0], [0, 0, scale.val]]) - translation_vec = np.array([x_trans.val, y_trans.val, z_trans.val]) - modified[:3, :3] = T_lidar_camera[:3, :3] @ rotation_mat @ scale_mat - modified[:3, 3] = T_lidar_camera[:3, 3] + translation_vec - +def project_points(T_lidar_camera, lidar_homogeneous, K, shape): # Transform LiDAR points to Camera Frame - lidar_points_camera = (modified @ lidar_homogeneous.T).T # (N, 4) - - - # intrinsic matrix - K = np.array([ - [1180.753804, 0. , 934.859447], - [ 0. , 1177.034929, 607.266974], - [ 0. , 0. , 1. ] - ], dtype=np.float32) + lidar_points_camera = (T_lidar_camera @ lidar_homogeneous.T).T # (N, 4) # Extract 3D points in camera frame X_c = lidar_points_camera[:, 0] @@ -172,36 +27,191 @@ def update(val): v = (K[1, 1] * Y_c / Z_c) + K[1, 2] # Filter points within image bounds - img_h, img_w, _ = image.shape + img_h, img_w, _ = shape valid_pts = (u >= 0) & (u < img_w) & (v >= 0) & (v < img_h) u, v = u[valid_pts], v[valid_pts] - dots.set_offsets(np.c_[u, v]) - plt.draw() +def modify_transform(T_lidar_camera): + modified = np.copy(T_lidar_camera) + rotation_mat = R.from_euler('xyz', [x_rot.val, y_rot.val, z_rot.val], degrees=True).as_matrix() + scale_mat = np.array([[scale.val, 0, 0], [0, scale.val, 0], [0, 0, scale.val]]) + translation_vec = np.array([x_trans.val, y_trans.val, z_trans.val]) + modified[:3, :3] = T_lidar_camera[:3, :3] @ rotation_mat @ scale_mat + modified[:3, 3] = T_lidar_camera[:3, 3] + translation_vec + return modified + +def create_sliders(fig, update_func): + # Create space for sliders + fig.subplots_adjust(bottom=0.4) + scale_ax = fig.add_axes([0.25, 0.35, 0.65, 0.03]) + x_rot_ax = fig.add_axes([0.25, 0.3, 0.65, 0.03]) + y_rot_ax = fig.add_axes([0.25, 0.25, 0.65, 0.03]) + z_rot_ax = fig.add_axes([0.25, 0.2, 0.65, 0.03]) + x_trans_ax = fig.add_axes([0.25, 0.15, 0.65, 0.03]) + y_trans_ax = fig.add_axes([0.25, 0.1, 0.65, 0.03]) + z_trans_ax = fig.add_axes([0.25, 0.05, 0.65, 0.03]) + + # Make a slider to control the scale + global scale + scale = Slider( + ax=scale_ax, + label="Scale", + valmin=0.75, + valmax=1.25, + valinit=1, + orientation="horizontal" + ) + + # Make sliders to control the rotation + global x_rot + x_rot = Slider( + ax=x_rot_ax, + label="X Rotation", + valmin=-30, + valmax=30, + valinit=0, + orientation="horizontal" + ) + + global y_rot + y_rot = Slider( + ax=y_rot_ax, + label="Y Rotation", + valmin=-30, + valmax=30, + valinit=0, + orientation="horizontal" + ) + + global z_rot + z_rot = Slider( + ax=z_rot_ax, + label="Z Rotation", + valmin=-30, + valmax=30, + valinit=0, + orientation="horizontal" + ) + + # Make sliders to control the translation + global x_trans + x_trans = Slider( + ax=x_trans_ax, + label="X Translation", + valmin=-10, + valmax=10, + valinit=0, + orientation="horizontal" + ) + + global y_trans + y_trans = Slider( + ax=y_trans_ax, + label="Y Translation", + valmin=-10, + valmax=10, + valinit=0, + orientation="horizontal" + ) + + global z_trans + z_trans = Slider( + ax=z_trans_ax, + label="Z Translation", + valmin=-10, + valmax=10, + valinit=0, + orientation="horizontal" + ) + + # Register the update function with each slider + scale.on_changed(update_func) + x_rot.on_changed(update_func) + y_rot.on_changed(update_func) + z_rot.on_changed(update_func) + x_trans.on_changed(update_func) + y_trans.on_changed(update_func) + z_trans.on_changed(update_func) + +def main(): + # Collect arguments + parser = argparse.ArgumentParser(description='calculate intrinsics from checkerboard images', + formatter_class=argparse.ArgumentDefaultsHelpFormatter) + parser.add_argument('-p', '--img_path', type=str, required=True, + help='Path to PNG image') + parser.add_argument('-l', '--lidar_path', type=str, required=True, + help='Path to lidar point cloud') + parser.add_argument('-t', '--lidar_transform_path', type=str, required=True, + help='Path to lidar extrinsics') + parser.add_argument('-e', '--camera_transform_path', type=str, required=True, + help='Path to camera extrinsics') + parser.add_argument('-i', '--img_intrinsics_path', type=str, required=True, + help='Path to ymal file for image intrinsics') + parser.add_argument('-o', '--out_path', type=str, required=False, + help='Path to output ymal file for camera intrinsics') + + args = parser.parse_args() + + # Load LiDAR points + lidar_data = np.load(args.lidar_path) + lidar_points = lidar_data['arr_0'] # Ensure the correct key + + # Load Camera Image + image = cv2.imread(args.img_path) + image = cv2.cvtColor(image, cv2.COLOR_BGR2RGB) # Convert BGR to RGB + + # Load Transformation Matrices + T_lidar_vehicle = load_ex(args.lidar_transform_path) + T_camera_vehicle = load_ex(args.camera_transform_path) + T_lidar_camera = np.linalg.inv(T_camera_vehicle) @ T_lidar_vehicle + + # Load Camera Intrinsics + K = load_in(args.img_intrinsics_path) + + # Convert LiDAR points to homogeneous coordinates + num_points = lidar_points.shape[0] + lidar_homogeneous = np.hstack((lidar_points, np.ones((num_points, 1)))) # (N, 4) + + # Initialize plot + plt.ion() + fig, ax = plt.subplots() + + # Project lidar points to camera frame + u, v = project_points(T_lidar_camera, lidar_homogeneous, K, image.shape) + + # Plot projected points on camera image + ax.imshow(image) + dots = ax.scatter(u, v, s=2, c='cyan', alpha=0.2) # Dots for projected points + ax.set_title("Projected LiDAR Points on Camera Image", pad=0) + + # Define update function + def update(val): + modified = modify_transform(T_lidar_camera) + + # Update projected points + u, v = project_points(T_lidar_camera, lidar_homogeneous, K, image.shape) + dots.set_offsets(np.c_[u, v]) + plt.draw() + + # Generate sliders and display plot + create_sliders(fig, update) + plt.draw() -# register the update function with each slider -scale.on_changed(update) -x_rot.on_changed(update) -y_rot.on_changed(update) -z_rot.on_changed(update) -x_trans.on_changed(update) -y_trans.on_changed(update) -z_trans.on_changed(update) - -plt.draw() -while keep_running: - try: - if plt.get_fignums(): - plt.pause(0.1) - else: + # Update and keep displaying the modified plot + while keep_running: + try: + if plt.get_fignums(): + plt.pause(0.1) + else: + keep_running = False + except: keep_running = False - except: - keep_running = False - -modified = np.copy(T_lidar_camera) -rotation_mat = R.from_euler('xyz', [x_rot.val, y_rot.val, z_rot.val], degrees=True).as_matrix() -scale_mat = np.array([[scale.val, 0, 0], [0, scale.val, 0], [0, 0, scale.val]]) -translation_vec = np.array([x_trans.val, y_trans.val, z_trans.val]) -modified[:3, :3] = T_lidar_camera[:3, :3] @ rotation_mat @ scale_mat -modified[:3, 3] = T_lidar_camera[:3, 3] + translation_vec -print(modified) \ No newline at end of file + + # Output and write the fine-tuned translation matrix + modified = modify_transform(T_lidar_camera) + print(modified) + if args.out_path: + save_ex(args.out_path, matrix=modified) + +if __name__ == '__main__': + main() \ No newline at end of file diff --git a/GEMstack/offboard/calibration/undistort_images.py b/GEMstack/offboard/calibration/undistort_images.py index a970f177d..847ab3c61 100644 --- a/GEMstack/offboard/calibration/undistort_images.py +++ b/GEMstack/offboard/calibration/undistort_images.py @@ -2,16 +2,31 @@ import cv2 as cv import glob import os +import argparse -camera_matrix = np.array( - [[1180.753804, 0.000000 , 934.859447], - [0.000000 , 1177.034929, 607.266974], - [0.000000 , 0.000000 , 1.000000 ]] -) +from tools.save_cali import load_in, save_in -distortion_coefficients = np.array([-0.2448506795091457, 0.08202383880344215, 0.0004294271518916802, -0.0012454354245869965, 0.0]) +def main(): + # Collect arguments + parser = argparse.ArgumentParser(description='Create copies of images with the distortion removed', + formatter_class=argparse.ArgumentDefaultsHelpFormatter) + parser.add_argument('-i', '--img_intrinsics_path', type=str, required=True, + help='Path to ymal file for image intrinsics') + parser.add_argument('-f', '--img_folder_path', type=str, required=True, + help='Path to folder containing PNG images') + parser.add_argument('-c', '--camera_name', type=str, required=False, + help='Name of the camera used to identify the correct images') + + args = parser.parse_args() -def main(folder, camera): + # Get camera intrinsics + camera_matrix, distortion_coefficients = load_in(args.img_intrinsics_path, return_distort=True) + + # Find image files + folder = args.img_folder_path + camera = '' + if args.camera_name: + camera = args.camera_name image_files = glob.glob(os.path.join(folder, camera + '*.png')) for fn in image_files: @@ -19,17 +34,10 @@ def main(folder, camera): h, w = image.shape[:2] new_camera_matrix, roi = cv.getOptimalNewCameraMatrix(camera_matrix, distortion_coefficients, (w,h), 1, (w,h)) - # undistort + # Undistort dst = cv.undistort(image, camera_matrix, distortion_coefficients, None, new_camera_matrix) cv.imwrite(fn.replace(camera, camera + "_rect"), dst) if __name__ == '__main__': - import sys - folder = 'data' - camera = 'fr' - if len(sys.argv) >= 2: - folder = sys.argv[1] - if len(sys.argv) >= 3: - camera = int(sys.argv[2]) - main(folder,camera) \ No newline at end of file + main() \ No newline at end of file From 2f4aba41cdf1c68d00b7c7901e6781c0ea5c8e88 Mon Sep 17 00:00:00 2001 From: rjsun-KA <92330153+rjsun06@users.noreply.github.com> Date: Tue, 29 Apr 2025 07:30:44 +0000 Subject: [PATCH 208/232] readme --- .gitignore | 2 + GEMstack/offboard/calibration/README.md | 89 ++++++++++++++ .../calibration/get_intrinsic_by_SfM.py | 116 ++++++++++++++++++ .../get_intrinsic_by_chessborad.py | 64 ++++++++++ .../calibration/intrinsic_calibration.py | 73 ----------- .../offboard/calibration/tools/save_cali.py | 12 +- 6 files changed, 280 insertions(+), 76 deletions(-) create mode 100644 GEMstack/offboard/calibration/README.md create mode 100644 GEMstack/offboard/calibration/get_intrinsic_by_SfM.py create mode 100644 GEMstack/offboard/calibration/get_intrinsic_by_chessborad.py delete mode 100644 GEMstack/offboard/calibration/intrinsic_calibration.py diff --git a/.gitignore b/.gitignore index 90ca50fe0..c34d6c8d3 100644 --- a/.gitignore +++ b/.gitignore @@ -172,3 +172,5 @@ GEMstack/offboard/calibration/calibration_by_segmentation/init_proj.png GEMstack/offboard/calibration/calibration_by_segmentation/refined_proj_seg.png GEMstack/offboard/calibration/calibration_by_segmentation/refined_proj.png GEMstack/offboard/calibration/calibration_by_segmentation/extrinsic.txt + +repo/ \ No newline at end of file diff --git a/GEMstack/offboard/calibration/README.md b/GEMstack/offboard/calibration/README.md new file mode 100644 index 000000000..7c692fe61 --- /dev/null +++ b/GEMstack/offboard/calibration/README.md @@ -0,0 +1,89 @@ +## Table of Contents +- [img2pc.py](#img2pcpy) - Camera-to-LiDAR extrinsic calibration +- [get_intrinsic_by_chessboard.py](#get_intrinsic_by_chessboardpy) - Intrinsic calibration using chessboard +- [intrinsic_calibration_chessboard.py](#intrinsic_calibration_chessboardpy) - Intrinsic calibration using SfM + +--- + +## img2pc.py +**Camera-to-LiDAR Extrinsic Calibration Tool** + +Compute camera extrinsic parameters by manually selecting corresponding features in an image and point cloud. + +### Usage +```bash +python3 img2pc.py \ + --img_path IMG_PATH \ + --pc_path PC_PATH \ + --img_intrinsics_path IMG_INTRINSICS_PATH \ + [--pc_transform_path PC_TRANSFORM_PATH] \ + [--out_path OUT_PATH] \ + [--n_features N_FEATURES] +``` +#### Parameters +| Parameter | Description | Format | Required | Default | +|-----------|-------------|--------|----------|---------| +| `--img_path` | Input image path | .png | Yes | - | +| `--pc_path` | Point cloud path | .npz | Yes | - | +| `--img_intrinsics_path` | Camera intrinsics file | .yaml | Yes | - | +| `--pc_transform_path` | LiDAR extrinsic transform | .yaml | No | Identity | +| `--out_path` | Output extrinsic path | .yaml | No | None | +| `--n_features` | Manual feature points | int | No | 8 | + +### Example +```bash +root='/mnt/GEMstack' +python3 img2pc.py \ + --img_path $root/data/calib1/img/fl/fl16.png \ + --pc_path $root/data/calib1/pc/ouster16.npz \ + --pc_transform_path $root/GEMstack/knowledge/calibration/gem_e4_ouster.yaml \ + --img_intrinsics_path $root/GEMstack/knowledge/calibration/gem_e4_oak_in.yaml \ + --n_features 4 \ + --out_path $root/GEMstack/knowledge/calibration/gem_e4_oak.yaml +``` + +## get_intrinsic_by_chessboard.py +Chessboard-based Intrinsic Calibration + +Compute camera intrinsic parameters using multiple images of a chessboard pattern. + +### Usage +```bash +python3 get_intrinsic_by_chessboard.py IMG_DIR WIDTH HEIGHT [OUTPUT_PATH] +``` + +### Parameters +| Parameter | Description | Required | +|-----------|-------------|----------| +| `IMG_DIR` | Calibration images folder | Yes | +| `WIDTH` | Chessboard width (squares-1) | Yes | +| `HEIGHT` | Chessboard height (squares-1) | Yes | +| `OUTPUT_PATH` | Output .yaml path | No | + + +## get_intrinsic_by_SfM.py + +Compute camera intrinsic parameters using Structure-from-Motion on a sequence of images. + +### Usage +```bash +python3 intrinsic_calibration_chessboard.py \ + --input_imgs INPUT_IMGS [INPUT_IMGS ...] \ + --workspace WORKSPACE \ + [--out_file OUT_FILE] +``` +### Parameters +| Parameter | Description | Required | +|-----------|-------------|----------| +| `--input_imgs` | Input images (glob pattern) | Yes | +| `--workspace` | Temporary directory path | Yes | +| `--out_file` | Output .yaml path | No | + +### Example +```bash +root='/mnt/GEMstack' +python3 intrinsic_calibration_chessboard.py \ + --input_imgs data/fl/images/0000[0-8][147].png \ + --workspace /tmp/SfM_intrinsic_fl \ + --out_file $root/GEMstack/knowledge/calibration/camera_intrinsics2/gem_e4_fl_in.yaml +``` diff --git a/GEMstack/offboard/calibration/get_intrinsic_by_SfM.py b/GEMstack/offboard/calibration/get_intrinsic_by_SfM.py new file mode 100644 index 000000000..2d941bc3e --- /dev/null +++ b/GEMstack/offboard/calibration/get_intrinsic_by_SfM.py @@ -0,0 +1,116 @@ +import argparse +import os +import shutil +import pycolmap +import subprocess +from tools.save_cali import save_in + +def run_colmap_command(args): + result = subprocess.run(args, capture_output=True, text=True) + if result.returncode != 0: + print(f"Command failed: {' '.join(args)}") + print(f"Error: {result.stderr}") + raise RuntimeError("COLMAP command failed") + return result + +def main(input_imgs, output_dir, out, refine=True): + # Setup directory structure + workspace_dir = os.path.join(output_dir, 'sfm_workspace') + image_dir = os.path.join(workspace_dir, 'images') + os.makedirs(image_dir, exist_ok=True) + + # Copy images to workspace + print(f"Copying images to workspace...") + for path in input_imgs: + filename = path.split('/')[-1] + dst = os.path.join(image_dir, filename) + shutil.copy(path, dst) + + # Create database path + database_path = os.path.join(workspace_dir, 'database.db') + if os.path.exists(database_path): + os.remove(database_path) + + # Feature extraction + print("Extracting features...") + # pycolmap.extract_features( + # database_path, image_dir, + # camera_mode=pycolmap.CameraMode.SINGLE, + # camera_model=pycolmap.CameraModelId.OPENCV + # ) + run_colmap_command([ + "colmap", "feature_extractor", + "--database_path", database_path, + "--image_path", image_dir, + "--ImageReader.single_camera", "1", + "--ImageReader.camera_model", "OPENCV", + "--SiftExtraction.estimate_affine_shape", "1", + "--SiftExtraction.domain_size_pooling", "1" + ]) + + # Feature matching + print("Matching features...") + match_options = pycolmap.SequentialMatchingOptions() + match_options.overlap = 2 + pycolmap.match_sequential( + database_path, + matching_options=match_options + ) + # Run SfM reconstruction + mapper_options = pycolmap.IncrementalPipelineOptions() + if refine: + mapper_options.ba_refine_focal_length = 1 + mapper_options.ba_refine_principal_point = 1 + mapper_options.ba_refine_extra_params = 1 + else: + mapper_options.ba_refine_focal_length = 0 + mapper_options.ba_refine_principal_point = 0 + mapper_options.ba_refine_extra_params = 0 + + print("Running incremental SfM...") + output_path = os.path.join(workspace_dir, 'sparse') + os.makedirs(output_path, exist_ok=True) + reconstructions = pycolmap.incremental_mapping( + database_path=database_path, + image_path=image_dir, + output_path=output_path, + options=mapper_options + ) + + # Process results + if not reconstructions: + print("SfM failed to reconstruct the scene!") + return + + camera:pycolmap._core.Camera = 0 + print("\nCamera calibration parameters:") + for idx, reconstruction in reconstructions.items(): + print(f"\nReconstruction {idx + 1}:") + for camera_id, camera in reconstruction.cameras.items(): + print(f"\nCamera ID {camera_id}:") + print(f"Model: {camera.model}") + print(f"Parameters: {camera.params}") + print(f"Parameters info: {camera.params_info}") + # print(f"Focal length: {camera.focal_length}") + print(f"Focal length x: {camera.focal_length_x}") + print(f"Focal length y: {camera.focal_length_y}") + print(f"Principal point x: {camera.principal_point_x}") + print(f"Principal point y: {camera.principal_point_y}") + save_in( + path=out, + focal=[camera.focal_length_x,camera.focal_length_y], + center=[camera.principal_point_x,camera.principal_point_y], + distort=list(camera.params[4:])+[0.0], + ) + print("\nCalibration complete! Results saved to:", workspace_dir) + +if __name__ == "__main__": + parser = argparse.ArgumentParser(description='Camera calibration using SfM') + parser.add_argument('--input_imgs','-i', nargs='+', help='List of input imgs', required=True) + parser.add_argument('--workspace','-w', type=str, required=True, + help='Output directory for results') + parser.add_argument('--out_file','-o', type=str, required=True, + help='output yaml file') + args = parser.parse_args() + + main(args.input_imgs, args.workspace, args.out_file) \ No newline at end of file diff --git a/GEMstack/offboard/calibration/get_intrinsic_by_chessborad.py b/GEMstack/offboard/calibration/get_intrinsic_by_chessborad.py new file mode 100644 index 000000000..aa6588a86 --- /dev/null +++ b/GEMstack/offboard/calibration/get_intrinsic_by_chessborad.py @@ -0,0 +1,64 @@ +import cv2 +import numpy as np +from tools.save_cali import save_in + +import glob +def estimate_intrinsics(image_dir, checkerboard_size): + criteria = (cv2.TERM_CRITERIA_EPS + cv2.TERM_CRITERIA_MAX_ITER, 30, 0.001) + + w,h = checkerboard_size + objp = np.zeros((w*h,3), np.float32) + objp[:,:2] = np.mgrid[0:w,0:h].T.reshape(-1,2) + + objpoints = [] + imgpoints = [] + images = glob.glob(image_dir + '*.png') + for fname in images: + img = cv2.imread(fname) + + gray = cv2.cvtColor(img,cv2.COLOR_BGR2GRAY) + + ret, corners = cv2.findChessboardCorners(gray, (w,h),None) + + if ret == True: + objpoints.append(objp) + + corners2 = cv2.cornerSubPix(gray,corners,(11,11),(-1,-1),criteria) + imgpoints.append(corners2) + + img = cv2.drawChessboardCorners(img, (w,h), corners2,ret) + cv2.imshow('img',img) + cv2.waitKey(500) + + cv2.destroyAllWindows() + ret, mtx, dist, rvecs, tvecs = cv2.calibrateCamera(objpoints, imgpoints, gray.shape[::-1],None,None) + + return { + 'fx': mtx[0,0], + 'fy': mtx[1,1], + 'cx': mtx[0,2], + 'cy': mtx[1,2], + 'distortion_coeffs': dist[0].tolist() + } + +if __name__ == "__main__": + import sys + if len(sys.argv) < 4: + print(f"Usage: python3 this.py [output_path]") + sys.exit(1) + + try: + image_path = sys.argv[1] + w = int(sys.argv[2]) + h = int(sys.argv[3]) + params = estimate_intrinsics(image_path, (w,h)) + print("Camera Intrinsics:") + print(f"Focal Length (fx, fy): {params['fx']:.2f}, {params['fy']:.2f}") + print(f"Principal Point (cx, cy): {params['cx']:.2f}, {params['cy']:.2f}") + print(f"Distortion Coefficients: {params['distortion_coeffs']}") + except Exception as e: + print(f"Error: {str(e)}") + + if len(sys.argv) == 5: + out_path = sys.argv[4] + save_in(out_path, focal=[params['fx'],params['fy']], center=[params['cx'],params['cy']],distort=params['distortion_coeffs'],skew=0) \ No newline at end of file diff --git a/GEMstack/offboard/calibration/intrinsic_calibration.py b/GEMstack/offboard/calibration/intrinsic_calibration.py deleted file mode 100644 index 611165cd8..000000000 --- a/GEMstack/offboard/calibration/intrinsic_calibration.py +++ /dev/null @@ -1,73 +0,0 @@ -import numpy as np -import cv2 as cv -import glob -import os -import argparse - -from tools.save_cali import save_in - -def main(): - # Collect arguments - parser = argparse.ArgumentParser(description='calculate intrinsics from checkerboard images', - formatter_class=argparse.ArgumentDefaultsHelpFormatter) - parser.add_argument('-f', '--img_folder_path', type=str, required=True, - help='Path to folder containing PNG images') - parser.add_argument('-c', '--camera_name', type=str, required=False, - help='Name of the camera used to identify the correct images') - parser.add_argument('-o', '--out_path', type=str, required=False, - help='Path to output ymal file for camera intrinsics') - - args = parser.parse_args() - - # Find image files - folder = args.img_folder_path - camera = '' - if args.camera_name: - camera = args.camera_name - image_files = glob.glob(os.path.join(folder, camera + '*.png')) - - # The following code is derived from https://docs.opencv.org/4.x/dc/dbb/tutorial_py_calibration.html - - # termination criteria - criteria = (cv.TERM_CRITERIA_EPS + cv.TERM_CRITERIA_MAX_ITER, 30, 0.001) - - # prepare object points, like (0,0,0), (1,0,0), (2,0,0) ....,(7,5,0) - objp = np.zeros((6*8,3), np.float32) - objp[:,:2] = np.mgrid[0:8,0:6].T.reshape(-1,2) - - # Arrays to store object points and image points from all the images. - objpoints = [] # 3d point in real world space - imgpoints = [] # 2d points in image plane. - - for fname in image_files: - img = cv.imread(fname) - gray = cv.cvtColor(img, cv.COLOR_BGR2GRAY) - - # Find the chess board corners - ret, corners = cv.findChessboardCorners(gray, (8,6), None) - - # If found, add object points, image points (after refining them) - if ret == True: - objpoints.append(objp) - - corners2 = cv.cornerSubPix(gray,corners, (11,11), (-1,-1), criteria) - imgpoints.append(corners2) - - # Draw and display the corners - cv.drawChessboardCorners(img, (8,6), corners2, ret) - cv.imshow('img', img) - cv.waitKey(500) - - cv.destroyAllWindows() - - # Calibrate camera - ret, mtx, dist, rvecs, tvecs = cv.calibrateCamera(objpoints, imgpoints, gray.shape[::-1], None, None) - print(repr(mtx)) - print(dist) - - if args.out_path: - save_in(args.out_path, distort=dist, matrix=mtx) - - -if __name__ == '__main__': - main() \ No newline at end of file diff --git a/GEMstack/offboard/calibration/tools/save_cali.py b/GEMstack/offboard/calibration/tools/save_cali.py index dfd0da8a1..078f9784e 100644 --- a/GEMstack/offboard/calibration/tools/save_cali.py +++ b/GEMstack/offboard/calibration/tools/save_cali.py @@ -61,7 +61,8 @@ def load_in(path,mode='matrix',return_distort=False): 'skew':np.array(y['skew']), 'distort':np.array(y['distort'])} -def save_in(path,focal=None,center=None,skew=None,distort=None,matrix=None): +from collections.abc import Iterable +def save_in(path,focal=None,center=None,skew=0,distort=[0.0]*5,matrix=None): if matrix is not None: focal = matrix.diagonal()[0,-1] skew = matrix[0,1] @@ -71,11 +72,16 @@ def save_in(path,focal=None,center=None,skew=None,distort=None,matrix=None): ret = {} ret['focal'] = focal ret['center'] = center - ret['skew'] = skew or 0 - ret['distort'] = distort or [0,0,0,0,0] + ret['skew'] = skew + assert len(distort) in [4,5] + ret['distort'] = distort + if len(ret['distort']) == 4: + ret['distort'] = list(ret['distort'])+[0.0] for i in ret: if type(ret[i]) == np.ndarray: ret[i] = ret[i].tolist() + if isinstance(ret[i],Iterable): + ret[i] = [*map(float,ret[i])] print(yaml.dump(ret,Dumper=SafeDumper,default_flow_style=False)) with open(path,'w') as stream: yaml.dump(ret,stream,Dumper=SafeDumper,default_flow_style=False) From 27ce08a89db0ef1ece12f967e42821b74fe4d44e Mon Sep 17 00:00:00 2001 From: rjsun-KA <92330153+rjsun06@users.noreply.github.com> Date: Tue, 29 Apr 2025 07:40:43 +0000 Subject: [PATCH 209/232] readme-followup --- GEMstack/offboard/calibration/README.md | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/GEMstack/offboard/calibration/README.md b/GEMstack/offboard/calibration/README.md index 7c692fe61..d7260cefa 100644 --- a/GEMstack/offboard/calibration/README.md +++ b/GEMstack/offboard/calibration/README.md @@ -1,8 +1,7 @@ ## Table of Contents - [img2pc.py](#img2pcpy) - Camera-to-LiDAR extrinsic calibration - [get_intrinsic_by_chessboard.py](#get_intrinsic_by_chessboardpy) - Intrinsic calibration using chessboard -- [intrinsic_calibration_chessboard.py](#intrinsic_calibration_chessboardpy) - Intrinsic calibration using SfM - +- [get_intrinsic_by_SfM.py](#get_intrinsic_by_sfmpy) - Intrinsic calibration using SfM --- ## img2pc.py From 5813a01d400d66d05416010f2098034877b56025 Mon Sep 17 00:00:00 2001 From: rjsun-KA <92330153+rjsun06@users.noreply.github.com> Date: Tue, 29 Apr 2025 07:53:41 +0000 Subject: [PATCH 210/232] readme --- .gitignore | 2 + GEMstack/offboard/calibration/README.md | 93 ++++++++++++++ .../calibration/get_intrinsic_by_SfM.py | 116 ++++++++++++++++++ .../get_intrinsic_by_chessborad.py | 64 ++++++++++ .../calibration/intrinsic_calibration.py | 73 ----------- .../offboard/calibration/tools/save_cali.py | 12 +- 6 files changed, 284 insertions(+), 76 deletions(-) create mode 100644 GEMstack/offboard/calibration/README.md create mode 100644 GEMstack/offboard/calibration/get_intrinsic_by_SfM.py create mode 100644 GEMstack/offboard/calibration/get_intrinsic_by_chessborad.py delete mode 100644 GEMstack/offboard/calibration/intrinsic_calibration.py diff --git a/.gitignore b/.gitignore index 90ca50fe0..c34d6c8d3 100644 --- a/.gitignore +++ b/.gitignore @@ -172,3 +172,5 @@ GEMstack/offboard/calibration/calibration_by_segmentation/init_proj.png GEMstack/offboard/calibration/calibration_by_segmentation/refined_proj_seg.png GEMstack/offboard/calibration/calibration_by_segmentation/refined_proj.png GEMstack/offboard/calibration/calibration_by_segmentation/extrinsic.txt + +repo/ \ No newline at end of file diff --git a/GEMstack/offboard/calibration/README.md b/GEMstack/offboard/calibration/README.md new file mode 100644 index 000000000..6cceb47e0 --- /dev/null +++ b/GEMstack/offboard/calibration/README.md @@ -0,0 +1,93 @@ +## Table of Contents +- [img2pc.py](#img2pcpy) - Camera-to-LiDAR extrinsic calibration +- [get_intrinsic_by_chessboard.py](#get_intrinsic_by_chessboardpy) - Intrinsic calibration using chessboard +- [get_intrinsic_by_SfM.py](#get_intrinsic_by_sfmpy) - Intrinsic calibration using SfM +--- + +## img2pc.py +**Camera-to-LiDAR Extrinsic Calibration Tool** + +Compute camera extrinsic parameters by manually selecting corresponding features in an image and point cloud. + +### Usage +```bash +python3 img2pc.py \ + --img_path IMG_PATH \ + --pc_path PC_PATH \ + --img_intrinsics_path IMG_INTRINSICS_PATH \ + [--pc_transform_path PC_TRANSFORM_PATH] \ + [--out_path OUT_PATH] \ + [--n_features N_FEATURES] +``` +#### Parameters +| Parameter | Description | Format | Required | Default | +|-----------|-------------|--------|----------|---------| +| `--img_path` | Input image path | .png | Yes | - | +| `--pc_path` | Point cloud path | .npz | Yes | - | +| `--img_intrinsics_path` | Camera intrinsics file | .yaml | Yes | - | +| `--pc_transform_path` | LiDAR extrinsic transform | .yaml | No | Identity | +| `--out_path` | Output extrinsic path | .yaml | No | None | +| `--n_features` | Manual feature points | int | No | 8 | + +### Example +```bash +root='/mnt/GEMstack' +python3 img2pc.py \ + --img_path $root/data/calib1/img/fl/fl16.png \ + --pc_path $root/data/calib1/pc/ouster16.npz \ + --pc_transform_path $root/GEMstack/knowledge/calibration/gem_e4_ouster.yaml \ + --img_intrinsics_path $root/GEMstack/knowledge/calibration/gem_e4_oak_in.yaml \ + --n_features 4 \ + --out_path $root/GEMstack/knowledge/calibration/gem_e4_oak.yaml +``` + +## get_intrinsic_by_chessboard.py +Chessboard-based Intrinsic Calibration + +Compute camera intrinsic parameters using multiple images of a chessboard pattern. + +### Usage +```bash +python3 get_intrinsic_by_chessboard.py IMG_DIR WIDTH HEIGHT [OUTPUT_PATH] +``` + +### Parameters +| Parameter | Description | Required | +|-----------|-------------|----------| +| `IMG_DIR` | Calibration images folder | Yes | +| `WIDTH` | Chessboard width (squares-1) | Yes | +| `HEIGHT` | Chessboard height (squares-1) | Yes | +| `OUTPUT_PATH` | Output .yaml path | No | + + +## get_intrinsic_by_SfM.py + +Compute camera intrinsic parameters using Structure-from-Motion on a sequence of images. + +### Usage +```bash +python3 intrinsic_calibration_chessboard.py \ + --input_imgs INPUT_IMGS [INPUT_IMGS ...] \ + --workspace WORKSPACE \ + [--out_file OUT_FILE] +``` +### Parameters +| Parameter | Description | Required | +|-----------|-------------|----------| +| `--input_imgs` | Input images (glob pattern) | Yes | +| `--workspace` | Temporary directory path | Yes | +| `--out_file` | Output .yaml path | No | + +### Example +```bash +root='/mnt/GEMstack' +python3 intrinsic_calibration_chessboard.py \ + --input_imgs data/fl/images/0000[0-8][147].png \ + --workspace /tmp/SfM_intrinsic_fl \ + --out_file $root/GEMstack/knowledge/calibration/camera_intrinsics2/gem_e4_fl_in.yaml +``` + +# Credit +Michal Juscinski, [Renjie Sun](https://github.com/rjsun06), Dev Sakaria + + diff --git a/GEMstack/offboard/calibration/get_intrinsic_by_SfM.py b/GEMstack/offboard/calibration/get_intrinsic_by_SfM.py new file mode 100644 index 000000000..2d941bc3e --- /dev/null +++ b/GEMstack/offboard/calibration/get_intrinsic_by_SfM.py @@ -0,0 +1,116 @@ +import argparse +import os +import shutil +import pycolmap +import subprocess +from tools.save_cali import save_in + +def run_colmap_command(args): + result = subprocess.run(args, capture_output=True, text=True) + if result.returncode != 0: + print(f"Command failed: {' '.join(args)}") + print(f"Error: {result.stderr}") + raise RuntimeError("COLMAP command failed") + return result + +def main(input_imgs, output_dir, out, refine=True): + # Setup directory structure + workspace_dir = os.path.join(output_dir, 'sfm_workspace') + image_dir = os.path.join(workspace_dir, 'images') + os.makedirs(image_dir, exist_ok=True) + + # Copy images to workspace + print(f"Copying images to workspace...") + for path in input_imgs: + filename = path.split('/')[-1] + dst = os.path.join(image_dir, filename) + shutil.copy(path, dst) + + # Create database path + database_path = os.path.join(workspace_dir, 'database.db') + if os.path.exists(database_path): + os.remove(database_path) + + # Feature extraction + print("Extracting features...") + # pycolmap.extract_features( + # database_path, image_dir, + # camera_mode=pycolmap.CameraMode.SINGLE, + # camera_model=pycolmap.CameraModelId.OPENCV + # ) + run_colmap_command([ + "colmap", "feature_extractor", + "--database_path", database_path, + "--image_path", image_dir, + "--ImageReader.single_camera", "1", + "--ImageReader.camera_model", "OPENCV", + "--SiftExtraction.estimate_affine_shape", "1", + "--SiftExtraction.domain_size_pooling", "1" + ]) + + # Feature matching + print("Matching features...") + match_options = pycolmap.SequentialMatchingOptions() + match_options.overlap = 2 + pycolmap.match_sequential( + database_path, + matching_options=match_options + ) + # Run SfM reconstruction + mapper_options = pycolmap.IncrementalPipelineOptions() + if refine: + mapper_options.ba_refine_focal_length = 1 + mapper_options.ba_refine_principal_point = 1 + mapper_options.ba_refine_extra_params = 1 + else: + mapper_options.ba_refine_focal_length = 0 + mapper_options.ba_refine_principal_point = 0 + mapper_options.ba_refine_extra_params = 0 + + print("Running incremental SfM...") + output_path = os.path.join(workspace_dir, 'sparse') + os.makedirs(output_path, exist_ok=True) + reconstructions = pycolmap.incremental_mapping( + database_path=database_path, + image_path=image_dir, + output_path=output_path, + options=mapper_options + ) + + # Process results + if not reconstructions: + print("SfM failed to reconstruct the scene!") + return + + camera:pycolmap._core.Camera = 0 + print("\nCamera calibration parameters:") + for idx, reconstruction in reconstructions.items(): + print(f"\nReconstruction {idx + 1}:") + for camera_id, camera in reconstruction.cameras.items(): + print(f"\nCamera ID {camera_id}:") + print(f"Model: {camera.model}") + print(f"Parameters: {camera.params}") + print(f"Parameters info: {camera.params_info}") + # print(f"Focal length: {camera.focal_length}") + print(f"Focal length x: {camera.focal_length_x}") + print(f"Focal length y: {camera.focal_length_y}") + print(f"Principal point x: {camera.principal_point_x}") + print(f"Principal point y: {camera.principal_point_y}") + save_in( + path=out, + focal=[camera.focal_length_x,camera.focal_length_y], + center=[camera.principal_point_x,camera.principal_point_y], + distort=list(camera.params[4:])+[0.0], + ) + print("\nCalibration complete! Results saved to:", workspace_dir) + +if __name__ == "__main__": + parser = argparse.ArgumentParser(description='Camera calibration using SfM') + parser.add_argument('--input_imgs','-i', nargs='+', help='List of input imgs', required=True) + parser.add_argument('--workspace','-w', type=str, required=True, + help='Output directory for results') + parser.add_argument('--out_file','-o', type=str, required=True, + help='output yaml file') + args = parser.parse_args() + + main(args.input_imgs, args.workspace, args.out_file) \ No newline at end of file diff --git a/GEMstack/offboard/calibration/get_intrinsic_by_chessborad.py b/GEMstack/offboard/calibration/get_intrinsic_by_chessborad.py new file mode 100644 index 000000000..aa6588a86 --- /dev/null +++ b/GEMstack/offboard/calibration/get_intrinsic_by_chessborad.py @@ -0,0 +1,64 @@ +import cv2 +import numpy as np +from tools.save_cali import save_in + +import glob +def estimate_intrinsics(image_dir, checkerboard_size): + criteria = (cv2.TERM_CRITERIA_EPS + cv2.TERM_CRITERIA_MAX_ITER, 30, 0.001) + + w,h = checkerboard_size + objp = np.zeros((w*h,3), np.float32) + objp[:,:2] = np.mgrid[0:w,0:h].T.reshape(-1,2) + + objpoints = [] + imgpoints = [] + images = glob.glob(image_dir + '*.png') + for fname in images: + img = cv2.imread(fname) + + gray = cv2.cvtColor(img,cv2.COLOR_BGR2GRAY) + + ret, corners = cv2.findChessboardCorners(gray, (w,h),None) + + if ret == True: + objpoints.append(objp) + + corners2 = cv2.cornerSubPix(gray,corners,(11,11),(-1,-1),criteria) + imgpoints.append(corners2) + + img = cv2.drawChessboardCorners(img, (w,h), corners2,ret) + cv2.imshow('img',img) + cv2.waitKey(500) + + cv2.destroyAllWindows() + ret, mtx, dist, rvecs, tvecs = cv2.calibrateCamera(objpoints, imgpoints, gray.shape[::-1],None,None) + + return { + 'fx': mtx[0,0], + 'fy': mtx[1,1], + 'cx': mtx[0,2], + 'cy': mtx[1,2], + 'distortion_coeffs': dist[0].tolist() + } + +if __name__ == "__main__": + import sys + if len(sys.argv) < 4: + print(f"Usage: python3 this.py [output_path]") + sys.exit(1) + + try: + image_path = sys.argv[1] + w = int(sys.argv[2]) + h = int(sys.argv[3]) + params = estimate_intrinsics(image_path, (w,h)) + print("Camera Intrinsics:") + print(f"Focal Length (fx, fy): {params['fx']:.2f}, {params['fy']:.2f}") + print(f"Principal Point (cx, cy): {params['cx']:.2f}, {params['cy']:.2f}") + print(f"Distortion Coefficients: {params['distortion_coeffs']}") + except Exception as e: + print(f"Error: {str(e)}") + + if len(sys.argv) == 5: + out_path = sys.argv[4] + save_in(out_path, focal=[params['fx'],params['fy']], center=[params['cx'],params['cy']],distort=params['distortion_coeffs'],skew=0) \ No newline at end of file diff --git a/GEMstack/offboard/calibration/intrinsic_calibration.py b/GEMstack/offboard/calibration/intrinsic_calibration.py deleted file mode 100644 index 611165cd8..000000000 --- a/GEMstack/offboard/calibration/intrinsic_calibration.py +++ /dev/null @@ -1,73 +0,0 @@ -import numpy as np -import cv2 as cv -import glob -import os -import argparse - -from tools.save_cali import save_in - -def main(): - # Collect arguments - parser = argparse.ArgumentParser(description='calculate intrinsics from checkerboard images', - formatter_class=argparse.ArgumentDefaultsHelpFormatter) - parser.add_argument('-f', '--img_folder_path', type=str, required=True, - help='Path to folder containing PNG images') - parser.add_argument('-c', '--camera_name', type=str, required=False, - help='Name of the camera used to identify the correct images') - parser.add_argument('-o', '--out_path', type=str, required=False, - help='Path to output ymal file for camera intrinsics') - - args = parser.parse_args() - - # Find image files - folder = args.img_folder_path - camera = '' - if args.camera_name: - camera = args.camera_name - image_files = glob.glob(os.path.join(folder, camera + '*.png')) - - # The following code is derived from https://docs.opencv.org/4.x/dc/dbb/tutorial_py_calibration.html - - # termination criteria - criteria = (cv.TERM_CRITERIA_EPS + cv.TERM_CRITERIA_MAX_ITER, 30, 0.001) - - # prepare object points, like (0,0,0), (1,0,0), (2,0,0) ....,(7,5,0) - objp = np.zeros((6*8,3), np.float32) - objp[:,:2] = np.mgrid[0:8,0:6].T.reshape(-1,2) - - # Arrays to store object points and image points from all the images. - objpoints = [] # 3d point in real world space - imgpoints = [] # 2d points in image plane. - - for fname in image_files: - img = cv.imread(fname) - gray = cv.cvtColor(img, cv.COLOR_BGR2GRAY) - - # Find the chess board corners - ret, corners = cv.findChessboardCorners(gray, (8,6), None) - - # If found, add object points, image points (after refining them) - if ret == True: - objpoints.append(objp) - - corners2 = cv.cornerSubPix(gray,corners, (11,11), (-1,-1), criteria) - imgpoints.append(corners2) - - # Draw and display the corners - cv.drawChessboardCorners(img, (8,6), corners2, ret) - cv.imshow('img', img) - cv.waitKey(500) - - cv.destroyAllWindows() - - # Calibrate camera - ret, mtx, dist, rvecs, tvecs = cv.calibrateCamera(objpoints, imgpoints, gray.shape[::-1], None, None) - print(repr(mtx)) - print(dist) - - if args.out_path: - save_in(args.out_path, distort=dist, matrix=mtx) - - -if __name__ == '__main__': - main() \ No newline at end of file diff --git a/GEMstack/offboard/calibration/tools/save_cali.py b/GEMstack/offboard/calibration/tools/save_cali.py index dfd0da8a1..078f9784e 100644 --- a/GEMstack/offboard/calibration/tools/save_cali.py +++ b/GEMstack/offboard/calibration/tools/save_cali.py @@ -61,7 +61,8 @@ def load_in(path,mode='matrix',return_distort=False): 'skew':np.array(y['skew']), 'distort':np.array(y['distort'])} -def save_in(path,focal=None,center=None,skew=None,distort=None,matrix=None): +from collections.abc import Iterable +def save_in(path,focal=None,center=None,skew=0,distort=[0.0]*5,matrix=None): if matrix is not None: focal = matrix.diagonal()[0,-1] skew = matrix[0,1] @@ -71,11 +72,16 @@ def save_in(path,focal=None,center=None,skew=None,distort=None,matrix=None): ret = {} ret['focal'] = focal ret['center'] = center - ret['skew'] = skew or 0 - ret['distort'] = distort or [0,0,0,0,0] + ret['skew'] = skew + assert len(distort) in [4,5] + ret['distort'] = distort + if len(ret['distort']) == 4: + ret['distort'] = list(ret['distort'])+[0.0] for i in ret: if type(ret[i]) == np.ndarray: ret[i] = ret[i].tolist() + if isinstance(ret[i],Iterable): + ret[i] = [*map(float,ret[i])] print(yaml.dump(ret,Dumper=SafeDumper,default_flow_style=False)) with open(path,'w') as stream: yaml.dump(ret,stream,Dumper=SafeDumper,default_flow_style=False) From f62fb8ad96d1ffa2c0be41c5335cb85ffca41a85 Mon Sep 17 00:00:00 2001 From: rjsun-KA <92330153+rjsun06@users.noreply.github.com> Date: Tue, 29 Apr 2025 07:53:47 +0000 Subject: [PATCH 211/232] readme --- GEMstack/offboard/calibration/README.md | 1 + 1 file changed, 1 insertion(+) diff --git a/GEMstack/offboard/calibration/README.md b/GEMstack/offboard/calibration/README.md index 6cceb47e0..cb1a13820 100644 --- a/GEMstack/offboard/calibration/README.md +++ b/GEMstack/offboard/calibration/README.md @@ -19,6 +19,7 @@ python3 img2pc.py \ [--out_path OUT_PATH] \ [--n_features N_FEATURES] ``` + #### Parameters | Parameter | Description | Format | Required | Default | |-----------|-------------|--------|----------|---------| From bbfbcc39f8ace74e08cc75c0dd371d0b46c81abe Mon Sep 17 00:00:00 2001 From: Michal Juscinski Date: Tue, 29 Apr 2025 21:25:19 -0700 Subject: [PATCH 212/232] Fix bugs and standardize inputs --- .../knowledge/calibration/gem_e4_fl_in.yaml | 9 ++- .../knowledge/calibration/gem_e4_fr_in.yaml | 9 ++- .../knowledge/calibration/gem_e4_rl_in.yaml | 9 ++- .../knowledge/calibration/gem_e4_rr_in.yaml | 9 ++- GEMstack/offboard/calibration/img2pc.py | 75 +++++++------------ .../calibration/intrinsic_calibration.py | 73 ++++++++++++++++++ .../offboard/calibration/test_transforms.py | 52 ++++++------- .../offboard/calibration/tools/save_cali.py | 4 +- .../offboard/calibration/undistort_images.py | 2 +- 9 files changed, 148 insertions(+), 94 deletions(-) create mode 100644 GEMstack/offboard/calibration/intrinsic_calibration.py diff --git a/GEMstack/knowledge/calibration/gem_e4_fl_in.yaml b/GEMstack/knowledge/calibration/gem_e4_fl_in.yaml index d6677bc5e..427fec5c1 100644 --- a/GEMstack/knowledge/calibration/gem_e4_fl_in.yaml +++ b/GEMstack/knowledge/calibration/gem_e4_fl_in.yaml @@ -1,4 +1,5 @@ -center: [980, 605] -focal: [1230, 1230] -distort: [-0.23751890570984993, 0.08452214195986749, -0.00035324203850054794, -0.0003762498910536819, 0.0] -skew: 0.0 +center: [971.5122150421694, 601.7847095069886] +distort: [-0.2625420437513607, 0.1425651774165483, -0.0004946279626072071, -0.00033457504102070386, + -0.042732740327368145] +focal: [1183.2337731693713, 1182.3831532373445] +skew: 0 diff --git a/GEMstack/knowledge/calibration/gem_e4_fr_in.yaml b/GEMstack/knowledge/calibration/gem_e4_fr_in.yaml index a5a24405d..6ae475334 100644 --- a/GEMstack/knowledge/calibration/gem_e4_fr_in.yaml +++ b/GEMstack/knowledge/calibration/gem_e4_fr_in.yaml @@ -1,4 +1,5 @@ -center: [934.859447, 607.266974] -focal: [1180.753804, 1177.034929] -distort: [-0.2448506795091457, 0.08202383880344215, 0.0004294271518916802, -0.0012454354245869965, 0.0] -skew: 0.0 +center: [966.4326452411585, 608.5803255934914] +distort: [-0.2701363254469883, 0.16439325523243875, -0.001607207824773341, -7.412467081891699e-05, + -0.06199397580030171] +focal: [1176.2554468073797, 1175.1456876174707] +skew: 0 diff --git a/GEMstack/knowledge/calibration/gem_e4_rl_in.yaml b/GEMstack/knowledge/calibration/gem_e4_rl_in.yaml index d46a384fd..6cfa24337 100644 --- a/GEMstack/knowledge/calibration/gem_e4_rl_in.yaml +++ b/GEMstack/knowledge/calibration/gem_e4_rl_in.yaml @@ -1,4 +1,5 @@ -center: [955.729090, 599.315043] -focal: [1216.836137, 1216.045721] -distort: [-0.24343640079788503, 0.09125282937288573, 5.21454371097206e-06, -2.2750254391060847e-05, 0.0] -skew: 0.0 +center: [953.302889408274, 608.1966398872765] +distort: [-0.2522996862206216, 0.12482113115174773, -0.0005993692936397102, -0.00017949453391219192, + -0.03499498178003368] +focal: [1181.6177321982138, 1180.0783789769903] +skew: 0 diff --git a/GEMstack/knowledge/calibration/gem_e4_rr_in.yaml b/GEMstack/knowledge/calibration/gem_e4_rr_in.yaml index f55460559..31dd44239 100644 --- a/GEMstack/knowledge/calibration/gem_e4_rr_in.yaml +++ b/GEMstack/knowledge/calibration/gem_e4_rr_in.yaml @@ -1,4 +1,5 @@ -center: [950, 600] -focal: [1210,1210] -distort: [-0.24754745389508612, 0.09944435338953724, -3.455420573094537e-05, -0.00022029168609146265, 0.0] -skew: 0.0 +center: [956.2663906909728, 569.2039945552984] +distort: [-0.25040910859151444, 0.1109210921906881, -0.00041247665414900384, 0.0008205455176671751, + -0.026395952816984845] +focal: [1162.3787554048329, 1162.855381183851] +skew: 0 diff --git a/GEMstack/offboard/calibration/img2pc.py b/GEMstack/offboard/calibration/img2pc.py index adca936db..fd2b1a97b 100644 --- a/GEMstack/offboard/calibration/img2pc.py +++ b/GEMstack/offboard/calibration/img2pc.py @@ -1,4 +1,3 @@ -#%% import pyvista as pv import argparse import cv2 @@ -6,7 +5,7 @@ from tools.save_cali import load_ex,save_ex,load_in,save_in from scipy.spatial.transform import Rotation as R from transform3d import Transform -#%% + def pick_n_img(img,n=4): corners = [] # Reset the corners list def click_event(event, x, y, flags, param): @@ -28,7 +27,6 @@ def click_event(event, x, y, flags, param): return corners -#%% def pick_n_pc(point_cloud,n=4): points = [] def cb(pt,*args): @@ -44,7 +42,6 @@ def cb(pt,*args): plotter.show() return points -#%% def pc_projection(pc,T:Transform,K,img_shape) -> np.ndarray: mask = ~(np.all(pc == 0, axis=1)) pc = pc[mask] @@ -62,10 +59,6 @@ def pc_projection(pc,T:Transform,K,img_shape) -> np.ndarray: valid_pts = (u >= 0) & (u < img_w) & (v >= 0) & (v < img_h) return u[valid_pts],v[valid_pts] - - - - def calib(args,pc,img,K,N): cpoints = np.array(pick_n_img(img,N)).astype(float) print(cpoints) @@ -88,30 +81,27 @@ def calib(args,pc,img,K,N): if args.out_path is not None: save_ex(args.out_path,matrix=c2v) + return c2v - -#%% def main(): parser = argparse.ArgumentParser(description='register image into point cloud using manual feature selection', formatter_class=argparse.ArgumentDefaultsHelpFormatter) - parser.add_argument('--img_path', type=str, required=True, + parser.add_argument('-p', '--img_path', type=str, required=True, help='Path to PNG image') - parser.add_argument('--pc_path', type=str, required=True, - help='Path to NPZ point cloud file') - parser.add_argument('--pc_transform_path', type=str, required=False, - help='Path to ymal file for lidar calibration') - parser.add_argument('--img_intrinsics_path', type=str, required=True, - help='Path to ymal file for image intrinsics') - parser.add_argument('--out_path', type=str, required=False, - help='Path to output ymal file for image extrinsics') - parser.add_argument('--n_features', type=int, required=False, default=8, - help='number of features to select and math') + parser.add_argument('-l', '--lidar_path', type=str, required=True, + help='Path to lidar NPZ point cloud') + parser.add_argument('-t', '--lidar_transform_path', type=str, required=True, + help='Path to yaml file for lidar extrinsics') + parser.add_argument('-i', '--img_intrinsics_path', type=str, required=True, + help='Path to yaml file for image intrinsics') + parser.add_argument('-o', '--out_path', type=str, required=False, + help='Path to output yaml file for image extrinsics') + parser.add_argument('-n', '--n_features', type=int, required=False, default=8, + help='Number of features to select and math') parser.add_argument('-u','--undistort', action='store_true', - help='whether to use distortion parameters') - parser.add_argument('--fine_tune', choices=['manual'], required=False, - help='how to fine tune after first guess') - parser.add_argument('--just_projection', action='store_true', - help='just show the projection. No calibration') + help='Whether to use distortion parameters') + parser.add_argument('-s', '--show', action='store_true', + help='Show projected points after calibration') args = parser.parse_args() @@ -119,7 +109,7 @@ def main(): # Load data N = args.n_features img = cv2.imread(args.img_path, cv2.IMREAD_UNCHANGED) - pc = np.load(args.pc_path)['arr_0'] + pc = np.load(args.lidar_path)['arr_0'] pc = pc[~np.all(pc == 0, axis=1)] # remove (0,0,0)'s if args.undistort: @@ -132,30 +122,21 @@ def main(): else: K = load_in(args.img_intrinsics_path,mode='matrix') - if args.pc_transform_path is not None: - lidar_ex = load_ex(args.pc_transform_path,mode='matrix') - pc = np.pad(pc,((0,0),(0,1)),constant_values=1) @ lidar_ex.T[:,:3] + lidar_ex = load_ex(args.lidar_transform_path,mode='matrix') + pc = np.pad(pc,((0,0),(0,1)),constant_values=1) @ lidar_ex.T[:,:3] - - if not args.just_projection: - calib(args,pc,img,K,N) - - c2v = load_ex(args.out_path,mode='matrix') + c2v = calib(args,pc,img,K,N) T = np.linalg.inv(c2v) print(T) - u,v = pc_projection(pc,Transform(T),K,img.shape) - show_img = img.copy() - for uu,vv in zip(u.astype(int),v.astype(int)): - cv2.circle(show_img, (uu, vv), radius=1, color=(0, 0, 255), thickness=-1) - cv2.imshow("projection", show_img) - cv2.waitKey(0) - - if not args.fine_tune: - return - - if args.fine_tune == 'manual': - pass + if args.show: + T_lidar_camera = T @ lidar_ex + u,v = pc_projection(pc,Transform(T_lidar_camera),K,img.shape) + show_img = img.copy() + for uu,vv in zip(u.astype(int),v.astype(int)): + cv2.circle(show_img, (uu, vv), radius=1, color=(0, 0, 255), thickness=-1) + cv2.imshow("projection", show_img) + cv2.waitKey(0) if __name__ == "__main__": main() \ No newline at end of file diff --git a/GEMstack/offboard/calibration/intrinsic_calibration.py b/GEMstack/offboard/calibration/intrinsic_calibration.py new file mode 100644 index 000000000..4f4d56b5e --- /dev/null +++ b/GEMstack/offboard/calibration/intrinsic_calibration.py @@ -0,0 +1,73 @@ +import numpy as np +import cv2 as cv +import glob +import os +import argparse + +from tools.save_cali import save_in + +def main(): + # Collect arguments + parser = argparse.ArgumentParser(description='calculate intrinsics from checkerboard images', + formatter_class=argparse.ArgumentDefaultsHelpFormatter) + parser.add_argument('-f', '--img_folder_path', type=str, required=True, + help='Path to folder containing PNG images') + parser.add_argument('-c', '--camera_name', type=str, required=False, + help='Name of the camera used to identify the correct images') + parser.add_argument('-o', '--out_path', type=str, required=False, + help='Path to output ymal file for camera intrinsics') + + args = parser.parse_args() + + # Find image files + folder = args.img_folder_path + camera = '' + if args.camera_name: + camera = args.camera_name + image_files = glob.glob(os.path.join(folder, camera + '*.png')) + + # The following code is derived from https://docs.opencv.org/4.x/dc/dbb/tutorial_py_calibration.html + + # termination criteria + criteria = (cv.TERM_CRITERIA_EPS + cv.TERM_CRITERIA_MAX_ITER, 30, 0.001) + + # prepare object points, like (0,0,0), (1,0,0), (2,0,0) ....,(7,5,0) + objp = np.zeros((6*8,3), np.float32) + objp[:,:2] = np.mgrid[0:8,0:6].T.reshape(-1,2) + + # Arrays to store object points and image points from all the images. + objpoints = [] # 3d point in real world space + imgpoints = [] # 2d points in image plane. + + for fname in image_files: + img = cv.imread(fname) + gray = cv.cvtColor(img, cv.COLOR_BGR2GRAY) + + # Find the chess board corners + ret, corners = cv.findChessboardCorners(gray, (8,6), None) + + # If found, add object points, image points (after refining them) + if ret == True: + objpoints.append(objp) + + corners2 = cv.cornerSubPix(gray,corners, (11,11), (-1,-1), criteria) + imgpoints.append(corners2) + + # Draw and display the corners + cv.drawChessboardCorners(img, (8,6), corners2, ret) + cv.imshow('img', img) + cv.waitKey(500) + + cv.destroyAllWindows() + + # Calibrate camera + ret, mtx, dist, rvecs, tvecs = cv.calibrateCamera(objpoints, imgpoints, gray.shape[::-1], None, None) + print(repr(mtx)) + print(dist[0]) + + if args.out_path: + save_in(args.out_path, matrix=mtx) + + +if __name__ == '__main__': + main() \ No newline at end of file diff --git a/GEMstack/offboard/calibration/test_transforms.py b/GEMstack/offboard/calibration/test_transforms.py index 1740fdc69..5edb5e538 100644 --- a/GEMstack/offboard/calibration/test_transforms.py +++ b/GEMstack/offboard/calibration/test_transforms.py @@ -1,13 +1,12 @@ import numpy as np -import cv2 +import cv2 as cv import matplotlib.pyplot as plt import argparse from scipy.spatial.transform import Rotation as R from matplotlib.widgets import Slider from tools.save_cali import load_ex, load_in, save_ex -keep_running = True -scale, x_rot, y_rot, z_rot, x_trans, y_trans, z_trans = None +x_rot = y_rot = z_rot = x_trans = y_trans = z_trans = None def project_points(T_lidar_camera, lidar_homogeneous, K, shape): # Transform LiDAR points to Camera Frame @@ -30,20 +29,19 @@ def project_points(T_lidar_camera, lidar_homogeneous, K, shape): img_h, img_w, _ = shape valid_pts = (u >= 0) & (u < img_w) & (v >= 0) & (v < img_h) u, v = u[valid_pts], v[valid_pts] + return u, v def modify_transform(T_lidar_camera): modified = np.copy(T_lidar_camera) rotation_mat = R.from_euler('xyz', [x_rot.val, y_rot.val, z_rot.val], degrees=True).as_matrix() - scale_mat = np.array([[scale.val, 0, 0], [0, scale.val, 0], [0, 0, scale.val]]) translation_vec = np.array([x_trans.val, y_trans.val, z_trans.val]) - modified[:3, :3] = T_lidar_camera[:3, :3] @ rotation_mat @ scale_mat + modified[:3, :3] = T_lidar_camera[:3, :3] @ rotation_mat modified[:3, 3] = T_lidar_camera[:3, 3] + translation_vec return modified def create_sliders(fig, update_func): # Create space for sliders fig.subplots_adjust(bottom=0.4) - scale_ax = fig.add_axes([0.25, 0.35, 0.65, 0.03]) x_rot_ax = fig.add_axes([0.25, 0.3, 0.65, 0.03]) y_rot_ax = fig.add_axes([0.25, 0.25, 0.65, 0.03]) z_rot_ax = fig.add_axes([0.25, 0.2, 0.65, 0.03]) @@ -51,17 +49,6 @@ def create_sliders(fig, update_func): y_trans_ax = fig.add_axes([0.25, 0.1, 0.65, 0.03]) z_trans_ax = fig.add_axes([0.25, 0.05, 0.65, 0.03]) - # Make a slider to control the scale - global scale - scale = Slider( - ax=scale_ax, - label="Scale", - valmin=0.75, - valmax=1.25, - valinit=1, - orientation="horizontal" - ) - # Make sliders to control the rotation global x_rot x_rot = Slider( @@ -125,7 +112,6 @@ def create_sliders(fig, update_func): ) # Register the update function with each slider - scale.on_changed(update_func) x_rot.on_changed(update_func) y_rot.on_changed(update_func) z_rot.on_changed(update_func) @@ -140,15 +126,17 @@ def main(): parser.add_argument('-p', '--img_path', type=str, required=True, help='Path to PNG image') parser.add_argument('-l', '--lidar_path', type=str, required=True, - help='Path to lidar point cloud') + help='Path to lidar NPZ point cloud') parser.add_argument('-t', '--lidar_transform_path', type=str, required=True, help='Path to lidar extrinsics') parser.add_argument('-e', '--camera_transform_path', type=str, required=True, help='Path to camera extrinsics') parser.add_argument('-i', '--img_intrinsics_path', type=str, required=True, - help='Path to ymal file for image intrinsics') + help='Path to yaml file for image intrinsics') parser.add_argument('-o', '--out_path', type=str, required=False, help='Path to output ymal file for camera intrinsics') + parser.add_argument('-u','--undistort', action='store_true', + help='Whether to use distortion parameters') args = parser.parse_args() @@ -157,16 +145,23 @@ def main(): lidar_points = lidar_data['arr_0'] # Ensure the correct key # Load Camera Image - image = cv2.imread(args.img_path) - image = cv2.cvtColor(image, cv2.COLOR_BGR2RGB) # Convert BGR to RGB + image = cv.imread(args.img_path) + image = cv.cvtColor(image, cv.COLOR_BGR2RGB) # Convert BGR to RGB # Load Transformation Matrices - T_lidar_vehicle = load_ex(args.lidar_transform_path) - T_camera_vehicle = load_ex(args.camera_transform_path) + T_lidar_vehicle = load_ex(args.lidar_transform_path, 'matrix') + T_camera_vehicle = load_ex(args.camera_transform_path, 'matrix') T_lidar_camera = np.linalg.inv(T_camera_vehicle) @ T_lidar_vehicle # Load Camera Intrinsics - K = load_in(args.img_intrinsics_path) + if args.undistort: + K, distortion_coefficients = load_in(args.img_intrinsics_path, return_distort=True) + h, w = image.shape[:2] + new_K, roi = cv.getOptimalNewCameraMatrix(K, distortion_coefficients, (w,h), 1, (w,h)) + image = cv.undistort(image, K, distortion_coefficients, None, new_K) + K = new_K + else: + K = load_in(args.img_intrinsics_path) # Convert LiDAR points to homogeneous coordinates num_points = lidar_points.shape[0] @@ -189,7 +184,7 @@ def update(val): modified = modify_transform(T_lidar_camera) # Update projected points - u, v = project_points(T_lidar_camera, lidar_homogeneous, K, image.shape) + u, v = project_points(modified, lidar_homogeneous, K, image.shape) dots.set_offsets(np.c_[u, v]) plt.draw() @@ -198,6 +193,7 @@ def update(val): plt.draw() # Update and keep displaying the modified plot + keep_running = True while keep_running: try: if plt.get_fignums(): @@ -209,9 +205,9 @@ def update(val): # Output and write the fine-tuned translation matrix modified = modify_transform(T_lidar_camera) - print(modified) + print(T_lidar_vehicle @ np.linalg.inv(modified)) if args.out_path: - save_ex(args.out_path, matrix=modified) + save_ex(args.out_path, matrix=T_lidar_vehicle @ np.linalg.inv(modified)) if __name__ == '__main__': main() \ No newline at end of file diff --git a/GEMstack/offboard/calibration/tools/save_cali.py b/GEMstack/offboard/calibration/tools/save_cali.py index 078f9784e..1213a249a 100644 --- a/GEMstack/offboard/calibration/tools/save_cali.py +++ b/GEMstack/offboard/calibration/tools/save_cali.py @@ -64,10 +64,10 @@ def load_in(path,mode='matrix',return_distort=False): from collections.abc import Iterable def save_in(path,focal=None,center=None,skew=0,distort=[0.0]*5,matrix=None): if matrix is not None: - focal = matrix.diagonal()[0,-1] + focal = matrix.diagonal()[0:2] skew = matrix[0,1] center = matrix[0:2,2] - save_in(path,focal,center) + save_in(path,focal,center,skew,distort) return ret = {} ret['focal'] = focal diff --git a/GEMstack/offboard/calibration/undistort_images.py b/GEMstack/offboard/calibration/undistort_images.py index 847ab3c61..7830cb4f2 100644 --- a/GEMstack/offboard/calibration/undistort_images.py +++ b/GEMstack/offboard/calibration/undistort_images.py @@ -4,7 +4,7 @@ import os import argparse -from tools.save_cali import load_in, save_in +from tools.save_cali import load_in def main(): # Collect arguments From ca6b137ff7a354668c35961681a27603cd0fb048 Mon Sep 17 00:00:00 2001 From: Michal Juscinski Date: Tue, 29 Apr 2025 21:26:44 -0700 Subject: [PATCH 213/232] Corner camera extrinsic calibrations v2.1 --- GEMstack/knowledge/calibration/gem_e4_fl.yaml | 5 +++++ GEMstack/knowledge/calibration/gem_e4_fr.yaml | 5 +++++ GEMstack/knowledge/calibration/gem_e4_rl.yaml | 5 +++++ GEMstack/knowledge/calibration/gem_e4_rr.yaml | 5 +++++ 4 files changed, 20 insertions(+) create mode 100644 GEMstack/knowledge/calibration/gem_e4_fl.yaml create mode 100644 GEMstack/knowledge/calibration/gem_e4_fr.yaml create mode 100644 GEMstack/knowledge/calibration/gem_e4_rl.yaml create mode 100644 GEMstack/knowledge/calibration/gem_e4_rr.yaml diff --git a/GEMstack/knowledge/calibration/gem_e4_fl.yaml b/GEMstack/knowledge/calibration/gem_e4_fl.yaml new file mode 100644 index 000000000..981ddb41f --- /dev/null +++ b/GEMstack/knowledge/calibration/gem_e4_fl.yaml @@ -0,0 +1,5 @@ +position: [1.7971794298679513, 0.796146176758752, 1.6332326141698077] +reference: rear_axle_center +rotation: [[0.7233635906739921, -0.14419134401014552, 0.6752436288506333], [-0.6903910162108187, + -0.1655825397435263, 0.704231975598754], [0.010264405559124336, -0.9755979073185922, + -0.21932478610916173]] diff --git a/GEMstack/knowledge/calibration/gem_e4_fr.yaml b/GEMstack/knowledge/calibration/gem_e4_fr.yaml new file mode 100644 index 000000000..f8216491b --- /dev/null +++ b/GEMstack/knowledge/calibration/gem_e4_fr.yaml @@ -0,0 +1,5 @@ +position: [1.8472221433459501, -0.6787392587860782, 1.7022719016848669] +reference: rear_axle_center +rotation: [[-0.7183636802296961, -0.09720447265520028, 0.6888431700262477], [-0.6952720410463521, + 0.13371206053116463, -0.7061995993856021], [-0.023460874382859997, -0.9862415394928613, + -0.16363744458479873]] diff --git a/GEMstack/knowledge/calibration/gem_e4_rl.yaml b/GEMstack/knowledge/calibration/gem_e4_rl.yaml new file mode 100644 index 000000000..f1bf54dc0 --- /dev/null +++ b/GEMstack/knowledge/calibration/gem_e4_rl.yaml @@ -0,0 +1,5 @@ +position: [0.07110185305534555, 0.6984132712665948, 1.4339602315138475] +reference: rear_axle_center +rotation: [[0.6844266376508905, 0.18773036711896313, -0.7044980446374145], [0.7276311666895623, + -0.11495808685709714, 0.6762673507510828], [0.045968178413242806, -0.9754701225801333, + -0.21527884108421258]] diff --git a/GEMstack/knowledge/calibration/gem_e4_rr.yaml b/GEMstack/knowledge/calibration/gem_e4_rr.yaml new file mode 100644 index 000000000..cf740f188 --- /dev/null +++ b/GEMstack/knowledge/calibration/gem_e4_rr.yaml @@ -0,0 +1,5 @@ +position: [0.16800762903335675, -0.7256009189651329, 1.6932350855315166] +reference: rear_axle_center +rotation: [[-0.7276140422452938, 0.15527317181293687, -0.6681826404962411], [0.6858832251924825, + 0.14775049453955932, -0.7125545527127647], [-0.011916291664040228, -0.9767599622253681, + -0.21400460836988996]] From 5e87e709bc37f52982e5ed8dbebbceebf7796a1e Mon Sep 17 00:00:00 2001 From: michalj1 Date: Wed, 30 Apr 2025 10:00:17 -0500 Subject: [PATCH 214/232] Allow variable checkerboard sizes --- .../calibration/intrinsic_calibration.py | 20 +++++++++++++++---- 1 file changed, 16 insertions(+), 4 deletions(-) diff --git a/GEMstack/offboard/calibration/intrinsic_calibration.py b/GEMstack/offboard/calibration/intrinsic_calibration.py index 4f4d56b5e..6226dc65e 100644 --- a/GEMstack/offboard/calibration/intrinsic_calibration.py +++ b/GEMstack/offboard/calibration/intrinsic_calibration.py @@ -16,6 +16,10 @@ def main(): help='Name of the camera used to identify the correct images') parser.add_argument('-o', '--out_path', type=str, required=False, help='Path to output ymal file for camera intrinsics') + parser.add_argument('-w', '--board_width', type=int, required=False, + help='Width in number of internal corners of the checkerboard') + parser.add_argument('-h', '--board_height', type=int, required=False, + help='Height in number of internal corners of the checkerboard') args = parser.parse_args() @@ -26,14 +30,22 @@ def main(): camera = args.camera_name image_files = glob.glob(os.path.join(folder, camera + '*.png')) + # Determine checkerboard shape + b_width = 8 + if args.board_width: + b_width = args.board_width + b_height = 6 + if args.board_height: + b_height = args.board_height + # The following code is derived from https://docs.opencv.org/4.x/dc/dbb/tutorial_py_calibration.html # termination criteria criteria = (cv.TERM_CRITERIA_EPS + cv.TERM_CRITERIA_MAX_ITER, 30, 0.001) # prepare object points, like (0,0,0), (1,0,0), (2,0,0) ....,(7,5,0) - objp = np.zeros((6*8,3), np.float32) - objp[:,:2] = np.mgrid[0:8,0:6].T.reshape(-1,2) + objp = np.zeros((b_width * b_height,3), np.float32) + objp[:,:2] = np.mgrid[0:b_width,0:b_height].T.reshape(-1,2) # Arrays to store object points and image points from all the images. objpoints = [] # 3d point in real world space @@ -44,7 +56,7 @@ def main(): gray = cv.cvtColor(img, cv.COLOR_BGR2GRAY) # Find the chess board corners - ret, corners = cv.findChessboardCorners(gray, (8,6), None) + ret, corners = cv.findChessboardCorners(gray, (b_width, b_height), None) # If found, add object points, image points (after refining them) if ret == True: @@ -54,7 +66,7 @@ def main(): imgpoints.append(corners2) # Draw and display the corners - cv.drawChessboardCorners(img, (8,6), corners2, ret) + cv.drawChessboardCorners(img, (b_width,b_height), corners2, ret) cv.imshow('img', img) cv.waitKey(500) From 18ff86eb588dbad49b95fd1bb10e667b32ec96c0 Mon Sep 17 00:00:00 2001 From: michalj1 Date: Wed, 30 Apr 2025 15:45:09 -0500 Subject: [PATCH 215/232] Update README and fix bugs --- GEMstack/offboard/calibration/README.md | 143 +++++++++++++++++- GEMstack/offboard/calibration/camera_info.py | 4 +- .../offboard/calibration/undistort_images.py | 2 +- 3 files changed, 138 insertions(+), 11 deletions(-) diff --git a/GEMstack/offboard/calibration/README.md b/GEMstack/offboard/calibration/README.md index cb1a13820..5e374a772 100644 --- a/GEMstack/offboard/calibration/README.md +++ b/GEMstack/offboard/calibration/README.md @@ -1,9 +1,37 @@ ## Table of Contents +- [Pipeline](#Pipeline) - [img2pc.py](#img2pcpy) - Camera-to-LiDAR extrinsic calibration +- [test_transforms.py](#test_transformspy) - Manual tuning of calibrations +- [capture_ouster_oak.py](#capture_ouster_oakpy) - Sensor data capture script +- [camera_info.py](#camera_infopy) - Intrinsic retrieval from hardware - [get_intrinsic_by_chessboard.py](#get_intrinsic_by_chessboardpy) - Intrinsic calibration using chessboard - [get_intrinsic_by_SfM.py](#get_intrinsic_by_sfmpy) - Intrinsic calibration using SfM +- [undistort_images.py](#undistort_imagespy) - Create rectified copies of distorted images --- +# Pipeline +**Data collection** + +Use the `capture_ouster_oak.py` script to collect a series of scans combining both camera images and lidar pointclouds. The two sensors are not activated at the same time, so it is best to stay in place for a few seconds at each position to ensure you get aligned scans. + +Some cameras may have calibrated hardware: use the `camera_info.py` script to extract their intrinsics if needed. An output containing all zeros means the hardware is not calibrated, and so you will need to calibrate yourself. + +**Intrinsic Calibration** + +There are two ways to calibrate the intrinsics, depending on what data you have. + +To use the `get_intrinsic_by_chessboard.py` script, collect a series of images with a large chessboard using either the data collection scripts or a rosbag. Select images where the chessboard is at different points in the camera frame, different distances including filling the entire frame, and at different angles. The script detects internal corners where four squares meet, so the extreme edge of the chessboard does not need to be in frame. + +To use the `get_intrinsic_by_SfM.py` script, *[fill in here]* + +The `undistort_images.py` script can then be used to rectify a set of images using the calibrated intrinsics to evaluate or use in other applications. + +**Extrinsic Calibration** + +The `img2pc.py` file contains the main part of the extrinsic calibration process. Select a synchronized camera image and lidar pointcloud to align, ideally containing features that are easy to detect in both, such as boards or signs with corners. Alignment can be done with *[explain minimum number of points and any limitations on them]*. The first screen will ask you to select points on the image, and will close on its own once *n_features* points are selected. The second screen will ask you to select points in the point cloud, and will need to be closed manually once exactly *n_features* points are selected, or it will prompt you again. The extrinsic matrices will then be displayed, and if an *out_path* is provided they will also be saved. + +The `test_transforms.py` file can then be used to manually fine-tune the calculated intrinsics. Use the sliders to change the translation and rotation to project the lidar points onto the image more accurately. + ## img2pc.py **Camera-to-LiDAR Extrinsic Calibration Tool** @@ -42,6 +70,72 @@ python3 img2pc.py \ --out_path $root/GEMstack/knowledge/calibration/gem_e4_oak.yaml ``` +## test_transforms.py +Script used for testing and fine-tuning extrinsics. + +### Usage +```bash +python3 test_transforms.py \ + --img_path IMG_PATH \ + --lidar_path LIDAR_PATH \ + --lidar_transform_path LIDAR_TRANSFORM_PATH \ + --camera_transform_path CAMERA_TRANSFORM_PATH \ + --img_intrinsics_path IMG_INTRINSICS_PATH \ + [--out_path OUT_PATH] \ + [--undistort] +``` + +#### Parameters +| Parameter | Description | Format | Required | Default | +|-----------|-------------|--------|----------|---------| +| `--img_path` | Input image path | .png | Yes | - | +| `--lidar_path` | Point cloud path | .npz | Yes | - | +| `--lidar_transform_path` | LiDAR extrinsic transform | .yaml | Yes | - | +| `--camera_transform_path` | Camera extrinsic transform | .yaml | Yes | - | +| `--img_intrinsics_path` | Camera intrinsics file | .yaml | Yes | - | +| `--out_path` | Output extrinsic path | .yaml | No | None | +| `--undistort` | Flag for using distortion coefficients | - | - | - | + +### Example +```bash +root='/mnt/GEMstack' +python3 test_transforms.py \ + --img_path $root/data/fl16.png \ + --lidar_path $root/data/ouster16.npz \ + --lidar_transform_path $root/GEMstack/knowledge/calibration/gem_e4_ouster.yaml \ + --camera_transform_path $root/GEMstack/knowledge/calibration/gem_e4_fl.yaml \ + --img_intrinsics_path $root/GEMstack/knowledge/calibration/gem_e4_fl_in.yaml \ + --out_path $root/GEMstack/knowledge/calibration/gem_e4_fl.yaml \ + --undistort +``` + +## capture_ouster_oak.py +Collect synchronized data from all initialized sensors on the e4 vehicle. Requires oak camera to be running. + +### Usage +```bash +python3 capture_ouster_oak.py [FOLDER] [START_INDEX] +``` + +#### Parameters +| Parameter | Description | Format | Required | Default | +|-----------|-------------|--------|----------|---------| +| `FOLDER` | Output data folder path | directory | No | data | +| `START_INDEX` | Start index for scans | int | No | 1 | + +## camera_info.py +Read camera info from ROS publishers to capture intrinsics. If the hardware is not calibrated, the subscriber will receive all zeros. Intrinsics will be saved in a file titled by camera. + +### Usage +```bash +python3 camera_info.py [FOLDER] +``` + +#### Parameters +| Parameter | Description | Format | Required | Default | +|-----------|-------------|--------|----------|---------| +| `FOLDER` | Output data folder path | directory | No | data | + ## get_intrinsic_by_chessboard.py Chessboard-based Intrinsic Calibration @@ -49,16 +143,22 @@ Compute camera intrinsic parameters using multiple images of a chessboard patter ### Usage ```bash -python3 get_intrinsic_by_chessboard.py IMG_DIR WIDTH HEIGHT [OUTPUT_PATH] +python3 get_intrinsic_by_chessboard.py \ + --img_folder_path IMG_FOLDER_PATH \ + [--camera_name CAMERA_NAME] \ + [--out_path OUT_PATH] \ + [--board_width BOARD_WIDTH] \ + [--board_height BOARD_HEIGHT] ``` -### Parameters -| Parameter | Description | Required | -|-----------|-------------|----------| -| `IMG_DIR` | Calibration images folder | Yes | -| `WIDTH` | Chessboard width (squares-1) | Yes | -| `HEIGHT` | Chessboard height (squares-1) | Yes | -| `OUTPUT_PATH` | Output .yaml path | No | +#### Parameters +| Parameter | Description | Format | Required | Default | +|-----------|-------------|--------|----------|---------| +| `--img_folder_path` | Input image folder path | directory | Yes | - | +| `--camera_name` | Camera prefix used to identify images | string | No | empty string | +| `--out_path` | Output extrinsic path | .yaml | No | None | +| `--board_width` | Chessboard width (squares - 1) | int | No | 8 | +| `--board_height` | Chessboard height (squares - 1) | int | No | 6 | ## get_intrinsic_by_SfM.py @@ -88,6 +188,33 @@ python3 intrinsic_calibration_chessboard.py \ --out_file $root/GEMstack/knowledge/calibration/camera_intrinsics2/gem_e4_fl_in.yaml ``` +## undistort_images.py +Script to remove distortion from images. + +### Usage +```bash +python3 undistort_images.py \ + --img_intrinsics_path IMG_INTRINSICS_PATH \ + --img_folder_path IMG_FOLDER_PATH \ + --camera_name CAMERA_NAME +``` + +#### Parameters +| Parameter | Description | Format | Required | Default | +|-----------|-------------|--------|----------|---------| +| `--img_intrinsics_path` | Camera intrinsics file | .yaml | Yes | - | +| `--img_folder_path` | Input image folder path | directory | Yes | - | +| `--camera_name` | Camera prefix used to identify images | string | No | empty string | + +### Example +```bash +root='/mnt/GEMstack' +python3 undistort_images.py \ + --img_intrinsics_path $root/GEMstack/knowledge/calibration/gem_e4_fr_in.yaml \ + --img_folder_path $root/data \ + --camera_name fr +``` + # Credit Michal Juscinski, [Renjie Sun](https://github.com/rjsun06), Dev Sakaria diff --git a/GEMstack/offboard/calibration/camera_info.py b/GEMstack/offboard/calibration/camera_info.py index c37c994e6..1ea9064ac 100644 --- a/GEMstack/offboard/calibration/camera_info.py +++ b/GEMstack/offboard/calibration/camera_info.py @@ -27,7 +27,7 @@ def get_intrinsics(folder): save_file = input("Save this file?") if save_file.lower() == 'y' or save_file.lower() == 'yes': print("Saving") - save_in(path=folder, distort=model.distortionCoeffs(), matrix=model.intrinsicMatrix()) + save_in(path=folder + f"/{camera}.yaml", distort=model.distortionCoeffs(), matrix=model.intrinsicMatrix()) else: print("Not saved") @@ -54,7 +54,7 @@ def main(folder='data'): if __name__ == '__main__': import sys - folder = 'GEMstack/knowledge/calibration' + folder = 'data' if len(sys.argv) >= 2: folder = sys.argv[1] main(folder) diff --git a/GEMstack/offboard/calibration/undistort_images.py b/GEMstack/offboard/calibration/undistort_images.py index 7830cb4f2..cf48c5d2a 100644 --- a/GEMstack/offboard/calibration/undistort_images.py +++ b/GEMstack/offboard/calibration/undistort_images.py @@ -11,7 +11,7 @@ def main(): parser = argparse.ArgumentParser(description='Create copies of images with the distortion removed', formatter_class=argparse.ArgumentDefaultsHelpFormatter) parser.add_argument('-i', '--img_intrinsics_path', type=str, required=True, - help='Path to ymal file for image intrinsics') + help='Path to yaml file for image intrinsics') parser.add_argument('-f', '--img_folder_path', type=str, required=True, help='Path to folder containing PNG images') parser.add_argument('-c', '--camera_name', type=str, required=False, From 78caddc3cac2401d0871ee298f1ecc9e87c3dada Mon Sep 17 00:00:00 2001 From: rjsun-KA <92330153+rjsun06@users.noreply.github.com> Date: Wed, 30 Apr 2025 20:54:15 +0000 Subject: [PATCH 216/232] mapping based localization using lidar scans --- .gitignore | 4 +- .../calibration/global_lidar_localization.py | 521 ++++++++++++++++++ 2 files changed, 524 insertions(+), 1 deletion(-) create mode 100644 GEMstack/offboard/calibration/global_lidar_localization.py diff --git a/.gitignore b/.gitignore index c34d6c8d3..2ee751866 100644 --- a/.gitignore +++ b/.gitignore @@ -173,4 +173,6 @@ GEMstack/offboard/calibration/calibration_by_segmentation/refined_proj_seg.png GEMstack/offboard/calibration/calibration_by_segmentation/refined_proj.png GEMstack/offboard/calibration/calibration_by_segmentation/extrinsic.txt -repo/ \ No newline at end of file +repo/ +GEMstack/offboard/calibration/data/ +GEMstack/offboard/calibration/global_registration_result.txt diff --git a/GEMstack/offboard/calibration/global_lidar_localization.py b/GEMstack/offboard/calibration/global_lidar_localization.py new file mode 100644 index 000000000..62b7b50be --- /dev/null +++ b/GEMstack/offboard/calibration/global_lidar_localization.py @@ -0,0 +1,521 @@ +#!/usr/bin/env python3 +import numpy as np +import open3d as o3d +import copy +import time +import argparse +import os +import glob +from scipy.spatial.transform import Rotation as R + +def load_map(map_file): + """Load a .ply map file.""" + print(f"Loading map from {map_file}...") + try: + map_pcd = o3d.io.read_point_cloud(map_file) + points = np.asarray(map_pcd.points) + print(f"Map stats:") + print(f" Number of points: {len(points)}") + print(f" Min: {np.min(points, axis=0)}") + print(f" Max: {np.max(points, axis=0)}") + + # Calculate map center for later use + map_center = np.mean(points, axis=0) + print(f" Center: {map_center}") + + return map_pcd + except Exception as e: + print(f"Error loading map: {e}") + return None, None + +def load_lidar_scan(scan_file): + """Load a .npz lidar scan file.""" + print(f"Loading lidar scan from {scan_file}...") + try: + data = np.load(scan_file, allow_pickle=True) + + # Use 'arr_0' as the key for your .npz files + if 'arr_0' in data: + points = data['arr_0'] + elif 'points' in data: + points = data['points'] + else: + points = data[list(data.keys())[0]] + + # Create point cloud from numpy array + scan_pcd = o3d.geometry.PointCloud() + scan_pcd.points = o3d.utility.Vector3dVector(points[:, :3]) + + # Add intensity as colors if available (4th column) + if points.shape[1] >= 4: + intensities = points[:, 3] + normalized_intensity = (intensities - np.min(intensities)) / (np.max(intensities) - np.min(intensities) + 1e-10) + colors = np.zeros((points.shape[0], 3)) + colors[:, 0] = normalized_intensity # Map intensity to red channel + colors[:, 1] = normalized_intensity # Map intensity to green channel + colors[:, 2] = normalized_intensity # Map intensity to blue channel + scan_pcd.colors = o3d.utility.Vector3dVector(colors) + + print(f"Scan loaded with {len(np.asarray(scan_pcd.points))} points") + + # Print scan stats + points = np.asarray(scan_pcd.points) + print(f"Scan stats:") + print(f" Number of points: {len(points)}") + print(f" Min: {np.min(points, axis=0)}") + print(f" Max: {np.max(points, axis=0)}") + + return scan_pcd + except Exception as e: + print(f"Error loading scan: {e}") + return None + +def load_all_scans_from_folder(folder_path): + """Load all .npz files from a folder as lidar scans.""" + print(f"Loading all lidar scans from {folder_path}...") + + # First validate that the path exists and is a directory + if not os.path.isdir(folder_path): + print(f"Error: {folder_path} is not a valid directory") + return [] + + # List all files in the directory (for debugging) + all_files = os.listdir(folder_path) + print(f"All files in directory: {len(all_files)}") + + # Get all .npz files using glob + scan_files = glob.glob(os.path.join(folder_path, "*.npz")) + + if not scan_files: + print(f"No .npz files found in {folder_path}") + print(f"Files in directory: {all_files}") + return [] + + print(f"Found {len(scan_files)} scan files") + scan_list = [] + + for scan_file in scan_files: + print(f"Loading {os.path.basename(scan_file)}...") + scan = load_lidar_scan(scan_file) + if scan is not None: + scan_list.append(scan) + + print(f"Successfully loaded {len(scan_list)} scans") + return scan_list + +def remove_floor_ceiling(pcd, z_min=-0.5, z_max=2.5): + """Remove floor and ceiling points to focus on walls and structural features.""" + points = np.asarray(pcd.points) + mask = np.logical_and(points[:, 2] > z_min, points[:, 2] < z_max) + + filtered_pcd = o3d.geometry.PointCloud() + filtered_pcd.points = o3d.utility.Vector3dVector(points[mask]) + if pcd.has_colors(): + filtered_pcd.colors = o3d.utility.Vector3dVector(np.asarray(pcd.colors)[mask]) + + return filtered_pcd + +def extract_structural_features(pcd, voxel_size): + """Extract structural features like walls from point cloud.""" + # Downsample first + pcd_down = pcd.voxel_down_sample(voxel_size) + + # Estimate normals + pcd_down.estimate_normals( + o3d.geometry.KDTreeSearchParamHybrid(radius=voxel_size*2, max_nn=30)) + + # Find planar segments (walls, floors, etc.) + planes = [] + rest = copy.deepcopy(pcd_down) + for i in range(6): # Extract top 6 planes + if len(np.asarray(rest.points)) < 100: + break + plane_model, inliers = rest.segment_plane(distance_threshold=voxel_size*2, + ransac_n=3, + num_iterations=1000) + if len(inliers) < 50: + break + + plane = rest.select_by_index(inliers) + planes.append(plane) + rest = rest.select_by_index(inliers, invert=True) + + # Combine planes into a single point cloud + structural_pcd = o3d.geometry.PointCloud() + for plane in planes: + structural_pcd += plane + + # If no planes were found, return the original downsampled point cloud + if len(planes) == 0: + return pcd_down + + return structural_pcd + +def fuse_scans(scan_list, voxel_size=0.1): + """Fuse multiple LiDAR scans into a single point cloud.""" + if not scan_list: + return None + + # Start with the first scan + fused_pcd = copy.deepcopy(scan_list[0]) + + # Add points from subsequent scans + for scan in scan_list[1:]: + fused_pcd += scan + + # Downsample to maintain uniform density + fused_pcd = fused_pcd.voxel_down_sample(voxel_size) + + # Print stats for fused scan + fused_points = np.asarray(fused_pcd.points) + print(f"Fused scan stats:") + print(f" Number of points: {len(fused_points)}") + print(f" Min: {np.min(fused_points, axis=0)}") + print(f" Max: {np.max(fused_points, axis=0)}") + + return fused_pcd + +def prepare_scan_for_global_registration(scan_pcd, map_pcd, scale_ratio=None): + """Improved scaling/translation using actual map bounds""" + # Get map dimensions + map_points = np.asarray(map_pcd.points) + map_min = np.min(map_points, axis=0) + map_max = np.max(map_points, axis=0) + map_center = (map_min + map_max) / 2 + + # Get scan dimensions + scan_points = np.asarray(scan_pcd.points) + scan_min = np.min(scan_points, axis=0) + scan_max = np.max(scan_points, axis=0) + + # Calculate dynamic scale ratio + if not scale_ratio: + map_range = map_max - map_min + scan_range = scan_max - scan_min + scale_ratio = np.min(map_range / scan_range) * 0.8 # Use 80% of map size + + # Apply scaling and center alignment + scaled_points = (scan_points - scan_min) * scale_ratio + map_min + + aligned_scan = o3d.geometry.PointCloud() + aligned_scan.points = o3d.utility.Vector3dVector(scaled_points) + + print(f"Dynamic scaling ratio: {scale_ratio}") + return aligned_scan + + + + +def preprocess_point_cloud(pcd, voxel_size, radius_normal=None, radius_feature=None): + """Modified feature parameters for better matching""" + pcd_down = pcd.voxel_down_sample(voxel_size) + + # Larger radii to capture building-scale features + radius_normal = radius_normal or voxel_size * 5.0 # Increased from 2.0 + radius_feature = radius_feature or voxel_size * 10.0 # Increased from 5.0 + + pcd_down.estimate_normals( + o3d.geometry.KDTreeSearchParamHybrid(radius=radius_normal, max_nn=50)) + + pcd_fpfh = o3d.pipelines.registration.compute_fpfh_feature( + pcd_down, + o3d.geometry.KDTreeSearchParamHybrid(radius=radius_feature, max_nn=100)) + + return pcd_down, pcd_fpfh + + + +def execute_global_registration(source_down, target_down, source_fpfh, target_fpfh, + voxel_size, max_iterations=1000000): + """Improved RANSAC registration with configurable iterations.""" + distance_threshold = voxel_size * 15 # Increased for initial alignment + + result = o3d.pipelines.registration.registration_ransac_based_on_feature_matching( + source_down, target_down, source_fpfh, target_fpfh, True, + distance_threshold, + o3d.pipelines.registration.TransformationEstimationPointToPoint(False), + 4, + [o3d.pipelines.registration.CorrespondenceCheckerBasedOnEdgeLength(0.9), + o3d.pipelines.registration.CorrespondenceCheckerBasedOnDistance(distance_threshold), + o3d.pipelines.registration.CorrespondenceCheckerBasedOnNormal(0.5)], + o3d.pipelines.registration.RANSACConvergenceCriteria(max_iterations, 500)) + + return result + + + +def execute_fast_global_registration(source_down, target_down, source_fpfh, target_fpfh, voxel_size): + """Perform Fast Global Registration.""" + distance_threshold = voxel_size * 0.5 + print(f":: Apply fast global registration with distance threshold {distance_threshold:.3f}") + + try: + result = o3d.pipelines.registration.registration_fgr_based_on_feature_matching( + source_down, target_down, source_fpfh, target_fpfh, + o3d.pipelines.registration.FastGlobalRegistrationOption( + maximum_correspondence_distance=distance_threshold)) + return result + except RuntimeError as e: + print(f"Error in FGR: {e}") + # Return dummy result with identity transformation in case of failure + dummy_result = o3d.pipelines.registration.RegistrationResult() + dummy_result.transformation = np.identity(4) + dummy_result.fitness = 0.0 + dummy_result.inlier_rmse = 0.0 + dummy_result.correspondence_set = [] + return dummy_result + +def multi_scale_icp(source, target, voxel_sizes=[2.0, 1.0, 0.5], max_iterations=[50, 30, 14], + initial_transform=np.eye(4)): + """Perform multi-scale ICP for robust alignment.""" + print("Running multi-scale ICP...") + current_transform = initial_transform + + for i, (voxel_size, max_iter) in enumerate(zip(voxel_sizes, max_iterations)): + print(f"ICP Scale {i+1}/{len(voxel_sizes)}: voxel_size={voxel_size}, max_iterations={max_iter}") + + # Downsample based on current voxel size + source_down = source.voxel_down_sample(voxel_size) + target_down = target.voxel_down_sample(voxel_size) + + # Estimate normals if not already computed + source_down.estimate_normals( + o3d.geometry.KDTreeSearchParamHybrid(radius=voxel_size*2, max_nn=30)) + target_down.estimate_normals( + o3d.geometry.KDTreeSearchParamHybrid(radius=voxel_size*2, max_nn=30)) + + # Use appropriate distance threshold based on scale + distance_threshold = max(0.5, voxel_size * 2) + + # Run ICP + result = o3d.pipelines.registration.registration_icp( + source_down, target_down, distance_threshold, current_transform, + o3d.pipelines.registration.TransformationEstimationPointToPoint(), + o3d.pipelines.registration.ICPConvergenceCriteria(max_iteration=max_iter)) + + current_transform = result.transformation + print(f" Scale {i+1} result - Fitness: {result.fitness:.4f}, RMSE: {result.inlier_rmse:.4f}") + + return current_transform + +def transform_to_pose(transformation_matrix): + """Convert transformation matrix to position and orientation (RPY).""" + # Extract translation + x, y, z = transformation_matrix[:3, 3] + + # Extract rotation matrix and convert to Euler angles + # Make a writable copy to avoid read-only array issues + rotation_matrix = np.array(transformation_matrix[:3, :3], copy=True) + r = R.from_matrix(rotation_matrix) + roll, pitch, yaw = r.as_euler('xyz', degrees=True) + + return x, y, z, roll, pitch, yaw + +def draw_registration_result(source, target, transformation): + """Visualize the source and target point clouds after alignment.""" + source_temp = copy.deepcopy(source) + target_temp = copy.deepcopy(target) + + source_temp.paint_uniform_color([1, 0.706, 0]) # Orange for source + target_temp.paint_uniform_color([0, 0.651, 0.929]) # Blue for target + + source_temp.transform(transformation) + + # Downsample for visualization if point clouds are too large + if len(np.asarray(source_temp.points)) > 500000: + source_temp = source_temp.voxel_down_sample(0.1) + if len(np.asarray(target_temp.points)) > 500000: + target_temp = target_temp.voxel_down_sample(0.1) + vis = o3d.visualization.Visualizer() + vis.create_window() + vis.add_geometry(source_temp) + vis.add_geometry(target_temp) + vis.get_render_option().point_size = 2 + vis.run() + # o3d.visualization.draw_geometries([source_temp, target_temp]) + +def main(): + parser = argparse.ArgumentParser(description='Global registration for LiDAR localization') + parser.add_argument('--map', required=True, help='Path to .ply map file') + parser.add_argument('--scan-folder', help='Folder containing .npz lidar scan files') + parser.add_argument('--scans', nargs='+', help='Paths to .npz lidar scan files') + parser.add_argument('--output', default='global_registration_result.txt', + help='Output file for transformation matrix') + parser.add_argument('--method', choices=['ransac', 'fgr', 'both'], default='both', + help='Global registration method to use') + parser.add_argument('--voxel-size', type=float, default=1.0, + help='Voxel size for downsampling (for global map)') + parser.add_argument('--scan-voxel-size', type=float, default=0.5, + help='Voxel size for scan downsampling') + parser.add_argument('--visualize', action='store_true', + help='Visualize the alignment result') + parser.add_argument('--map-scale-ratio', type=float, default=1.0, + help='Scale ratio to apply to scan to match map scale') + parser.add_argument('--icp-refine', action='store_true', default=True, + help='Refine alignment with ICP after global registration') + parser.add_argument('--structural-features', action='store_true', default=True, + help='Extract structural features for better alignment') + args = parser.parse_args() + + # Validate inputs + if not args.scan_folder and not args.scans: + print("Error: You must provide either --scan-folder or --scans") + return + + # Load map + map_pcd = load_map(args.map) + print(map_pcd) + if map_pcd is None: + print("Failed to load map. Exiting.") + return + + # Load scans + scan_list = [] + if args.scan_folder: + scan_list = load_all_scans_from_folder(args.scan_folder) + elif args.scans: + for scan_file in args.scans: + scan = load_lidar_scan(scan_file) + if scan is not None: + scan_list.append(scan) + + if not scan_list: + print("No valid scans loaded. Exiting.") + return + + # Fuse scans if multiple + print(f"Loaded {len(scan_list)} LiDAR scans.") + if len(scan_list) > 1: + print("Fusing scans...") + scan_pcd = fuse_scans(scan_list, voxel_size=args.scan_voxel_size) + else: + scan_pcd = scan_list[0] + + # Scale and translate the scan to match map scale and center + print(f"Preparing scan for global registration with scale ratio {args.map_scale_ratio}...") + scaled_scan_pcd = prepare_scan_for_global_registration( + scan_pcd, + map_pcd, + args.map_scale_ratio + ) + + + normal_radius_factor = 2.0 + feature_radius_factor = 5.0 + + print("Preprocessing map...") + map_down, map_fpfh = preprocess_point_cloud( + map_pcd, args.voxel_size, normal_radius_factor, feature_radius_factor) + + print("Preprocessing scan...") + scan_down, scan_fpfh = preprocess_point_cloud( + scaled_scan_pcd, args.scan_voxel_size, normal_radius_factor, feature_radius_factor) + + + # Global registration + transformation = np.identity(4) + + if args.method in ['ransac', 'both']: + start_time = time.time() + ransac_result = execute_global_registration( + scan_down, map_down, scan_fpfh, map_fpfh, args.voxel_size) + print(f"RANSAC registration took {time.time() - start_time:.3f} seconds") + print(f"RANSAC result:") + print(f" Fitness: {ransac_result.fitness:.6f}") + print(f" Inlier RMSE: {ransac_result.inlier_rmse:.6f}") + print(f" Correspondence set size: {len(ransac_result.correspondence_set)}") + + if args.visualize: + print("Visualizing RANSAC result...") + draw_registration_result(scan_down, map_down, ransac_result.transformation) + + transformation = ransac_result.transformation + + if args.method in ['fgr', 'both']: + start_time = time.time() + fgr_result = execute_fast_global_registration( + scan_down, map_down, scan_fpfh, map_fpfh, args.voxel_size) + print(f"Fast Global Registration took {time.time() - start_time:.3f} seconds") + print(f"FGR result:") + print(f" Fitness: {fgr_result.fitness:.6f}") + print(f" Inlier RMSE: {fgr_result.inlier_rmse:.6f}") + print(f" Correspondence set size: {len(fgr_result.correspondence_set)}") + + if args.visualize: + print("Visualizing FGR result...") + draw_registration_result(scan_down, map_down, fgr_result.transformation) + + if args.method == 'both': + # Use the better result based on fitness + if fgr_result.fitness > ransac_result.fitness: + print("Using FGR result (better fitness).") + transformation = fgr_result.transformation + else: + print("Using RANSAC result (better fitness).") + else: + transformation = fgr_result.transformation + + # Refine with ICP if requested + if args.icp_refine: + print("Refining with multi-scale ICP...") + icp_transformation = multi_scale_icp( + scan_down, map_down, + voxel_sizes=[2.0, 1.0, 0.5], + max_iterations=[100, 50, 30], + initial_transform=transformation) + + final_transformation = icp_transformation + else: + final_transformation = transformation + + # # Extract position and orientation + x, y, z, roll, pitch, yaw = transform_to_pose(final_transformation) + + # # We need to scale back the translation since we scaled the scan + # # The rotation part doesn't need scaling + # if args.map_scale_ratio != 1.0: + # # Need to account for the initial translation and scaling + # # The final transformation includes the initial translation + # # So we need to extract just the additional transformation from global registration + # x /= args.map_scale_ratio + # y /= args.map_scale_ratio + # z /= args.map_scale_ratio + + # # Modify the final transformation matrix to undo the scaling effect on translation + # tmp = final_transformation + # final_transformation = np.zeros_like(tmp) + # final_transformation[:] = tmp + # final_transformation[:3, 3] /= args.map_scale_ratio + + # Print final results + print(f"Estimated vehicle position: [{x:.2f}, {y:.2f}, {z:.2f}]") + print(f"Estimated vehicle orientation (RPY, degrees): [{roll:.2f}, {pitch:.2f}, {yaw:.2f}]") + + # Save results + with open(args.output, 'w') as f: + f.write(f"# Global Registration Result\n") + f.write(f"# Method: {args.method}\n") + if args.method == 'both': + f.write(f"# RANSAC Fitness: {ransac_result.fitness:.6f}\n") + f.write(f"# FGR Fitness: {fgr_result.fitness:.6f}\n") + f.write(f"# Final Fitness: {max(ransac_result.fitness, fgr_result.fitness):.6f}\n") + # f.write(f"# Position: {x:.6f}, {y:.6f}, {z:.6f}\n") + # f.write(f"# Orientation (roll, pitch, yaw degrees): {roll:.6f}, {pitch:.6f}, {yaw:.6f}\n") + f.write("# Transformation matrix (4x4):\n") + np.savetxt(f, final_transformation, fmt='%.6f') + + print(f"Results saved to {args.output}") + + # Final visualization + if args.visualize: + print("Visualizing final result...") + # # First create an unscaled copy of the scan for visualization with unscaled map + # unscaled_scan = copy.deepcopy(scan_pcd) + # # Calculate the unscaled final transformation + # unscaled_final_transform = np.copy(final_transformation) + # unscaled_final_transform[:3, 3] /= args.map_scale_ratio + # draw_registration_result(unscaled_scan, map_pcd, unscaled_final_transform) + draw_registration_result(scan_down, map_down, final_transformation) + +if __name__ == "__main__": + main() From 374f10d07d0b2d0c0775bae54ddd22eda831c4b3 Mon Sep 17 00:00:00 2001 From: rjsun-KA <92330153+rjsun06@users.noreply.github.com> Date: Wed, 30 Apr 2025 21:38:07 +0000 Subject: [PATCH 217/232] cli argument clarified --- GEMstack/offboard/calibration/README.md | 21 ++++++++++++------ .../calibration/get_intrinsic_by_SfM.py | 2 +- GEMstack/offboard/calibration/img2pc.py | 22 ++++++++++--------- 3 files changed, 27 insertions(+), 18 deletions(-) diff --git a/GEMstack/offboard/calibration/README.md b/GEMstack/offboard/calibration/README.md index 5e374a772..a32bf3feb 100644 --- a/GEMstack/offboard/calibration/README.md +++ b/GEMstack/offboard/calibration/README.md @@ -22,13 +22,13 @@ There are two ways to calibrate the intrinsics, depending on what data you have. To use the `get_intrinsic_by_chessboard.py` script, collect a series of images with a large chessboard using either the data collection scripts or a rosbag. Select images where the chessboard is at different points in the camera frame, different distances including filling the entire frame, and at different angles. The script detects internal corners where four squares meet, so the extreme edge of the chessboard does not need to be in frame. -To use the `get_intrinsic_by_SfM.py` script, *[fill in here]* +To use the `get_intrinsic_by_SfM.py` script, prepare a set of images recorded from the same camera going through a continuous movement, and follow [this](#get_intrinsic_by_sfmpy) The `undistort_images.py` script can then be used to rectify a set of images using the calibrated intrinsics to evaluate or use in other applications. **Extrinsic Calibration** -The `img2pc.py` file contains the main part of the extrinsic calibration process. Select a synchronized camera image and lidar pointcloud to align, ideally containing features that are easy to detect in both, such as boards or signs with corners. Alignment can be done with *[explain minimum number of points and any limitations on them]*. The first screen will ask you to select points on the image, and will close on its own once *n_features* points are selected. The second screen will ask you to select points in the point cloud, and will need to be closed manually once exactly *n_features* points are selected, or it will prompt you again. The extrinsic matrices will then be displayed, and if an *out_path* is provided they will also be saved. +The `img2pc.py` file contains the main part of the extrinsic calibration process. Select a synchronized camera image and lidar pointcloud to align, ideally containing features that are easy to detect in both, such as boards or signs with corners. Alignment can be done with 4 feature pairs(must be coplanar) or 6+ points. The first screen will ask you to select points on the image, and will close on its own once *n_features* points are selected. The second screen will ask you to select points in the point cloud, and will need to be closed manually once exactly *n_features* points are selected, or it will prompt you again. The extrinsic matrices will then be displayed, and if an *out_path* is provided they will also be saved. The `test_transforms.py` file can then be used to manually fine-tune the calculated intrinsics. Use the sliders to change the translation and rotation to project the lidar points onto the image more accurately. @@ -37,12 +37,14 @@ The `test_transforms.py` file can then be used to manually fine-tune the calcula Compute camera extrinsic parameters by manually selecting corresponding features in an image and point cloud. +**Note**: On the img prompt, click n points and the window closed itself. On the pc prompt, right click n points and close the window manually. + ### Usage ```bash python3 img2pc.py \ --img_path IMG_PATH \ --pc_path PC_PATH \ - --img_intrinsics_path IMG_INTRINSICS_PATH \ + --img_intrinsic_path IMG_INTRINSICS_PATH \ [--pc_transform_path PC_TRANSFORM_PATH] \ [--out_path OUT_PATH] \ [--n_features N_FEATURES] @@ -53,10 +55,14 @@ python3 img2pc.py \ |-----------|-------------|--------|----------|---------| | `--img_path` | Input image path | .png | Yes | - | | `--pc_path` | Point cloud path | .npz | Yes | - | -| `--img_intrinsics_path` | Camera intrinsics file | .yaml | Yes | - | +| `--img_intrinsic_path` | Camera intrinsics file | .yaml | Yes | - | | `--pc_transform_path` | LiDAR extrinsic transform | .yaml | No | Identity | -| `--out_path` | Output extrinsic path | .yaml | No | None | | `--n_features` | Manual feature points | int | No | 8 | +| `--out_path` | Output extrinsic path | .yaml | No | None | +| `--no_undistort` | to undistort | - | - | False | +| `--show` | visualize reprojection | - | - | False | + +*`--no_undistort True` is rare because it's almost sure that extrinsic solving performs better after undistortion* ### Example ```bash @@ -65,7 +71,7 @@ python3 img2pc.py \ --img_path $root/data/calib1/img/fl/fl16.png \ --pc_path $root/data/calib1/pc/ouster16.npz \ --pc_transform_path $root/GEMstack/knowledge/calibration/gem_e4_ouster.yaml \ - --img_intrinsics_path $root/GEMstack/knowledge/calibration/gem_e4_oak_in.yaml \ + --img_intrinsic_path $root/GEMstack/knowledge/calibration/gem_e4_oak_in.yaml \ --n_features 4 \ --out_path $root/GEMstack/knowledge/calibration/gem_e4_oak.yaml ``` @@ -176,9 +182,10 @@ python3 intrinsic_calibration_chessboard.py \ | Parameter | Description | Required | |-----------|-------------|----------| | `--input_imgs` | Input images (glob pattern) | Yes | -| `--workspace` | Temporary directory path | Yes | +| `--workspace` | Temporary directory path (default `/tmp/colmap_tmp`) | No | | `--out_file` | Output .yaml path | No | +*note:`--workspace` allows you to save running time for continuing/redoing a previous job. you can clean it up after. check [colmap](https://colmap.github.io/) for more infomation* ### Example ```bash root='/mnt/GEMstack' diff --git a/GEMstack/offboard/calibration/get_intrinsic_by_SfM.py b/GEMstack/offboard/calibration/get_intrinsic_by_SfM.py index 2d941bc3e..0b7067160 100644 --- a/GEMstack/offboard/calibration/get_intrinsic_by_SfM.py +++ b/GEMstack/offboard/calibration/get_intrinsic_by_SfM.py @@ -107,7 +107,7 @@ def main(input_imgs, output_dir, out, refine=True): if __name__ == "__main__": parser = argparse.ArgumentParser(description='Camera calibration using SfM') parser.add_argument('--input_imgs','-i', nargs='+', help='List of input imgs', required=True) - parser.add_argument('--workspace','-w', type=str, required=True, + parser.add_argument('--workspace','-w', type=str, required=False, default= '/tmp/colmap_tmp', help='Output directory for results') parser.add_argument('--out_file','-o', type=str, required=True, help='output yaml file') diff --git a/GEMstack/offboard/calibration/img2pc.py b/GEMstack/offboard/calibration/img2pc.py index fd2b1a97b..7928504bf 100644 --- a/GEMstack/offboard/calibration/img2pc.py +++ b/GEMstack/offboard/calibration/img2pc.py @@ -88,17 +88,17 @@ def main(): formatter_class=argparse.ArgumentDefaultsHelpFormatter) parser.add_argument('-p', '--img_path', type=str, required=True, help='Path to PNG image') - parser.add_argument('-l', '--lidar_path', type=str, required=True, + parser.add_argument('-l', '--pc_path', type=str, required=True, help='Path to lidar NPZ point cloud') - parser.add_argument('-t', '--lidar_transform_path', type=str, required=True, + parser.add_argument('-t', '--pc_transform_path', type=str, required=True, help='Path to yaml file for lidar extrinsics') - parser.add_argument('-i', '--img_intrinsics_path', type=str, required=True, + parser.add_argument('-i', '--img_intrinsic_path', type=str, required=True, help='Path to yaml file for image intrinsics') parser.add_argument('-o', '--out_path', type=str, required=False, help='Path to output yaml file for image extrinsics') parser.add_argument('-n', '--n_features', type=int, required=False, default=8, help='Number of features to select and math') - parser.add_argument('-u','--undistort', action='store_true', + parser.add_argument('-u','--no_undistort', action='store_true', help='Whether to use distortion parameters') parser.add_argument('-s', '--show', action='store_true', help='Show projected points after calibration') @@ -109,21 +109,23 @@ def main(): # Load data N = args.n_features img = cv2.imread(args.img_path, cv2.IMREAD_UNCHANGED) - pc = np.load(args.lidar_path)['arr_0'] + pc = np.load(args.pc_path)['arr_0'] pc = pc[~np.all(pc == 0, axis=1)] # remove (0,0,0)'s - if args.undistort: - K, distort = load_in(args.img_intrinsics_path,mode='matrix',return_distort=True) + if not args.no_undistort: + K, distort = load_in(args.img_intrinsic_path,mode='matrix',return_distort=True) print('applying distortion coeffs', distort) h, w = img.shape[:2] newK, roi = cv2.getOptimalNewCameraMatrix(K, distort, (w,h), 1, (w,h)) img = cv2.undistort(img, K, distort, None, newK) K = newK else: - K = load_in(args.img_intrinsics_path,mode='matrix') + K = load_in(args.img_intrinsic_path,mode='matrix') - lidar_ex = load_ex(args.lidar_transform_path,mode='matrix') - pc = np.pad(pc,((0,0),(0,1)),constant_values=1) @ lidar_ex.T[:,:3] + lidar_ex = np.eye(4) + if args.pc_transform_path: + lidar_ex = load_ex(args.pc_transform_path,mode='matrix') + pc = np.pad(pc,((0,0),(0,1)),constant_values=1) @ lidar_ex.T[:,:3] c2v = calib(args,pc,img,K,N) T = np.linalg.inv(c2v) From 66cb580f7e865d6a185fb4ab4e6b9b437a78694f Mon Sep 17 00:00:00 2001 From: michalj1 Date: Wed, 30 Apr 2025 16:40:11 -0500 Subject: [PATCH 218/232] Move and update utility functions and README --- .../calibration/calib_util.py} | 7 ++ GEMstack/offboard/calibration/README.md | 19 +-- .../calibration_by_SfM/SfM_handeye.py | 2 +- GEMstack/offboard/calibration/camera_info.py | 2 +- GEMstack/offboard/calibration/create_map.py | 113 ++++++++++++++++++ .../calibration/get_intrinsic_by_SfM.py | 2 +- .../get_intrinsic_by_chessborad.py | 2 +- GEMstack/offboard/calibration/img2pc.py | 7 +- .../calibration/intrinsic_calibration.py | 2 +- .../calibration/play_with_pycolmap.py | 2 +- .../offboard/calibration/test_transforms.py | 7 +- .../offboard/calibration/undistort_images.py | 8 +- 12 files changed, 143 insertions(+), 30 deletions(-) rename GEMstack/{offboard/calibration/tools/save_cali.py => knowledge/calibration/calib_util.py} (91%) create mode 100644 GEMstack/offboard/calibration/create_map.py diff --git a/GEMstack/offboard/calibration/tools/save_cali.py b/GEMstack/knowledge/calibration/calib_util.py similarity index 91% rename from GEMstack/offboard/calibration/tools/save_cali.py rename to GEMstack/knowledge/calibration/calib_util.py index 1213a249a..9b4a2618d 100644 --- a/GEMstack/offboard/calibration/tools/save_cali.py +++ b/GEMstack/knowledge/calibration/calib_util.py @@ -2,6 +2,7 @@ import yaml from yaml import SafeDumper import numpy as np +import cv2 def represent_flow_style_list(dumper, data): return dumper.represent_sequence(yaml.resolver.BaseResolver.DEFAULT_SEQUENCE_TAG, data, flow_style=True) SafeDumper.add_representer(list, represent_flow_style_list) @@ -86,6 +87,12 @@ def save_in(path,focal=None,center=None,skew=0,distort=[0.0]*5,matrix=None): with open(path,'w') as stream: yaml.dump(ret,stream,Dumper=SafeDumper,default_flow_style=False) +def undistort_image(image, camera_matrix, distortion_coefficients): + h, w = image.shape[:2] + newK, roi = cv2.getOptimalNewCameraMatrix(camera_matrix, distortion_coefficients, (w,h), 1, (w,h)) + image = cv2.undistort(image, camera_matrix, distortion_coefficients, None, newK) + return image, newK + #%% if __name__ == "__main__": diff --git a/GEMstack/offboard/calibration/README.md b/GEMstack/offboard/calibration/README.md index 5e374a772..29aaf5cab 100644 --- a/GEMstack/offboard/calibration/README.md +++ b/GEMstack/offboard/calibration/README.md @@ -46,28 +46,31 @@ python3 img2pc.py \ [--pc_transform_path PC_TRANSFORM_PATH] \ [--out_path OUT_PATH] \ [--n_features N_FEATURES] + [--undistort] ``` #### Parameters | Parameter | Description | Format | Required | Default | |-----------|-------------|--------|----------|---------| | `--img_path` | Input image path | .png | Yes | - | -| `--pc_path` | Point cloud path | .npz | Yes | - | +| `--lidar_path` | Point cloud path | .npz | Yes | - | | `--img_intrinsics_path` | Camera intrinsics file | .yaml | Yes | - | -| `--pc_transform_path` | LiDAR extrinsic transform | .yaml | No | Identity | +| `--lidar_transform_path` | LiDAR extrinsic transform | .yaml | No | Identity | | `--out_path` | Output extrinsic path | .yaml | No | None | | `--n_features` | Manual feature points | int | No | 8 | +| `--undistort` | Flag for using distortion coefficients | - | - | - | ### Example ```bash root='/mnt/GEMstack' python3 img2pc.py \ - --img_path $root/data/calib1/img/fl/fl16.png \ - --pc_path $root/data/calib1/pc/ouster16.npz \ - --pc_transform_path $root/GEMstack/knowledge/calibration/gem_e4_ouster.yaml \ - --img_intrinsics_path $root/GEMstack/knowledge/calibration/gem_e4_oak_in.yaml \ - --n_features 4 \ - --out_path $root/GEMstack/knowledge/calibration/gem_e4_oak.yaml + --img_path $root/data/fl/fl16.png \ + --lidar_path $root/data/ouster16.npz \ + --lidar_transform_path $root/GEMstack/knowledge/calibration/gem_e4_ouster.yaml \ + --img_intrinsics_path $root/GEMstack/knowledge/calibration/gem_e4_fl_in.yaml \ + --n_features 8 \ + --out_path $root/GEMstack/knowledge/calibration/gem_e4_fl.yaml \ + --undistort ``` ## test_transforms.py diff --git a/GEMstack/offboard/calibration/calibration_by_SfM/SfM_handeye.py b/GEMstack/offboard/calibration/calibration_by_SfM/SfM_handeye.py index c215084ed..f9cf48d83 100644 --- a/GEMstack/offboard/calibration/calibration_by_SfM/SfM_handeye.py +++ b/GEMstack/offboard/calibration/calibration_by_SfM/SfM_handeye.py @@ -8,7 +8,7 @@ #%% import os os.chdir('/mnt/GEMstack/GEMstack/offboard/calibration') -from tools.save_cali import * +from GEMstack.GEMstack.knowledge.calibration.calib_util import * #%% N_PAIRS = 20 STEP = 3 diff --git a/GEMstack/offboard/calibration/camera_info.py b/GEMstack/offboard/calibration/camera_info.py index 1ea9064ac..781d10ef4 100644 --- a/GEMstack/offboard/calibration/camera_info.py +++ b/GEMstack/offboard/calibration/camera_info.py @@ -11,7 +11,7 @@ import os import time from functools import partial -from tools.save_cali import save_in +from GEMstack.GEMstack.knowledge.calibration.calib_util import save_in camera_info = {"oak": None, "fr": None, "fl": None, "rr": None, "rl": None, "oak_stereo": None, "oak_right": None, "oak_left": None} diff --git a/GEMstack/offboard/calibration/create_map.py b/GEMstack/offboard/calibration/create_map.py new file mode 100644 index 000000000..648cebdc4 --- /dev/null +++ b/GEMstack/offboard/calibration/create_map.py @@ -0,0 +1,113 @@ +import os +import glob +import numpy as np +import cv2 +import open3d as o3d +import pyvista as pv + +def load_lidar_points(npz_file: str): + """ + Load the Nx3 LiDAR points from a .npz file created by 'np.savez'. + """ + data = np.load(npz_file) + # The capture code used: np.savez(lidar_fn, pc) + # So 'data' might have the default key 'arr_0' or 'pc' if named + # Inspect data.files to see. Let's assume 'arr_0' or single key: + arr_key = data.files[0] + points = data[arr_key] + # shape check, must be Nx3 or Nx4, ... + return points + +def make_open3d_pc(points: np.ndarray): + """ + Convert Nx3 numpy array into an Open3D point cloud object. + """ + pcd = o3d.geometry.PointCloud() + pcd.points = o3d.utility.Vector3dVector(points) + return pcd + +def perform_icp(source_pc: o3d.geometry.PointCloud, + target_pc: o3d.geometry.PointCloud): + """ + Perform local ICP alignment of camera_pcd (source) to lidar_pcd (target). + Returns a transformation 4x4 that maps camera -> lidar (or vice versa). + """ + # Estimate normals for point-to-plane + source_pc.estimate_normals(search_param=o3d.geometry.KDTreeSearchParamHybrid( + radius=1.0, max_nn=30)) + target_pc.estimate_normals(search_param=o3d.geometry.KDTreeSearchParamHybrid( + radius=1.0, max_nn=30)) + + # Initial guess: identity or something better if you have one + init_guess = np.eye(4) + + # Choose a threshold for inlier distance + threshold = 0.5 # adjust based on your environment scale + + # Run ICP (point-to-plane or point-to-point) + print("[ICP] Running ICP alignment ...") + result = o3d.pipelines.registration.registration_icp( + source_pc, + target_pc, + threshold, + init_guess, + estimation_method=o3d.pipelines.registration.TransformationEstimationPointToPlane() + ) + + print("[ICP] Done. Fitness = %.4f, RMSE = %.4f" % (result.fitness, result.inlier_rmse)) + print("[ICP] Transformation:\n", result.transformation) + return result + +def main(source='ouster1', target='ouster2', folder='data'): + source_path = os.path.join(folder, f"{source}.npz") + target_path = os.path.join(folder, f"{target}.npz") + + # Check for existence of files + if not os.path.exists(source_path): + print("Invalid source path", source_path) + exit(1) + if not os.path.exists(target_path): + print("Invalid target path", target_path) + exit(1) + + # Load LiDAR + source_points = load_lidar_points(source_path) + target_points = load_lidar_points(target_path) + source_points = source_points[~np.all(source_points == 0, axis=1)] # remove (0,0,0)'s + target_points = target_points[~np.all(target_points == 0, axis=1)] # remove (0,0,0)'s + source_pc = make_open3d_pc(source_points) + target_pc = make_open3d_pc(target_points) + + # Run ICP + result = perform_icp(source_pc, target_pc) + # point_cloud = np.append(target_points, source_points @ result.transformation) + + # View result + # cloud = pv.PolyData(point_cloud) + target = pv.PolyData(target_points) + source = pv.PolyData(source_points @ result.transformation) + plotter = pv.Plotter(notebook=False) + plotter.camera.position = (-20,0,20) + plotter.camera.focal_point = (0,0,0) + # plotter.add_mesh(cloud, color='lightblue', point_size=5, render_points_as_spheres=True) + plotter.add_mesh(source, color='orange', point_size=5, render_points_as_spheres=True) + plotter.add_mesh(target, color='navy', point_size=5, render_points_as_spheres=True) + plotter.show() + + +if __name__ == "__main__": + import sys + if len(sys.argv) == 1: + main() + elif len(sys.argv) == 3: + source = sys.argv[1] + target = sys.argv[2] + main(source, target) + elif len(sys.argv) == 4: + source = sys.argv[1] + target = sys.argv[2] + folder = sys.argv[3] + main(source, target, folder) + else: + print("Usage: python3 createmap.py [source target] [folder]") + \ No newline at end of file diff --git a/GEMstack/offboard/calibration/get_intrinsic_by_SfM.py b/GEMstack/offboard/calibration/get_intrinsic_by_SfM.py index 2d941bc3e..8c902f9e0 100644 --- a/GEMstack/offboard/calibration/get_intrinsic_by_SfM.py +++ b/GEMstack/offboard/calibration/get_intrinsic_by_SfM.py @@ -3,7 +3,7 @@ import shutil import pycolmap import subprocess -from tools.save_cali import save_in +from GEMstack.GEMstack.knowledge.calibration.calib_util import save_in def run_colmap_command(args): result = subprocess.run(args, capture_output=True, text=True) diff --git a/GEMstack/offboard/calibration/get_intrinsic_by_chessborad.py b/GEMstack/offboard/calibration/get_intrinsic_by_chessborad.py index aa6588a86..3dca9bdbb 100644 --- a/GEMstack/offboard/calibration/get_intrinsic_by_chessborad.py +++ b/GEMstack/offboard/calibration/get_intrinsic_by_chessborad.py @@ -1,6 +1,6 @@ import cv2 import numpy as np -from tools.save_cali import save_in +from GEMstack.GEMstack.knowledge.calibration.calib_util import save_in import glob def estimate_intrinsics(image_dir, checkerboard_size): diff --git a/GEMstack/offboard/calibration/img2pc.py b/GEMstack/offboard/calibration/img2pc.py index fd2b1a97b..eb4f14ba8 100644 --- a/GEMstack/offboard/calibration/img2pc.py +++ b/GEMstack/offboard/calibration/img2pc.py @@ -2,7 +2,7 @@ import argparse import cv2 import numpy as np -from tools.save_cali import load_ex,save_ex,load_in,save_in +from GEMstack.GEMstack.knowledge.calibration.calib_util import load_ex,save_ex,load_in,save_in, undistort_image from scipy.spatial.transform import Rotation as R from transform3d import Transform @@ -115,10 +115,7 @@ def main(): if args.undistort: K, distort = load_in(args.img_intrinsics_path,mode='matrix',return_distort=True) print('applying distortion coeffs', distort) - h, w = img.shape[:2] - newK, roi = cv2.getOptimalNewCameraMatrix(K, distort, (w,h), 1, (w,h)) - img = cv2.undistort(img, K, distort, None, newK) - K = newK + img, K = undistort_image(img, K, distort) else: K = load_in(args.img_intrinsics_path,mode='matrix') diff --git a/GEMstack/offboard/calibration/intrinsic_calibration.py b/GEMstack/offboard/calibration/intrinsic_calibration.py index 6226dc65e..4933d6a22 100644 --- a/GEMstack/offboard/calibration/intrinsic_calibration.py +++ b/GEMstack/offboard/calibration/intrinsic_calibration.py @@ -4,7 +4,7 @@ import os import argparse -from tools.save_cali import save_in +from GEMstack.GEMstack.knowledge.calibration.calib_util import save_in def main(): # Collect arguments diff --git a/GEMstack/offboard/calibration/play_with_pycolmap.py b/GEMstack/offboard/calibration/play_with_pycolmap.py index 8406490fd..b19906fa1 100644 --- a/GEMstack/offboard/calibration/play_with_pycolmap.py +++ b/GEMstack/offboard/calibration/play_with_pycolmap.py @@ -6,7 +6,7 @@ import open3d as o3d from pathlib import Path from scipy.spatial.transform import Rotation as R -from tools.save_cali import load_ex, save_ex, load_in, save_in +from GEMstack.GEMstack.knowledge.calibration.calib_util import load_ex, save_ex, load_in, save_in from tools.visualizer import visualizer as vis def pc_relative(pc0,pc1): diff --git a/GEMstack/offboard/calibration/test_transforms.py b/GEMstack/offboard/calibration/test_transforms.py index 5edb5e538..da647325d 100644 --- a/GEMstack/offboard/calibration/test_transforms.py +++ b/GEMstack/offboard/calibration/test_transforms.py @@ -4,7 +4,7 @@ import argparse from scipy.spatial.transform import Rotation as R from matplotlib.widgets import Slider -from tools.save_cali import load_ex, load_in, save_ex +from GEMstack.GEMstack.knowledge.calibration.calib_util import load_ex, load_in, save_ex, undistort_image x_rot = y_rot = z_rot = x_trans = y_trans = z_trans = None @@ -156,10 +156,7 @@ def main(): # Load Camera Intrinsics if args.undistort: K, distortion_coefficients = load_in(args.img_intrinsics_path, return_distort=True) - h, w = image.shape[:2] - new_K, roi = cv.getOptimalNewCameraMatrix(K, distortion_coefficients, (w,h), 1, (w,h)) - image = cv.undistort(image, K, distortion_coefficients, None, new_K) - K = new_K + image, K = undistort_image(image, K, distortion_coefficients) else: K = load_in(args.img_intrinsics_path) diff --git a/GEMstack/offboard/calibration/undistort_images.py b/GEMstack/offboard/calibration/undistort_images.py index cf48c5d2a..de0075b7f 100644 --- a/GEMstack/offboard/calibration/undistort_images.py +++ b/GEMstack/offboard/calibration/undistort_images.py @@ -4,7 +4,7 @@ import os import argparse -from tools.save_cali import load_in +from GEMstack.GEMstack.knowledge.calibration.calib_util import load_in, undistort_image def main(): # Collect arguments @@ -31,11 +31,7 @@ def main(): for fn in image_files: image = cv.imread(fn) - h, w = image.shape[:2] - new_camera_matrix, roi = cv.getOptimalNewCameraMatrix(camera_matrix, distortion_coefficients, (w,h), 1, (w,h)) - - # Undistort - dst = cv.undistort(image, camera_matrix, distortion_coefficients, None, new_camera_matrix) + dst, _ = undistort_image(image, camera_matrix, distortion_coefficients) cv.imwrite(fn.replace(camera, camera + "_rect"), dst) From e09e8a2f98709a562f38be86e1b4697769ea54f4 Mon Sep 17 00:00:00 2001 From: michalj1 <70865139+michalj1@users.noreply.github.com> Date: Wed, 30 Apr 2025 17:01:25 -0500 Subject: [PATCH 219/232] Rename intrinsic_calibration.py to get_intrinsic_by_chessboard.py --- ...{intrinsic_calibration.py => get_intrinsic_by_chessboard.py} | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) rename GEMstack/offboard/calibration/{intrinsic_calibration.py => get_intrinsic_by_chessboard.py} (99%) diff --git a/GEMstack/offboard/calibration/intrinsic_calibration.py b/GEMstack/offboard/calibration/get_intrinsic_by_chessboard.py similarity index 99% rename from GEMstack/offboard/calibration/intrinsic_calibration.py rename to GEMstack/offboard/calibration/get_intrinsic_by_chessboard.py index 4933d6a22..ce1dd26b0 100644 --- a/GEMstack/offboard/calibration/intrinsic_calibration.py +++ b/GEMstack/offboard/calibration/get_intrinsic_by_chessboard.py @@ -82,4 +82,4 @@ def main(): if __name__ == '__main__': - main() \ No newline at end of file + main() From ac2ce4857c3933135084a1e2c892cc16fb717f51 Mon Sep 17 00:00:00 2001 From: whizkid42 Date: Wed, 30 Apr 2025 20:02:10 -0500 Subject: [PATCH 220/232] New oak extrinsics calibration --- GEMstack/knowledge/calibration/gem_e4_oak_finetuned_new.yaml | 5 +++++ 1 file changed, 5 insertions(+) create mode 100644 GEMstack/knowledge/calibration/gem_e4_oak_finetuned_new.yaml diff --git a/GEMstack/knowledge/calibration/gem_e4_oak_finetuned_new.yaml b/GEMstack/knowledge/calibration/gem_e4_oak_finetuned_new.yaml new file mode 100644 index 000000000..1d53c0cde --- /dev/null +++ b/GEMstack/knowledge/calibration/gem_e4_oak_finetuned_new.yaml @@ -0,0 +1,5 @@ +position: [1.9564719286254562, -0.016357857507817864, 2.0489178127802745] +reference: rear_axle_center +rotation: [[0.02777285065736978, -0.1147911851051555, 0.9930013356428667], [-0.9996095786617777, + -0.00014910886738464478, 0.027940436900108796], [-0.0030592505596502726, -0.9933896323138769, + -0.11475050935535633]] From 01f24273dd565f20be1941c43c471f95f07d091e Mon Sep 17 00:00:00 2001 From: whizkid42 Date: Wed, 30 Apr 2025 20:19:44 -0500 Subject: [PATCH 221/232] Resolve merge conflicts in calibration scripts --- GEMstack/offboard/calibration/img2pc.py | 19 ++++ .../offboard/calibration/test_transforms.py | 92 +++++++++++++++++++ 2 files changed, 111 insertions(+) diff --git a/GEMstack/offboard/calibration/img2pc.py b/GEMstack/offboard/calibration/img2pc.py index 82ff2852d..ac4b1a2f4 100644 --- a/GEMstack/offboard/calibration/img2pc.py +++ b/GEMstack/offboard/calibration/img2pc.py @@ -59,6 +59,24 @@ def pc_projection(pc,T:Transform,K,img_shape) -> np.ndarray: valid_pts = (u >= 0) & (u < img_w) & (v >= 0) & (v < img_h) return u[valid_pts],v[valid_pts] +def calib(args,pc,img,K,N): +def pc_projection(pc,T:Transform,K,img_shape) -> np.ndarray: + mask = ~(np.all(pc == 0, axis=1)) + pc = pc[mask] + + pc = T @ pc + if pc.shape[1] == 4: + pc = pc[:,:-1]/pc[:,[-1]] + + assert pc.shape[1] == 3 + x,y,z = pc.T + u = (K[0, 0] * x / z) + K[0, 2] + v = (K[1, 1] * y / z) + K[1, 2] + + img_h, img_w, _ = img_shape + valid_pts = (u >= 0) & (u < img_w) & (v >= 0) & (v < img_h) + return u[valid_pts],v[valid_pts] + def calib(args,pc,img,K,N): cpoints = np.array(pick_n_img(img,N)).astype(float) print(cpoints) @@ -66,6 +84,7 @@ def calib(args,pc,img,K,N): lpoints = np.array(pick_n_pc(pc,N)) print(lpoints) + success, rvec, tvec = cv2.solvePnP(lpoints, cpoints, K, None) success, rvec, tvec = cv2.solvePnP(lpoints, cpoints, K, None) R, _ = cv2.Rodrigues(rvec) diff --git a/GEMstack/offboard/calibration/test_transforms.py b/GEMstack/offboard/calibration/test_transforms.py index da647325d..64eb05fc7 100644 --- a/GEMstack/offboard/calibration/test_transforms.py +++ b/GEMstack/offboard/calibration/test_transforms.py @@ -1,7 +1,10 @@ + import numpy as np import cv2 as cv +import cv2 as cv import matplotlib.pyplot as plt import argparse +import argparse from scipy.spatial.transform import Rotation as R from matplotlib.widgets import Slider from GEMstack.GEMstack.knowledge.calibration.calib_util import load_ex, load_in, save_ex, undistort_image @@ -12,11 +15,18 @@ def project_points(T_lidar_camera, lidar_homogeneous, K, shape): # Transform LiDAR points to Camera Frame lidar_points_camera = (T_lidar_camera @ lidar_homogeneous.T).T # (N, 4) + # Extract 3D points in camera frame + X_c = lidar_points_camera[:, 0] + Y_c = lidar_points_camera[:, 1] + Z_c = lidar_points_camera[:, 2] # Depth # Extract 3D points in camera frame X_c = lidar_points_camera[:, 0] Y_c = lidar_points_camera[:, 1] Z_c = lidar_points_camera[:, 2] # Depth + # Avoid division by zero + valid = Z_c > 0 + X_c, Y_c, Z_c = X_c[valid], Y_c[valid], Z_c[valid] # Avoid division by zero valid = Z_c > 0 X_c, Y_c, Z_c = X_c[valid], Y_c[valid], Z_c[valid] @@ -24,7 +34,33 @@ def project_points(T_lidar_camera, lidar_homogeneous, K, shape): # Project points onto image plane u = (K[0, 0] * X_c / Z_c) + K[0, 2] v = (K[1, 1] * Y_c / Z_c) + K[1, 2] + # Project points onto image plane + u = (K[0, 0] * X_c / Z_c) + K[0, 2] + v = (K[1, 1] * Y_c / Z_c) + K[1, 2] + + # Filter points within image bounds + img_h, img_w, _ = shape + valid_pts = (u >= 0) & (u < img_w) & (v >= 0) & (v < img_h) + u, v = u[valid_pts], v[valid_pts] + return u, v + +def modify_transform(T_lidar_camera): + modified = np.copy(T_lidar_camera) + rotation_mat = R.from_euler('xyz', [x_rot.val, y_rot.val, z_rot.val], degrees=True).as_matrix() + translation_vec = np.array([x_trans.val, y_trans.val, z_trans.val]) + modified[:3, :3] = T_lidar_camera[:3, :3] @ rotation_mat + modified[:3, 3] = T_lidar_camera[:3, 3] + translation_vec + return modified +def create_sliders(fig, update_func): + # Create space for sliders + fig.subplots_adjust(bottom=0.4) + x_rot_ax = fig.add_axes([0.25, 0.3, 0.65, 0.03]) + y_rot_ax = fig.add_axes([0.25, 0.25, 0.65, 0.03]) + z_rot_ax = fig.add_axes([0.25, 0.2, 0.65, 0.03]) + x_trans_ax = fig.add_axes([0.25, 0.15, 0.65, 0.03]) + y_trans_ax = fig.add_axes([0.25, 0.1, 0.65, 0.03]) + z_trans_ax = fig.add_axes([0.25, 0.05, 0.65, 0.03]) # Filter points within image bounds img_h, img_w, _ = shape valid_pts = (u >= 0) & (u < img_w) & (v >= 0) & (v < img_h) @@ -49,6 +85,16 @@ def create_sliders(fig, update_func): y_trans_ax = fig.add_axes([0.25, 0.1, 0.65, 0.03]) z_trans_ax = fig.add_axes([0.25, 0.05, 0.65, 0.03]) + # Make sliders to control the rotation + global x_rot + x_rot = Slider( + ax=x_rot_ax, + label="X Rotation", + valmin=-30, + valmax=30, + valinit=0, + orientation="horizontal" + ) # Make sliders to control the rotation global x_rot x_rot = Slider( @@ -60,6 +106,15 @@ def create_sliders(fig, update_func): orientation="horizontal" ) + global y_rot + y_rot = Slider( + ax=y_rot_ax, + label="Y Rotation", + valmin=-30, + valmax=30, + valinit=0, + orientation="horizontal" + ) global y_rot y_rot = Slider( ax=y_rot_ax, @@ -70,6 +125,15 @@ def create_sliders(fig, update_func): orientation="horizontal" ) + global z_rot + z_rot = Slider( + ax=z_rot_ax, + label="Z Rotation", + valmin=-30, + valmax=30, + valinit=0, + orientation="horizontal" + ) global z_rot z_rot = Slider( ax=z_rot_ax, @@ -80,6 +144,16 @@ def create_sliders(fig, update_func): orientation="horizontal" ) + # Make sliders to control the translation + global x_trans + x_trans = Slider( + ax=x_trans_ax, + label="X Translation", + valmin=-10, + valmax=10, + valinit=0, + orientation="horizontal" + ) # Make sliders to control the translation global x_trans x_trans = Slider( @@ -91,6 +165,15 @@ def create_sliders(fig, update_func): orientation="horizontal" ) + global y_trans + y_trans = Slider( + ax=y_trans_ax, + label="Y Translation", + valmin=-10, + valmax=10, + valinit=0, + orientation="horizontal" + ) global y_trans y_trans = Slider( ax=y_trans_ax, @@ -101,6 +184,15 @@ def create_sliders(fig, update_func): orientation="horizontal" ) + global z_trans + z_trans = Slider( + ax=z_trans_ax, + label="Z Translation", + valmin=-10, + valmax=10, + valinit=0, + orientation="horizontal" + ) global z_trans z_trans = Slider( ax=z_trans_ax, From 0699c430e2536cd5cf093734e3c999ddb47c9ec0 Mon Sep 17 00:00:00 2001 From: whizkid42 Date: Wed, 30 Apr 2025 20:37:51 -0500 Subject: [PATCH 222/232] Updated oak extrinsic calibration --- GEMstack/knowledge/calibration/gem_e4_oak_finetuned_new.yaml | 2 +- GEMstack/knowledge/calibration/gem_e4_oak_new.yaml | 5 +++++ 2 files changed, 6 insertions(+), 1 deletion(-) create mode 100644 GEMstack/knowledge/calibration/gem_e4_oak_new.yaml diff --git a/GEMstack/knowledge/calibration/gem_e4_oak_finetuned_new.yaml b/GEMstack/knowledge/calibration/gem_e4_oak_finetuned_new.yaml index 1d53c0cde..57dcc8fbd 100644 --- a/GEMstack/knowledge/calibration/gem_e4_oak_finetuned_new.yaml +++ b/GEMstack/knowledge/calibration/gem_e4_oak_finetuned_new.yaml @@ -2,4 +2,4 @@ position: [1.9564719286254562, -0.016357857507817864, 2.0489178127802745] reference: rear_axle_center rotation: [[0.02777285065736978, -0.1147911851051555, 0.9930013356428667], [-0.9996095786617777, -0.00014910886738464478, 0.027940436900108796], [-0.0030592505596502726, -0.9933896323138769, - -0.11475050935535633]] + -0.11475050935535633]] \ No newline at end of file diff --git a/GEMstack/knowledge/calibration/gem_e4_oak_new.yaml b/GEMstack/knowledge/calibration/gem_e4_oak_new.yaml new file mode 100644 index 000000000..0d78c35d7 --- /dev/null +++ b/GEMstack/knowledge/calibration/gem_e4_oak_new.yaml @@ -0,0 +1,5 @@ +position: [2.0808976903925527, 0.0046454831123376285, 2.2564570873915066] +reference: rear_axle_center +rotation: [[0.03012359754389654, -0.16959859553080173, 0.9850527322255357], [-0.9995391306089103, + -0.0014095974215514596, 0.03032390833472774], [-0.003754364473137365, -0.9855122167832769, + -0.16956289487477566]] From 9812d36cddebb7d799c27bc8f12658226017e14b Mon Sep 17 00:00:00 2001 From: Michal Juscinski Date: Mon, 5 May 2025 07:12:15 -0700 Subject: [PATCH 223/232] Fix incorrect linear algebra --- GEMstack/knowledge/calibration/gem_e4_fl.yaml | 8 +- GEMstack/knowledge/calibration/gem_e4_fr.yaml | 8 +- .../knowledge/calibration/gem_e4_oak.yaml | 8 +- GEMstack/knowledge/calibration/gem_e4_rl.yaml | 8 +- GEMstack/knowledge/calibration/gem_e4_rr.yaml | 8 +- GEMstack/offboard/calibration/img2pc.py | 23 +--- .../offboard/calibration/test_transforms.py | 108 +++--------------- 7 files changed, 38 insertions(+), 133 deletions(-) diff --git a/GEMstack/knowledge/calibration/gem_e4_fl.yaml b/GEMstack/knowledge/calibration/gem_e4_fl.yaml index 981ddb41f..9e10bc4ed 100644 --- a/GEMstack/knowledge/calibration/gem_e4_fl.yaml +++ b/GEMstack/knowledge/calibration/gem_e4_fl.yaml @@ -1,5 +1,5 @@ -position: [1.7971794298679513, 0.796146176758752, 1.6332326141698077] +position: [2.008491967178938, 0.9574436688609637, 1.7222845229507735] reference: rear_axle_center -rotation: [[0.7233635906739921, -0.14419134401014552, 0.6752436288506333], [-0.6903910162108187, - -0.1655825397435263, 0.704231975598754], [0.010264405559124336, -0.9755979073185922, - -0.21932478610916173]] +rotation: [[0.7229102844527417, -0.13938889438297952, 0.6767358840457229], [-0.6904150547378912, + -0.18396833469067211, 0.6996304053015531], [0.026977264941612008, -0.9729986577348562, + -0.22922879230680995]] diff --git a/GEMstack/knowledge/calibration/gem_e4_fr.yaml b/GEMstack/knowledge/calibration/gem_e4_fr.yaml index f8216491b..00a391c92 100644 --- a/GEMstack/knowledge/calibration/gem_e4_fr.yaml +++ b/GEMstack/knowledge/calibration/gem_e4_fr.yaml @@ -1,5 +1,5 @@ -position: [1.8472221433459501, -0.6787392587860782, 1.7022719016848669] +position: [1.8861563355156226, -0.7733611068168774, 1.6793040225335112] reference: rear_axle_center -rotation: [[-0.7183636802296961, -0.09720447265520028, 0.6888431700262477], [-0.6952720410463521, - 0.13371206053116463, -0.7061995993856021], [-0.023460874382859997, -0.9862415394928613, - -0.16363744458479873]] +rotation: [[-0.7168464770690616, -0.10046018208578958, 0.6899557088168523], [-0.6970911725372957, + 0.12308618950445319, -0.7063382243117325], [-0.01396515249660048, -0.9872981017750231, + -0.15826380744561577]] diff --git a/GEMstack/knowledge/calibration/gem_e4_oak.yaml b/GEMstack/knowledge/calibration/gem_e4_oak.yaml index cb9a6c0d0..ae8d1fce7 100644 --- a/GEMstack/knowledge/calibration/gem_e4_oak.yaml +++ b/GEMstack/knowledge/calibration/gem_e4_oak.yaml @@ -1,3 +1,5 @@ -reference: rear_axle_center # rear axle center -rotation: [[0,0,1],[-1,0,0],[0,-1,0]] # rotation matrix mapping z to forward, x to left, y to down, guesstimated -center_position: [1.78,0,1.58] # meters, center camera, guesstimated +position: [1.8680678362969751, 0.03483728869549903, 1.6545932338230158] +reference: rear_axle_center +rotation: [[0.020064651878799838, -0.013111205776054045, 0.99971271174677], [-0.9997929081548379, + 0.0031358785499412617, 0.020107388418472497], [-0.003398609756043868, -0.9999091271454714, + -0.013045570240818732]] diff --git a/GEMstack/knowledge/calibration/gem_e4_rl.yaml b/GEMstack/knowledge/calibration/gem_e4_rl.yaml index f1bf54dc0..786036fc8 100644 --- a/GEMstack/knowledge/calibration/gem_e4_rl.yaml +++ b/GEMstack/knowledge/calibration/gem_e4_rl.yaml @@ -1,5 +1,5 @@ -position: [0.07110185305534555, 0.6984132712665948, 1.4339602315138475] +position: [0.0898392124024201, 0.71876803481624, 1.71024199833245] reference: rear_axle_center -rotation: [[0.6844266376508905, 0.18773036711896313, -0.7044980446374145], [0.7276311666895623, - -0.11495808685709714, 0.6762673507510828], [0.045968178413242806, -0.9754701225801333, - -0.21527884108421258]] +rotation: [[0.6847850928670124, 0.19803293816635642, -0.7013218462220591], [0.728026894383745, + -0.14318896257364072, 0.6704280439025839], [0.03234528777238433, -0.9696802959730001, + -0.2422269719924619]] diff --git a/GEMstack/knowledge/calibration/gem_e4_rr.yaml b/GEMstack/knowledge/calibration/gem_e4_rr.yaml index cf740f188..8d2dfc105 100644 --- a/GEMstack/knowledge/calibration/gem_e4_rr.yaml +++ b/GEMstack/knowledge/calibration/gem_e4_rr.yaml @@ -1,5 +1,5 @@ -position: [0.16800762903335675, -0.7256009189651329, 1.6932350855315166] +position: [0.11419591502518789, -0.6896311735924415, 1.711181163333824] reference: rear_axle_center -rotation: [[-0.7276140422452938, 0.15527317181293687, -0.6681826404962411], [0.6858832251924825, - 0.14775049453955932, -0.7125545527127647], [-0.011916291664040228, -0.9767599622253681, - -0.21400460836988996]] +rotation: [[-0.7359657309159472, 0.15986191414426415, -0.6578743127098735], [0.6768157805459531, + 0.14993386619459964, -0.7207220233709469], [-0.016578363047300385, -0.9756864271752846, + -0.21854325362408236]] diff --git a/GEMstack/offboard/calibration/img2pc.py b/GEMstack/offboard/calibration/img2pc.py index ac4b1a2f4..f62f83fae 100644 --- a/GEMstack/offboard/calibration/img2pc.py +++ b/GEMstack/offboard/calibration/img2pc.py @@ -59,24 +59,6 @@ def pc_projection(pc,T:Transform,K,img_shape) -> np.ndarray: valid_pts = (u >= 0) & (u < img_w) & (v >= 0) & (v < img_h) return u[valid_pts],v[valid_pts] -def calib(args,pc,img,K,N): -def pc_projection(pc,T:Transform,K,img_shape) -> np.ndarray: - mask = ~(np.all(pc == 0, axis=1)) - pc = pc[mask] - - pc = T @ pc - if pc.shape[1] == 4: - pc = pc[:,:-1]/pc[:,[-1]] - - assert pc.shape[1] == 3 - x,y,z = pc.T - u = (K[0, 0] * x / z) + K[0, 2] - v = (K[1, 1] * y / z) + K[1, 2] - - img_h, img_w, _ = img_shape - valid_pts = (u >= 0) & (u < img_w) & (v >= 0) & (v < img_h) - return u[valid_pts],v[valid_pts] - def calib(args,pc,img,K,N): cpoints = np.array(pick_n_img(img,N)).astype(float) print(cpoints) @@ -141,15 +123,14 @@ def main(): lidar_ex = np.eye(4) if args.pc_transform_path: lidar_ex = load_ex(args.pc_transform_path,mode='matrix') - pc = np.pad(pc,((0,0),(0,1)),constant_values=1) @ lidar_ex.T[:,:3] + pc = (lidar_ex @ np.pad(pc,((0,0),(0,1)),constant_values=1).T).T[:, :3] c2v = calib(args,pc,img,K,N) T = np.linalg.inv(c2v) print(T) if args.show: - T_lidar_camera = T @ lidar_ex - u,v = pc_projection(pc,Transform(T_lidar_camera),K,img.shape) + u,v = pc_projection(pc,Transform(T),K,img.shape) show_img = img.copy() for uu,vv in zip(u.astype(int),v.astype(int)): cv2.circle(show_img, (uu, vv), radius=1, color=(0, 0, 255), thickness=-1) diff --git a/GEMstack/offboard/calibration/test_transforms.py b/GEMstack/offboard/calibration/test_transforms.py index 64eb05fc7..671578c14 100644 --- a/GEMstack/offboard/calibration/test_transforms.py +++ b/GEMstack/offboard/calibration/test_transforms.py @@ -11,9 +11,9 @@ x_rot = y_rot = z_rot = x_trans = y_trans = z_trans = None -def project_points(T_lidar_camera, lidar_homogeneous, K, shape): +def project_points(T_lidar_to_camera, lidar_homogeneous, K, shape): # Transform LiDAR points to Camera Frame - lidar_points_camera = (T_lidar_camera @ lidar_homogeneous.T).T # (N, 4) + lidar_points_camera = (T_lidar_to_camera @ lidar_homogeneous.T).T # (N, 4) # Extract 3D points in camera frame X_c = lidar_points_camera[:, 0] @@ -44,35 +44,13 @@ def project_points(T_lidar_camera, lidar_homogeneous, K, shape): u, v = u[valid_pts], v[valid_pts] return u, v -def modify_transform(T_lidar_camera): - modified = np.copy(T_lidar_camera) +def modify_transform(T_lidar_to_camera): + modified = np.eye(4) rotation_mat = R.from_euler('xyz', [x_rot.val, y_rot.val, z_rot.val], degrees=True).as_matrix() translation_vec = np.array([x_trans.val, y_trans.val, z_trans.val]) - modified[:3, :3] = T_lidar_camera[:3, :3] @ rotation_mat - modified[:3, 3] = T_lidar_camera[:3, 3] + translation_vec - return modified - -def create_sliders(fig, update_func): - # Create space for sliders - fig.subplots_adjust(bottom=0.4) - x_rot_ax = fig.add_axes([0.25, 0.3, 0.65, 0.03]) - y_rot_ax = fig.add_axes([0.25, 0.25, 0.65, 0.03]) - z_rot_ax = fig.add_axes([0.25, 0.2, 0.65, 0.03]) - x_trans_ax = fig.add_axes([0.25, 0.15, 0.65, 0.03]) - y_trans_ax = fig.add_axes([0.25, 0.1, 0.65, 0.03]) - z_trans_ax = fig.add_axes([0.25, 0.05, 0.65, 0.03]) - # Filter points within image bounds - img_h, img_w, _ = shape - valid_pts = (u >= 0) & (u < img_w) & (v >= 0) & (v < img_h) - u, v = u[valid_pts], v[valid_pts] - return u, v - -def modify_transform(T_lidar_camera): - modified = np.copy(T_lidar_camera) - rotation_mat = R.from_euler('xyz', [x_rot.val, y_rot.val, z_rot.val], degrees=True).as_matrix() - translation_vec = np.array([x_trans.val, y_trans.val, z_trans.val]) - modified[:3, :3] = T_lidar_camera[:3, :3] @ rotation_mat - modified[:3, 3] = T_lidar_camera[:3, 3] + translation_vec + modified[:3, :3] = rotation_mat + modified[:3, 3] = translation_vec + modified = modified @ T_lidar_to_camera return modified def create_sliders(fig, update_func): @@ -85,16 +63,6 @@ def create_sliders(fig, update_func): y_trans_ax = fig.add_axes([0.25, 0.1, 0.65, 0.03]) z_trans_ax = fig.add_axes([0.25, 0.05, 0.65, 0.03]) - # Make sliders to control the rotation - global x_rot - x_rot = Slider( - ax=x_rot_ax, - label="X Rotation", - valmin=-30, - valmax=30, - valinit=0, - orientation="horizontal" - ) # Make sliders to control the rotation global x_rot x_rot = Slider( @@ -106,15 +74,6 @@ def create_sliders(fig, update_func): orientation="horizontal" ) - global y_rot - y_rot = Slider( - ax=y_rot_ax, - label="Y Rotation", - valmin=-30, - valmax=30, - valinit=0, - orientation="horizontal" - ) global y_rot y_rot = Slider( ax=y_rot_ax, @@ -125,15 +84,6 @@ def create_sliders(fig, update_func): orientation="horizontal" ) - global z_rot - z_rot = Slider( - ax=z_rot_ax, - label="Z Rotation", - valmin=-30, - valmax=30, - valinit=0, - orientation="horizontal" - ) global z_rot z_rot = Slider( ax=z_rot_ax, @@ -144,16 +94,6 @@ def create_sliders(fig, update_func): orientation="horizontal" ) - # Make sliders to control the translation - global x_trans - x_trans = Slider( - ax=x_trans_ax, - label="X Translation", - valmin=-10, - valmax=10, - valinit=0, - orientation="horizontal" - ) # Make sliders to control the translation global x_trans x_trans = Slider( @@ -165,15 +105,6 @@ def create_sliders(fig, update_func): orientation="horizontal" ) - global y_trans - y_trans = Slider( - ax=y_trans_ax, - label="Y Translation", - valmin=-10, - valmax=10, - valinit=0, - orientation="horizontal" - ) global y_trans y_trans = Slider( ax=y_trans_ax, @@ -184,15 +115,6 @@ def create_sliders(fig, update_func): orientation="horizontal" ) - global z_trans - z_trans = Slider( - ax=z_trans_ax, - label="Z Translation", - valmin=-10, - valmax=10, - valinit=0, - orientation="horizontal" - ) global z_trans z_trans = Slider( ax=z_trans_ax, @@ -241,9 +163,9 @@ def main(): image = cv.cvtColor(image, cv.COLOR_BGR2RGB) # Convert BGR to RGB # Load Transformation Matrices - T_lidar_vehicle = load_ex(args.lidar_transform_path, 'matrix') - T_camera_vehicle = load_ex(args.camera_transform_path, 'matrix') - T_lidar_camera = np.linalg.inv(T_camera_vehicle) @ T_lidar_vehicle + T_lidar_to_vehicle = load_ex(args.lidar_transform_path, 'matrix') + T_camera_to_vehicle = load_ex(args.camera_transform_path, 'matrix') + T_lidar_to_camera = np.linalg.inv(T_camera_to_vehicle) @ T_lidar_to_vehicle # Load Camera Intrinsics if args.undistort: @@ -261,7 +183,7 @@ def main(): fig, ax = plt.subplots() # Project lidar points to camera frame - u, v = project_points(T_lidar_camera, lidar_homogeneous, K, image.shape) + u, v = project_points(T_lidar_to_camera, lidar_homogeneous, K, image.shape) # Plot projected points on camera image ax.imshow(image) @@ -270,7 +192,7 @@ def main(): # Define update function def update(val): - modified = modify_transform(T_lidar_camera) + modified = modify_transform(T_lidar_to_camera) # Update projected points u, v = project_points(modified, lidar_homogeneous, K, image.shape) @@ -293,10 +215,10 @@ def update(val): keep_running = False # Output and write the fine-tuned translation matrix - modified = modify_transform(T_lidar_camera) - print(T_lidar_vehicle @ np.linalg.inv(modified)) + modified = modify_transform(T_lidar_to_camera) + print(T_lidar_to_vehicle @ np.linalg.inv(modified)) if args.out_path: - save_ex(args.out_path, matrix=T_lidar_vehicle @ np.linalg.inv(modified)) + save_ex(args.out_path, matrix=T_lidar_to_vehicle @ np.linalg.inv(modified)) if __name__ == '__main__': main() \ No newline at end of file From b6a67d234b2ccd6ec7ef16fd582c9529a20325ce Mon Sep 17 00:00:00 2001 From: michalj1 <70865139+michalj1@users.noreply.github.com> Date: Mon, 5 May 2025 09:41:08 -0500 Subject: [PATCH 224/232] Delete unnecessary files --- .../camera_intrinsics/calibrated_fl.txt | 37 ------------------- .../camera_intrinsics/calibrated_fr.txt | 37 ------------------- .../camera_intrinsics/calibrated_rl.txt | 37 ------------------- .../camera_intrinsics/calibrated_rr.txt | 37 ------------------- 4 files changed, 148 deletions(-) delete mode 100755 GEMstack/knowledge/calibration/camera_intrinsics/calibrated_fl.txt delete mode 100755 GEMstack/knowledge/calibration/camera_intrinsics/calibrated_fr.txt delete mode 100755 GEMstack/knowledge/calibration/camera_intrinsics/calibrated_rl.txt delete mode 100755 GEMstack/knowledge/calibration/camera_intrinsics/calibrated_rr.txt diff --git a/GEMstack/knowledge/calibration/camera_intrinsics/calibrated_fl.txt b/GEMstack/knowledge/calibration/camera_intrinsics/calibrated_fl.txt deleted file mode 100755 index 4ac9fb31e..000000000 --- a/GEMstack/knowledge/calibration/camera_intrinsics/calibrated_fl.txt +++ /dev/null @@ -1,37 +0,0 @@ -**** Calibrating **** -mono pinhole calibration... -D = [-0.23751890570984993, 0.08452214195986749, -0.00035324203850054794, -0.0003762498910536819, 0.0] -K = [1230.1440959825889, 0.0, 978.8285075011214, 0.0, 1230.6304235898162, 605.7940335714893, 0.0, 0.0, 1.0] -R = [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0] -P = [1060.7667306621374, 0.0, 981.9084026840044, 0.0, 0.0, 1159.9175090232534, 606.1729100950629, 0.0, 0.0, 0.0, 1.0, 0.0] -None -# oST version 5.0 parameters - - -[image] - -width -1920 - -height -1200 - -[narrow_stereo] - -camera matrix -1230.144096 0.000000 978.828508 -0.000000 1230.630424 605.794034 -0.000000 0.000000 1.000000 - -distortion --0.237519 0.084522 -0.000353 -0.000376 0.000000 - -rectification -1.000000 0.000000 0.000000 -0.000000 1.000000 0.000000 -0.000000 0.000000 1.000000 - -projection -1060.766731 0.000000 981.908403 0.000000 -0.000000 1159.917509 606.172910 0.000000 -0.000000 0.000000 1.000000 0.000000 \ No newline at end of file diff --git a/GEMstack/knowledge/calibration/camera_intrinsics/calibrated_fr.txt b/GEMstack/knowledge/calibration/camera_intrinsics/calibrated_fr.txt deleted file mode 100755 index 31e4e111d..000000000 --- a/GEMstack/knowledge/calibration/camera_intrinsics/calibrated_fr.txt +++ /dev/null @@ -1,37 +0,0 @@ -**** Calibrating **** -mono pinhole calibration... -D = [-0.2448506795091457, 0.08202383880344215, 0.0004294271518916802, -0.0012454354245869965, 0.0] -K = [1180.753803927752, 0.0, 934.8594468810093, 0.0, 1177.034929104844, 607.2669740236552, 0.0, 0.0, 1.0] -R = [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0] -P = [995.519995797456, 0.0, 923.4562756312389, 0.0, 0.0, 1099.6556283728762, 608.8885739196182, 0.0, 0.0, 0.0, 1.0, 0.0] -None -# oST version 5.0 parameters - - -[image] - -width -1920 - -height -1200 - -[narrow_stereo] - -camera matrix -1180.753804 0.000000 934.859447 -0.000000 1177.034929 607.266974 -0.000000 0.000000 1.000000 - -distortion --0.244851 0.082024 0.000429 -0.001245 0.000000 - -rectification -1.000000 0.000000 0.000000 -0.000000 1.000000 0.000000 -0.000000 0.000000 1.000000 - -projection -995.519996 0.000000 923.456276 0.000000 -0.000000 1099.655628 608.888574 0.000000 -0.000000 0.000000 1.000000 0.000000 diff --git a/GEMstack/knowledge/calibration/camera_intrinsics/calibrated_rl.txt b/GEMstack/knowledge/calibration/camera_intrinsics/calibrated_rl.txt deleted file mode 100755 index c019d274b..000000000 --- a/GEMstack/knowledge/calibration/camera_intrinsics/calibrated_rl.txt +++ /dev/null @@ -1,37 +0,0 @@ -**** Calibrating **** -mono pinhole calibration... -D = [-0.24343640079788503, 0.09125282937288573, 5.21454371097206e-06, -2.2750254391060847e-05, 0.0] -K = [1216.836137433559, 0.0, 955.7290895142494, 0.0, 1216.0457208793944, 599.3150429290699, 0.0, 0.0, 1.0] -R = [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0] -P = [1046.2719621718043, 0.0, 954.838848203849, 0.0, 0.0, 1143.0056282011747, 599.2973574785816, 0.0, 0.0, 0.0, 1.0, 0.0] -None -# oST version 5.0 parameters - - -[image] - -width -1920 - -height -1200 - -[narrow_stereo] - -camera matrix -1216.836137 0.000000 955.729090 -0.000000 1216.045721 599.315043 -0.000000 0.000000 1.000000 - -distortion --0.243436 0.091253 0.000005 -0.000023 0.000000 - -rectification -1.000000 0.000000 0.000000 -0.000000 1.000000 0.000000 -0.000000 0.000000 1.000000 - -projection -1046.271962 0.000000 954.838848 0.000000 -0.000000 1143.005628 599.297357 0.000000 -0.000000 0.000000 1.000000 0.000000 diff --git a/GEMstack/knowledge/calibration/camera_intrinsics/calibrated_rr.txt b/GEMstack/knowledge/calibration/camera_intrinsics/calibrated_rr.txt deleted file mode 100755 index d1bb29ee1..000000000 --- a/GEMstack/knowledge/calibration/camera_intrinsics/calibrated_rr.txt +++ /dev/null @@ -1,37 +0,0 @@ -**** Calibrating **** -mono pinhole calibration... -D = [-0.24754745389508612, 0.09944435338953724, -3.455420573094537e-05, -0.00022029168609146265, 0.0] -K = [1210.2941870955246, 0.0, 951.3029561113208, 0.0, 1211.035575904068, 600.5637386855253, 0.0, 0.0, 1.0] -R = [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0] -P = [1042.941578923699, 0.0, 948.9910317286675, 0.0, 0.0, 1136.9823670862872, 600.6610182272711, 0.0, 0.0, 0.0, 1.0, 0.0] -None -# oST version 5.0 parameters - - -[image] - -width -1920 - -height -1200 - -[narrow_stereo] - -camera matrix -1210.294187 0.000000 951.302956 -0.000000 1211.035576 600.563739 -0.000000 0.000000 1.000000 - -distortion --0.247547 0.099444 -0.000035 -0.000220 0.000000 - -rectification -1.000000 0.000000 0.000000 -0.000000 1.000000 0.000000 -0.000000 0.000000 1.000000 - -projection -1042.941579 0.000000 948.991032 0.000000 -0.000000 1136.982367 600.661018 0.000000 -0.000000 0.000000 1.000000 0.000000 \ No newline at end of file From 9f41ecc87aa85890ba0356e1771f8396324308fb Mon Sep 17 00:00:00 2001 From: michalj1 Date: Mon, 5 May 2025 09:59:03 -0500 Subject: [PATCH 225/232] Remove unnecessary files --- .../calibration/calibration_by_SfM/README.md | 10 - .../calibration_by_SfM/SfM_handeye.py | 191 ------- .../calibration_by_SfM/data/.gitignore | 2 - .../calibration_by_segmentation/.gitignore | 6 - .../calibration_by_segmentation/CalibAnything | 1 - .../calibration_by_segmentation/calib.bash | 15 - .../data/fl/calib.json | 57 -- .../data/fl/images/.gitignore | 3 - .../data/fl/masks/.gitignore | 3 - .../data/fl/pc/.gitignore | 3 - .../make_dataset.py | 124 ----- .../calibration_by_segmentation/npz_to_pcd.py | 59 -- .../segment-anything | 1 - .../calibration_by_segmentation/setup.bash | 2 - GEMstack/offboard/calibration/create_map.py | 113 ---- .../get_intrinsic_by_chessborad.py | 64 --- .../calibration/global_lidar_localization.py | 521 ------------------ .../offboard/calibration/lidar_to_camera.py | 20 - .../offboard/calibration/lidar_to_vehicle.py | 220 -------- .../offboard/calibration/manual_fine_tune.py | 144 ----- .../offboard/calibration/output/.gitignore | 4 - .../calibration/play_with_pycolmap.py | 161 ------ GEMstack/offboard/calibration/run_img2pc.bash | 9 - .../offboard/calibration/tools/.gitignore | 2 - .../offboard/calibration/tools/__init__.py | 0 .../offboard/calibration/tools/visualizer.py | 42 -- 26 files changed, 1777 deletions(-) delete mode 100644 GEMstack/offboard/calibration/calibration_by_SfM/README.md delete mode 100644 GEMstack/offboard/calibration/calibration_by_SfM/SfM_handeye.py delete mode 100644 GEMstack/offboard/calibration/calibration_by_SfM/data/.gitignore delete mode 100644 GEMstack/offboard/calibration/calibration_by_segmentation/.gitignore delete mode 160000 GEMstack/offboard/calibration/calibration_by_segmentation/CalibAnything delete mode 100644 GEMstack/offboard/calibration/calibration_by_segmentation/calib.bash delete mode 100644 GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/calib.json delete mode 100644 GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/images/.gitignore delete mode 100644 GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/masks/.gitignore delete mode 100644 GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/pc/.gitignore delete mode 100644 GEMstack/offboard/calibration/calibration_by_segmentation/make_dataset.py delete mode 100644 GEMstack/offboard/calibration/calibration_by_segmentation/npz_to_pcd.py delete mode 160000 GEMstack/offboard/calibration/calibration_by_segmentation/segment-anything delete mode 100644 GEMstack/offboard/calibration/calibration_by_segmentation/setup.bash delete mode 100644 GEMstack/offboard/calibration/create_map.py delete mode 100644 GEMstack/offboard/calibration/get_intrinsic_by_chessborad.py delete mode 100644 GEMstack/offboard/calibration/global_lidar_localization.py delete mode 100644 GEMstack/offboard/calibration/lidar_to_camera.py delete mode 100644 GEMstack/offboard/calibration/lidar_to_vehicle.py delete mode 100644 GEMstack/offboard/calibration/manual_fine_tune.py delete mode 100644 GEMstack/offboard/calibration/output/.gitignore delete mode 100644 GEMstack/offboard/calibration/play_with_pycolmap.py delete mode 100644 GEMstack/offboard/calibration/run_img2pc.bash delete mode 100644 GEMstack/offboard/calibration/tools/.gitignore delete mode 100644 GEMstack/offboard/calibration/tools/__init__.py delete mode 100644 GEMstack/offboard/calibration/tools/visualizer.py diff --git a/GEMstack/offboard/calibration/calibration_by_SfM/README.md b/GEMstack/offboard/calibration/calibration_by_SfM/README.md deleted file mode 100644 index 2f3937738..000000000 --- a/GEMstack/offboard/calibration/calibration_by_SfM/README.md +++ /dev/null @@ -1,10 +0,0 @@ -data directory looks like -|-data -||-fl -|||-images -||||-000001.png -||-oak -||-rl -||-... -||-pc -|||-000001.pcd diff --git a/GEMstack/offboard/calibration/calibration_by_SfM/SfM_handeye.py b/GEMstack/offboard/calibration/calibration_by_SfM/SfM_handeye.py deleted file mode 100644 index f9cf48d83..000000000 --- a/GEMstack/offboard/calibration/calibration_by_SfM/SfM_handeye.py +++ /dev/null @@ -1,191 +0,0 @@ -#%% -import cv2 -import open3d as o3d -import numpy as np -import pyvista as pv -from typing import Literal -from tqdm import tqdm -#%% -import os -os.chdir('/mnt/GEMstack/GEMstack/offboard/calibration') -from GEMstack.GEMstack.knowledge.calibration.calib_util import * -#%% -N_PAIRS = 20 -STEP = 3 -cam = 'rr' - -#%% -def get_shape(): - return 1920,1200 - -def getK(): - K_path = f"/mnt/GEMstack/GEMstack/knowledge/calibration/gem_e4_{cam}_in.yaml" - K, distort = load_in(K_path,mode='matrix',return_distort=True) - w,h = get_shape() - newK, roi = cv2.getOptimalNewCameraMatrix(K, distort, (w,h), 1, (w,h)) - return newK - -def get_img_np(img_path): - K_path = f"/mnt/GEMstack/GEMstack/knowledge/calibration/gem_e4_{cam}_in.yaml" - K, distort = load_in(K_path,mode='matrix',return_distort=True) - img = cv2.imread(img_path, cv2.IMREAD_GRAYSCALE) - undistorted = cv2.undistort(img, K, distort) - return np.asarray(undistorted) - -def get_pc_np(pcd_path): - pcd = o3d.io.read_point_cloud(pcd_path) - pc = np.asarray(pcd.points) - pc = pc[~np.all(pc == 0, axis=1)] # remove (0,0,0)'s - return pc - -def vis(pc): - plotter = pv.Plotter(notebook=False) - # plotter = pv.Plotter() - plotter.add_mesh( - pv.PolyData(pc), - render_points_as_spheres=True, - point_size=2, - color='red' - ) - plotter.show() - -#%% -def pcd_paths(): - img_root = '/mnt/GEMstack/GEMstack/offboard/calibration/calibration_by_SfM/data/pc/' - img_format = '.pcd' - for id in range(0,N_PAIRS*STEP+1): - path = img_root + str(id).zfill(6) + img_format - print(path) - yield path - -def img_paths(): - img_root = f'/mnt/GEMstack/GEMstack/offboard/calibration/calibration_by_SfM/data/{cam}/images/' - img_format = '.png' - for id in range(0,N_PAIRS*STEP+1): - path = img_root + str(id).zfill(6) + img_format - print(path) - yield path - -def pcs(): - for path in pcd_paths(): - yield get_pc_np(path) - -def imgs(): - for path in img_paths(): - yield get_img_np(path) - -def iterpair(iter,step): - pre = None - for i in iter: - pre = i - break - for i,v in enumerate(iter): - if i%step == step-1: - yield pre,v - pre = v - -#%% -def findE_img(img1,img2,K): - sift = cv2.SIFT.create() - kp1,des1 = sift.detectAndCompute(img1,None) - kp2,des2 = sift.detectAndCompute(img2,None) - - if des1 is None or des2 is None or len(des1) < 5 or len(des2) < 5: - return None #insufficient features - - FLANN_INDEX_KDTREE = 1 - index_params = dict(algorithm=FLANN_INDEX_KDTREE, trees=5) - search_params = dict(checks=50) - flann = cv2.FlannBasedMatcher(index_params, search_params) - matches = flann.knnMatch(des1, des2, k=2) - good_matches = [m for m,n in matches if m.distance < 0.8 * n.distance] - - pts1 = np.float32([kp1[m.queryIdx].pt for m in good_matches]).reshape(-1, 2) - pts2 = np.float32([kp2[m.trainIdx].pt for m in good_matches]).reshape(-1, 2) - - E, mask = cv2.findEssentialMat(pts1, pts2, K, method=cv2.RANSAC, prob=0.999, threshold=1.0) - if E is None or mask.sum() < 5: - return None #Essential matrix computation failed - _, R_rel, t_rel, mask = cv2.recoverPose(E, pts1, pts2, K, mask=mask) - ret = np.eye(4) - ret[:3, :3] = R_rel - ret[:3, 3] = t_rel.flatten() - return ret - -def findE_pc(pc1,pc2,mode:Literal['icp','kp','svd']): - if mode == 'icp': - source = o3d.geometry.PointCloud() - source.points = o3d.utility.Vector3dVector(pc1) - - target = o3d.geometry.PointCloud() - target.points = o3d.utility.Vector3dVector(pc2) - - source.estimate_normals( - search_param=o3d.geometry.KDTreeSearchParamHybrid(radius=0.1, max_nn=30) - ) - target.estimate_normals( - search_param=o3d.geometry.KDTreeSearchParamHybrid(radius=0.1, max_nn=30) - ) - init_pose = np.eye(4) #assume continuous movement - # Robust configuration - reg = o3d.pipelines.registration.registration_icp( - source, target, - 0.1, - init_pose, - o3d.pipelines.registration.TransformationEstimationPointToPoint(), - o3d.pipelines.registration.ICPConvergenceCriteria( - max_iteration=30, - relative_rmse=1e-6 - ) - ) - return reg.transformation - else: - print(mode,'no imp') - return None - -#%% -rcam, tcam = [],[] -rlidar, tlidar = [],[] -#%% -for i,((img1,img2),(pc1,pc2)) in tqdm(enumerate(zip( - iterpair(map(get_img_np,img_paths()),STEP), - iterpair(map(get_pc_np,pcd_paths()),STEP))),total=N_PAIRS): - K = getK() - E_cam = findE_img(img1,img2,K) - print(E_cam) - E_lidar = findE_pc(pc1,pc2,mode='icp') - print(E_lidar) - if E_cam is None or E_lidar is None: - continue #unsolved - if np.isnan(E_cam).any() or np.isnan(E_lidar).any(): - continue #has nan - if np.linalg.norm(E_lidar[:3,3]) > 0.1*STEP: - continue #too large to be possible - rcam.append(E_cam[:3, :3]) - tcam.append(E_cam[:3, 3]) - rlidar.append(E_lidar[:3, :3]) - tlidar.append(E_lidar[:3, 3]) - -#%% -rt2cam = [] -tt2cam = [] -for r,t in zip(rlidar,tlidar): - B = np.eye(4) - B[:3,:3] = r - B[:3,3] = t - B = np.linalg.inv(B) - rt2cam.append(B[:3,:3]) - tt2cam.append(B[:3,3]) - -X = cv2.calibrateHandEye( - R_gripper2base=rcam, t_gripper2base=tcam, - R_target2cam=rt2cam, t_target2cam=tt2cam, - # R_target2cam=rlidar, t_target2cam=tlidar, - # method=cv2.CALIB_HAND_EYE_TSAI - method=cv2.CALIB_HAND_EYE_PARK -) -#%% -# Result is 4x4 transformation matrix: T_cam_lidar -T_cam_lidar = np.eye(4) -T_cam_lidar[:3, :3] = X[0] -T_cam_lidar[:3, 3] = X[1].flatten() diff --git a/GEMstack/offboard/calibration/calibration_by_SfM/data/.gitignore b/GEMstack/offboard/calibration/calibration_by_SfM/data/.gitignore deleted file mode 100644 index c96a04f00..000000000 --- a/GEMstack/offboard/calibration/calibration_by_SfM/data/.gitignore +++ /dev/null @@ -1,2 +0,0 @@ -* -!.gitignore \ No newline at end of file diff --git a/GEMstack/offboard/calibration/calibration_by_segmentation/.gitignore b/GEMstack/offboard/calibration/calibration_by_segmentation/.gitignore deleted file mode 100644 index d86c77005..000000000 --- a/GEMstack/offboard/calibration/calibration_by_segmentation/.gitignore +++ /dev/null @@ -1,6 +0,0 @@ -weights/* -init_proj* -refined_proj* -data/* -extrinsic.txt -!.gitignore diff --git a/GEMstack/offboard/calibration/calibration_by_segmentation/CalibAnything b/GEMstack/offboard/calibration/calibration_by_segmentation/CalibAnything deleted file mode 160000 index 4122ea18a..000000000 --- a/GEMstack/offboard/calibration/calibration_by_segmentation/CalibAnything +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 4122ea18abe1831b99abbadce91362571a9b5158 diff --git a/GEMstack/offboard/calibration/calibration_by_segmentation/calib.bash b/GEMstack/offboard/calibration/calibration_by_segmentation/calib.bash deleted file mode 100644 index d80424546..000000000 --- a/GEMstack/offboard/calibration/calibration_by_segmentation/calib.bash +++ /dev/null @@ -1,15 +0,0 @@ -data=$1 - -wget -c -O weights/sam_vit_b.pth https://dl.fbaipublicfiles.com/segment_anything/sam_vit_b_01ec64.pth -# wget -c -O sam_vit_h.pth https://dl.fbaipublicfiles.com/segment_anything/sam_vit_h_4b8939.pth - -echo 'running segmentation...' -python3 segment-anything/scripts/amg.py --checkpoint weights/sam_vit_b.pth --model-type vit_b --input $data/selected --output $data/masks/ --stability-score-thresh 0.9 --box-nms-thresh 0.5 --stability-score-offset 0.9 -# python3 segment-anything/scripts/amg.py --checkpoint sam_vit_h.pth --model-type vit_h --input $data/images --output $data/masks/ --stability-score-thresh 0.9 --box-nms-thresh 0.5 --stability-score-offset 0.9 - -echo 'reprocess segmentation...' -python3 CalibAnything/processed_mask.py -i $data/masks -o $data/processed_masks/ - -echo 'running calibration...' -CalibAnything/bin/run_lidar2camera $data/calib.json - diff --git a/GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/calib.json b/GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/calib.json deleted file mode 100644 index e3f633280..000000000 --- a/GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/calib.json +++ /dev/null @@ -1,57 +0,0 @@ -{ - "cam_K": { - "rows": 3, - "cols": 3, - "data": [ - [1230.1440959825889, 0.0, 978.8285075011214], - [0.0, 1230.6304235898162, 605.7940335714893], - [0.000000, 0.000000 , 1.000000 ] - ] - }, - "cam_dist": { - "cols": 5, - "data": [-0.237519, 0.084522, -0.000353, -0.000376, 0.000000] - }, - "T_lidar_to_cam":{ - "rows": 4, - "cols": 4, - "data": [[ 0.62707208, -0.77887383, -0.0116692 , 0.63835046], - [-0.10590946, -0.07040732, -0.99188003, -0.67206479], - [ 0.7717278 , 0.62321615, -0.12664056, -1.06795501], - [ 0 , 0 , 0 , 1 ]] - }, - "img_folder": "selected", - "mask_folder": "processed_masks", - "pc_folder": "../pc", - "img_prefix": "fl", - "img_format": ".png", - "pc_prefix": "ouster", - "pc_format": ".pcd", - "file_name": [ - "b9", - "33", - "37", - "38" - ], - "params": { - "min_plane_point_num": 2000, - "cluster_tolerance": 0.25, - "search_num": 4000, - "search_range": { - "rot_deg": 5, - "trans_m": 0.5 - }, - "point_range":{ - "top": 0.4, - "bottom": 1.0 - }, - "down_sample":{ - "is_valid": true, - "voxel_m": 0.05 - }, - "thread": { - "is_multi_thread": true, - "num_thread": 4 - } - } -} diff --git a/GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/images/.gitignore b/GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/images/.gitignore deleted file mode 100644 index cec9082b6..000000000 --- a/GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/images/.gitignore +++ /dev/null @@ -1,3 +0,0 @@ -* - -!.gitignore diff --git a/GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/masks/.gitignore b/GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/masks/.gitignore deleted file mode 100644 index cec9082b6..000000000 --- a/GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/masks/.gitignore +++ /dev/null @@ -1,3 +0,0 @@ -* - -!.gitignore diff --git a/GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/pc/.gitignore b/GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/pc/.gitignore deleted file mode 100644 index cec9082b6..000000000 --- a/GEMstack/offboard/calibration/calibration_by_segmentation/data/fl/pc/.gitignore +++ /dev/null @@ -1,3 +0,0 @@ -* - -!.gitignore diff --git a/GEMstack/offboard/calibration/calibration_by_segmentation/make_dataset.py b/GEMstack/offboard/calibration/calibration_by_segmentation/make_dataset.py deleted file mode 100644 index 15d742184..000000000 --- a/GEMstack/offboard/calibration/calibration_by_segmentation/make_dataset.py +++ /dev/null @@ -1,124 +0,0 @@ -#%% -import rosbag -import os -import bisect -from sensor_msgs.msg import Image, PointCloud2 -from sensor_msgs import point_cloud2 -import cv2 -from cv_bridge import CvBridge -import numpy as np - -def write_pcd(pc_msg, filename): - # Read points from PointCloud2 message - points = list(point_cloud2.read_points(pc_msg, field_names=("x", "y", "z"), skip_nans=True)) - # Write PCD header - header = f"""VERSION .7 -FIELDS x y z -SIZE 4 4 4 -TYPE F F F -COUNT 1 1 1 -WIDTH {len(points)} -HEIGHT 1 -VIEWPOINT 0 0 0 1 0 0 0 -POINTS {len(points)} -DATA ascii -""" - - # Write to file - with open(filename, 'w') as f: - f.write(header) - for p in points: - if p[0] == 0 and p[1] == 0 and p[2] == 0: continue - f.write(f"{p[0]} {p[1]} {p[2]}\n") - -def process_bag(bag_path, output_dir='sync_dataset', time_threshold=0.05): - bag = rosbag.Bag(bag_path) - bridge = CvBridge() - - # Topic configuration - topic_map = { - '/camera_fl/arena_camera_node/image_raw': 'fl/images', - '/camera_rl/arena_camera_node/image_raw': 'rl/images', - '/camera_rr/arena_camera_node/image_raw': 'rr/images', - '/oak/rgb/image_raw': 'oak/images', - '/ouster/points': 'pc' - } - - # Create output directories - for d in ['fl', 'rl', 'rr', 'oak', 'pc']: - os.makedirs(os.path.join(output_dir, d), exist_ok=True) - - # Load and sort all messages - messages = {topic: [] for topic in topic_map.keys()} - for topic, msg, t in bag.read_messages(topics=topic_map.keys()): - stamp = msg.header.stamp.to_sec() if hasattr(msg, 'header') else t.to_sec() - messages[topic].append((stamp, msg)) - - # Sort each topic by timestamp - for topic in messages: - messages[topic].sort(key=lambda x: x[0]) - - # Reference topic (point cloud) - ref_topic = '/ouster/points' - group_index = 0 - - for pc_stamp, pc_msg in messages[ref_topic]: - timestamps = {'pc': pc_stamp} - entry = {} - - # Find closest camera messages - for cam_topic in topic_map: - if cam_topic == ref_topic: - continue - cam_msgs = messages.get(cam_topic, []) - if not cam_msgs: - continue - stamps = [s for s, m in cam_msgs] - idx = bisect.bisect_left(stamps, pc_stamp) - - closest = None - closest_stamp = None - - # Check next message - if idx < len(stamps): - if abs(stamps[idx] - pc_stamp) < time_threshold: - closest = cam_msgs[idx][1] - closest_stamp = stamps[idx] - - # Check previous message if not found - if not closest and idx > 0: - if abs(stamps[idx-1] - pc_stamp) < time_threshold: - closest = cam_msgs[idx-1][1] - closest_stamp = stamps[idx-1] - - if closest: - entry[cam_topic] = (closest_stamp, closest) - timestamps[topic_map[cam_topic]] = closest_stamp - - # Save only if we have all sensors - if len(entry) == 4: # 4 camera topics + point cloud - # Save images and point cloud - frame_id = f"{group_index:06d}" - - # Print timestamps - print(f"Saved group {group_index} with timestamps:") - for sensor, ts in timestamps.items(): - print(f" {sensor}: {ts:.6f}") - - # Save images - for topic, (stamp, msg) in entry.items(): - output_subdir = topic_map[topic] - output_path = os.path.join(output_dir, output_subdir, f"{frame_id}.png") - cv_img = bridge.imgmsg_to_cv2(msg, desired_encoding='passthrough') - cv2.imwrite(output_path, cv_img) - - # Save point cloud - pc_path = os.path.join(output_dir, 'pc', f"{frame_id}.pcd") - write_pcd(pc_msg, pc_path) - - group_index += 1 - - bag.close() - -# Example usage -process_bag('/mnt/GEMstack/data/mybag_2025-04-01-17-41-55.bag','/mnt/GEMstack/GEMstack/offboard/calibration/calibration_by_SfM/data') \ No newline at end of file diff --git a/GEMstack/offboard/calibration/calibration_by_segmentation/npz_to_pcd.py b/GEMstack/offboard/calibration/calibration_by_segmentation/npz_to_pcd.py deleted file mode 100644 index ddbc89e29..000000000 --- a/GEMstack/offboard/calibration/calibration_by_segmentation/npz_to_pcd.py +++ /dev/null @@ -1,59 +0,0 @@ -#%% -#%% -import numpy as np -import open3d as o3d -import os -import argparse - -def npz_to_pcd(input_dir, output_dir, data_key='arr_0'): - # Create output directory if it doesn't exist - os.makedirs(output_dir, exist_ok=True) - - # Iterate over all .npz files in the input directory - for npz_file in os.listdir(input_dir): - if npz_file.endswith(".npz"): - npz_path = os.path.join(input_dir, npz_file) - output_pcd_path = os.path.join(output_dir, npz_file.replace('.npz', '.pcd')) - - try: - # Load data from .npz file - data = np.load(npz_path) - if data_key not in data: - print(f"Skipping {npz_file}: Key '{data_key}' not found.") - continue - - point_cloud_np = data[data_key] - mask = ~(np.all(point_cloud_np == [0, 0, 0], axis=1)) - point_cloud_np = point_cloud_np[mask] - # Validate shape (Nx3 for XYZ, Nx6 for XYZRGB, etc.) - if point_cloud_np.ndim != 2 or point_cloud_np.shape[1] < 3: - print(f"Skipping {npz_file}: Invalid shape {point_cloud_np.shape}.") - continue - - # Create Open3D point cloud object - pcd = o3d.geometry.PointCloud() - - # Assign points (required: Nx3 array) - pcd.points = o3d.utility.Vector3dVector(point_cloud_np[:, :3]) - - # Optionally assign colors (if available, e.g., Nx6 array with RGB) - if point_cloud_np.shape[1] >= 6: - # RGB values (assuming they are stored as 0-255 integers) - colors = point_cloud_np[:, 3:6] / 255.0 # Normalize to [0, 1] for Open3D - pcd.colors = o3d.utility.Vector3dVector(colors) - - # Save to .pcd (supports ASCII or binary) - o3d.io.write_point_cloud(output_pcd_path, pcd, write_ascii=True) - print(f"Converted: {npz_file} -> {output_pcd_path}") - - except Exception as e: - print(f"Failed to convert {npz_file}: {str(e)}") - -if __name__ == "__main__": - parser = argparse.ArgumentParser(description="Convert .npz to .pcd using Open3D") - parser.add_argument("--input_dir", type=str, required=True, help="Input directory with .npz files") - parser.add_argument("--output_dir", type=str, required=True, help="Output directory for .pcd files") - parser.add_argument("--data_key", type=str, default='points', help="Key for point cloud data in .npz files") - args = parser.parse_args() - - npz_to_pcd(args.input_dir, args.output_dir, args.data_key) \ No newline at end of file diff --git a/GEMstack/offboard/calibration/calibration_by_segmentation/segment-anything b/GEMstack/offboard/calibration/calibration_by_segmentation/segment-anything deleted file mode 160000 index dca509fe7..000000000 --- a/GEMstack/offboard/calibration/calibration_by_segmentation/segment-anything +++ /dev/null @@ -1 +0,0 @@ -Subproject commit dca509fe793f601edb92606367a655c15ac00fdf diff --git a/GEMstack/offboard/calibration/calibration_by_segmentation/setup.bash b/GEMstack/offboard/calibration/calibration_by_segmentation/setup.bash deleted file mode 100644 index a3ffa9e26..000000000 --- a/GEMstack/offboard/calibration/calibration_by_segmentation/setup.bash +++ /dev/null @@ -1,2 +0,0 @@ - -cd segment-anything; pip install -e .; cd .. \ No newline at end of file diff --git a/GEMstack/offboard/calibration/create_map.py b/GEMstack/offboard/calibration/create_map.py deleted file mode 100644 index 648cebdc4..000000000 --- a/GEMstack/offboard/calibration/create_map.py +++ /dev/null @@ -1,113 +0,0 @@ -import os -import glob -import numpy as np -import cv2 -import open3d as o3d -import pyvista as pv - -def load_lidar_points(npz_file: str): - """ - Load the Nx3 LiDAR points from a .npz file created by 'np.savez'. - """ - data = np.load(npz_file) - # The capture code used: np.savez(lidar_fn, pc) - # So 'data' might have the default key 'arr_0' or 'pc' if named - # Inspect data.files to see. Let's assume 'arr_0' or single key: - arr_key = data.files[0] - points = data[arr_key] - # shape check, must be Nx3 or Nx4, ... - return points - -def make_open3d_pc(points: np.ndarray): - """ - Convert Nx3 numpy array into an Open3D point cloud object. - """ - pcd = o3d.geometry.PointCloud() - pcd.points = o3d.utility.Vector3dVector(points) - return pcd - -def perform_icp(source_pc: o3d.geometry.PointCloud, - target_pc: o3d.geometry.PointCloud): - """ - Perform local ICP alignment of camera_pcd (source) to lidar_pcd (target). - Returns a transformation 4x4 that maps camera -> lidar (or vice versa). - """ - # Estimate normals for point-to-plane - source_pc.estimate_normals(search_param=o3d.geometry.KDTreeSearchParamHybrid( - radius=1.0, max_nn=30)) - target_pc.estimate_normals(search_param=o3d.geometry.KDTreeSearchParamHybrid( - radius=1.0, max_nn=30)) - - # Initial guess: identity or something better if you have one - init_guess = np.eye(4) - - # Choose a threshold for inlier distance - threshold = 0.5 # adjust based on your environment scale - - # Run ICP (point-to-plane or point-to-point) - print("[ICP] Running ICP alignment ...") - result = o3d.pipelines.registration.registration_icp( - source_pc, - target_pc, - threshold, - init_guess, - estimation_method=o3d.pipelines.registration.TransformationEstimationPointToPlane() - ) - - print("[ICP] Done. Fitness = %.4f, RMSE = %.4f" % (result.fitness, result.inlier_rmse)) - print("[ICP] Transformation:\n", result.transformation) - return result - -def main(source='ouster1', target='ouster2', folder='data'): - source_path = os.path.join(folder, f"{source}.npz") - target_path = os.path.join(folder, f"{target}.npz") - - # Check for existence of files - if not os.path.exists(source_path): - print("Invalid source path", source_path) - exit(1) - if not os.path.exists(target_path): - print("Invalid target path", target_path) - exit(1) - - # Load LiDAR - source_points = load_lidar_points(source_path) - target_points = load_lidar_points(target_path) - source_points = source_points[~np.all(source_points == 0, axis=1)] # remove (0,0,0)'s - target_points = target_points[~np.all(target_points == 0, axis=1)] # remove (0,0,0)'s - source_pc = make_open3d_pc(source_points) - target_pc = make_open3d_pc(target_points) - - # Run ICP - result = perform_icp(source_pc, target_pc) - # point_cloud = np.append(target_points, source_points @ result.transformation) - - # View result - # cloud = pv.PolyData(point_cloud) - target = pv.PolyData(target_points) - source = pv.PolyData(source_points @ result.transformation) - plotter = pv.Plotter(notebook=False) - plotter.camera.position = (-20,0,20) - plotter.camera.focal_point = (0,0,0) - # plotter.add_mesh(cloud, color='lightblue', point_size=5, render_points_as_spheres=True) - plotter.add_mesh(source, color='orange', point_size=5, render_points_as_spheres=True) - plotter.add_mesh(target, color='navy', point_size=5, render_points_as_spheres=True) - plotter.show() - - -if __name__ == "__main__": - import sys - if len(sys.argv) == 1: - main() - elif len(sys.argv) == 3: - source = sys.argv[1] - target = sys.argv[2] - main(source, target) - elif len(sys.argv) == 4: - source = sys.argv[1] - target = sys.argv[2] - folder = sys.argv[3] - main(source, target, folder) - else: - print("Usage: python3 createmap.py [source target] [folder]") - \ No newline at end of file diff --git a/GEMstack/offboard/calibration/get_intrinsic_by_chessborad.py b/GEMstack/offboard/calibration/get_intrinsic_by_chessborad.py deleted file mode 100644 index 3dca9bdbb..000000000 --- a/GEMstack/offboard/calibration/get_intrinsic_by_chessborad.py +++ /dev/null @@ -1,64 +0,0 @@ -import cv2 -import numpy as np -from GEMstack.GEMstack.knowledge.calibration.calib_util import save_in - -import glob -def estimate_intrinsics(image_dir, checkerboard_size): - criteria = (cv2.TERM_CRITERIA_EPS + cv2.TERM_CRITERIA_MAX_ITER, 30, 0.001) - - w,h = checkerboard_size - objp = np.zeros((w*h,3), np.float32) - objp[:,:2] = np.mgrid[0:w,0:h].T.reshape(-1,2) - - objpoints = [] - imgpoints = [] - images = glob.glob(image_dir + '*.png') - for fname in images: - img = cv2.imread(fname) - - gray = cv2.cvtColor(img,cv2.COLOR_BGR2GRAY) - - ret, corners = cv2.findChessboardCorners(gray, (w,h),None) - - if ret == True: - objpoints.append(objp) - - corners2 = cv2.cornerSubPix(gray,corners,(11,11),(-1,-1),criteria) - imgpoints.append(corners2) - - img = cv2.drawChessboardCorners(img, (w,h), corners2,ret) - cv2.imshow('img',img) - cv2.waitKey(500) - - cv2.destroyAllWindows() - ret, mtx, dist, rvecs, tvecs = cv2.calibrateCamera(objpoints, imgpoints, gray.shape[::-1],None,None) - - return { - 'fx': mtx[0,0], - 'fy': mtx[1,1], - 'cx': mtx[0,2], - 'cy': mtx[1,2], - 'distortion_coeffs': dist[0].tolist() - } - -if __name__ == "__main__": - import sys - if len(sys.argv) < 4: - print(f"Usage: python3 this.py [output_path]") - sys.exit(1) - - try: - image_path = sys.argv[1] - w = int(sys.argv[2]) - h = int(sys.argv[3]) - params = estimate_intrinsics(image_path, (w,h)) - print("Camera Intrinsics:") - print(f"Focal Length (fx, fy): {params['fx']:.2f}, {params['fy']:.2f}") - print(f"Principal Point (cx, cy): {params['cx']:.2f}, {params['cy']:.2f}") - print(f"Distortion Coefficients: {params['distortion_coeffs']}") - except Exception as e: - print(f"Error: {str(e)}") - - if len(sys.argv) == 5: - out_path = sys.argv[4] - save_in(out_path, focal=[params['fx'],params['fy']], center=[params['cx'],params['cy']],distort=params['distortion_coeffs'],skew=0) \ No newline at end of file diff --git a/GEMstack/offboard/calibration/global_lidar_localization.py b/GEMstack/offboard/calibration/global_lidar_localization.py deleted file mode 100644 index 62b7b50be..000000000 --- a/GEMstack/offboard/calibration/global_lidar_localization.py +++ /dev/null @@ -1,521 +0,0 @@ -#!/usr/bin/env python3 -import numpy as np -import open3d as o3d -import copy -import time -import argparse -import os -import glob -from scipy.spatial.transform import Rotation as R - -def load_map(map_file): - """Load a .ply map file.""" - print(f"Loading map from {map_file}...") - try: - map_pcd = o3d.io.read_point_cloud(map_file) - points = np.asarray(map_pcd.points) - print(f"Map stats:") - print(f" Number of points: {len(points)}") - print(f" Min: {np.min(points, axis=0)}") - print(f" Max: {np.max(points, axis=0)}") - - # Calculate map center for later use - map_center = np.mean(points, axis=0) - print(f" Center: {map_center}") - - return map_pcd - except Exception as e: - print(f"Error loading map: {e}") - return None, None - -def load_lidar_scan(scan_file): - """Load a .npz lidar scan file.""" - print(f"Loading lidar scan from {scan_file}...") - try: - data = np.load(scan_file, allow_pickle=True) - - # Use 'arr_0' as the key for your .npz files - if 'arr_0' in data: - points = data['arr_0'] - elif 'points' in data: - points = data['points'] - else: - points = data[list(data.keys())[0]] - - # Create point cloud from numpy array - scan_pcd = o3d.geometry.PointCloud() - scan_pcd.points = o3d.utility.Vector3dVector(points[:, :3]) - - # Add intensity as colors if available (4th column) - if points.shape[1] >= 4: - intensities = points[:, 3] - normalized_intensity = (intensities - np.min(intensities)) / (np.max(intensities) - np.min(intensities) + 1e-10) - colors = np.zeros((points.shape[0], 3)) - colors[:, 0] = normalized_intensity # Map intensity to red channel - colors[:, 1] = normalized_intensity # Map intensity to green channel - colors[:, 2] = normalized_intensity # Map intensity to blue channel - scan_pcd.colors = o3d.utility.Vector3dVector(colors) - - print(f"Scan loaded with {len(np.asarray(scan_pcd.points))} points") - - # Print scan stats - points = np.asarray(scan_pcd.points) - print(f"Scan stats:") - print(f" Number of points: {len(points)}") - print(f" Min: {np.min(points, axis=0)}") - print(f" Max: {np.max(points, axis=0)}") - - return scan_pcd - except Exception as e: - print(f"Error loading scan: {e}") - return None - -def load_all_scans_from_folder(folder_path): - """Load all .npz files from a folder as lidar scans.""" - print(f"Loading all lidar scans from {folder_path}...") - - # First validate that the path exists and is a directory - if not os.path.isdir(folder_path): - print(f"Error: {folder_path} is not a valid directory") - return [] - - # List all files in the directory (for debugging) - all_files = os.listdir(folder_path) - print(f"All files in directory: {len(all_files)}") - - # Get all .npz files using glob - scan_files = glob.glob(os.path.join(folder_path, "*.npz")) - - if not scan_files: - print(f"No .npz files found in {folder_path}") - print(f"Files in directory: {all_files}") - return [] - - print(f"Found {len(scan_files)} scan files") - scan_list = [] - - for scan_file in scan_files: - print(f"Loading {os.path.basename(scan_file)}...") - scan = load_lidar_scan(scan_file) - if scan is not None: - scan_list.append(scan) - - print(f"Successfully loaded {len(scan_list)} scans") - return scan_list - -def remove_floor_ceiling(pcd, z_min=-0.5, z_max=2.5): - """Remove floor and ceiling points to focus on walls and structural features.""" - points = np.asarray(pcd.points) - mask = np.logical_and(points[:, 2] > z_min, points[:, 2] < z_max) - - filtered_pcd = o3d.geometry.PointCloud() - filtered_pcd.points = o3d.utility.Vector3dVector(points[mask]) - if pcd.has_colors(): - filtered_pcd.colors = o3d.utility.Vector3dVector(np.asarray(pcd.colors)[mask]) - - return filtered_pcd - -def extract_structural_features(pcd, voxel_size): - """Extract structural features like walls from point cloud.""" - # Downsample first - pcd_down = pcd.voxel_down_sample(voxel_size) - - # Estimate normals - pcd_down.estimate_normals( - o3d.geometry.KDTreeSearchParamHybrid(radius=voxel_size*2, max_nn=30)) - - # Find planar segments (walls, floors, etc.) - planes = [] - rest = copy.deepcopy(pcd_down) - for i in range(6): # Extract top 6 planes - if len(np.asarray(rest.points)) < 100: - break - plane_model, inliers = rest.segment_plane(distance_threshold=voxel_size*2, - ransac_n=3, - num_iterations=1000) - if len(inliers) < 50: - break - - plane = rest.select_by_index(inliers) - planes.append(plane) - rest = rest.select_by_index(inliers, invert=True) - - # Combine planes into a single point cloud - structural_pcd = o3d.geometry.PointCloud() - for plane in planes: - structural_pcd += plane - - # If no planes were found, return the original downsampled point cloud - if len(planes) == 0: - return pcd_down - - return structural_pcd - -def fuse_scans(scan_list, voxel_size=0.1): - """Fuse multiple LiDAR scans into a single point cloud.""" - if not scan_list: - return None - - # Start with the first scan - fused_pcd = copy.deepcopy(scan_list[0]) - - # Add points from subsequent scans - for scan in scan_list[1:]: - fused_pcd += scan - - # Downsample to maintain uniform density - fused_pcd = fused_pcd.voxel_down_sample(voxel_size) - - # Print stats for fused scan - fused_points = np.asarray(fused_pcd.points) - print(f"Fused scan stats:") - print(f" Number of points: {len(fused_points)}") - print(f" Min: {np.min(fused_points, axis=0)}") - print(f" Max: {np.max(fused_points, axis=0)}") - - return fused_pcd - -def prepare_scan_for_global_registration(scan_pcd, map_pcd, scale_ratio=None): - """Improved scaling/translation using actual map bounds""" - # Get map dimensions - map_points = np.asarray(map_pcd.points) - map_min = np.min(map_points, axis=0) - map_max = np.max(map_points, axis=0) - map_center = (map_min + map_max) / 2 - - # Get scan dimensions - scan_points = np.asarray(scan_pcd.points) - scan_min = np.min(scan_points, axis=0) - scan_max = np.max(scan_points, axis=0) - - # Calculate dynamic scale ratio - if not scale_ratio: - map_range = map_max - map_min - scan_range = scan_max - scan_min - scale_ratio = np.min(map_range / scan_range) * 0.8 # Use 80% of map size - - # Apply scaling and center alignment - scaled_points = (scan_points - scan_min) * scale_ratio + map_min - - aligned_scan = o3d.geometry.PointCloud() - aligned_scan.points = o3d.utility.Vector3dVector(scaled_points) - - print(f"Dynamic scaling ratio: {scale_ratio}") - return aligned_scan - - - - -def preprocess_point_cloud(pcd, voxel_size, radius_normal=None, radius_feature=None): - """Modified feature parameters for better matching""" - pcd_down = pcd.voxel_down_sample(voxel_size) - - # Larger radii to capture building-scale features - radius_normal = radius_normal or voxel_size * 5.0 # Increased from 2.0 - radius_feature = radius_feature or voxel_size * 10.0 # Increased from 5.0 - - pcd_down.estimate_normals( - o3d.geometry.KDTreeSearchParamHybrid(radius=radius_normal, max_nn=50)) - - pcd_fpfh = o3d.pipelines.registration.compute_fpfh_feature( - pcd_down, - o3d.geometry.KDTreeSearchParamHybrid(radius=radius_feature, max_nn=100)) - - return pcd_down, pcd_fpfh - - - -def execute_global_registration(source_down, target_down, source_fpfh, target_fpfh, - voxel_size, max_iterations=1000000): - """Improved RANSAC registration with configurable iterations.""" - distance_threshold = voxel_size * 15 # Increased for initial alignment - - result = o3d.pipelines.registration.registration_ransac_based_on_feature_matching( - source_down, target_down, source_fpfh, target_fpfh, True, - distance_threshold, - o3d.pipelines.registration.TransformationEstimationPointToPoint(False), - 4, - [o3d.pipelines.registration.CorrespondenceCheckerBasedOnEdgeLength(0.9), - o3d.pipelines.registration.CorrespondenceCheckerBasedOnDistance(distance_threshold), - o3d.pipelines.registration.CorrespondenceCheckerBasedOnNormal(0.5)], - o3d.pipelines.registration.RANSACConvergenceCriteria(max_iterations, 500)) - - return result - - - -def execute_fast_global_registration(source_down, target_down, source_fpfh, target_fpfh, voxel_size): - """Perform Fast Global Registration.""" - distance_threshold = voxel_size * 0.5 - print(f":: Apply fast global registration with distance threshold {distance_threshold:.3f}") - - try: - result = o3d.pipelines.registration.registration_fgr_based_on_feature_matching( - source_down, target_down, source_fpfh, target_fpfh, - o3d.pipelines.registration.FastGlobalRegistrationOption( - maximum_correspondence_distance=distance_threshold)) - return result - except RuntimeError as e: - print(f"Error in FGR: {e}") - # Return dummy result with identity transformation in case of failure - dummy_result = o3d.pipelines.registration.RegistrationResult() - dummy_result.transformation = np.identity(4) - dummy_result.fitness = 0.0 - dummy_result.inlier_rmse = 0.0 - dummy_result.correspondence_set = [] - return dummy_result - -def multi_scale_icp(source, target, voxel_sizes=[2.0, 1.0, 0.5], max_iterations=[50, 30, 14], - initial_transform=np.eye(4)): - """Perform multi-scale ICP for robust alignment.""" - print("Running multi-scale ICP...") - current_transform = initial_transform - - for i, (voxel_size, max_iter) in enumerate(zip(voxel_sizes, max_iterations)): - print(f"ICP Scale {i+1}/{len(voxel_sizes)}: voxel_size={voxel_size}, max_iterations={max_iter}") - - # Downsample based on current voxel size - source_down = source.voxel_down_sample(voxel_size) - target_down = target.voxel_down_sample(voxel_size) - - # Estimate normals if not already computed - source_down.estimate_normals( - o3d.geometry.KDTreeSearchParamHybrid(radius=voxel_size*2, max_nn=30)) - target_down.estimate_normals( - o3d.geometry.KDTreeSearchParamHybrid(radius=voxel_size*2, max_nn=30)) - - # Use appropriate distance threshold based on scale - distance_threshold = max(0.5, voxel_size * 2) - - # Run ICP - result = o3d.pipelines.registration.registration_icp( - source_down, target_down, distance_threshold, current_transform, - o3d.pipelines.registration.TransformationEstimationPointToPoint(), - o3d.pipelines.registration.ICPConvergenceCriteria(max_iteration=max_iter)) - - current_transform = result.transformation - print(f" Scale {i+1} result - Fitness: {result.fitness:.4f}, RMSE: {result.inlier_rmse:.4f}") - - return current_transform - -def transform_to_pose(transformation_matrix): - """Convert transformation matrix to position and orientation (RPY).""" - # Extract translation - x, y, z = transformation_matrix[:3, 3] - - # Extract rotation matrix and convert to Euler angles - # Make a writable copy to avoid read-only array issues - rotation_matrix = np.array(transformation_matrix[:3, :3], copy=True) - r = R.from_matrix(rotation_matrix) - roll, pitch, yaw = r.as_euler('xyz', degrees=True) - - return x, y, z, roll, pitch, yaw - -def draw_registration_result(source, target, transformation): - """Visualize the source and target point clouds after alignment.""" - source_temp = copy.deepcopy(source) - target_temp = copy.deepcopy(target) - - source_temp.paint_uniform_color([1, 0.706, 0]) # Orange for source - target_temp.paint_uniform_color([0, 0.651, 0.929]) # Blue for target - - source_temp.transform(transformation) - - # Downsample for visualization if point clouds are too large - if len(np.asarray(source_temp.points)) > 500000: - source_temp = source_temp.voxel_down_sample(0.1) - if len(np.asarray(target_temp.points)) > 500000: - target_temp = target_temp.voxel_down_sample(0.1) - vis = o3d.visualization.Visualizer() - vis.create_window() - vis.add_geometry(source_temp) - vis.add_geometry(target_temp) - vis.get_render_option().point_size = 2 - vis.run() - # o3d.visualization.draw_geometries([source_temp, target_temp]) - -def main(): - parser = argparse.ArgumentParser(description='Global registration for LiDAR localization') - parser.add_argument('--map', required=True, help='Path to .ply map file') - parser.add_argument('--scan-folder', help='Folder containing .npz lidar scan files') - parser.add_argument('--scans', nargs='+', help='Paths to .npz lidar scan files') - parser.add_argument('--output', default='global_registration_result.txt', - help='Output file for transformation matrix') - parser.add_argument('--method', choices=['ransac', 'fgr', 'both'], default='both', - help='Global registration method to use') - parser.add_argument('--voxel-size', type=float, default=1.0, - help='Voxel size for downsampling (for global map)') - parser.add_argument('--scan-voxel-size', type=float, default=0.5, - help='Voxel size for scan downsampling') - parser.add_argument('--visualize', action='store_true', - help='Visualize the alignment result') - parser.add_argument('--map-scale-ratio', type=float, default=1.0, - help='Scale ratio to apply to scan to match map scale') - parser.add_argument('--icp-refine', action='store_true', default=True, - help='Refine alignment with ICP after global registration') - parser.add_argument('--structural-features', action='store_true', default=True, - help='Extract structural features for better alignment') - args = parser.parse_args() - - # Validate inputs - if not args.scan_folder and not args.scans: - print("Error: You must provide either --scan-folder or --scans") - return - - # Load map - map_pcd = load_map(args.map) - print(map_pcd) - if map_pcd is None: - print("Failed to load map. Exiting.") - return - - # Load scans - scan_list = [] - if args.scan_folder: - scan_list = load_all_scans_from_folder(args.scan_folder) - elif args.scans: - for scan_file in args.scans: - scan = load_lidar_scan(scan_file) - if scan is not None: - scan_list.append(scan) - - if not scan_list: - print("No valid scans loaded. Exiting.") - return - - # Fuse scans if multiple - print(f"Loaded {len(scan_list)} LiDAR scans.") - if len(scan_list) > 1: - print("Fusing scans...") - scan_pcd = fuse_scans(scan_list, voxel_size=args.scan_voxel_size) - else: - scan_pcd = scan_list[0] - - # Scale and translate the scan to match map scale and center - print(f"Preparing scan for global registration with scale ratio {args.map_scale_ratio}...") - scaled_scan_pcd = prepare_scan_for_global_registration( - scan_pcd, - map_pcd, - args.map_scale_ratio - ) - - - normal_radius_factor = 2.0 - feature_radius_factor = 5.0 - - print("Preprocessing map...") - map_down, map_fpfh = preprocess_point_cloud( - map_pcd, args.voxel_size, normal_radius_factor, feature_radius_factor) - - print("Preprocessing scan...") - scan_down, scan_fpfh = preprocess_point_cloud( - scaled_scan_pcd, args.scan_voxel_size, normal_radius_factor, feature_radius_factor) - - - # Global registration - transformation = np.identity(4) - - if args.method in ['ransac', 'both']: - start_time = time.time() - ransac_result = execute_global_registration( - scan_down, map_down, scan_fpfh, map_fpfh, args.voxel_size) - print(f"RANSAC registration took {time.time() - start_time:.3f} seconds") - print(f"RANSAC result:") - print(f" Fitness: {ransac_result.fitness:.6f}") - print(f" Inlier RMSE: {ransac_result.inlier_rmse:.6f}") - print(f" Correspondence set size: {len(ransac_result.correspondence_set)}") - - if args.visualize: - print("Visualizing RANSAC result...") - draw_registration_result(scan_down, map_down, ransac_result.transformation) - - transformation = ransac_result.transformation - - if args.method in ['fgr', 'both']: - start_time = time.time() - fgr_result = execute_fast_global_registration( - scan_down, map_down, scan_fpfh, map_fpfh, args.voxel_size) - print(f"Fast Global Registration took {time.time() - start_time:.3f} seconds") - print(f"FGR result:") - print(f" Fitness: {fgr_result.fitness:.6f}") - print(f" Inlier RMSE: {fgr_result.inlier_rmse:.6f}") - print(f" Correspondence set size: {len(fgr_result.correspondence_set)}") - - if args.visualize: - print("Visualizing FGR result...") - draw_registration_result(scan_down, map_down, fgr_result.transformation) - - if args.method == 'both': - # Use the better result based on fitness - if fgr_result.fitness > ransac_result.fitness: - print("Using FGR result (better fitness).") - transformation = fgr_result.transformation - else: - print("Using RANSAC result (better fitness).") - else: - transformation = fgr_result.transformation - - # Refine with ICP if requested - if args.icp_refine: - print("Refining with multi-scale ICP...") - icp_transformation = multi_scale_icp( - scan_down, map_down, - voxel_sizes=[2.0, 1.0, 0.5], - max_iterations=[100, 50, 30], - initial_transform=transformation) - - final_transformation = icp_transformation - else: - final_transformation = transformation - - # # Extract position and orientation - x, y, z, roll, pitch, yaw = transform_to_pose(final_transformation) - - # # We need to scale back the translation since we scaled the scan - # # The rotation part doesn't need scaling - # if args.map_scale_ratio != 1.0: - # # Need to account for the initial translation and scaling - # # The final transformation includes the initial translation - # # So we need to extract just the additional transformation from global registration - # x /= args.map_scale_ratio - # y /= args.map_scale_ratio - # z /= args.map_scale_ratio - - # # Modify the final transformation matrix to undo the scaling effect on translation - # tmp = final_transformation - # final_transformation = np.zeros_like(tmp) - # final_transformation[:] = tmp - # final_transformation[:3, 3] /= args.map_scale_ratio - - # Print final results - print(f"Estimated vehicle position: [{x:.2f}, {y:.2f}, {z:.2f}]") - print(f"Estimated vehicle orientation (RPY, degrees): [{roll:.2f}, {pitch:.2f}, {yaw:.2f}]") - - # Save results - with open(args.output, 'w') as f: - f.write(f"# Global Registration Result\n") - f.write(f"# Method: {args.method}\n") - if args.method == 'both': - f.write(f"# RANSAC Fitness: {ransac_result.fitness:.6f}\n") - f.write(f"# FGR Fitness: {fgr_result.fitness:.6f}\n") - f.write(f"# Final Fitness: {max(ransac_result.fitness, fgr_result.fitness):.6f}\n") - # f.write(f"# Position: {x:.6f}, {y:.6f}, {z:.6f}\n") - # f.write(f"# Orientation (roll, pitch, yaw degrees): {roll:.6f}, {pitch:.6f}, {yaw:.6f}\n") - f.write("# Transformation matrix (4x4):\n") - np.savetxt(f, final_transformation, fmt='%.6f') - - print(f"Results saved to {args.output}") - - # Final visualization - if args.visualize: - print("Visualizing final result...") - # # First create an unscaled copy of the scan for visualization with unscaled map - # unscaled_scan = copy.deepcopy(scan_pcd) - # # Calculate the unscaled final transformation - # unscaled_final_transform = np.copy(final_transformation) - # unscaled_final_transform[:3, 3] /= args.map_scale_ratio - # draw_registration_result(unscaled_scan, map_pcd, unscaled_final_transform) - draw_registration_result(scan_down, map_down, final_transformation) - -if __name__ == "__main__": - main() diff --git a/GEMstack/offboard/calibration/lidar_to_camera.py b/GEMstack/offboard/calibration/lidar_to_camera.py deleted file mode 100644 index d45b7ab3d..000000000 --- a/GEMstack/offboard/calibration/lidar_to_camera.py +++ /dev/null @@ -1,20 +0,0 @@ -import numpy as np - -T_lidar_vehicle = np.array([[ 0.99939639, 0.02547917, 0.023615, 1.1 ], - [-0.02530848, 0.99965156, -0.00749882, 0.03773583], - [-0.02379784, 0.00689664, 0.999693, 1.95320223], - [ 0., 0., 0., 1. ]]) - -T_camera_vehicle = np.array([[-0.025131, -0.0304479, 0.99922038, 1.78251567], - [-0.99892897, 0.0396095, -0.0239167, 0.18649424], - [-0.0388504, -0.99875123, -0.03141071, 1.5399846 ], - [ 0., 0., 0., 1. ]]) - -# Invert Camera->Vehicle transformation -T_vehicle_camera = np.linalg.inv(T_camera_vehicle) - -T_lidar_camera = T_vehicle_camera @ T_lidar_vehicle - -# Print result -print("Lidar to Camera Transformation Matrix:") -print(T_lidar_camera) diff --git a/GEMstack/offboard/calibration/lidar_to_vehicle.py b/GEMstack/offboard/calibration/lidar_to_vehicle.py deleted file mode 100644 index 0978b325e..000000000 --- a/GEMstack/offboard/calibration/lidar_to_vehicle.py +++ /dev/null @@ -1,220 +0,0 @@ -#%% -import sys -import math -import numpy as np -from scipy.spatial.transform import Rotation as R -import pyvista as pv -import matplotlib.pyplot as plt -<<<<<<< HEAD -from visualizer import visualizer -======= -from tools.visualizer import visualizer ->>>>>>> 8be544d4a607faeb03c1752c8a7bdd618b6cbf69 - -VIS = False # True to show visuals -VIS = True # True to show visuals - -#%% things to extract -tx,ty,tz,rx,ry,rz = [None] * 6 - -#%%============================================================== -#======================= util functions ========================= -#================================================================ -def vis(title='', ratio=1): - print(title) - pv.set_jupyter_backend('client') - return visualizer().set_cam() -def load_scene(path): - sc = np.load(path)['arr_0'] - sc = sc[~np.all(sc == 0, axis=1)] # remove (0,0,0)'s - return sc -def crop(pc,ix=None,iy=None,iz=None): - # crop a subrectangle in a pointcloud - # usage: crop(pc, ix = (x_min,x_max), ...) - # return: array(N,3) - mask = True - for dim,intervel in zip([0,1,2],[ix,iy,iz]): - if not intervel: continue - d,u = intervel - mask &= pc[:,dim] >= d - mask &= pc[:,dim] <= u - print(f'points left after cropping {dim}\'th dim',mask.sum()) - return pc[mask] - -from sklearn.linear_model import RANSACRegressor -from sklearn.linear_model import LinearRegression -def fit_plane_ransac(pc,tol=0.01): - # fit a line/plane/hyperplane in a pointcloud - # pc: np array (N,D). the pointcloud - # tol: the tolerance. default 0.01 - model = RANSACRegressor(LinearRegression(), residual_threshold=tol) - model.fit(pc[:,:-1], pc[:,-1]) - a = model.estimator_.coef_ - inter = model.estimator_.intercept_ - class visual: - def plot(self): - inliers = pc[model.inlier_mask_] - if pc.shape[1] == 2: - plt.title('ransac fitting line') - plt.scatter(pc[:,0], pc[:,1], color='blue', marker='o', s=1) - plt.scatter(inliers[:,0], inliers[:,1], color='red', marker='o', s=1) - x_line = np.linspace(0, max(pc[:,0]), 100).reshape(-1,1) - plt.plot(x_line, x_line * a[0] + inter, color='red', label='Fitted Line') - elif pc.shape[1] == 3: - vis('ransac fitting a plane').add_pc(pc).add_pc(inliers,color='red').show() - return self - - def results(self): - # return: array(D-1), float, array(N,3) - # ^: , coeffs, intercept toward the plane, inliers of the fit - return a,inter - return visual() - -from scipy.spatial import cKDTree -def pc_diff(pc0,pc1,tol=0.1): - # remove points in pc0 from pc1 s.t. euclidian distance is within tolerance - # return: array(N,3) - tree = cKDTree(pc0) - diff = [] - for i, point in enumerate(pc1): - _, idx = tree.query(point) - distance = np.linalg.norm(point - pc0[idx]) # Compute the distance - if distance > tol: - diff.append(point) - tree = cKDTree(pc1) - for i, point in enumerate(pc0): - _, idx = tree.query(point) - distance = np.linalg.norm(point - pc1[idx]) # Compute the distance - if distance > tol: - diff.append(point) - return np.array(diff) - - - - - - -#%%============================================================== -#========================= tz rx ry ============================= -#================================================================ - -#%% load scene for ground plane -# Update depending on where data is stored -sc = load_scene('./data/lidar1.npz') - -# %% we crop to keep the ground -cropped_sc = crop(sc,iz = (-3,-2)) -if VIS: - vis('ground points cropped').add_pc(cropped_sc,color='blue').show() - -#%% -from math import sqrt -fit = fit_plane_ransac(cropped_sc,tol=0.01) # small tol because the ground is very flat -c, inter = fit.results() -normv = np.array([c[0], c[1], -1]) -normv /= np.linalg.norm(normv) -nx,ny,nz = normv -height = nz * inter -# TODO MAGIC NUMBER WARNING -height_axel = 0.2794 # 11 inches that we measured -tz = height - height_axel -if VIS: - fit.plot() -rx = -math.atan2(ny,-nz) -ry = -math.atan2(-nx,-nz) - - -if VIS: - from scipy.spatial.transform import Rotation as R - rot = R.from_euler('xyz',[rx,ry,0]).as_matrix() - cal_sc = sc @ rot.T + [0,0,tz] - vis('yz projection').add_pc(cal_sc*[0,1,1],color='blue').show() - vis('xz projection').add_pc(cal_sc*[1,0,1],color='blue').show() - -#%%============================================================== -#========================== tx ty rz ============================ -#================================================================ - -rot = R.from_euler('xyz',[rx,ry,0]).as_matrix() - -if False: # True to use the diff method to extract object. - # load data: update depending on where data is stored - sc0 = load_scene('./data/lidar70.npz') - sc1 = load_scene('./data/lidar78.npz') - - sc0 = sc0 @ rot.T + [0,0,tz] - sc1 = sc1 @ rot.T + [0,0,tz] - - # crop to only keep a frontal box area - area = (-0,7),(-1,1),(-3,1) - cropped0 = crop(sc0,*area) - cropped1 = crop(sc1,*area) - print(cropped0.shape) - print(cropped1.shape) - - # Take difference to only keep added object - objects = pc_diff(cropped0,cropped1) - -else: #False to use only cropping - # Update depending on where data is stored - sc1 = load_scene('./data/lidar1.npz') - - objects = sc1 @ rot.T + [0,0,tz] - - # crop to only keep a frontal box area - area = (-0,20),(-1,1),(0,1) - objects = crop(objects,*area) - print(objects.shape) - - -#%% -if VIS: - vis().add_pc(objects,color='blue').show() #visualize diff, hopefully the added objects - -# %% use the added objects to find rz. -# TODO after dataset retake -# right now we assume tx = ty = 0 and \ -# just use median to find a headding direction -fit = fit_plane_ransac(objects[:,:2],tol=1) # tol=1 because 1m^3 foam boxes -c,inter = fit.results() -if VIS: - fit.plot() -# tx = ty = 0 -# hx,hy = np.median(diff,axis=0)[:2] -# rz = -np.arctan2(hy,hx) -rz = - math.atan(c) -tx = 2.56 - 1.46 # https://publish.illinois.edu/robotics-autonomy-resources/gem-e4/hardware/ -ty = - inter * math.cos(rz) - -if VIS: - p1 = (0,inter,0) - p2 = max(objects[:,0])*np.array([1,c[0],0])+np.array([0,inter,0]) - vis().add_pc(sc1*np.array([1,1,0]),color='blue').add_line(p1,p2,color='red').show() - - from scipy.spatial.transform import Rotation as R - rot = R.from_euler('xyz',[0,0,rz]).as_matrix() - cal_sc1 = sc1 @ rot.T + [tx,ty,0] - vis().add_pc(cal_sc1,color='blue').show() - - -#%% visualize calibrated pointcloud -if VIS: - rot = R.from_euler('xyz',[rx,ry,rz]).as_matrix() - - cal_sc1 = sc1 @ rot.T + [tx,ty,tz] - v = vis(ratio=100) - proj = [1,1,1] - v.add_pc(cal_sc1*proj,color='blue') - v.add_box((2.56,.61*2,2.03+height_axel),[2.56/2,0,(2.03+height_axel)/2]) - v.show() - # the yellow box should be 11 inches above the ground - # rear-axel center should be at (0,0,0) -# %% -print(f""" -translation: ({tx,ty,tz}) -rotation: ({rx,ry,rz}) -""") - - - -# %% diff --git a/GEMstack/offboard/calibration/manual_fine_tune.py b/GEMstack/offboard/calibration/manual_fine_tune.py deleted file mode 100644 index 17a52d96f..000000000 --- a/GEMstack/offboard/calibration/manual_fine_tune.py +++ /dev/null @@ -1,144 +0,0 @@ -from transform3d import Transform -import cv2 -import pyvista as pv -import numpy as np - -class Scene3D: - def __init__(self,pc,T:Transform,K,img,on_key_pressed): - self.pc = pc - self.Ti = T.inv - self.img = img - self.plotter : pv.Plotter = pv.Plotter(notebook=False) - self.plotter.add_axes() - self.plotter.camera.position = (-20,0,20) - self.plotter.camera.focal_point = (0,0,0) - - self.plotter.add_mesh(pv.PolyData(pc)) - self.camera_actor = self.plotter.add_mesh(self.make_camera(K,img.shape)) - self.plotter.add_key_event('a',lambda:on_key_pressed('a')) - self.plotter.add_key_event('s',lambda:on_key_pressed('s')) - self.plotter.add_key_event('d',lambda:on_key_pressed('d')) - self.plotter.add_key_event('w',lambda:on_key_pressed('w')) - self.plotter.add_key_event('c',lambda:on_key_pressed('c')) - self.plotter.add_key_event('z',lambda:on_key_pressed('z')) - self.plotter.add_key_event('j',lambda:on_key_pressed('j')) - self.plotter.add_key_event('k',lambda:on_key_pressed('k')) - self.plotter.add_key_event('l',lambda:on_key_pressed('l')) - self.plotter.add_key_event('i',lambda:on_key_pressed('i')) - self.plotter.add_key_event('u',lambda:on_key_pressed('i')) - self.plotter.add_key_event('o',lambda:on_key_pressed('i')) - #consts - def make_camera(self,K,img_shape) -> pv.PolyData: - h,w,_ = img_shape - Ki = np.linalg.inv(K) - rec_c = pv.Rectangle((Ki@[0,0,1],Ki@[w,0,1],Ki@[0,h,1])) - o_c = pv.Sphere(0.1) - c = pv.merge((rec_c,o_c)) - return c - - #statefuls - - def show(self): - self.plotter.show(interactive_update=True) - self.camera_actor.user_matrix = self.Ti.matrix - - def stop(self): - self.plotter.close() - - def update_T(self,T): - self.Ti = T.inv - self.camera_actor.user_matrix = self.Ti.matrix - - def update_Ti(self,Ti): - self.Ti = Ti - self.camera_actor.user_matrix = self.Ti.matrix - - def loop(self): - self.plotter.update() - -class Scene2D: - def __init__(self,pc,T:Transform,K,img,on_key_pressed): - self.pc = pc - self.img = img - self.img_shape = img.shape - self.T = T - self.K = K - self.scatter = None - cv2.startWindowThread() - self.window = cv2.namedWindow("projection") - def handle_event(event): - on_key_pressed(event.key) - self.overlay = np.zeros_like(img) - #statefuls - def _update(self): - self.overlay*=0 - u,v = pc_projection(self.pc,self.T,self.K,self.img_shape) - for uu,vv in zip(u.astype(int),v.astype(int)): - cv2.circle(self.overlay, (uu, vv), radius=1, color=(0, 0, 255), thickness=-1) - display = cv2.add(self.img, self.overlay) - cv2.imshow("projection", display) - - def show(self): - self._update() - - def stop(self): - cv2.destroyAllWindows() - - def update_T(self,T): - self.T = T - self._update() - - def loop(self): - pass - -#%% -def manual_fine_tune(pc,img,T,K): - on = True - tu = 0.1 - ru = 0.1 - T = Transform(T) - def on_key_pressed(key): - nonlocal on - nonlocal T - print(key) - if key == 'c': - T @= Transform(p=(0,0,tu)) - if key == 'z': - T @= Transform(p=(0,0,-tu)) - if key == 'a': - T @= Transform(p=(-tu,0,0)) - if key == 'd': - T @= Transform(p=(tu,0,0)) - if key == 'w': - T @= Transform(p=(0,-tu,0)) - if key == 's': - T @= Transform(p=(0,tu,0)) - - if key == 'j': - T = Transform(rpy=(0,ru,0)) @ T - if key == 'l': - T = Transform(rpy=(0,-ru,0)) @ T - if key == 'i': - T = Transform(rpy=(ru,0,0)) @ T - if key == 'k': - T = Transform(rpy=(-ru,0,0)) @ T - if key == 'u': - T = Transform(rpy=(0,0,-ru)) @ T - if key == 'o': - T = Transform(rpy=(0,0,ru)) @ T - - if key == 'p': - on = False - s3d.update_T(T) - s2d.update_T(T) - - s2d = Scene2D(pc,T,K,img,on_key_pressed) - s3d = Scene3D(pc,T,K,img,on_key_pressed) - - s2d.show() - s3d.show() - while on : - s3d.loop() - s2d.loop() - s3d.stop() - s2d.stop() \ No newline at end of file diff --git a/GEMstack/offboard/calibration/output/.gitignore b/GEMstack/offboard/calibration/output/.gitignore deleted file mode 100644 index fd0c7757f..000000000 --- a/GEMstack/offboard/calibration/output/.gitignore +++ /dev/null @@ -1,4 +0,0 @@ -* - -# track just these files -!.gitignore diff --git a/GEMstack/offboard/calibration/play_with_pycolmap.py b/GEMstack/offboard/calibration/play_with_pycolmap.py deleted file mode 100644 index b19906fa1..000000000 --- a/GEMstack/offboard/calibration/play_with_pycolmap.py +++ /dev/null @@ -1,161 +0,0 @@ -#%% -root = '/mnt/GEMstack' -#%% -import numpy as np -import pycolmap -import open3d as o3d -from pathlib import Path -from scipy.spatial.transform import Rotation as R -from GEMstack.GEMstack.knowledge.calibration.calib_util import load_ex, save_ex, load_in, save_in -from tools.visualizer import visualizer as vis - -def pc_relative(pc0,pc1): - #get relative translation and rotation from pc0 to pc1 - #in: Nx3 array, Nx3 array - #out: 3 array, 3 array - # Load point clouds - source = o3d.geometry.PointCloud() - source.points = o3d.utility.Vector3dVector(pc0) - target = o3d.geometry.PointCloud() - target.points = o3d.utility.Vector3dVector(pc1) - - # Run ICP - reg_result = o3d.pipelines.registration.registration_icp( - source, target, max_distance=0.1, - estimation_method=o3d.pipelines.registration.TransformationEstimationPointToPoint() - ) - print("Transformation Matrix:\n", reg_result.transformation) - return(reg_result.transformation) - -#%% -img_dir = root + "/data/calib1/img" -# img_dir = root + "/data/test" -output_dir = root + '/GEMstack/offboard/calibration/output' -output_path = Path(output_dir) -output_path.mkdir(exist_ok=True, parents=True) - -# 1. Feature extraction. google 'sift' to know what it does. -extract_options = pycolmap.SiftExtractionOptions() -extract_options.num_threads = 2 -pycolmap.extract_features( - database_path=output_path/"database.db", - image_path=img_dir, - camera_mode=pycolmap.CameraMode.PER_FOLDER, - sift_options=extract_options, - # device=pycolmap._core.Device.cuda -) -# 2. Feature matching. match_sequential tries matching only on pairs close in filename ordering -match_options = pycolmap.SequentialMatchingOptions() -match_options.overlap = 3 # how many subsequent images should be tried matching. - # 3 is too small actually. do larger if you figured out pycolmap+cuda -pycolmap.match_sequential( - database_path=output_path/"database.db", - matching_options=match_options -) - -# vocabtree matching. alternative to sequantial matching. -# requires a vocab tree from https://demuc.de/colmap/ -# match_options = pycolmap.VocabTreeMatchingOptions() -# match_options.vocab_tree_path = "/mnt/GEMstack/GEMstack/offboard/calibration/output/vocab_tree_flickr100K_words32K.bin" -# pycolmap.match_vocabtree( -# database_path=output_path/"database.db", -# matching_options=match_options -# ) - -# 3. Sparse reconstruction. ba_refine = 0 so it don't mess with the intrinsics we got in feature extraction stage. -mapper_options = pycolmap.IncrementalPipelineOptions() -mapper_options.ba_refine_focal_length = 0 -mapper_options.ba_refine_principal_point = 0 -mapper_options.ba_refine_extra_params = 0 -reconstructions = pycolmap.incremental_mapping( - database_path=output_path/"database.db", - image_path=img_dir, - output_path=output_path, - options=mapper_options -) - -#%% -#%% -# this part tries 3d reconstruction with stereo depth given the images registered in the previous part. -# but patch_match_stereo needs cuda and compiling pycolmap from source so haven't managed to run it. - -# dense_dir = output_path -# dense_dir.mkdir(exist_ok=True) - -# pycolmap.patch_match_stereo( -# input_path=output_path, -# output_path=dense_dir, -# output_type="TXT", -# ) - -# pycolmap.stereo_fusion( -# output_path=dense_dir, -# workspace_path=dense_dir, -# workspace_format="COLMAP", -# max_image_size=2000, -# gpu_index="0", -# ) - -# 4. Depth Map Fusion (Global Registration) -# fused_pc = pycolmap.dense_fusion( -# workspace_path=dense_dir, -# output_path=dense_dir/"fused.ply", -# max_image_size=2000, -# gpu_index="0", -# ) - -#%% -#%% -# get correspondence between image registrations and filenames, -# and find image142 is from oak -[(id,reconstructions[0].image(id).name) for id in reconstructions[0].reg_image_ids()] - -#%% -#make a copy because I was in jupyter lab trying to test different stuff with it -rec = reconstructions[0].__copy__() - -#%% -# anchor the coordination system to image #142 -# because I found #142 is the first registered images from the front camera -trans = rec.image(142).cam_from_world -rec.transform(pycolmap.Sim3d(rotation=trans.rotation,translation=trans.translation)) -print(rec.image(142).viewing_direction()) # shoud be a trivial direction - -#%% -#%% -pc = np.array([p.xyz for p in rec.points3D.values()]) -################################################################################## -#so far we have got pointcloud reconstructed from camera images -################################################################################# -# tranform to vehicle coordination just for visualization -camera_ex = load_ex(root + "/GEMstack/knowledge/calibration/gem_e4_oak.yaml",mode='matrix') -pc = np.pad(pc,((0,0),(0,1)),constant_values=1) @ camera_ex.T[:,:3] - -#%% -def load_scene(path): - sc = np.load(path)['arr_0'] - sc = sc[~np.all(sc == 0, axis=1)] # remove (0,0,0)'s - return sc - -#%% -# get lidar pointcloud -sc = load_scene(root + f"/data/calib1/pc/ouster1.npz") -lidar_ex = load_ex(root + "/GEMstack/knowledge/calibration/gem_e4_ouster.yaml",mode='matrix') -sc = np.pad(sc,((0,0),(0,1)),constant_values=1) @ lidar_ex.T[:,:3] - -#%% -pc = np.array([p.xyz for p in rec.points3D.values()]) -#%% -#import os -#os.environ['DISPLAY'] = ':0' -#%% -v = vis() -v.add_pc(pc,color='red') -v.add_pc(sc,color='blue') -v.show() -v.close() - - - -# %% -pc.shape \ No newline at end of file diff --git a/GEMstack/offboard/calibration/run_img2pc.bash b/GEMstack/offboard/calibration/run_img2pc.bash deleted file mode 100644 index 116d02291..000000000 --- a/GEMstack/offboard/calibration/run_img2pc.bash +++ /dev/null @@ -1,9 +0,0 @@ -root='/mnt/GEMstack' - -python3 $root/GEMstack/offboard/calibration/img2pc.py \ - --img_path $root/data/calib1/img/fl/fl16.png \ - --pc_path $root/data/calib1/pc/ouster16.npz \ - --pc_transform_path $root/GEMstack/knowledge/calibration/gem_e4_ouster.yaml \ - --img_intrinsics_path $root/GEMstack/knowledge/calibration/gem_e4_oak_in.yaml \ - --n_features 4 \ - --out_path $root/GEMstack/knowledge/calibration/gem_e4_oak.yaml \ No newline at end of file diff --git a/GEMstack/offboard/calibration/tools/.gitignore b/GEMstack/offboard/calibration/tools/.gitignore deleted file mode 100644 index c20c2ab73..000000000 --- a/GEMstack/offboard/calibration/tools/.gitignore +++ /dev/null @@ -1,2 +0,0 @@ -__pycache__ - diff --git a/GEMstack/offboard/calibration/tools/__init__.py b/GEMstack/offboard/calibration/tools/__init__.py deleted file mode 100644 index e69de29bb..000000000 diff --git a/GEMstack/offboard/calibration/tools/visualizer.py b/GEMstack/offboard/calibration/tools/visualizer.py deleted file mode 100644 index 2139a020c..000000000 --- a/GEMstack/offboard/calibration/tools/visualizer.py +++ /dev/null @@ -1,42 +0,0 @@ -import pyvista as pv -class visualizer: - def __init__(self): - self.plotter = pv.Plotter(notebook=False) - self.plotter.show_axes() - - def set_cam(self, pos=(-20, 0, 20), foc=(0, 0, 0)): - self.plotter.camera.position = pos - self.plotter.camera.focal_point = foc - return self - - def add_pc(self, pc, **kargs): - self.plotter.add_mesh( - pv.PolyData(pc), - render_points_as_spheres=True, - point_size=2, - **kargs - ) - return self - - def add_line(self, p1, p2, **kargs): - self.plotter.add_mesh( - pv.Line(p1 , p2), - **kargs, - line_width=1 - ) - return self - - def add_box(self, bound, trans, ratio=1): - l, w, h = map(lambda x: x * ratio, bound) - box = pv.Box(bounds=(-l/2, l/2, -w/2, w/2, -h/2, h/2)) - box = box.translate(list(map(lambda x: x * ratio, trans))) - self.plotter.add_mesh(box, color='yellow') - return self - - def show(self): - self.plotter.show() - return self - - def close(self): - self.plotter.close() - return None From e849ebb6856c54e0a8f0b3c0f5c0983bb7b30a1e Mon Sep 17 00:00:00 2001 From: michalj1 Date: Mon, 5 May 2025 10:06:03 -0500 Subject: [PATCH 226/232] Organize calibration file --- .gitignore | 11 ----------- GEMstack/knowledge/calibration/gem_e4.yaml | 16 +++++++++++++++- 2 files changed, 15 insertions(+), 12 deletions(-) diff --git a/.gitignore b/.gitignore index 2ee751866..0c36d682f 100644 --- a/.gitignore +++ b/.gitignore @@ -165,14 +165,3 @@ cython_debug/ # and can be added to the global gitignore or merged into this file. For a more nuclear # option (not recommended) you can uncomment the following to ignore the entire idea folder. #.idea/ -GEMstack/offboard/calibration/calibration_by_segmentation/init_proj_seg.png -GEMstack/offboard/calibration/calibration_by_segmentation/init_proj.png -.gitignore -.gitignore -GEMstack/offboard/calibration/calibration_by_segmentation/refined_proj_seg.png -GEMstack/offboard/calibration/calibration_by_segmentation/refined_proj.png -GEMstack/offboard/calibration/calibration_by_segmentation/extrinsic.txt - -repo/ -GEMstack/offboard/calibration/data/ -GEMstack/offboard/calibration/global_registration_result.txt diff --git a/GEMstack/knowledge/calibration/gem_e4.yaml b/GEMstack/knowledge/calibration/gem_e4.yaml index d0954dc06..aed13aff4 100644 --- a/GEMstack/knowledge/calibration/gem_e4.yaml +++ b/GEMstack/knowledge/calibration/gem_e4.yaml @@ -4,4 +4,18 @@ rear_axle_height: 0.33 # height of rear axle center above flat ground gnss_location: [1.10,0,1.62] # meters, taken from https://github.com/hangcui1201/POLARIS_GEM_e2_Real/blob/main/vehicle_drivers/gem_gnss_control/scripts/gem_gnss_tracker_stanley_rtk.py. Note conflict with pure pursuit location? gnss_yaw: 0.0 # radians top_lidar: !include "gem_e4_ouster.yaml" -front_camera: !include "gem_e4_oak.yaml" +front_camera: +- !include "gem_e4_oak.yaml" +- !include "gem_e4_oak_in.yaml" +front_right_camera: +- !include "gem_e4_fr.yaml" +- !include "gem_e4_fr_in.yaml" +front_left_camera: +- !include "gem_e4_fl.yaml" +- !include "gem_e4_fl_in.yaml" +rear_right_camera: +- !include "gem_e4_rr.yaml" +- !include "gem_e4_rr_in.yaml" +rear_left_camera: +- !include "gem_e4_rl.yaml" +- !include "gem_e4_rl_in.yaml" From fa7bdbf142f7d08a040cf5e4881309b66beda666 Mon Sep 17 00:00:00 2001 From: michalj1 Date: Mon, 5 May 2025 10:22:08 -0500 Subject: [PATCH 227/232] Update README --- GEMstack/knowledge/calibration/gem_e4_oak_finetuned_new.yaml | 5 ----- GEMstack/knowledge/calibration/gem_e4_oak_new.yaml | 5 ----- GEMstack/offboard/calibration/README.md | 2 ++ 3 files changed, 2 insertions(+), 10 deletions(-) delete mode 100644 GEMstack/knowledge/calibration/gem_e4_oak_finetuned_new.yaml delete mode 100644 GEMstack/knowledge/calibration/gem_e4_oak_new.yaml diff --git a/GEMstack/knowledge/calibration/gem_e4_oak_finetuned_new.yaml b/GEMstack/knowledge/calibration/gem_e4_oak_finetuned_new.yaml deleted file mode 100644 index 57dcc8fbd..000000000 --- a/GEMstack/knowledge/calibration/gem_e4_oak_finetuned_new.yaml +++ /dev/null @@ -1,5 +0,0 @@ -position: [1.9564719286254562, -0.016357857507817864, 2.0489178127802745] -reference: rear_axle_center -rotation: [[0.02777285065736978, -0.1147911851051555, 0.9930013356428667], [-0.9996095786617777, - -0.00014910886738464478, 0.027940436900108796], [-0.0030592505596502726, -0.9933896323138769, - -0.11475050935535633]] \ No newline at end of file diff --git a/GEMstack/knowledge/calibration/gem_e4_oak_new.yaml b/GEMstack/knowledge/calibration/gem_e4_oak_new.yaml deleted file mode 100644 index 0d78c35d7..000000000 --- a/GEMstack/knowledge/calibration/gem_e4_oak_new.yaml +++ /dev/null @@ -1,5 +0,0 @@ -position: [2.0808976903925527, 0.0046454831123376285, 2.2564570873915066] -reference: rear_axle_center -rotation: [[0.03012359754389654, -0.16959859553080173, 0.9850527322255357], [-0.9995391306089103, - -0.0014095974215514596, 0.03032390833472774], [-0.003754364473137365, -0.9855122167832769, - -0.16956289487477566]] diff --git a/GEMstack/offboard/calibration/README.md b/GEMstack/offboard/calibration/README.md index 79dee6fd3..e16eea130 100644 --- a/GEMstack/offboard/calibration/README.md +++ b/GEMstack/offboard/calibration/README.md @@ -28,6 +28,8 @@ The `undistort_images.py` script can then be used to rectify a set of images usi **Extrinsic Calibration** +These scripts use a package within another folder in GEMstack: as such, you may need to add GEMstack to your python path. On Linux, this can be done by running `export PYTHON_LIB=<$PATH_TO_GEMSTACK>:PYTHON_LIB`, replacing `<$PATH_TO_GEMSTACK>` with the absolute path to the main GEMstack directory. + The `img2pc.py` file contains the main part of the extrinsic calibration process. Select a synchronized camera image and lidar pointcloud to align, ideally containing features that are easy to detect in both, such as boards or signs with corners. Alignment can be done with 4 feature pairs(must be coplanar) or 6+ points. The first screen will ask you to select points on the image, and will close on its own once *n_features* points are selected. The second screen will ask you to select points in the point cloud, and will need to be closed manually once exactly *n_features* points are selected, or it will prompt you again. The extrinsic matrices will then be displayed, and if an *out_path* is provided they will also be saved. The `test_transforms.py` file can then be used to manually fine-tune the calculated intrinsics. Use the sliders to change the translation and rotation to project the lidar points onto the image more accurately. From b071e38c82da7f4fce7e1e52e1a2ab4cd39638f3 Mon Sep 17 00:00:00 2001 From: michalj1 Date: Mon, 5 May 2025 10:22:32 -0500 Subject: [PATCH 228/232] Update README --- GEMstack/offboard/calibration/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/GEMstack/offboard/calibration/README.md b/GEMstack/offboard/calibration/README.md index e16eea130..10b81907e 100644 --- a/GEMstack/offboard/calibration/README.md +++ b/GEMstack/offboard/calibration/README.md @@ -28,7 +28,7 @@ The `undistort_images.py` script can then be used to rectify a set of images usi **Extrinsic Calibration** -These scripts use a package within another folder in GEMstack: as such, you may need to add GEMstack to your python path. On Linux, this can be done by running `export PYTHON_LIB=<$PATH_TO_GEMSTACK>:PYTHON_LIB`, replacing `<$PATH_TO_GEMSTACK>` with the absolute path to the main GEMstack directory. +These scripts use a package within another folder in GEMstack: as such, you may need to add GEMstack to your python path. On Linux, this can be done by running `export PYTHONPATH=<$PATH_TO_GEMSTACK>:PYTHONPATH`, replacing `<$PATH_TO_GEMSTACK>` with the absolute path to the main GEMstack directory. The `img2pc.py` file contains the main part of the extrinsic calibration process. Select a synchronized camera image and lidar pointcloud to align, ideally containing features that are easy to detect in both, such as boards or signs with corners. Alignment can be done with 4 feature pairs(must be coplanar) or 6+ points. The first screen will ask you to select points on the image, and will close on its own once *n_features* points are selected. The second screen will ask you to select points in the point cloud, and will need to be closed manually once exactly *n_features* points are selected, or it will prompt you again. The extrinsic matrices will then be displayed, and if an *out_path* is provided they will also be saved. From c07d0427fbbe3454fe22ac034c4107d0e0a4b6a7 Mon Sep 17 00:00:00 2001 From: michalj1 Date: Tue, 13 May 2025 19:16:24 -0500 Subject: [PATCH 229/232] Include updated lidar calibration from homework --- GEMstack/knowledge/calibration/gem_e4_ouster.yaml | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/GEMstack/knowledge/calibration/gem_e4_ouster.yaml b/GEMstack/knowledge/calibration/gem_e4_ouster.yaml index 5987373a6..47897f62a 100644 --- a/GEMstack/knowledge/calibration/gem_e4_ouster.yaml +++ b/GEMstack/knowledge/calibration/gem_e4_ouster.yaml @@ -1,3 +1,5 @@ reference: rear_axle_center # rear axle center -position: [1.10,0,2.03] # meters, calibrated by Hang's watchful eye -rotation: [[1,0,0],[0,1,0],[0,0,1]] #rotation matrix mapping lidar frame to vehicle frame \ No newline at end of file +position: [1.10, 0.03773583, 1.95320223] # meters, calibrated by Hang's watchful eye +rotation: [[0.99939639, 0.02547917, 0.023615], + [-0.02530848, 0.99965156, -0.00749882], + [-0.02379784, 0.00689664, 0.999693]] #rotation matrix mapping lidar frame to vehicle frame \ No newline at end of file From 2292ef45e24d9a0e94b72bc6189e1d2e47908c6b Mon Sep 17 00:00:00 2001 From: Michal Juscinski Date: Tue, 13 May 2025 23:02:34 -0700 Subject: [PATCH 230/232] Change format to use text keys instead of lists --- GEMstack/knowledge/calibration/gem_e4.yaml | 20 ++++++++++---------- 1 file changed, 10 insertions(+), 10 deletions(-) diff --git a/GEMstack/knowledge/calibration/gem_e4.yaml b/GEMstack/knowledge/calibration/gem_e4.yaml index aed13aff4..ef1f4f30e 100644 --- a/GEMstack/knowledge/calibration/gem_e4.yaml +++ b/GEMstack/knowledge/calibration/gem_e4.yaml @@ -5,17 +5,17 @@ gnss_location: [1.10,0,1.62] # meters, taken from https://github.com/hangcui1201 gnss_yaw: 0.0 # radians top_lidar: !include "gem_e4_ouster.yaml" front_camera: -- !include "gem_e4_oak.yaml" -- !include "gem_e4_oak_in.yaml" + extrinsics: !include "gem_e4_oak.yaml" + intrinsics: !include "gem_e4_oak_in.yaml" front_right_camera: -- !include "gem_e4_fr.yaml" -- !include "gem_e4_fr_in.yaml" + extrinsics: !include "gem_e4_fr.yaml" + intrinsics: !include "gem_e4_fr_in.yaml" front_left_camera: -- !include "gem_e4_fl.yaml" -- !include "gem_e4_fl_in.yaml" + extrinsics: !include "gem_e4_fl.yaml" + intrinsics: !include "gem_e4_fl_in.yaml" rear_right_camera: -- !include "gem_e4_rr.yaml" -- !include "gem_e4_rr_in.yaml" + extrinsics: !include "gem_e4_rr.yaml" + intrinsics: !include "gem_e4_rr_in.yaml" rear_left_camera: -- !include "gem_e4_rl.yaml" -- !include "gem_e4_rl_in.yaml" + extrinsics: !include "gem_e4_rl.yaml" + intrinsics: !include "gem_e4_rl_in.yaml" From 7aaa606fcc3ad9d9445a2e5787637f366f052b9d Mon Sep 17 00:00:00 2001 From: Michal Juscinski Date: Tue, 13 May 2025 23:03:15 -0700 Subject: [PATCH 231/232] Add helper script to create cameras.yaml for perception --- .../calibration/make_camera_lidar_yaml.py | 48 +++++++++++++++++ .../knowledge/calibration/new_cameras.yaml | 54 +++++++++++++++++++ 2 files changed, 102 insertions(+) create mode 100755 GEMstack/knowledge/calibration/make_camera_lidar_yaml.py create mode 100644 GEMstack/knowledge/calibration/new_cameras.yaml diff --git a/GEMstack/knowledge/calibration/make_camera_lidar_yaml.py b/GEMstack/knowledge/calibration/make_camera_lidar_yaml.py new file mode 100755 index 000000000..6f1c71d55 --- /dev/null +++ b/GEMstack/knowledge/calibration/make_camera_lidar_yaml.py @@ -0,0 +1,48 @@ +import yaml +import numpy as np +from calib_util import load_ex, load_in + +# +# THIS FILE SHOULD BE RUN FROM ITS LOCAL DIRECTORY FOR THE PATHS TO WORK +# + +# Destination files name +output_file = 'new_cameras.yaml' + +# Collect names of all sensors and associated extrinsic/intrinsic files +camera_files = {'front': ['gem_e4_oak.yaml', 'gem_e4_oak_in.yaml'], + 'front_right': ['gem_e4_fr.yaml', 'gem_e4_oak_in.yaml'], + 'front_left': ['gem_e4_fl.yaml', 'gem_e4_fl_in.yaml'], + 'back_right': ['gem_e4_rr.yaml', 'gem_e4_rr_in.yaml'], + 'back_left': ['gem_e4_rl.yaml', 'gem_e4_rl_in.yaml']} +lidar_file = 'gem_e4_ouster.yaml' + +# Initialize variables +output_dict = {'cameras': {}} +T_lidar_to_vehicle = load_ex(lidar_file, 'matrix') + +# Collect data for all cameras +for camera in camera_files: + # Load from files + ex_file = camera_files[camera][0] + in_file = camera_files[camera][1] + T_camera_to_vehicle = load_ex(ex_file, 'matrix') + K, D = load_in(in_file, 'matrix', return_distort=True) + + # Calculate necessary values + T_lidar_to_camera = np.linalg.inv(T_camera_to_vehicle) @ T_lidar_to_vehicle + + # Store in the proper format + camera_dict = {} + camera_dict['K'] = K + camera_dict['D'] = D + camera_dict['T_l2c'] = T_lidar_to_camera + camera_dict['T_l2v'] = T_lidar_to_vehicle + for key in camera_dict: + if type(camera_dict[key]) == np.ndarray: + camera_dict[key] = camera_dict[key].tolist() + output_dict['cameras'][camera] = camera_dict + +# Write to file +with open(output_file,'w') as stream: + yaml.safe_dump(output_dict, stream) \ No newline at end of file diff --git a/GEMstack/knowledge/calibration/new_cameras.yaml b/GEMstack/knowledge/calibration/new_cameras.yaml new file mode 100644 index 000000000..5af63ffc7 --- /dev/null +++ b/GEMstack/knowledge/calibration/new_cameras.yaml @@ -0,0 +1,54 @@ +cameras: + back_left: + D: [-0.2522996862206216, 0.12482113115174773, -0.0005993692936397102, -0.00017949453391219192, + -0.03499498178003368] + K: [[1181.6177321982138, 0.0, 953.302889408274], [0.0, 1180.0783789769903, 608.1966398872765], + [0.0, 0.0, 1.0]] + T_l2c: [[0.6847850928670114, 0.7280268943837436, 0.03234528777238468, 0.17880325315750822], + [0.19803293816635603, -0.14318896257364072, -0.9696802959729997, -0.00709827567190402], + [-0.7013218462220598, 0.6704280439025839, -0.2422269719924622, -1.2677840886549123], + [0.0, 0.0, 0.0, 1.0]] + T_l2v: [[1.0, 0.0, 0.0, 1.1], [0.0, 1.0, 0.0, 0.0], [0.0, 0.0, 1.0, 2.03], [0.0, + 0.0, 0.0, 1.0]] + back_right: + D: [-0.25040910859151444, 0.1109210921906881, -0.00041247665414900384, 0.0008205455176671751, + -0.026395952816984845] + K: [[1162.3787554048329, 0.0, 956.2663906909728], [0.0, 1162.855381183851, 569.2039945552984], + [0.0, 0.0, 1.0]] + T_l2c: [[-0.7359657309159464, 0.6768157805459534, -0.016578363047300274, -0.26405025731519305], + [0.1598619141442639, 0.14993386619459945, -0.9756864271752845, -0.050075615562659825], + [-0.6578743127098728, -0.7207220233709472, -0.21854325362408258, -1.215243265562286], + [0.0, 0.0, 0.0, 1.0]] + T_l2v: [[1.0, 0.0, 0.0, 1.1], [0.0, 1.0, 0.0, 0.0], [0.0, 0.0, 1.0, 2.03], [0.0, + 0.0, 0.0, 1.0]] + front: + D: [0, 0, 0, 0, 0] + K: [[684.8333129882812, 0.0, 573.37109375], [0.0, 684.6096801757812, 363.700927734375], + [0.0, 0.0, 1.0]] + T_l2c: [[0.020064651878799866, -0.9997929081548386, -0.0033986097560439466, 0.018143199324486804], + [-0.013111205776053955, 0.003135878549941185, -0.9999091271454708, -0.365411601947232], + [0.9997127117467701, 0.02010738841847249, -0.013045570240818816, -0.7734450616622106], + [0.0, 0.0, 0.0, 1.0]] + T_l2v: [[1.0, 0.0, 0.0, 1.1], [0.0, 1.0, 0.0, 0.0], [0.0, 0.0, 1.0, 2.03], [0.0, + 0.0, 0.0, 1.0]] + front_left: + D: [-0.2625420437513607, 0.1425651774165483, -0.0004946279626072071, -0.00033457504102070386, + -0.042732740327368145] + K: [[1183.2337731693713, 0.0, 971.5122150421694], [0.0, 1182.3831532373445, 601.7847095069886], + [0.0, 0.0, 1.0]] + T_l2c: [[0.7229102844527424, -0.6904150547378917, 0.026977264941612063, 0.01257665857972412], + [-0.13938889438297952, -0.18396833469067195, -0.9729986577348558, 0.0033662620482308725], + [0.6767358840457229, 0.6996304053015528, -0.22922879230680993, -1.355203063833986], + [0.0, 0.0, 0.0, 1.0]] + T_l2v: [[1.0, 0.0, 0.0, 1.1], [0.0, 1.0, 0.0, 0.0], [0.0, 0.0, 1.0, 2.03], [0.0, + 0.0, 0.0, 1.0]] + front_right: + D: [0, 0, 0, 0, 0] + K: [[684.8333129882812, 0.0, 573.37109375], [0.0, 684.6096801757812, 363.700927734375], + [0.0, 0.0, 1.0]] + T_l2c: [[-0.7168464770690617, -0.6970911725372961, -0.013965152496600495, 0.019552675988915413], + [-0.1004601820857898, 0.12308618950445345, -0.987298101775023, -0.1720739924899677], + [0.6899557088168526, -0.7063382243117331, -0.15826380744561552, -1.1441700433020388], + [0.0, 0.0, 0.0, 1.0]] + T_l2v: [[1.0, 0.0, 0.0, 1.1], [0.0, 1.0, 0.0, 0.0], [0.0, 0.0, 1.0, 2.03], [0.0, + 0.0, 0.0, 1.0]] From 991e77e0660429ee2a342baa469cd6fca137edc0 Mon Sep 17 00:00:00 2001 From: Michal Juscinski Date: Wed, 14 May 2025 19:58:49 -0500 Subject: [PATCH 232/232] Remove cameras yaml, allowing other teams to run script as needed --- .../calibration/make_camera_lidar_yaml.py | 2 +- .../knowledge/calibration/new_cameras.yaml | 54 ------------------- 2 files changed, 1 insertion(+), 55 deletions(-) delete mode 100644 GEMstack/knowledge/calibration/new_cameras.yaml diff --git a/GEMstack/knowledge/calibration/make_camera_lidar_yaml.py b/GEMstack/knowledge/calibration/make_camera_lidar_yaml.py index 6f1c71d55..ba3b098b4 100755 --- a/GEMstack/knowledge/calibration/make_camera_lidar_yaml.py +++ b/GEMstack/knowledge/calibration/make_camera_lidar_yaml.py @@ -7,7 +7,7 @@ # # Destination files name -output_file = 'new_cameras.yaml' +output_file = 'gem_e4_perception_cameras.yaml' # Collect names of all sensors and associated extrinsic/intrinsic files camera_files = {'front': ['gem_e4_oak.yaml', 'gem_e4_oak_in.yaml'], diff --git a/GEMstack/knowledge/calibration/new_cameras.yaml b/GEMstack/knowledge/calibration/new_cameras.yaml deleted file mode 100644 index 5af63ffc7..000000000 --- a/GEMstack/knowledge/calibration/new_cameras.yaml +++ /dev/null @@ -1,54 +0,0 @@ -cameras: - back_left: - D: [-0.2522996862206216, 0.12482113115174773, -0.0005993692936397102, -0.00017949453391219192, - -0.03499498178003368] - K: [[1181.6177321982138, 0.0, 953.302889408274], [0.0, 1180.0783789769903, 608.1966398872765], - [0.0, 0.0, 1.0]] - T_l2c: [[0.6847850928670114, 0.7280268943837436, 0.03234528777238468, 0.17880325315750822], - [0.19803293816635603, -0.14318896257364072, -0.9696802959729997, -0.00709827567190402], - [-0.7013218462220598, 0.6704280439025839, -0.2422269719924622, -1.2677840886549123], - [0.0, 0.0, 0.0, 1.0]] - T_l2v: [[1.0, 0.0, 0.0, 1.1], [0.0, 1.0, 0.0, 0.0], [0.0, 0.0, 1.0, 2.03], [0.0, - 0.0, 0.0, 1.0]] - back_right: - D: [-0.25040910859151444, 0.1109210921906881, -0.00041247665414900384, 0.0008205455176671751, - -0.026395952816984845] - K: [[1162.3787554048329, 0.0, 956.2663906909728], [0.0, 1162.855381183851, 569.2039945552984], - [0.0, 0.0, 1.0]] - T_l2c: [[-0.7359657309159464, 0.6768157805459534, -0.016578363047300274, -0.26405025731519305], - [0.1598619141442639, 0.14993386619459945, -0.9756864271752845, -0.050075615562659825], - [-0.6578743127098728, -0.7207220233709472, -0.21854325362408258, -1.215243265562286], - [0.0, 0.0, 0.0, 1.0]] - T_l2v: [[1.0, 0.0, 0.0, 1.1], [0.0, 1.0, 0.0, 0.0], [0.0, 0.0, 1.0, 2.03], [0.0, - 0.0, 0.0, 1.0]] - front: - D: [0, 0, 0, 0, 0] - K: [[684.8333129882812, 0.0, 573.37109375], [0.0, 684.6096801757812, 363.700927734375], - [0.0, 0.0, 1.0]] - T_l2c: [[0.020064651878799866, -0.9997929081548386, -0.0033986097560439466, 0.018143199324486804], - [-0.013111205776053955, 0.003135878549941185, -0.9999091271454708, -0.365411601947232], - [0.9997127117467701, 0.02010738841847249, -0.013045570240818816, -0.7734450616622106], - [0.0, 0.0, 0.0, 1.0]] - T_l2v: [[1.0, 0.0, 0.0, 1.1], [0.0, 1.0, 0.0, 0.0], [0.0, 0.0, 1.0, 2.03], [0.0, - 0.0, 0.0, 1.0]] - front_left: - D: [-0.2625420437513607, 0.1425651774165483, -0.0004946279626072071, -0.00033457504102070386, - -0.042732740327368145] - K: [[1183.2337731693713, 0.0, 971.5122150421694], [0.0, 1182.3831532373445, 601.7847095069886], - [0.0, 0.0, 1.0]] - T_l2c: [[0.7229102844527424, -0.6904150547378917, 0.026977264941612063, 0.01257665857972412], - [-0.13938889438297952, -0.18396833469067195, -0.9729986577348558, 0.0033662620482308725], - [0.6767358840457229, 0.6996304053015528, -0.22922879230680993, -1.355203063833986], - [0.0, 0.0, 0.0, 1.0]] - T_l2v: [[1.0, 0.0, 0.0, 1.1], [0.0, 1.0, 0.0, 0.0], [0.0, 0.0, 1.0, 2.03], [0.0, - 0.0, 0.0, 1.0]] - front_right: - D: [0, 0, 0, 0, 0] - K: [[684.8333129882812, 0.0, 573.37109375], [0.0, 684.6096801757812, 363.700927734375], - [0.0, 0.0, 1.0]] - T_l2c: [[-0.7168464770690617, -0.6970911725372961, -0.013965152496600495, 0.019552675988915413], - [-0.1004601820857898, 0.12308618950445345, -0.987298101775023, -0.1720739924899677], - [0.6899557088168526, -0.7063382243117331, -0.15826380744561552, -1.1441700433020388], - [0.0, 0.0, 0.0, 1.0]] - T_l2v: [[1.0, 0.0, 0.0, 1.1], [0.0, 1.0, 0.0, 0.0], [0.0, 0.0, 1.0, 2.03], [0.0, - 0.0, 0.0, 1.0]]

_yd1#3dT2Xzah8}VXJ!FFjt7y=D5QBXXddMmCkgK63Mo72Aaj@e^ zA2f)t8zA#_EeZth$w*ftJL@blLb@FgqKBM857}{0c8ZRJvb%GcFS|P&hwcZVhwK=o z7IH8|C^tO^p@*D757{CD1~c^M#vOy57Ud(*i-2p)kLJv8E9&!;{VuY+kfe=09 z40^~0L9}`?^JRAj1n-MN4>^M#auHf$gseq@AP1p`oIwxSAc$5kX1?t1fFK8=*Lr$TGY!D%X znfbE21A-ic9&!pjvIl8T611g5#=JSe1PB zfgW-OJ!DgTVuU>3K@3(n=pkp&LpBJGt6pJs^(z_ZA!pD-HdQo6$a5;h;93-V$QksI z4T9sU7pt~*34dP{ddL~{kWDv;5ppLLF}N0m9&!dfWP{+i>V?dw9y0H80wH?H8T62C zSBnsGCl!c!ea9x(e|Tti!x~>Yggm3qIj%hIbA3>r%H`(ypqrIiVua4n-;;qJat1wQ ziwI`Lvmj6V5QBXXddL~{kloo;OL*krdGl8gddL~{kPRaA;?(2}$OaK+3A0k3_8|td9eT(a^pIV)t0hKg=KDSfJ!EJ!++q-6wv%1* zv=3L1tc4zO20diQTD8OoWw5Ud&_m9khinibYgr}aX&+*+`almkg&wl2K5B^(T8aEx z6ne-h^pFiAtUj!E^0W^zSVf_SoI(%TRZ+FX2(75T4?+()g&wj&gjJMPTb}kI2KylN zkW=U(yKbPC7@?iPcO2*;^ZB4bgx!GMN1pZ}2K%5q?Q>mCEipnnT%8_r20i4G87^<3 zI1b8tYi`%4OsmsF&Y*|v5NaU@>k#-Y@5~?*MGrZH9&!VOdJ(PsuhT=$#?Icfq($DX zbF-57;oPj`eK^Eu(|1{Nalh@bV(RK*sDf(dtD$%KLCYurfdoIfEW@8Cqh5yuAYicd5`r&Y*|vDua$iw0e<`@;)38tPIdY z&Y*|vc&?ThA#d*h!4)#}kW=U(8wAHyFY-~|hXaC@0eZ+O^pG9T)e^S%vg5g0VuZZC0}gTx2R-BzddLRBan*}_l=tDJGC&VG zg&uMdT4IE}y#oYS$nplAs|-38(dvcF*EhbUGRWIIWKo?ZM#$Scf{=Ia41#ER58bVh zHMXCXyh(0m6(i)`bDUk)MCc)>&_gyy&RMCKy&gQf&_hn4hiuMnjF30}yH0Jq2Qr zQP4w9p@(b`99O+UHv4`KJ>(R6$cE=JLcSzH3|0o{A!pD-HVBTZUSU=8)dzaW8T61% z^@$PkMGRuF!a)x?gC4R$a9s5YtE;b~&_m9khis~7jF2yT5QCK(ddL~{kPU+4su!!a zb_w4Npog4657~5s7$NVTBZlZ9XV6172#%{>$o#tA^M#vh8XSLf$<`jNMv{ zO@40ED!cgZy&OWmYIJ>2zK?Q!P`+aVBKV@p%}OntNr=!H`Xh%Pat1wQiwI`LvmjqS z$=QV-at1wQcXrhh9(j1){0bR*$QksI4I=d7)s*j}5QA9)J>(2}$SzCN5+gKYd?rE< zIfWjwL4;Yttd#Gg5QEtcJ>(R6$S&K}5+gM8eIJA#atb|Ug9x*o?2_-J5QD6R9&!pj z=_O62<>^pI2NAsa+k zeOT?}`zXXu zqq`HLEa5TV@k9E2Wn3O!_t00-5JnJ-^tBL;V=&_hn4hwK=o7IH8| zC^vl-g&uMWJ!FI6xa!5sm+yoTgKrK%4>^S%vSXB5VuW(ja}avSDfEyHBIGtRU%nGY z3~~^9$SL%Y9i!9|Bb1w-gU~}xp@(b`A-9?N@|`eZkb}@ePN9eFIH;Bwp-l4}gdTDV zJ!FFj8O+R=?}QP99E2Wn3O!`UD7C~0<)-H#^pI2NAsa-n=&d?t@^pI2NAzMT+E1m_>jY16eLFgf;&_i}-S1sX@hv&`rLFgf;&_gze(2G}7 z6rm8qtwq;AKZPE$%M!K32+bJZ2cd_YLJ!#>!YpA{iXs$ZFx#ProI(%TWxHBpgl4|) zgU~}xp@(b`VYZW9q6mc;WG(cNQ|KW()~Y2&D1&_;gdTDVJ!FFjS<5ORicpBbw^*Tv zoI($|3@tH2E0OPm&_hn3hwSQ=juloPRy$FILJamn=piT2Lv~eEEipnXs_%o)Lr$QF zY!G1;Wz`l%D8yhNgdTDNJ!IDn)Dk1KGx&}pN>i@mC?f0z>^`C!g&6FE&_kwflpy8C==pm=jLw1Z(3pp4fl$(A(2tDK!ddLRBan*~NFG_`o!L=y#kW=U(J4UG`MkqHu z2cd_YLJ!#>LT)qjMR5@^$U*2Kr_e)oj8aRCP;UA=EYL$vpoeS_A-9?Nq8y1BZZq>m0TVH}0)QTJ0zG8MLAAsPWt!(8^pF$iAv+E# zB4jW#Uz9u%gB*k&asoYM$0)VL2<4{dAoP$E=ph?K$Zcl6D3T%uIS4)E1bWDhgKCKp z$~4bG=pk2HFaE@FP!S=w$wARfMGSHfddO6Ja~xDlj8JZR1oV(=uNXAiAUH1HQ^o(9 z*nU&}Xkj;^ER_bN12iKy|L#{v%*__=NK{Pa45rbC{ddLa% zkPU+4s+Y|xu0^4TT!9|4$&wgBG&EWfgP90DkJfgZ9!a9s65=BtJ&5Tb{iKo8k=wFp5p I)LVi0f0HM^Gynhq literal 0 HcmV?d00001 diff --git a/GEMstack/knowledge/vehicle/model/meshes/front_right_turn_light_link.STL b/GEMstack/knowledge/vehicle/model/meshes/front_right_turn_light_link.STL new file mode 100755 index 0000000000000000000000000000000000000000..a4488df1f1383ff543f3b9d57e15d096d56fd94e GIT binary patch literal 66884 zcmb__dE8gi7XF(Ckw}JQYA`0VOuc8wkPxmRuc^=_L`5i55fLue6uByixXMh%-tYIE z5XwAMhHK`^SeKOP;`cmzuhqNPes4cNpU?09aqoLu>)C6c^WD!{d!Mt4WogZGGi8H%j^U?8=+P3X!Hy>m6E;VKIvHi@I(-L0OW^Ep>eD-lmiSc=|O8HjT zI)?}?iXi&4J?2!t-?xb%M!wOm?6ctkjS%X^Ufucg?8?*a74e_x9m=_D?ClVtB}6Qm z{CefAX1^qiS5tG~Ia`$FFPTGx7DdqK_cgz*T(IyxL2THhTUoc_PK^-i#a@j$d|{=- z`yUFT<;K0sd*`g@?(Sc@tW>Srb$UXt5vMe*_P+ON=cQ=ItEuUi?OuLbZt4(f2@(9e z)z|;2bbe8Lb>wZeN))s~H}LlKOz&BB(|YrlF(u6**qL&~Ln+cZL`S9nc6MyKqoa>z3m zXSDPgyJ7W_+dH~m{r3I()ti>ox_1BZ#)j2fKk6tk);;!&@~0Okx$961(Td>T&z`n+ z_4+v%3gWr1Pc5&z?x9AA&`a-#@6{)FoLp}E$cv5cl_D79o?q9hem{1!#OQkA3FY3! z`;8FlMTFirA7jw1=afm!apuZt39o715uK{j#(z@l5wngRQNDhASBD5KilEn=UK>^0 zoO`$+TJ$}?eEPfvE=Pq3^bgk&Fw2rVH(a`B)H= zsT(2Gi@lN@EC|We4iQ>Hgwzi~>^N(?^0%FKafr~O2=+?ql^d-!HM1Vp_UNAzoiCCucSIRLa0~cUdc?xU5Cs? zT(4yANd>@uC<$cCd?~7PhMh{w;GYLG1YayrTEbCpAKZUV2CTmCLNpA=DDK z%fDqdC^2NV)Ci$oM1*&`rbcFD=E@m8ye65ENer1GJ49$v1ko}N7KF@@8zIz-y^^`F zAY_K@5TPYR$h=(;GShd6(4q+TivK|@L0nR7Sbh5C3mPHRi@nmn`M)(aK%|P`|8Ho^ z|4js9*J3r%(5n>d4~-F68qnxrE!HA}7}#Q+3~Pf%2=!tN+>u(WCIo@In_>Oo5TPYR z;CD)}dJzPE!3=90hX^f-;I-k`OtAJ51V%}Qd3z&-da+mFO@f)eAi$^$YXgS}Eg=G2 zNwEG91lAuJ)*lWLS`@)vfdvWHID)_$C&L=25kkG#E3hlU3P}(Pl2vl74IDp^OA@RB zH2Wl2K{zi(GhR*2^SjjK&BpdqM!D#07c6oJ{tb2|SdmE#ur|Y5tr0@K8u#j`+iLTk zn{Dl`1DQI(Y}?gy&- z2@#mjrC5Im0_%@_>~#-0L}*b2dxbe%iZzZPu*S);#%Y95FZK%axfClTL12cQzj1q4 zH;2PaIK>*k%~&ySOR<7*b6iC;UQG>VeL2=2I_q=M*{&k^H)en-R%8+bGs_%nwMGc_ zYTPT#sqA{4Mi#tUvO7x4*^p@qZwk zm);Q{Lwe=dqL#2-{*75bdn+-pn#i9#Z$Tr3dJ&=b&BqV~M&Pox+!cmB6omVC%;Eem zm<4Sa1lyHg(A}M7zhEPTda)(>Z3H2|phJX~5Fz7A5LkcYGoHW2Awr8H*ee;wg1{Ol z#~P;*LcQ24VSylowHezIrY7_fZaXhU)2F6JSnCjK2@(8TSSvAvwT%$!)woxZ;c~{4 ztmb+p+0M1Ay`@i0jbu27Pz&2t1pk&iCcTmj*9f6rM1*&trbenkPK)GoH^!uXxOSyV zq`p^J8{}9UxEN|7S`qwP>Xq~g>yI4kk4A{lOYew}fi+GZJdI+7boWXTj3E_OVo1et zF|@7Fi+}5V^D(5VnJcFyye6q?a^*71aEQ>N2%=?{AqbgeG(xBsdnNM+LC7q_Awo-t zkhzZ_u>Q!f{&0xUq6qd%=30Wl8YjaVrx8NE*ejW-2|{L;?(WKL(v1?CWjZfKGoD+2 zaAxTcYGJ#I;NLQTlo&FzY=ls+#=Vl6zPk>6+D|XW$Nx&Z;omaTcQMo}MDTB!=?fa` z56<)(Awn;`BW$szMrQgBp_Z^+{w?!)i6JxnMhNvHLhlHJ2i;QP z-v@264&Hg(=KiK3#1Wt|wy-AA)D>$Nq_4 zg@{Fy55`-7^ZuY$>cw8^9ckRF-@cz%xoJs#J-wbiZCvI0IZggVuR=uilfQF?@dv$9 zFUHe5(zsV^UNfaqH|QVT=_P;9;NSH8<8c)t<{fcsW!m`T+}y|h9@-Y$RWJUncZ7C} zkgH7suiF3jUP-$SA@SUt$j0~|y>bY>BaM3{Bg6Gd?x_1)TWX9@3;P}-#!Gay^mJ_a}N4B4ix@L9f({z0y0xXgK>?|9;I-Jj@Hh`?Q_ zMHcquR;Vy44!42_XoXFFZN3BNaJ3C+X=F$ zV=6e2AdCKqUWEv-%gr_$$Kbzc#ZfQzO794*_BTh)NRUNc=9Ir(My2QfQx+xKA&{>U zWYIs)SI&#Q(mTRPwpVhsmB6c>f7A1idnN5Ug!JlW$qawcEA?Wp^p3b*mHhAEKO1BIQRV-~+?RWC+~3|VbJ67@LNA#)JM<`nkkyv6 z$QtL5W1wjtJw(X50sEBy^hclBEl!0%SVJ>;T^FEeLBQg z`ee$-<$o{d_gH2L5%PS-j}r5H`1X8Tp;vfEY_IfL29f%-#ka!${-a)ni14YAjp5rf zy-N6R;T^GvaJ?L^=);yQBD91Eef~iE@)4m|ct;u|z^IgM>1vXH`~UpWy$TV!3MaC0 z488B6S9nJ(0+wZa(tvQg>7+~epFiqVh(HhBj=leTuRK(DY!d-NGqv(OV8|=B_ zzx+|JLIi%zW&6l%47Q|gg)+Qta4BlHUI zh(*ZgbG?$W>;4W~vWU?a)KB9xcu-G5+-#Qk8$}+uq08 zAC{Ee)=s()-4HQW-?}bMzrH)0_Vj5Eq3>&n&^NI}bf0x}^6d(IUpxQsy7Y+NE%K(9 zAK?(;yG?z=N5p{dA4;}v#rLYU-RjcMKkt-(_GV9q2;T|nJ4hm$9Qs=F>DfQw_h>() zE}b-~S3d304h|8%8Pzv`MErH)3h6gzKLtd-WnDVwvXk=>=e$s`@B03Xf9v}%A|4vO zR=UcsqkvenUtRjmKhDj&?7Oc+gm0Aey$TUmAJsAaWrvS3cBgGqm+rOp1^JDWFLie` zd=n#Ym+FZ)_^Qrn=Mn9IIQy8obp8q>^Z8@ix_1+TaPOn^O-vA@wx(vgo$J!Ei-zSl zjlaSn^oDQYam`@+PX3loQC;$5Vn+UnPKrF=F?S6OneDOV7JA^)0Ct9Dk6YdgdU92;Up%b8#YMl%zE^k8M|%&g}eUwtLUx973OLGlo91CZfmY z*CqeCXmud2I-xH8vdfrk!2`n`B76$0&q9fi(GG<0qX0h~0#8rf-fYGI!tL@FL{5lgxp;qgdZjN;SlnBI0X2?ecBEI zepJ8@AcP+!_~8)po4dRsqom5~kWo@y#*YI0a0u{&x(9(Waq&0C$C|M$Zqt3$VW#2|=P zuT~2_Np{Tp)eoNdH4vk}9+=;E-NfoWyZn{;PiBiwl5wcuv3kyV2vT-_823 zK@hE8o1HyBX*XeLeTVJ1Pv-6C>++sG->9zlRLe57#E1`nTvR`()31neNZVfd{;xb; z-E*xD20^rX&3NXSM~TG4aG6AglB^}6lKi<6ayUSGeYuyDto*x(l(dxyKe|+VM%4TQR0YMH9KIy1pT+21H&=Mp5z2ZHU5p7vNHUkIe zUpk?<|C!wkf@t;P$Uo+Qmn*Y(83F`3Sgd|e@#4b+v(OSF{<2nC8MoV2K#+q!zVKGj zY22j-L9}{t|?Mf*icQX{U1V=Fb}h z(dxyK-|4WL>iq4l2Z9{@smsRYGsk?Gg_amGrTR_fm0uqKf*gGJ!5zza{XaDbqScEd zf9K6xRQLX3JP`B2!M(rQscf^y&sk`R5v?!&v2sk)CxCbg9K3o#&+_X3{%8M=sorjhf(J)(*I#`Q3m`WX7_O?ggd2r;T4%VU$B8Jq#1a;6cN-a_c-FqV< zP~mD(2Z4|}n4k`3VOyaWM?UIcE$Sc;QU_DiLB}Yy#0XTlTGT-xqz;gx1S(uD z>L6lB9ZXRN4T5O(;>brGtVJC}45@<|>R=vPVgxE&f;tF<)WH;W&>)CbFOGcF!CKTo zAfygvsDpWEi4mx93F;saQU^2CL4zP#y*Tnw2WwFWfglG_2Q$>cJha3JRJa6n5D2M* z8S0=x5UpMu`KW`nsDnUA9n4S%9i!9|BT(TI)IlJm4rZu>2ElgKOR8Nh>L3tO2Q$<` z$3av`XNeIFYc+BZbudL8bn{PrUn5nGZx<^Z`KW^l>R@GA9ZXRN-CR^HF#;7XK^+7_ z>R^UCXb@~yy*Tnw2NTpmAfygvsDnjli4mx93F;saQU^2CL4zP#y*Tnw2NTpmAfygv zsDnjli4mx93F;saQU^2CL4zP#y*Tnw2NTpmAfygvsDnjli4mx93F;saQU`O?L4zP# zy*Tnw2NTpmAfyiFsDnjli4mx93F;saQU`O?L4zP#y*Tnw2UFBRAfyiFsDnjli4mx9 z3F;saQU`O?L4zP#y*Tnw2UFBRAfyiFsDnjli4mx93F;saQU`O?L4zP#y*Tnw2UFBR zAfyiFsDou_i4mx9De52)QU`O?L4zP#y`vH?ZIP&@L{m-rf!8*9^m(SMUea1Y;D78oxU502_L6U<@zk0U* zwNZWCdQcH;SG_p$`R^Dxh(QjH`DtwBg{BufMyVx6G^`+52e-Rm&&s!*A2SHHt6m)W zY-#o`3lZZY%thCo_+90Mp|3bbsU=1e+UMs^{QA zQ#YyRpRMdxcWQ|d4J$};aGURER1SW-qd~A;_2S59OOxMfg&3@Z+kL-(^{acfaH~7D z#E6C!BsqB6k`F6?`6V?7wyRzo`D|(ac55OAIXGqeq16lb*vqZ%)Dj~aR*>Z2?vK}0 z?>N2AAlR;Yapbe5y}#ghMdaXpyIorC|8rlrx>HMxXjnm#gX_M~y1M$5fd;{L)r%va zE!{Gg-$$_yo_@o1)optWag0(+jA&Rvl7nX))2=#T^|K6u?Wz|!$d=xo%P+&o!S{NP zuYP*RIgW#Bi4hGe$csnLPw(A%gKCQt&o>CEuWp^mr&MeS|BD!xonM#s++kAnw~zeS zXKINNvL6-*#+Wc<&*Iise6Msh%67viMGd{$_T;*Bmq)fPzWL-l*DJMz2>vZkSP|ov z?saLWBUUU%pD?l!LcNG+=vDCS)jhwG=dJGfl|IYjHOaGA#F%vY{Ive+e-sz|`*asW zEo?VL==I?p8Gesd@B2q_+1W!3g6*mof1705k(E`p<8y|-_|1RqcX6>~S3gSB5+n3^ zKuygl7+1}&ytX)Q{BdrSD1z;(7suF93lFJGy_QezICdXudTuebcYil_)e&)*feqQqC23?D@wph>QM76{SeO~7C?#RKL7njUxW)N&wy_kbn`Mz^y@jHB4 z%iLZav|@4e*rhJFt0hM0b3b1{_CEIKYH{SV2ElgKi?!s=huccyJ4czlz}j;;8G8*A--yY#INJ#2qhYt<4X z^f|1r=Uw()Qh9dni>{t4g6*moYdiM-$PR4I8Q!|4XQkr_2f8_fT4IDg9rm+~v7@f5 zjM!}-gJ8SZN96W}+w0&gtXukLBCob9TY z{XIC#m~ix))!EMtHFq~gd~{)t%EnVm`31LpwPo?euhR^I?W&g@SDa;BIbe%ogR*Ky zNsM^&jYBKHeKZ#_I1=x9Dlax$2@^?8+@zU3QUW`;RiTwOf2 z;kE|BcGb(~E6y_RUOc6kw&{*0`^1QEn_W^FIiwk~4`&${y>e@D=F@&&q8X0us+Y~X zoMpVQ@X_Mb_xCYbG)DYol`ASMpUUU$%+!m{exO+M;=>Js?W&ipADm@8deSq+O*bE5 zszHo+aQM}gA#+zn49+sXojs$tb>Z;_!FJWl*1?NV)%rJkrC9Xaai*%ph=zAXoB^~M zIkRXr{S<>>yXwU%sx{cpGTt2hMlrHH$yDbUq3@fpQUa2KUXb*ioZ_=wt+2XW1g9v-YyRh!m`zwcC-dyf(k9!vuGyitD zySr+M5qhV6J^%TprNycD?`II<-Q};@rpH~Ctp@YW4@b!wfB&fX&&&I{QKFU@p(Do6 zcQ?NF)8h7zQ-cUc2}fnW_iwB0aO)3X6i55K_g*f(XpuO6s3k_|$oKX9qy;Y)b57dA zAi~j3c3t}5O_d+-{X$qfyxn8PNs~5ptW`^lPzL*YzJ0d`ii?W21`)EBS>lAnS5(gJ>PNbtBWtcU+6NNBEsy$Y-`Tc#^Ialu&pqQGHd_y;ZrIzx8e8atmos7+NQYmv&pU+ zs3k^dW$^X<+7>Go|Gxb=g9xhutIyW82UcF&ZxUj#p6~n4oa#pF*Se~vmKdQG&e!vv zuO3=mq3aW_aw;OMYOJEzlkC3D^40l@bY^A!<8xP?)e}SAryl~3=^xaYI%Ny43?O3Z8@;pQ+|2@z5+^>CE{M^$Z!u&yY4LIke%4Z*Np2&Io zl)G0ecieR!$6B?-2<5-$`BUB7mec;57(|#q$gWd1eXep|-8YCa6FlGc`4!72`(%!_ zYKalbe?M<;f7OcRIfrgz5Mlms>>6EEHd^Hq#30Xq@9pIq|B}OR!{jsTDo~tEBD4RXc*ZY22@%v-%I-V;c%pYXe9vyG0tUB^h z#Ncdc=+d#pzpi-Iu~scHLiz7`zW%`@i?@Hd-5^5FlU+(wT-nSzLdA{({Ly7}$ zyTP$mEipp*?|FXg-#Qjw3_jQ(!u&yYwYdI_%0(Mrix}kj9pj#ZQM_W)N&wz3jN+6Z&>bt|`9ja)TKqG2)56 z?yc;1?i9q}NbI%c-Nork{7hd*BHL9j%MZ@mZyo$p@%{PFnb962uHB_tIrtK;?#QVB z*1uU?_qDHsAwSg1@|^Sbt{W{XI(+-Rd)}@*XHP=JyQjTSd1?{YILr*=oBUqXG;7_6 z=jvti73b~y|GIK{#I~!N?8Bafh#zivv$D#77Z8IP?(HUR%AeNlU=VCqy=>m)(~rY` zTem!5;D#oP#)yND`lzyGBG*xzkyU}=!o(4yh+`bzFzDxIWs5Oy8bruiW(nB=gBZ*{hcx}JIAxEyE?=o7MrdB~^?cR6 z-YWJSd%r=1*@xLqcJd$wv*<;u&nyPMG}Yx@wZsU`sQx)z@7}i-|2$;0L4;Y9SzC4_ zAqMODmV+)YYEL=cRRgue2(1jhp1)q*ulT%vGlK}L0jrPftU?S{wddz;Sln#DO_VuV&|oN<@crA?X~ zRet<&Q^#}N9ZS~g9$2!gVW({Cf%DUA-|171y04XEty*G)^54(fSD$rA`Tm6F1`*~D zvP*Ud;X3&AW4*b(%N-ZDa;#NLj8Oi2p7&X0-*Sb`elNnd__unIU9!^&F`h;>xcQ+T zLzi z#a0RP2iYY%=n#WEKl!3&<>2~99c$GRBb5K1=QFqas;Kt5!63r?L3YVbK*S)=U+edJ z@k`%p9c$GRBb5K1=k3q9zc_yIF$NLl53);kG$IChKIxiq#a4Dx*L z^Ifa0p8s9<$#A9Z_Qq(tHZug@0=OOVvj5+$&vkb^*(KisAjWCu%uoM*?tt>Q(eDR3Te|k4Bg-N8edbuJmKdS@_v`Zx z=O0!+IQnIS2suwaexI&doilhCVsO^C+pGi1vHQH^SgV#8q5Svt{QNh1mD3+A4I<1R zWLIbGrJge9WW*rP`&ZNQ%+a$QYt<4X8ZrZC$Qz|Ql(n1PV-R8fAiEwtsir#d>VAkp zp69JLFSmX9LC0FP#0cfTujj91>y}6Mzuq9i{6Tg#dw*eN?KKWS4Dx)?E~}QW&KT!d ztCkp{{P#THY0=Nc>kEe(M3_Iwt{toIRPKEwK@9SI{%aowz)vr-Dy_Ih5)NJC3yK>4+y}b_hYOk+mS6|z$t?5;axc{O@DsT6F8{gyb z%A1etS={&4M1x?v>J{EYe|NWk`kZ3eHusym8zaUKd#Uo|%1aT0zu*Bk-c>Aqp}F}5 z*{*uoamDv)kDoWI=zCsEGfHB_?43TX?0H8^8HsD|vaopk-CYfW?W&jM2iNC6O=((A zY`K#e?J?r{oqnq9xXW6IK}M~y0p^uxCJw|d$7 z!S`yPHvelmc&!Ph8pMc)HfUd6v+vG`!HVUJ@oaw-GgVA&Cl;+5Mi%)7n+>7LG{^| z?}N3xyPuqJYWdG?&T@BGEippxw4b+cb-}>$vh{l#M0j`kYrc5ZI@N=AcoQ+W*LjtG ze=W~%d$JoPYKaj#V*I>)t1AvKpL#qoh;Wo}RG$0o>eUC{e+e--+MASrDbLvUFgM!O z5+iiv`+0kt-FGi{zQ2n>grlA8s(*Z?>cc&sLJZdPJ)7-PzOX{>SgV#8p$x{|MP@jC z`_0N{&S`59A#0f>2CP$4J?FuP5rf%hz^wJkr5km2*+(rgLNk%C=M!4CEKfLmQ8jEU z%s$L^`;7mxGVZK95QFu6@_-+TBYQV-SyU}CLNltb=Z~%NLUGoI)2m@yVHRc9UTLQ{ zDlLAz9x+%AcJB6I@$)q^T>Vf>jL^#9E6yq%E-XH2c9KDa)qvG!a3O+ zp_STvU+eb3$v3r*=lbO=*(KlCBE~1D&QHs2N0xm?%yVCQs)alc5z2qh^TWEGQ-1l* zQw9;{53*~()g7v*J-8-fkmsu}IkWuauojNBYKalbf4|Riy;ld9>ra|d4cp@1>P2>K z`_FZ&?`+TpF*tAUJNd-&t>U+8Xo(TZf6w#Fuj*TF@Z7xyL9}|2U3Y%FMs?TsS3(T( zJR8@i96RRAYG{cO%Kw@gR?fe_-?JPub)rEKtzKl;suNpP|I>a2#30ZAb6`@=z3kO$ zXo(TZf6w!}gSIG_-hZh<5UpNh*P^$ZRKIBY-3-t3VW)H`r=9YkW35_Zg!13>e7|uk zm)}2gv_XWNC%Y!R_DyB`Ti!zqzCVAU`>(~5-~ZjQRxL3?`R{pt_t!5MKR&v-L4=$q zyY^Uber4}5&mjhRKJAo8ioPumaI95Jj8Oi2o{zkFbg|27@3|GWBEtMZb{({7wK9Cq z2M~iizyHXCiypO09c$GRBb3da=UtDUTU|VMFM|m42YD{%Kq3ZtzS>s@S2uZjO~-S! z#0cfTN9_K}q17|;UV0iDPubM-;oOOv_BuFk@A>LH>@=yV2`xcSx(EN>-Cy}%F6>hz zFVAvo0KM|i%l;mGuhy&2#l>%X_Nomn%RwLpf58>Ed93*MhBl3U5BY7n+i}Ht`))tI zQr!90tlH2L#0wFK!HUy%%J0S7-D@i$BKW(z9S?CPI>)Q#&`-mrL75?YpnKn!N; z=bs!{cAaped$OrHJV4imIp0@<$`?b*yINh9gqGzX5Q7zG=N--})3a}O->zuI3DC8+ z4)VR)zYagQ+;Pf{NoZLP0x>vmU-ydh%OR)V;!bYR${C>DDK1)r{eHObZ@QqoZN$w9 z>#JIpgFuYn^oxuLJyj#9&h9#-Is@^k)bm3}%uCs>T4F@Q2^;+0;NEr5E^l9R#VkaG zz2aSvx+{10n)buXZ_g{z&=Mo$t^>jMYP-)KRF1m7CJPba-Q}+-br%TE+kbfCr1IP| zr>CJMM#$&^f-A_Tw;WaO|JpYO5sng$N~ya*aI`m@bZ9xR=JqtS#0Z%I0Ks~mweDG- zK54E&grlA8lDZ27>v{hkY1#SWYtqmXBZSRBa7900N|*As?H)CVkhRPbQk{Wd_IWVr zSYE&6^fa`@2&wbPSMJHgYAcr)?KjpS!tBFrC)F7-m_>(;`>p7-FiS&AjF38y7~BEz z_Kq(Xi*G!_Ai^vfR8hoWHRyi!qs67&Tcn{SMrdX5^?Y%U(M5-zD;h*t4Oo4oIwJ<_ zc|QA)V)*&jC!r-qNVUUtuyRU0H;AyR1@m^qU_F=WTpL-JSm#nrCgFHXu%HzvyyPjESi4hH%fjmF@{z~}9~ZtGEAxlT`mAX>f1E?I3O26_G!b`Gp^ zXNN4b#E6E>!1ej(Z*5ZEuv-^{AX>f1E?I3O26^7{_zlW+t1Yt75+fQi19|@3uPw^a zd#q#-M5`CsC97@3AkWWP=jYBTq4-{@GYmKY)Pb|5&jtUYm5@oL9W1`%cnvP)Lm!t*BEA6Rs2w`CeyVnjn`AkSre z?s%?k5v^Wiv#hp-=Q3|kLQ9O0dAlHFMQ;#9%hP%j+h-qn-fpfVM#%dF{DRDIH81Q_ zOn>PTgJ7@J%l;m`yGw38s~Gvo40Cs5guE9)3})&v_uX5ZHTesJV7uyN#}%u=2K}EZ zepq?UEVRT3dA}ng@$Ox|EAD@PBZDAXy+RiFs@7wj70PRx_cEhBM#y_A#2};2KY5+< zh%XN?2)3(UA)7I?1Z($rwL^J)$6bnujk zyOy&iTxGIPjF9(+h`|i^&ra9@G3ajw!FJUv%&va6H1e$j%71Tii^-xfLf(HO1~c^| zz511Nej8^HY*)Q({a`h??!QNuPtCg9RD&2H?{N`>^Y&YR8dy$$>lTAxyXwX2qt(to zZ~toYz%twHVN=y&M8m0doVQ>7@6*apX5MZPY*)QlMYRU|=k1@48dC1t?r~F{V}zcP zXHJxJ2-zp&>bblPclBJ}bK}bO{rT^s-*vrG3wshGw1>W)pLt`ya+|HcFo>{MybJO+ z95GnW582?D^7wZ1+}%}6jL(_BXs0@M*XtJw&hh- ziwH+M*(GnoaUFb1_Qlk$<)g8>l{LN(_wZsU`L_Wja^WoCsfL0e8M3{Y;?c{AZVz8d?*LFd1bf6?Xh!wV z;bxxwcrj+n9tII+QD$v<&y5(Y2CK}tqqyma^|R0tBeXL3dfs*YQ;Mz~7Q6bPZH3i< z)kofjBL=J5fN4F7u`{Q;s-~70p%uhP&#lmKdRx8vEgp zOIBKVP&ss^HaS@&yVxAh!&5eu%{4WT46I9^n|^4y`GKoAgj&dRMeuLgO@}MLxM9y- zBZPVpp*hB!HJQ^Q`*dBe^c+z3R`%8+Mz9;##ZU{;AwsXuXP-^#lk$}-H#UgyE|BxG zw-zy&+b_DbM>(bAdUfsj#GK7GEAvZMHwdEDi=3CewLmcYOxkg?a_iA8^3W0^WS1TgTut1z;@aiS zBUUg7qScF>m%X(>aL(}hwriH{w_50OiCSWW?9u~*PYwREbCdGskslfa+f^@eUiQ`k z!R&Kjn_r5J&z<9PiCSWW?9u~*tBJ|OUoXDA;8BBMyXr;G%idZb_!gl3jn5V1=HKFS ziCSWW?9u~*^TbsSySeyvrOOP0?Wz|!FMDf&VD{Oj_Uhu>>yCHXM=dczcIg4Z`EG~m z-o?5XZfOu~SG~x2*;@+)v(LY(n-&8;ZkmOb7$LjqfZ%FEcH_G2qiqqbUd%qSw-$(C zm!8W$YKakgUZY10^ZR$xur2;A-{!d0gvR#0lCNt_uVRFJ3nW)Qb^o=CTaQ@VTseEC zUiSCk-F^GW9g2as?{4mHjF7LO5QD$qUB8VgPT$y{TBpAt+f^?+uDIsBV$gJ8Sr71m(?7NFf5UCS}OQ&XK|gr4hdPJ(s_JtLg$ z>Pg^4%eSwo`C8WXN-Z%$d+6)=W)H1iUN@z;L4>{HU65~I5rcR4AJ?=iryjnC`#sbW zBlJ%Dw*WKOYgN9v&+Y~h-d+Bh^6e{PaLxJe<5nxX-?NJwC2ENgI%51t+^AiX^2$xR z8ALcrI4b4aR~hXi@52dcr+0CqT`e&}N4~G;r_NbW+;nXxg9t}E*(Kk;A_iI8?yN70 zn_I8#SgV#8p$x{|MP~T-gU=NoG;3uLA#0f>x%V?k2a|@h_D*4`pCDhh{1Zk{=B9|-`ShG zs-~70p%u z&awbM^z@6SQ~NpAswGA!|2@yAZ}eT!X{)0QBFrCTmz-rGJm2bx-;3WS9pYH4mKdS@ z_nCUst_zA6I~-&XVg4Yy9@t&ZTEJpRZEOe{`;o}mra;o?Dpku1`*~D z$1Z=?3u3UUZJ)khd@ycj$67h%!o4fhc5P}x*xRpVKUSyY?Wr5$EJb%B{ zGsQ+Xc6O{)ON>zdd!GN^=AXsAcdum-Vg4Yyrj_#05+juVp6A;i zd1PjswRON>zdd!GM#Ym?&VCr>blFn^F;a+U>RkmrYP{z3J@CEXm) z)e<9=&7S9S`i0}UBEtMZp37Mlh(VsqSMiSLYKalbe~*y!G7N(44)dpExp}+B_PvtR ztW2+Bgq*!4SN_qh)2n}fpoh6~_Da3%@4qReAx698ocQ;1JsblgBUUE|V;OJlyQYV%C3bzKRiYW)))ayuOvzf2g=L_oq#3hGV`eXZwTFK(D=5o}kzSVgr4`+57o z)1E9YyT|JjmByr`pG@MT9u0t&`LVM`ne_VLUnBtgi zhZ;oKE8Yb;MN;l=pIvV(jy&-ccX!niBlJ%DdVcZcql%q3J;5NtyUSlwPLV_m&f8Dz za&@s}?9pzNs3k_|i1GEj{j4Fyx~Cp$5aB4{sFYJA5rda3O+p(EeV z+dmsySBxB<8$>wT$u2oX5;4fyb4Ls;p8lqrW35_ZgfiGahue39U5h2NH#UfnwagN7 ziX^g6A7q~{>+Drry-9nQebf>oG!yxH{`Pw9ilf@JFo-bwFx$x~l8C{2e!^QD6x;8z z*kw_*#0br({yE&dmp-l@x8ZDq2(u`&wwxk~7_8^t5C5dvZM*wiHBd{8(8?gs;oiEo z`sR@H4I-=ttUhvzBx10hUwQ8()jqH8@1*5mq%;Q8{Z8F<8&# ztVvg$)eHLxl3* z^Zch>)+^rWca}l0UG*ZnKYY#Nqt=5ABFrCT zmz<4^7@W5sz2c5V>%R_gtW`^lQ2zV%`L`>rT-@{3kp>aw53)zdd!Da(>W|f<2kdDOVg4Yy_E(Q_i53)zdd!9ct?fz=>EBs7f5n=uyyX5R} z;rXPAv#T>JKRec{B}OR!J&fKomAv+%Ec&?Thp=|a%7nL!`b47&tgFF|# zGU2(LLhE?0mKdS@_nASo&kTa?`V+LLxOuzA_Pvs`?oF>^1kpGhU#|T8AI4T@%sIqd zIeVpE_V?ht{h{;rtZcOX#pd^j5kzww_)Pu9xbG^bO?=cK*sglnamBYXCmnfBWyy=L zm{AfVh{oyoXoVH$?J1j7_k8a+gJ8SrW%R1K4LIa z?|I1KjY*Yu;i&a!>u%EYg*t$dY!ZR;0)tNmB z5&RoS#NZ5I#!q*4hNgw%xwlMlZ{?6BoX%6ou4O#0g{Fn$IT7TuWSnIPWCl@#;!Fmb z7PZi{a6DH8+f}cST|SFK(;|VUg<~xd9Jet7`MB1rL5ZeC0!<5pko@7iLU#G5IMB36 zplRV)%NXQyj6huxH7N2NnidH(Eet~Phw}>A<*OPrEmCM&IMy--`5Yrq?L-ZVl@pp4 z2{bJXg6*nT$Sz- z9BUbae2x*AuZS8Hc@9mB6q*(WA^F33h3xXHB4}Eq(6n%@WeoB;Mqu70YEa}kG%ZqS zS{Q`n59bxKYni4+3QY^gTE-xsV+7`pq6S5tL(?LKriDRB{%~F)yZr1GnieTEEgWkZ zgM5w=m=#YC@FdxSD{bMFvd^gJ8Sr z#oUEw00}fLFzT5Tp=psp)57IMwZsUlCPX2R^DAgtWYDxQ2)3(U%)xjDkU-M{F__z{ zgI3I-Y2k9aT4DrN6QcCT=ey9fNTF$A5NubySWEB>Ac3X@V(_T}G%ZqSTDTgemKcH6 zgeVqrz6(u@6q*(W!FJV)H4)DM5@=c=25T)eEmCM&xLT{07=hJ{kv zGH6=3cV5bm7=d?T2{bJbgN%ZvMFvfaM*L7O%X6|8nid%}EevbflMsQofC)4$5QCWk znid%}EewL~s+Y}I%szK7o{~Y+!epNqfoJ^*G%b*QILm;hMFvd^gJ8SrW%I6RT4d0) zFj+K4;H_)|O$*7?(6q>)X<-m-SG{cg5KW5=nii%S#0b1yPM~Rl7@TE5(;|bWg+Z`g z^;qVa&>s4F4o!<3nid8T_KJ4_@8}a~TFBjnrbPx#3wL+b5+n3Z`=^7@w8)@oVG!Zn z<*$i%>B&}un;-`3IW#RYXj-^YqLvt;BgW5np=psp)50LaQNmG)Jvs?AEx;&_c4%5; z(6n%)T`e&}N4}r8L(?LIriDR-qn+%+JNg8g7Q$L+T4d0)aI95Jj8Fz+wuH<8O^Xbg z76uWrmRSOC-xFwBNcMrIMFvd^mwnU{BQ&r0brdu$GH6=p?j6@wn0=V-@Qyx#rUhc~ zT`Dv!GH6=3EUK0mp&8Xb9fYPu22Bft2(u`&Hr~-E(6m4d)^liDWYDy5)j%yVLMww` z*Fw`GgQkT+gw=r62k+<;Xj&i!>p3(nQfOMZs-~70p%uq?7q{ykyY!N$+c$AM$DX_7 z)3aF(MAIUNriEjzTFCPdq5Steho(giO$&n{Yt@VF!k)VXnihz`c{?;Ma%fsO)~Y2& zDE~drp=psr)50La{6ThM&s_pd3&apjiyWF3jzdd!9qnB7>%dL4^5(?82VA1ez9z!Ric6iwv3;j=QT4d0)aI95Jj8Oi2o=MLOF4>8Dd?A}SBY2kRTmKdS@_XzCkOQC6D5NsEF_LC0pAM57r8r$~@yY5qH zT9{tN2<+2OplKmj4o!;;nil5D*(>$3zX#{-(6q>)X<_bejKJRd1ezA|3qsQ(gQkT+ zuwC`CI%!g`eA=TO90FhGrM>TcTEC)8I=}dy`-T_a#HHVy{S*-L6k;Qtmn|Q$e?NAs)1T!gjNP$ z&!K6NLDRw@!fL?kgRk9^iTnH&F<8%`X^}zG!c{f3#0af$zH;I#x)hogu5v0OtZJ;H z_$DsteeWKK!FrBw;!bthW{6Ti%i~JPI6^KEeL(?LMriFg1?<_Gw+3a}^O^Y0w76uXK53&nizd`*}MwEpljD7(|#q$S!=5pY&|Y85wyFO^Y0w7LK)Qi4n?w&vR&6 zWYDxQh%kSUUHBqDnZ3&p#30Y1X^}zG!m(B@F+%z8c@9mB44M`O5#|rF3*Xn{B*Qwy zAkU#`kwMeKu~scHLiz7`4o!;;nid8T<`1$9U*sqK&rT78Jcp)522Be;-xW)YP&Rv> zL(?MN^uH$?M3_Iwb9|BScS{ZT_6gPR>W1^MX5*1E+PQ z*U!1op>V=R`u*6^j^{XGBVFZJ=0rJ@BZsDiJ7GgDP2?p zgpCxM7Kp*w5;QGxXj(YdswGA!|NZ(Lnie@UEes;eA7mF!*hryiff%gk(6q>*Y2jF_ zmKdS@_w^i_7CAI63?j@QWEW1@NTF$g800xLEpljDIM%8qMl@sw&XA#LkweqMAj14X zcHxAL6q*)@L7qd?B8R4hW35_Zg!13lb7)%R(6lg!Fn^F;IAJ4!rUhb<=g_psp=se* ztCkp{{P#SErbPx#3xf#r2ib)aHWFxBAO?93O^Xbg7LK)Qi4n?w&vR&6WYDxQh%kSU zT{vMQfu;pwkmt~}$e?NASgV#8q5Steho(gaO$&D>ha$rKL3ZJUjRcw&h(Vr1(;|bW zg=4K+Vnjn`;CnTk$&o_S!XU!@L7wA;jpX_{O%TJ?^K*Ain{PSa@mwu2!e$1X;*mnr z!XVf#&hAQXT2fzYuY) zX<_bejKEoF2{bJbgTEj&Ei!0Ym|u|Xs+S#Ce6I#giwv3;W|YJToavT8(?UifG%Ye{ zS{MY|RWHjAuFs)qkweqMjP@9TQ|l6FS|A1)1x=x7CAI6Of`rRIJ+^0rUhcK;y}|P zho*%=uwC_H_0ekQSEGyRAoQ<1K8~=$ra~CIIrjOj-(baRDfSLZX z!^dEhoSB(J)57&iE$m5%&>s4F4o!<3nid8T_KJ4_Ct#+~v_K5rU1(b5(6n%OS1mC@ z@3fz{L(?LMriDR-cbC5=&bCaUX@MC0x(1pSIW#TYC{as{&=KS3?a;Kyp=n_d;V9v# z#Mzc9G%XN=qaB(SIW#TYXje;&(2?)w?a;Kyp=n_d;bU9QD$wNfSEwk z0x?((plOjo)56scwZsUm48ER2(;|bWg+YYXfYk?QTPD!7Kn&J%Xj){@v~X2TEipnX zoS(Pj%*+&;7Veq1BEqW1DvA>@lWF6RLk!k)oPe1^)529}wZsUm)XOw2@*5{#>fV{- z)aHn?lpV@mwu2Liz6z zI5j(kriD8-TM@-=XY2mJLIfxnl%AskILDRym0rbj)c4ye%gY$N1 zT4d0)s1Gg6K_CWyL1v;^@&1Y)q_K+__FrbQAW zg1={2eu$<;4owSHsBp|#4gxXAC}>*b(6mq$42KBXond*->I_Yb9GVuYP~kGbauD@C zGeFZKho*(9U^qn3ZoSP{oVP>MB8R4hDpa^kwj2avFvCI9B8R3$61ElmU2pR)=k3t6 z$f0SW3KcFRF9(4b%+%1d$f0SWDi{tCv|DfM2j}h3w8)`pp$ZkQvMdLI7_2zZw8)`p zp(+>-5wu&+>Z8>T*$4aKplOjq)1neumV-bH&fB4BkweqM&7HNa0PVD-vg=vV>MjtXX^}(IqRMvF64dkX%7G9~iyWF3 zMTiJ{6;x3mcz2;`kweqMDNae1(qf)9f5FG8$w8)`pQ4K9ILh3vaWE3*2G6$OIX2bvZ+G%c#3B}Pb{N4|1TCRSTHho*%= zgxQDLPO39vFpEOdB7>$yHMGPCsq=`z9T3p8$e?Lq5MdS#swiTx8bH$`gQi6_w8RLl z48ER2(;|bWg+YYXAgH2mXOu9%Sy7^u9)??W35`q^AMr@_w#mWTIA5Q zFo=-zWS6YA5rgm5plOjq)55VJ?^JpGBc* zkweqMWYHKQ?>`ZPnHriFIW#Q{g6*o8tsmSE2Th9{nii%S#0Ythix`|)LenCLriDSU zUG-x1(Q4;suh6u>=S~lssum;U2|Z$P-VRNR9GVse!FJV)Ra9&6GEIvdnii%y#|U{s zj~MF=uS+*s+CLw*$s&i4eKM||%iC~Q&*eQg5c>Wcnij5CYGF@8g!a(ab7)%R(6lg! zuvfeb@-`eXSkIwpkweqM-CecB2))z3o%ds~_4{SPfWx%dt7>YA5nADV<&^j51`$>@ zR#AByju@=x@;2O6XSKu#t<=jjEpljDlw^_YPjft%J+KkaMbjdOriDXT=u zXj&LVco)cd*;|Vk%f1dD&YF1hWq`EpljD zl%XX?$Syq~xSD{bMGj31gCJVH$a&dY3k0(dG%a#yT9lzBM#wHbAh?=;p}U44M`$m#8I1 z$Syq~xSD{bMFvd^gJ8SrMb69KS|Ioq0GbvVG%Z{%QA>=FU3x%po(N5g44M`O!FJV) zoR__|Krs72(;|bWh08u_i4n3(4+ze8p=psp)50Lwu6mL4vbPopW*=x;WYDxILQ9O0 zU3x%pH6gokUG~woh*mFVAK6d}D?fWE3|J05mOfXj&LV zcz5}0%D1nG!8Io|EpljDxKW~(7@;G^k3?u%*Y2ik@ zT4IEbd|%I@X^}zG!XU!YPIk$+uZTg`LenCHriEjzT4IDU7)Y2m7YT4ID&24ByiX^}zG!XUzG!0IF4z9I(e zIW#RYXj-_crj{6?70y>q`C8UhPDO-Oja5{>eMJn`bNTkwRcE!t2(8r1G%d2-dmiU_ zF6Ux6p37Mlj^}cg1^A(-UqI8su~seQd5BQ{d!9qnB7>%dL6EiTMRv(q7Q%CAT4d0) zaI95Jj8OjjOg(DX1sOCg3?j@QWS5*}ff%d?(6q>)Y2jF_mKdS@_fHL=X^}zG!XU!@ z;n?NRdO-~G9GVsxG%Xx!<&+Eeu29>xnSpQnplOjo)50J^FS1L{vcPXnou`g+xJRNvogJk5pw>OTsbr?QfOM3D`&6N%l;mmw?oq+ zg{FnMyD>se9g|-Wnid%}EewL~s+S#CoVP>MB7>%d86`17PESJ&&fB4BkwMeKAlR;Y zg)CU6X^}zG!tf(T$SGHdK}JE-B7>%dL9ku*vOH&XhNeXZO$)=?7$K+GA^R{hK+__F zriDSUUG=j0icbxoX^}zG!epNqA*b>ohG<%3(6lfJwyRz?@AByfG%Ye{T9_;vBjj{J z$<)xa$e?Lq5NubyZ2jO<9B5i((6lhsAV$b3iHO0OB{VHEXj&Kq+f^@CAFX!2szK8t zgQkV4YB562zd{Vo+o5TZLDRw@*sgl9ifRq^^LA)jWYDxQ)j3AU`B#W>)d_X!mtDqW z3mzEm5OV6JtLJjoq^sw0iX;%CX~EMeU9Z%_o`eYPp5-~V$ho(gaO$#?l)Dk0f#Q1s+O^Xbg z76uWH5{^naMG`SY(;|bWg&XZ^i4i*T{k$ET78x`x3?dxuWS5*Gi5O%pG%Ye{S~%9K zB}OQN{c|{IT4d0)Fo=+~%o1{nB(jfaT4d0)aM?#KF+wwuujkOT$e?Lq5MlOVwv$sN z5rg#{nid%}EnF5=ON`Kr>Yu|w(;|hYg+YW_lv!I&kwgsEb7)$m(6n&XKrJysD}y|T zd+XX1nid8TRs&WaIYkmNSkIwpkwVkLRW-H52(56wa?0tHu5v0OtZJ;Ha@Hhbu%1KH zf@e*->a3O+p_O`>rUlQfbv&2zX&uky+*-$TIU5(_N;EApXj(Yds)alc5z2qhb7)#* z(6lfJvR1vwE;)G^G5EIcvbFOJnih_=YKalbf6sGhT4d0)Fo-aJkX>?uGGcJv4o!;; znih_=YKalbf4@G5rbPx#3xf#r2iYYjK_dp|?a;KyplRV)tCkp{{P#SErbP-(3xf#r z2iYYjS|bK|4o!;;nih_=YKalbf7B?<0P63XpF-2ZAj14XcFCFBh{0I~G%ZqSS~%9K zB}OR!JXk!xOe zJXb`RKge@AlU{f(r_ef{t0hJ#|9xhFrbTV0EnHriFDKsq%g6*o8tskOkkwVkL zRD&2nG|s?B3|1UyTBOjlFbKA*UaUS^?R-^(rbP-(3sco%1kpGHA2B#@ho(geO$&oy cyXwU%sx{cp+o5TZLes)j=NLgWkcjbr0Qifv$^ZZW literal 0 HcmV?d00001 diff --git a/GEMstack/knowledge/vehicle/model/meshes/front_right_wheel_link.STL b/GEMstack/knowledge/vehicle/model/meshes/front_right_wheel_link.STL new file mode 100755 index 0000000000000000000000000000000000000000..85975cc77cbec83e77a8ae00baa8f5c42200a197 GIT binary patch literal 476284 zcmb@PWqcJ$u(uB$oZ#-Ri_4il5Zv8e7Izj|EGHp^BuIb&!4f18WO0X_=}dwLSTwl1 zyR*ox>Ll=Q-h02j`(@9Ms%L6?rl-4XCN|su-~TEVvDu2%_l@MEo-RGkN;NKtywzfs zy#KCl7J^)N)b!L zMp-ENonYH>#GJ?oMYQZTOe2_1&>A~4GE=0okvOy*>6UYUp@`tsy%m94{F}9OqIsI+7GK>KIXYV?;ok{FRO9#R zcc*!I=;-fmyDQ>#x7HegTKt=@dK^(GZ*fITPw!!&1c~F1GDfn!b|MAY*f_O8Na zZ<5492@-tgn8;XoE7|yPqo*S5+uuc^t`u-Skx{tp8God`H90ff>@I4+zm5ioKGO5m&vxC+8%OSrlLDVk{n zYVmI#Io%H;;0`)af&|PSB4Cy{Q1Uy$W1@LQ1k6N@fLS8oDImg%pY1)aN(V}QC)fr( zA4DWPQK?qNY6Q%70Z%g#2~TaO*;gGX`JG@J^qdm`D}zSBQ!8MNAp%yPn!juDacPbE zjer%dCLRk`9|7y5gSLTRtEfhx7ObvBz)D>cB}l+JPXz1+8i87{OAzrke#d#!t#wV5 zAOZUo5wNRi1Zu%t!Kld^0Un^ENt5{|+o1J~Y$V(CQnHN=!m}nyeka&Q z9O1FZQxOfkof^UPFD;vmZDiiufNa!W^quwuo2}z5XHEWpg5-CC>7N9xzW*=5|CXRd zwDD^kbXN4V+idY?1rnY3b%rT6y;MZ}$bS-i+ypJU3W9C?yt*_Rn=St8{*?SqF#Yom zDkA<4{v`Og30ibF)xZCoC5j-wooC5U$?pWyKWCyM$ZyvOrW3SiR;nY#&35wJ6+wPG z&-R~^-wCGU2zsIvL4LbNFrA=9PnSB<&!<)q6SQcR zP)8zn+pdg~$1# ziXbnXJjYWb~;)w#i0~ ziE+ffrc)G=Ai?AEZytGEGy&t#j)humJN`&6Z5(QZ2@)jWH|>Bh4vEJ?Ef^o!fN>}S zuWtOgn@q>g7_tHLN}>d9!0aJ{Vw{9|6^R6D!Tpyi#z~l096=_`YULlq&sP&>4-pjO zB+M&~KrMLEh=3<55+%PAY>%EnA}GdDHsYggbyh5a`6^+>AcA5XMNo_riIU$5wh@;D zpcqFH6ysH4e^lpcbshM8HaI z{jS9}I1i%}6yqoxoW(&2tke?rl1OrTe(g9Kfm*N=5dpiJg%TuSPb30%PK`h<*ing~ z7)OnRVjK%4NWk7s1b6@%fm+}h5CL8WXYLYw2F?g3_zaQY;Sd3yjD?cl3BEUUzlfk1 z$HAUue3nz$Uk>IHj0Unu!lHUoo5tn2AjH3w7I^(hUcY+r9)MNu<93~_`IeaYAQoqTMR==6%-!@y}fwyVS+iVv` zdTN<%Bv{TzqG&=9y%e!E#HkUw*3UR0ju0$mg8$FfEx?_cAf zkvmwEVgo*_pAsbSy4h@J^T(adrJL(S-;d=S+a^wzSr=3{`FD}@s|5eP@K@ZwmtC-m z)^Og{jCuoI_FRN_#o_&pMoVhkhjo5iEp93XG z{9U<>qTPa1(VeLKW1=G5dREd1)H-~tjI#0c$tSY0r)wM$>{i=>5+wLHUy(Q)4Q|F= ztNue0Nw`+V#W{Z@?BVu{tNu^~-QP8QC%n{I@h_BU#4nn5XRsmu55fhuX&jlu;?Byw zN*C=8f(=C^+)bOU^3gaV^Oxd^NRS}GzY{zI{jBglqZXenAL)M|d4fbEe%T=Z3PvvR zSU}jpwxNwfq89&7@XmAsu9doj@gvvnAY5It0ndjc}33$5%7FO zBEi2CwD>9Dv!&;Q2zWjsQGx`_UAiY@x5Ul%kji$AKrNX0M3gl*na3YFt!x{7%yDIN zI(9UjAqRbXD=gns>Z~?ZzACcbNT+^xiatfe&1VJ8l>a%cDo3BYkU*^w{}ok7GJ}{H zIBJ`Dlx+0qJK01D5^LUOP&O{!k0D~-_Bm$y*G}v7jJg_uTE&y*a;#1=L-t#Gl!)Vz zkIe>`o!0O#Atp+YSer77W8&)R^3VK-h?pOcTuwdVv?i?EWugR$OP@2UvwHsS01^H- z(#d*bpSi7WEgh-y)~A{$^r{1Zr)*pVCoiNq}@;&BUd4_2m0Ndd`QYlqf->W5#5TEhz$I zp{p(;ipMmQe@%5-)B0x62-JGxO6r*N)n6_SW8%`o4zlz(r?unPc3RhZ=a(o!qVeKHj@R@2 zWy$mVh}a&`S03!+v{Jq;tP!Y%Pnyk^HE@7*^l(}~b{5l~K_p!Jeu%;y{H5dUUb2z? z`w%&#qtj{~TS_BP3!g`utxf76S@g80)#i_>vf8GlqQ?NI`v2}rhs5c*K61(1wW4U` zLD8(UkKD9sE!p_|YMwMNdRjl`Pm(A>LK;WK(- zp(v;2=#)iP7#A%%=A16=JJLCLjpcoipUVo94v4XXr^{PaGm@v)h|2*?9}uNK{<2frNjeDDmw|fcz-ZkPXN6r{;ivoR)FB zv__!Tm}*hNb(fxxIZPZ1ZsEH0-D$a&u6FT`$vY?ShrH+UZ{F!nPKyzXvd)mci*gh3 z$!ncCiT1%EK{HLC z9n)5t?quU*_k|jPT0SQ~t1Hd_x7ofVcQ-GRjoC-sO_U&UIaz9Dga2={r8u&{^duXZ zTCC6r)Z+8!yUAy5v&H=9W^N@LO`7B}QGx`YKVLVtYqK@mHp@)UK11PuGy=8QH(?um zEy;%Y-NoaG9#p_Y2@-gpY_=XZo#t7xF~8kbjX*7&l{Q<~m6gq)H%@EJq3I?{kkIdW zgF(y8GZ&rKpxiGt0<~~X(_XvjquH6f{h^+fB+fXTiN`-jik|BOWZ9uS@+ZT-o6AF; z*4bm#BubEopq=LNvH(;f6OGy=6oAC44NXpc&lg^8E@lE{(^oz}PU z4v7*Z+SZK}%lral4Ud#WEP0herl0GyZiUs+2-I?aYKlA_0W$mjmh_Y;L85rteZr%kzdYQ;MmBQoE-WkkNksL& z8i86RPwo|^+WSknfuGtUZ%RoI+CTbd9V$_RguUe+QSOVMbX)#~h?EQdkTYA-J%2t@ zBT(yuwOhQ5^^;vgKM^tMP8Ip29<5is{+1{~qT9S(!Y#m0?q2hb2#=?BIaoNYyUizS z1Zq9lwo{yI>L8i88*LpO_ow4b-ya*c?{=pHh0BB%9Y z#Vm;uB(^TvETR|s$}Jn2xUs&coc_bpn)E^^P-~d~X3;IkSJofE#E71~<%zGJR{4p6 z5+z9VnXpOJuH!57oWDfG)TI4n=8vA%Kl5g51ZrI`y-{?&F;%u}8B2ukr-3r|m8X>} zYK}y$uU9vSHHW9larMp#ov0EtOkN>xsn@Hy5+z8i6#s~94X4V_yZ$8`je3ui)_qUQ zV_uL(pw^#f){6{9r^+4GP7vW;Y^;pE;c4|*G*6-giI&UPi6=*VWN1;2Yv0xUTRyw$ zX(jrs6R5R$)jAP=)JJ|P%|yN62{QVUr?t7$e2EeylK;0>q?+#|6F=cdczM5xatnEu z!^X{*s8#FpT2Y9!ay>gFbRu>CNwUWUPixDP`4S~alsdguwDt3mpS!b-vMDFap!1&A zxJ^2NT3^Sk6*C9<$Yuo&60xSdr_3AcX&pT|U!nww6p7Y~vGsjqmxcR@DB9L3cc1mN zx;@hg)GB;)jc921krQ$;5!Ba9z9TREVCn@DB}m*azeaRR<|Fr?;^^-586r-3T2pfA z1Zp*FxJKMh?IZum5=F%9zXRp^XirKR1j^h;mWq*oJ7t;VAp*Vr7iX7>Lr$mMTsDM= znu7!7Y$DD@=>%#ey1i8R`8#F79!#|A6DXZT%sCY(QG!Iw{iS0345u74oQbO)1LY7R zw%pMP)Ozq`saU?qDYNZmVr%O_*^`K8&jTe&kO=>@RFq%nlts2OVbl+ljfp6qbhbvI z*73|CV&6KaOyeF(#91Ry)*#|!=GhV@NOZ{?B35p8%BAI*s8cLZW+fs^4V^%(1r0;Q z`=d_zem@glIRj;4BA&OHEm49*#=0RQ+hM27xPyt=wm^9`%G0_(K_^hF`=k(If9#Yu zM=vAd#Isq_B4Y27*%Bp4c+L(Hnch3)w_QvWw`NISA_m{q3DkOZH$=S6>?OBeT24gQ zIy2-3%hM{pE=V@2vRnk5@{;^)bZoU;)V$;+Cze|$jyzr_g7$dHZO7LT@nh92*_UiA zN;OB~ai3nHGs);BAMIT(bQ?kAX2~iuAf3N|0FUwoJ?&;UxnPa(3H4V5STsBK$9%K&>@7mx<0} zy=2a$tBJVOW~Q7+#LG={B}$M;(RP`r=kF!Q9%15WiJ3Bxh)tJt0=244Stecvd&vj= z!-;tR-wZjOh$6{@BubDNwVdYD3NP9H7!y4Y&rmk5RMiR8(q~DIl`~`z*_hucNTLLZ z>ra-6{WP!Y{mb*}*}xfc84=g~bpo|;hT3cyVyDSs2R*II7v{_QMZ-jt^p>w5ZxfBJ zF!AiUw|w|!hv@r0Obq_vEj`J@wAmhi@|80Vd0L@K7D$vJ@$T6wF{arRIsQB6MLSLQ zmIF`HDq3!V#1$D=>ap9x#ei#5NeZ@chltwy62wvf+Vguc%OMa`S8h0)}6PWY$WraE;G@}kfHQEwbCR=ka*u` zg}6}GTka<>jdry})8$}Zucqn*YPtEZ5R+mzJ>uTH0CUyg#176U-rHWm zq`JWym&zwb)K6ic1c_X+HV5Y{YlRgiqVwZum9u>N`kfsK)T-Myk%KdyQ*xIeB2XSw zdC?8gA$F7?@uB!Nl`o}oD^*|fxo=k)$g_2eY2)~`FpY!jEt67C)5c`8-LAe_Rb|{3 zmoo6&k=VG|-N6-_n|(s)tY+6*uPP?rzL(Po)LMK#lY=WJqYs1=(Q5H(RWW(dtBQdV zBr4U&?BI&YmAPw)xG{W%s+g>NTU8@aYr8F*gX=h}H|`+9mT{S?m{bq1W}w!sLs=bM zB^e&I-PDPapBAf%$xM5710_gY&!5A=)ul2yB-!}$Yp|*=-7csTsFkR6P6yYfB7>ue zSp6|bRj_8CsAix9iKi2DIk>V_Wz-QO+D@ONvgcV^=mcs-M(1*HzP;4UqeSG%a8Xqh zi%g$w$Etqsu{Bkm(lfGx#Et@+ty294s%qIi`{x=cL83vUI*QJhX*bz;`u3u#jF$a4 z)Q$vdK_!-mV4qp4Zt!VPRRhl#$1%M_9#xyT>V1lc$A8aIwTYZtsu(CiBK5^Qs{S$i z_!%N9W~6IC^^aAJDr*F4^?#mM)mYAsyFkR|!oI4;5_P(wff6KYR>-gFI5mrKUxt6L zDXNY$u4x60K&`eu`Bkkb^RVkg#DtDhwIbiJG6qVJc<`vOsz>d){ECPsyN9TH)csK< zGy=7HW+|d-ULMZZL>brNIY9!LREP0A4x2!5;v>9st*!IhtpQ<-=Z+ecM?c9$w@q6CS9tqVK2@>9M3 z3nDg+8Kf#dF_(&K1Zw$|Dd^zJPaS!Wh#Xx;smjlcWTj1%AYm>l;NZ&7rzUrZxRb?G zReoHV|Ii53YWgm(gDXGTf-eveGG~ga{M>I@!9=aoH}X2T@>8|-1w$wPD(SB(KkKVk zHc^7akHWbfT={w4@fg`i+hB&O{M`M!ibkMTXICxkwmooI8Rl6ipS~%YOSA=-NBU~N0SI5j*VZWDnD;)RX0(B#M*6H9d1qn`YNgzq$-$MMs4U?`#Con)m7g8ss+cH2;<?vkC;P}^8i87mSEhDwHxY$mcB;xx=*}W0N|3nyJ*9&yKlf{nA;NZf zx2pWyTv9+IQ0vRf6b`QZ#HQ;*gvhi{Ren-u$YY{biZLl1T>07irn{jNho`$#v{dECwmp@J5+nk8 zC3bM-r$pxpL_F;mr7Az-VRDT?t+ss=JGk;Qwl5QBJfl_R=fcp$CQ6V<)Gd*ND?h#4 zmLS6SdbFzioIh$aQ7bQLapkAUpb~~o;upWshAbK_XkxZ>sWh=TQbCN=+kzDnH-+?rQ{Ub?g64 zRelz}cPFA#XpE}-tQzjSxAcT-s`8V!$M$NNzbL)@nyUP?h)z_Up26@KRr$%D_KilM zR-fb7ROKg8j|xOg`X@$JepYA6u@5CkG`Mn2RetWStW8A7))-a!8T_QSMxfT>+}Bm* zr}PnDBL3JJqbffw{JZQ!2@<`tTvwH!O3~g#6n4d^%1?BwX&QlAr-oivm7kdI+li0W_|_77rIwg{9U zQT@dYRr#s3vNjQEKgFoZ&yE5f8i87qKi*W8pD~AhiAYoCn5z6_YgWv4S3FdepO4FG z+Xu~ms471_);6>+Y4Jc+e#&;OKwbAA5*<^OpUh1t-j8ex`B2@(xv-c^;K zM^+-bR{qtGsmjli{x>uNwLTrXt13Us4<#ewsBuhHesWZN6M+&Ww)}lhRett-bSI*& zIHsyHQx@4=NTAlSRQFZo=VgZ6L?j`CD?fGqadV*riL8C^tICgOxq?L0uMuaX^Ko~L zKrMZi9H@FsRenCZXLq3liAk*G#rROP2*_)#8t&ZDaGv$M=UE|efqF6jqV`5Bbv zE)lV552?ye@yj<{xFX|9Jty!#Rr%R{IVG*syM`T7m7jCFF1t{I#JG?zs`69sKr$lg z-94l#KldHyGy=5_?)t1MKUZZUA_}!StSUdN7oBjS1c}QTKdH*kK>K?dhsUMEs`3*w zmOk=>&5x+cPu-?27fO&20q<4ir^~AwWWzjlL{)xrJ=>}gsD)SEW^>PfOjUkL zFRbXo6$kHg^~;Y`B9&rP1$=*Ur3`5EK3SR+sipB0Pe;OJf^QWWX`9|-65lz?3`hh>IMF1dv3>s;85Y)D?qL-n%VI-O_*3ixs2_f zxRcx-_QqU2#c9>A*Il9ni94x-#fxixazrmTBF=A_XZUzIt;>InmfI&>HW#!SE6-&K z6I*VqFh4#XE(<*!D*T=`SHDvo;BP=&x!+WrrEaS0EyLyYw;g4ot&?T-@w>$4C8Oo* zd0ukV^k`AU%R}-wW_TH6H5a#be1 zgQ@-p?q^}n^(n3nus!S`eJxRYjuGO;2il~cBwcETJ{YO9)8-VOhu znb>0YIx`dX4z>>1C5AOUWi;qFNe=9PP!`E%8GL=V#BP>jGPPH~f7IGRHioRg@ltxUHZ&_^*_$s2?sk|6Vh?^k?z8 zgpYhV`<=11?N`C~yy1hl#&hdG!S}rQ_0Kfh>&#mwpHkQ4p!OAHm)61Re8ZfL#mVE# z1>eDt2F1kk^ee@_t#miblq4J7FVB$~o6>s|TXvZBS8Nn}%Ka_NcfMd$coizfFBl_N z?z&=p&O2INtK%OAlZ^&VN63~wPU};jr6x*{s5oq}BDy}yPwPOc-6ozd zj$^-D21mKvlqqUmkj`pJn#J;v;k35&3NcZFL{Nc34t{D&ZRYIx$c&R^$@2m zfm(yc=XdZk|DY6q880H$NmaY6-!h$v*B$T2rv*jS{g|A5ED;s1y^Og0!)ck*7et&` zQ9|9d2`3MWet#EsW(P{Yve08A&iDE_bC>#A- zao5vX;&du3(gg%M0d$lIglD0)L-WaaWEN|4aU@po)3Wg~1ypbH7q zy49?jvXTF(KiTlwX_#*GKBvELpbI5P;B})|ZS6|w`IP$lw$+q4<9LtK#x#Swz zoYs<>i`z<+AVKSjh+kKTh|RiCrlK|RWWKr@fm&goZI1n?{iIhu?iRVVEl7^fPVXo# zt|(E0#DOQ@#q5RCWN7a>L{z>oRvzr^wEp$Zp%JJxsbgBlj>Q4ec*UJgww(Rt(a}!p zQvYNUB}gQrOls=CsMlo)_b2Y?R!6p2Lhlugd}<HHlSK|M=(Gm9f<+PIwlQ-0DEZ}; zpIUEu-KF(c?y{9r#FIVChrJb+1I0wqZBa~SV^kd5*a+sMZB45m%9N+VDUuZYdI)V0Ta z-Nb2y2hS0_Z}9#>`-s{%c>kbXLE8FFHF)1mQg;;DINWxXS)cZgmdS<-l<-cIK^v?YoZC_&D+t zWMsp8@p7{d-N6EPcWMM`t+<;*3@1Oh<*U?0WcfG1%$&k$E&jAwpcZ+_27AlwHS5HJ zT(it|_37=JGYbStkeL7G59ROvajyW`II>`cS+}{HsFr6{5_c*-7}kKXdk?H^@K*CR>YyH%0~3oLPR_ZnqvNU#c9>+{>A`L zKay87Ue#z7iX44WDjVg>lqRBb>yBo#`%WvS;VAb0u-@vE=qX~#oDVoUN=ztW|@tb#Bu<`uPU9}e-@HlE7dGbkA zDd{7-t$Aw>&i+xHrx>@>aqi@Zx)Ci8obj}3kM}fCf<(h{HU~#V4LZ*xqEI?NS-F|h z^17BnU{o}{L$LDnhr4CeA|%Q{Zkr$tdaH5P#3u&EPDs!$CwRA`U5{*>D%4S)oaeMQ zp4+Dps0FbB5k=QHWr?Bm1%W>g87M&_Rkp?ANb@n$ZytA^EpnSJ54NB;++Od}2-L!> zPWNN(TIrtNY5nv5ly*Ompx9RJyBzD*ol>a>Qw5EPKs1c}zaU#vD!z*Naind=D ztSbt>U#{Y)E**=bUn)CvJ0N(E%H%zPo{!AeR?v6a=zW|d?F34|_eGDBh_Z#($ZE7l zB|XwsBfyj8*k8qioC~noQWpr7!zl9F<>Mhxg2b8WiB;rPuXzv=qZJkXrcZ;-+`Qrm*%O^Wk&V<)?%7_p#w}T-MtaMtn58gI7o01?wVqc`Y zgCqR|d-f3Vb!Zv6cRQ_Di}z~;YJopT#DzqsOn1sNObi@upacns$cT7&AzF2RhHPt~ z5vT=zA`$Icq;hd|clyYy>JZDw#>1Qq`?hKS5p^pP1NIMd!1+ggEXtTYd>U)jMw#SYVB=EYChg`^#cPTT`^-hR^ zs|>C_5UbM@<+vneDIx;v?8W?rw!*Fb_dn&GKU~6nmW!RMxJ&ogS z@ujkJRmx0^T4tcup3-R@ykDJYnOo{a*j6vOhvKMK?PeJ$L898k{3?#xU$idSs9wH? z9J$A7?HgWSBTy^HqVkTT8>UOqp)?Wu=arTxsH1W1fW`(&kcbK@qT;A7>zWg>yzw0~ zDR~(w`hT}0fm%4nXqJ5Zq2j28jq(^MK>~6dWTVKB7iN;%)JIl0pGKe-&M})UQ|&NO zo7StCJgo%9*0eV~O}H(>4+K+0#nWEE{|KK?3vpl-XV~ zN3?G3v^wsatr4ijQAB*^j%?VvdyB#JeTJSn1{o+pqUN1Kk-T5Ek4;ZRuG92IJj#BQ zDl$qVP-|$h0+F+cC>KCD^-0Wf$2_a3{@wK9h`#C2 zPDYB)PD>0uY)1(adM?~_vl|b{Z+}rLTq98H-pII4U{0k z@e{{U6g3fX=8rnYeX>#OuctMd@?7D0QN|4a6RfiwR#Gos*?$%GQ z5vYZ^ew!`ZfHtDkDyQ{ye;WfONZ`Gpt+u+qSV!H4-adK7h|*7G>77$$)y(8kPz(~E zNt52*86r6&ynHL?OM1^7Ahyuj9+WnTKnW7;;m7C5h{&46A<~hj-?j7^0}0gPm@q!$ zMZ~d6=|pkLp6`6@E7;rPwS>Gs$-XqNCFChfPxs_%WtiHX??;E_kB!c>mTbD#L!bnS zuSqYdT9IM)CgM#ahp0`@;2&j|39Rs7<%fMYeg?^xqlo3t=t3fvvgb9^`w5gF@ubWS z$=B-aV~)I>!x9S*is+M_@1qf@#oiu2gXH585gF}a9HW_dq4@#h!;6KIXI#&}^F?yS zhkuio7Rk>GKR5jR&{t^5cVi#!Vxm(9N|0dxko`pR>xf|gko`pR7X?a?(9h~_x{JoJ z^-e4DX(f$7t=O@9WX_b+yJAGVtK(xoMbG(PKouXas5<&9z?HXyzMV5*$l&-GE|idZM~{tTa~AUOOq=)Cf)M z&UurwgSV4^C&J3H$*4v9dC$M2gbgG}u-D3U1M)nHNVY53NKSsqAZwjQpw|BCDP+!f z{xYkTkFM1pH$x5IQci2m*X05wNU#UXs~!2LL|l08Wt^t?+_%XzjXi~;vqqp6&U|{)g8W>r8<5{?pacot|9<5YcRa{$ ze51O-l$@_L0=01F+iX=D^c92X9p030!X?(_x%SL+iEBo#jKQ+5r?+hM-(Eo-jX&Co z5tIWsU4JQ7*|n-ZRNRS}{$QjiM(^+r%e_+KvCzieLcy}0kGD);ejgD9uKg*d5K(SYdP(MTPOs$`R zGW2GAhFYJK z7?1nYUVC}6LZ9a_!@-Uxb*)py#Eh?) z;7Y_52s6H#LBy!!D~%bnUftSas%RlW0;?UaF+|Kbve76>>s9%wQ5pej7gr$6_-Y0b zkNh?p?a0e$)NTj&68w_jQ-TEdg0KfbULg^Q+ICPLfEZp=BTx&T zU?Rru{a|M=V^YS4CQ6WiJ(!3>8QqK++6VI&J*5$-1uFv)C$BB6!TWj3-7g|w_i|AE zU+w2y$%NgGh*6H$_JXvZKTk2zLSSI8-j$}!i-c9Gug>;J_>0=00C(br)PO;9^0SKd*A1o+ov z!+q?ZhK({svuEGZ2-LzkM&I74v|Mzg`%$dU6_cyr@$~_N`^PwQLw=nBc?N^twe;H} zn$ox18kW0iq6CRTd3VW)vEyay53xjipS?|F`{ZdAd>)|@s0CROCPq&aHj34n3`wJ6 zG+uWpW)mEv@vcS@nAlOXql(q`4*NmGA7^{1yicjxcTAKZ0eK%Hw&kuWmQkHEYfy~I z5fJ+ybe#mpO!0Yfj74egK1|YAl%dFLgr^PTSB>DPj-xw@<%l@YW}4_$$7z*4noA>4 zOI~^^OYNO1oz{a=YfV_r)j0F*g^6V8eA9z~z zbM7+nin903I~n=bm_eeE?|CFe8S=ujuLw8sx+B5fH+xRxH52imixhilSF5%rNFz`S zvPMK)xDX}!(607)dN}rla>eZDaoPLkrbiExu8g-bv4S8i87V+1(?(HcylD zrk)|9v}2Q~L>|ETYGEcykYMjSKA%k2YWK@0y0QMWSyAO&O2wJ ziisnTKrN1p<2yl#=sP^tY@L_>vPx6xCu?!b_>uK5nWN(jjtvc7OSmEjJ(onJzJAJl z^3v1ln{o$sV`{|t9A}Jq`6kIzZTXx1u~XNXAv8sf}fH2h?R&WnP->}Z_*cmR+}1uTF^N{>u%cuE6wLr6Mh=7U!nvFev;zjTC#ES zb*LFm&quOi(HenT{9MFGsYD!Jno2&PT)6Wyy$wriVSN5d@LCw3zY6=k+ON70 zQS|5)RX-2j&_|*K3FzJ-V)M;0W=_f{{xSES2^Dt-^iMc=jf~G4(a51^!bAxY&>2Al z^h{_3YC&%U5zsSXq67)(j3A;x;Y{j#0Bf^KW z0y~=NjgeQ?u7=cCQ6WidK=A>$$sVKmq_x+WHF6EEshD|`^AZPRl2(Y1QCZN5gJ7IboujVqg_bls!=cHcWL zeE$ROtsWu8{mJ7c)rsiKU&Tl5ktN7a%ZlBwuDmL%`X8AzZOcJvl`l zyy9tPD?C=~_dx>tizwQ@b5LfXuOZeIi!=hY$aDJHYh<%6t58GE-s`l!oGYVMs>y#) zeZic~gPBj)tHs>zvJCkpg&Q~4s^LhGhod@|Ip0WMfjSu=tMsA2|8dn@BTx%wK3%H; zXG3LIdIme}^VRwQkf`4`orAm37Bu2o>c%5`rKJ1eU&l`)Pz$>jY__Ty#!7on^7=-( zv*)c=HLd_)Zwz+B*lf>p&z4WgFUkM4veqYq1a{fb_W*7N$`x5C`_Z6|Mxa)*kY|Ed zA6Kt6bglM(S|n%EINsFjEKq_(HOkoWTJrTezxlFq1O1&Cik<(?JVc-bi4P6-srRPd zmE?+IuI3>!lDb&$UG6DRf&_LX(V94Vv0OvX`Lk*xGy=88R{KZn&+8@A4xCFisui0j zS5d}m`<_7pB}jxd4p7fvSlAFEPSlwt&AXJpigaoOYBhi7tDbZEKM{-b`N)qHL7oow z5-33;-G|CoZMLu?gJf^IA5{}A)(F(1Y^{jTqp*$oz2qCZ zR*M%e7AQdiJJ)ICvZriCodbDm=mcu%y`10e?PM4c_lkuIlpuk<_4JkhSst?cH%}|) z^~D;2TG-b~bJt^@db?&urq?yV)8i_lNT?!G#zJuXK^eA4>dbsx$~^sw{w~1x#aeGI zYJtZ|#K0cw%^Jt3b6`z6t(OxCe*1yrD0=6Ci29wLn{{Y~8*;g}MxYkze<>YZ3bu%YjrmR6(H-Qo)z&j&i!271=7V>>^hP2ZN z)MB3}J`YQT{c10>H~Bt+bA1F#kiZ^s`YulA`!y2L&UtRh9#O}#ski=WOxsB_uGSjf zUukcY6|a}F^UhhI#4h^xW=UQ~6riu;-`!>kUGj^_GpM`0OUX&H$f;vQOuKx{<)Fyx z+UxVxvmk(thF+mHy2KrMat%s7_OI6$3% z@0#q_<`ojjV~d;r{p%&$xIG{nLoV#HN6-paxN@XM=vu$#7`+RSK8tYBZ2xNX6j+Og z%xxs^vAoyP&Pp~eq%AN0A}^!e*=YhLNI;&N2xpoOBAP~?Klu`kKrP;td6v*#OvIe{ zT==fKs{~4rz;}D8->1M}@tJCO9j2|&2-M)dy3r4;Lswg8PrT zhD2S*L<~H{KGS-Q7-v@~0 z3N$;h;Tqx?%GuXs!s79cc{=ReW^C2SlEsE~ebrmQ< z0y{S8yUruRMc(6{R`&y4Gy=8wT{zAyab=ml$?;*WG2pq=dKFyX;N3U=eOJstYrS#w z&E=9dar``Wg*}|Dy&I05ReCp7I%ODoFLex9?{Che?v z?~Z?yQ9DC=r(vIms6hMq&c?5`9xo*LZ4}Pd(!NeMl6@a4&JUpXiVma~c)Z%v*IdjKVE!qcHED?!l z?v6>+PM`#dL`hG{Dgi!njvM#s&!E2{v4Xxi@E~Gs{& z9ZP?EdD{|=KrQb2xJ&Aa^vxZntG0xTChbBsp;QmUEamdFbBI%G`q78X{x$|XG zotFs`B-q=F&#(~To^6`wXQy|5GM7+(V1fh*y_Q+n0&u^n7H=+Dju)i#^KtyblqvH&zLg zB9^dRU6ikxAVGq?J@)#@VvY z`glLF)12A(H5;un54=Glz)#c&)B^8}h|~|`{KN^3d?ZScI7)uvUGfu4RP`s~;PwD< zoZj><)O(yppq74h+YJd4g~^ATv~Zkut&m_3pLaF#>&Zs9R|`cWTB+SB$Arg1Eq#`J zIQQ5%7)D*i6RTp~D*h^w>iM$&ks?5(O zDpG!TX1U=Sfm#sn&^S`fDleK*cEte4?kg8Bdk zg=qw8@zXNI!(VOzS84m8} z>d`L=5R|1b&tOIg1pKtK+Fh|6o57_;aZJY$d62-KQ+r?}bg zq?bIC`T-GnOouU%Jb-HZBP2?YfE)l39pfYVER`cQLf48a8lPt(0hC`#NI=es zh`Wj7vQZninHqsw9v!;dvrslF$;o3xTySo1WurB*R7{ja2@;g0FygZxL?k*QeH zjeR(NGn?KrZ53#Gab`Q&8xtjv-~a9FdjrDnntRFX%XHqZ{J?}`K_1`1-X8mQ{DwLC z?Tx;f(Nmn3d(ke+4@{6Cp?|M$=3lwx;f_wLeVTC^fm)OURFyccyV2kOm|a{}EAO=S zCYr&uxt|gwxH~WY9V|Mlo1GnU7rp<{Jk1=9KrNpftHoLRUdG(s^i5Vzd-+^$D`*HU6t_<-R(k z2l>?3do0rk)PgS_5dqac2^Bu9;|Zv-5z&sSeIu#b_c_^gi4yYR5~_$IPs~h_W$I+< zIe#e;DU*zn)5v?xe>YGgPz%RL@yGemav{|RyYvdy#(@O;Zt>Y#va#@eKRJfh-D+i* zXas8McW|Z{F2B(oED#i;-47%vx2$TyTmh!Py5Q<5+tVyrRc*0Gpcc+I>gCKdTfWRp z&-sEn+V{xV`-;z538)W~jTMO(%Rc1ET9u`O z_+f*;hZ5q`}`w-E=9^$n)}s`uCIhqA0_XcYA)L@)vqPDpMv+f<*hHClp<6 z;#MNwhbJ@G#=WAK?RYHITA%HmvJo<1H4&92mNlx8jqo&y4U`~pz3MGxV{fvBMAV<< zu59=w*=t7vwR|2Y7CgTBy{8c|;?fK?a%ayx#*@n3ly(2EZo+x0xjJr(b)Su$SpwC+ zXShz=ziso~D0@{ps~-95Xc8pyPo1LZ{E^Sd#)WsAm5nZ~GHV2CU7Wi?+4zzBB@ufA zpV@ijJ^rae9?>re5?dFCDjWZ;zDmS@r%o#y6<)Y$1Zv@(rOHp*)avR!{!+%IL|cXsjnyRS}evh)3D6u>>g zqXRbA;E_L>+R;D>68Y9GxAUw#xFs18|K5C~Y<%}Dp%JJxu1GF*bw9jLOT^2pLS5Y^ zgWDP?L1L9pIyLepeG(I~?odN@b*t|wtP!Y%vxmMqlz&c~jrPs7d4)v!icORa=hQEB zbq}QpxAV7(Z$>xL2-LzkMwy9eXZG<-Y_&}Px-nkq%_(cS_*%6NOHSh$c%g6v-;cR> zN*O3YqHg+DF1{Zf=4K>fM5X5ud_U3$chCsby6C#0Y}o20C1Tt7cgjZ0m=Xp`ka#!# zjk3}0JNH25JJ7|&HlEFCtr4hIsYDr*$I&4TKZ9pxHgfSelC3Ljpah9gQw)>G@w9Jh zBE~HWcJX?ZWn@#0KrQ&DG~JJ&ZBvvD|3C8?C_w_gHcd9*`_vkNTJWuEvT<gmKN&aM{iFUp-!py}Ko&fs&T8pNH%)?sZTLP#`}^_V zsB+7j!Q@%ewNxREK&|3QEoI}3%_3rFr5DOZrc)!BTDP!@Z&+52?cQ!XRtWU1~{bv24L>#Ks(B#?vwZuj{N|0F4_oJc< zzUTS<$eByoxbbYBMxa*x{@>JD-CnnVh<2lDnLMxVmOXAq2@?GdJyJFXjSnCq!+LjR zW8#KA8i87Ko;_AJob&lFP6cMJsB8o^_-IE761#6*P&TTi;$7{);bh82>I;`N0=4w3 zTdiUtW#iP_^fY&WU3VnTevDQ&rZqFkMhDMa>gwh`kX<8COS`kS`*lmJv*Nni*Si_j zomw+Kwaa*sT=H}G+rLx&qfc}vlXrs~+dfnW!j443@3DDpMC|r0rEIiL_E(MnjbN=@ zu^E)@tM=1GxF6}DMqc{Z?HVY-<90}yOr7DR1{M)3eTyp_e&f?>$3iWfq4d3sXRVcu zVddIua~Fxu^%E%@r61*?t6O?`GqVbf{FujVjX*7&$G@Hrhx;TK%ytvBOgJl(zC-`Z zh6^P~fIT9jG8I)LH(yuQ2-JdW=%Q#MXInM$yE|*UP=W+p1tMlQE~#u>EPo;b3Dkl+ zOGI?{j><;r@B1Q9f&|=6B4A$aLjtuDe)Fu<)+-mRY9`EZ6P_EoR`7gi5+vYRA;Rm! zH?<~yUh>F=$3iW5{)rg>cTqL+M#a;ZC_w_AU?My(rB+vW=F6ilBv1?1F(TY~MCC%rOCQ6Wi z*oTN46H3_GlNtM0JB>gsh%AV($`rKo$cuC?W}*ZMh<%8-6E;oRNb|b6MxYkNA~f4q zR~eyf#P%v+q67(uipU1UI2wUk5aW;yh|f)wAOZ0?*?{<5BTx(CXtH5uxu-^+xI=Xl zB}hP2OhmcaQEKEb_NOyZf&|3vM64^3!r(iYWL8OyKrM))iLigUrEJvck=R5D5)ii& z0r9y;pccgEL_prhg%TtnS3?BkeM}@!3-U8Wd>m0qjXb?uauX#;Kz@eL>O*RS=kEI@ zM_njE0IEbj7 zt&qA_bH8-e2-I@8rB~PLV69X{jJ?!Sjr{fU(RP#|@w9gm!S_7(_iuKJASV=8Hk#B+ zrxBME6s(q9+1MN7BqFPKDP`kb?XfkGK&>K0GbtN! z-fQ~qos^Azj-oYCf&~A~s)Q(vdW7?qRyHQNt=NYIYJqL?sk3B^v+=R^*a(y$0rrTf z*}9~%@p{2AjX*89>L%5lBigBPJULg$g%Tv-x{-~8tB={M)4RwEZj?Ze%z$qY3h=w= zo}d3W*tm6r@}jNj+o8XFHI3Nj$g94W5t6KqpiZa$ua%8}ZMii9wZNYz8`G|CRyNLm zkHXl%K%z>;O3KEymu1ODjy|aj9!Kw1X*B}1z@H}@7e*gcHX`2tgRy~uM6neOl#P*n zvy+Wl1#&7Ihn{@I*uX$7hych&(WV!b4ac+~6D3IC7es8fDZ7d(8?k%NU~FKZ7Q_Z* zBQnoJWn(~w5hhBI(7#5K>173FL(E%;v4MeF5bu(W<6GY<8%uXp#TZ#5;0w4!gofLd zjZFn6U?hy+$u%H)rKdLArLW3{nDrSWVLKl8a=CHpe#jl=$;Rn@9?Hho#rZS>wIF&W z8$GKh51c{S7Cny`I(hMWwY?gY;#`yo?>dfP8uKqthh!7PaNk!R(QkI$f zIrk#%i}Y2B5T%9ok_a=lj3s2rSjU=FmMq2G&zYfYgD5G=)}|s9C0hMnuhZx1b$)-< z!~6Z5Gk50R&)j=n=lOXr7^{@3XTK^8X;lF8p_mXNvFC zU7VzL$eqYux+A|2#sw(| zkC4|q-XTx8rkY!0dC?zq2Qt(yxh7(bnHR2iYiu}gL7){S>$TjQZU+XJmAA%A_a z#`>|l-QSN!!)kbhcIhW??3c{%@7B1g*EfMyl#o0BVU21RFLP^*?0A(&XqSHS#>~m` zH@G#%?fE&-iV||qL#(l_dbV5Rig(jJLc8>nH}2fB{2aGNx3B*Qw4#Jeki;6V4ruDu zXy2=aM`)LR^2Q#(`!iy^Cf@o^n$e09wH{rXE~!%6N@!Ua*Z!n z7cp8<;_tgE1YF~S?!2qR@RMuuxWGJdV@%jdW|2za-rwv`aq~V-Gp( z)W?Rk6*QhKEYjA6nO~QRa?xtg&oek&wTS@vSR* zgm&p?Tx8pSu5xR{Z+llyS%gY7PsH6CoqoLnYm^;Q-mOu6|5+ZPUHTapCsNE-w?@C> zxq8YXRKlN3`o%TX-5MR6AJ9`4-uzPeWQl8g-^u&k8Z8G8)lZ`yq0@X|3C(Qa)>zfo z>SxYSyX2E4*0_565x2(Et=a`zQ9`Hr;KWw(gj=IZ#_jrfP$!6n`e_NDoy(+IzCONh zZ1wYCQf7{Z&vonLejgiW9l^V$9R=69HJ0u8T0ajawM#$4VM6!uB5sXmpC}&FiV~}8 zzU0>U_Y>r#yzAW>O)Ae!S3I?Atxc=Xt)qQs_)6au}67q8cab1^|ZjBXp)$$1KlHV+d=}-Oce&>T$Rt&YGg#6Ay zd{Q~)*2r(0l~h8zDD-rxjfX05_0Xr8gJJw<<`g&H_XnMzQp;nZTcLN}@HazIo z_`Zkn2jTcA$ z8EQodc@Gbw#eF^88iNl79-&?GNe09{PqcJvy!qiV&1=0ou*+u=5Lwy7?8}{C-j`g< zsYdQjj-0OgPtHVB@yX}yIgR$}j@#&{OQlyn5AhYn)zmgGXqWUQw}=I;5prqyDA6tX7op&$rM0 zpqyKy&U5#9gm&o_6=!SfUE$Wqsxj2NTc{HL$^Okj1v{%nX2IU~hI@o|>77b(3hCUd zY#+Fm`;X7|?qRBgngqDlBxXoA?U7l~_xAqouFt7Eonn$eYI3vjuG(qMwyY0}_sJ|M zlJT5=cG6kTM(<9G`}<6s6P_H4E5q(C9^rM#RU1jeON+v__ro!H7kA{9iW2^vZZBN^ zT*&9{?wkQ0p|#2Ur+-0jvlJ@G-0&@SI5pL|b!w?@q) z*L!Zb60(1ZH4Z(U?$)^Jrk6ZIyZjj=M^}}1YuxbRz23wSC1n2+Yuq>UEJysatgA<8 zm;Vmnq1Juedxr1c{5I5z60#?Y-}(8aXSw$!br)Rg5!&UyFL~*X#YvtV__}EY-AOe{ z$muPtF?H34?%Y!2bqSBqE;&;M!jv6o9_p4^u)6QzQ180`+s&`oGHTLc1hy!5WoY<+$h7xf4cc664KH@bBExFl(S&5G& z&bf775PiDcz<{X`<;eB2COJwoWE!)ZcK2`^1JVLwVIuGK} zyR+QyW9z}IjaHP9zfmBT9JfV@%+*@ZjFZNj~T5fA%CMl?0xW3x5lO?@AL@mlIuK(dvsf6C`55Dt{e+9>2VV}Et zFy{@p87#cUFV8P)2VULF_8u@nr*`4HTKUR1LE`buf?1}ok-uslA=AJ>$doaU&@TDp z4Pw~sYl7Oif62ZoL-iB3n{OXYFS8vs?Ft_m-P_J6F(1TVCnp9+`(c*pC%rvFyX5^N zhj$A@5{C zF*^0sZkjSu&;k3F&$ z#C7F1gxQ#Px8T`9hPyY>o_bK_vJszQ5@`)bAt?#ATINtm0za~>BgYfl{`s{4wlQ)QxGmBe3cmJ;1 z)g!b^_8&mJlTpv|dG*o3K}IV|$PNOCZ`xeu)|isl#v`;#_EA7Qn0Av}$zAU?FhPQ_n?J$QcUGzYxjab0``_>&#lfBl->j#t#TJ?4a3Q9_d@ zO!K&XvU}tmA9}(gv`eNV1Zin4dkl0x-PgaX>dl)_LK8FGMKGM|)=0Krk<_oHT{`6f zcli4RcbLVq{kiVNlUh+ilRtR$fBn10mp6BhDWP4mHr`(?dHCNoMz&uO(~1(Z9^O-z zIcJJ{99sw77AT=z@>9ne&1z=3$8lcIyY)BaC9d*w1F^0P?xTc9eonQK9-&>bw+!OC z<)>U?GGTBP-H-M%VaYi`d_S$3OR(xy7$4KGrCpLVg6LDdmOER!uTB%qAVVemld=c8 zwsB``8ypzy5!xl^p0UQ9mmaY@e;ZKn=Y?ZTy_t*5Z#hG4m-Tz>n70<2hdvx?-)i%v zT{G_u^JC#)YlDq=eH{Mk8QTPRO5gj%Sfdps7S5S(ZtpPI*2?E!gMTLUvmx#Y`1{Y} zJwm&t{4(Es^y*;y?yhwp{&&?7TMPFJyX%~BMk`7*UpUotc{J1FzaTod>}_18+VQzG{k5{iDhZa&BRNG*{+G7K)lnX zm3a@dmM?gOc6HqLp2@77ZO>}? z7l^G_HnO|#$}IR{(9=dMO58JRr5STuwyja~G>E%))VGi0J@tA2Jnj+N72m$n)M%e= zldDK{>E1uwh`WV8_Ut>s&I5&RM%C-ToSz?#+vX-0JpE^_{QK5ybN^mxA15L--FU=J zwc2<1@<1y}^!WQ1NB3@61;mAK4GuSBjjO_i9-&-WU$ znwK8%2<@uAE6;4-nr%1UT?|C#z^eAqXEF=2E8K6iqQvCcNi+7ZY(#LL~!x6cj9ET~g>yU~gg<>uy_E2a#$iw=|mQR#_N z_QYts1GxKokI=4V>+;RoshB2s0e`x0?k{Q|&dDsudBhm4DDmOye3Qr>ZcANA;(}AB z!&j!^o;5bzBeW~``vP;rr^D?-#mj(r{@UYV!`Cq{_1mkAR+LybZ;dH(#R&WHdFO$+ zp~*L4ttFWSt*@@_5!zMn=o*u3Fv32ONupzyZQ&bXX2G#PFEUzD;>fQbxaZZb-^+v8 ze0f25JtmoD?>pCMMTv*1tursp9bxB}stBU*8!N&gTQDfGe6e{iqj*V@Ezt%!5Z3$6+lR~`5Nc+_@iPSto$rIB{)%Y`5w zA2%xOhil2HtTzI^X6Uu#q33>Zzw_fW`5HWaq*VCMAIR07s~TuUiR9GN?s_%0D1YZC zJ5LJBVU1-k&+-WE8oc#)w+8-;?`q73a^X&_@kfbrfmW3Gy!bipG2y>hqfXPiD08$MAw{=kCacJuG~c;wqR zHMhCban||Ce*aj;V9_`w;&Z65BciQiyWV4t3h46;^Hql9*yTd{P!DXyZ=uP5<$ zpSZ0zDYM|GRmF@}l*njVDn4V_aNDjmi7#hgXU}^zvtY{4XM2QpRX$K6eo4#Ww%m`r z&*{MpH`}qpGYf9{t&Gu%61lBQ#2;%g++H(`#DPtB*?;=u6aDZC9-&=#cPbYDa9g$= zwkHq7RrT++n_mEN*+oXXYTQ&TzHLjktqG0IC#Fq#z@EZB^&i8k8LcR>{?@d3%ZIaV zowBR2#6<(H+ny$~pyiJ-kI=3@V~&|mZX0I5dx!HTcGkko4crg8Z}pZ&D@uG( z@h5Zl#l!5hUzdS6f6E~Id_!E}7Pa;W?OI;)sClf!F#F@1BxXJ{#5SsvSy1ftwRr*6ANCp$L}Vw<-jo8u}Wsa&13KM z2<`go`ESgQdN12ruPp&Fzu9p61@1f8?xX)1ttgRp;v3Vd38vM)N8;8JBkkE`GYhWo zbFW8e*QBHSP0jr{7c^!u*Z6j%ty~Ie#upuoSCOy#%R~FjcstbYtW2US?(E$g_vLKd zsTtiPiX0)sK^`Ds6*AKCO?S9MpMAx5R zwO`!nr|`Z*BW9U`gj3| z2Xn^T9hkj5u=Wc^D@shSwb2~fFxcLi`v!<2zmKdT5;~Jz=md@h4M&Cwot@i}Cq9_u-d}c3pgUow)*CEqYfs zCO0S3e)k87!$(Hj2S6;jYqZgd5;d1hGgnW_wDV4pxcaOy_7)Jq4L+e=Wy(!AtKP`8 zn=4EMv9-b&n*m~bFxqHEiK$mlH?tOH+K!i!sF*RvRswNdZJ*Gt6YozqCpKoL|MS>&KA34c_am`#${1S! zV$0!Ij8>HR8#9eAIFV@wj3LqUt1)&ch&ly6p-rdfZDqqmH;O+k$7{fg0w5}zbznt63Gk*yXdHErlK)?Nsr``tdFU75iw z)1gV09egW^{AFY9uXr4d>%C&MqJ+(#Wm>k(vL8G{V%Cpi?M@IM{5{GewCj$Uv(5Iq zvuuTBBtE?6Rl5qrfz_joR+JdMc8+=V=`1_7B!5=(o_p2K29Z77C$y`|S#wQ?7qaZ@ zRY?4_@Krk=#IFC1GFnmMg$;Af_1RhW>~(7BkD@rsdX-&DcgY4RF zB>G=B(f+x4K*7jKgFHgJ&MO_7Pu?D6XI3F`?D~l|xe50qziP12iV{;>TSiT3ji0}2MuA7ZqkM43MCnR8nXvP0JLXVndV)w-=8 zP*CZ`p&p@K`cua}=)N6ix8Qfa;MWmGuQ>X9Zasd1`R!De#nl39oPXtbdjYNt#j{5k zttj#S?zhZm4F}p256%RUGi1E&38HNgpU|#PJG^cBWel_>vq{|a(Rlkgh&%faH(F6* z)K?45xXuIZrawsRE;hlo#9xDqiaw!T4A-|FnaBj4V-cEIH4vT{qk$I-9U%OR7WQhFIV1x$X%v{>K~+V%Vg^Fk&+lRv!x#L=!z z113LhC(kunQR0hN=Z8#wuFa?bV%9Is0wzEEo|@?q+BNs>Wg(NFrD+#}NT1g{VDghz zeumMmr&ccwnf!dYu2Q~FjEbcPOn&N}nryV9M1zZL$mC~lwTrOESC^*;Onx5v>ot$i zuKd^5giL;lT*<^_%$DW>lb^XK#~H0C(e&93A(NjUU*aBe#Wu|YCO_>)jP(fZsy}LD z$mAz~4T+i~#>ANXTyp--;KxI!Lhc){|FS{;fc(am`>@?!NaS}Lv&a4Wygm&rhK+X zXxH}MpM^|*9yxL;h}9om6EOK%RAZ>oiV}&MdqO5ZiN@7H^uDcez~m>p>mZNNt_n}? z4VnD38%$#8>;?gopTgT}MIml!5Lr~YUHBB#iuF(yAtMtu?J zHAAl@l_sXUYf1N${0){I(>8<2kF9fOpcN(FIrNmfUcDFcdeyP8dj^xACtB?F2)`@s zbw00l&bbPNX;5+{lb_dT-5%f$0cR@zpWx$reQIkEQ*L`QkI7H&b(|&fAHn}mb>X`W zxW>PaV@YB6JSIQKD!RuZmH!B==YEF&K91HuRZBAYxhQK7AIBL&yYMq~|NifFx9-%{ zd3+pOuDOjr-7^&>^!J22{C$(1+>SMN*V^e3+NIA*>>AjwUK5*qetF2`XKwEO zMk`9x%smz``Pt>Ji5HZv88Z3#vTaw7(5`2O91EEIjIP8r-mPCNWb$)-$Ad;IN~GU# zG+^?x_AXxA3wPBCnfxs5)x#sS>pJ^wz~pCegUdmTEPiFk$PbwO+}M-v$m;B99y0m4^W=Ds(60Ecc>$B31%oPs_@za9$mC~J zpB$qVC8j*GG+^>G|D8%8K0V$%Wb)JY^i+?~u8y_e4w(F0eG7BvbMI*$GWn@HHP>iG ziAnMK0h6B=wfTPclF7|NCODXdG_Oxx(!1nKNs&@&Mvvlb=1N zEQrh7Ul}s_*>&p@qZK6%t{)mO`S~cDXIOroTsLI$)BgUY9-&>u+F<$+KK0%EK2!a} zx6}!l{48v_%xFc4%i0YJnEdQ2AW`|5+98vl*Eactc1>M9Fktd?a2AQ_%WH;Aey%87 zZnUDrfkdx>$k-{CO<_w@zeIF8`DB2KSTGfG1_%&kGcVqpG(o@6Nh{Kon-QJ zaohKeR+MOaZS8=`&(f+~qxp(Il1zTyLsp}Nc0JqR@_@-t<|ytOl$muR$>gU}Gx)#(TWn^%xaa+ z>-*V)AqE zW}ncmBkPN2F!_m{zYj#=<}X$;`C0pMq0x#GX={pPF!|Y9ghbsBisv!;*|ygww5wz1 z#u-e0<}W3&K9`gNzR9+<)8XYLpKt-r=U`I&i4eoCLe$!JB1?5k#HF!?FF;Y+M>N8{0XOn%ZX z@(Jx4-DznClb^eSuRx5hFf)(I&oftSGFnlh^UU`%nEbr3j6}bW-pOO~GqS!EK$yM8*qYK+OxrqTyMT=!yfJT?cnEX`gPNKu+a&C z%jeZI)v70%{4{Lr6WXQE(6qFP{bnSY{Oq5w(RA#vG{)qo^b0@RX4Bt~G5MK(*KvFA zyp1s?KXXnW#~RBUyqRS3Q>@BHqZK83l=&vc6;G}+T2bQq4~hp&etJ*)1H^&&CrKth*MH*^+O^vj37Gt> zUBPpfb91&NnfzSQcD>Px5|71B#F+eiUj7t_aU(xSGWlt_%O|wUf8?!iOD388ti5A{ z(TWlsf8G~k@?(b69=Q1Mk|dL#aGOtPm;Tf-)oRi;NhUw#s%oK%6>vaFWSS znf*8_fWRl5G&1-!^yYy9%me%&f*d&vm$4cX`fxJGHnALr0 zjLFZAK0jlPUL_|dnf%%-&+?vK&$T?x8AOn%_#;Jc#h!{i6e00=hnKH}gOtPu=Hp2a>1m>H6^B zVfcWc>%-&+?oUiBO5psqqj`QGXN2MUF!_P|6DXlwbbYwSzh}>#>x1M6?vK&$S04vm zA0|IAe6R*xA0|I=e~ea?pzFir2aXO1x;{*P;Qn}ocG2}=@&m&M1YI8{KX8AHR+OOY z!{i5!4hXtFOn%`0c!YM*^e0JVLwZ`Y`!{;RAxM50f9bKY>=1fK}k0SF~X88{BuUVe$j_hxWjk ziV}2vnEb%e0YTS?$q(EgkI*iC-M}k?>%-&+?vMA1Qi84zlOI?;Sc9$)lOMQ09-&?O z>cT8jxIRpN;Qko8K1_aK?Bw%N@>RsgM%RbQ4{QkR0nqhf@&otBXoap1lOLEo`TCXc zeiyC}lOMQ0-Wp2K^?ooAD9>*==w1Ef%_BVwSre1UKM!N z;s5hd)AeEU1H%IZT^}YtaDV8SoVjM`wS=w@e+vJ)GIV{I{J{O8`EsVB1YIAl_pd8M z*N4du+#iq7F1kKk<6q~8t`8FvxIZ*_&Qz43>%%qvb$;mjF!_P|;}P1$@1JY%yT+$& zxIRpN;Qr7=I#W@C-#^#jy0|kQTpuPsaDO~PyLi3j8vI#e4Y)ph9B_YVRGq0Pp}!}1 zMR0wX{J{P32<_5mWm+0tA0|I=e*s4I*`Y`!{`{NPXrO#=+XMpR&_6F==w1Ef#Cy!t`CzRxIacKO3?LT@&jK71YI8{KX8AHcG2}= z@&l8{*+KsibbXlo!2L1$wUoeFUd!YMjt%-&+?vF=k7hNAFKQMei(Dh;R1NX;h zMG3k-On%_#fS~Kce0JVLwZ`Y`!{;RAxM50f9bKSnD`(Dh;R14jo0 zT^}YtaDO~PyXg8b`GMgBg02sfAGkk8D@xGyVe$h<2LxRoCO>e0JVLwZ`Y`!{;RAxM z50f9bKSnD`(DiZ7k26N-`Y`!{`{NPXMc0SP4-6lyLDz@L58NN46(#8UF!_Of1A?v( zlOMQ09-&=yeVF{fz5zkkhsh7zA4AuN$q!!}bbXlo;3U3teVF{f-2g$?hsh7zAERHF zt`CzRp3V2ypzFir2kwv2iV}2vnEb%e!5VaZnEb%~@d)jr>%-&+h7Sn3K1_b#{ur$& zLDz@L4;&p3bbXlo!2R(E?V{_$%-&+h7Sn3K1_b#{ur$&LDz@L4;&p3bbXlo!2R(E?V{_$j{$|7(Q5ot`CzRxIacKO3?LT@&iW)1YI8{KX89M zLc8etxa6k;O>eqBOn%`07_BHl*N4du932pJeVF{f{qYFxqU*!t2Zj#_x;{*P;Qkn` zC_&eU$qyVI5OjT*{J{P32<_5W0seBr^e0l3G!Mt`FZi;r%-&+ zCXe@+;IY8e0JVLwZ z`Y`!{O9O(g50f9bKS{bi+y#WG5b(4;_Yisdo~{r79fl7Gx;{*P;Qr)kMG3k-qPnxHt(e_XGPbC$q(EgkI*i< zK1_aK_<*46!{i6xeVF{fxG~71;QBE6f&1eT z+C|rg$qx)45OjT*{J{MQwW0*=7e24(3c%We>%-&+?oX%{CFuGv`GKPYg02sfAGkkB zCA3RlH~1U{*N4du+#l~1r376cCO@!xum)Y9^N{?&{qYFx(pMMusp0xC`GNZr(Dh;R z17pXTP0^!ut`CzR*bo+<=;8V>`GNZr&;m+T==w1Efyv{nq10Exz7Jde0yfu`d z>%-&+W<-bt3$727AGkjrp?pXz~2u1 z<)rJw#02h7bFC;r*N1ETOVIUU@&orLLkaDY?-oBRx;{*P;QnN2MG09C1YI8{KX89y zN@$n-3_;NK;p3<~b#;bTl#rhr2)aH@e&GJZl+Z4D-QdyF^iKBwWn!u4VD1NSG;XPiD0>H0AFf#HM4LDz@L58R(XD@xGyVe$h<2LxRo zm;98j=@HsR*N4du3?C45eVF{f{Ry<91YI8{KX7zF(Dh;R1NX-xw2Q6}lOGs9An5uq z`GNZrXhjLSK1_b#>wuu^!{i6uaAn5uq`GNc65!yx9hsh6o9T0SV znEb%~3ACaFT^}YtFm6E5^?oo9~eF$==w1Ef%_9^MG3k-OnzYafS~Kc z%-&+h7Sn3K1_b#{sdZ4g02sfA2>Q7==w1Ef&1eT+C|rg$qx)45OjT* z{J{MQw4wxEA0|I=bU@JcVe$j_$0M|ht`CzR7(O8A`Y`!{`x9tI3A#Q^e&FkXpzFir z2kwtYXct`{<~Ze0Vp>sxt`CzRI67E^t`CzR zxIZ4DU37hz{J`)5LDz@L58R)aR+OOY!{i5!4hXtFOn%`0c!YM*^e0n$z`R@&os0rS4zQ^s>r7;M)K1_b#{-kR~3A#Q^e&FbUpzFir2kwtYXct`{ zCO_6F==w1Ef#Cy!t`CzRxIgJyQG%`y zlOH%bAn5uq`GNc65!yx9hsh5NpFG^*53UcBAGkm1T2X?o50f8QJs{}%F!_P|lc9um z(e+{S)3I}75OjT*{J{Om(25dteVF{fz5zkkhsh7zACJ&3x;{*PVBdhC>%-&+?oW)a z50f99pHI^DVe*5M_({4x+|!4uUeVF{f{mIa;OV@|V4@{mse+{}mOn%`0WN1YR zx;{*P;OOAHqU*!t2kwtYXct`{CO_6F z==w1Ef#E{}t`CzRxIY?oo9~eF$==w1Ef%}u8 z6(#8UF!_O_1A?v(QyI8FF(tH%t`CzR7(O8A`Y`!{`xDcO63+EO@&iW)1YIAl0r$rv zw99{%(Dh;R1NSGU6(#8UF!_PigEi>-F!_P|;}P1W&rqDdg6qTN2kuXdt`CzRxD83V zKFo1oCnV|mFyDb|!bc9*hsh7zpO{vZpzFir2c8QEx;{*P>U_R0rdMRWQq%Qe@&m&M zS8BRGOn%`0#I&LWT^}YtaCAV>^?oo9~eF$==w1Ef%_BFiV}2vnEb%e z!Q-Io!{i6i|H$e3F!_P|6Vr+kbbXlo!0N#obbXlo!2R(E?b4rmS{hv+CO>e0 zVtU2V-!okwCO`0Xum)WpCO>e0Vp>sxt`CzRI65Hc`Y`!{`{NPXMc0SP4-6j=bbXlo z!2OA7MG3k-On%_#fS~Kce0yw`^kbbXlo!0N#obbXlo!2R(E?b6qZoAcw6AGklx^@-;E zaE^^LcwobDHjguVVE7m$yl{P({J{Nj77#NbR+OOY6V3SnLDwgm^WzcPMb{^q^8f&1gkCgxmxv`WzRiRS!Z4Z1!| ze&GIigm%&OiRS!(pz9OO`EeFds-gs4pJ>hx2)aIWe&GIigm%&OVe$iC2LxRoCO>e0 zoHvyET6BG)IX|4uBLrQaXwHxGhEiWk3A#SfoFA+~*N4du+#iq7F1kKUeqi{3pz9OO z`EeFds-gs4pJ>hx2)aH@e&GIigm%&OVe$i)1_WK7XwFZFc_r?YHynnzoVt(G^>I6? z`_7HKIX^KbKX89SttcVqw?WYLiRS!xgm%dZa}acWnEb%~ac)xT`_;!m*C(3u1A?wk zH0Q@zK&grnbbX>ZKOpG(M00*TLc8etM00*X(Dh;R1NX;SK&grnbbXloz|jFg*C(3u z;}P0L*C(3u1A?v(lOMQ0&H_qRl%VUwXqhASY!1amd{CI09LDz@L56lRxLDwgm^WzcPMb{^q^8<`GNZrYDEcgj6l%!iRS!x zgm#HH1%j>*9|zo@q*j#B-;KaDPIrDB=Ik>H0)-emp|E z^f~S3{J7)??oX)CIDID4^@-;E;E~hyVe$j_C)A1(bbX>ZKOpG(F!_P|X5OjT_IX}(!Ag>l4lS0YTS?$q(EgkI*iX z5OjT_IX@nuU37h-IX@ui`b2YnoCTDsC_&eU$q#%T5OjT_IX})cO07=UCz|ua**rqf z^X5OjT_ zIX@nuU37h-IX@ui`b2YnoCTDsC_&dJn)3sKu1_@Q$0M|hu1_@Q2LxRoCO>e0oa@8n z2kwv2{R_H2(VQO;bbX>ZKOUi7bbX>ZKOpG(M00+e1(d2NLDwgm^8h+R_6))XwDC(`N$e{eWE!(&NND`t^{2lCO>d=um)Y9XwHvE zXct|dXwDA^x<1jIA7=rjDoW7xiRS!(pz9OO`SA$tqU#gQ`2j)Khsh7zA7=rjDoW7x ziRS!(pz9OO`SA$tqU*!t2Zj#_x<1jIA7=rjDoW7xiRS!(pzFg_2JVkXXct|dXwDA^ zx<1jIA7=rjDoQxl=ifO$An5vV4Y)rZpKW?h{J7)??vHbQqB%c?t`CzR*a@8Gl4lSaTZXjq6A%^XwDA^x;{*P;Qn}ocG2}= z@&m&M1YI8{KX8AX1(d2NLDwgm^8KGB>XkI*iXd{=aRnEb%~@d)jr>%)8ph7Sn3KGB>XX91-uO3?LTS_5AP1YI8{ zKX89MLc8etFs*^F1A?v(lOMQ0&KpX7ExJC@oS(Q)(DjMt{5WqY^|h3s>l4lS!5VaZ znEb%~@d)jr>%)8ph7Sn3KGB>XX91-uO3?L*=KO%5>%-&+?vF=k7hNAFDR5~((DjMt z{DgFUxEBtGAuf|P;&grZ@9=d%(Dh;R1NSG?iV`xj0R&y2XwHvEXqQZt072J>$q(Eg z=O(4TUws^OeVFgS@Bu;BCz|u)ETB|H3A#SfoF5Q$eWE!(9-&=yeVFgS@Bu;Bhsh7z zA7=rjDoS7;PvD%N#??U3^@-;Ec!YM*^%)8ph7Sn3J`W@Lf&1eupj1T(x<1jI9}skXqB%bvpl4lS@d)jr>%)8ph7Sn3K1_b#{x}OLRZ&9bf`Fjw6V3T? z77(A+@DAci(DjMt{D7eA6V3VY2<_6>jhpk6r1Jy!$JukKSCkTTeWE!(Sc9$)lOMQ0 z-fK|1^ws6&{J6Wl!ToWr50f9bKXE)-m(lVu(e+{S0~-Qs(DjMt{5T6JRiWz>&H0Jb z8cKa7H|NLQ?G5gaw}ujQeVF{fjKCUneWE!(9-&=yeWE!(An5uq`GNbB#MK}*8;n;U zch@qwKXJM~OnzW^fS~IW&G`xSnxWScnP~%pu1_@QC)A1(GRFo4U7u*qk4N}jV{7p@ z3ttC>bA6DQ!2Q9Qr2i^Dv7{EAA2>Q7==w1Ef&1eTu$sIX@nuUHYta zbADoUe&GIK(%yg1S0()4IbEM<&JSOMXP)8ORLDwgm^WzcPMc0RE4SXFC zbbX>ZKh7IUeJ#2^(VU;SPtf&Y@&otBc|)nMr377{XwDDTpzFir2kwtYXct`{<~uNa zK+yGJ@&otBSwN|Z5_El-{J_xxLDwgm^WzcPMc0S<4h$aZKh6S5Rg|FX!{i5! z4hXtF(VQQT&@Q?@%y(e;fS~KcjHvw%_+CFuGv-+|!+g04?A=f_zl4lSaTZXj zq6A$ZrZw<&K+yGx=KOescG2}=S_5AP1YMtK&X4nkQeTU%50f95JaM0(>l4lSao$ks zYbin3Cz|tvHR$?8bACKRyXg8b-+|!+g02sfAGklx0!mespzFiz1@;XHx<1jIACJ&3 zx<1TzVEBNb>l4lSaTZXjq6A$ZrZw<&K+yGx=KMI*D789WpJ>ic+$ZSzF!_P|*feWE!(9-&>B=Cg|V4h$aZKUOPB(DjMt{D7eA6V3VY2<@Wl z!+ZyZ4+y$G(VQP=0i`NR(DjMt{D7eA6V3VY2<@Wl!+ZyZ4+y$GOn%`0I14CMQG%{d zH0K8dT^}YtaDO~PyXg8b-+`|Kg04?A=f_zH08xfqeslt`CzRxIZ4DU37hzy}-T!LDwgm^W$6}?yKYcyrJvE zeOR2t=bV-#ckbbCfS~KcZKUjmV50f9bKOUi7w9!(}P&el%7R~u_t`GOTVLceSK1_aKCm6au%y;0LU=6xH zOn%`0I14CMQG%`yQx148An5u;bAFtCnYtqDm71;(^BovIAn5u;bAFr!l&UB}*C(3u z1A?v(lOMQ09-&=yeVFgS@Bu;Bhsh7zA7=rjDoW7xiRS!(pz9OO`SA$t@*g=}pJ>jH z^Pf^b6D8>SM00+y23?l4lSadu(qile`0x<1TzVEAASx<1jIA7=rj zDoW7xiRS!(pz9OO`SA$tqU#gQ`2j)KCz|u)ETB|H3A#SfoF5Q$eWE!(9-&=yeVFgS z@Bu;Bhsh7zA7=rjDoW7xiRS!(pz9OO`SA$tqVbk`72s|QaDABk!2R)FA4<^miRS!Z z4Z1!|e&GIigm&p`1sOd~EMxyFffLM0o=h(D<{X|>rZ-_~e>sOInBzEM?EW7oTk($U z)$%nkmmxE;yxYF8)B9!P>95T;`wp!(m{t*Qv}U%!*>=N|@V(xhZEzkP-xbfbW0y05 zbMB#5l)wqvc+K~PI-se>r3#Iw^o$E zd2z$vAph%5lDo&jljKTh7r%f0r1?F#)9NAiEECILo)v0E34Z@vgX_8z@gep_6PSkK z5!&THcX8@I#NKNH6E{MwD8Xk3*Wk|&cM)vgI-G*vd9TNZdW3fA>n1I2_|Q4wue&l6 z_r395s1+snEaw`0c4EK1$BYoWg9)4u_XzEx{cz}?*|Z@*U{*>9Zz5sttLVIlRK+9U zQEXW_n>GXp%t{Hdd!B$l;SsbgQeBvWVut69Zz2JI0`}#96(#6PJoDsi zgVW_8etNQ={o(D*M8(T~@U9H{n#bInc;2J44J;cxOE6K#B4bIwvI(`K1g7i6mo=Vk zVBCPf)EXPz#IZW0||Ll z;=(6Nd4zUhj#2!Isk02MClIupka;CwJz1?NL6hpNv9k;eD6a8+dy8Bx0kg^@vu+TtY z;*>=OnJD#34XYI;Fn!7t`*Nm%kp{w2)v zOstrFw{t~zJurh-DW|iUB{Opk>`#N4apv>?&7en$H41+oYS&cHOw1c`o7IXEx^`Mx zqth?jahGH!ik-Z}BeV-M1x=4DXBbQt zDrY4-h3MUS*LRBtAa!j7Mk}=FOPggEI~66cDsgkWD1I zS9-!~MF~u$F)MzbX<(}0uR&E9FUUUEStDbU}}#=j+21NW3{3Lrumq?t7jQ_Kv?6;;T0^hqQt>XcX@<%(Lj22$1DRQ z3B=7XkdQ|ue%NrcbCXgPB`}G|l)rekft>_m8Z0MdUI|!F9-&>Bm1N$;Up1IjAdapo zW|6BUU{+bJD1nJerV|KQRv>6=A-hY!-tq|T!ptYLBbaUAfq|eAmODK&0Yl7cMG61! zIju8fkO@qj@(At1Br4OW_iO_@4QpUpT8R8S0fW+NMG1ZXfV)5~YHgAHB+lD1$a}V9 zf{)odIoH7VG5Wf}KHLL0StLIRxIf-2N(oH!F-7jmHE@6M+{K(9i{vK(_s1i&3-fr) zViv83v9Hh{mltTO>aTxIb1a zN?@9g*;{{xf%^jjbABw6p9I_=kI*j6<1tM@z|jFg*9XZ@0`8C1iV~RSV?M4q!@&Ik zfjK`G$xj0Ak4I=1U7vS9n{HtBfWVv|i{vK(_s3a4sfrSGeYQR`ohA>6^KhCNdrOIH zKbv524|Q{G+bIU;Dmf#->>oFUCyEVE7C$g>3eOFLz$5{Sy`=ty;9Ab74FyPS!=+2gEsVWx#? ziY}aU=d24Ms>~W`v6Gs>S$cPNKJ~SfzzhxZ{56w#t{!W2#rb^f)+TUX-y^gOQ$Eat z^(GrQ0U&<;bEL(NZ~{(%)ru0B1!7iRJlVhx071`yYrs432<@WFu(i}=1GfPL=9pOQ zY$xD0ILjebQ35kfO!2cO8+Z;NFe}Ak_dEfA!XvZ`Q&-Fl2XhP@4G`bK$-oYM;-hO` zwOUaEvsuiF9XSTR1_;c2u}A?D@IX95yD&Y*Y~7e+;F^HITp5d`0XKvnYqg>T{gsPs zj)8Xq0<&u@(u@Rr7LU*_Ou;daypcm^1_b8gSR^J1I5W_0Onr&-Az;pwFsa6&_X9A|1bKX)FB{1R2Tzy}Tf%OIgld~+c)C6og zkI*j6;4&-Q=NK4!ATXWFBCk!r*t1$u0+YH-`~T$_*n1%2Jx5z)!invxeL}nF6E19% zV=zk$1WiNa&Iy=@&NNI_l<+^XVCIWO3Xp&Y;;fp~UrWqIo&>~$*eA>t-vadIF5chqV{2~3kG~(fRNMkI*hm&NFHMOf~RqL13ny#VLyf zJX@<3CHOaXW0h$J&Mk;5OZB%n$&u)_&?mHuM)82!)94F>C<8wjr$rL*g`I1hswjau zfo2j2xWgb8JoJ)XhR^3?UhoO+!X!g;(f!j5yk`)*CiJy9^^&-y!vw1pB{0d*bnZCK zz<~yVIf@o1YZ7p)Jwm%MkpNr*{(Yx2;x`z}!YNayNcfD?S8qOSfk% zP6#DhjUVR`+U37{#mq^IQ%DJT=+0qJy{}b*)_Ro=(+!+-tbw_f7AKt&aNRvZyZram zJh9B=2Pc^GcuJW&@jRoAJJ-Aa=jmdeSY{%GbE;TlVU0QA1nh-x?cFn}6(wj`aA*79 z=_+5AJ;#2(D>ISz!#0o5E}rxzfpf7~gJ%Z0UxG7)A@0T<=Y9!J=mk8B$o&$WA>>`b zR7slxzQ(bH2c_e*e2G1Q6@Jp0J~5}btuf%~4j{gPi>q=#Bjg6Au_UxIUyAljT9 z@AgY@-qItqi)T2wUxG88Ab5t8`z1Kj8EQod+{-=A{Sut-1i^En+%GxsVpEUME}mZH zehJQ|g5X(H?w8C@ZxU)3?n58vehJQ|@^14&;9mD`zvR0+8}pv_XDUkYOfC0IaC#PN zd|PpV+b;<#T;&nk#dEvd6~Q@P5Incb{Sutx4Yi^K?%yBhehJR>f>?yJ!Q3ywSz(XR zE}lQ;ehJPagZOF3gKocMMg3Z#R+PXTf;jg}a5fnP&p5mNlF~IjLc4g5n)@X`nI1MVX23M_lL;+T}mn`&``AS|p=sTgq~R%bC}K z60{$f@8EnmULU`WEMu7!;Y2wnxSS!hOJAGre)?{QrRwBn-s^+sXt~3JbG3oK(%k*@ z-3|-R*m|!)C3vQmJ1jV3i${+8>AM{koU!!??ZSQUAM{koU!!??ZSQUyH1StzAGhg z&s4X=f^!sD1NUNeJ1jV#;St)!GauYX!5I(`JoCXF7MuY|YDEd$`_=8R;5-NjlT+w+ zShjWQ?Gf6AyVJTI7Mx`Pf&13F9TuErNoqw2+{4!Gu;5$^2;3Xj?Xcjyj7Mk}&){$$ z1!rB(g7Y~b&abw~?Xc9Jbd5)77f&2=9|b26LExU`ZifZu z6nP)=GZiIxE|I$;IDrP@Dx4qV4$HIEswcGz_l|ZuEI3cbdrAwzGiuynIaRK5QY%W} zUe#`g1?ShW2G7B9_XFqRJVLv8){Z+YIC}@8C{E{bhXrTvl3Gy$_uO_nEI5Y;g6H|T z#^9VZkI*ij8RR|+&JcpY{leW23(gScX+;U#JKXKC;5;D++>_kxu;84cM`#z%K5~Zz zXCX6?bK>kHcUWrNU6`j8C2$XPx5I*Sksxqyb+^Ov(ns%jgm&=^CwEwIrV|A2-|lu; z##ES@rxhi5PL#VMINu2Z_lS2pENvQ(_6Y6bc~|bR;A|=g+=t%nu;6TJo_66r^lpa* zXH$8%c_B{VyeoHDF1YnR-qZd}MG2n5w<+hM_J=5#j^!R@f%l(a`^7f)Vu9|b3|LGa`?cUW)|dzDs{zyt=j!-7-UATZg% z?Xcjqw?}9fPmpsT1t-cuV0whxVZn*=Ra#L3lO)^@3r?4Vn7*XY?Xcj~x<_aiPr`GD z1?S&EU;M}N3Xcy0-avud}Q~92u?RvMvg0rbfttf$e(z_iNoKpqC z^RC=s!TDE@&@P^-3XbKvFA8(EH#H3p@}InEB#%Sm1#qwW0*(zqlP1I3XY~SH|tI zz%}s*?Q;GKc39xEfWYh;x5EOTC8-r9Fvlj&9TvDPAXeahX53-9cEukappmUhu6;tmV^A`tll*0>#( z+jh#o*j$>$sD$<*TPT_n#+aaW4RO=K!9Rg}-mz3{ZDc7WV}Rcu#>;g?9@`5%Q@I z1ZIG`ld`xkfJbN-W_7xgvhepoG}(QbJ1HApw z-aIKw<68;s!lXy{9n${B9X7J|xRbK9%C({dO?5tU`sr>;r8_B0b6pATq7BczGhEx} zr=`(`AAl34wBxm+1dV&Hfn5pwHK1|N$3X*M3GI@#@l3=-Pj^!GepvomQ9{-OfvKVH zq%7|wpoDhG&kzJAle&|#lW?~JttcTsHxQVM9O51+3EnG33GLE-KbVsfZgJ;D|1P}9 zdwu9LpZDV6c~RV(BXo0k-FeXmwp~Irxw)2@_3O@y;{G2Vp;{2Wl)#K+cU~0tO#v~y>mYYtw9jpgJwm%4!98AhUKICy0kIJGc;R_b-18;SiV~Rh z?9Pkg{x2XfL)x7e#eHQwLc4gc8lD%$y=y>VPPIEPT6J;LKr2dMW_6tBMR6Y+5EF4f z9NZTtf&1flgm&@1K0FnQ`}~05oq%{=v{IYqfmW2@-G+E76n7s2fl1@;yy)mH%>%6{ zfvMwho)^WPh(J8wV3Ip8y61{?kI*j6LXY#jDDIC0VsVWr?!4%4pEeJw^{g1@dC_C< zy&dvyOgt}&do6KhxqMg8J;IM0jXo>3tt&Bu9O6nCG( z8rw_EcjrY{)w(9oiW0gu?)x$84R>Djjq4kGgmz)le4OV+arY^#@z5PJ+&1#|fl{Rc#ogO`QrvBU;tmT7EWS7_yifA$vQOT>=!co_og+EP zWM+~uVLsjb8F%PP4}W z8Lmq0T&C(pv6GoWuvYGP4wEhrpt!%$pD&k`7CF>f_u2Fwy5>qU!!McOhEyzKJ z=k6jqbUiFzj}8)hEVbCw#p)BX&)xuz3_GRpVU~) zK{QfUTOr=(XeaBZ3)R0{tX&ORC;ejmck*{#BxZNt-`Mr1yPUu5>ngT14-mUXM2N6h z&$z$SM2TFLqr{F+nc}VohY1%>drgM(U(xSoa?0<2`#MXZRw2(Kr>LAEK-BBALGJb_ zFVwX^+q+T*v}&XO?pkXpY}8r0QvQWHvVrX@$?)`%;=*6cM0nX!;@s(QQSQhx5!#@* z=+Zhs6H%_lxR2Lm+RNxjtYaxv*Zwnc37@MQuu5P+4&i)I*vB(%lxQEHUicR*?4z!* z^cI!#imbIX_WBQGGcv#NZZ!X}SP+lZK;w$UO*nT{GA3KF*jG3}*2fbqizk}sPU!!8R@svHh;*y*tjb)ls)y!`8+1HM z{F*&ds^_Af51x~pIyFO_x~lMP8*u0Kr*9MelDeGzD^0ZP_e~df=*mj5ywNdhR*sBu z?`nmMr86#A?_ED+6g>UN&3p0AvrSCtQ1?-|a^l#=L%rhEeKd}?!~=&%Gks^3;NV9RI1&bS`m@X-Vl#fDS;Ubg0*rtX`!F)&b0zW!OJV$ z9pAW|!&9xdS;B<6FMWSQy+F(;lS042MEO&?nP4q-_v$I&X@H1M8DS58>+9@LdADqL zHHV12xKcz;PVMt&@Mo)k%22WP>{rqJZIsodXqfo?C>e;D&X2qk;TyaZyjRxQ?_sO< z>OE7{${#4!uk~`VdYBZIZ{iFJwwYqFJsZe$%G!x2R)oj z=;3@$%?1)u`=x3=8BRfOgt;QQ>q^B;#0ND&4)`*ts|&CPcyNGL9o`7Uc060OTMR7 zE8N!a9xs;T4R%_*NV+ox$bA`uMWe6#MB=`E^tg1?o-dle^ONd(#J_k}4L(d18S&LV zU*;!S!o>Vk(=D?eZ4uF-F}C_|s+y6M0&sjZ@=Q%V(;O z`Mi0sC^rD>AUCAvaYC?`y!Mw2M;)ZA##|8VI{Jx@4piN{aK;Epm`E1-T&l0j-BZ=Q zc3T-LR$z4gIKQ4juon9d9v*)#4Hl*FtO7o?l`LUmb<*=PDo?05>=_0dEq1IF;i&h? znysfnu$JkUJnq$1w7`fH8rsFKF|mLiEe{o|tH!1{HAbnC2O~|KY9(rfK)p}a^;QRr zA5W{UaPv6GW1mT+x|B`~xa@L%S((*l2@|!x6^IMWi3-+=_0)Z=?<{(UxSWw`Mi>NZ z@zr{G6z?-tbi_KAN4^7XzIN8)u^nE&Ot+3-mEe3$+X?w#D|#%QL$B2;@8qyIY(Mra4E^D)d z35;gi?^2@>qEX%Agg<)f3o`~71Z$ah9#r_S$by=?Q*%4oEMWqpS)3Zx)VPJyJp5xs z8{EgUUc(H6wb)a`x#7QU6Kmna%_%w2I#@Vk+^?9E)!%u+#%LC&zB@Hmk!>4&$&45= z88#~XI*h$LgTQDOr$#k33SmC@#x0WKeLUk%gt$Eg9Gl9`e zs!>giLfFakQLOm-%-1=udntopEqb$V509f|4vD;YgL&egI9S5Om(JH@AGDIv5AT9V zojp#h#(h+|JKP{xi`y7h#gFag^#h|?y5hfjgs)5Kvk<6m(kmpi)$Ti!n zk&`;6)xD4PdKdS{AnL``5|z+j?P~nS;@@QgqnYln)aZse&h-c}@UE}(xA0bCSed_M zM1wFVq{A42Zq8reQF7^xqv2+l6hI_uwpwO|#{DbFbWiduw#u)Xf z+H4RTcFYl{(YL?tIaaWQ2^!%*ynXz?aj<8j=?1}CG@^o_v6e?+$pnqNAUY+C=fxK< zG6>cxkR?D?%@i!Q|JVnjqE%89PVI8GX%!-ddS;RpyDb%SI|Rrs9ZSfT8<&Yf@55!$ zDYbMzHm_C?2(Mpiij-)(tx}*)j3i8atUgNS$PpwStUUlC;Cov!0z~)vAqK%(e1&Sg zbAJ(ztV|7WRKot}i%2HS`?xiruV{0R7c|XaJwsBkD^ZF&ISZ_0fVQOoR=^u3r^`#l7^WK`baZNPI@kc88e}2Ekg0 z7U-yf8l@2f`18K?Is&UR2MIADAWVLK7b(^j%MuqqX0Kcr8YSLz$QVcdTpWmn&#j9f zE;R8LEMWpZk5s;o@>M)MoU5~o%2=^pzvxhdV6E7tbM;L4&a|7jsw}fBis7g*9lUX- zU*~@?e8tE%VOD%>Ck}eCkE_QaUit)IPQHHZaeW3G>Xj zt9K^qzg;!GaUVDCwy?78LDadwLwpKqt9|OKqe{eeS=U_q)Cc^F#=(Qp{;u*uaKdWc z=GK^Kj34h?D&OX(gbDaRGGVR`V#nQIt>TC?c)V+=JfoiyCg43u6?0I21S&HR_Ov=L zb~!hD_csXEI^>l?E}Ru9vhB|g;_9LK);-ju`uX_@)`AZrl`o>a4U;&!YPq$%w97eu zRD@s&6Eugz`)GV_idCzG%Ng@9${<(^5eqvZVu7oAH^pU5z#A-FB}Th!^YnS>53Qj6Hftjqv|Th=6xtC(NC3RcE?Rx1M3-?6OV@LqY`26G7x(*2J2F zo}qy_Xb`NGJidfI6tlZFo{vEkw|%UM=zSU-iWMwjf@Y8)eoL4S7O5I%5T;hmH3?A) z5ERQ0h?4%4FhLOu5Y3YOFP8CeyKNAxm3Lq_M-*ZiMbDoCF(G=RI~O7o-;N&;EMWrP zg_SUO266I6TKgOByhdHO@;iP?n4lO3h-y|{yA9sQyxjW@g0c3JK29? z?tFEgt^B8-5+*3d0itDe7rPp4cgeXb5+*1T1|sS6w(dQjT+XnuLoEI+)}k00h@kw_82oNk`0@f;wfIqPrSSjd z5r~<07s`mNcpnYwh$j^j`DE=DA=1{_EHNI5ggLo<(fq2usy@kXHd~7ealt%BMi2 zs0CK;;HrLfF$vb<*5l!kBIk1X4H2(IkrRz}#l)Bz8$`7ofg5 zgJ3OgV;&yuTBLHT(fRk|ue~rT`y|A|rHcNl(OHes_nOtve;4>mdB`P~Dr*p|g^}MUA(jE6#gcBaEM^l$8aK9B!i0*_CqzO(OdYjeeoy6c)){-+uJk%g zC=WSu_YJFl#3rFUh8ry82cPYhA?SB+^*?B{gozs$E~6SdP+Tmi z*RizUCyV2qKiR&_AXw|#$DP{7>Pe+xV_CcX@&&%ylkLaYthFH9N0Bot>bedOwM?S% z zH%pjMaedX>K^>JGB}VL(B@s`|Qme0n3DzRpwueXUZBp)qjR)NyI9S4jip;D2O8FF6 z2YKayOocm7^1eJj6PvXL<@hKX;kk7>t*Tyjq&O;s;N6md6m#zyU$$=uWFZMS4wNEXBU@hunKvcT*DpvJZ_T1&M$UW-*O64LE%g}w4 z%0)hTT2B9cZh^`Pm#AA(s@X)+dHZb@nNNsW=*WCRc2P&oRbPTQ1BhBRYDhJk$P{qL zR`K+IB`TKxFM%k9?n@BY0I_GWCDm-=%)QGtOPD|g(a&MWwLTGIN`AF7MadWA<^9fBQRSUQWkY}d*5PO0g_=!-^;#@U;-8dDVVFDw+_5jov zj~xAmFj)<=i5)qAQ+eQ@5+>k}=LMtlAnb zF3e5r^B{GA=rt@t4D0FXqjE$E@e&`bypMip@55{&^JRx*3DsrzsGO9VGa%yxqG+py z_7pXnNcPrd2@_NS0m46j5?jqC)|G2+5UfS@6CgaZ@0Tgjb|+s6RgvbO;{=Z%+~*?> zcUH<)@Dl?H>@)gyCSL4Eo*wlqC2oJlXpnU3DmlK8%b95RN`qi6?zOR2AK&?53%k%J z4l~9mCJuRK@KH~_OY1^-AHy?EmQ}~QoZH^bGYHn=e%{05eBqAr+)|fw)1?@@+tBV} z*zCpP%LWa$RPdyzdYW8``ET`lJp&h9eb-Ewpqf&_rT@Cg$z;Z z^0z^xyEj0V$BNvh??ViNwLa$?rEQ%4FbKrF$17#-SIC&8sw=tYMATU%M4frgfIIJ8 zYK?4;S&} zMW47~uwCGz%b9rpcQ;FzFh}Rs+Yj0}vCui)yP+{UvsUq9dG)B>ua(-frq1SSx<)wm zjO}I#6Suon)gHi0ON}3)f1j{Nz{c>Z6>TP1>(lb0+Q#JMV?d0Huc>WB?Of<)2@^Cc z0`Z{AIr|K3+^d_`W`ea$Pi98Dnl?^ebjBPQ;bsXFGz)``!Rxo%?Ovf`>)a`WU@i8$ zut(#di}q2>an2@Muje*uj)S?5RC60O$HB}+QZ=1aXHK58JD|0%?!1%h>dik-w_Zk_N=orzs4%lIlB#lwK!^oInMAXdk*%QnESWQ^?Q;D<%uhg9DX)zIPK~7 z6?`8aiQ)``wK&d%(+a}F?1lISFIPG!Si*$r3ss+pJ`6S{=bdBQ7}a)-kp{t9X8dYu zP`KS2xuSv(ccF&wzsMF79M{6rJv+zFk^*1Ur!5A-TF7-;%5PV>PgK_Q@w1oL$2)Hl zpt7JpB}|wxvWcFn>}c#DaIW+}RkJx>J!bH-kZ?(PJue*TgQsaxQ zM(6qqrx*llsTxI9tB9IK5C#3bY*n4Gv8}(w)rK^3#wmYYdFLum2>+^hpuIKT<#hb> z!(s^&G*W}8-|2;22T_CHuGiMS|G&S*TFS#$Q3I8i#JZyS-|U{K<&28#ELg$>*LcFe zDw#+2=;U(l2^nJ$tc6Ue_Ni6o6srgREG65P!D^0K^HmP@r-TXR?JKVzBNB+9B(-En z2A8wujU@)bT4q#j{DNAt+dsa}T(^S+OPD}DRgZ8gzY4$I(N0FeBm1Lxm_e`>d1oMY zAL<~d;2SKEG1`drF`>pkH4b9j0+IV$XL%mq`ON(*4T81EX9Q7kVjI~Q<6zn}tBjZ> z6KecZ;~+*l5aMD(+35kYmXo3kg0;Bj7Uu#ikFe`DcRBAjTw=tjm7k;h9e6ZG%o-<| zbzW?jz!&8=b&}vnGZShCtY*USfzYmYmM@Ou&{2^Rn86@eizCoD3u0AHJLg>xe|@xA z!UW=SdT(`%FRYj-e>Kkhyj!;>@*10LiI9Ld9NA}CZGO5+bvs348g94nIW3Kk5P+fT0KdZS70$Fe!%Tn2EWO#2y$ffwA7AI+E5UfQ$Du{AL*2o(8 zYLgys%YLn@j{o_)sA1Ey2~@{}=>0T61|@bmlf9{95Uj9Q2EWWCyVvN(cG^E0Vx(N#=F<#SQPvMNmWL3A+fquCZqn4lRX zh)u`$NvR^jb!Hg^YpIImgc>gpxeD)>4>9NL@*vb=2@}VkeG(fG7wx*{Zx9FW9F&I< z7p*igsuCi*RChU-#D*CJYw`O> zoFUzA`RFC~_?@uVVhIy!1%aAJV?_b(!{?fmrO~by*4bweti|siv(!SD>=_t8rhR(u z;Or7-vuJ*W`}kUTs+}LR)cxs094ujiW?>*`c4y?gSc_(TAZP~ZU3#REr7L zqS-45nh85t!UWBVLC|d5VuH13-VUO2fy#Q8TBlizgC$H*>>WhQb&s@PQuFq3iwV{; z`(3X*f7>&zV?1v$-(m?9D*l#GBMuu&I#}{BB6qcp+&2i;;yxcE=ghRC;we-PwAyTO zRUsl1di{^8_U9@@?CJDjt=0d9%lSH>zEPjZ1XojHPmWn{t;#oGquy+TU@hgr{8u%3 zw?rE&*=Lut(Sm#G>Hd^3VOD0|`}K%*9vY22kGS8dAMq}L9mvZQ6xlCK{V*KM3ijpa<)4*-C_w7 zTs4h-anf%TZPFpDe<;ErSW87c5+cIrcTcz9BeK0g%(CZFizQ5$71-+@91zXmC+?~d zZ4j)bqBjY7RoH0ss}xc2MVk-uw^+i2S%Dq-&py!?bIx_8HX8(MB`&&C7IR{a$)I@H z7@2vySoj$^;dZeWOPHY5pdeb8-zp9uQyq8pnnAFZijyVO1b|2}ZJmflR4rSp>#ADd zr-TU|W&2-60SK@9T|_+MCEL1fu$EOCCRI%4$_{@!-<7`l@32XyY!z8ah;oDYwsVZQ z2e0q+fp``F{wZOi&yIz%>n4A!KJ`E=iT3EV&`(JFBXt>nau&bk6f zd5~(=ClhM!pAZX&jgM19MHa;29;fVS5Uj=3*w~}-OQZ;ff92J!yy6W(T9-7c)tN9y zoV8xF#X9WXI%Rr3gJ3Nc?@7q^;y!xK?=QB(hx1RHL`Q=Dl`z38XW=3L(M5zH`?|aC zDqZ`OkfW1axy+To*ctD)mLfZd+vV086~9cVd7$b`Fn_~Uz1~|~)=&iIv!4VC$U-{r`pk8jSmx)9j#C9CaCYa`_3CFoC$J z{crRW_3cG>SZDB^uRGkyAXw{L(rem=W%q)OeG491&fl;;N=y(eVPaQYT3NNsQZd$d z8Hh~79$O9kFn&zzW)Q69n=!fm&S!K}qw~;@Tdl;ee4Pg->{jcae%2l0iaK@LZ4j)bW<#pK!t4lyuV*GpWw2TgPGi)Ca~-j9!#`WbW-$4(Z>17k7T+QB!dde#z~Y(Q-@hDA~8T$|xLEnQuMns~k72 zX#x>?${`M-FIm$xO0t9rD0)eDi%<`+pDF>0T19n#kB^(TK%G2 zGF8=JaV7O>5M9U2v4-44MPu-Do7cGWntJLnaOd;d{BWq4%vZm`HcObGegy>eR|dga z)boL$KG9|g6VyL~pnlgNSc`ga5Y)HZEMbEBc@Q*y7zAt4NCYC!=aIVKz2H^TW(gB& zHmt@ERU3e;%%PmR-<|U3M}uH3^BcU|Bctwjhc8MYS;B;xGpl|Vb6wa_Ghj6n#*Ek? zSc|`ZoLAIlrs!J79}UgA6NOOsZ9xsxAYoH1(=XHR2%iBWOP%5Nl9P-xK}SmVavSPD2K9 zpxSP^d)^9BdSfRL`9i{kCsvGnINR7DSc_&$Abz(Oh&OkAov7HBymJGsOBJXY)GH@d zr6A%Arx%G7h=qqu9wAx6glVJe>lLCAW_KBr3^oYXLd~FFIjJfIaV}Z9Fp&~#cw6ND zMXj#*DPe-|3A?1Ni54%AH<;I{i$Sm!vROJZfh-wpye!>Wv|IoWVDLqoX1^BAovjaz z7Rc5E{6&wn>U@KKS4WA&qY)#^bIE226EtrJ@ox-Zd$$cd*EeiXYyd>~x0yI|1HR7| z+aOp=`MJv9h2IOJ-u2zWf~OzRf1RyX7be8+wTGV&W9PN+Ag)|FAbP{gcse(lSJ+!> zPVg_GJbdNp!!rl*xQi6~;K|fj<8KhGMbQ=zd!I;A7M_0gh-hQa0Vb4(uRMMD@*s}p z-6!Uw?zMid-3Gy0yuTOfeZG#Wjy)KhBJAou#Eo@CP}NoPw@ndGyz})H+FL%KQTq{m z$juTa%&(RrsRqGX6!C-&ilo{sVS=KcASjaRW`eaS`UzrI=DSui^ghp$r?FYWgjzA1 zur>$8-#rqGNQ};F?iDZy*5ds+um-EqKlVXXt7k0M#i*3!+FHtzV>EC?y|q_^s9&#} zWC;_hhfY`r4PxN9MYbCi5I5Q-H3-(C+&zfIc}M6>L-~M5HcOa*FCo$a0?5PNN1I83sH z399!2G4XW=IS_rx->ISvg0)nCt7b*2ngBV-{9UB#OGeu(B}N6-M%c0VBUY@ByV+f`gl$lTAc%o7#t!@iRjhYr8w6{q zktQL+0-|QsIksAxk#UTayi*zP4@dQvXzl0TgxS$(CCQ2(H1<4WLX9*Du_f3j@o~ES z60IccgER=%q6$+Go#w8zhhoH;RN36SjR`f_n^e7 zJw@i)9?5ZneaEfFo%8;Hykj1o)rbYQUC-sLTrt4dOOFYv7Q?e@-XO|u(-3uJ2bUTI zYpETL)Httl>R1`(USe;=46;oBDUu~jpcX(^A*oD1YCn<(yFC%bIXBAN=6;F$E2=L8 zk+WMC`vM|Gf80D{>^sN=<|Vq{#V7i4vbeaTjUsJ|eiw&9m#pPLER zn*KDgQ1`d2m)cEt*tL23&Rsq7+Rv(X)z)YK;wfF{o9o|gvF@|IE9*l2{~2zp?9!Hp z2OQOLRox5JF(gbBm@!S$1>&B=#+7$lw2dyUvKRzwU0t$K+xU^^6^MNcpF7l@ci(^t zf08h^fU<8;y3Hzu{dpN{dAx9DQ>fbi3j8MXd6?;s9l=( zzsqV>!Bw>@oX;Rwi{C$D009NP)jMDFsI=XF&OC4R+=H`bmUqic@mB5X_uMJu>vNkO z>i-+f$%v;rYR(pKb?47!bhKH*ME-T*4n-f?nheC*yKl9P@4h7sg0;pL&8?sAhc{_K zyvio@(`_=St<4f9R!vW*@4QLx#30rkZK$8F*WMxq!CKsU5D_l0_04^f&=>MNR>kqUN&wLqdbyb~97d9kJ+-fw2cur zKY=*1`m=t6C2Lo*S;EAr7K^owc7f`uCN|%yZ9J%!#UNOVTd0ReNX%Jnqta2Q(RP`r zJhQ*Hkvjc5*!Wm_r(5+tYohBL1Z#0S#tP}C1#H!>oEay%54+Py)kYisS=tVo^jZJz zpk2-Fjq8)^|G!&*Fl-#H+0a&R@LS1EZk8~yyzfU%7kb|b#1mI;ZR5`Kr3S%T_51y! zpYHv2%R#goQPWm!_hGryZk90d>(M9L#=!A&Kx9~-QQMffaj!wJ*5c<+wGG!YwGaKm zES0ql{{|o3EMa2Ly(`*AjZ|u^J$x*gwvqbEHG^O+ZlN9?H7Xa@HqQT@-ew6C7e5}< zHfA=nVWWd@ZvAxg9L`}7ti|mZtI7RJ>#J&=Y-H@Whne)7S~EVi+j^N?s_$-0J`Z>9 z_ze30Z#sU*o`4yTchFZ==G6UImN3yFWim}qYOo(fq+bbbW7hbz#&59}w;t3pJa4US z3@P8huAfNTDDxyQ?z~KRGrJnz`Kelq41%?|js4eleKJmRP)oE(%c85Yuyf>p zHXJNrg6x4fkhz$?bNfwIgJ3Osh7Q!Q{a; z_!_aQhig8rlf@Dy$a4ZQD_@lM$g2J*We}`I{v(JCzopVocgMB%7E72Q4-iDh-Uap3 z?fz?VgJ3Q4kU<>FK2+Pd=EYTRp2Riy9m4 ziV5;$@CM2EF$mV;Hik;4gn6xRkGvMmUj@w|ESj<4K4|`7NSL6x2(D^%wP6m`N-p;- zXb`ML^DEeR5H-`Ge4jLLnp-Skf@Vk{_LnWBZ4~WX+#pzs=7}KgOem>sj2YR^VhIy8 z(*u#wUZrP{X+M`T2-f1S05kfqnR=Fb_CrVG`(T1Reb~5_Z0x^t1A|~K{#J16^nWoK z2gOS)nqgZsZ^!$f`MDusg68TVyuRGiPq$9@#0J4y6n_A*u4D>Jy}=|4N?9ynf+7eY z$}c*gZM-^^&LCKeTPW)Ev;LvqVB!v5M%!hAA|bFrF&TqkEpEq%GYraSskS?`$t;Kc zI;Bu^1FyfETElvMwp0&yVrg@WB1N##;B{Rc@%oTC*1-}c!l%C0^w$StKs39SP20Gh zZH+;&7DcH*+LgBbna8#D;kqBjd-Wbr0C zeid*t%*_%evJCo1zrm(;ED*J`7uHXA$(LUYg0*}+)9coAq-H7*W3IK-cm5`Pl$#|? z{M9RoP;D&F_kZ9gKABKL+h|fRok6gc%$rHucFTPJNJ#-~^;OPD~^L)-Wt@g`pxZDW#WgclR6 zMYbK-10vJ^Y<#Re#+xNfkUbF2)}^$KH_J~M1Z&Y#w-7y#ZKvk`mM}rj4K~IX zET(PTDN)rRSc_T@Y&`1OLfa_&Xu8ptFhTDh1hqtiU@dBuAXdcIv%Qd;sG1`phM#Us z(TPIUZ>x7e&k*mtUb4jU-W_Bb;vev{ax*cq*LY2zh=aUYd*EW`=2;-jGAZj>$w2iLs z3d2U7G&!}6sms5xmtnIOc^R+~9qZOM-n(|O&tMRx{jkyltujq>FWA^rJf*e~h?qM6 z7Hg3&0UISVL~9$HhMr`f!Diz5fK1xPxwK7TqxYtlZuNaMvhx}QYmt`$!j)ydw&9w0 zlYIus1m&Ya#B4pTZ4`_vWe}`IJ~fD2wR>qB9sHlMhs=3yV>cS~43EOJjh>yW8U$sk zC3()U5mvsWwo$G52lkN7-=*De5H&d7Tif_^pfCu^ZU4WlOx(DeZuJemS@xYhWXZ%o zt+VJ|ZZh{BhpU>o#8cadxmepESc`mW5ZS)g);9XCP9#{u#PZ@Vy;ZxKoN^+F^oPsF zs(0Scw;ub{lC@|q3c~YVb8mGYgUcl5`Kv(`>%YUTY#c1Ec8wTRp^>+;(XCHCo~26G zqPZxD@N3H)%EsDz9)cxI@Twbl;ce49l#TZ@YV#~rvKGxnVWafjvS+bPZgYaxs ztAjiD>Gww4n6n+Hy3=p57Dd}&W9H2*+Q#MY2RL$PGf}N_6>a0zt8%cBvv(>>z4KnJ z(i#M7QM3&zzfiQ*9rw2k3?)f(QK1#@W|N1uJ<$eqnv6rY2QVok4V z8$L7rEtW7rRiPlJ?Jllu#P7Ypkvpy({eL-@xV(RA8~rm3vnZx#5L7z~8<}5K(l*4> zbsV`f){Iib8^q~te`^~dyQ_1Q+#slS6hv6GL)+L~a017|ZPudrHN2(l*S={RV!>yQ zg}a%!UVf~8A980!*!VrBmbURND8E6l7RQ!7JbHK~66!l2UT%tmB}|;#H9^}rpJoWI z>SES<+Q#_xejGh_vlji519P=%iM5SBJqmCv+`$C>4Px=;|JfLx>?+5?nc({a(W3kR z?&H>|-`w;R4TA2;!U_f7I{H464tmXb90zOBI|p%e$Upjhc$|O5ITnivdN&|qm-uKK z9dEQT2-cz&3ZmrVciP5-#Fe>K^Gar;iW&PYeXOQ!Jg*(#=HH?g&R-gAY^nW3+xQSX z$fj@5_+9!2LF7MEM%&mr=>X>kE!LvG1ccv?YuZNH5sPh>FhSqEz)ppg3uqg=5#Z?w!r1zTILi8lzw%_0>RaqtC62HcObGu>>}bExxJ8kMgsM7zAt4SPSCI z+R55Rh0zafmM}qMB8URHcWN8+x>PU-)*_z)MB_~LwGIDUuWgnvLEZp}^95&X8-@3H z83b#QhXdl=uGHE_uLobal7m+O^NM2-OMI(o8y!a1Gzjv2*i!>B>(EN=Up3k8A<4Tl zewTbL5MA5s(mvd?DRsH_L$DTkoFGD`FVcSE^FoOwOPC-p6GYhAF8kDY-r`g}n+ew9 zXf*o7B;~cgd+$IZ_O=BRBGl-AC4RH4TEbXpRG-{IDXn8lyJm{%9ML|K=PVKZ8+BaWwV3{nuURAS#poIao)eYL9iChIq{vR`Y=b^cys@j%@QVPZU`Gc2Hep$ zf|e9E2-c$cE^H*tw@TZ%pX9X75+-Pl3mZF+CbHH0SXwu$L9iCZ0ASz@MA%|2iXefgc=3g{F|2l5nrM3{H5vnWOeqV}#&+Qzc!xonp3?@}xaL{KuPwvo%bnVSjLqF5jNs|Kjm zQ{Uj9l_W=m9ZXP64n+L^I@-q0_y@84Tdc)#M#K}}Cek)W3{K`|2@@P!#JSZOh_h?< zf8+OTvlg{6iMotCGh{?u^nNBfdaIgJ3QCfYdWH|-a}5+>;60ubv)m(n(VY^iS$ ztVKN$h@3NOX&a^UjTS6nf>w`!SbaF7wozhaCxc)u>QO=LD^*zAm{P<~u!IR(Jpy9G zpv-bjP3$%KVva$umbruS^ETzBg>@|P)+)ggCd{2~Px|b&lc7j&tBB{2k zb~U0g5mz6KpiQ*509P3`!KrUYPN_e6k=Ssm;DQl#R)+ry2xnkI~oLQ(d-4pvteFBJ*x%{ zCkmD@!Kc(>jA~z6+bH^?on4s0tAYOR3(>87u$zc$zMYCdzQIQ*_X&WQIl@csrf>x}gG+ja|}s_ce-Z z;66G`Su7ql!MU%6V>o`HPJq*^@X>GCypJ13oGp{|vnus)wn4BKMO$DaN9{oUtkNx; z%W)XvcWH$*h;mb=Y8#JR+ zE&6|WOXmxPY8x9P{bE_d1pN(STBrZn*s(m0V{d#;xe?34(>)!mZG3N4#HOcc@$b?- zS=b{b`4oL0T~Ue71Z&Yd2k}q+71~DR@4+0|g1$6d)rgBTL~itntJ-FgEMbDa z6@fcX+f_fS16CS?U@ht~K=f}nML(-^Pb*56FhSouh;7drYa3Vl7BvXgqMi@Lv5Nz= zjq%A^NR}``eHVzbFRN-B^DN6CSc`ga5Tkaq&^F3>4UjBhg8E<(w|nQ)Hcky`X%MVM zBN2#9-yd5~;VtdDK3T2E{kb0z$Ck_;fiB*AYPFq;6Do4_k}P4uw9&kIcJZMRMzzs1 z41%?2yuwwv*H+SZ-XrrAW1k`>_@1zfIrcCehTW`wuODI%ti`)3VXVbD?xEN<`-XR@ zvELFC?o0u4U&dh3=<7aQRrLma#Xy|np7O1^LlbM^%m%&B1omwNG57IsQ5>hT56KfL zS;7R)hm#5C*McZ`tB;rl!fRu+L9mv&Pm!zGAn^g`xKH$pkSt+B?N*s^el2WNN!UMe zdfin9!CJhl64qc9>>vWMN6L@%!N%@MOyHCcsrGMIC+MNNtx!eLvI_R0zcte!Sc`Xu zLar!FR#6bUg?{hc!`KCi37l4h97TF#5|R=#M?f}xz37fjI10>qXbQ}i6Cdh|4d zU@e+0fta1^ho0k%Y8N6|!UWBbKx9K{mwHw&j!iKLL+ig;ABdB`&(?Fbz%GG2Q{+>d z_>?FR8%u4ocVVpcOo_dx>9=Thr+2scZ_k0$x6j+pu**%~lshHwM!=N%hWue>#opZv+z*4*>D7MSg7~IJSjBuogu{K=k%#sBL_?F;udI35sigunt$# zHg*qo7zArkbO%JokG-^wZZq0TmM}r_84#zVn`j%gT}2FnwJ1sjVr|?6ZR1)gZ^;rS zD9!}JwW+JNv9?xfgJ3O+w!y!89Xdk}e=L#J;q|rkT4l3@ z2|8~AHmVn$qVGKYpmqkqS{%PbJTY~!e!AzTHRUQs2NQH|25fBqb(*#@ufuLP{}yYR zanbtULbQ#0jrtnZm`w0V(Hf5}>z zF+IlG_vbB^Fo9WyZiy<=0nPfAqXmzixZdy5e#hp_Mg{W&fJf~4T80< zea@tb7w-;(xK?bc^n)iepBkL=1a!a@feYaEYS@TXz$`c{FF5NB1FM1;y+zS_v zx98aN8`(*6zGbf8duvU&o$$gf@ zM~aMpDdNfTMshLEOKtQajbI5A-nCNtWXc^S+SZK&aWATlOpo&iLtm#b2-ZrMHI>hX zN>O6eF-80{-ba>NfxYx%k_eVC@ibd1pROQc4=5t@6iW^ZLL{|VVuN6S>QF!52O@fkiOO3Y4#9d|tzIZMc|Tkt;GKQai`GF$uG%Q>aA zk&o(k-eL(8_o`>|dGKfn2 zF3*?Zc2KzZYr{^-Um7Y>hR=}YOCa{zqoMH)GT}MxnMl++Tzp)$16TENq@Q#a!TC5l z8XE*_HSv2Y28eL+ww)r*JenoDm$Tk@oMuZBCRV(>D}qL>6b%+_RW|;ZCv&94i3m43 z8w6|p-RF)-(Q2i*nnMvi^DK~Ku}fN|+T8?8m}s^2mbhJdr6>@#1;opU1u}6W>^6O{ zyFswl)=jrWRS??(6*1}M0y+1Guk+6O9)cxI)bD>wTqwFy44JKniW3*gGv9oj!+P{G z2-eDb`I^{sB~0|5uo=XLrHf=1M5AUT{Z+7piFPgH#kt{O;&vIeQ+kyv%VhB*IL$nM zrg-yoyQtDCSkx~TC4IN=5_kQBMc?;P^3S(BMUSb$qVfJH5MfD{%Xvq!bL1yK!4f9M zf8Q&f-U}A*p05H?!d@l=4*NO>RGnoI`Ce=n%VBR+i73gok$qjfOkT!}UL2TZTon`T z{@f}~7Yr8ROCn+8{@`V@D~Q#3XBz}-^)9qk%ugRIig!@Nn;OexEFu$wSIrhIVPgLM z%_8~RAaUwT1c;kSmdRQmYGj>b5Uh2%^Ct27Y>@Drt%!!dFO}C1_&Qrno+DVo#G#uT zMdL$3;(c#LteCM>4pKy-xdy>nb(gLe1Lp^cC;QZSsTs;Fm6<^#n>|;sgo)C>uND9F z3KET~DPr;;{_@OzoMiUSBv@-=`E_FFpdit)l_E;4^OqYz{8DG0UpJi%J^&aM&FpmqD%N@)_yI{8a~5V<1f36?O??NqcFRT+DHhbtR5 zs{6}@AbK7%3D$btFIx026(p)nQ$*3^{&FsecVFiTmM}5q_-YZ8J4mExs|cL&plzHe zIo}{yD_7Fh;#|rgu_l)yUTt0?m%_%iHuD8bm{@pZl}MH}NQ8JQB6{Q!83khY9Ft(J z<`Ge%{?kB_Wv4o^@b}6~WDJPM2j&ZwFd^e2#qRh(ad@~QBL7+}uYx%Ik4dnW%Ze1| zP6UeSO%xHgbFq8}qEe{^f+b8`az}`qGEj6VrikO?7t8EuiGACd1Z!=(7B2d&3ly&( zhJtw6c(JSo!hh@n!CGk9VpepZ`0GZfG>H|d7R$aMzOPy!Si;0VIIZUUfpmPto8m-n0PfdP%Lk#h!-su$;9YOrsP^ESi(d|#V~PnV4&!dPZ3$Y7s+fO>J&E# z)=HBxOkC&}C{AZl#JMbsq&J9*)wg6=}N%is(-vASxzZBpZXU>YD^>W#1Pn zj(~XlMG?b+2~go!QXLPdu*f#T&wMO-|vP%Z-DGsq-Zt8DU6vAIQ{$a7o~_S%JV zJ%~l)77CUyQDbw6Slu8{;9n5Eaxa&?j`=#Xjq?*c_N5uWS4@i!7Bh~llIA$Ltm<-k z{kX4l`q~+SB}|0Wj1`%(g@{#4SHng&=W%d*h{<)9%de-gYxat12Ekgl(#MHgLqo)v?TV=4y+AgXb*f+q6Nk?47Z(CU#G{I9KwK`rTn;$r>+C$)Bv@-h)&rtbc!+4$P!ZGcbl+jO z&L1?keI)Y7jWBz`ySl!4f9AtT-f|T@Mi{60HT%?fEjf=c2E( zSX-AtuvW8zM})`s5b;ze$26OyqukRIC6|^Rprrjaepl;uMVaeI^=zzWaH5 z9p-~?zUCAxVFGayy-zCUiy%%H+Hco8hP@5%q%#QC>QmsTcvXFsSer5{hN`Se{+4co?dh9~my~qZOB~0`g`9$CO+lZtfPJZ>Yx4}k}CV35lwXP>i zt>b0*7etEV%WYrS$lM~rVhIz|&wbW5@Gsicm*g33bsvk4XEX@b!u4w#xM~o)W=7f> zVdG=B6&6dF!1e2>8tj7DH!_dC9X8&+NNEtP#Zf%eGfY`$PlAo#{O4ONVFIl~+raaK zjdJ#8`!tB`8>brtYjNBUeo6i(_LEI6=c^&5jPHY6e)ymJMQr~l(I;6NJl#=M-rD8X z;Jmv(DhQS^arQu**onAL%IvD`X8!cUUJ!~Md!?5_u-49_aiT`~C~+vWBG%tcEPoAj zIRpC%!4f7iu8tEc%0`JTk5YojJ~*X(ztH8p)~=pGuvX!lZc#WSQgqCe48+X78RWZZeawmr@GZr@f>|hYARq$G@sNXA6oM@K>gllRZ*?%~C zhAh7bmN4Qz9N9^`Tsnb^Z1SgX|K7}2+Qq-Y$J2t>-ii^wB5 z?{3GOzJeu8w2#~;lH7|BMT)An`(sye>C+u2VJ_@%5Uk~Mai0i$79rd*ifA2QTKfSKr9(CwGfUB@tR4grJRa5!}T^RMe&(; zU?X~NQ+co;h}V9CB}}kw)DC`ZF8%W&Q~hJ6L9mur&mCfJ&2W)w(^J@}KG7-9RYx|w z@D#xkCd~VIbi1Y;R~2>P$4!E@c6#g*DR+d6p3YaW;rZEHR&ctUk7`U3EMdZYy4`AZ zlf9B+cl;gmjr%ASu|*6lvr=?Fc1!Xz^zc|Uv7fy9!PogU`y%7%GI20^o#@^*R7mRt zuIl;y;j$_`fZI0~8w6`@UbR*nd=Vmw#T^0hec2>w!(00NdZ}Ou6TyG46?Kb-iapnk zf@o7=hAalpvUO^IgJ3OlZtybErdXAg$#F_LeB&zV(W}=OXI%cwdn`5XHfU5QF7;n| zh04l&`l3$yJ2!TaTV-W77g=Sogo$2@ZdocT6Ft5hh}b9R-6|_{FKueU1Z#N)q|#&5 zxTm?$&ss}mWoj1B5*OTWho!PIYqw{M>r#A^rLr;=8>_MQ^4l7= z%F49*5h7T^gin)LOJ!x&Ps;(~T}`ZVLRRL~_&~uDCNlPjvs6~5!JwQVO2pT&RaU0O z$E60rTKR^ZuvAv2vs?Kki=8!Wm6aJEwpg%)i5DGDSt={@qlh}O@X@$xw#v$+Z7|Ou zSSx$L6-#Ahn!d{iVy#zITV-WNmYOYCt9t7zmdeWfekWg?Njz>@$yQmJ(8bdPOPKi7 zOfOpq#Jpr>Y?YPC*=2-a2@_uRUs@_F zbEI_<5GSvduvJ!O%jkgy!CJ#-ys=bPW?{CXAa<87W~;2stN7l6B}^0ze`Bev%(bkF z$egOEt+F!rTJ9jS}H4(yq_YfUN2;ahoPb|{1?FzCKA{BVyUdm^EB%0%s=O5 zw^deVUD}2Q!CGc(_c)W*R#}4WTH#bm6poNyvV5L z2K_^-+A1p(lVXiQuvVFDp_aDfkuV6CPv7h5VTb1jpayp zwIqwf&07F}%2~vN8dub_$j-5prOvrLrG6>ds z;|{W$|T8kLa>C1foUE(R92>Z(hnd; zdj`2xR;JN$lZfoQ!=bV=@#9}hwhbTd{bIMu$_z|((zq%nQk9ExsH{xt$d|A&qs2V8 z%E}b2ViK&?HGQZg44vN9sj zBv`A%5kH5@%3SXC7l_Fr1KcVr(^H-lEMeke+*F6k%8Y;Y48-5g4sMl|sr<+!SZl`H zZVr`|@w%?&YL{lzajUG%^<<|6OPKh$vbIBIWgdz@L6lxm*{!lN848#LYjt1S(4n$2 z1D7cxd$Zzhm6b_T_LN`=6XkxXX?_2@}5M3prF)CR^V}u+jN+Mz_k!)b}P6?JUvG-#}hsw%q9rp)_>46^FM&18MuvYldWDb>;`E>Llh@6$*#;UB$3G0+# z2@_BDCvvE)OoRD~2<~?$R%d0rOoFv0yu0JAvNFY{J^)dq-N{&$m6>1plwb)H-69To ztE|kJo%caZ{C#_@%F4_uZ4#`tuWju141Z#~x=I5=lGLt{v1@S%36|1r`sWO}rtQC4-s<+C@tiEwqnndO% zonlp1=6#}5f+b8;iLC9dvNB#T)vRb|!CJ8@E0gxqNrPamF5N15tE|l09g4X8BYUjM z%5->)zJw%9cpOaRt+F!b5-FnO;bgHYD|7a?NwC(7W68W#R>qM*5vNYyh*4RYBNt8z zLqfm1Hu8{{%E|=JyA2|3+e0xbE7S3`NwC(*ZachGR_6R*MZAm&j8Rz`?*k_VOPHu~ zaH^Ne%Jj;rh=Z+W#;B}J5w}UOR+-~|UMedSlt&RQW_O8ES(ysEP70PV@i4Nsm&(dC zxN!@_pl7vXR8}Tzn@O-%qVAQvR92?0R92=;xFT|- zeY;O(Wi~~d1Z(B%zN3c9%9NR)h*d-V_NlB)r?8WPB}`!7pfxHh^Pz+yazEeZR#_SQ z{Bgl!UzgW+94ad#=De5YI9Ru-+pV%PN1GoPEMa1R>hGdu!M;RPcm34E0ew0KOjn8zvEU}nagQSg0)t>&uFQv z%>OZVCh*o>^ZmYPHI1<`6b%iP5JW15Cb{R_mzr8*X|zfyEv3}ZNDxyJL58X!A%=)V z5UnwUhP-FrH!;;zYA8xlQ&pSbZ=O2%f1h>MzV}({yyx`I=i~Ek_xF3w+SA#4pY_|% zS`T>?#DAao^_^5@Zt=YLPaQFF+^^hVLRIFVJJRoS^sE1KCsmne-TM7gM@+ov>ibTp z%FNydany6Zvy-aK-=FrrhH%!A2i;^sRp!{|ujOg!s;~LsPO383z25t#j+nUL?QS-q zD)Wwg>G8VVyMDHls?57m4>IAbKRx2W300XZJOtufNB_@GsxrTJzxPfZF>%kw95|sW zbE85W`Qf!0Rhi$q99Wim>gASQcl{xw0 z5Yum5c}7*{@;|?*A)NK*Gk<$RRp#IgdLXaxj=g78Wxn%>T~kL)9CYsQOsLA->2io4 zK4za8Rhg6id)5%nYM)-GAH432s>}yZ**SH@#Jj)u&%oF#z#pc)l;fe!QnQxwT zVA?qC&R3sMmHGYK-eKy9iTq9+=wX@nm;BR*e{n)p=Au{Jydj+RsP|ocpepmCYag68 zW_P}1ovO_3zxeA@M@-y0voq4hXP*S|qFa9GaH=vFJ?|^)>Fb$|y+i3W8d#>+Xval2 z7^uqp)5*6B@uhz|ah12Ig4vz3R(JV-`>j)zxxsOlOdK(B-IpF#w)~MlX3Nj}@FNeWD)Zgz z{9Z$}S!?IA7tTH7E+Jldug4!wRpzWae{qrlfVUz&!QTDcYkxDu^q{>CWjoG&&Al4} zdd$k&PH1Dk9e@1cM_x!(=5cqtl(kZ1n@D@5A8x)Kd%f^}7gCiOZeF%yi*S~E@$!z> z6>hYXs?2%M{{nlr5cCL|$bKtr%+Hcr|M+n`smfgb{m(Uov)u2OcWXa<{Rvf>AHL)s z&G*A+{vGe}(-~Eni@$h4_SM5acEbr(nM?ov{!>Rxy#B23&Zx@#sPy}M^TEF{p(=C4 zXCKlK&brgF-Yq*>F>%4ad}l^g=HLH={;RJadEkVq%sv19 zFB`&H*M9t^GpaI2oUmVr6V5qkLRIENXFg@>h>0EhUoxXAv*QqmWA1gxgsRNR4}W$; zIO|hS`Rt6U%%i?V@8CuMblVA4nYUyV4@XSA@S~rcQI)yM=WZC{wZD7&300Zf?sHN@ zIO~hYe_}>e=9E8#*!OLBm{67Z&!_(N)DaVRIPxE6RAnxII{l(QdCYH3sLH(bguiJB zXWjDoADU5>*}NFyy7xVFLRIF7Q(iQ6#Kh+57tg55T;WzX2=RiC9Xg>Z^SU3OI(5Xv zLDwHdRap_>j@XVV@6fx%OALIh#&p)p%bbyZ@cL$r{BHc z%`>Vp`#ttLo3DHG`7^3A?^yfQO}Cx?#HZbALRIFk&U*9o-%dMuMpfq4kGb0BQSW>G zjH=8l{`p#)&-mr%&8W)!R!>dJ4JI%2|YXFQp^9x|aS^WfL~Z9_Qg zOMmvN8C97#zmsLK5Mue_t#jzTy!Np?mt1(aUz$*rx#RbCHpIUv>yGE#bVgO?*FM8D-1oox zgLSGh5BkrGr;eC-_Pz(ssLI^s2%gB^bn&a!smi=ycz;8*S^jN+BSTdt&dfTF3|D>L zdccuknYSTuWT?vI?fbNWBSTdt&dkIS6F4&5OHvgNfg?jzCeBPlI15JxV*c(2jto_q zI5WkOp(>L%`3D>ssxt9e1{@ixGBIO@wKW_WsxonAiaj$%OyI~+m5CV>0!N0bOq`iw z&x{chI5Jda;;A^X8bH18LBcdU^ZI;9#W{jA?k)bLRw%RU zlXnY4;K)#wi8E6i8LBezRt6jysxo;Cc)*dNDibp%1da?St}DbGE`;awxkUl8LBdIW*Wj-I5Jda zV#b8Pk)bLRXQtRQW5fiG3{{!9Eg^7ZsLI5dX$WWG$dszggD{bBWT?u-nJMdz92we( zGt&^x!jYjW6Eh|Rjto_qI5Wkb86zfeWT?u-Z3%%RLscfuOhY&eM~13Q%$N{3GE`;a z%oKZOjF`ZYp(+!%B?OKPRhc+54dE;t8LBcdV?yA_P?d=@Q|y^BVgg5os!TkW5I8ba zW#Y^!jYjW!;A^X8bG@I5Jda; z92u%Iab_CASvWFOWn#vJz>%RU6KAH_Gh@UAj!bc7io1j(LscfuOhY&eM~13Q%$T%+ zBSTdt&P=gq#)t_V8LBdITSDN-P?d=@(-6+Wk)bLRGbRL%3{{ypGsT`6BPMWUsLI4` z34tR+RVL0%LpTdZhN?`=m=HKJRAu7K6nkcjn81;tDigOQ1da? zCU9h^%EVL&fg@9@G6%PWvv6dn%EXKbfg?jzCeBQ;XU2#L92u%IF=ImD$WWDuGgIuD zF=7HohN?{5mJm2HRAu7KG=#H?Ba^C3%$N{3GE`;a%*^eX8Zp5=ma0tLmJm2HRAu7K zG=#HoWT?u-j0u4wLscfuOtELihzT4Ssxom~Lg2_ym5DRc5YEDpp(+zICIpTQRhc+5 z#hw`>CU9h^%EWC6fg?jzCeBPlI15LHs!Yt75I8baW#Y^fduEK7z>%RU6SpM@M~13QoSEW&kI%IxaAc^;#D+;5I5Jda;>b{yi8Ip>&cczQDiiM{ z1da?%RU6K7_fULksi=<}hsh-G?@aAc^;#EeNBI5Jda;>={u z^X-V+^Cx9Cs5mlIW#Y_WT5PppqFpN-8LAm^W}3Bf7LE*SICo5NWT?u-nZX#@ikQHW zVaw-^362a^nK&~I;Vc{(+L*gCI5Jda;>=*aY(-4q$k4{zmBEo=JL1eVgtJ(G+F-3S zGDRF2sxonAFnG2iCRl&kpxulJ6i0@tOq`j9aF%=V*4A)jsLI5d!9?2X5j4TsK^yG9 zynhu(hN?`QnTBwd`~Biz#gU;Z6KAIRe)!DCk)bLRGbZO1jto_qI5QJROyI~+m5JLD z0!N0b%(Z^<^M-I1jto_qm@y%6WT?u-nJM*fV3q1da?Mk)bLRXQm;X zg(E{%CRRrX92u%Iab}7mLscez$$%q6RVL2N(5@AZ3{{ypGsTgiDihyhz>%RU69ZA)JLHLscebOxnPap(+z+rr0xM z#6-ItI5Jda;>LPE~xCKK(c{RAu7KG=#Hw=L3RwHPRy-M~13QoS6xZ41L9UlYfRILscd| z%M3?`+Dpusw1Fc-RVL2N#1RuXGSpsT#)QC;p(+z+X5xqm92u%Iaa%&*$WWDuGt&^x z!jYl&5;G%RU6SpN>jw3@=CeBPlI15LH+Dpus5I8baW#Y_C95I0-LscejO9&hpsxonA8p2sP zGSpsT#)QC;p(+z+X5xqm92u%Iaa%&*$WWDuGt&^x!jYl&5;G@f&Vgg5os!ZIL5I8baW#Y^@f&3rB{kObnQvErBCL zRVL2Nx+5lVWT?u-ZAlwAGE_|B%ru0vaAc^x#Ec1nBSTdt&dj%RU6KCddM@-65^ydGE`;a%ru0vaAc^x#EiKxzb4|y zP?d=@bGRcWaAc^;#BB+IBSTdt&P+o%3rB|9OU#%MI5Jda;>;ZGhzT4SDkLhN?^qmA)JLHL+vGIOb8qqsxonA4tK-^jto_q*f1e*WT?u-nP~`T;mA;Xi5U|DM~13Q zoSDNMF@YmPRVHrBdoo^l92u%Iab_CASvWG(USh_Cz>%RU6KCcyM@-5&}nt zs!W`jhHw^+47Hb-F(GhdsLI5dIm{6gI5Jda;%RU6SpMyDVfk)ieyGbRL%3{{ypGwY6+z>%RU z6SpM6iab!}Ji8Ip>&hnFUuDfw$sLI5dnc>J#m5DP`92u%IF<^=#Lscek z`{(L_BSTdt&ddyZW{hCfjD&vmg}{-aDidd>A)JLHLscf;NeCPnsxonAb~<7L`++_g zJcqOqM~13QoS6&N*E3PCQE_Cb%EXLG8#pplW#Y{2#GV-=ZqJ_-`z($ORhc+5I~_66 zt`&|9)r^q(F@YmPRVHpr2pk!zGI3@a!dW;n)Lvr7gus!ZDiddB=7&cczQ z_7XED1da?5&}nts!W`jhHw^+47Hb-F(GhdsLI5d$$ZP(5feBv zRApkSgus!ZDidd>A)JLHL+vGIOb8qqsxonAW{#M^k)iey`yvF63{{ypGc!j_;K)#w zi47A1M~13QoSBAj7LE*6nOGemaAc^;#F?4l$WR%HUoydwp(+z+X5zNw*yCps!W`jhHw^+47Hb-F=+!whN?`QnVBOd+P#Y-LscfuOtT$0 zGE`+^z)ZXk^VAndhN?`QnP%^rz>%RU6SpO6g(E{%CeBPlI15LH+Dpus5I8baW#Y{2 zbi@RX3{{!fFd=YcsLI5dX$WVvzYTC?sLI5d*{Qc4iX+2aCKdAH$kcgdau30gsq@Or zuxG}I-fbw340oJV#Y5o8)OlqZ0+VLU(mNU9!8LBdIW;K?7=k*V{_433zC#$WWDuGcz~~M~13Q447io zY!f&#bzYglpJf6^rp_yqHgII9%EXyz2xsBQP?d=@69Px3&MPxGVgg5|&MOlFM~13Q zoSBAj7LE*6nK&~caAfMdGJ_)~aAfMdG9hqesLI5dX$WWG$WWDuGZO+whN?`QnVBOd zaAfMdG9hqesLI5dX$WVvXFHAzRhc+5Ge=C|$kcgd(gu!9omZwIoaOIknOCM%W#Y^< z-wzy_Ibx?8BPMWU>bx=`aAfMdG7aG@92u%Iab`l`$WWDuGc!110!OCKD-!}o zrp_zV5YEDpp(>O2`$FKz)OlqFM@-bx?=&l%e;^U9Q}Oq`i! ztxVv^)Olsn2969>nK&~I;Vc{(sxonALg2_ym5DPmIAQ`vrp_x90!OCKE7K6p%IqGWT=?LnP~`T;mA;xi8B)dN2bmzGdN-bN2bmz69PwuHsZ`QgtKsD zsLI5d34tS1=am^8F@YmPRVHpr2ppL*g4xN>ZwP1M$WWDuGZO+wrp_xfIAQ`vrp_x9 z0!N0bOq`j9a2AdXRhc+5A#h~syfT9$CU9h^%EX2Vfg@Arm1ziP;mA;xi2)M=N2bmz zGdK%Jrp_xbx=y;Vc}PQkD4%1ddFdS7va;1ddFdS0)6GOr2MzA)JLHLscfuOb8qqsxonA21iWj zeYg-fGId^=!S_BKnL4jbaYeW9gE%sEUYWsnNE0|RbzYgYfg@Arm1ziP;mA;xi8B)d zM~13QoSDH96F4$dW#YDkz>%RU6KAF&oP{GpRVL0%2ppL@ugu_x2^^U^uS|%{D^sd6 zab_CASvWFOW#Y_)z>%r*$_$Q}z>%RU6K5s_j!d0bW^lv=j!d0bCIpU5omZwIoK+l| zRAu7Kgus!h^U4g4n81;#^U8$4k*V{_G=#HoWT?u-nF)a-Q|FZ#95I0-Q|FZlfg@Ar zm1ziP;mA;xi8B)dM~13QoSDH96F4$;UYQU$GId^=hHw^+3{{ypGa+zf>bx?8BPMWU zsLI4`34tS1=ap#)XSGkSI5Kr!nZXegI5Kr!nY4i;Q|Faw2xs}pxy&n5Mlg#rGvLTj zm5DR6fg?kWB?im}jtsSzyzReH=9MWUn8leH95JC05<=j})OlqZ!dW;nRAu6wgus!h z^U4g4n2_HP0!OCKE3;GH#D+##*}##Z_7XED1ddFdS7zpj+w&)td1XpfCeF;v5fklN z;mA|Gq0IA)JLH zLscfuOb8sAI%r*%7nm? zp(+z+rXie#BSTdt&P)g#8LBdIW(G%0;K)#wiQ5taN2bmz(-6+Wk)bLRXC?%WOr2L| zaKr?TOr2LIX9wSEf{D;><87O7T46 zdlW~e&MQ+K8LBdIX3_?ZOr2L|z@8Z+ST!Tzw#&RSr79C=rXie#BSTdt&P>|Ck)bLR zXJ&B3M7te0GE`;a%ru0vaAc^;#F%S^IB)WA;K)#8iO;fuBSY;aW=sei8LBdIW(G%0;K)#w zi5U|DN2bmzGdN-bN2bmz69Px3&MVUp&cczQDibp%1ddFdS7va;1da?Y!omXaX!~~8^omVDp;K)#wi8Ip> z&cczQDibp%1ddFdS7va;1ddFdS0)6G3{{ypGY#P^92u%IF=ImD$kcgd21iWb$kcgd zLS$Z<300XmGY#P^92u%ISAG<2;K)#wi8C`eVgg5|&MOlFM~13QoSBAjR(rPN$WWDu zGc!110!OCKE0Z>GWa_*!4dE<*)5^RulRB?V^Zme)sq@Ng_?uSdm6_CeWt#7x2^^U^ zuT0hoN2bmz(-6+Wk)bLRGbRL%Or2L|aKr?TOr2LI1ddFdSEeDHg(E}lC1y+r9GN<= z%;1O#92u%Iaa%&*$kcgd8p2sPGE`+^#)QC;sq@O@?z|l_fg@Arl?j0(Q|Faw2xsBQ zP?d=p69Px3&MPxGVgg5|&MOlFN2bmz(-6+Wk)bM+_xnQN$kcgd21iWb$WWEZyM-Ze zWT?u-nPG01om58RtrSOw8cW^+E{+VfmzXiRN8!lSd1aV!X6G2esu>9!8G57gMsNrm z8LBdIW*P!Vrp_x<{G74vGOx^fomZw=D-$>}bzYgYfg?jzCeBPlI15LHs!Yt75I8ba zW#Y^Xj+nrasq@N&z>%r*$~1(taAfMdG9hqe>bx?8BPMWU>bx=`aAfMdG7aG@92u%I zF=ImD$kcgd21iWb$WWDuwGskHhN?`QnTBu{jto_qm@y%6Wa_*!gCizzWT>&ka|wYX zQ|FZ#oP{G(=anf|%{GA}Q|Fao#+j|pGJzvg=aoqtI5JdB;>-nUYQU$GId^=!S_BKnL4jbaYeW9gE%sEUYWsn zNE0|RbzYgYfg@Arm1ziP;mA;xi5U|DM~13QoSDH96F4$dW#YDkz>%RU6KAF&oP{Gp zRVHRk2ppL@ugu_x2^^U^uS^IWnL4jbLpTdZhN?`=m=HKJbzYgl5feBvRApkugus!h z^U4g4n81;#^U8$4k*V{_G=#H?Ba^C3%$Pha;mFi^Wd=t~;K%r*$~1(t+NW0>nL4k`;D`wvnL4jb z+Q5;i^U5@Yv;5>-=9QV%d1VG18LBdIW;SqSsLI5E*}##ZDwDVU(*}+Vu1uVn!4VVr zoj9e3C2mUy9GN<=OhY&eM~13Qyps?(GId^=!4VUh3nT=NOr2L|r{);hNUzb9_jlvW zY~aXHm5CV>0!OCKD>HM%?fH|+yfQoMyfQOKOtfo-BSSSK&P+o%OS7(It#D-OyfQOK zOlaPe5I8b*UYUmIvJPM`#B&LOBSTdt&deXF zj5cD%gus!h^UAPRifj{UZ=4?|1ddFdSEeDH;Ksxt9QHgII>yfPbZyUZ&ytMkeX zI5Jce;(Ki1$WUX60keT4L+vGIOxnPasq@MVj+k)UWnP)tsW&Y1$~1(taAc^;#EeNB zI5Jda;>-+=m}s{HM~13QoSBAj7LE*6nV2zY14pLLD>FD^qTRbVGId^=W;<|X>bx== z-iKvgnOU7zrrEm<5l4oqOx%{N6^;y5nK&~Ifk`uF;mA;xi5U|DN2bmzGdN-bN2bmz z69Px3&MVUpZI*uB{&8S=iw^xW@Xvn+ouBckwk?hO1r zhTFC7Ux;Vld!Is#5fiC~7kci>eDiAeEyS-q|GEv~tklv=8+l_PZM^s2?oo)V?7QzS zM|y&_ofCK8=Wc~K@Zg&?1oW7d3V&%MZ!DyZBaXOpA-;di{<|FM3FtX-&ks)u@$hfl zsv)4qth}jEo|gDG^M8Er&_dk*3b)ziNKZh|2{JhzkS16jvsfGUI-jz(#@axzc8>G} z^qlx!witpvV1nf_i@i!4?2Y^?%3g(FFFVo`&~xG!A9(#jeDit(?UgzU`Mz=FOXqaKuE$Or6#-Q&$kqV#`1E@soJ- zrXw6N!TTn4oYWPBv)G5NgK-uXJxLO>8TGreuxLu5t;L2 zdaZqq8*qCvH^=l^KRkAbcTkq={2v{WIasE5J?Xe1eo663Ui`%4hIk+=*2-&wfnwrL zcRFr};nB5Wg5@y_@1xFd(h-iBVEgJUC>_Dpj$7z0-zSDeot2~`GQ-WZ&YUyNj5^ag z2Tyr}{Oeaaf%nEcf_KZuhzY!?I-Ac5!dbj?{yXa@@ZNYwIAVgcr_PDAf^Zh^oIn3D zC-B~QM|dxK?|L7$XQCq}I8LuW@Hp(7t_>5;@)_E;;q~=)@Lv1gFFApC)4MhtF~Rqv z&QZ03a2D^izy3of@NRlXIAS7mVomE@TPp}>@m~8i4|opmrgsEp6UPH2uJ_#}0A7y0tRlEdD5ojmM7sCU3J61KM#4z#nT7g;FMwg{Hy0zs-I*WF~RcouT&F^zffl; z-JrdLpK{KW_89x&4riUr_zhhfnKg3y7cYPA5F@^f3c`D+84ILX{ri9ExkGIHZp-og z#|Yzyj07Wu)VXt45YEcXo72zS;(0?x73c`>E4Jxje|PebktCY^*6u6s9}~;B+=R2( z>mPf|IT;mhcgJIlnDCx%*UEP??l^Up%3^En{;uZxoe8c!ykExMu5H7FvlwgOLI3(3 zjH`}t!~|D6YV?cOM4u(x+o_*&*Qf0|A5+%`M4jcdoJ+iu$hqWCYPZ7?&asi;EUELp zc5Qflxwh9i%E~AU|M!-g;O%6aB8{WIl@^Na9hxdEt;hom`efMy!Ok}3uX`Nem#acPb*OkS!8m}3? zmeAhcY(8(uC@5VUj+kJyp*j!u3c^{e;a^<%@(bc7=&7;T96+cRQNcilDNEVlg9 z_d1dBX1X>UF~K(dzt5b==t>>ohzUj;s`GGnYh}V&Y|}0O;3P&@>e_I`1lPwp4|msw z31_i}|M-cM7%QnG{LSH)9&ftv8_?gh_AGJ4L@|o<4$I=NI}^_G_oi*b5fl8rs&nmi z`^to~d_`^B@crC(9PhW5aKr@1=7x7VnNgy;y=%f*?eVzakDp%pWKQ4fw>KGul;;oL zu=wDY=gXI0_7l&JkuAT=&*#Km54&9<=!x$M#+u}lQb(U;tguU-QQA1})4$#j&eBMg zAx`+hGYfI2-~WY8M|y%bcq<|^lMc@+#O<&6(ZK}EW0uCx4DqS`GWSRR`}~*wc5tL8 zpm{4I<9J;(Cth;iZ5sl5%-S9Ylo3hSzcVLJJMa9NBRv6~RcVQd36{q!t?jH?tEnSB zQP(hpw!9&$l(|H6g|?cEtile34nEw;~+V?X`t8;+RJ z8Jhj|&s{Q4jKXp>_;{mX~#Vq9P9AH1_9qAZW+^lD+8xV@He zq$jB9V38~*pvNrFq0$nLnDD$QE#WQnmV1Vhmhdb(p0y`$sSnh5<}*8Z?>b__GX}M7 zm~a*|K2Z6Y&jsN&95Lbfk=iy)IExt{sQk?5f^Zw&i{885hiw~3^O8~d!MSA4Fe*RzknCxyHLJf-CTNe!&wQ3Kx8cun*79qKuTh-sRDLk_{7LPW zJ7R)w8kL{u;Cmt7-{HOfVM=m7n=6F5*$ye>R4M$AS-u8@BZo`DLmfsD$zN{gYA1pL)U%OV0m|zYjDnIkN zoxD~ioWRn{$UFCRpaTbNW#_!fj-{hfOLbjPhW*T`NaSFjp(JqWLVYJ{~5V1-(5d zs|jYmq`HLJ?|FZjd6OE_d`3?bj+pQq!0mRJa27L&(o@Xn2rc2ejOUzOe#dddglEWX z+c4oQ<}so+F`u8)TkePn&n4Ej;l0aUbesW-wzp?$avPqFl>J7Hg=64PTHb~U&(GQt zUSF=e_%Dq$i-~1ew$gV%IbT(J_m)p$$Hz*foV{Z%e zZxp*`zE;`Gj`RfdoZ!f@9UMs$ERR{79kjtw%@`0lJ0LF4+2V)^&NFDv$c(@HrE3=A z>eu}JhHw_kv@s|0KKKT0pIcp-6>Ye6mPaB+L>XC?u{zuBFySngsmd%8 zj+ltqk>7&F80p&ZvE>}AF4^F-r(G*YdScv%%L(u4m_4N`!}z={;fRUV$74KdCcF>Z zHXJcQ+tsM**2;vle7?19c)$C2aOPM4r)$Fz6MRy&omLRe@^`acD@RPkx+$aVGBWLQ z!ddM z-W@KLCgwJ2iM+WypW!4kosd=CoU&Z4q>jj&{bhC@X48p1Q0Dnz_MW^mRjM+~J1Z&dQrrr7FYB4{aNcnBZKfKF$ilS$VT+s6I|dc>l0>tKqa_UwOZq;AmE( zYBz0+``uZ~&l0b%w!^}!8 z5znK{uf%*vWK|z$53fEZXs`M>T^qh$Im>s6cCEa=tYP(W_HfHh#Azv28RlYY+wi_} zmVfWGgpY@5Z(mC|VuJRnkJGJ{31|5@wQa=O7^;u6>ED_0KZfe#A}Q z#6;c~FS7$P7jU~BCY%+kV5sl!cZBaU+zqNLGc3R3IAVe;Lv>}kHcU7x4#iN7k&bZ0 z1XrT!%5;SHE_c!D%9QP>uFP(T>dKU3P|cUYpVaPMN7&ON!QQQ|OxK3jm+NkIWd?6w z+lC`1xHD8&rfb85v+{2JP+gghaKr?6xa!Ju1V?b(i?ml=nLXTBCTP35GF=u1wd4BPQ6U>dJJ4BPL=*4AqtC*2;vl z*rw{rbZt0df~$6QWx6&@IEyu`u1rVxo5QcL>dFlMrnN`V5fl89S)02u-FBF8me1+7 z4M$Ay+o!rRT^lBx0~gd-+6Hr18s_O1zMwZ|il%m%$5I5WJd!LtGH zPQ;O!v5Ygr-|2zo?-|eXVT>|5cV-+hf&BoD^RTuSN2U-sGbWs+kt##Pktqbuj3Yfk z8@Lo1;qQtcow8O~9VS>FvowBYh&VEZz#MU;C!ldcGV8*5w=D$Dj0u*vv-UfeeTAu# zF=fx=4fN5O*^cxC^cIo&=pwPUw%@s9R_FXvVP7W9~v zy-@zXwRa0q_wH7tC!ps<9GPtY+?nxbu{>twXqHc!pCxf*3c*?8h>4s%Q|S4b7)PcM zI5Q@k#q##K8%L(paj0I#kr{Aha6dRJ$IoSX&xkQAj?4^K20x&9I9qLS)auyd*?$i^ zm#PeJZpC<+)v*mbqK&i!)eJn4whg!Lb&n%6!W zn{i}jRAsOv+BVo%R20~Y5cKb3!|+K|Ww0SyqW@fKEPU?rHXLDjBx1bG>d2~H8z!8^ zGF2H|igv9WF%d^*MpXtgq9uH6ImhZqz?(jMTEdZ@8290F!h1T7%nVls@1!LhF|qo1 zj7QCc_hH+HBPM9Ojw9Tyl?iA0d~4hAe)sX<%%>`YYtj;qnBbG@sJAN!XZgF?w&940 zj7U4HqwIEVm~fWA!KIB-W8u0R17#f(g}0>h_WR)&BfQPbGBpd9TOwA?I(7{nK&+Z| z>>A!+-!sBlv1-<_Yj`uhZKGeSaZTdRtmDw|-grxR-Q!3cjw^u;;r14Z@pDbY=s6s- z2Y+HY;jDN+htt>38^JA+x4RFoGn`-t9bRWtDa*Sj^5*_}ot*~ey)almBgtL~PC0<`|M;w_6RTB8daHM!!&22Kg(ImuRi|P`uhk$Rc7&e<%o$m zG80@G-ZXBv!-TWAR@Qm2I>HeXabzaAGQ2U}wqe3q-XksHh>18d>$oz!)4iNt*YYP45poa)xfgtL5{+BV|IOsLA>v*dTw*6++XGG&xB%$SyN#01OZ@6VQS8*yYN zRAqRl*K|ubVj_;rgsKd0>n+R!dY=-CRAm3kH2lhcNy*mb(Tu3%q4dmM@(>Ks54}CXNd`C#gUm%mBFQG z*UAwST#4!|V_h5GyWBU%Tz_ z`f}Z^vzK89?ZK9t;LcFzCF{1_pXIDLG83vYyp`W>ha)Dq!_|4ox;DHQX|K+zx`+G9 z1Z~%OU%R#P-gTCbQ@b7B?=es&b$;JHTq_fCOD1)0;T3D;EPo#t*J}K(`8!B^RAum7 zTEY<%@jfPXhVB)Fvsgo_GMF)K8;+QW_c5t6bgv+s#gjtx~AY?$SQv)bdq z3^Y7h;>_foiSlf~`}52|!*c@841cEwn!m5DF#`=mW~3>^7%>soq0n0vL?Liy{8`S5 z5mDOMGA#;GO^dBaPq2ntHb)_FX8c(!k6AH0$|uc@5oVxaJE}3V73m4+Ei0uE)k@hS z_}noohD!PSmiaPYtGW5I73m4+Iib00aAmd#mdC8D%?5iNQ)NB_4ck!-o~=kvK+g$g zpn<@d@n^9-W@WFIPs-j%8=B__6KN~b6VP))a|tyB^q7^iqkK}1YTAe+Q`QP+#t{=a z0}IXDJ!@-mWD0>ZW5QW1v#;hv-a^{Jmh;XwbJj3-4Nd@OC2PeQ&Rj3lCU8PZWps;h z#01OZx1c551~bCYvyDYyx+NSj!K^CuZ1e8^a>7}xEmf!8Z^sxhL3>n}Si`oBylpnl zUBg>*)6w~11{$hM*eNaHNKa6eSxrEXSYTGd3EVi7Q*W#9YpFmJo<8!?a+cq3A z;kK6(&f?fmD_T5)j+j`!9sLm;j~ZtpRhh*z(Ged_K8dOf=R&(3CYQ?T3;%=JL^h4;gmvxd46?{T}mmT;ses5C8ZhY6O)EM`2R zPal_}ZNm{0Y#%iQwy!0;h2C;zVJLIg-S zVuGVdRfeOvoNyN76;qYr4Xc)L!~|y#RT<8n<%F{s)tIVGdBe(c(e3hH^xpM8Y};_e z1jmW0+~N^5;Vhq_Z5v)+ZwGVMP?h1mua7~OBQ4>G3Fc>@D#JV7%L!-sd}|4=mc^CH)si`D zsLJ4)_&K;G95KOcG*o49P+Ec+VW`UBVvt2uhAdyTTfz|&v`1BjHC#?OYx&*4>&qHa zm0=CNeQg_#m|)Htsxo*d%L!-kN#iezmhka#d)^~0;fM*^qbjqwRwkU~Rm!c&cF~OCHs?6f`%6pglE>#)s$h1vWX7SDm zK~;w1!JekZ!ZGkCwQJ>w3HB~knZ>>9_2s%tRfg-ix36u(5fj`QsLCwfaZEUi`DCcd z@Q!`kh9f4p!%>x4e0ud>q&=!K95wHewhc#2&^A?>#kDfwEdD+or?w66cV=s$DuYGh zPihHAOfU}%RT=z{<%F~ReQXJT*Zdu%J*qOSVM{n-f;m#C%HVD+C!EC^Qk7ZU4o6Hd zM+#LLyo0t46V77GsmgHeY6(Y7uuW8D7Oz*1m|$)Zsxp`nZ5t+>#WqouS=?8SnBb~S zRc7(pZo*ltAyt{hedTWszrv`>@cYc)w01ijF;V7|NmXX?mzN1=`J8UsaKr?^WT?t4 z{wgxzEMHOEHhjPHebD=@B^)uqv7sunc+5>Wt34iv{O6^m_v55@{`sy4UGuf2clnL) z*mr|vo)cKU@B_~&f4}&=-`GeG{hdEih+AIwF}ob;3FtX-#+843ZXq6fg(G)4(i6~g;@pousr1ml@wTtpc-rY_PM`bmlZQ7PaP4M0 zynSnHs|fno+48Sm<@D*dFFA2|;=}jKTAA=?(cVvg@R}*@Ehil5i9dbf+0(@~Ot3s= z-Ss}FP7mJq#Nm^tT(Mg#M|$G5Z#!$cnt&d&e&O@aoqpjjPZ(}=@V`#mEqA0R?z8r) z>1qOc%(~X`Pn$mDtLe*l$oslB9O;Sg9Q}&vocP@;$QmQiS2*vP1GGP>B^)vF&)5It31_jq@!Hd;i-aR4 ze&JD{n>^{^PaV#>$(y@2OgM|>TfhG$(?!A&6VJNumnT2J?vsY=Kk%=+HcU8+iD}Oq9^e?|^`i6h}ukM)l#CXh2 zu>6CgPZ*%vHk|c<&s}f&noqrY`kH56Wn(olewK-k{ocOQE8X&}=>@mCTCSpAD}R== zpby&dyn*&w!VweiJ>V|WW3PP9^w6j8w}NmM^b241ykT*z95M0WzrD}&vHx(+^rBPu z@7gfoEaEvN?tsF7odvLquCY%NR#C zgKkG!;zbA0#uhPJzYVdrww)DvMjKmemGAD>S}D>J+uI>~neEsjSRS*o7s}ta_HJpT z?%l0OPe9KJ=DB07>Ji)`_}nooN3;BWewHxL9Rz2IBPMbt4$z!$YirDN2N8$2A)LkX zc!oA_Q*FdiEN_d%KP_kY__@q~S54M@y57^@aD?x~NU;2Ww-KvxQa#9~y|xX1u8FvW zlj=csYh}V&tZj9aJHinYv{zl^j#yi}X#eUWm-C>y$kW)eljpOKGf^Gh6$JE{ z6-#hZ9o~*`q$jFB+!1jqC)MHI_+n_SPkjjv@xF5&VsJKdq+58f<4V! zJ@K|z5YF;mXt%==6Pz*CaqrqN;jD$dTb^EHPHyB)*;zG1xDIYzomn2QsAa9Th%oVsllJtG^MGac8xDr*ZIhR_k{U3ECJxH*Vj~YW;R?^lLQ|G2eDp z>$fAAJ*oP&(-=b+R=>6^SHHF+ytOevFRY&MitX^an}~6GVfBP})5f^&&SDLBzgF=F zcUJ3n8b@(wwSK30`+HWc->wZuOmJ+f^}B*_R^AbxRqMAS95KPUP_5q;gtPLF_^evL z^Rs>HO!QG>UsdaO#S!#gG{Lc{)^E2~CY$h7g z6VA#T@w00Ec5OIfBBs^OYW;R?m~d9Cn_0DfyEfuP?X1@CG!E9zYW?ov_rnD3RqMA~ zEAMw_Ex$7Oio@Ant=~OdD-(Rvs`a~Kt(>*|>f>*%zmE{r`t90q#6(=FS+#yw5YFOS z$@?W4x1l2(F%jo$R;}L^gtL5{+V6)WCSs-Stk!SWh6!i+d~4f?>G_^&X|U5YA$@ziN|rgd-++`lz<_3c^{;xL6I>j&Q^T-_2@auOOTiCw5kC z*^Y3;1m|@1l2;JUTK=td!~{pS+RI%VCY(xK+*2;vl z;>6CXE!z=}m|(A0zj_7Xtk{{eYRh(nv)FIdyxv$&IAVgUYaK_SYr}-I;*ZX%W!e#r zm|!2)(H2$^&f+>&M~&zRM@+EStLeRha2DHFz3q@mBlN}%Aeb=l?i9DOz-d_LC-usC!-0{J~wrk~x36|;EUR*0jOk~`|4f?6mo7=Tv!dV%|a)Vy=^v!leMutou z--$!|D`)gi(odOw#j;GVGt2FEkTph3WE9K|dLYxsxPovN%k+yc5{{V2*qj^m2&eC| zYr}-I*mC-*7q{H|1cFKfpX+_tZn+~S-1c(9SsWXB=ogQmBPNz_M}GvzW5ZR6esQi! z?OHkFqsb>x1>js*PB_cgv6gVe#D0&x&IVP0^h$Sam~fV_u1y=eGGb)08q+_vo)II9 z)tH{0^^7rD+@|T@HWsTfJ%fj5JjP-*=C^KHrgxa-mdMy_ z#cE97%sRa(^oyqtWyM-~O?rZ!^u_Hk!Sa}u5h{z-m|n?ltsF7I_R&Ym_O;u=){a}~ zEzhWF#cE^}wU)@pcg1QS?^NVKE5{{VQXwvJ<(OgbAD`QL+ zt1-WOx;7j!!P!HvGiOiRh6!h7q>~MLo%6e=Yr}idd)NE0ZNm{094BfBi$~CevwViO zZFqgX9T`n!gI?$Sw(7RS5fgkr=yhKFewc7p#+clo*Ezqfx;7j!kS?(^s;dF(!-En7)}k{0^F+J$juN*NUS?Rfcb;vzA{=e2wC4 zr`MV9hd-%3f{vKrn?|oQ-?Zg~vwT%*34d$-eT1Obnd?|fIAS7WOctv#y)NDHFySn& zcJw-PeQeus#6-rJELLNBkGeKYILrI6ZNm{08Dp|ojp^U&*2;vle7?19aJ8g=m#byQ zm@HOfdTkH$^L0x&Vj`nQ7ORo5AzLCNI2NlheWHhvMb9=_zG}CGBPM8%o^94}IpM73 zcLT34Ye@etYv}E3+i=80#+WQtV|sAAwKCx>{=VB^EW0wAWAO(Wc~QSPru5j+bH^Bt z?OHivLcbY0!fj+U$Kns>*J{&V+lD{aL`HKg{$PHGc4xZ@XF*fDr@gifpNZaYJ{MZT z5fkibssM|}!-TVZhPG|^dd_v1{&ud^%dhQ@nBY4|e>>Owwha@`%4m)o^tY$qtlL+P znBY54fBWKZ>}95KP2f&TWzr#^3a#KQX<8 z6Ys-zI~*~QQ9?K9PfY(`w^k;cl~MOL=ub=!RYy2tBBLN~(4UyTz!ikEGU{IOywYRT z5#A>}Wzwh56RY=OyXB6U;MtBo{l#Zd6V76<)2F}tGjWWV;MtBo{l(`*f0na2HuULp zG~4ZP#01ZF^yx1?Cz@~;$A&)r#bfS>3BLdI=`TJfns63JlRo{$WA2CvzBlygFJ4Pb zIBWU$+z}HTS^D%Bzk?>65uo`9Ycu^Bh% zZ^u0Jns}RH9d2SD;uNl}nTRDfU}s@zv5afSatyrz2M@EZB^>DqY{1n7^q4h#{_^3h zd!9Kx_Rv$hHXJb#H*pjD5T|f)t^B#SeD`w(K6g3c2<@4`oLp?f1j}RA^1bUwPhg)e z9uE^Nk6AvlYiqF?cX7;d6)(EOyN2Vx^UUFvZ~CL=2>QsjL=46O4-)e*cHw}Rh#|-_ z#v#is;fM*hy_|3s%kTQ@mrYsQmT<(x^6iMPIpA<&o3V_k$?}hW_iu*#|HY}(hh6Pw zxh8sFInon5-}IzmH32vG5fKiFV*bHD^iR#z;5|8n=)3TEfTKXH1OA0q+uru_a>rZDRdl?8PqJ z#4^MXgustnB;1BScRAsR3EIQ8q`h{nOgPJH+Y*lS1g<69x14|;v%IHU!jYbM`Ss74 zE*?P>ERR|35q#Uv{=J-6H+bqJ7;T|=1-be&N3YN@PwBU&SIHopGCqE6A!-sO$MF@-n-W|vjuL$ zgtJ)YNoJ97#Kgbf@-72U1CKcdPuOjka2Crv^(_*PnDAb2+c4oQmbZ_`3HQPk%_!zi zeOYr1d~9y>pwG^D;<(${Sn(zt=?R`o7Kz;LXBx#}HjdTsnswrx0K!fh`noCW>T`#pJ}y_Rsq1k2mo@u)wz zdHFT*jDNl3j<>$@sNuV(WxU5zE}mZc{Rfukgu{+`*YvqhdwO|(IP#SDrwtR1nBbEh zd9#esnon9zIEzo>d1bMUeyw=oV6EI<+lC`7kHo9)ezWqF@$ru`!iKlQgtJ)YnPHJ| z#KdQ>aGl}&$31y?^rv3dwPC_pEZ^rNr%e|LM@;yvY`4RNv-~YsTYKLnPb$a!O&>aA z!$;7^;8EusJM4Y?S57~B6=sh%@h`7DbKnW!7jIU^#o4;!{Q0lGX5gvjw_bJqTzyP9 z;yaG-T`l3Y@|v)G`fH9K7T3xV6HolsbIX&=z6UV^jn~SAvsmUyW|45j#F>BkqJig< z_g(hCT^lBx#WGJ$i-aR4*y}uTu-Dt|FySm8rOX-v0_dm;Z6sR1*^!IGF;fM*hy_|3s%h$W!E2gY%OE_X;`F7}DL|@GK zd^Nmt^J>HGZ*|)ADbIRI*M=iKar|wL9##|3W0v<}yB&`71W!xs_2mTgnB_fP`eJtR zyi4Cq`d?;s1go-K$1I{}WmZSIN*n3D*&-Z)Ho;R3eKyMp=rJq39J?aHd8D4$mH*{^7a2Csd`=FOh7YRp9`1rS5Zo*kC*IxixtMtW` zy-UAIe&d%X8Gf7ls-1q4@+8Br?v`-G1k2mkcDLc9=Hs7!l35+us#_})&SJTaK-CeB zm`FcKc`l)UqumY@&SJTa8`Tkxm|!2)v8h%N&hlPw*UAwS?DaY}Ro8|IXZhHyt*MT) zpS@i^aQrS=k~S=?U&viv(*mwtmI^&mRuh z@zUvmkNwQdYumQrh>7&Yl;;xqI+hd8g8s8VJZ7N1mT<&`w{JP&ENJ?c7T3xV6D)7< ztMrqU`v<)T>4hkLB=jDn-=g$i@XM8D?$j)=t(kBHn)@!aKdB`gF>&%o&L3WUw`UGN zyxs%4HcU8+<>3x5n=TTLm`JZj=`W$@qFpN!&SIITj77o`6OVYu3x-eL=BRAPTGxgN zXR-W{H=mmA=m|$m_{?v&!-TU~u63N8iRmZFeP{j~+V_wAPA+vEei8f5ut;#N<@b$= z{E{z~6ncjAseU+|M~cZO{H(LqLyNKY8i?rHyA^`N?VHeRuuKLOkzRKd|9QPe9L!vmXCfh4}a#-`Eh) zV^*FeN*nVhna6$d$U+=>&^bK&Y(;tkdQLDRH{U^eLA8gd;ss-!JKiT#={a6`AGwCdVwl%gcz} z`~q*=aHJ==pDz-u)!6#u&wBNApJ%>gdi0L{%ZS|d4VbPCZ-)uD-L91hXF;!j`Y8kL zwS*%kSl-?aM$6`S(0g#mL7$m^c<*C}`#tYtGseEI?|aNriJ#W@Kyp_z;fM)7>0hq* z@+qIRoNyMORNp)4h<>ej_MwNu?X_(sukS^eJrAcQJ;4xa=p>JKW-g;UVXKKl{pr zBPRHy`nE_%IAVh3`mRa09gdh_kJNWGRuIneK5Vzc5fkjg`esenh6!hRPq%G&?|Q$n z{Knyo>F)RL7%|~*bK8bL%USKWR`X_1&6x6BlJ%yKY|5FzvgYi_8MR-Xo8#-}KVgR> zJprBBJVI#xkA~3P9Mp|U+qq+h&>SOFm$o83K^t=-{UqfcMW04`9?EPU^cZ-pynUr- zWsAt~?+JG@e&4cO-xeA2+ke7cl;7+v;Yd%^_e)j~&|}uwU%USFYhQTv^!L7Vm2A1U zqtAN6-Jds*wVZH-<&j7~NtyqH{*AT`6V76pXOu<45fk3)Z5t+>#WK%Y9H*9W#6)`p z^Cm|*g7lj_{$8J$-2Km=G5p1&-rpQSAKB8gvPGmnWK!P>p@(2n-$E(N^$m|4LAOEH z7%}0tmlMun`Q;xxeahOlgd--FZ%6vP$GJ<&`>ypJmf@<8|MFz#UZ+mq{RV!qcsm?{ zHt{!?9XYHfpvNrl!?q1adV(hzdRmqf&|{YOba?|}7k4#!TDZ&jY*_yyj!VZvD~^JFrrN?pyy&a;VkI-21G|VV&bj$IemJ^FP%7?dEs6i;Vt*pvRvOU z>9*Vv6X{tgbBxdr(QbzcXR%!0FX;$JOt2mAJo4=6;&zyD*77ZP#02}TzQfY(D-+K0 zUSC^Ne+fR$*hj)~FVDN2A?l@=HvJ`=j`Rd)Px?zjsK2BkpvNrrQiM={$)+Pc0iFJm z5b7^!29KA%r}0-F0_sWfCC&+njlf+@erxnHo%lMKrj-|DB+$K}cL z|Gn@Bla_F#Cw_Y13Bzgvdd$jGQt5NxxutEx5fgd3C_N!OA+&_IoaJ$A^Q=(%eRwKp z2}gROR+?52&|?;BMZeGDS~=1awbInJVZvL>9^naa_xoy$nDBlp^^dePzk`0^lm9%u z(=(18K6T@dG{@ZMLQCZCTY6Hs&!!eqdTzMSvdj|>%PrxE3AeqRa2Criz2D2HtZhp; zVq*Dr=r=OX&)8Em`QMknbb9PZPMu!m;7hwU9O;ScJpQO*H329lP)(i62-)Dd3av##-)>3h!03~2}5qHM>weQg`wauaTQIpHkmPhOt+ z)zV%|IAVh3?d{;5TJ|o_KzZ&ceKOq9e84y2vsmW2WRY;h1pBa7u(~!(ILmvzT`NaS zu-9u{t!u-CvwUpU){cJSHOe>Yp?e>(iy6^5Qp{@pxvzh?ET8-RYi{s&?pOSMZSC3j z-lq_^z1IB;F-A=M(Z!!A^mYIB>LGsZ`PVJPH?MZzhH%zfZvVy7#;)h?9pWnc?puiW z{@XovInooX?VLF9;F}cU?)%)WA)v>sM?C32N*muhn;Edaf6V@cIO2#q?{cIkpy$NH zzj3QV-1EbehJYTkPWbpwOB?w&$K(E2xXpa6zIW&@M|uK!PTc)_hZZ7aLqLyNS({Dv zdOjs>WNiwOwcF)LPe9L!Y;hsJcg+3`0X=4Aua-8lH_}G-Y9X?hcRA7%&~qY3t`Iqr z4FNr7j$Ffc;w0h{m7mYZ;-Cm11ik??k~R*cxn zx_ghbZ8&1$UoX38U>w+oyq6gyy;dfi#eQQXSN3#EyzotL8yFk+P51rs^uYI@KQOZH zAOFd>%a-qcJJ|9uVuDX%EM7jTZNr4KyboK#>&rGVjx1-4x347}G4UH;+&M6M>jU@s z#cs<@IP1orzi?pm)(<`4N*(d`55Ftp?Pg~5`~GnH;7?pIFna4R-08o|GUI@<+^!W_ zW5mS9r`|mj{CoxBES4F)b&+ty#4Y~$J#n*68t(CmD|Fjo!dYxNqqi<@x%UYK zqqp+8-iPg$J7U6ZFDIPEv0?Pq#Utp5iRIhTAHnh1a2_*yD`$SYR*v{+@=1)|%DJ$d zaF)MmE#ZiX|NP)P2S#r_<8$Bb+A!fPe;>>BHb=g+wIegXZ!%KZM}NA>6UElm*;nnB zc<&eAG%#n_5C1G<2LIC=2IdU=-8-B$9X4MxFcRbYGXBnT!dcJ%%3B8J4ExB>&hCi+ zc=uTYvv6Jhg;!1g=UuNJm|yEzFPtwk8Y;_e8&Cd+*A2`j_De^+disL*zjk1}*E9Bd z^@_Ffn)C!Cxh`&p36{sKPwzZ?V2-LkJfPolM@+DNjQ7g+wcEkgj$7z0-{<@@2j)cE z=Po_*(2u-+V3x5XQ}@5?Kb|`<%h;uty?Xk_>s&N2%h> z81HrQ2%2z~&(O9Fudlb`ikE$0V7%8W|5v{qj+o&4!FaEW-wzYc`q`~MG%()lTVMOP z-M(_f!~?$Zwt-p3&U!JwAoC=)b!9N&tn&~3*uZ$NkN6}rznl2R_s$=fW$Yfi&Y9lm zTW=qjW$dV%XB5PxR|ZE+&>rKxF0PdcXDz>$_!`C8&UmkUKm1AUb~s{!ZyMvh@=aS# zILlY1mhiXM-!2Hod*wRT5{{U-~=S4+lwavc|sz8^z!M4zkbG)EXI2!%UA8T4M$AS z9^<{ThRX?OEx#LheOW`sdu0v1eQg_#n0V{0Uo|kF*S9~_Z@CF)@%Ql;Qrm`)hiUJT zmT<%b?J?@<;#!$-mXA~0hOcT|eHitW>(%lroFgVU6B+fCD_`4&31>av_dYW)>glDo zVq^-R?T(n>%xBco#qUS|499O-eqmqzI(u(29^FwN-0a$L#7}zb=U;u3@plh-%Ec=P zXZ^;DuDZ$0Sw|mwQAc=v`JOXQD%THh-|{Ut!Ig+{QWvjq{w!zR?a`MEjFbBKliu2` zl_Ms&qB2hE;?vR}pZSx4F=c+h$>yzsjNW6J*f+uu38-`g%37*lq?Gy66iG4am5 zzCAFe?B#DfzgsI4FZ=eF2F7B&`wQPTb=&Q}a>T@cAN93?u~-i{{k*OX6V4jm^z(tS zSa0$1cXxy%CiZ&vWdmce{`j@;SV1`J0S~#-CUZNTc*%tw;r-4NAY-xeH0k5iZn+~S zc*2U*U6V76jlB8P0^WIGT*bx_HbTF~N6}u~-+ca3-9!{QKdE363mdu`Yhk zO*qTnwDx%Te1&E#R=%mr&s|4M@SSHYR<06l8z!7}y{}(+lUc@olaIAVftGh?xG zRchNX;ViEC%+9s@yTKSS!S|oBSQoDh{w!y)eT>Dr_&xW1g8LP-jM3-dJ5jqGj`YO1 zw#x~xA$x?eUw6NE$B2n`JLoG}TRX1wZa?kg9~_SO+UutuJNv+m`~2X!WjX(r=PUl6 zXO$d}`G0fbp7(sogvg~gz1v2XXX7$CEMNPrcQ3!W`2Ta_S(}GUiTvr4cWgf8sz;aQ ztG<7_x%X49RF=Q~gS%{!&3|(uS!GSg+FJgD!#8h#_T9?gzq-EB5pKhud*9nUv8?R{ zd-ZKNVuH1(+tIaQ!ddxy*$caEqlt{4oA%0fEN;0!%URjJLa+~MoBy_s;FQnJ5!~d+ zvCNU=$g#}R<~)BSe)(FPC33|x58j-e`iZjq#Q!>A^P+qFuq^-4X*cZJaKyyZqma|a zU#?$g1>vlZ{>MIrc);|RI>HeX`RqdEZz~9AJ@6JcE5uhG_l0iD9WjxuFGRL&1>vl} zJL8Z->~queI>P(i$HR1cJRC8>capu!cXT=7tmSLv$nJ>uy!D)}4HM%sS*Klchq6{5 zd+gaA;fRTczwY*hIOu7N6f*yBe(suZ))yW!Ed<~FmT<(xRsZ1dJs_O*l^5Ts5dX8! zUAi{%9V-#ObGg!#Wv)EqHeKmSw_Z+6^|{kr5em(fqumZiOg!V~cPqrhFFRoc;Vga9 zY-t-a6I$LgV&*;4w&93BSKG9FUk%Rko^IQ4#DtG#ON>V<=j(J_&Np?cGiKTnj+oFH zx`J?))~X{MF`;vM1>r31k&eim0#DuP6D+p)ly3!Gjn9!B4 zBgSLE5i~viouk=qha)Eb?>6`>XX!4{wc&^f-Mcp0waPWG?03$uUwZTLW%(hOOg5hU z*z?LVYuyt5T-~EKmbc-E3Ef4zHcU86_xX-+#Dve7b~{WsOHUtN8;+RpIo-Bl!dc7r zt|KNm&$!nv9uE`F@{w)V%E#GRdiL$M+>zZ9xx2M(nAloQR_;?}JGer$gr0FX^t8+~ ze0f6VdA=naF`?(+6@;_;-wCuce*$pCM3%=V=fyTkg!Ofno|Zep5fgf*UO_l3dwSq3 z$?uYm$eCCod8X#NTbB7I=UY&g^Gw|lj+o#%w?0#^Ae@zNb0P9f-4TwM$W@{ce3RQ_ zZo*l)@)aV_)Qi`|t%!+iefc}z8ucWrtaF{cPnQ#*O6SC$}-ogahvi?-4Xs=6U*Ch#Dv>!x7>uYa&0MV z_!nPf_M!QI^Xru(Civ~o_HhkcPB=@;-BY+emnY=%x%^65PB>yhYumM9!dY5gu^r0d zmql5_{9@_aP}am*TJG8y&xU*___b9&H&=r}XXViDT}MplTd;y~md>}1aKwbZH!BEd z>8$JsU9SdROX$TJuY4WhhzVWoRuIn8-Dk7iyN;O1)w8S>?Y6{t3^;;btMTs~&D|43 zOn8qhC!D4GO4o)XCUm#!w!>Mvt8FeP95JE$Zr6qhXX(kHBOEc|m_U&3ZVuG`VtLSRNS-Jleg6lxr#@4f1?qXZZ=}%rxIAS8t^QDda zZtL1G;Vf@oyH>dxY_Nsgg>$7Y%iJw1TI9!dWA|*bnE(?ue}6(5{t)&btm9UsCGL1G zM2_$ZVr^|ZD{EVh`EIvEk!>RF>F@KsHGd-WXE}@S1#6Wf+3hPwOz_=<*zNJy`YdPh zEry^@)gD1dc1z@{w4B(YlcnB-j&Q_8u1f!(vGahNqpJGVaes^c~`QDrC z{+G|^eKS7ieCM2dXXehmbM~AYyqbPYBtb2F<49~!LPBG3urd7=Btb2`B?957Q`~Y& zNa)QFi0Nk;B&enLRUrKKj%`pv!YfK&LC>aQg7Y@cseN~t@KY8Ol#uWpXu?l*XM$Sp zRTF;7VuF$x5grFR6D4geKdrW*FEPu<1SKRqA{4~X&IGke+D}SV0WEnOuK5hx0m%R%d-!|HN_(VkOQ_}N!tKzNOj=F}2|s%#^u%=`sHLkJ zi0QxFQ8GhfM&DlB=W5f^!VEC+iV_l-KXxIgg_&hSP(lK;@atMD6!6<)t4#BiQG4}|C*lg{iF9p zmBd;nK9IflzX{pv>pB-XwNVn(!uuofiV_lkYTTENxkr_UH*h{DZIGbWS%dD)jy!Ba z_TS7|jh%?K&#Y&!+sw(*`AF>mdyehl%+K&^0l5rp3o;`Z=`0S;H{^hws=6k{a#_gbl#78^cmK~Ul z&$c@K-7W;RcD?J??9QpmXZYmJgrMa4MQ_Pw`|*|8e}49Ak6w|ub?nXAF#Y29mK**4 z;9bIYP-~y#Z_4ic%N5y>=Uzw%O1}E*@3O^rxgtAu(?9p<6^W~}8?tl$IxhSC4}VN- z&?{>FX#Dlr?z@i5u2_C*LQt~N=htPI=(ny*OnazDuSh8CCY!pryxRSt#0I^h)@*~W z%ieqO@@&^j?oS9x-dgk8?3uBbXZJtV?9nR{5AHoFJAJ3iv(;wz`@GW?q}DYTP0SWp z`10)Xjr_}H5|o_w;5FH)&t8_zecW9=dPQR2PbOrqU3gh`a`?R{ZLqJXwb}9$vhOKd z;lp=-pLq57g5$Dh_8*(gJ@|_3?Jq9R9#mG!B9lYrONVEW1nvE1i*eb%jvbqQa=)`0 z=@rjA=x>*2lXn`MeP@quHh5kVOFp7p`X7$XR{NGSUuc5_wfy%oPbVhWCoAl9b$0H2 zmu35W=awF?2Z`Cwx+?qkA1}?G+r_yVoxGx!vH`P$&b>6-=1|#tMfG}A>m^arYn`DMs5;_KP=oA5$DgeP|%uk`8WQZXxp|v z5Duya;_Y9p5_v`9#aZVHwEtCAm05-b!vFGI)N;GrCd(@o`|p;!J@&JlC;GUY&$-3^ zyW837BNOg3N=U>u++q{%0TR@5>utkrt5n=#6Yc>@NU%-X6G`)26TbGm=GV=!Q1xHy zs#?o34@JLWiV0pd5-ZNKM0L?iuF3Yh+;2|WAVID8nv?iw$}H7c&c8albi$PE=C|gk zUb5PRZ1BWJa<`M9)*Oqd>V@W_f7G0m?Tfvlgv2xR%~w6<&I#E=lbq*88ziX3UWkdj ze`>bJZsW51CdH%Loi99;Z8CIRcG-WN?@Sw%(4LP6#vB$$NX9ul%Ww!EFH}}|b z5-XhXYWCvxS7xW^%@BJZ!|tzf3MpTV$fHgXMa59s_cKgT|K!+uSl%B!c5iGHn=+ba9PhX*m8PBE#5sbL4WtE{VSW}HobK!cl78LiCO;q zarWHOS7qP7>JMGKq859kQaS0+Pxb6pDu3R0&ziqg_<8mh3Lkqc@$u7Rz89XT+P#bC zF+m9le_1i@FD;!3YMsB}8sVAW|ABcEqPEsD;TfzAeYyVjJAL69yz9k(*ZqaaHsrjb zGHeGW5wXzF@H|c$|6#o|@hPL9H8a9$fWP``SL^65^F*7OVQHU2UIcUNU(je4YuRK?fRBsS<3wZ`lqk6w{DcH9@?OVOqe z%$nGsSJZlOfzQI1q60VlWW)Fwq$C^jN%&H<>%U*!kY|bsN=RJu%}3!&(aw{mCN@Y= zYt9k>4qu9P-Q~7~ck<-`bnPRU_ zcT)H=ksm!@RlgAqD--8TVD6J|zU9VY?X&c^@2poUyZ!itKy3Y=?^h`y;p1|(RH^*q zvy%gH<@R@FB<`xW&iniK4zJU8rSjGdt)1V`zVS!QsjQQ@_VP`F4b9uH)BjaQ1sgu% zxu}J|YfMBt8t^xoC&F71=&J@LXgR$VftIru`{@bVBmynZDIvi&sk!T47FMa*l1Df7 z%bCz8ilb)x{i3gW-m}+aTb}zsluA?nx)ef7M-T#*>vyHa* zS7+Mbxu~_-Nl#|0%|9+1^s2wy_Py1snhDcUH=$yB!?7`eM&V8Ry{`jX3K{IUEV#N37+@mi~7Pyee0%!^O&H71g>ls zf?A7>U9;L>yC%zaS~VdkA@PI5*AH)>A57{`2ueucUg$zl%g4oCk`V0CEp(kdo^QU( zxm|jf{X^p5MgN;^se9}vj~`x-dzS>YcrQdFbroZ+Ghc%5{>2lY#bwp6B>^J`= zD;lY*l#sx9ECM5SL{JMOstAnKRZ2);JQjhGIwGir5mf|6>MA89;%knPIwGjWJ0^Oc z*FN3+?l2;Myz<34-n;pT^=`=4xovDV&w&@nE6f0Dl#syNIU#6cJ$qu|-x5>yx;C*vf?DsaIjFkO?pI~=Y>09Vv|R{lu}!fJYI!#7S+VB8QGKVF;JHY6 zp6hpsX0+;Ewu1z7W*7eSt%RV&vtf^-nge&~UD_bwS+Zx#ngb^`NKlJc zwo=Kz{$H41t^L23)6x{ejr_zC$8{T60ak zDA;&r&2^+Z{N+0XanF#$Ym|`iJl8ffW=gkz{DeU4+c+vBsI|maKMXc*zs`9q^B;9y zAWoZOM2!*>p6A+zMpNl-x7O%Dyz}#8BZ68!_LJ5kJTvw~tGQg&GhokzHJ8)fFp%>z zoNP|I`af%}RCB_ulc6$xswr(>_!yPn(njiXs?k1Z#0+h-H{4;p$!Hu@j4c4;}a z*z3WoFjD)Pd!Fl2P4nK!6VF;bifXRfve71D$-q@pkK|GB&XAy%=b#?vHSwl{QmW4%YS+1)!D+$rK4Vm`-*oW39k=4wrh5qw1Wh-Jm>YO ztr=}XP~ugKM`z7kqvx@+S0ujm?27fn_qsIOe)hLp&tSXd^eWckQ~R5fpQ(Ce`1{2N z)*f2#;?RrD?T0lyw=J*p)Fpl!{=Ut~HPw#6*S#HxbqkTcwb&z-%8{##(o=UcAF5Ckf80@1_^3CJL0bV zm*Xa6AMTXepoB!+4qrK6Kwp>DmOL+i?yKKqpRIFN=+W{TkZxV;lJFDb=gw{Lv7ZSa zU-9SV8!x?hO}6(O52<%)gA&iBi?7asF3%Jbv_Zmi>Ef$%VuJ*=I=6#bo=X>Bnv?sA z?cljccrIOhLr%ORL9IcvJeA+DTPglFiW{{{HyQ`^v@{+qZJCR^H~qDkUWR z#x(6wuTuHvVKZ{f3phXuJd-k*yV-%XETq@R(bQaDKS9_ z2_O5JZ)N>@CN?7*o*x$9LL+;z4W5^T=h(&f>w0H`TK6qCxUrvp-L~27{^c3HqQvv{ z;#+ufYnlFa+jPE61 zHP4JaCTc#c{|y^8O4tjq-G!i*XU1WMJgGk+C?SD%bRnpPUPuVG{LDoMH$EOdKD+3& zXZqQuxaE|P@XWaQlHT8$pq6LG#n<74pu{s{kF}cj_UILfn|FR8UrJBy+)uxzUnlSi zvK`d&-v^#rjG~T5HHy(PtgL;PXynW=9;^=5B zj-`g))f*>#6)N5t;j5sJ{dbL@1M{n<=bFV=*)WUrc%|7`hIep6P~v%KNq9!-@k+D8 zE(EpkhD!)aNDNTH9Az9)wnvVTX>nV^=w4u`p~e^U_?l<13a7-F=c^^^T~rR z%eMS-a$*50=f?8O&i@=J$ zNeKz8?nSJ)=iU1M`kB<#heZUn@Wn#9{l%Aw17AO)NeKyja}aU*z}Jt6pq6L&es1&@ z5}{vL1g{*!qa-E#M70RdjNJ~sK^ywYSuegJ>)H-fBRTht73(kQYt%Dyy{*5Kh$RDr zX(Z|0BpuN}zB_#A+v|fCT7EP~6Q0s%QX3Jka@#^f~OD>ZTl;}Hk z_3kI;hGOzHC|2iZky1#vhrL$F7G~l#SM`^{}v&5HA8}0@;01F^N56?goNko#h2|a zM6A`R9n|vrp!kxm^L8RAA)&9s{lz!r#48fi+V-Of{aYyt@cCQbX`H=FiM}WI7hjrt z^ooS%)x{U+)-%|?9`uS@@x6d}l*f|xb>{U)WJ?|*=GCNxghrxp%{8MHkqyMvB7$0o z(1}3ou1N_Aji|wfX0#&8_~1789TE}LLZndyVvtQrNO)%Kr=WH3BF-5R)I!8mHV{i~ zQbIy+xL~6-_d&ciBBQiq<0~xg{=RCaHhI5)|GqQaHhI5)|HdqK#p=Adqpj0syky{ zdFWjTo{NMt)t#}fob<#i64YWZ#9ld5-MO#ID$hwfQ{B0*%1=+)K?w;T7a8jbK^x9g zckZk5&?9@XS3EBXXR15*RXOR24HDFHrn+-ql?k2@&Qy2qtMasSXR15*Re9(=dPTyS z>dshKPI{N?K`q`ram(qiGu55@syy@_y&~aEb?3e+Cp~F7`-)oZktmP8=_+5&OH~c8 z+%>zL&#CHMiC4(gZ_)+{R~U0Xr|Nmht4;*9T!+m0oT~Gc5U3}SyJnlSa8;2lNBxNz z5FRu1Tt|d!wmJ7zwbr^2)MEQOw}XT$usMfURn!t2JQuat>#+^?iEEuXlU0?>db}Pa zTVbXR@l2S&v?kaIG_EvZ|_CVuO7ZX?^l$sClLe zX9?jdXwGr9#I??x$*M|bJ$gmLwa%Q$s;Xv*4SGc_*E(}1t16r&1SPI@=1f*qGV9SR z60UXTOjcDjOKi|9YPr^#Gg(#PEFmaytutq`ZuI$eJ$gmLwa%Q$s;Xv*jmRr#xz?F$ zo~goFLQvvbXRdjsN@hKJMZ&etT=Ps-%@P~*idwF9=9*`!aF!61xYn6#o~e>qk6w{* ztuxm=Q&qFX2EC$|Yn{2~nd*EcglnC-=9wy)<*s$+nrEs}*2OClwC7r9u6d?vP>Btm z*R{@E^Gub@y4c`(Nx0UTYo0Cnh$|>}dK*y7XBwDgkYJy<)|qRbsghZbUXgIEGuJ#* zRkJQ$QOmW?T=Ps7&JuzW*E(~}GgUI{(JK^C9s%n(MI`u65>`XR2zJ z*q~R`itl#UI`aZjb-ZdP4AcaR)*PtTrCA?ph1DoQ<*z_{mD*adpz>Elpr%)Ywxh~l zkyj*8`Ac4*=2=8g3$@Thpmtl0^DEA&P}5Dli~4XiN=U>uQ0*-usD(OivVm%EHA+aZ zO|3dhzJjX%(Qs`g_q%dy!?9<8K6afYuLo6KNiBC}rjnopb)*}pXx)XNmg_8e#j5H< zDWN(`UO}o3PQ!JUyn<8}C20-pln{GG2?^I(@@i7`krEpus6`KB8I=Zv*A0>n@>JwBb5SUURC7Qe-bC z*jFT6XUS_$Ra8p6B0(+JS@N1wb&L|ib(Xy5RF$EI>nwTAsVYi6dPTx@mb~UvMWw_B zy`q-udX@KE+;aNsI!j)2s)|yNUXgH}C9gSEQK^ep)MAeWufn+Nr&jk>`K8fMZ8-K* z>pDwb>8biq%SM}^goKaF=RdaLI!j*Hs$NmlTGv_fT20lJ5*x8(;7+8su?-T`a-Aiw zIaOULu|Ww5wlB89cDT-x*XOFD6tyWPc$biHoh7f&RZ%JNiUhS>XUXexRaZ&~N?d2j zt5j7{>d`9_uCwG-swyfaHs}?#TxZFvR8?0>2ufUM$*WXVQR>kv60Wo4RjMi~B{t|4 zwOnV(Yf)8KN(f3^XUVHnRZ;5ED-y1=*x z(JK#5=oPhGXUVHnRaZ&~N?d2jt5j7{>d`9_uCwG-swyfaHs}?#TxZFv zR8?1My>Z&34<)X%GdrG%iwb(XwJ zRTZTky&~Z{OJ1d_qEcdmUQx?+mb^+;jiH2aoh7eQRYfUxoh7eQRUfH~S0rf9b(XwJ zRVA9l2G8p{OJ1d_ic%LFJTD2?S@J4X6_pYjBx0>(Uedlx*e9;DGdrG%iw zb(XwJRTZTky&~Z{OJ1d_qEcdmUQx?+mb^+;b)|%$#C4XuN>vr59=#&rI!j)qs-jY2 zgI-Z9zS~`ANt&)DRKwoX(Hh5fmOS@SjUkP2uCru9^@?hgaE;^Rf!UJlESXUCp@?vu zC2Og!P=mHB71voZq3T1CS0pNxWv(@?>O=Bs;J;B3K`rl%>vfxI7q!|EIJbkdJ0F*; zJGHNWpyleTK)A0cArae9%X52Hw7h*TYN<`(@9u@r@<6!dl#pPX!WXZqZ7AO9h)HhW z{jcMjMP+VBGeRzaV-_(%2?@tHi^|+x2x|FE?yKo-IKEj_=FT18EGl#Rn@ro=*ehx| zzFAb}?n3ZfBplx?Dsw08AVDqmLhO~}n_hD&78!Zs_-0X=JF!6t?fE$R0@=QTwBh(> zQJFik7kkC?l5l*}YfeQn6R${6%kj;kGIv5azFAb}&K=(@Ds%Vf6$!^Ti^|-I4SGc_ z-aT>4>96CPMP=?Dy&~cGW>J~Di&xZQkF=gWKZE*~Ty=c2*wv`v_-3(3kz@3@+x@hb z1SKRK-z;`i(#X(>pqAsC#lA}k;iuA1r=L>CH;X;0{5>&v<-f-^C?Vnarq`T`OLifs z#rDNEC?VnaX0hW`VuJ*=*z2(k_KD-0#okUmUJnwEZx(wy=`QJXJ*egQX0f+ZLQvxP zX0f+Za_@GsLBjFPVsEF!2K$Oyj$#&jJ0%1qj&BxwJN4)l3CA~!y`2&p^om-JZx(wy zB?KjoZx(wy_2?A|$2W_;oe~@Lidv3u7JEA-1SO7d7JEDO=oJaaH;cWU5*zf2T8?iP zdpjirC5~?vdpq^$6$!^Ti@lu^8}y1=j&BxwJ0%1qj&BxwJN4)l3CA~!y`2&p^om-J zZx(wyC4}Rf#okW2fN;TD^450IdiTW=d~TZr%mLh;TTB_!CUR(#Vo6#HsAI^uJA zP3vQ~*2j)-dOfJ9W)>5akSH@89ewCbP|NX6uUHlJO9;m|L)>ZT%l(dTdIhQIrR&g# z*{kxBwIj46K4m*7i3mk$yqZ*8vcEIoC}^og4`YH75{_?r&8bLc(hd^T>fCb2H@)Um zEHY}X?@PU1SKSVTs;2?;rM2;uS}i&=J;l@uS`9*K?w$7YB|1H>?@NHlsLXw>?_lw zS0o(YEcTU2Y|txeIlfu!E0YkEIKElzE7PM_Bplx?_LWI&&?{;=zFF)mlMs|RzFF)m z)1y};9N#SVl}T*SD{48u=~b$tnh8OPifSeVC5~@;m8$4vk6w{*eABB`MKY7SgkDk0@lCH%71c}#N*v$xDpk?T zdw8bKcL@o{H@!+#Br~zWb5Se4+a0s>+Q2b9$N#*paZC+!pAg^l+{dxKR(#Wh;+@`I zCCrK}A%WSF=GBh!nQ+vPgd=-Cuj6^N-HLCTP`opzgoNXprlq#Lbw>poJ|aOa{9R+B zu^F(+n0)6Ejb%J%Z+p^-e0xf4RdKaCtr@dEBIFnfnVjW$L2}(#PQ#1U2*Lw_iCaC2z*;{>~NC;)*G74aR;S)Xk!WoPDIb9!Il&IBbSl&KkhTkAcBV;dx>#a@UB$2Yy^^e(}q zm9-h-oZfFZCMY4{UeT8W|CMY4HOwADI z^d7^V32L!NqUdW)nT26JsK{HU?98x^QuH$M$`MhIKDz6@Z+IC2jR<9GhIN!8newU= zK`rGjHi~@Cgur*hO!=H)^{eP*h*V8)#qLh$ue6z^s>_SkB?d#kQ63WyJYiC6= z6B|4iwb<*i4fct$Gs6l}(aRpM2MJ|rhB&7pnO(f1ma;ZOoKsQFgrG#(nIX=p=w**y zkx-^)h;u5Enb=@oMOvS{8RDFZY9@s8IolFtXNEYZqL)2-MM9aHAb0ku|cn>rQF4^f>dlTA(WjNR*;HbX3Dz^D@es9yLd%{ z_LSikR*;GSB{q0o$2Y?Y@^9U2@Vq3HsTo#~iex4>NKngvADCtE{lPv_c4k;XDtg(a z<+MRUnVMk*sYqrQuc)Q0&9H)0R5KwcQFdlnK`MILqgN!9sTo#~iex4>*bZtbYcs4M z71c}#N|c=$R*;Hb_UIJ}Wom{Mq#~J#4SGc_Wo?EPq@tP$L5bs=MLuVbUXf6yW>`Tg zl9||`SJaB{c1J5clW}$Inl8MG=mnns7cOZScG? zf%ssP5)z04%7!DNw&8q864au%QM|Uv`IV2$nG@o;>RrTyo0O1XFSO#D_R1NpB&dbh zt!y~HX+rI3QbHnbhvS$u7uSigWU;I{)UDbu4mgAd6 zK4(fOzFFkgRUO|f@;RmT^z!yl-#XNCdPNBd$2Yy2R9rH#L4sQJFt$Mn3CA~!e9puM z32Jq2x#OE&b1D`YwN_c1{Y5@!Vk4HYf1Y06Z-eRkiZ+y;*wE7x|n~ zn__}@2?=Ft){A`3#48fiQr2d@$mdK5N|c>hFY-Bi^ooQsHS0w_XJUh1QOohoBA+uM zC{cE1y~yY6(JKhFY-Bi^ooQsHS0w_ zXJUh1QOohoBA>JMc5aV8lsLXwgJ$7SZE2;@OVHhA8cKpte15)#OElnqBj?V0i*BO=xs@HWazwO8%gosY}a zouim;pQ4(rc7*mT-r1yt1bZPwc6C)kyfY%G<@ly;DBjs>M^?j3o6W-C_j+%1JtioT z2SLk(W9g>d8=VPi;Y|Gw>rV9EK0dE2n4=wG9~=MOb?RfU z{QJ#PG9yCko-Ra5Tg&?u`AqU9{AOanD@sWCS0n|YUy`@}Yqf&}wMyFi2E>G~me1uj zw4cETvj(2DMoi%TG10o0wC|n!&S!F8#sqEfyuLe3_)5kEB_yn6LSso6f?9Z1rYFj$ zGf2ww;z{d5P)qF#Eq5Qr?QjIw=he4Fe?6`GSl|4r_x|9M@b{lwG^836l#qD*odp8D zV>VktP(s3XY|np-ZIGbW&MU7Fh`$~BQgZK7Lc;B`4YxD4L4sPk69ch8pW~dZ|62F1 zYtQ>!u7W?uw;SPjrYqK{x>COXZZak)Au;0MTYDg=<%<8d(b`FXUQt3~wi{0g#BMM5 zCti`D7M_)apk#)`bR#v1_OZ0^3??=xA%T0h3qdW9g)_b$l#uW!_x~qit$UX@(b`vr z*TZ{Sl#-ZuI{dx$CAAabd8uh@c`WSc6(j?M?BVaU!E;edy&j0^XEKzKP`?F2W6AW_ zqkS%F>1u|*Pyarrgak&^#73LYEUbO3`%3q8urb5uqb(t!`#Ai4hR;Wvpq8Gl@b~GT zb4Ox)r98@bPcCMY2x&jQif z&4YJ|#@*n%$8e30;n-s>+ZWrQghcs1pMDf2K`r(|XB!&ZgI9iM(A$`xgoLO-`wh{V zpqActp|5869&AfUu-9W7JQua}W(a5UyCfzkA<_8?lAu=SdzTUtdUpk{roY=sP^4At)h%yQd35t+J>6T+aA z2?@;MyAagEx+EbeA%V3>7b4c$=vrTMe|w5sUa1U7Vxlt1gx`9d2}#;o@;00CeU(Vs zgzWV|P)ofY2*34WuP7m*ehY-(jhzW<>1qZ-Yqf-+gap4c#Wr+@w_B*Et9|S_kNe7R zy_jg*&|Td=mM5JFN=WF=4>q*AOKgy!7QKzV(pXWozaA~iV~-XZ?ZV$Z*2IMV60CbX z)OZz+J(}wM7>@m(j0s9eXsir`$IQ+IwK{u62?==?+ToEkwn2hgWiL$s{@`_HkFrN% z8SPhE{ip4HDGSyFK*P^m7JENN8pd2(76T8ziWu za|gonh`1e;kl?k62}($4W)N&>b)Q^w64dH^%}a@&iSpQYhMwK3p8bTNgoNhTJrLB=cpC`6_2S;uxEdsWKWS|cjvbrQdN&+TA6=q^gkzE( zV-Ec5jY&L;1hw$@B)Ww2I#yJAn1N0RN=S6J!Ty0g$5w*9>HCTj60n!_E(vOtcZ_EU z@%5l&Mugw-or#jRmcQ%zdPw`)n4pA&zu5l&32K$JX9%&48EN^w-kG4JJT`$|NNki^ zwoWbddO}b_0#~yOK`lI+2|)=7+;3e7YGI5?2ues`l;}cGtL#I+_2Mf?$&3h%k6nn8 zwie#O2|)=7jNn}eYGL+~5R{O>{Gkg$Exfg>abHnF0`K511hw#PPY6m#;7y$n9Q!an z)^Xfr6opn@zZ?i-;`F~xfL1@Xa4Z|n_H~ab7t7U#v#|@G6ZT4VJ8s|lobctJZR$>V zjPjLKh2U(&!Dr{npjFFhgA$&X*QPT;tv@yH%NAPU?EJ+Iiah#uJDi<-;A&%X?UXaklY0kO(lJ2^31<|4{nD7+d%<=l zsMWdU&gz|g%$d3OW_3>R8eg25dpB3w?rejE^O1+|cUJD*V>=Vn>fBe(>izz(Gji|E z>YU(DetSml-CTR~iiGo#cU9mV4LL*apw*yyN>WIX(A|v7}>y5)#gNz9>IE>}lJXpcZ>QCY+-?Vzbe? zcUpCZ?+#~<&b@;xZFeT9s&oZx%&Q*!Tb+M8D-oP&JuH>c#@J+`w~)MAfJPwa8P$lP8y!}rKvjLf|^Yj0kW zP;KPw%(F)3-V1hm8-8c_oYZp8^Z2nN!=AP=;r!VP?;4eR=Tm3m)?OHud*9T~UQx># zzMpphU8g{ zYZ6VI`J7zUhx~hnFeCHdrzd>3r-bVvoiOq2Ty=iB5Y%G(VjGl@aJ8X9%blI8u25ow z1hrh{7DE(T&w8)M@Q$XE0kP8&q2%H zrB@_e(dg+5M(3(yl-M9aE&sh7$Kt+X3$>3;b-ByN9AC5R~vD;yM$9Z%at9 zO|7hc6UvUS;aiV?y%A`C@hrbNw7#l2qqrm}A))H#VGQD`WbrkJ3FgtPiRiYgnw-kG2lzt6=4C92F_^|-6d^}6bMS3T}}ALE#y#QFLj zcfD6K&lD4skWj7is>faL&D@!wme1sISJzEnIe7)yT2*`xojU}p18Eh1FIopIYw0vIYl=0hHE9=ZQin^R_uShsY&a~97vu^9x zb3Wp^sD;0)ubiQ0?V>JcIG4vLw8K?IOK(LuPtAn-%5^#05)!cuw4A-@Dw}1ST$eMP z$=PX9%R>fR(LWKvHbvLmyGNAmh`!LfE`z@Ts#<}r2cFs{C1^)GZs3SOX9DA+_rR|D z>!5eOjtNRg40~jys=xKEzSPVKp=#_^f1&g4)2iQI^>;t-SIws&wm~h`h_CwVp!dY? zOi)5X_35kr?x*?2 zLGPkXZ(|#jkWdx-s=p3;*Y3^)wRoLkLN(&6{yOMAu~k*R>aT;|MVq!`f)Wy{Vqf*w zLGRk#nV=SXBqmhlz3Q)n-ql+5;;a5T=>4&2yE8#8Re!Jg>!5eLjtQPumFuhiI_RCc zNyh{wBvdKC>aT;|8N4$=E%tg$sN#G0I_Mp)RU^LYuY=wbo3=X>)Kc~L@O99;UB?8^ ztIG9Ne;xEr-K1lJ5)!JKU-j2PRh39=kf2uQ>!G^v;p?FH!B&O&@O4lX7&hdYI(tPz zRqVspLGRk#nV?qZzEXAc@O99;L95Ps_&TUM1U-61LRIX;*Fo>v-PtQ@u}7vS%GsT2 z#D}kg-V?jGz9QkO4*ojmJ-Da0QAWL~r5gC*>!A1ijtNy@4_^np!;2+_6_Y7qxh0V?s6C!`DIYQLT#a;p?DxxaOH+f)Wy{ zHXptYdUx&41hv?QF~NR+>d;rh*FjbGSf93If)Wy{_#VCvdWY-I1hrHzK71WiJ%xmz zM0M!H*Fo>QP1~JqkWdZ$@O998es?CQ#p|T$-ujn?Rcf~6(M`s-|2NOP)xY09CVyw| zKco?N5RAB!*zXs8)y0ONlW%$M1DgBL1_^5U@16}h_8k-S%Exb=bew;2uU6lX9kkS_ zeDDDmBm^b%t$BC0>F87P$;(}w@l2g5!7Oj!~`WIe)QfQ*{_cqlP~$hc@i5Ws5NCT)!^Oy zjC|H{)6{Z$Wum+@NDq1R+-#xKPRdXIwKEP$P(tG4l`qbYKmC;a)6MTr2wES#*u?Bl zm!F35oXap7mSEN~M4N zgh1@uI4UBjwZv9G3^s1R&J{N1KkB?doHoaZCM6{B3v&_Mtu;Cj@BIAOh@h5_{dD