From 1a0edcb29902a803eaed18d85862a2fd025df503 Mon Sep 17 00:00:00 2001 From: Tucker Alban Date: Mon, 8 Jan 2024 19:24:58 -0500 Subject: [PATCH] Add vehicle configuration (#2130) * Update truck urdf. * Update truck * Move assets from ``smarts.core.models` to `smarts.assets` * Renamed vehicle.urdf to sedan.urdf * Fix sedan vehicle urdf reference. * Update substitution configuration loading. * Allow vehicle composition. * Add missing scenario_definitions_filepath property * Add missing glb files. * Fix trajectory controller test. * Fix collision test. * Fix types test. * Include smarts/assets in manifest. * Add default truck definition. * Update test with truck. * Remove unused files. * Change [resources] to [assets]. * Retype moving_truck definitions to truck. * Rename vehicle_filepath -> vehicle_dynamics_filepath * Move MACOS gui BulletClient. * Remove color dependency on VEHICLE_CONFIGS. * Add visual_model_filepath argument to vehicle creation. * Fix missing argument. * Fix plan frame generation. * Update changelog. * Add type checking improvements. * Clean up vehicle methods. * Use PyYAML cast. * Update configuration with `SMARTS_ASSETS_DEFAULT_VEHICLE_DEFINITIONS_LIST` * Attempt typing test fix. * Attempt to fix typing test. * Add missing docstring. * Update AgentInterface with vehicle class. * Fix pytype types test. * Move all vehicle related assets to `smarts.assets.vehicles`. * Update truck urdf. * Fix base-tests. * Make format. * Fix types test. * Add moving truck to options. * Add trucks to tests. * Add pickup truck urdf. * Fix test that broke. * Update to final vehicle set. * Update documention. * Update engine configuration documentation. * Add information on creating a new vehicle configuration. * Lessen redirects in test-docs links stage. * Remove accidental method regression. --- CHANGELOG.md | 13 + MANIFEST.in | 3 +- docs/benchmarks/benchmark.rst | 15 +- docs/conf.py | 8 +- docs/index.rst | 3 +- docs/sim/configuration.rst | 27 -- docs/sim/engine_configuration.rst | 68 +++++ docs/sim/vehicle.rst | 150 +++++++++++ envision/server.py | 8 +- .../tools/pybullet_linear_tire_example.py | 29 ++- .../pybullet_sumo_orientation_example.py | 9 +- examples/tools/pybullet_trajectory_example.py | 15 +- examples/tools/pybullet_vehicle_example.py | 3 +- smarts/assets/__init__.py | 21 ++ smarts/{core/models => assets}/plane.urdf | 0 smarts/assets/vehicles/__init__.py | 21 ++ .../vehicles/chassis_params/__init__.py | 21 ++ .../vehicles/chassis_params/generic_bus.yaml | 8 + .../chassis_params/generic_moving_truck.yaml | 8 + .../chassis_params/generic_pickup_truck.yaml | 8 + .../chassis_params/generic_sedan.yaml | 8 + .../vehicles/controller_params/__init__.py | 21 ++ .../controller_params/generic_bus.yaml | 14 + .../generic_moving_truck.yaml | 14 + .../generic_pickup_truck.yaml | 14 + .../controller_params/generic_sedan.yaml | 14 + smarts/assets/vehicles/definitions/bus.yaml | 7 + .../definitions/moving_truck_empty.yaml | 7 + .../definitions/moving_truck_loaded.yaml | 7 + .../vehicles/definitions/pickup_truck.yaml | 7 + smarts/assets/vehicles/definitions/sedan.yaml | 7 + .../vehicles/dynamics_model/__init__.py | 21 ++ .../generic_class_2a_truck.urdf | 166 ++++++++++++ .../dynamics_model/generic_class_4_bus.urdf} | 0 .../generic_class_5_truck_empty.urdf | 226 ++++++++++++++++ .../generic_class_5_truck_loaded.urdf | 226 ++++++++++++++++ .../dynamics_model/generic_sedan.urdf} | 0 .../assets/vehicles/tire_params/__init__.py | 21 ++ .../tire_params/base_tire_parameters.yaml} | 0 .../vehicles/vehicle_definitions_list.yaml | 8 + .../assets/vehicles/visual_model/__init__.py | 21 ++ .../vehicles/visual_model}/bus.blend | Bin .../vehicles/visual_model}/bus.glb | Bin .../vehicles/visual_model}/coach.blend | Bin .../vehicles/visual_model}/coach.glb | Bin .../vehicles/visual_model}/license.txt | 0 .../vehicles/visual_model}/motorcycle.blend | Bin .../vehicles/visual_model}/motorcycle.glb | Bin .../vehicles/visual_model/moving_truck.blend | Bin 0 -> 991416 bytes .../vehicles/visual_model/moving_truck.glb | Bin 0 -> 43140 bytes .../vehicles/visual_model}/muscle_car.blend | Bin .../vehicles/visual_model}/muscle_car.glb | Bin .../vehicles/visual_model}/pedestrian.blend | Bin .../vehicles/visual_model}/pedestrian.glb | Bin .../vehicles/visual_model}/simple_car.blend | Bin .../vehicles/visual_model}/simple_car.glb | Bin .../vehicles/visual_model}/trailer.blend | Bin .../vehicles/visual_model}/trailer.glb | Bin .../vehicles/visual_model}/truck.blend | Bin .../vehicles/visual_model}/truck.glb | Bin smarts/core/__init__.py | 14 +- smarts/core/actor_capture_manager.py | 11 +- smarts/core/agent_interface.py | 29 ++- smarts/core/agent_manager.py | 1 - smarts/core/agents_provider.py | 1 - smarts/core/chassis.py | 48 ++-- smarts/core/configuration.py | 64 ++++- smarts/core/controllers/__init__.py | 5 - smarts/core/models/__init__.py | 12 + smarts/core/models/controller_parameters.yaml | 76 ------ smarts/core/scenario.py | 17 ++ smarts/core/smarts.py | 20 +- smarts/core/tests/test_collision.py | 5 +- .../core/tests/test_trajectory_controller.py | 54 ++-- .../test_trajectory_interpolation_provider.py | 2 +- smarts/core/tests/test_vehicle.py | 6 +- smarts/core/utils/bullet.py | 53 +--- smarts/core/utils/pybullet.py | 54 +++- smarts/core/utils/resources.py | 82 ++++-- smarts/core/utils/type_operations.py | 4 +- smarts/core/vehicle.py | 200 ++++---------- smarts/core/vehicle_index.py | 243 ++++++++++++++---- smarts/engine.ini | 4 +- smarts/p3d/renderer.py | 12 +- smarts/p3d/tests/test_p3d_renderer.py | 17 +- 85 files changed, 1743 insertions(+), 538 deletions(-) delete mode 100644 docs/sim/configuration.rst create mode 100644 docs/sim/engine_configuration.rst create mode 100644 docs/sim/vehicle.rst create mode 100644 smarts/assets/__init__.py rename smarts/{core/models => assets}/plane.urdf (100%) create mode 100644 smarts/assets/vehicles/__init__.py create mode 100644 smarts/assets/vehicles/chassis_params/__init__.py create mode 100644 smarts/assets/vehicles/chassis_params/generic_bus.yaml create mode 100644 smarts/assets/vehicles/chassis_params/generic_moving_truck.yaml create mode 100644 smarts/assets/vehicles/chassis_params/generic_pickup_truck.yaml create mode 100644 smarts/assets/vehicles/chassis_params/generic_sedan.yaml create mode 100644 smarts/assets/vehicles/controller_params/__init__.py create mode 100644 smarts/assets/vehicles/controller_params/generic_bus.yaml create mode 100644 smarts/assets/vehicles/controller_params/generic_moving_truck.yaml create mode 100644 smarts/assets/vehicles/controller_params/generic_pickup_truck.yaml create mode 100644 smarts/assets/vehicles/controller_params/generic_sedan.yaml create mode 100644 smarts/assets/vehicles/definitions/bus.yaml create mode 100644 smarts/assets/vehicles/definitions/moving_truck_empty.yaml create mode 100644 smarts/assets/vehicles/definitions/moving_truck_loaded.yaml create mode 100644 smarts/assets/vehicles/definitions/pickup_truck.yaml create mode 100644 smarts/assets/vehicles/definitions/sedan.yaml create mode 100644 smarts/assets/vehicles/dynamics_model/__init__.py create mode 100644 smarts/assets/vehicles/dynamics_model/generic_class_2a_truck.urdf rename smarts/{core/models/bus.urdf => assets/vehicles/dynamics_model/generic_class_4_bus.urdf} (100%) create mode 100644 smarts/assets/vehicles/dynamics_model/generic_class_5_truck_empty.urdf create mode 100644 smarts/assets/vehicles/dynamics_model/generic_class_5_truck_loaded.urdf rename smarts/{core/models/vehicle.urdf => assets/vehicles/dynamics_model/generic_sedan.urdf} (100%) create mode 100644 smarts/assets/vehicles/tire_params/__init__.py rename smarts/{core/models/tire_parameters.yaml => assets/vehicles/tire_params/base_tire_parameters.yaml} (100%) create mode 100644 smarts/assets/vehicles/vehicle_definitions_list.yaml create mode 100644 smarts/assets/vehicles/visual_model/__init__.py rename smarts/{core/models => assets/vehicles/visual_model}/bus.blend (100%) rename smarts/{core/models => assets/vehicles/visual_model}/bus.glb (100%) rename smarts/{core/models => assets/vehicles/visual_model}/coach.blend (100%) rename smarts/{core/models => assets/vehicles/visual_model}/coach.glb (100%) rename smarts/{core/models => assets/vehicles/visual_model}/license.txt (100%) rename smarts/{core/models => assets/vehicles/visual_model}/motorcycle.blend (100%) rename smarts/{core/models => assets/vehicles/visual_model}/motorcycle.glb (100%) create mode 100644 smarts/assets/vehicles/visual_model/moving_truck.blend create mode 100644 smarts/assets/vehicles/visual_model/moving_truck.glb rename smarts/{core/models => assets/vehicles/visual_model}/muscle_car.blend (100%) rename smarts/{core/models => assets/vehicles/visual_model}/muscle_car.glb (100%) rename smarts/{core/models => assets/vehicles/visual_model}/pedestrian.blend (100%) rename smarts/{core/models => assets/vehicles/visual_model}/pedestrian.glb (100%) rename smarts/{core/models => assets/vehicles/visual_model}/simple_car.blend (100%) rename smarts/{core/models => assets/vehicles/visual_model}/simple_car.glb (100%) rename smarts/{core/models => assets/vehicles/visual_model}/trailer.blend (100%) rename smarts/{core/models => assets/vehicles/visual_model}/trailer.glb (100%) rename smarts/{core/models => assets/vehicles/visual_model}/truck.blend (100%) rename smarts/{core/models => assets/vehicles/visual_model}/truck.glb (100%) delete mode 100644 smarts/core/models/controller_parameters.yaml diff --git a/CHANGELOG.md b/CHANGELOG.md index f0f8409083..9eb690d6dd 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -12,6 +12,8 @@ Copy and pasting the git commit messages is __NOT__ enough. ### Added - Added a utility method `SMARTS.prepare_observe_from()` which allows safely adding sensors to vehicles. - The following methods now exist explicitly `Vehicle.{add_sensor|detach_sensor|subscribed_to|sensor_property|}`. +- Resources loaded with `load_yaml_config_with_substitution()` now substitute in SMARTS configuration with single squiggle bracket `${}` syntax. This is currently restricted to environment variable names prefixed with `"SMARTS_"`. This extends to benchmark configuration and vehicle configuration. +- Default vehicle definitions can be now modified using `assets:default_vehicle_definitions_list`/`SMARTS_ASSSETS_DEFAULT_VEHICLE_DEFINITIONS_LIST` or by providing a `vehicle_definitions_list.yaml` in the scenario. These vehicle types are related to the `AgentInterface.vehicle_type` attribute. ### Changed - `VehicleIndex.build_agent_vehicle()` no longer has `filename` and `surface_patches` parameters. - The following modules have been renamed: `envision.types` -> `envision.etypes`, `smarts.core.utils.logging` -> `smarts.core.utils.core_logging`, `smarts.core.utils.math` -> `smarts.core.utils.core_math`, `smarts.sstudio.types` -> `smarts.sstudio.sstypes`. For compatibility reasons they can still be imported by their original module name. @@ -20,10 +22,21 @@ Copy and pasting the git commit messages is __NOT__ enough. - The `examples/e12_rllib` training examples `{pg_example|pg_pbt_example}.py` have been changed to `{ppo_example|ppo_pbt_example}.py`. `Policy Gradients (PG)` has been dropped in favor of the more well documented `Proximal Policy Optimization (PPO)`. - Vehicles can now have sensors added to, overwritten, or replaced outright. - Logging is now improved to give information about sensor changes in the sensor manager. +- - Renamed `vehicle.urdf` to `sedan.urdf`. +- Environment prefix is now configurable for custom `smarts.core.config()` calls. +- `Vehicle.build_agent_vehicle()` argument `vehicle_filepath` now renamed to `vehicle_dynamics_filepath`. +- Renamed `MACOS` `pybullet` gui utility from `smarts.core.utils.bullet.BulletClient` to `smarts.core.utils.pybullet.BulletClientMACOS`. +- `Vehicle.build_agent_vehicle()` and `Vehicle.build_social_vehicle()` moved to `VehicleIndex`. +- `smarts.core.configuration.Configuration.get_settings()` now uses the `PyYAML` default instead of forcefully casting to `str`. +- Added `AgentInterface.vehicle_class` which allows selection of a dynamics vehicle from the vehicle definitions list file. ### Deprecated +- Module `smarts.core.models` is now deprecated in favour of `smarts.assets`. +- Deprecated a few things related to vehicles in the `Scenario` class, including the `vehicle_filepath`, `tire_parameters_filepath`, and `controller_parameters_filepath`. The functionality is now handled through the vehicle definitions. +- `AgentInterface.vehicle_type` is now deprecated with potential to be restored. ### Fixed - `SumoTrafficSimulation` gives clearer reasons as to why it failed to connect to the TraCI server. - Suppressed an issue where `pybullet_utils.pybullet.BulletClient` would cause an error because it was catching a non `BaseException` type. +- Fixed a bug where `smarts.core.vehicle_index.VehicleIndex.attach_sensors_to_vehicle()` would pass a method instead of a `PlanFrame` to the generated vehicle `SensorState`. - Fixed an issue where `AgentInterface.vehicle_type` would not affect agent vehicles when attempting to take over an existing vehicle. - Fixed a case where newly created agent vehicles would have a constant `"sedan"` size instead of the size of `AgentInterface.vehicle_type`. - Fixed a case where if vehicles are replaced they would not respect controller and vehicle parameters. diff --git a/MANIFEST.in b/MANIFEST.in index 09fa472fa4..f732772a66 100644 --- a/MANIFEST.in +++ b/MANIFEST.in @@ -1,8 +1,7 @@ include smarts/core/glsl/*.vert smarts/core/glsl/*.frag -include smarts/core/models/*.glb smarts/core/models/*.urdf -include smarts/core/models/controller_parameters.yaml include envision/web/dist/* include smarts/*.ini +recursive-include smarts/assets *.glb *.urdf *.yaml *.yml recursive-include smarts/benchmark *.yaml *.yml recursive-include smarts/ros/src *.launch *.msg *.srv package.xml CMakeLists.txt *.py recursive-include smarts/scenarios *.xml *.py diff --git a/docs/benchmarks/benchmark.rst b/docs/benchmarks/benchmark.rst index 77769035bb..38a4894a14 100644 --- a/docs/benchmarks/benchmark.rst +++ b/docs/benchmarks/benchmark.rst @@ -108,18 +108,5 @@ The benchmark listing file is organized as below. params: # Additional values to pass into the entrypoint as named keyword arguments. benchmark_config: ${{smarts.benchmark.driving_smarts.v2022}}/config.yaml -.. note:: - - Resolving module directories. - The benchmark configuration directory can be dynamically found through - python using an evaluation syntax ``${{}}``. This is experimental and - open to change but the following resolves the python module location in - loaded configuration files: - - .. code:: yaml - - somewhere_path: ${{module.to.resolve}}/file.txt # resolves to /module/to/resolve/file.txt - - This avoids loading the module into python but resolves to the first - path that matches the module. +See :ref:`engine_configuration` for more details. diff --git a/docs/conf.py b/docs/conf.py index a6123ed1e1..1fb8684439 100644 --- a/docs/conf.py +++ b/docs/conf.py @@ -47,12 +47,16 @@ ] extlinks = { + "assets": ( + "https://github.com/huawei-noah/SMARTS/tree/master/smarts/assets/%s", + "%s", + ), "examples": ( - "https://github.com/huawei-noah/SMARTS/blob/master/examples/%s", + "https://github.com/huawei-noah/SMARTS/tree/master/examples/%s", "%s", ), "scenarios": ( - "https://github.com/huawei-noah/SMARTS/blob/master/scenarios/%s", + "https://github.com/huawei-noah/SMARTS/tree/master/scenarios/%s", "%s", ), } diff --git a/docs/index.rst b/docs/index.rst index 942675f284..8419ed659b 100644 --- a/docs/index.rst +++ b/docs/index.rst @@ -46,7 +46,8 @@ If you use SMARTS in your research, please cite the `paper ` allows with a few extensions. + +Dynamic module resolution +^^^^^^^^^^^^^^^^^^^^^^^^^ + +The benchmark configuration directory can be dynamically found through +python using an evaluation syntax ``${{}}``. This is experimental and +open to change but the following resolves the python module location in +loaded configuration files: + +.. code:: yaml + + somewhere_path: ${{module.to.resolve}}/file.txt # resolves to /module/to/resolve/file.txt + + +This avoids loading the module into python but resolves to the first +path that matches the module. + +Environment variable resolution +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +Resolving SMARTS engine configuration. + +The engine configuration resolves by referencing the setting through +the evaluation syntax ``${}``. This is restricted to ``"SMARTS_"`` +prefixed environment variables. + +.. code:: yaml + + is_debug: ${SMARTS_CORE_DEBUG} # literal environment variable or engine setting `[core] debug` + diff --git a/docs/sim/vehicle.rst b/docs/sim/vehicle.rst new file mode 100644 index 0000000000..b9b3ff924a --- /dev/null +++ b/docs/sim/vehicle.rst @@ -0,0 +1,150 @@ +.. _vehicle_defaults: + + +Vehicle defaults +================ + +``SMARTS`` provides vehicle configuration for agent control. + + +Default agent vehicle details +----------------------------- + +.. list-table:: + :header-rows: 1 + + * - **Vehicle** + - Sedan (Default) + - Bus (class 4) + - Pickup truck (class 2a) + - Empty moving truck (class 5) + - Loaded moving truck (class 5) + * - **Resource** + - "sedan" | "generic_sedan" + - "bus" | "generic_bus" + - "pickup" | "generic_pickup_truck" + - "moving_truck_empty" + - "moving_truck_loaded" + * - **Dimensions** (LWH) + - 3.68 1.47 1.30 + - 7.00 2.20 2.40 + - 5.00 1.91 1.89 + - 7.10 2.40 2.40 + - 7.10 2.40 2.40 + * - **Mass** (kg) + - 2356.00 + - 6000.00 + - 2600.00 + - 6500.00 + - 8700.00 + + +Note that the dimensions do not take into account elevation due to the wheels. + +.. note:: + + See also :assets:`vehicles/vehicle_definitions_list.yaml` and `truck classifications `. + + +Specifying vehicle definitions +------------------------------ + +Vehicles can be configured in a few different ways. + + +Configuration file +^^^^^^^^^^^^^^^^^^ + +.. code-block:: ini + + [assets] + default_vehicle_definitions_list = path/to/file.yaml + +.. note:: + + See also :ref:`engine_configuration`. + + +Environment variable +^^^^^^^^^^^^^^^^^^^^ + +Setting ``SMARTS_ASSETS_DEFAULT_VEHICLE_DEFINITIONS_LIST`` will cause ``SMARTS`` to use the given vehicle definitions file as the default vehicle definitions. + +.. note:: + + See also :ref:`engine_configuration`. + + +Scenario +^^^^^^^^ + +Including a ``vehicle_definitions_list.yaml`` in your scenario will cause ``SMARTS`` to use those vehicle definitions for the duration of the scenario. + +.. code-block:: bash + + $ tree scenarios/sumo/loop + scenarios/sumo/loop + ├── build + │ └── ... + ├── map.net.xml + ├── rerouter.add.xml + ├── scenario.py + └── vehicle_definitions_list.yaml # <--- + + +Usage +----- + +Agent interface +^^^^^^^^^^^^^^^ + +.. code-block:: python + + from smarts.core.agent_interface import AgentInterface + from smarts.core.controllers import ActionSpaceType + + agent_interface = AgentInterface( + max_episode_steps=1000, + waypoint_paths=True, + vehicle_class="pickup", + action=ActionSpaceType.Continuous, + ) + +.. note:: + + See also :ref:`agent`. + + +Syntax +------ + +A vehicle can be composed in the following way: + + +.. code-block:: yaml + + # vehicle_definitions_list.yaml + f150: /usr/home/dev/vehicles/f150.yaml + + +.. code-block:: yaml + + # /usr/home/dev/vehicles/f150.yaml + model: Ford F-150 + type: truck + controller_params: ${SMARTS_ASSETS_PATH}/vehicles/controller_params/generic_pickup_truck.yaml + chassis_params: ${SMARTS_ASSETS_PATH}/vehicles/chassis_params/generic_pickup_truck.yaml + dynamics_model: /usr/home/dev/vehicles/f150_loaded.urdf + visual_model: /usr/home/dev/vehicles/f150.glb + tire_params: null # ${SMARTS_ASSETS_PATH}/vehicles/tire_params/base_tire_parameters.yaml + + +.. note:: + + See :ref:`engine_configuration` for details about how YAML is resolved. + + +.. note:: + + See :assets:`vehicles/controller_params/generic_pickup_truck.yaml` and :assets:`vehicles/chassis_params/generic_pickup_truck.yaml`. + diff --git a/envision/server.py b/envision/server.py index 065b898940..af3120d549 100644 --- a/envision/server.py +++ b/envision/server.py @@ -46,7 +46,7 @@ "Missing dependencies for Envision. Install them using the command `pip install -e .[envision]` at the source directory." ) -import smarts.core.models +import smarts.assets.vehicles.visual_model from envision.web import dist as web_dist from smarts.core.utils.file import path2hash @@ -473,11 +473,13 @@ def initialize(self): async def get(self, id_): """Serve the requested model geometry.""" if id_ not in self._path_map or not pkg_resources.is_resource( - smarts.core.models, self._path_map[id_] + smarts.assets.vehicles.visual_model, self._path_map[id_] ): raise tornado.web.HTTPError(404, f"GLB Model `{id_}` not found.") - with pkg_resources.path(smarts.core.models, self._path_map[id_]) as path: + with pkg_resources.path( + smarts.assets.vehicles.visual_model, self._path_map[id_] + ) as path: await self.serve_chunked(path) diff --git a/examples/tools/pybullet_linear_tire_example.py b/examples/tools/pybullet_linear_tire_example.py index 959fd22a28..3002e1898b 100644 --- a/examples/tools/pybullet_linear_tire_example.py +++ b/examples/tools/pybullet_linear_tire_example.py @@ -1,9 +1,12 @@ +import importlib.resources as pkg_resources import math from pathlib import Path import matplotlib.pyplot as plt import numpy as np +import smarts.assets +import smarts.assets.vehicles.tire_params from smarts.core.chassis import AckermannChassis from smarts.core.controllers.actuator_dynamic_controller import ( ActuatorDynamicController, @@ -238,21 +241,25 @@ def frictions(sliders): # frictionERP=0.1, ) - path = Path(__file__).parent / "../smarts/core/models/plane.urdf" - path = str(path.absolute()) - plane_body_id = client.loadURDF(path, useFixedBase=True) + with pkg_resources.path(smarts.assets, "plane.urdf") as path: + path = str(path.absolute()) + plane_body_id = client.loadURDF(path, useFixedBase=True) client.changeDynamics(plane_body_id, -1, **frictions(sliders)) pose = pose = Pose.from_center((0, 0, 0), Heading(0)) - vehicle = Vehicle( - "hello", - chassis=AckermannChassis( - pose=pose, - bullet_client=client, - tire_parameters_filepath="../../smarts/core/models/tire_parameters.yaml", - ), - ) + with pkg_resources.path( + smarts.assets.vehicles.tire_params, "base_tire_parameters.yaml" + ) as tire_path: + vehicle = Vehicle( + "hello", + chassis=AckermannChassis( + pose=pose, + bullet_client=client, + tire_parameters_filepath=tire_path, + ), + visual_model_filepath=None, + ) run( client, diff --git a/examples/tools/pybullet_sumo_orientation_example.py b/examples/tools/pybullet_sumo_orientation_example.py index 0c3ebd8750..8854eb7edd 100644 --- a/examples/tools/pybullet_sumo_orientation_example.py +++ b/examples/tools/pybullet_sumo_orientation_example.py @@ -1,9 +1,11 @@ # type: ignore +import importlib.resources as pkg_resources from pathlib import Path from typing import Dict import numpy as np +import smarts.assets from smarts.core.actor import ActorRole from smarts.core.chassis import BoxChassis from smarts.core.coordinates import Heading, Pose @@ -121,6 +123,7 @@ def run( dimensions=vehicle_config.dimensions, bullet_client=client, ), + visual_model_filepath=None, ) # Hide any additional vehicles @@ -165,9 +168,9 @@ def run( # frictionERP=0.1, ) - path = Path(__file__).parent / "../../smarts/core/models/plane.urdf" - path = str(path.absolute()) - plane_body_id = client.loadURDF(path, useFixedBase=True) + with pkg_resources.path(smarts.assets, "plane.urdf") as path: + path = str(path.absolute()) + plane_body_id = client.loadURDF(path, useFixedBase=True) vehicle_config = VEHICLE_CONFIGS["passenger"] diff --git a/examples/tools/pybullet_trajectory_example.py b/examples/tools/pybullet_trajectory_example.py index 0f648325f9..a7d34b0126 100644 --- a/examples/tools/pybullet_trajectory_example.py +++ b/examples/tools/pybullet_trajectory_example.py @@ -1,8 +1,10 @@ +import importlib.resources as pkg_resources import math from pathlib import Path import matplotlib.pyplot as plt +import smarts.assets from smarts.core.chassis import AckermannChassis from smarts.core.controllers import ( TrajectoryTrackingController, @@ -79,12 +81,6 @@ def run(client, vehicle, plane_body_id, sliders, n_steps=1e6): vehicle, controller_state, dt_sec=TIMESTEP_SEC, - heading_gain=0.05, - lateral_gain=0.65, - velocity_gain=1.8, - traction_gain=2, - derivative_activation=False, - speed_reduction_activation=False, ) client.stepSimulation() @@ -162,9 +158,9 @@ def frictions(sliders): # frictionERP=0.1, ) - path = Path(__file__).parent / "../smarts/core/models/plane.urdf" - path = str(path.absolute()) - plane_body_id = client.loadURDF(path, useFixedBase=True) + with pkg_resources.path(smarts.assets, "plane.urdf") as path: + path = str(path.absolute()) + plane_body_id = client.loadURDF(path, useFixedBase=True) client.changeDynamics(plane_body_id, -1, **frictions(sliders)) pose = pose = Pose.from_center((0, 0, 0), Heading(0)) @@ -175,6 +171,7 @@ def frictions(sliders): pose=pose, bullet_client=client, ), + visual_model_filepath=None, ) run( diff --git a/examples/tools/pybullet_vehicle_example.py b/examples/tools/pybullet_vehicle_example.py index 5b6fa2e9ad..39d0df0875 100644 --- a/examples/tools/pybullet_vehicle_example.py +++ b/examples/tools/pybullet_vehicle_example.py @@ -127,7 +127,7 @@ def frictions(sliders, client): # frictionERP=0.1, ) - path = Path(__file__).parent / "../smarts/core/models/plane.urdf" + path = Path(__file__).parent / "../smarts/assets/plane.urdf" path = str(path.absolute()) plane_body_id = client.loadURDF(path, useFixedBase=True) @@ -140,6 +140,7 @@ def frictions(sliders, client): pose=pose, bullet_client=client, ), + visual_model_filepath=None, ) run( diff --git a/smarts/assets/__init__.py b/smarts/assets/__init__.py new file mode 100644 index 0000000000..2c65923417 --- /dev/null +++ b/smarts/assets/__init__.py @@ -0,0 +1,21 @@ +# MIT License +# +# Copyright (C) 2023. Huawei Technologies Co., Ltd. All rights reserved. +# +# 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 NON-INFRINGEMENT. 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/smarts/core/models/plane.urdf b/smarts/assets/plane.urdf similarity index 100% rename from smarts/core/models/plane.urdf rename to smarts/assets/plane.urdf diff --git a/smarts/assets/vehicles/__init__.py b/smarts/assets/vehicles/__init__.py new file mode 100644 index 0000000000..2c65923417 --- /dev/null +++ b/smarts/assets/vehicles/__init__.py @@ -0,0 +1,21 @@ +# MIT License +# +# Copyright (C) 2023. Huawei Technologies Co., Ltd. All rights reserved. +# +# 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 NON-INFRINGEMENT. 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/smarts/assets/vehicles/chassis_params/__init__.py b/smarts/assets/vehicles/chassis_params/__init__.py new file mode 100644 index 0000000000..2c65923417 --- /dev/null +++ b/smarts/assets/vehicles/chassis_params/__init__.py @@ -0,0 +1,21 @@ +# MIT License +# +# Copyright (C) 2023. Huawei Technologies Co., Ltd. All rights reserved. +# +# 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 NON-INFRINGEMENT. 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/smarts/assets/vehicles/chassis_params/generic_bus.yaml b/smarts/assets/vehicles/chassis_params/generic_bus.yaml new file mode 100644 index 0000000000..a708d27819 --- /dev/null +++ b/smarts/assets/vehicles/chassis_params/generic_bus.yaml @@ -0,0 +1,8 @@ +chassis_aero_force_gain : 0.63 +max_brake_gain : 10000 +max_turn_radius : 2.2 +wheel_radius : 0.31265 +max_torque : 2100 +max_btorque : 1200 +max_steering : 12.56 +steering_gear_ratio : 17.4 \ No newline at end of file diff --git a/smarts/assets/vehicles/chassis_params/generic_moving_truck.yaml b/smarts/assets/vehicles/chassis_params/generic_moving_truck.yaml new file mode 100644 index 0000000000..a708d27819 --- /dev/null +++ b/smarts/assets/vehicles/chassis_params/generic_moving_truck.yaml @@ -0,0 +1,8 @@ +chassis_aero_force_gain : 0.63 +max_brake_gain : 10000 +max_turn_radius : 2.2 +wheel_radius : 0.31265 +max_torque : 2100 +max_btorque : 1200 +max_steering : 12.56 +steering_gear_ratio : 17.4 \ No newline at end of file diff --git a/smarts/assets/vehicles/chassis_params/generic_pickup_truck.yaml b/smarts/assets/vehicles/chassis_params/generic_pickup_truck.yaml new file mode 100644 index 0000000000..a708d27819 --- /dev/null +++ b/smarts/assets/vehicles/chassis_params/generic_pickup_truck.yaml @@ -0,0 +1,8 @@ +chassis_aero_force_gain : 0.63 +max_brake_gain : 10000 +max_turn_radius : 2.2 +wheel_radius : 0.31265 +max_torque : 2100 +max_btorque : 1200 +max_steering : 12.56 +steering_gear_ratio : 17.4 \ No newline at end of file diff --git a/smarts/assets/vehicles/chassis_params/generic_sedan.yaml b/smarts/assets/vehicles/chassis_params/generic_sedan.yaml new file mode 100644 index 0000000000..c3b3ff8736 --- /dev/null +++ b/smarts/assets/vehicles/chassis_params/generic_sedan.yaml @@ -0,0 +1,8 @@ +chassis_aero_force_gain : 0.63 +max_brake_gain : 10000 +max_turn_radius : 2.2 +wheel_radius : 0.31265 +max_torque : 1600 +max_btorque : 1400 +max_steering : 12.56 +steering_gear_ratio : 17.4 \ No newline at end of file diff --git a/smarts/assets/vehicles/controller_params/__init__.py b/smarts/assets/vehicles/controller_params/__init__.py new file mode 100644 index 0000000000..2c65923417 --- /dev/null +++ b/smarts/assets/vehicles/controller_params/__init__.py @@ -0,0 +1,21 @@ +# MIT License +# +# Copyright (C) 2023. Huawei Technologies Co., Ltd. All rights reserved. +# +# 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 NON-INFRINGEMENT. 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/smarts/assets/vehicles/controller_params/generic_bus.yaml b/smarts/assets/vehicles/controller_params/generic_bus.yaml new file mode 100644 index 0000000000..450528f29b --- /dev/null +++ b/smarts/assets/vehicles/controller_params/generic_bus.yaml @@ -0,0 +1,14 @@ +final_heading_gain: 0.15 +final_lateral_gain: 5.3 +final_steering_filter_constant: 27.5 +throttle_filter_constant: 3 +velocity_gain: 6.1 +velocity_integral_gain: 0 +traction_gain: 8 +final_lateral_error_derivative_gain: 0.45 +final_heading_error_derivative_gain: 2.5 +initial_look_ahead_distant: 3 +derivative_activation: 1 +speed_reduction_activation: 0 +velocity_damping_gain: 0.001 +windup_gain: 0.01 \ No newline at end of file diff --git a/smarts/assets/vehicles/controller_params/generic_moving_truck.yaml b/smarts/assets/vehicles/controller_params/generic_moving_truck.yaml new file mode 100644 index 0000000000..3efff5dc2c --- /dev/null +++ b/smarts/assets/vehicles/controller_params/generic_moving_truck.yaml @@ -0,0 +1,14 @@ +final_heading_gain: 0.15 +final_lateral_gain: 5.3 +final_steering_filter_constant: 27.5 +throttle_filter_constant: 4 +velocity_gain: 6.1 +velocity_integral_gain: 0 +traction_gain: 8 +final_lateral_error_derivative_gain: 0.45 +final_heading_error_derivative_gain: 2.5 +initial_look_ahead_distant: 3 +derivative_activation: 1 +speed_reduction_activation: 0 +velocity_damping_gain: 0.001 +windup_gain: 0.01 \ No newline at end of file diff --git a/smarts/assets/vehicles/controller_params/generic_pickup_truck.yaml b/smarts/assets/vehicles/controller_params/generic_pickup_truck.yaml new file mode 100644 index 0000000000..afd196e73a --- /dev/null +++ b/smarts/assets/vehicles/controller_params/generic_pickup_truck.yaml @@ -0,0 +1,14 @@ +final_heading_gain: 0.15 +final_lateral_gain: 5.3 +final_steering_filter_constant: 27.5 +throttle_filter_constant: 2 +velocity_gain: 6.1 +velocity_integral_gain: 0 +traction_gain: 8 +final_lateral_error_derivative_gain: 0.45 +final_heading_error_derivative_gain: 2.5 +initial_look_ahead_distant: 3 +derivative_activation: 1 +speed_reduction_activation: 0 +velocity_damping_gain: 0.001 +windup_gain: 0.01 \ No newline at end of file diff --git a/smarts/assets/vehicles/controller_params/generic_sedan.yaml b/smarts/assets/vehicles/controller_params/generic_sedan.yaml new file mode 100644 index 0000000000..428d75ff45 --- /dev/null +++ b/smarts/assets/vehicles/controller_params/generic_sedan.yaml @@ -0,0 +1,14 @@ +final_heading_gain: .15 +final_lateral_gain: 4.65 +final_steering_filter_constant: 23.5 +throttle_filter_constant: 22.5 +velocity_gain: 5.1 +velocity_integral_gain: 0 +traction_gain: 6 +final_lateral_error_derivative_gain: 0.3 +final_heading_error_derivative_gain: 3.1 +initial_look_ahead_distant: 6 +derivative_activation: 1 +speed_reduction_activation: 1 +velocity_damping_gain: 0.001 +windup_gain: 0.01 \ No newline at end of file diff --git a/smarts/assets/vehicles/definitions/bus.yaml b/smarts/assets/vehicles/definitions/bus.yaml new file mode 100644 index 0000000000..207224397d --- /dev/null +++ b/smarts/assets/vehicles/definitions/bus.yaml @@ -0,0 +1,7 @@ +model: Generic Bus +type: bus +controller_params: ${SMARTS_ASSETS_PATH}/vehicles/controller_params/generic_bus.yaml +chassis_params: ${SMARTS_ASSETS_PATH}/vehicles/chassis_params/generic_bus.yaml +dynamics_model: ${SMARTS_ASSETS_PATH}/vehicles/dynamics_model/generic_class_4_bus.urdf +visual_model: ${SMARTS_ASSETS_PATH}/vehicles/visual_model/bus.glb +tire_params: null # ${SMARTS_ASSETS_PATH}/vehicles/tire_params/base_tire_parameters.yaml \ No newline at end of file diff --git a/smarts/assets/vehicles/definitions/moving_truck_empty.yaml b/smarts/assets/vehicles/definitions/moving_truck_empty.yaml new file mode 100644 index 0000000000..dae0650191 --- /dev/null +++ b/smarts/assets/vehicles/definitions/moving_truck_empty.yaml @@ -0,0 +1,7 @@ +model: Generic Empty Moving Truck +type: truck +controller_params: ${SMARTS_ASSETS_PATH}/vehicles/controller_params/generic_moving_truck.yaml +chassis_params: ${SMARTS_ASSETS_PATH}/vehicles/chassis_params/generic_moving_truck.yaml +dynamics_model: ${SMARTS_ASSETS_PATH}/vehicles/dynamics_model/generic_class_5_truck_empty.urdf +visual_model: ${SMARTS_ASSETS_PATH}/vehicles/visual_model/moving_truck.glb +tire_params: null # ${SMARTS_ASSETS_PATH}/vehicles/tire_params/base_tire_parameters.yaml \ No newline at end of file diff --git a/smarts/assets/vehicles/definitions/moving_truck_loaded.yaml b/smarts/assets/vehicles/definitions/moving_truck_loaded.yaml new file mode 100644 index 0000000000..ffe3d91c53 --- /dev/null +++ b/smarts/assets/vehicles/definitions/moving_truck_loaded.yaml @@ -0,0 +1,7 @@ +model: Generic Loaded Moving Truck +type: truck +controller_params: ${SMARTS_ASSETS_PATH}/vehicles/controller_params/generic_moving_truck.yaml +chassis_params: ${SMARTS_ASSETS_PATH}/vehicles/chassis_params/generic_moving_truck.yaml +dynamics_model: ${SMARTS_ASSETS_PATH}/vehicles/dynamics_model/generic_class_5_truck_loaded.urdf +visual_model: ${SMARTS_ASSETS_PATH}/vehicles/visual_model/moving_truck.glb +tire_params: null # ${SMARTS_ASSETS_PATH}/vehicles/tire_params/base_tire_parameters.yaml \ No newline at end of file diff --git a/smarts/assets/vehicles/definitions/pickup_truck.yaml b/smarts/assets/vehicles/definitions/pickup_truck.yaml new file mode 100644 index 0000000000..999c691a1d --- /dev/null +++ b/smarts/assets/vehicles/definitions/pickup_truck.yaml @@ -0,0 +1,7 @@ +model: Generic Pickup Truck +type: truck +controller_params: ${SMARTS_ASSETS_PATH}/vehicles/controller_params/generic_pickup_truck.yaml +chassis_params: ${SMARTS_ASSETS_PATH}/vehicles/chassis_params/generic_pickup_truck.yaml +dynamics_model: ${SMARTS_ASSETS_PATH}/vehicles/dynamics_model/generic_class_2a_truck.urdf +visual_model: ${SMARTS_ASSETS_PATH}/vehicles/visual_model/truck.glb +tire_params: null # ${SMARTS_ASSETS_PATH}/vehicles/tire_params/base_tire_parameters.yaml \ No newline at end of file diff --git a/smarts/assets/vehicles/definitions/sedan.yaml b/smarts/assets/vehicles/definitions/sedan.yaml new file mode 100644 index 0000000000..745d2a1531 --- /dev/null +++ b/smarts/assets/vehicles/definitions/sedan.yaml @@ -0,0 +1,7 @@ +model: Generic Sedan +type: passenger +controller_params: ${SMARTS_ASSETS_PATH}/vehicles/controller_params/generic_sedan.yaml +chassis_params: ${SMARTS_ASSETS_PATH}/vehicles/chassis_params/generic_sedan.yaml +dynamics_model: ${SMARTS_ASSETS_PATH}/vehicles/dynamics_model/generic_sedan.urdf +visual_model: ${SMARTS_ASSETS_PATH}/vehicles/visual_model/muscle_car.glb +tire_params: null # ${SMARTS_ASSETS_PATH}/vehicles/tire_params/base_tire_parameters.yaml \ No newline at end of file diff --git a/smarts/assets/vehicles/dynamics_model/__init__.py b/smarts/assets/vehicles/dynamics_model/__init__.py new file mode 100644 index 0000000000..2c65923417 --- /dev/null +++ b/smarts/assets/vehicles/dynamics_model/__init__.py @@ -0,0 +1,21 @@ +# MIT License +# +# Copyright (C) 2023. Huawei Technologies Co., Ltd. All rights reserved. +# +# 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 NON-INFRINGEMENT. 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/smarts/assets/vehicles/dynamics_model/generic_class_2a_truck.urdf b/smarts/assets/vehicles/dynamics_model/generic_class_2a_truck.urdf new file mode 100644 index 0000000000..4b17b9e9e8 --- /dev/null +++ b/smarts/assets/vehicles/dynamics_model/generic_class_2a_truck.urdf @@ -0,0 +1,166 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/smarts/core/models/bus.urdf b/smarts/assets/vehicles/dynamics_model/generic_class_4_bus.urdf similarity index 100% rename from smarts/core/models/bus.urdf rename to smarts/assets/vehicles/dynamics_model/generic_class_4_bus.urdf diff --git a/smarts/assets/vehicles/dynamics_model/generic_class_5_truck_empty.urdf b/smarts/assets/vehicles/dynamics_model/generic_class_5_truck_empty.urdf new file mode 100644 index 0000000000..abedacb0dd --- /dev/null +++ b/smarts/assets/vehicles/dynamics_model/generic_class_5_truck_empty.urdf @@ -0,0 +1,226 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/smarts/assets/vehicles/dynamics_model/generic_class_5_truck_loaded.urdf b/smarts/assets/vehicles/dynamics_model/generic_class_5_truck_loaded.urdf new file mode 100644 index 0000000000..deb5ec3c88 --- /dev/null +++ b/smarts/assets/vehicles/dynamics_model/generic_class_5_truck_loaded.urdf @@ -0,0 +1,226 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/smarts/core/models/vehicle.urdf b/smarts/assets/vehicles/dynamics_model/generic_sedan.urdf similarity index 100% rename from smarts/core/models/vehicle.urdf rename to smarts/assets/vehicles/dynamics_model/generic_sedan.urdf diff --git a/smarts/assets/vehicles/tire_params/__init__.py b/smarts/assets/vehicles/tire_params/__init__.py new file mode 100644 index 0000000000..2c65923417 --- /dev/null +++ b/smarts/assets/vehicles/tire_params/__init__.py @@ -0,0 +1,21 @@ +# MIT License +# +# Copyright (C) 2023. Huawei Technologies Co., Ltd. All rights reserved. +# +# 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 NON-INFRINGEMENT. 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/smarts/core/models/tire_parameters.yaml b/smarts/assets/vehicles/tire_params/base_tire_parameters.yaml similarity index 100% rename from smarts/core/models/tire_parameters.yaml rename to smarts/assets/vehicles/tire_params/base_tire_parameters.yaml diff --git a/smarts/assets/vehicles/vehicle_definitions_list.yaml b/smarts/assets/vehicles/vehicle_definitions_list.yaml new file mode 100644 index 0000000000..d0a95a2801 --- /dev/null +++ b/smarts/assets/vehicles/vehicle_definitions_list.yaml @@ -0,0 +1,8 @@ +generic_bus: &GENERIC_BUS ${SMARTS_ASSETS_PATH}/vehicles/definitions/bus.yaml +generic_sedan: &GENERIC_SEDAN ${SMARTS_ASSETS_PATH}/vehicles/definitions/sedan.yaml +generic_pickup_truck: &GENERIC_PICKUP ${SMARTS_ASSETS_PATH}/vehicles/definitions/pickup_truck.yaml +bus: *GENERIC_BUS +moving_truck_empty: ${SMARTS_ASSETS_PATH}/vehicles/definitions/moving_truck_empty.yaml +moving_truck_loaded: ${SMARTS_ASSETS_PATH}/vehicles/definitions/moving_truck_loaded.yaml +pickup: *GENERIC_PICKUP +sedan: *GENERIC_SEDAN \ No newline at end of file diff --git a/smarts/assets/vehicles/visual_model/__init__.py b/smarts/assets/vehicles/visual_model/__init__.py new file mode 100644 index 0000000000..2c65923417 --- /dev/null +++ b/smarts/assets/vehicles/visual_model/__init__.py @@ -0,0 +1,21 @@ +# MIT License +# +# Copyright (C) 2023. Huawei Technologies Co., Ltd. All rights reserved. +# +# 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 NON-INFRINGEMENT. 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/smarts/core/models/bus.blend b/smarts/assets/vehicles/visual_model/bus.blend similarity index 100% rename from smarts/core/models/bus.blend rename to smarts/assets/vehicles/visual_model/bus.blend diff --git a/smarts/core/models/bus.glb b/smarts/assets/vehicles/visual_model/bus.glb similarity index 100% rename from smarts/core/models/bus.glb rename to smarts/assets/vehicles/visual_model/bus.glb diff --git a/smarts/core/models/coach.blend b/smarts/assets/vehicles/visual_model/coach.blend similarity index 100% rename from smarts/core/models/coach.blend rename to smarts/assets/vehicles/visual_model/coach.blend diff --git a/smarts/core/models/coach.glb b/smarts/assets/vehicles/visual_model/coach.glb similarity index 100% rename from smarts/core/models/coach.glb rename to smarts/assets/vehicles/visual_model/coach.glb diff --git a/smarts/core/models/license.txt b/smarts/assets/vehicles/visual_model/license.txt similarity index 100% rename from smarts/core/models/license.txt rename to smarts/assets/vehicles/visual_model/license.txt diff --git a/smarts/core/models/motorcycle.blend b/smarts/assets/vehicles/visual_model/motorcycle.blend similarity index 100% rename from smarts/core/models/motorcycle.blend rename to smarts/assets/vehicles/visual_model/motorcycle.blend diff --git a/smarts/core/models/motorcycle.glb b/smarts/assets/vehicles/visual_model/motorcycle.glb similarity index 100% rename from smarts/core/models/motorcycle.glb rename to smarts/assets/vehicles/visual_model/motorcycle.glb diff --git a/smarts/assets/vehicles/visual_model/moving_truck.blend b/smarts/assets/vehicles/visual_model/moving_truck.blend new file mode 100644 index 0000000000000000000000000000000000000000..7c354228f2c6c80717748df914e1a5876cead29a GIT binary patch literal 991416 zcmeFa34B&po&W!ku!KE<5W*hzlzlCswj^vVXcq)ps8%6_0BHlE0ot@xo7UE%wY6HU zv{T1UT?VboPwhBNRl4cOjCC1DM_k9BvoZe1ncuj~;NSU~-}im)`8>~kZtk-sM8Q7y z#o^que81@dpeT&={tTo*VrEY!j`|Rvz5HfAfY(GoG&= zGVDmUe$lr6{rfjoRaM<=GVO}C6;iIKsA$b)qd0zJ#*AqzDJj_**OsZSw6t_*PjO?u zEZG0%)0^;bCV4W|qg%gz{dQtoFl2lVfCI1rE=ZhHM;m<%AIahUfybQwiwMGFbaO?hmP<<-#EHVbvBP3uT1Tk>TRroZA9F_ z#+i6#syBb^FH|q^k`G3S1;hkmgUz9vCrp?CE^fEj0X8~_CBzhBOQx7mHF)Tujgx1* zFr@#0J(+Zft2bZXWaAbTN0AphBD2YKBl8~nkccDbOg-)NqklHrfg7VO*q4lBaUg3P zjp~g3uw%47SJ|*u@EXN9W`lzKfvt!cl83ovF?EmmsMUOR^VqRtj~G5~BW{czKfc4{ zIy7q7@V0dmr=6HpQF(VZJBz1slW#9RD}=`6$r=NZ*W^EFGB=?+HUMMht0YFi3v0K{ zLx&H)cQ{a}FNquAOZw!KYmLsQZ@3S33YYUaCq5Ob6YC8A&WAs-oAq|l*a`2dA2;RW z<427?Y?u%>ZZkg|HrpRGJKcnx!fUMAp$R_~BA`jgFtKjJ)WStxvQKUtohm=HrNggKm7~ z9+TETljE$&VlqH+Z>74rn_07dIJPtI> z7wVwH=g3ctK!@-e13s81tXtSPyax&Mj63g%|9i4#7&eK01?@9T&lX~GoZOk}E*m%b zskx)7-jS(2T90k9nT@rN*lc!8UaNR)+|C+f_P&`lhZv48%r|Z3i@f3zV;XJ2x-j<{ zD=Kre%>2NQ;Dh;s9v&ZBV_GRwZ}PLoG|?YA!x^&O6y=$%j15TH`b68nXg<1#4!@vF zA#-Nx@bWv?Pn`D5z|zv3Hq$uF8Rm}4aXE6E?cBAB`Q(t{f@|2@NnFRq(M0Qd5(Ahs z%z-GcY-KPLXES0p^A^7uZo_+!R`#gigSbL`0Y~T@$A__z30~Rc2)BVV#jhOQ2Hr1m)Hp7=- z5}Y9$*bqL5qr?{C7Bb7W_#Qg(%9W!-u9zI=;jZ;3<$tY@A6UQhl?nfvuI#U3<53(Y z!t#aBZ5=5nt`$0WSl9FMXILh53zu`9Ne z0~jBB#Mvn-tIFn|g09UA@jr6lOO2H)$B*i-JqYmuJ2A(xn_>uZn5}O_UvLjTuvfM* z=2VP%V3l3#XX_JgW3CpWFMiK8pNMtHZ0o1nV-dg5&&SB5j_3+6)AxYot?0;_OFRn8 z7(GV@`bO(Bm9b|bctNgAyrT8UTgY0j`4Ht3SH=!t*JvC*WWNwTxDUb})!hdfHF#(% z*ZSp=YyCLh)R|v)WBXi~50b3`WlI z9)#G#I%IiXcEOkM%@-?*>!w3fCi%nlTzi;LW7iaTh4gfDfxRlYkgl8)7r=;LZ<6tn zGATS>w(~;#&v^O9BJ{}S&!|l3lrL|))_;>->;FagS|5C9jX{5tH95DiAF?oysP{ID z-Gi_<$k+E_JmGuhbv~FuR{F9&M(q$+29ID`ZDC#goMgRm@d|(XJ(pW=s5gC+*Y(l$ zrV#&wIj|`?vgOESwoG0tXX}gKut&B&YV+6n&y5{2?6B&x<;*keM<2ys*$jQqKa|}4 z5HJ81(G^?A@h84u=WrY25ZA+Xna+_RQw)gGfD@B3uYDKt8rEH3>5DF40PLI2H~CoN z^v3QccXGW^+>Fy3JH^#U<)zFR`L09Q412`!iPjZzt&bm(Bg!MLY_{1$j6i0S#o3Fw z6SfuS)Zu6BW;RXRmnr69!?-b`bs8^PA6KStzH4c|SYaIN>*lm!ME3{Tn{$1ioEMx^ z=XK`#Cb{0k$?7qfaV-zipp)^<>$xk}`rPNs=ea)mz&9V8nIE|qn6oc>8CKnMV&;?K zt0fxmnXA}|xfj+m?i@Q}+qkx9o#B)Do7cLIukwx4Hh%0rBsxAZn)%N>MR(=_>nU|g z#4~Kd{IEKA&p($Ptp7fAi;fp9yKDUk)BfD9^*f_&(Xz)>Uh6A!9h{(FluxuQy~3FC zbA@%pCG3g+EqBk0@G&vP`0tGJqbxhcwT0`v{qtG_%s+ebji-h9A6>&TMbGgyx*AX7 zBz}#HB{y=7LK`w-duVd4EB;#lW6?3AW%yuI=5(|zTJ|yGfY~9Wq4g;>yT|9&v5a zI*X+lubr?ZI>3*yEx9$79Q{bx2COk2_8T>1Xsf-?^gk5sQ6fbjL>k7QXa%VcXxtdo@ zL2vZQ#7FhmGMjzi1CEK$JlCH$dh9#OO?Ph>hY@6Fy}@quv-3URCzqeh=5CE9mppMf zao+f~8sD7jQyjhFH?KXu>DiRcX6Pe(V6$v71$=TwAyfJ-}+XF7BLpm23X_YyD@(4jG#DTHpJMeMC2(YVKfL!|)!D5x16y?ZG@S zUnlRU`FWOheHYaOo@TdhV}|=lHu7+N^c-7YlW2XkjGx$BMeCzwVg!Ao^(xCQ;KK09 z^{)0QN!wr_5`EaGfhDkv-uM_E;ztfXOoyDYAA0Z#;zIqwbG zwSK!@>pz?8THoeE&S&cQp1GCD_tM$)Vr^(OpT(|o*xu~Q^$l~v`5HTWnnrw$&+%c@ zPK&kyhp`z~a>wP!nh)m8SNo7Vj)&@)WBKqxE-)e+L}Ci} z(%f7k2Gdt_3BPErFjjwiuD^D|)X(O+)`t#zp{rz#<{rB@nJih?V6%hUJA#!c50!n4 zzKOo7BL_F=mO~D=pOCGQ%lPS;aWeiIANRf$I8g#GT+i9K?t0Sfwg>yc3wwoS37?y7 za>iKWxeqzQbkTG4##hn$XgMG3q6^rK=${r-7FLaW$e!yzHF{*Zn`fc8n%vJa4>j+i za;S_y%!c?YtM7>+;5(b|!5ZTkPGjet_eoY85f@CJtUf^o>=^c|n-i(n;$kqeun)jC z*ffk4%`N(Xd+d!54KF)o8|Bu%m$|2MT<+sp8s?+@;K8`j`fwS%=E4Z?@bm4KuJt3j zyLp1%JbS@sVZE`1=7?-qgS3mJrIhx|fZ~9l!F1n~Z*1wW=!!8a^+QavA_yLc!nM}iN+-iF#%-9VrH4OGM%p~Zm zWb>pSHaGkBS6wu>`C5WpHfEA8+Q<0!uc@gS9jykj7kJH=i zVO1%6gwI!xuX)8=>(+f@*uX&_NNPXkb`R@f|g2@Zfh`a>eHtjvia9x@b-e!nWCT zwsFdlCrYcbVYCz;CU=?YqPfXCgg(qM>)$UrH;jM9MHgK(!Tc6p%Ux`Mm+9Bv=*MQ7 z57^MYKO158FqK9QG#?0qBdosM+p&Te=IvNvb}To%j%02!N11n4=P&}ls17PKZ*?A* zgMa)O*QPq-k@Uan!a4GQgK(YBv7h-IdsH!&$?xVGHVnj7Mh_=8`?ytJV{t|?1|9sotTx}c zI0x3iGI2qe!T0zjlMK`w->m+(_R;t!6A$(>>_alO&l^=W!{+|ys)i05hOddS(hHlyw0h=)4cC3%p&NFOYom^K!+B+<`82ryfReXdyyheJK3{z% z9{Aa0cJma7H|WQla5-x^m_dKVPq2dRn5#CY$B>8l>)h}- zfVs-PPIdSj|63iuZF7XVXxJHHbB?i*$0c+(8Aef0J6L6W#$pY%z9USxjB^7FWx^z~ z7@xt`Cn=ZYQ_eWpMdfJDo<;5Wig-=K>_Tr-lu0C+%O$)%h+_(D%?BmQ{Xma)cxN9@NsAI1$bNDgGgN7jEZ z_5`Ktrj@;!EEUg6g`Y*0s=$ufeqRXmlW z4{?pS6IzQ{k4Ion{B8bl`#&%+ckbL-^XAQ)6&K6#6FxFNvHK2Un6;0NlM`C>1Phvz z_zT>CO=JPTW@8s`=m(ByqYr(}Miq>$c?nPHiQTPFx7ez7;u?Kaj^^30=i^(qy*T5e z^R0_7eel}pbFL>Inyk*YU`F$RdB@yAM~@lB&N6I*&EjOk2eN_Tz(h`8w-_7W+7Y|& zvA6*5QD!eLuF~eT$zB3)OXbG9(RAebD)+{^mMmE^7Yu~vXeluVELvW|n1=CKTN1}I ztpniGXk848%0n67M%M^$W3JQsV?(o-+oOXCj~jRW0d9~Boy^W7JZ_S9W{$ukIyV^? z+vA%!nW!_~6<{u|y|KVW68__!fPQ=kVxUL+tN;wwefwC+qce{GiS!) z#f#_QPsTPGka4)-dW6|{gw54Ta+1~I3uGLIe~=6Lu(!$Q;ydGFKht4QHhh@Q8P~{c za~QvZ3C56}nI9&@0B~$}u0Rj^5G%n5vYVYo(8jpvCR?*cVIRu}(kA?eF;HRG`VXwU z{LdDQ9y>c+uXAEwj!$_Xei>wZKG6k01CEjB3qco`N05AijeEv*l21 z4tC7uN$j9Eb_f5|3p>cmd@-8j-V44O8-LiivDf(YlmFE}oFi+v96mQ&xwTce!B!#M zjIx--eZ(YgkR5xs%w5*rwxI4dbfDejPtH-3h5cSRz6+1VIrGB%zFQ16-?N4?H@mH| zn%CGBT!i`3hVQ{Oe$YI|7tCSvMEfdyg5#~mjxwn27bhxLMfX73@Ue>uFP`vd&SJkfaJ zoOx~j?6$Vk2j3w}xWCTr_j#t<+<&@q@DP0A`U*ED(@^A;{OF3jvbka>v4K9Cr_3o& zXC_JEo-s`?hZ*9(WKfR348zR#Zr6Rp8QN?d7fVD#4#sG+ILUL%-PV`)1G~V0$ubzZ z%*R8)fb9w9dAkoYU0lMy%yZ%peW8ICd9VfZ#LD){Tleb;>}o#mhJWOuEslmZc!qVr zPOLHb+~gWbyh9f3YO=dE3)`co>`&Qb=Kh^qcTJBG#1_eo-{FfN(I-3}=UnUGvwZcF zYbQ>-EZRm~wXw=grf%!9@pW^X96H7j?o9@_zm@FZ8v7!v={yo#Fu$oIe#_qU!(L|l z0me6ZKg@V1<3V(dk#Dd8{`PU7-xh0PtZ08^wQIMU`Sa(`3a=Z~6aUSwteftcg4u9j z7(d{{WOj0!{7LNKN5(=1o4alfm=0yoqNnL+tLtFrhp>$qD_jnrW0!DQ=U@>3s!R^P zu)o>YL>@5!xjlBc?i*@$b$c^p!3V-VI&7UWZ%fCLOCK1Wiudjw2zI5v;i}sjg-vS= zgK_&vbd9q+wq`th9=1Djn~Vd^?;~w2cTY_76+D0y8;j>&thvK14K+IxBZtDv+AGXf zLs*BHJ7x=>4fCBN&w+TxNbGWZ2mFD3klW(GRKvjRuq@aTd63_Db(_y-Q(}FrU+^U| z5Q8;`8O!WZ2ByKd>4z_z+~`8R`2(GtUBdW*AMzSc7k`8wY!hd9FaQq2xX`)jPaNsy z$BDy7j(Xsd%l~Y8MP*e;W`{3qV7iXL2WH=-%*c!H!4dTy@6K;FZ-zi;hqHs?9Fn1$f6+_}hGxeBS~776-UCMApId_jALo33eZ( zhU-IoY6%^a3EzM-#y1(=dcd3pr&f0H0h{4(lZorD{_qLwr*rhs-cohs$ZRRO1|qNU z116A{K8y=~ki+!m{)n3g^zry{a@#muQ@VW{^B>;uz*fv>upJ)%$f8T`+cIs=wc$F> z!EKz(Mvot@d4#(Lm%Qc!?q{+7xcf4izh=9kjBR+~`JZHV^H*4*4Q%2Ue2Go*FZhaL zg89ez)_;(Voz%t0D#jmbcINt@_W<4XKRhj!;#;##w|fhAeKDChfNo(sK!**8b=b|X zZKc#B1H8Oncz(wHV26D_mz_UM9-grbg^%ISJ@4^;adF7#2Ve(bC_Fy2;j+%*uk&yY zAJaP-f50QYXMDysn>jh@N8RPqX20Ui%U8dDO7%F0ea52=UCbvHoZ}OCU|;k{k1$>t z9}Hky^I4j_)Z<6wjoQ}Yz#w=bBmTywU_*z4!5c#-c@wY8NhCIMec33l=PxX}+JaV#SK3R-S8pCmXMc zCi6JsJI405TzghB7Iq+(pqFF~+n;mriagPJ_A=N38`4MmGPltS{@5M8(3eDi*j~+Wy{m8*N{f)o#IXZ&@;;sRmOpFUJ<1sXh75aO748?Ym)%dx3Y=n#?aES~i z`#vyW{hL@1!gSD^Yy+VSkAqLm*AopFwa8|^;JFdkmt$=IFahkC-6w-1yN@u4vG<#;eA3pJcW)7URd7T%);jLZwX7LjV z-eEl%7yQB_iX+q6T`R)VbQxyyvyZ4W9F4dA#uRX5Sg5gQ=fV;3NLX?>0$*I8SU-n5 zv!|&rq1qCB#u$#cmP@{~W4>|wMA<_*cEWBdlh3UjJN4*_b;qlRj~IrI=*k?YugU55 z4%iJGVQX}x4S$iSryZZsA6j_eYcN7zY@ji*6MQVC&3SxAUt){)M%FiBy1Dro!Vk|v zU7R%ii5-%y%*J9h7=qC)( zpE~2|_FVW2-(xrMB{>+AI_xfd8wTCGur}5ala24OnoV~0&4Z8yY#^h@@F1ggi8|UC zN3xjBCNcj^E*A%kAJ1&St9xE7Imn??Y{X{x7y0RnoXE}mKu43AJ*c}DlT6rzzOoHE zArH1de#wL^&@dLZM{mX=Vc)P!oMT5j+@7EQjDKD2!cB)3U2^xN$}yvif0g-$cStAM zx;4XaG}Ypti%IN@JcfuzGb|oW7mkQc(3st-O`l3|R1>^QVX6l2VPXgDZZd%PWc)E1 zxJCkV1FTO!=BDALzxRoI-x4{Y1!M9JHo;%m2)|QL9kw@{j9}e0+}E01yzjcp65kc_ zO<5Oq!w=X%V`+Ts1m>}~@fif(kO^FyPSwmSWRd@{y<}o+qXR=uCS*fK>PYBmecW{o zIw1$VphFhMU@Y^ai%&8BbMZ>@Kx6z_8^My>?|=;(%f(jYXME(4og@!q+S?M9_tmZa z@SLh~{O4}2S2Mgw}3ARp60!PFm^9fjD zKQtqhW*UyB8jWr9rx3p;*g81b^06i>*RHIWE@s&IK;!{SHm2lsKEh`vcRBG5%$i-@ zo(O;AcWZAnI`{k!yI>D|?)~W26Yn4N9H>6nLjEH+T_&K5wabrOuer4Z+sTi}#~897 zcHynDHiQ-*U`vzBt(jm0IT#ne!7nTe{xE(nzCs5*e5?<$xp#ZO663)K z*~0!iIKS?WO;c;HmMqK(bb&9tkOMqn7aJQpxbYElq z=ue^!J4ha@{>a3bUhaO@RzjW8x@$5pYVwyxb+I@%mi5s3vUU?c z2EdynJ>ZM&Y>!*lzV|Eq-98z=n(f?tr62O4EB%m}v1ChYV;>53m@i5HF*dSN zM>5%*jqTj6S@0P%Y{X!@&-3WQvE!!+*EWX34RI8IA`5aGKNmNU0eR2|o*JKa{KUB7 zL_cgnUwlXI{o>wj#;)|I4>~d?c1B0~%N8bga$X^WttlgH?r|+N!}@Zca3C~(JSPJ* z=x+6H{+W(VhL1+$*~of88+{m0{-rPV*q3CwJ3AVGWKa4RnW3f5;!8Dhm>(Rbun)E; zH(Ap#2ClF%3H`7wW22Mzt@aeeT_?Y{pBtMoDQj%#J(e6M;6cJ3(8F84g$`U%CQiI= z)`HjXoV}<~W7FTu?e-Dyh6bBRUyVmUBM`X=T-IkF=w z{ozkCJ(z#ar^sUCV@KY%1pmmyHCKQ7F&^jWiu|@FRe20JJb@`_=!5RaWao|#c+&&G3hfsQfZ zK^^@V3wh1&Rp$3u7V9Ta$JpqE-ke*X67jKfY>O=&2C4VBVE*s2`Oo*Wd_(Dcs`22* zxwnUt$>eo$*>a~le9+DKJO6s#__oyct(9B@QAZyVW1us(Gu{r9;c>hU&i5LdI^>52 z9@vT;d)oMJZjmcNC%K^E92!5S!z*R4SO3cLiUA#qUvbac$upKhi*B@Ge~robl+n}1 zcJ_q_V_F~lj$F>J$i|rTH{F>>%t>K6j3-wI9qo*Pt{!7<-XaI%AeZstJ%9GuGi*OO znlb1v`yd;Av9ZxP-_b@LJ|MvlUg7y~c-h7H)I(?euz|Y7 zhm9@KHS+=e59}Oa<+$#Hh9yfcIuEF-hOOXrkynk3|JpWLqGVDhiRha zuzlgF_V8HLQDz)FceZ34>?--fW2rwm?e^B;NW0JXj_ISuxOcJ94?EGW1V8mh4#o@1 z=G)zPw2?$h?)f>JLr)ohFqXGflE0^Q^k%mT>}D~3qS5e7%gtfqnKo8Tw$v)mN`u zxT?B-!KKwJ=hcl}GUwv4^OjsTb+cgTiCW%@7kzSJAGfbs(RJ6E5}~GckTFVDXX1ayo`Uv-Z@Keyk`2Gby`bg zOYu_K(1K@D9^c4=?7wt^fRni`)NGA5Nm7FFeSH4YzB|iovB7W9++|>S2Sb z?RANX)5}LrnO!kv+T2m&XD+IoTDz=jw)uR){FP&u&40z%OAHGQiyOwRU%qbQm1|!+ zVQ1Zy)mv9yRehad=QW0**IV7L^{=1UYg!j$vg+C;>&I+bx^C=MiyNvp81B|Ax~%%Lw%1NN^sRg6{Kwbt zU-#R8d}!g>ZR^HwnLMjv)cC38!^eyVbHn=Aj2m|2M_MNTyuE(vKU9tw$#WR4ot+O% zPq)6K^BvbrxcT|prhW49rkeX!)>h7xy=4zgxx z#*gjlBnP?lv~$OUT<7qFo<1bIMk%*@R5hlbtpzFDX$CTYUi-}_-#Yu$qx+})f4}~txxe|#H%veK;O*1D`0!n` z{_Md!XMW;scg#3`Z^!gMdEmC`AAIKi+Q0dm2QK;T(f!wSz4X>q|M#P}P5+A(uN=E| z+2vz4EnZXgD#P3ri&j;yS#astOXsbuT0ZCEss*!`j+u=-Q|F8tH)&@1sPQ!;hgVG) zQC41Q&!;Nvn$~oYP0-c$dPD8L?j-K*+I@gw=k9?`~ zFfaOZ-LC{5;6q;$=Ol}ZB=?-g=k8t*=jt2H8AnO-h&Q?IXGYjwW(sZaK^F3CJQ*X* z6PmD`@crJ=SzmqMJu|!Beb4f)Iki)|mMmS`HE+(0uD9Mct?Ss`)4QI!cShHz-ZG=> zix14|dh)iKuJ_(Jsq2B3iLPvQzqRy#E&b1nmYz8}kGHf{>`U5rad*KwtVc=xfPRUEF3j`){@GLE?Qo>aBkh0!q8=ZMRtW+O@2&H%!=J>uaN}rMs@!Ihl3V@=3d_ywl>~ z4(oG6!}jslui859x=XI9-hA;!TUXasZd|y!a=r0iJ^vL|m(5){X2qO~$1JX0HfHY3 z#iM6Vn^!RzxhBmhA5}eN#IP~rhm}=~89HG2NPF%$%zfLFv=^}je_PJqbJ}mV+-r&J zS9hPy`-1zG-FzJOWAq$4XsFk@=cRhu98bG`8DaONClj-xeuUohaCum+@VR)4=P!=U z{pEY!JiF`NcN+%YT-)`QTc&h9eAkSwcXdvSNmH#ZoNBC`O7FCD(wh#>?5bZmzUzj~ zle->&)3mO?dGpM_ijx<)kO#SgbL=q0os&~vUOsZblqr)d!9Lf` z>iiLJWB%K??)`tBE7Wb3}lE#3_$_Jy(6o3VcJ=-gjEa?eFwkK9w+1r8h* z-aIS7gJA+JJbc%5m)><(7!!tryQW(GG)v?`Ij938hKsvux<2=|8C^ek+w30>vHL59 z$Z7LzAhtEUPcofH;AdNV`^?6}h7ILjJ>OJS&YC@I9An$K?mK7mt&^SkZ}+r$|F6Yx z*kaFaMsv@O=SPOm$vm&LeaL8=r+k0FGjQJV;{6==ZLZzl7F-l>AK_1H+0>8_v^bJc*Cr&XYQN%+aKLu``z{PM_rb$@0m;X zoX$OKvp72#-Ow>#di4v_ajqnLneE&+*0#4AZR1tT-}plQ7B6ziz;j>2fs*_FPdp75 zgLy~5_N3Lum+x!beNtP4xkusN^P!K8;l8;s|MQL*nBYD1k(PJ|vceMB8EshNyHUPh zD>ID{Qd_FWa?*lA(rrM=~&ZeG``Q&w>R~MpCM+m z@pes`_AEZi6Z;9H)|XhuUW4n4{%0PZ`_m^MSl;!=Zx7P@?qAmRzWbN@w8ZkoUGFn| zyzgy`x*m6Fq2;6nU5~$Yfnj96rFkyxbiRLg*S8*Q_^)HT=f7o!VbtRhY$g-;FvYwh_L?86@VA}YpA#7A zo^eNQlyBMlJ#GGHqeU(-hYaA&Y@gLv*?7gZ83qPhycuWuCf|dK>zAqShxgC^$=B|` z=(o?@TTAMC=H83CK4-C>^m&`#Cy&nQ`g4o_AHA!#>wR}#)b-FC=5)Q?(gSat+x3n& z&Fy;V&LBPh=DA&8xPNZfzrSbBe;(U0vBQLMb3SfdY=Wv$&jV7M3*FtyZer%sZ2U5{5d&-tz6WM~=eIV}ese_e+O9L)z6E{! zoN&)hh;t-->*oc}uZDmDJ9uX*xyR7_Fs!(J2H3H&*=xA{hUNUumcyB0&i#HIGHsq( zd&yNbv+K~mrbfwrH_WhR_9j(K^Eq|ci+;i~^B|08_E_xYt>0*q!NqfAK`s(t<1xx?H=4O@vh&WM+XoXzGTA&_kA1NpyqLd%?Cv)$MpDN(#Gx<^ z=lI*wP8)BJ$=6~rW(>48|M|YaeJ5>mmiLj}Z}?g6e(S*N=H{x`5j}ZV*L~9kA8cyA zaKATd7)-t^jNX>qJ`$NVj}40s6U=2~1uMqe{r+H2*8=G~(e9`<&R%rQ$U$YvZ!grA zZ;lM;&$^FZ;1@YVSay35^oheW@xic+ughg0e1-jda&ceyF)StVZ9d?8A$;O~D+#PH zH%Qpo$7o`;`%M$WY4W>eotsao;~im_jFm;4>T7eS=~&$l~5p zMCVL;hjj;Y@GzNJGu-#Dh7lLbiRpemxcAV&C@E|UJ9qXlo4MaKF?sox4J^6@E=k}N z`INk#N&RakOdP&#`rOrZ6Q@j}4SOhs`$A8d9G)Z_%l(Fn)w|ySBfgpMqqujnBfoS) zKjJPv#|H2uj`+ESEqNEj?d{@l&pJlJp74<$Om1Qw@20qS81X|Keu)R*letD;)5ED&jn&NjHU7M}>JqV+Wb}L=<-T{pMqrp^dQr!BQ_1h{IH#W6 zC--fq#{v6`VAR>U;{l$K8-H6p-x;}gy$wI^n+(f&_tAYb z#yJVzthLz4+T8xm+amd$hiFW9-idPG8X!A1^<%jA@9aElKDDxH=ylWQUS>J_X?Q6) znKX|4VdJ^)Y_KDCHoUoghj6Fd=#q29^x?N6*eBpK%@sEvWMk~bxwo6M0k*?#*aN-D z@s026a%}2-;Jz(`2Q>88926gu*L?>F{*_E#_l_sFW8Qgx>9?2M_kV`tCSd>@kwP|h zzD5RQ0~6%fojP)#+_}afM~^Tc@wVLglQO!11N1`Iu= zPP=I3geg2zQ-9Y_<#3Kou@SOJ9+TgFJ4Y_8KqG(A&-Zb-_clq+8SBgUlx_}kj{L|; zKP972+7cU3PapKeU-B>ZKnCW761GGJ~p69Y8=89$tS z|70EIaGlpN=_j@O+`X#~Kg!ZOoXZ9#oBKA%^mOlBnttvbXrH@x+Q5ysMQj`Gq>ILk zEw{hHF>m~s)VEOZ_bG`rlSw{G(@FZHTehTrbxisJnUs)C=a$PJ z4o8%ub>c-1-T11pW%gUlvo0D_&7LvLH|?Bp!YSN0)4BIqa{j7}AEHTq!VlO!gll(h z^Vq$MN1NKAiJT{KPrb$npR0~s^5mQ2e_I1~k-&qk8SZ^Sa+0mhTvxhxiI7+IwPW3uv;-7DQHam$&R8G~C8@;nx*az9p@wZ*?y1(zqeE?nm{w{K^pOwPn zsjerv{rG7~_0Zvi>^@)V@PUI$!l@_x&S#pi&3bc=-wg*led^Ku|G0Zl#k$PT3(ptZ zF#kio&-ncRe37>($GOK;*#F?6XybElN6|3%-&&422^MlpZc*kPynx|oVK zC}N<9fg%Qq7${<(h=C#oiWn$jpooDY28tLcVxWkDA_j^WC}N<9fg%Qq7${<(h=C#o ziWn$jpooDY28tLcVxWkDA_j^WC}N<9fg%Qq7${<(h=C#oiWn$jpooDY28tLcVxWkD zA_j^WC}N<9fg%Qq7${<(h=C#o&La$5apg5@HrZbTZ}{A^Uzw0dB&zN6U%mjYsad>o zv@2P`juY?x^wWE-;n+_v{+!D{@{`YyCy(+(3Fi+yf9VeLrX{-;FI%>I&(f94`5RM- zwU^v*?V;xOLpLm5v}oDN#miT$ykTAQp_>l39lT+G+bt~z_U<^`ex&K91-n|C5Aeq* zibv4`MGO4lSYX>#7Gnk^5_R|g@l(W&GK&`B@R3Q=ZC7n;IdE0uflTfB)+fiRNl_e1 zopw9haIoYH$a%WrQ!egh%1b@v>A!x`>2>U@pMD`NF8cN}kCnejef5=3e4V_;>Is-G zX!<^J*|BvkuD|kVpJRU!jC=Z|A7AA!rq`bsyTFYf&Cis6(8(>nr~dtri|;DipOZ_J zFSXyxP(?8>THxhtf%>n$bY(K7%+Oh%I!~TaXNk5>Xf9JyT~Fqeh0w&1?@Yfmk+^*w z^y^k{UA@Up6rToXh^w1^`mK)=cN)gLBW=EGKPRcLYiYi<=E}y~n%h-VSib$Qcc;aV ze5tj+9F#a#);Z|c_IJghEVZ~pg!R8lV`pbS`MLCcC*AC*e&|hZT;*j|hh2H!+t+>! zy-(eqo(EK^|IhsJ9WKtNYJ#&QV?4IO`MQ~W<; z=T0@tIks&vohH{tN8xOa%9Z1-}9v@*@#N@C}vgBp0 z?{qlYzCXy1{bk^Hl?X=y#&a$td7R5d3K@7UGW5#`+1<$j6bF+)gx$t(HQReDMOL(Q$tO}{7kB~v)p zJk`8R&eMazJk|US({R3R%i6a62ip#{m{ay9dJLPin4vL_=p;+t@yZrAPfu+Q@(o`J z=Be^5q}`f`V>&c%#9#A9Eccsl6RTrFVJn`3fVk9}Xe<*Fd9vhtTYK*z;lxv=9 z{3K31E`$@U6T*+=R=#bEExK(-4kz~ZSY*d4E}q|_L1OZKVcYv0t~W@m?6nzP+HFpA8_h7*At%GFb2OD?r% zlk2*T>$fdkx8s_vJ9=&%jh`!*T(V;}xz44%&dP5-mz+_1sb4m^ewX&rI-t0(b>Qqx z!G596uMg5k`L-=rwe4=%?r z$P%Y+{;JzwoOmF$4rpxU(10KI_2RF%tZ~Fw*MaA1UoZX|Pvc0A4gYv<*8$ln*E*o_ zu?y>f?5H?;;&{rQ$n4|jj$Q3X4((g8uDvmvGo|D?&HE+7`@ijNsW|G^F)wdYevb#~ zrFEdE*CnD4MY^`a)C<;uqwf#mZ{6gG{9azkFW&Nl#&_~35(QsyiawA((Sz%(XFF2zcbc%$D_i_KmvOoJiNKD^WiQQntru#~CfDyWE=w-iF`HcH(q3mC4*aG( zlfBfQO)hV*E3VkOqhn87`~Dq!TW;T9;B3(NxpJ*zTDP>0ZTO(S?)CS-qI|Y(*=!GT zo7-8)dUHu5Jcaq^b4%m&z~DOO#Lt84nxkJ1)-mN_e!0#Eg*s>*6MwBM8b@7EU7NP9 zsJh@>T&@_4;~7cFMJmX?)>CxDZaZe<;9-@FTgEZ`-n^slDZ(yF1du zTWXF~98PZ2AX)Od{sB%-cLg{(rFcfy%)cj|2c?u1A6S8ll5*SNcP_io`87oYCXAX)MagM#>^{McW4 z-1$68+VNn3yXv-pF5J$uLmk4M_-4Z0hGXX#cV6yXxRYE-+QAJ9#eoC9mXH2kG_ump}fwljgnVx#s=85Bq(IUw5RB z@@-qTHg_C8(%xLNsj=li!Iyht6FcwUkZjF-a_WEle#Gb7pAY7}^30T}7J1ZO?@S(= z_u`*v-gjJeZs)z^&Nc5Pm;5F_$!}6b{#04{wk_9QSF?V1@VKpKk7ymMxOn|W4U#3V z{_ntV$~U|a_)U2h(qxmy*1Kgi$Zz7C$#47Ke{TIIxpVnVa&1{_?~9E~y(j!FlU@2G z6^uFAvUW>T^8tHg-MF_oVKXkKOI}rJWBHBNn~bvV6HRH)FT||u%LCkdekv z`0VO7GkPzM%UfFaw>0&Ffg?@XL!1t6zG98e&t?9cG3)$XYA+u3RhJz@@)&Tu^}%0D zd|#dO?t1Y4IyFwOdd^7HciPQ_It$1Rc225JRM`Kov6M)>+7kV$DY!#+QLcLB)GIyb z#tF*(5*GXWwT*i7CG=c)c>lp0L{iL)7ARWaWo3aWcHuYdWu|IT;@5;~^s{TXWcP(5PQnGkj zv_R1UFE0y}BudKNRgC>HVLKB2N>X9fEYaYtQM>S!?t8SeOM_fS;%cb-p;+BL=L->w z&1(ai&iY^UU;ZrVmp&bx7JLWNo#)H3CRoo>*NiH6x5c`TQP)|&=fh8#Z9D5rl3nD3 zWJSgk=l@V^q2&;1#?uq`d^GKQrtTd(-F0!PhvD{5-Ry7|?f2rZCO#jm^XV;CS3`}x z`{Z)Y-C;QQXLdDT_~F+7rkeRRYZ?zV*Q{+jaJaqkPyx4@&((dG4O4^f`K3W`@4NJt zUUDcu=6`2E`H441es@3}eSXPTN7pNHkBn;D_qls=+z;>PUt)9LwfZ>aNsC$00xwq! zB)@6p8Yzbne0%1#BQB1%ZwS8RBx=^!0GgY&BWPf}#~yvu?pwcf8FO@=G2opm>TKR z7t@_Xa;cx>iuT7|jfW03AKum2zN0rEUb|6q|0lU5hvX8a?{ zYr1&X{JN!eyXP-jx@X0nrp86PE?&Nj?V$9M9@6W?6M&*KCxg;-g9o*lv!!1k)?Q^vrf2o#PmT-&Yk{pt&`dxusk{7vx^WB43pUmtXtYqX?&@ncZdsqk>A3h|PlDYcHKxXL@vZV=Z-@G)oo>Oy1)sT-RhvYitZ76xea<#P|+-GX_ z=^?o!hvYi@k-%P(Hzd~qe0*-L6}&?eR#b9Hj-*^Z=1AU?LcYPu&-ucJHK}_;`?a+%v_MMSJY3 zOWZqi`(72~N7n}VXMLdRTVcmP7W|f>`oI6c>{Y?N4SBJ=)9lgB zTs+&EZt0~j-Nrp6lQ)qV{m8rB{T;Aj#n@x2t9|Xd#B;;e#de5PzU1!rMk>>a8`h+X zj4R&CgVx|T$oviChnakQ{ww0H#*tDD@wm`;?tK=_x+K7WocsreZt3y#{1m7 zVV)6`HLt#8=g{wa#~-=&4POi19hOza+Jgm z=kibYJitfhXK?#6d?TeXUS2u&i%Z?DfPZ)wRQ5Yz&e2><^%k#SFGGLf<{3K&J7w1g zc&a-bw4B@5JNp_>^?~ojR30KK_H@PqRq)A{YL|udnb|_w_&z8?t!B zVo!5A-8{md?3XY8gqwWuchrW|KH^zB2NxTjz1^+Pwc~5tbBTpn6R=X@XZ?IPF-=My%P za0NcY*b?rJ{zHJjGe5#+}{8pPAncLwF^4+i=1Uj_N8#{CY@ zC$dFCYBVUwBb`7LKY%2Y5R1 z`2c^yov!CzFj{bz>o`8DFx>qMxYGu~PLsIveEJG^NB_3CFG%?^iZ_*0J#>bDz>(~i z5AJr--`@{-(a!V1(W%vi;phxF3T=>uBk}1g93A_gB96@R{t#}Wx!O~?a3uTXizD4n z`l7MQ2S*z!3&YXBf+Jlp+o^CQK7EFx|0?1rg^nnGR8IBKSrSLye)-^t`yRTlD1R3E z?(rapzRdSMj&8ri?fWF>%R86xH%mWf|6O`e+RJS<#N}x#Eua zJYtLk-s&6NK@Mp9^%K_gd_h=aJRPZX@#voWG1dk&-M@J_{`2BGB6|k5$A;0A>Y+3F zQ})Ye9a&_=dXB{P6wi|Me5tNHxZdA>D!8udI2K%2o!IZoq3ipD_JOW`>tULK033Y7 z|Mr8O=5;JwxL`r*pa1iE#qaU*vR$!L(E>#a6fID+K+yt43luF-v_R1Uf4CN?S*`c0 z!#Z;PbIdCAZT_e2oa>P2H~Ov3dwTUY`i?8ZqxSq<@=89*D~{5moe%d^*@Jw?<{l8m zkRb1AGpK&s?-qZZ7t=MZ>guhbzadw1wf%jV!|lz@X3RN$ z-P1Z{X&Ct$i$s<#yaT^KVUCu4+P&ZR&ChP9jr;lW)1Du_rPs(MiFM}reu<7J4!Gae zV3u!bYr3iV@LE0b-J0#){kji&WlW#tE7j9ZsCyT6uR$Ok#WUq%Z4%6cJml4FI<-XFR`SM0j1e#-Za3f7&v z()9I5-*c#6=DcQgur43`gIJek56$b-o6_wPwL@>$)!x#d-W7Z=!n)jLzv+Fh*X8Z+ zyfEgq%bBmAwWdv_gxt4vgFLQua-aM-!oGJ|H|)C@1^{+V^L53wrh$$ z$~nLC*|xs*@9E|X!@rU{bTt(>b!L=d-kkr>G5ONL~rTOzOHYtf45&C^H*}_@~`|U|JH2{=CAx7=U>|+ zMXU2Jop-sn^r!ncKA*in z{3|(g`B(mwf6vzY`RnI#)Nxm|wjDauivZnQ`t3LN?fmVyK%Os1&RqVLKjq&u*9QKT z-(&sTiva8V+Y9<*eH@=V_FWj)N0Kv_f8|g4cl+xD|H|*N{_RD8cK+=J{fWJOJAaQ| zApVt{x%?}C%D<<(g8j4n9`*0m_QnIfiO;>I-+riX{aby3+~1I#x%?}C%D;ABGx$E! z&*NDC_9DJI|Mr4@dmqo=?H7oDC1)=G%AfM@@zsHU<@Z?s_9DJI|Mr5u&c7GkSNE^B zUm*Ku$(hT)@~8aU@jpR)mfxfP-Ew5tp(E{k8k?GXwu$a7{jomw@7W7v{z}eV{*^!F zUww}!zi0Mu&w^~qzdfU`?&J6CIxZ0ZO3qyVl|SWQ`BQ#ZS$WDoJqxnEr9a!=xBIJO z7s&Om=jEhj~xv`xg6+ja@AVdin-?@XaE;^$lR3@b=GkluY0XW#rd zx&0at=H1)xsrb$W-um7q%)7VW@QAm*@d)$o?RO*Mt?vrLynFjDj(F>x_P*e)_o@4W zx8CIq^X~2Y!Lo_oBMtNJ?YpVst#=s1yw8;{_5NI6@YcIqeZgDr4TX8z4x?A^GRfY0 zXQdnOUc5(>K-g-`)#=Do#p2b_wD8sya``lB!^?WSK zyJx%6VAmwxdNvc~-LsukI&VD}2=ngkvj)knd(z!__rfURt^1+fc=y66;;nmeVcxyH zznA3g?*nz?eGY7*dl21tp97od`ZvrwwI}b{HMwk}Yp;0TJu{4WYu_KwyJv=hcO82+ z|C@bBLVM(3b_M_IH+S?KJNiuy{bp8)?+icwM$3k&!QbxD-%8+bw3PZj%H#evL(rwO zz9h?+==9l_;cr0rA(B}xK4rhi@0;FSd`|tk5I&jz_Do%#@+1{>C(*x=pmKUIO8AFw z{$;-t<}3Lw)jLJ6{<2fP{bi4Q`%CY9`p+;yk4_8zE(`s;<0;|)ZUh>o>r!t0kA37P z?)U88YKmL2+i_h>^R2oZ`=Fj|TGKbN>E{^!2nG%Pf8xPFF6C;9%BA*9a?$_Dq2?XCn-8?L9BMhR zSB%b4E_uXG_7c9fWx&amcB5rWbI)JNWiEtu-fd<5T`9>zetPQ%-0xl@SA&%`ukOnr z*NHa2 zb?VI25UStj*A(TUrmUwmSz9wVVkfu8_;Fv6!A^=7S8lQUXx2ymyE}uwq9b0p#UbnP zZLPie_0@PE-W44z?=tI6LxaafeMxP=pK=h>`F-5b(J=AyA)z9t^bP3Y6@PgC@r@T) z?TKfecF((&gCBnPOXWiu@UW$E|H0N?gt=gy?yUD~t&PaNn$*mV4_`1SwjmrK9Ez9QF=N0(eI`lNlsKmT{P z-xu!Z{vuZ}9CH8vmY65exf1mF{rtc0o?yRp!oP1+W@2QwvG$_Td7Y^~tXCXOxSjKG zpYVCKO?1&d+4>dISNxSjdrs&(Jx6j&jwk0jIzx4K?hea4>sw1#)PE(h^w~tst`pRL z^k<)3_1$lOX4Oyr>-8?ij{fHf&wgsplxKhY@NeATqkLxlcb|XY$w!`F_qrpip?7|D zt8i)me!&$}>357zzeJb!`2dSjQ9V^w&d9w#&W`)Fi~qN zKb*_sjK7{zF5a5+l1uH`%<^=iaZ@$Lehp79TAkWMx_`90f+T+^5O^r23j-lReXT4nAX)0Zn=+sYi z$G;NjA%3Fo8k|n2exlp{#eh!yL}!S0TStwjexlpp?IwPr>l&O+r+%WVejyl7{6x35 z3_1I`dv`Ts@e^IwVCaJT zJ2jT8pXiQz{lt&H!SR0_RAo=~6J4$MgZPPRZ5ebaIn_^er~P>1C%Qypp;4veR6o&` zd7O!#=+>4&ml{v~M0di=DSo26rvLTsRQjo(=+1aL@k`Nt#`Y8`In_^enxEn)x}TM# z+f)5Sr+(t6^3O_A_^h=`&HG_~{%yD@nE&dpc@f1OdP1-MN&1;Sj`(;Y+(q%8r1$+r zf6B)n@zuCd9Ex83lk|Sv4W6&Y&q(k4C+TMd@{6zJj^a5vzV9#kvbmn#^OgNF(W}4c zH%##Kp0DK2M6dp$KkEG_zM4HaM ziVGTVoo$!9><|Bqv5H^W3fte(=llI{yAHMbF7-;~wQc*|eocAZ*yHZLct;}0Q$6!L z0}ubp1{0sL(&vBv)bUN{GJ0)L{>JJc|52oz-aA_Q97@?Sj{iFEHQH0FlX>X+x+GCr z+CMR@{}8jpc$XkZKjLgd583kvW=HH9J>bZ`0#SnVXpalCEI*$0ev==C3;8$D?u^;} z^ouD?t^DI-Urd#=pH1}5e;H$6YvP_uL#I8&>6aK(I?5nDFfl3d<^H7Ze6#s+r_BxK z#rI?A0&autzI(aj-ko!L&6%y&xOt;Iz4iPl;m0#3j^rHa=VLAjH*LOV)B4R@H?H5Z zW7F0h2O4i_+3PMcckF7+>&G^(PEypY$&aGDMA!Vbt80=~f68Q5-o01$8sS*D6^=zE zdf947)CzrWv? z`;!8G;r}z?xG@yp<8U127CsO24xgXd?r~ffLe@Sl+J-x9wwZQA+b9GJX@9U+%+B4-T z{dYIF9&X%Gs1?>hRnt2wNPlERe;qN?UQONdr2gLD(*MkByuC8agOvX5&8;qi7xq5P z<{nX{i~n)&e`@3Ok9$8OokMV6!>wap-=zLay#C%UQM#1=P01H33b8=yHH<>2(xrG$ z4*e~p=RA`B_xdLFzs~FL?Gj~_(!b@vp~H;_nhJadzOhGC=~BEghyHPYr#ziQ$p2p7 zr2ezL{@yN8x|II=+qg--<6z_AeFeDkDo0hbsW7T^DVlTWpU-pZr2oCXN&RcR{@yO> zBlCWO*1w)TKDzE4JaoD$hyFbK%5^05_xdLFU+(qyc8T&y>A$<>(81QmLZ6-SPT|3} z_QN&ndPMHTS)N1xVNs!D%1QmbzDfNr_4<3eL`hTnHyt^2xNZLq-is^%|7#sp&8FVG zO*tut{==g}$CQ)$dwrAoU+newc8QX1yJqv1>%!Z=Tie=OcSn2mZQ1SrYzVji^Le2o zCiVCFCiQRd`g^-X`L17o-TL)Al2-7)B@peExx6L#@qx@8@@V-p{BQk`S$UW&v?U5x zr=2JD_xdLFU*Yxlc1a_$LPY;t+FFn7Z;p1#QogQGf*4-!^ZL_-{yMb(a}RD*nITW= z@AXaU@2}g=c)LW&lb*lD2eKW7#ldqC|L)D9zrUQ0ik?hJZH{_1qb+eKyNN&R~k z{u1XR{_W49zi=R#<8t)pCZq1t{>VDzGjHVHfV7 z>wdZJpP%|#aQ|HQ)pg%o&jB(%kMs9e{@V=q-*#bMYT*2QKRe9aarb2EmVL_I2TbNA z!F}_xxAgM@_)09=YQIe#AOz^pOp-<*==tr$2=!4d+dhby*}l42J72~ExlXk z$~+&%$D?oU8NaYzeR&>d8;yrOv1Qyk7x;3RS@$k=|AWZECC~fiH~DeH{ed6l-$2=g z>w?_xR~lZCUd~|=?91Vv_wRg{(b|4RdF=E4pOuU^RP%&BdgStBru|C5E%2r|oB9|0 zAwSA*^5dzS0zb;Xfuf`AIq7|Ff08Qy(v{z874P!aSnmy^YhFDkeW!0f6K^>8yg&4u z)SeH$EAg-WNS-j1W%DE5h;MQGmB51o(ylaO*oQ{CFiz!1`AvRQoR)tBZI-P~?EK>| zrZk%#lsg}M@dH-*v~T#f-^@Je%krbjYESWTXU>m9%&7L>2G6_Ak54E5uJi+zB0a5` z$&bu=ty7u(*gw(VM$wTvQ_Y2!%a8J#{3uQ2UzN|7Jd+=hPkxMBAA`L|phfune9^cYK|rdH30M^{d{tZ`HqlyV~`==$HMLZ@Rp#zGcv7S9wyGP5oxu z^L%>-{Ub(Gk~q7}8ag|SSA)@SHX1s@7haye^Zr}st)4%Bd+PQ>i_8XrSUa55kVJUNEHV|4uwzx0NaW2Vh=b?-6V>O=Oh zJ4DN{$3Ab5RSUkdYR%4fuli{7d!K{P@W20X{qFnz`Q#6 zoiWbobNrIGFaP%y->d)3?$4ey9w&eBrRMq%zj{!8-K*Z&U_2U-;pKGP^Vv@%Z7;p^ ztqc22w1wrJ^$Y%TReja{rO*C)=&dI|G2=5Q!IXGBSn=nV=$!nz`{P^V0zVhyqrT_NRlaVg2JM;I){q6e(f8FyvtBvay=FNGkPYR9WTj9k+@*Ocjf5cV+ALy5>ENM_SL(je|m!JP-QYYg5gK4lii#Xg?2x`8|lR zXm?}NqFsxYH#RR@wtLa;x{EJf+O%ld%BJ1Bn^!K{wWO(e_lo8{%a^a*v3SSwMTt zBE#&ZhqYzTp;GK~m7_!Uxc!y#vTOZy=$@Y4AJTqWe6*iFwL6aA5+D2geTqf>*9Us& zIZIfp?&s*q;qFsB_ch~X_bHTnU(y~tS4r4+32V#7yF_jJk!?TCIDcmr#GcUuj>LAF zg7avP3$rXg%5U;x*$sgo<=;TN4QmsLgD-eZSJ?Vy<-dI~ljdLc4SKGk@`qyVt2v3Q zgXbzG_FUyu;=}z&-ABmgN5)}Zd^?6N;ASIOdpzgvV_gU}@}vAFKOXh-TmC)YbjjpL z=Az{`pg%fTkzdB+iwQ*v3*b? zafc<|h0}by-O3z#KTc(})Ar-8J2!T9-FfGb?@YJfaoDitl~mf4EKii!r*C%*ikpjc z$mGXU)|SnWVUFQ*cwWc{e%xvCN9*mCb{-Rsx~VANbZa=zE5gqS`$AORBTcj6rqa@q zJA=_wkKNg4X>1Vi4}G5{zsZkfHwS){e*=54uPW0% z%c|HX-w-ONTg~l@txEeWl`l^3=1W|kbk?Wuv&JV@BuL$lIE;sT;m68wg+CA0XZBf| znK7L%z$(p0`AvS*{FZ;uH`OxvQTwdye*DATXUT8!qx>fSruJEykJ@(y&kzpSJ21Ce z3SPhosBiJ_#i&kY@g~o{&$>1ArcIbC^FB+xvip%YZET_gMoo z?z6P7(mqS0YyYM9r1ajD-WS$=E%pC*gC(&j{QlIn19*Qb9`n`j58j_rUe@9FS+~XP zi!?}$LAH{>C`{VfO9$%(B%Ro7sg7ukhsry;1rooCDCC?PsWzU!G`%~U;Nk8rg z{3x6RcHEl2Uw-1F>E)=gBjv63ZW>4a?@wJjV0?nq{mA9VOz%$x+yZQf^B=;FOY`xl z_nZ89>UDu1)92;xHHpNd$@`F9U3=Fg8t(WaR?g@Bsg>Rx|He(h?g#ht8$$0-*?q}N z5?b?=WbgSliFz_;0Q92fpDhzlD3!m$hbp-Vt#s4~f*LryY~qN)kIW50S*NmsdDG<`KG>O*NS#BQ%Y zMfBGJMme(KGw2b_<4sl&F3XK5j&9@O=E8muMg#af883W%NX84luT>lgy4P5|IPrXn z1?A^l`Mp;8gl`y|>X3H!{;ci6J~VyZdm>S7T&vT#1cglTqSj&yDbu|Dz1jh*31 z&T)3tkZ0ETc;R!^pKp0`zIZvK^CgqK{7TsBt=DYk6Z`h&-EEorWvX9&@L=n0HP^V` zWa{b9?3}URS9-z^pq!%Si*L%BC2{O=D;$gHl*hNq=S!Xm$GV=<^=VXIU8_F?XJzq!pjIJ_UgkGyZI{@=EK%+KY|uS?e4=EUVQVPgL*@AP%htBtxur_r4> z9`(k<-TyZEKS(dhhdw61tD~L+eXM;d=R+p$J=uQp6DL3MqaXeSyubIh4-d1{U}=^$ zcg}y$9kVPAv(!M@{%XpLmOf(X9ac`<;>Ul`#<%CIP6qhU#__t2ldE1h`}r??bNZ`Y z-L_>d^&flln=UK=$~WA*zI*OC@cG3Ty{Z0%mA`O*WA2G7zj@i`Up4FGw<>OX4n8-m z?_XbfeZ$Fn7rgpeX(C5E$eZPj~m;d4m#^VbQ z4H>m+!@7^0JpAg`2IJ9y3@@)EW&4!gy{QwID37?ZtHaOFDvi44UmC>WpZ@;WuK?%5 zd{EzC%`X4@vuVYQ1?KOMja2u^zGpqNt*>H~>Jyd!{CwY*Z(Xy#Z_7^)lnxkM$osak z#mhA>zHeK6-?p#cx3!-KF7SQZWb7nd!TZ7; zzX|e8j2PcPhRoC@wx0E(##$tY{%*x_FIRV>O1GYfPW?o8?Aw7J;wSnwgVO2LPjpBB zE}#=X(b?Chwi^wu$7?KCKhd4>bmB)}jx~eQ>C{hjb*F>z#4n(-{|6#x>hF%IpXl~^ zI`K=e*6tWkNnF%rttTRT$JCeU&tTy z;BOFq$c6s=_(2c;e&L5)l-rLV^qRj?&a)6X=%37bhw}FeJ@^}@3x45;{>}Oae$az| zXsYmwT;%J=4|?$TPnPmaIZ%F-1N9R5gC6{4azBAw^p~gyCO_!G-+*#UIZ%GH9U*_v zYktWea*@9;ztDq!s6y~dIZ$r2Z?pWM2S4to4I&qOe)n|dw1gW+{P71ZPNc_g(Z`;XyH&TH;!U_hNm0)MDay?5$e z>UDkya`E>W5ARO`Ihfb$|Gbjx=G?nZh4G!w_l&Tc+6-Zzu6;Qn)OjSebb1K?@|~A% zmz4pSS-JZg*BkTq{qF%th3e#{6eIdUghmXR2v+vD?3t!LThM-_xL@k~=iZ;O&q2j~757by1N_FL=KF_Q8`{xGHr&$?4==V?94R!>6*w+sC-Ay{5bPv)ji|x4E1`fYMzjx`!`#F7^ ze(W&r!S@^pe_bUTf7yn8)t8h0*^cyu60J|GE%`6|XOL3RtBy03vt8UnQcTAZKZuU| zUEYrr?fY2*Y4%NCxII+lMYiq7y$Ab|lKytFfgAgg@^esw^xNpi`!}oSAoTBej>YpN zp2zTfZ&q`iS~24}Ncl>c0n1*}{HYcze%3=?-^_YdZafFA zH^NR-`PYn-o&6kyeGlN<^WV;XocBMlH6hwiy!h*-8=dCRC*rhkOZ(tH2f=QzV`ZnZ zBkGCL!{~Q;x;|`U7kCbW-C#$wZ`gMmE4J_bnA<%1H~;S|Ke*rJ!EUf4><0V#f0s9W zH`6-5%ftKwzQa>DCt8z3&zkIz&euWToG18Oocr3>yU%~pfc?tukScxT(#|vv;3Zy)fo1JJI;dLV8>0L zlW~^R6IB;zA7!gzL#|#>c=loU=E8-qZjt1R?OK{gYtJ`3<|*xclrJg0)w;xk-m8wY z#07GH=62!rysV_D?_lyuupLLBJ;H9V}y%E8tVC}Jr0vChw3go`KWsrz5LbsM~~>((0<~f z^>x$^xGnHp73_2ph1p^L3SpJ5=BsF3^j!Y^?UREi?DWJQv(=fMW0-9$OT46%e;jnX zLU!bQ{Oss0%`JO-3~_t>I`u)g-|~DS1p}R0FB?d<%@COTOL2Xf)M4(K+*f_tyzkW> z{@TGZ4#*Y1{Q4sw;qMCJu*xsfwJ4KJE$d39kn-O6Y$tmifUMiYxD2^ryoPx%jL$G0 z!#o)1+2?Ut1^Gu3F5Z{Q+Tk6J_I#!s+)d4Y!7u;PRoAjUHhx+8He-Z8xDP-M`j7I9 zJ>;!FeY+W#?Lj(Wedf6j`1}{_20N}eN7)hfRr=uhuTSHCPPbEA<{j?f>~AeX;qX2YsRY0O!N)Vs{TaDruC1hs^Cc3hfbggB{VnVc%^H zqn{ly|K(>#H7@($&VRvfup{gS`})s+srGmb-5V|Gj@#pD)c@dqJ39ZhWwylpmrIJr{-5~n1K)YzyN~{F zsP8`TJ%~#V1sa!*%;^dqw;YT2?g(-l4?f)uhiS&-ZzzB zNS-~d?NyKhOk7`Ml#X&>eSG;Om480#9(EM?KnK1RhblhE1OJ-wZa&a~Z{uN#5Awig zS8?a^D+(4txWLD?Z4}@jXjx zadUj210U=Qc{#oc7a!=r2Rg_@c+GgVYL)fE-x;9ZOd$Jn73d#S^$7H^hgoj$gC6`1 zKUe&a3%mI7gC6`t!VkH?ZQ2R>gC6|-(heXO{IEZ8fgkkX9}<4Zh5r1?4|?$T|5V|J zT;vZqdHD-H_!~t3kc)D|z9v8D!9TD$ZTAZ(2l!wIlOOcp-}tuThg_5!a!h{EYkui} zAQ$z=&wd+)9{i9GxzL}N{_W>u>F4l#Jn5hA{tkR54pSeCX{@t`*2(j`(_^UT;C1qo zOLObwhkyO@HO~2fNzbbH7Vw9!U2U%~9R7jwfg{LAx6AdB*U3W;#&N^n^pbaaosui- zLuOAfo|g;fS|Rgf;n&GerZYVGm+$<>anL8P$z^?-PDxXva;N0AU7xe(8BF@^C9Lfz zcGGs0dI9??JiJc+7aMZew!L-oY{xU`$L(S-4?8;7$vaoz_g>iLX~%)VTkLaX;ODS! zTUTtyVJZ^J>9-$G{{h#y&LLc~ly~G=Hh)ed@5s}USe0Ix=uT%k;!TNAr%)}@9I@JP z9Qk_drv0mU-N6OapTJjCAI~TDiP7~~>MiOq$ld+YxO%JamyUYOVfDSo8{EN3f3u_1 zpYa?=4rBB^Bt86h0(+L0j^Q88W6QXTMcZOF+oJRSv^n~BuX?PcDK_Wz(C57Sqk$n+ zk9%L4VZXo5%g~7E{Z^}eUxsfazh^;RkEOh*#{;*k^801Xd|ZRuGs$#II@Oi+BlL-1 zSR|iQ+|#tL6dUzWj)dKVU26P-SL44^`XSMa$)DSYPVFQa=WQk9$)3)(baSFR zWs>KGYwZ0eW4x_oURv0QiwOUBh`57(@SVJ~odKU~jbHF;{MQS9pL&qPulCbyPi0$E z$#i!-)5+agV0Bm=j?AajD*7A>G>&^biemoEH?WHLmRcZryrZtG5U#cGntqoT5EIrW171&U$(?0c>4)C?XM8o%HL zevm>h2*Y>bZ|=!bWsmbtoPiBr1k~9qu`Sw;6ZU73UiOz^1d8nG13&6J@DDsL^ONpG;*!OsYO4lsUp&i?;c6;<%B#xHm^{>KEr=*1Lb;%{op zWTI?TTN{zy%%8(`0r;nQF&S|hzu?vQuN3^E7lX|*@h4NA-L3IVOPmJ7ZAp_lKU~lB zu}n*BZaDgU33LX$2Y#l*{coxllM$!!3to-?2ZCSpVzA}m&-OHBd%9Zah91w-0GRG= zg*$^rO&@CvLvQBK;XMNIPxE3j;xvB2tMUIx@QYpywtW1}wB)BFZVzc_qurLa6bCOB({1)H;rQO4Kwtw&Qy4;d9e!;8pUnlrQFK#X?4}W_`&0@6m zgqp^%7TWZ&+OYIy{v3WW06*4ydhsGo;}^Ud|60K>dI3Frv;D8iwDq*7y1UZNpeXF0 ztm(s!nDXU4;DMj1(Ecm)S@L2ue!;8p-yrx!FD9djzcrB#XLu3R5Ru-@pToBV;Gf~e zWW;Iwf>-0eQSggi47R-bpKVPfGiQdkWn)BoGk*?$D**pYFD4^S;}^WZ-~Z=J?fKaO z(Tl;BhdO7TJ3RuKl-}Vw=87$h$mN!GhzEYA!2ORu%n5QD zzu?vQcNhGk7gJ6Se=<#|`H3%l=TE}wi{f&Z;!(y=QROrSwC6u$EC{Mk;DY?#KdX5! z_(%eN!~;Ll{rnvMmaas5iiW)HiO$Z#V}7TsWrUx`z0sJQ0_Ym}IofOf#~}9%0)M~Q z8~A(oQuBrVQZG#A9R4gl>!dQ-=1galF0ipEE_W#g#r_-%{LcRGNH@7>2>5|l<9|uj z7wE-g&f(AWba(cIZ1p)Qi;LpQ@$=O$-cj}cNxEkI>^t32&VbLg#xHm^{sUybSn7ev zp2MH*rl~A5IWW91)tyKtx)Xtf1qf~s{7eG-^ELWEK3_b@Y5am$<9}KD3(<=yCx@Rl zx9;Yt-{w>{8@~N7AugW%jmG6J#Ww@+ALAzX3~Bs=SK}Wq_7}aF%>4dmLCvSs6mVN& zbt=-+k7b>lPMsNB5S`CijvILXgCcmG58s)7gfrlCt?>(9jlWdzi(X827k)JbY-=Ij znaE~S!MDOC;mFKvUEx=y|65D3jGuj{`!{F6=UU?zyc+*MrT&XvOm^nuS6?`VjNgBn zH1Bmd=>50fIbF_jY5am$<9|W$i(Z^Od=31oQeEAt-uTL{Oi$={Kg@r!%@>;&m5+Jh zl2rfsz5i((0UwFvmpiWgE;W9^tMNZ4_(d-!Kk(CYe`hLwMrw6%m3N7t=l{-B?4-zi zP9cAz`mb?&;J4TBIT<{zHGaXX@xLqhMK2~R@b|2Wll{AUx}rV)Sj$hQ!GEM0W0ru{ zA`AWnoJ9C--$6FfaqV}h@e5v!e@E&6L@y>k@Js!-AA+J(0jdA?V^9=6XE_cHz`vi9 z*ymc~7rYw(Yhr)Vi^&fB_KZJ`;-g}i%k$n_SOeD6{a@SN!~V{Fc+B!6tnmw8jsO1y zzvu<@@PWT0)773R;$+xGMe-qk_S*!%Ji ziD%n0neK46L3{m6V|aS6asdCKoJjcD=jWd&PU9DQ1Ap(EqA#fzrcB_M&QHDgF^LL< zm#I!uy#OjeS19Q}-&XbiS4>3sZQsFgpyS%_QsWoA8h@Gef1($YANc9Hzo?N9J^B~L z=Pbv!-ctCV;7G!6`woJG9M^uA8o%Jx_}>xxi(X8A;8#muqCd&aOVR4E?yl9b`r;n~ zUwu>Izk~}%_-)@&(3s=e?^5Fzyc+-RVt>(#$?wLmmj1*em~~9hxn{{1OlRNcZz|_>-x&?nFGQ7V4R+*aL;7P{3~o2|pa> zzYs3uYy4tw;O~81+P~BbQ$`MdSE|kaf+N}pcxh2w?owPY_P1j_@Z-CDHxN^a)z*Vlq>h9(;=6atpd70ROITa?g;)FL*V6OWKR*#bnOmPj}D^ za7T0asZU$f{Gzzrr8p-5Kfa%FbGbtrzu?vQ_YwS}7dMyF{<89?Gtu1|p$W+PpC!?_ z+@(kb;NRU%?itef1+T`xr{EX8n9Mo*uS#drP3g9Dca+yZH2+%+m%9`T1Mu(RCie_! z{DN2G|6ghUq8F1nhd-IlcGA?ZNe~d``R~q5S9h$wD0W-=v;h2Jo&`02!K?AVE%-$* zCY&7pA{M`su#p)59uR^q9>Won5n_xn&Q}8f{zWrKh8z%9nkm%uf{(?@QYqdZjHYyy)vDQ zH)WEm<7Z~N!Yuu_MJ;8vSS_)|=u^1RY_4KV48Skj(YtuefW|L)HU57{{TIEMd>Vgo zx4#j&|CI*dr|midoyISCHU6E&{-PICko!CS=u<#-nGT*hHpNB?2hD$k5vK7AUXA|^ zvA^i0b#Sd~9|QXSZ$Z6t`X@@|4^yxZG>m^wy2%|%wD1+%;kH*6LWagKcs2gN34YN_ z*$Zy`bLN~pXHHyeLB4$nk)e<@s*h#DGk8$mM&m!m&1HtK$W+V6KA9e@I!fagyc&PG z)PK=S!!HWrSD!yi#w$5;;H40Q(|7L-Ahu znFRj`ucGd1FR`xhC>ZNykm9jFCHAYt{=C?)7yDFV-%G#!Ke4~! zWSRtfhJJjK@8r@O?DEiE)7tc+d%w!^bJV%i@LLzEeI?gk@3p_A2LOqJEg28*R|z@T zAI?*rc`o&q>{l7;TYU;ol_E3>CdHcD356-0~@M?*L$GOz#x6zM7 zQRv^zeUH(fV?Schv%iq)JipiAe!PT?wrJb~w70iqQMA?jl)E4AKkYy4c{=!O2UPz( z+#jwVAH49bTX-L1)D7MKMGo5k@O&?M>fC6{K6`};^kd`gdhV)Ds(Y-xuqZUS$91 z^;f&YrqYZs>zAGV{mE$;5${lq1wZe6@d;$dMdK#gKgH+#8)Qen`!P%8TFmxS*Q!oW zI_HC7N7xN^Tzjjub62}e)>`Y2yBGR=XY_;Fgm>g?UD20{>|%ttfcXIiCkVKnQc0>#@mj)`^$5? z_(Zx*I__78sbnax`P_*@_rLC*cQyANRlCoEI@sq8XS2a%1t|`r?@riePtkY|zG4XT z#H}dxeMRam>T&B&R6R!hR@8hh*ne(N*ZlWXI=@xbIY+8Ri z0{dtGo8V7U;hgqISuytIaPO|tABhhdjbGw{AL)L6Vf?|L6D%vL*Kn5x`1!kG#&3Q< z?56e(Y5Zbu6MwJN3zOTme{%cQ**|-Cu|Jp1X@9hPy1fTF#&6H_$$cC5aXfEgT&e`c z>gWW!yK_Q0yxtC9N|9Gc!ag|y*VT6mr+bV?ub@2u_~+q#?&BVmt|%p~jC#nOwPbE5 z!{_?k$A_gK6yGIm8w%)pEaf!oF^bwS*L@%7(@biXEw*>U?n)&iuLQKWz>hW2caUlO zGm4aD(U;N4Eu240_4o=Qh0npUR`l^G>MiQAh_x^-MR;5BgPxBuZ)BF2=a3NRydK_0 z=Q+#&(QTifg);MV2ambgImhW-kJl11&_7P;+&)kL!yB`h*6FTlJc|1am&@!v=I0X8 zN51@Wb5D{c9_G88u_|u<4!c*svg`G-1*7I?dF=Ys&!**TxIRkaGW8MvUBrI}Uvpg4 z@}Jst;jB%cI$h`AJ7w%_CCkp6F0H<+cfJ$&`y`FdUH#VvPITnYNkoSqr?RulsV?gz; zF=ot|ar^9Q@hZk#dH9_&JHm9r<(KU{i{I<+Hksx*DSBj1oVCSomw#F^U9=PH(W%~u zd$DboU_A<5kxVpKG*wJXq^3?yRwOHrJ8nvI#nc(i$z*CqMboj(spRxj%d}}T;*;ak zDk^&Ecl7C!s@PQ6|4bLe)$OFH5&NS%2H|bf$2YKK# z&zS}t_|`rtdXs#?XPz?+I`CD#r1&5Yd`aV+Y0!bMO!NYIIX?F})1U(%>tEh$WIn(= zWDF}|2>06A3J zPQWSogL2L^>;^jyNWFl4l|J}f>5Utpo6Vd5Tw_@W-ivUMzrPTi>7idr;&IRHK6*}} z=dLldCkL$)IKb*HOeZ_-MN!yXu3G8Z1hh)EVrUy@-tHv$jgMM4{ zxjhb3p-^7GdD(68oax2%ev$W}yqWqF_)5QrgjO^9Bh*{eV+cU~w!?kzQXg`zuE+0g zewU7jJHW2Tyf+@!x7<&CDm(L>>35_PEL4x(>s{V0=`H0SoiqK~SM2)4RnrzjeYKbS zyrX~js>e#2;&fj7oijbSTGivBXOwT|x$%-y?Q&IKuKcpsKd1VC@lE>oDy-|Vlo$1Q zu*35`^^1O?9Z4OKb&-<)@Kk=z}NT%ug3pv!7q9-Mda{ry?y2$ z3c!D=S!j>2#xHm^{x1oB(TmBN!@u?RnY%3j|G%4s_6TeIf>+~j68xeUlQoBb>+Li5 z?Ew6rH4E(#*7yal#($pR7rmIQIs991pSkk`@W;(UdxSN9!K?8P2!7Fv$(q9-ZGQ#G z8Hw*q+XL{QhRh218o%Jx_}2)2(Tgb}hrgJwOh;y)x#a=)6K0`3!WzHe)%Y(G{Gu0= zmHBvgh4xG`O-CztMP0kRut+{s|5iAOeXccr!K?BAhu{~zlx5xPz4bmz zTX~;7em3HL_TVd+|7Lri^ug?m*7yal#($~c7rpeK?}L9U@3V(zL->qsto?45&O&wq z^|{vg1+T_`rr;O7^k3tHe=F~^2i)*^9tQXueK0$tHGaXX@wW+n(M#oLeeiGPefEGG zK4Sy^Wlo?z*BZaz)%ed6{Gyjlt9|fq<$d;m8@?0&av#jjXpLX+YW!al{Gyk#0U!KZ zd7nMthVR60??37U>v65|3to-CPwiS#xHm^ z{>ufw=*5fAxx12mytGO59*2YO|6$gRYy5&&iHqFdiSUfdKKF}$vjva% zNYeNv9{7>&=X>Dio#uGQ`IH}zGhX(Y$*rz-CWgEQekO|s#!sj1B{PvW8l!XeB664|puMW;JqF{xl9Je;Nj~F;TZ{|x2R|=(&QLy*G=53f z_zgPH!}r2(A38~&O@XG6&-;uLX-w%M>eG{w4E#$d$oScJ;xCjx(lma-3;alj-VlcG zjX#lXP9#&wxT+6y_;@GiO}|b^MFD)|oJkTGewLnp9~CP29K`%5sU*;8{8Hb6f3QR9 zi?j<<5b!&1|M3XjptS!j`dpCDnMb>a&*cREC1#;L!WzHe)%gEg@QYqdR=v+AK9k%^ z`^@f6M&{>#_|9_9a|V2_HGaXX@qa<^i(X82b>Gukh_=Zf2^)!h26>-Z#?57h?<{A7 zGvITr@e5v!zgh5$UQBiaf3!^oN!Up2GsyeQGH!P8`5N_qJ_iDv#xHm^{x1rC(TgcY zTOOP2ZKZu?fg3)T6ZlUw3+)ls_yw=V-y--$FD9$T@9Y3gq5|QO=>K@1S>T4xSpxq_ z1@cFd#xHm^{__RD=mqrfbLXr}2Z)6C(dXwMUOU14AAD!_QO=nk6ucV$R|LQ4#VMDs zbNJOEoV1#QFeQa?^dV}2#K1=nVai2{;_|EYke~TC7G=9OW@qb6~i(X7Q zCjO?jOeV_bp|ug|&HOohzu@O<#?OxNqy6*qK#8Y5am$g2z&FTg{DN2GzgX~#UQ9Wr{aX|1aE2E_4H450RL<+CL>Pc z7rYw(If7sGVzA}eU(I-gx8;`1`=Bfb1>mm%VF6#`7rYw(C4yh{Vu~>BpYBMeyHd^F zY7V4u-_Nq<3w_L<2o9z<^XKsR0Q|LHOh%l>FL*WnRf1piVzA}eza`xkW%y&wjYx0i z&*9f-{tN9MKF6c|)1vD@r|}D3jlWayi(X7YIs0eRJo0Z@ZBi5tHx|X^midGSe&_wK z-c9Zq()b0h#{Xr(FM2VVbNE~6#-Ht8-4<%vUyGSr6qjbVFYXG!KgUh(8PfO#ug3rX z1i$FTWX|EI^`Dt8n(FOHtW34jBalhy9j0@JGhH<68;#2?>lHd@g6sY5^z*9!a~)rynmX0?3>U3$4FV(8|)Q4;v-4pmw4bu zx}WchKb}ag;+KF)KTZ{26N;*^4B%%fulFB?xmBvhFZKrh!OKKnQZGzddHC&jAMwzq zP20Eq*cKf#ZS5xZ=dyX>uP_Vk5!Uzxug3o^!7q9-S@ZC#2Y}E6KsEjkO>SmyhyO+6 zAK-@13Aq1H_T+L$YW#v%<4*{F(Tkgl)~}lFKjH(xNR0oV_rUM$|Bf{a?Ge`a1+T_` zn&20`n5=pDBMyT`V*K;V0Q^(TLVJWYe!;8pCk4Og#bnLHA8`U;B%c3o4!}RvEVM^h z;}^Ud|K|k1=*48s!yoYhU?j%>mwDjla-#iDGYjnz*7yal#-A1Zq8F1j4?pdZOZ)uL zFfiQumnG52&Ft;)c>(y3^W<_zYW#v%<4*~G(TkhQqyKA4oDt;-pf(!0nY|rO2jHLX z$>omJ_yw=VpAr0`7dMw><)5>Lg#hp0Ig4?5|MNX69FPCmce*I&tPKiYjXy2;MK4ad zeC<4Ete7=`BeDMPzsUZK`zQ4Cdj9!17c{_W`wL!;zgzH&UQ99h_K&s%VkFi-06$~L z&sok%&VbLg#xHn*e`tf?7rmJ5`S{fU(4_MVtMQ*-YPk5-Vt=Ogvi}hw!~j3=YWz0{ ze$k65Dj)y*f6n4pW&Yza!Oy-0eRq%^m zOx7g}>+I#gKt$~8? z%=;70fX}tYFL*WnUkHBDi^-mw_(`T|){j>_M0%L5FN(`uibtjYD<}MR|3|*l#TzKSz7@{|32dP~#VS z1OL#CqA#fzCUXvdma1$jlWop)MtKF$SQMAL6oVf3Kj-uR$K2$eA&p<~YW%+y{Gu0= zIftJ%dF-Tp9wWNNMRB<^`GxdRWTHC}NLYZN-^2b)j{Dys1$dF9@e5v!{~EzBdI3HB9RAKswwpc!$~334+3@Xu z330_}^>;Kb_o)t~GwatMT6{_(d-!d;a`aG(aPP{}k%~x!zaP=4Q_NkFxHE3-X5^6Fd(pA4wX& zq-*@Qx#>U;-v@s@Y@c4gg?&Gl<92EP_tG`vXFsab_yw=VFM5LBOu2se!+ru}zyC6Y zMhxF4_WuL%F@E-)j+#WE)A$81@Pl#4ryls>Z|+*%*&X7vnL3+}<_f!`%$lN9%18a@ z@4Okm`Mozai$JIGOM3_Yq3fi*NWWkT%EM3d|52XZX#PJ6xtYBkt`_@qz}fzB|HJ;D zp3D-d@e5v!|1QBVdNF0>;m^>+YgalM)|!i>k(=4u;g1L4KfsgA9jWmPUXA~5!7qAo zb9v1FCsQ4nboc>aeKc}2dpo>~2Y%=C&w-v??nsSa@M`>nf?xFF=A!S07cHLOIA=+* z(;rs-QMQ1Yv6}fYrHkkzp*Lv#59&R9C;o%XLVJWYe!;8pKPmV{FD5JVIrl$krb&RV zEqa%ctPe(GI zZl{H?CV5`CRx`xrGecOtIR*VW0RP@jVxMb`U+`-DKNS3;7n9vx|090^@|9+~TFZe|-P9DD2_&(U@3<5^t{nt+e@Ryr~_6TeI zf>+~zO7M$bOxD~v!H#pH!XTaxL;}^Ud z|2=|V^kTB-@Nd0yq7M@Myzh~7{vT!C1sCKG{Z8;(;IOetu#6@6S2Wz|YeS zj6cM*LmnKBU+fM1Lq8IINxd)`Y5#+h8kf}6&EcECRyrqoyx5=1=CnWhzg^8jdxSN9 z!K?BAMDUAVOjhP|KL50*vaKe~dmRpX{uvXZ02;sG)%e#6e$k653i$0;_Puew_jg9Q zho8)^`g>#ZqVhS*ktF-`xaTyAgzrp8J#faE*BZaz)%brb_(d;Xd~ARE?y)l!r%gbk zfG1(}{bOe;c2ZNL~_ z5C!N8C3Oej=M##9oW?JBHU5o)U-V+i0e)KdRMefHmOd55=Pbvm0r=G}xK57zYmHy< zYW%kge$k7`3H)m9W7xNzIVtl}nf6q7*Xr07ya=riz&|0Eo$r;#FL*Wn-wS@xiz&d3 zU!H#>m~b~n#(ce zhY4R1F#e15{!{R3{Lct}(TiE0B@LfyoL|?-@Ds_Tnfm^O&k+24h8&Oo*mpX|l&CY> zb*=3$c!3{8L!uXi;XBU%pp~z523WeIJIY;fantFvTLv%sErMAJ5%m0nvKI0g{}2)2 zJi6UTX{@(R7pimVOkTb2d-(zy_H<|4GTqrQ=ggRLI85f-%wv==<5VyHFmb>KJR0A{ z3LkJo*1|cB4ROM@N?zydai0>sXlo$Ab z2l$Y_NpK^q`(?5r`r~+ZH7!zZ&*nvd$;W@c@bNh{IR9}EX@6#sdeZX6SR5Y=m=uM> z1Cq@8Xf#eP!4%q95oZk>2OJ6N3`?96|2dx>?0BVzEnwhb#u0jw83 zUwOqv>OAFr=$iGi;wv8KEB8&RS0Wy*vHkVexWf+lUYE;dV!~dZc?I**`O5I~&R4eR zeC3nJO|*ac()`ZlWlGNHRvH96 zT*0#HYc2Sm?XhL-u@?XGou3`KE^&MOJXy%gj!N2Csw-oCBbc3hqq858pUDCJq)nd(q0Dk2IFN!~E?)KfBDXPjC$Z~mzb^-JfUYIU7z zb%r@13g_$3EC*Sn>K*#j#nHTpL)j8t;z5oeSd&8GYV}~0}(XP z$KwDVgRl?2KDyY^Dl6e9TYe_0-~pe*@wj1-!mWS(v^@^liv+NYwQs6$`8&!ldp>EW zSH7hDNzW>O@M+~kWQqnjYv@Juk7z9T3}rZme*2YHQvPZTx#`81ui^OxxbljdZ{;xj zp_hMnEr-iCDIaw3H+4<5%dxRr`G|)|jISXF<7-cOeP69p{Ft}cq23jSa36o7jCa*{ zrPE0k&0ART)%coO)%bb>&0FkOI??{+3(Q%}od$j0M|xy^nvNx6-a=g~iiWd4XY0|V z-(JG7BkTq{qWrM03RjTs7uuJZFG^gaU3$}kdE+IXkeLqV|3Zpg;6%|tN zR!`gXvnlqxDg4SC)jX<2`x-Yk_q26(k4zCyvv%S2+`HJ)#?4zg@Ojk_a(m(RjmUQf zDVg=m@BH~UTgqd%D@T~y2d7V>A9D=+^*H@JTC#)NQhX0-_|qG=p#SD@?=`CbR@^1l zV5d90@w4u5WW7-|Ayk3PF2j91FpTd2M%fSx!v*F*X`%}Yn%E$d{ z?UU~N7V|XIy^Ft>;C_~GSjlk@*wv8x=H92=_pObq|HHm-_20hS)>qjanTH!cPwS6m z!fk3-b{g(g{@|5w*?NSAb$=&v(BEy`%}XBlN$mW5m0H|i^S;IN?QCiOm+$=UTTIFN zWL2PCDm#_~d>gLTWYpvOB_i~u$(D^$=cHfclBG#tkd(;^!*}BQ@Z6uKMxUJ9rJdHnc?@eY} zH;>_8j!0ioU*+dGAMW40#ve+WdT#>BY{#KB-gX?iLe|5G@0aJ+j^}=Lm~lus&GjrO zU;pdw^X$#>_^Ue{wOFY58o_f`49x3;Fs_1x#E$6bkzEN@8-(op`gqPX0m&!&1jL{V*|SNMwJ zVB3qdE>-Yq{8vjqBzjr#+Z${-1JrQjF6IOXzn4u2DE&5%rWossU2_jIJ`SjwbH>lLn5TqmWs;Q8$(+LwdvK9>49 z_|Ck_oB^L}ZGXY5@!ur)MK311Cw^)Iv^`JCr1c6@{SQm(#cs!aP4MⅈSOrr^7sq zGtRu$_yw=Vf3x5hy_kGC{Jbmil%%~fJACuEzsojdMh)|KS&aK_`mz5_Ljd2a;D&xG zc*IA%#xL=}k90pj4}V*x`3yf|k9f5&Uo;+54Dc_a1jf&PRHyNay@7w|7SWf~3sY_$ zemadRn+gAVX-YjGOBIE~ECH?O75hI-NsOO;r<2DxXH?#`#xHm^{znAA=*48r;ipg1 zf(~IdnJG*kq!q#C7W688m(RG_!RKq#`!MUBHGaXX@joE=MK3JZ>2mm2^5z<;IIV|h zPKV#3x~8Ke)1By!x}CGL2-fcc@YADRpwsvTug3o~!7q9-1?BKN_9ZZh3WP^uUxGX6 zeH7dMNczDqkfmpm#xHm^{yPM}=*48t;oo}u5*#4-zbyF8GCGGtLq8Wh;)7P>mw4bu zx}RSd|NFBq0r2yF1Z;oyqdJXW><#>QZX1$%VanYW_9Yl6_UE#B^?zQEza|dg2VUR@ z-H_-7Vfd!~`IEF%lE%Q9&QP7&;&5ch&eQJ?z%SEcp1g=;{7Wc+=kr~u(QvydJIno? zKA%2p08cT#&PU`TAIt|Je;yYVBOg4-2Xc`Q(t(TTkq}pm&-w6tH0FCS|Fc5gQ(#_5 z$&S_0$&h#F^5O7$JA5fcULgs7`v`rvaJt7l<`q^sNi7#Xm*+G8!*i+p^P9(1Gtp(V z!hC02GS?CQ4WH{h|I__bc?`C3BY6EL&`E%iWbqM(%oR zIy>7|$K>n0A}51BPwoE-Dqsu!*oVXT58*;S>M`mq>M?jwzY*S6{Gj(Lc;9H27w;Z9 zp08s>j-Lm7=)3jeGXG=G}O{n&)cSIp=rTj%(?L2l~e;o!jUB_utI@ zgUjuC_1k%I7w*t^7rpnSpK>4h&4P7&_4D;FRaG>+bb{4#uAO%JyKC;c2+yNJ^J$~_;bJlHMejW91ebtZN{Zdsk@w^$YxQ&wg_90md zo;qpfMa0A5w^HZcb^Njye?Fl2`|jEC+PmMmcg(t9w;eH?`Hy_+z~diZn3y##OY|-0 zR+s+b=DYrK#4l$alz6d<%1|{pch+t1?)6sn^yM$zNoBZm>ArtG{;rBQ*By1=H8oU* zng?$ELDdnTth{TdY46;cx$%z`=Pq1%!s{14JY)F_R`u`O{_^9#`ya3U&W{hRK6OLm z-Dki3-St0s{IPqQUO)J*?~GeobM4qG>@sjUsI0adc;*kc((iJL6J6PQyNcqbf=1Ez zUB%%GI!`!$*$uy3cirr(h`z7-fM0#-#~*#^g-bKLkE!DH6TY=i5C8n_=|>QKt{j~9;c#A<{o|hdpCj&iV6drred$wou)e;! zc--ud_x)tuKmYGK`}&IyUpb4f^L1&;hpCOJ}4{Pqj>&HX}YcKCPmnmwrc|-nr64(DoZeZE1o2BP6g zR@pw^cfCi&__KUR_1+xg&+-F3)@O}=53N+Y4gS@36uZHWD_&OfZm_Q^`snx2+n@>U zBEgQZ8|+wKs@kKgU7FuNo8bVE_>Ok;d*}c~6_E@(!fvo5M8Uo)Jo-H}^s=q_Y)Aec z8qWdd_t1D=K>rGRk28P_^ljPq&?WZQPr2`*A@7fr504iXWD?1kx!Jr?hAj!!%{+B^ zHr16qHPMvpX*;z(l|7?7L*GM>ei6MTS{>yb)xd{E1Bv!TM>28LnTa!3cO2D~YB_51 z2kt5G!(z%&oLf@^p}vRSwai__Mp~Q}qk+QU#Xq*+XY54RJZ>0TuEPD_P`;as_HSRh zFq2HRg+K7v6d+;F%XTsG$@^07GViMYe_s9>znAHk@3G6}JGX|(Q`LI*BbC46PwG4F z{(mSxPmqo%vGQ^qRj?$}i;r zzhC*wgkJMY{{y+GKfd-8dhnxskPH2J>7Ty`Mn8w|fqTn7vkXq^CBx=@{-4UPOy`GEM`xTcU2NriN1d;)GI6X9ckbBB#XWyg)j5( z%$(cDVlwSI!M}Xxx84Ez+?#aC`ZOI&eI^zfS`h(Vkm2dJ#4R2iX z~8PBd4N?qhJX2T3)%4uY8%`x_VVCkX(hDd%outRaE)sn%#x+N0&Cg) zIri4@9f?)xmG)}#cvB+OThK+CgJ!Klapdc3F@1k<07c(S^&P&V`glIEPYmiY>MiOq z$WgylcpUXVNk=`Vu+-y^P+zmB^f#!dO`_OrPrv_*^p%yB!N&jsFMI4~bq( z_S`yZ$9EL(^ZAY!5q{n~po4z!o#m`^27InHe!;8pUnTgBdH^vw{OUW3t+9^$Fu}i^ z3WYrsxO`)!kksjD*L$_#5g!Q}zr+JS(*67({P9E&oqL+<@;mCbhLU3o{nP#Ob;bif z#{oazhk@To>vyg3i@kxrcTn^t^}^)e7QUn4^KBS6?=KGgTu$Jh<0y3R!-D5lqi1%AkY z-VlcG!mkc_QimLYAiy7~^NnD4_?#{5kNb6@qG??agHf8QaHhf-efo!L%t27InHe!;8p-zE4(FD82qe=4;qm7)XA+v#ZIj?k;q z8Y9x1`Exic_&-V4jGuj{o9YbsTx?Zz1ds8~qL7!1IH@Ed<>GM#N z!3ftV`q<)-^ai^f{EXn|0OM!p?Ej~!sDghre!;8pKOy)9SAz%+dkpbZ;x%88m8o+72-U zy_r9U_XxmW>BVHkY5am$NpuZt~GwatMUI{@QYqdR@45iiF7!_i=c*x^k)7Xz9j(v@m@?uoW?JBHU7s0zv#ta z%d zTe}PQ{VZ#~(8m^pqc`*C@D~E`&+=k2;xvB2tMUIx@QYpywmkdOrbtnSKNdazMWQ$J z=kOT;_<3S9$Z7n7SL44$@QYqdIXU}h(>(HTS#44j4mTFX<(Ap#f!}%mo9!m|3~Bs= zSL0tR_(d-!a}IwC-T1TJtHW)drNzuGic7QG7gYiHYux0XA&p<~YW#Nye$k7`oWpM) zZBJ*Nb|hBPnbjTLCZ%`SKG>cPc#p>AmUV~+ex|_vuhvcO8PfO#uf~6;;1|7^%sKqY zG@<4vzVMwt39B!P%Uy~`89zmp(-_d6|B$gDsE)=3`Mp0AJmMos8u>AzOV;%HpE9 za{PSt3))AEaq~CF@Hrl?0v82*jbHF;{7(yh(Tgb}hdb3x3hdq+`6_e`6P6e*fu{#d{VV^#0pxJ(gJ*jbHF;{7(sf z(aYKvZ~Uuh@6=RpT%87Q3NH{o+2)JQ>&oN_M~CUqC^|&%V>~+NL0<@e5v!{~p0F zdTFin#xM2Xeh7+UN~!<$V^9=6C!RwC@E_=>z|v6v_B) z-$@YSTH_ac1Ap)RqA#?A3Eudn^HVQ=LgWXMWvbIuFMtpk(f`l4RsH`J@iBh(o$h1K zfX}tYFL*WnD+IsjW$pgn`02U7sF4pn`WMCLgz>Gn6#geDlJT?ebO$>FKGzz*;MMqt z1i$EIa4&ECYUxY#C%JhkS{>HiwK`T`{6pZYZz}wk5H`lozSAAz4ES7Y{DN2G|GwZC zy=*$L5Pr4vCmzA1BeDMHdcl7LVPpL4J0152K~Ccryc+*~f?xDv%2_sN#j@o~=kOBP zt+oJY9gTl^d$C$B9DGMX_jO$RU26P-SL6Sl;1|8D*yOhV;@T7E)Gc$sk7t@rr}sa8 z`MekL{?9*$+u5l-+Y0Bb@e5v!|2n}hdRg(9AO7y5PQ)p4>r@w*`(*sbOWL{q!;Q7S z*vze;=lI?S1dsTj)%YbI_>m5O=t@8Q^p$IOB6#C)2ok@Zxnf(U1>k3qZu~}O1%evC z*cKm1*(wj$00SXva98^|(w{#}uWe+QdzcQ?6bNaGj08vpfzU-Z)Y zpdWsE^a)z*;*m2w_!PnA7St*DG5$j;>i-^yDBx@Sf>-1Jh2Td$xWW&Ax`Sqb=?sbR zYah8d^NZqg18Efexc?y)`1xHxkkj}Dug3o?!7q9#`?Vi_S^3kM=x&Yh5Gd<^mPF%n zqq$xBziTMk-Tqbm-^)S1X`g@D-{HVV67VA)_>m5O?VDln$CK%7C(VO`%ipgLOXx4c z0)8fO<1fHuBmsY~*c1f5C5ukHrqPTMWd^IVc{qOB2 z_Y7(Lf>-0eLGX)SD(~>aAKK)u{CWPrGt<=_+k%SlOR4{Sev{k&s{Zfe$Z^yDQvbzA z67VA(_>m5O(r^I&cvGgQBN@5}sEtI8Qn-EK=UCu(zW;PndxwC(SL_Y^y^o6hrCwBC z>W9CGj~}QgBk}z6PqBY~|4$$Fk}J3W7XG903to-?M!_$7F{L!t%~@nW{bZX{9TDe# zSyp3lY_4MP_iy~%b27)mcTkLVT>D*W{DN2Ge@O6)UQB+CpUw^}=Amafv4w6dX66z; zOYqx4*Z5x%&?l{dPU9E68vm~azv#sjr15vQuFj^LBSV?jMISOpyJeU~u$nyZJKMkN z1@qWk5gNbX)%b4`{Gt~Z69qK>Gg7N*=oinXqM4K4{198LF(R9*7$- z@&X#a;MMqV7W|?YlTqVO^d!@fPZ6=Kn&Q}8#W*$qf0>KgJD~9kUf}N^bD{mcbFb*d z<#r~of zlUw62?)En#_rKBr{Jax?kkj}Dug1TtvOn}<%5m@G5Pb@;F4MuU4otC;!aV=Q_dR=_ z6TU;j7{|5WrN%FKHU7UT`}d1pS_j?dq0{%D3+kQIe^DyGUtuD~`_KO=K~c_;?iaio z|9G*#=%wrhH~u+uPM$L-uC*ZFK7|L+s6Lho&)`9Mn~eXs%sl>O-|2YIiy)`%FL*Wn z9R%6??m3&mEu<5lY@8kk|KCaNtcTKZ=wXR_J6p^;1SmN1+T_GLGX)S zhAlV#eEUbc1&l=hAD8$4k5V0A{OmhjnBAN-e!;8p|3m7(=w;ICApFs80VC1>&lCKN z*~|WuoXYUI*7yal#=o1`U-Ysf8HAsn0QtMOkWa$&;1_|~yYQ#V`iI8^Kl@H+z7Kb% z;acMtyc+*oVt>)g&^d1W&i0R6AY_K|N8FZ=&nh=OSRf*1HVm8<#Ee$mU| z7ya=Ua|;}a`M)uOAM<~vy+08FKk#b&Z>W9C`b95go4)JX|I79MKTGex(;bl}K;#5b zdJHOpS#Sl7|Bdd@QyZ}VCc&%m%f4;UOW8p`bm3pp@Ttc6b@nEHwEK^z==VJGJh}g` zp`5t>v+s1qzz&F^h@Bw$(A~(L=y8YrIz8AQlp8n_E_<#raDsPniBgKxxpK{~tS;dR8 zZxt;&$;R!!1@kGC2wd)rTTZ1Y9U)lCmv@ZG6f7V0A*d-K;hH(4eDcXzldj7(?_)J z*}Mn{@$ugaT*zwZyjyht$?L1IKkFWHe*hi)p0qsC#upa#{68RqxIg0?5cUm!hT{2t z6yz}H6-2k~q>rKfc*kgLgB$?0qmXMC|A!sVdKsj6?B9<4+;M&d_IbxX z?${UJZ-0F3KR%fz$)BMgpUXSB^ai^;tnW=Py7zNmQF60=|JVM%WtHo*w6hw(j)8BbbkA} zH=M2ZPhLAt?Vk+aCjZwSHdQXag=!@m4T*K+I&Wyj0ur9a!zvL=k(fh1mR|J;;? zLe6$^FG(>SON5&E8m{aDWyhgXWk>i(FV-JiuIxDUvv79oKe2c_E+JrO-_KHkfwNHA zJycYPe5Pm((CwK|k?6ff z_1{d$;lWOKc;jc?;mR}I;ej@Hc+-vU@W!+|TzS0;bK4!`C?LO+X1s8$r9+H`D$aDK zGsC4jlvr!8+tq&lVSY|W823rs7jd6tIqY!%G|yeZ{SxP)C~Eb0A@wP|u7>;d63T4R zxCiXL@G08read~GoK*WC_I(omz~9yVapT+G_sQYc)cvvSCFKvUeap5RFr$Bk9Q3an zck(!ATkd1HpXK{bR8g2;rEdDM5)-}7u{=%N2> zs(-a3NASistyV_;4*0L_!09fyAURnEYb=$oh=Dlfn-x78=$xW2^ z@L;!_@~j!+BVB^#&b~6<5x@Ukd2b>U#*PQo7q5EHVzxOxKJy54# zfI8S;mZ5o@V6uV~57T>Jw%M^{2>6O2%o|TdiT()n7WH^wqUw)OzZG>uon<||L0$9T zQ|qkRsvduzLbpo7<6KF|U8y`>kDroo_*j|U}RlOAEV<1hvKrM#%e{X400gKlk&I&TVLM?KzZ-*28x^_bs1w2>j;tMaLp z3tr|&`QdB)f>-0;TkI!#S@GK&T<@=P_+{;){Rua1%99TF`i8dd>I_ef(z^Ym;OAJz zpL1&EGS}50r|}D3jsGKpU-Z(y#1FsY{GOo99O*U9-RV`S7|3_>GPzu4Qv-;Z{1>`gBFyUuTE zr?>YJGp0rBXV{zFN91#o|K6wlquo0mo1JW~YsSBXVsL-jl`0L_8}mLjpI$Jy7$XLd z59A^rh(Z2a)FF^C&WFd>7>8h7g6C(9S5&?i)X}Qn4Jdm>E-ip~AkXI#Q#eE#{3OVsmjnKjd=iVUZ^7L}o`F)!%TjUD+@#}Ue?%;a7me7FyaZ2a*x&Qq)bN}FSUU3)h(03Qj!_iN*bZ+yD)wyxjwR=+mXIg9D1KYsO{y%#@rLdkC)xtr(p zZXo{uBc4*L{x(YP`w_`X5Pz0tbaeP@3yiBuB)znymK9uVcodrU%qqt ztGmy#>K?A4GSuwU`osypJLS0Qsh{5IwrhVVwY%T!d9~)rF<01S;Brt|#r0jKE)ZwWH%gqQA$mo( z?ibhInR)ry6XveFiA>j5z5fY^{D7%4yN~%f`xKsa-h!kZ$6&K6A(A zH{E}H#oJR!f5?+lJ}k})^OnRxZ>9{da9{OJCze-RH@>#+&KDnEx3YW8T|YS}cQ*Im zJ~>#$c7=^uGS9m^-P@ZvWXP6zPbVF>-{+`ZV?O>#N;E_{$@O)P#>m5p)jagzf?2r} za9N&uUenC_0=)2b!WLcR%En@NR->$p-ziyELoMs%p$8wNqfgGNx1(}@#*7&=Zl7H( zegl&$PpP~;B1|V-e%ZdW_|55V6*MZL!DoG{CDGH?os;k(yK2dF(a9D^r+T|SWWWV( zMKaM`(Nr-lk(xR+S&^(f?zkz<6;o$4CzGie6-~!Br;^iCEz_pWh)<4BtElLu-_fUc zuKYmhirUfw{mUV<+mGYkWv57()3^;TH~~M^-ukND?N+2w!<}7SVW~E2Ibzp?-YTC`<#7?)0Ui;n=hhhcpaWm4@IfBavRgjR%?CR04Lq;%gFMB>e;=lvIhP;k zz&G@g;)6Vhv_$E;#>dgePU&FDg{(v5OHOtNRXMWIwzhC$v7v(nf1%A+j zzu^-qf5-*DZ~j6L{<0}j|D_x#zhC~K2YEXn zbc~c=WH4;s-tQNB^VCf&NL_o5>G)@FN{^ zQEspNd7Wp!^mAChvZ=(~-$C!dfqH;?f&9`m_FYcnV%`hxA?i8CQur0?XQkXfdOhoJ z{7Sps-@+f5AnOzU;=O(a`S|&4PkTO3;^jy zNWDNkQD~kcy>HwAWScktxyD-m@p};t@^Nm%cRchb4VNI}THEP+q@zS+m6M z{a!j~^Qx8huCMW?M5w2uMVcd48;-*)fn_bG_a$66Zl=x)em+&<7}R6bThwE4p?<6I zk~*vJRb7uuEDB3K-k-{F7w=zA9V$&4D$-|aq1 zOo!4BepDG6zu?vQ$BO+#FQ(iaesyS7mJV-gi?DZZV?=s0e-38_|0n61@w4xA(u|x@ zdDj}h;MMrY34Wh?VB$}-H>K&&&UmJ|xvhs!vCPZK9Z{p`V~a!5ySY{9GlHK(jGrAp zWl>YMok#PRl$@vW3to+XKfy10$#JMF6Ms`%CKKiLSZzdlGk*@(1>l$N)QeTeY5am$ z<9|W!!=e|>AQvY7WU8~fHJ)jSx1>{HHm|E^`dFqVHa8r-nLmd=;ensyVSo4>=jSwj z!K?8`=Fj0h0`PlG5`Z7y`+4yqPU9E68vp)+U-SZc_$GeZ2O*g`GrTS7+`>ro$k*wA zD*%6_eLDrO#(#j|7ri+1(HT zS#44j4mTFX<(Ap#f!}%m+u2R-8Pe@v@M`?>+}baCF`0AtTj<80?OxrMGD!-C=N84~ z7FiX5Uwt&{<}pJWzu*Oa(DjR65Qd+_PaBA2x@Zrdj>Jkji>{*^6oq{{we?jgz*>Fd0@Q?)@xwA1$y?m{>~?#*A?tQlYp&b z&!;P&aaK${=QW7G@l`b*TCtb9pE6$*r~3nugZ`j=*W%XH=56F$}Xs@@Ca+>orpfmmX3v1@tn@bn>dA>Cg-{%k0d%7Vh7<{vwL1D(fgot35 zUCF3kb{(njhS5IIUT{A|J5uF6o!ZNF_vFe>;n}C#?d5rj{HrAJcYj{)FNM?X^=Xdw zLhI1~YF#~sfBDi1-M^Tc#{*vNMcu!6U!I&cb65HKY%ekB_h2{J5#@({Rrv36|N3(M zlqt8|Ic3UMsxQCnvOE8G{@2(BfsUVB*r`#Lx-Rx_Av>bq^BRX>jK}#puZu0mw!+7D zY(0XWOJscdXDV2j`iXbnD`sBn`p%rY*rW@bm$WHjQOio$w12N*kLtv%hUd?!W`4eA z{|ghpFl+6F$5o%#XSsfM6ZI0!f<9#K!r4oYKlMvrJYm1S@)?)yQ##|^cP7r@xwEqu z9WnhQ^|wq>OIrvPJC+mZ)OcnC%Q_$ex&^? zHVxB$w)qk}{L@2!J^k-TJUIRFT~gBz|Lo=VHS;np`%K$BE;D`Sy`HnfOkX$u2Aj5~ z_dM+v8FxYu>|7a?EZDmVI|BMsU%VxfK?L9O1{GVN_UT>IR_08MoRW;tVplZ^*IaQPPnO}A9 z^RufS`BA<7JK&RZs-C%{rfQ#yW>;PDTwT?@zpSk~^4!@~6COOi>g@X)swTWNv#R{8 z+NyWIR9AKR$EvH=9ejM%KiAe&y;4$D^{H6bXHa0>tCvR<@;Z( zn*7A7s@?aGSDm?WUKQ!Is`30is&@I!?p4=M*t_b9TlcNH{`GyTetF8lRj;f#sH*nA zCRIJN$Kh3fz51xCKVErs)!zT8tXlS`sZ~v%`M0XSU9oS~Bi|lhb<^R0n)%aj+%mJV zvTbJbxYsH_WYu^SZjl-oZU3X~zsRaH%Ju=!z-ap)ZT}yDYCH;|NDYj(|IzkeWYrmE z8`Z$521YfoooYbs6Tov_JQe7kcMJ!q?+Nu%2=j?g9&+KV(ch>JM(e<69T=?xqjg}k z4vf};(K;|%2S)3_XdM`>1EY0dv<`f*>j2LsjQ&P-Fj@yb%ymG`9Y&l_G}f}p;zZi` zk{yS!51ra^MMY0XrGV=KFhkzzJy*t2R_h29>THG z9N#30M7ziS*$qdz_isnLFzX%X%lx1Rf7w*U54os!W_<@g=)vDF`9m)F&3Xua(1U+S z_#qehn)MOI8}bgMZ5CD4|?#IVgGq42kH;xnD{{t{(j+yT=4mpU+BSKR-wud zxws#g?Hu|8J@^}>{-PYvzaKy7H9ztfANL2dzd-&CLI?hS2}3UGzaKy7!9P@^?%$A$ za{KXv9{dfpiXU=OezV`wz6<1!9O%x@k1{9 zKhy)W{(&C+4b_5Q$^m}A{6P=?e&L5);79*#<_~(!FXJ!B1t08~$1n8YM>^!9{E&lm zwjY02k8vKpt6#CR`}_mc|1#q~i*^lpB{T@E9k2FjSx9$6KL4P$WQOng2d!Uhx5t_A z%lDD}Y5w7{-w-k>;4>cHzX)>hJ=?}|ukY&3^AEmPr$poX>;f54QjH9{?Y%Q_?g4x~ z|Dg808EZ|T{flZ#CfdJzxqjcXL7!7em#k0Iu|$3%@f!b|wA)h{c7)wv#}!g9U|)r4 zxW=-6yCH{wZGi{{}zYEj?Vr6VJCC{|3jq_ART##Z`;xFoiOb~ zby&$krTjA}Dd=a%10DUFmmR&O<;&mRV%Uz{$)KMe-TzNnkoCg%PuwqY{~Rh+_fOnc zG5*Fl&hL2y{ry4obp15__5G~y4uAp2FcsQqf9)-$wM$U%E8 z_mbE5Rcf#7aKGGw`=>RXWc`2kz6G$ZqFQ_B(e_X(ARvVD3K!H|Md*V>rEPlClm<{a7eoTcQ^0^g3n)ekDikq1Oka43zu-mukzN$&y?_KPqSpsS zk^XDVtZzT&%sywIBrPYWd)l3u*?X-uv(}o&+H+>sCVwVwjCIT5nLjs@99f=bDE0Xh zdV?OpKlH2ene`<5nhkj7IIPFRHgf(=y56IUmp^Z#iv#SQU3AvX-zE8Ar1f}91^oYw zqj5J?_HA_qAvtGj<9y%WFE$V@Gcd(c4BQ`2r*Rkk{3T*irn#K#T11o+zGxpVYoQMx zEMK%VqQBgHe9UonXZdNDx1&y&0eFn#7`HKwcUS0f9OFCQAIQYZc)C&EcO~AmT#w(g&K=q~4m#-nc6!w*uCF(aAJ`Pk>s;91Wnw?6_n>tL z5H5}5h_l{<*pF*R`FM3@Qw;0>49W6jS@LBD{RYH;qx23FyLj`MkD)i{5jBQ>Res$V z(c3eP`gua~)s6d-?5agiD}ijpu!HT-^*GKX%E&6AnDodkny>7TPmkyqCZ?U52{rQa ztj7sdZS?aOC>^Dx(y*aIrNkJgFfL)7>im!%r!anDod$L%)@?V*I<$~;=hf3lp$F2W zQ9)O#On*turo-BVwl@)Xuh8RD)#9OzQ=o(PZKwBjY1hMGZ)PqbS~N}}wvJPSU$3bo zIkG&>Q1bSsv;*i7{6oJguk6ilZp1TfZ%$G9W2sZ5=wjOv<9wLCiRT_2PU&ZkL? zO>2AeM?_Ws;uVCpwQ+`ky~+K8`-B?Vsg%_x3QU#b{S(kSG+!;t4j zD$BNRpsAIbwW;^V@b4$k8}!(Hj@BdeYuC*Cch}a&qt|9vnkz~x;JpEQgC47-e?z~; z#&wt;xj*v7?+v!~AKep6_qzem8}tahLBA@md_hyH{=%lQ%m1hGo)7=HY1KzpH*Eaf zav5KNWsfng;`_>eDE-}l3ltrC|KmsW{`XSF_bd4FL+W%cJz}1+>CsLtoBl|%;3yi|Ar|id$@T`M;@lYa1(C&$>|W3z2x%`C@-8vDlOTLPFA*4?zdx=&a_! z(F-YN*l*ip6TOhq{oVrf20d1FXgxx|N=BK5#(M?UL!-TCU_Dg5XUw^tXwiBR;;i)| z-rrMA>)L!}hg^E(a>Cv-G_~M+Mkx&T=#S7F^tfq;=rPbQ=cF9x=8c|IDW6%b@>kPM ztXFR)IdZsNM-IL%bByHAvI{OrkL!K=Lg*Yrt#fu6UxMh1a_N!5czmpvcP zbM+|WH1w-QcvPb^=k~`vaUQDknX5P6MK`gY_bkm19PZSSt4HMVTplA*dK^nSE2A|R z{=IrMQT%nqU33A&i^KHDeG&6ixE_P=8J1?^6*NLp=#QI3Z_p#E5B(xvEOD3~xqi^2 zZT$weN3rmcuO3y^oys1{2giEk?`Q!2Swi6UdB79*bN>j0FYQ`UAGkr8t43$m(i%El zI_&z)$$gw^dh3^Ulkb13ulM#d6rJfS7ACJbX?oqEhd->I-+AU|9=rRHmgL8#zEYf^!@cy zZ}`Pas=kwNyK=+5i~rj2pG#63w)|t|y76UKq`GeW-}NW{us*e4<*ItFgT54Zh08;u zIfp#crsTo=9J63ifS>zceL28S|LTf*@FVEX!K)WF5Dk*a&K17;(Dzll^K%{bo?mZ% z{OIXS^7D1aBx@hp-1p|sZ|JMo@8#Wz0~9V=Xs{(2M9@fFx*c4p}OIzCr_>`_sxMkKiUIu5!;~(z3bJDG0U7v zCy}^T5lN?5H%~qJvj@ig_8oA;}$Aih30k*q74 zw|Dk1zpb6Vuzo~KXZy}6i3!bf=S?_g!j!o!M;+BXp}F?xqbJXsaMZE$nwwjWop8>i zc`ePyw9KC}<=EL1XHS_hp_8s7zPNNjNy&=((#h`Sai;o@F)lcg=V#mpPo9cP_c!f} z)1x7&J?LdAIl<9=7Bu*orlaF}MN?z&eFZ16%IinIzdY{oK5DElVZ8|;Sck&CJFGil zoyk1c#CUA~Jw!2oXKzn>A)qs_YACXe#oZtLtg^2VZ~Bb9hh8?g^&!`u7CNw}XIbfe zwo&tmb%`OYQ()g6VplKNN3Hj54R)R443eeoyM?xO3eD5V{tG=qZ_p#SLOW4;cmLfI z(WmG!^HgB}-7Uch5u{Xm<&6C~_nS8 z11vV)3BZ*--Xgc7`yzPL8BfwElY z@L}%&tj9~~;=OdXZ>ei)+82SHa*&Iz(Yie&4n8fO9P4p_s)Kq){WkpRGfq2w+Ke+# zoHldz>1WPfGWWcN3+8q#Y+Ew>oVo2$xI5Lws7^)0$fkPQd)u}hNVo4N;}UT;RPH-y z$7r``$G{4XOQ+NLGumypWzOl1WzvrQz8GGUc4zux&?kr-Cs#Z6{pL>X_-Sgxe4#d8 z9M+D%Mr|15yR9Ajsrl0$}R`r>Ll@~S);FsIBZF`y?9!VGCFxasB zF8{)>%m2QjKaq=x@A1!!FPnW%`|@S2CQy!isz7)fsUGUb%=ZVWA9MVU0px#o?D~-K zBQZc-{^dUS$Mdk*%Kz*(df{zbvMdbAcmK4=kUk_M3I6#u^N&DXIdX9M7kz{Ou6K3& z59G&JS%FZ{avzbgETTucIX{^!qKw5V~f-JY@ z7u#ko4}TQQ)EaBvfN7N;h$dD@&=cG;n(H= zb>Uy+ViNNBU#8aiW;dU|q@!(Vn+X?|Zz>GjN@jwEe_myR-lMGBx%>;iF8_ZJ{zWck z1+w^GcK+hUEgkJqbkDSA76xt>ukuwE{`mp;58IjGC+6}m{JQ*$-PR>?@#Anhi~s0T zpCUCJ^PiK4|Abj-OWx&Q_yzv}?Gm{lkNE7z+u|~3m8Hro7hXTZdKuQw@OuH))v#`c^}De3P^|aNB%|ahx_Gb6o6d!*KDKwV zs!Ht}!i{HZ`?dQN9b2lL^A_`?)?I`S-dC;kvV4&ZVg1bYK?a{>`nOlEEc+DDzB~uN ze)gcq(`3HX*Uz9g=n?!^iGFpS*Bw5-5zicl^|)aJ=U<_V{gH8)qy9P$);%$9Adlw) zCXv?TEo5YPz9HUp<`UJpK|qzWwQ+vn?-y%GmuB!&^QTR?k(THF$i5-azh5E-qKvy0 zBaKm`zWw6M+1U=h$fzmqu8K2!k?lb@Q7-#LVL4aH^|aK7^^u_m$k$SuVfZ&Z4&84Y zt$aLuL}vqknVvuF$UOH|e|fya)1T*h6`l`b1am=pEbv^<2Uk90>413{^DgFLJjeWu z-@(k^)A0Ki;5lAE#tX04^E}LZi(4xnRwIvXjM_R$pPfY9eWsp&H_aK^JPbM*zh`AE z^y+VH()GsgSXUW&{WR<^^T|Q|j_>Q1lv5Ub*F!igdWX) zKk~Hb^U)%DgC48S(0YV^HE*pc$2s9~k59_iAENU7y{Y5m!B^F2l6`jaSmU`zN2S#7 zkr&e>CTH&Gcbwy#OUwB(ASr7bs{qC2@c4GK1y57svy)t3O*xkyy9Q((L}HXtY%%vo z^?Rh$(|nH)tFO0?p?}BFzvhHNXW!=^aH6dDXJdMIUU_%hHf}oykWvtPPot$U9--Z$ z9nboLv}0-CnwqlR*Lsw_{9SZ2-`PARw9@0n)F!?0 zXcgJSd}RlF3A#OVo6fDr1f8P#fJ-#jc;o^Vc>?_rdV?NOZRi*IVu{1_$n`^iwA%+O z-PxwK(n}W$UuHdKeY~(Uz<__22yy$godI6E_(Sz(IbmmjH?8?Xa^RB6zBi`7t(|}5=`DJmNj~w{o0A_~b4%a#GvDSq^zHw| z#N-#=8I^o>!dXeGL-NiGZd{W-YmfRhSA4aP>d?3Hin>WPci%ht$7lR^J=LN9$W;d? z-#w$Z?y0^5*8FVxM?X^?U|+ zVntWOZ8!XW{XS28uwj488Q`JHgZWwWz~upc#%BId=jUh6`A&eJ2kyPu<%eXpQ-!GK zeQj{ueugHjO!9_LG$rSB?X&h{XCKmcM&pb=Zd0JyKJ&XYWvF(26y3}4{h^)##{2v8 zOp6KT2_B5eYcZYy9w$F_rBke%9A|*{h;jya!o+fQ2DqtZ{@mq@I`T-WbRX~RXMpF? zRtDPG)wW`ZItLw}0d||Z8WYShP~~sA`Q{{FIRDGB9xv@@fKy}`Z;vy;IJbp!S~$1W zd5S)_h4Wl4OOl{-Tdi}O`P9~g36sr-1?0W)(?hz#ONOR8f2Yqm&3aYGX*uW7m6mfO zyX*5>U9WE6Z)l?)I4?9X5bfL+;DFcpmc|1;Fn+x84Q;>yuS)Ph4|tCAJ9;D2>sHki z0}gnda^4N}7?#8FV}f{q177d%bv;2(V>!-0jPqrH177VL!k?7u;RVYB9PnoSLF0j* zhgTcm4{*Rszpn8>4|vCq3E}|`c!@VP9_RtjaULPl!uy6c;DEPD^Zu=T^}fUJ zdDV0iaKP&o{y-0Sd$UDO|R zO!)yG_-X0?po?(@dNA<;5Bx67=TZ;gqaB&}fCoOFgD&uG_2+$D{bD!Z_v6G~!E@gz z*X&2=mniRD`hDhjTHEIJ%wuS#;&YG%MHU_JtzxrUml*;8GofZq%6D zBk$t^9jq&MFSOCStWndI-;Xn^g84j!){7CRem};ym=UWr0R3+4?c-`F8&A?0Z=q|G z4TC|R2azmUo@UV0^lHDIvWYP=^3Wsn=IT+}1@x=A37&&=_#9+?>hY+Y;v8hcB447x z?=4y9Aa|)a(AmWTpG%KbwBefjh3#8Sni|eQ+9(IP>3Tzcca%8zw0Lr?NAvQra!rF*Jnst@HE^>dZlIyRC4pZ>*Gdd=-r~H_3SO7>%hM%yW>3%JW?9ICu{7 zu(Dk$_|o+Jf5Y1Ge$<9BzT4WdpPE1Ir|nO7{ZqH&?#I_y&q2=m?&sCMGQ@t|9hr99 zvD6psxa%!l|FF8yKKPT>G01ssOZfEH>=kY8i<-lrx6l3G(hniLzHu0lN9->NzN`KB z%(TnD@ayvb7a4~{E+*czX=hEFHrtiLvgPgb3)<8_vrq)H0+jy|or7S$xz33FV05-U zZ*ch+eqH|mD*T7E1B3tb+7>Ne+>*C658$jq5j<2kb(`?dH<*6}8AhDFa3e?T@-O_l z{Qph(7rB@uT+N@iuw}*4w)T$M(a(S}t+NEJdI$%?F3rQgUU4vM9?ZM^3%@S^Zwvn- zmmrqoxctvszO18d@$9ATZA%N;57Vg7s!u1hmiCT?ErsBsE{pT<&o)WE;PNm0y8Ley z{zWb(9o_y ze6eNT4&5}s_CLQnvi*5BzZQH<=kvVK{T<;)VmxvAm;2x!&%OMjvvwg4d^ru3JcgezA+E~QQCpazwqnw zzee~Mxdco0_y2`UmUYZsGLN@T6cA1v6jrc+FX!Q(ezM3LT>gb$m;ZIbzsSWT$NAQO{jgza=A)k;VjZ4+%K1!*EHu~d|Mbb^{-tBtqPC7@v$LS0 z-5~RITduOAQOOO({4qoLJ^Dogk5XooxifdkJNoG;hyMw0?yFBeKQGu1fc*iRWPbqm z4PajY_BT|?J{5Dn4Svr)mW-}f>0&=G4Q2PK`q+MR>fS~Bc|km@UH^_>b+PUD{QRQp!{-Ix;KdsSmPTqiLj?&{^ z8#&KDUf!dNe*?OWE)EY!=fJ#BFZt{BW8*LH@yH}^AtS=`^U_fE4QkcjFd#W=YvX+1 z-!Fbnx-^5Inm=vAjkG-XNA~lA{{0d$AmYx+ibX^@;fw8Im+V*D(SBY~F8sW(?a$Y> zQXkgG9ABROyzuiHx>z&t^TN4`(VnKXpA#>yp`+)yT;7L1$wa)-?_oaG%=~<`mGrd9r<{8kz_*8Y$ z;O4DD${q@A*!aXWS)MFQzRaL^pq1`7;Gs9@anq-?9-&_?kMGkw!@>1OW90SIu)i!{ z4thV~uL-xG{QFCswV#l`tu~(a67rQD^67C^h#oaHtxZt2s5`sBBEN(F2)#j%-JjEX zgno;SjW9iOTj7hxx0MzJX$_XH{|D#|dc-&l{f-npqMo_+$o^mOw0lSOT#GVhO|&h$Rq9AeKNZfmi~u1Y!y7j1tIRcib7J z5c3>MAeKNZfmi~u1Y!xq5{M-bOCXj&EP+@8u>@iX#1e=l5KADIKvW47w*OH33ifEr zzQ;Z5)h*7+9S?+3y#JEV&ET92&dm($tNl0QJPppr;Jgg{LBp>zi0)5?{GA*k;M@#- z5XaeEsdvuW_P!4Md&9j82nTWNa(!N=<{LvhHv>A@7hJQ#LT}w^O}gGVZ*i-U2Uqs^ zrAmEYowwNBO}KR40N_IE>X&|}X9 zT944L=H(vR*L}}MkFTRB|5sn$dtytik(;mEI*9mh_I;<3&a*w}yivwiHnlK4a-TrI zhG3${ zvNFE1>4xc%`y*dF>v;?44SIy+pkK$SZXk~l)c>Z?byMRPul(5K4_$gy(?hE++W5KC zS2jLJW9DYM_-ynQB6p0VI4_O7ey-0)Q}3D1*OoJSr;dGYuX^osvx19P6t67XT znz;9+)K+r`{%TiC`>AcsEoZj36ykt6H`&mqu*+bF!7jshxnQs1yCR+9F9Y8lS*M z=S3f|%dRr=A%)0ooHNpP*;`_lNo=*t27eAV%x{M69Bl4dkBq0#BlHG6wyxBAL_5*k zsIhyk$C;PkI&_~rdOoN2?0r9*?O<&Sdu8gBt&RI(xL?@(W@u``^OJtOk(!1cp*L5L z(!Zf!%^&x_D?I-v4(GqF^5>D+6;Ct*1WKtd`q^qpFf-Z3x*;2?l%EJxfb+2C?NR=jRAbNmNkR80CWZFwqt3x zXvd&~_O0`mQQJH5aXeFPF!Sn0&a*!1A355=k- z|GaE`+0TWZA3oQ3#O3gKbSbrEGx(|b(}84TQ=M=e(0i3=aD8UZJ+Gy@VOe!*QOgoC2&<@iX>|7FPYd?3{ zQu;{JvLnvnL2Bn>KIS%-z%WT5!?pkdXx39A;Uwsr))n;6arPh^!5`Re;NR1*PJ?wD zz+gQG>oZudf!|a7t_FBsYvy%ItlLn*w0;`CZZqqQ3)Oe<5D$Dyzn9nCVOeKEAvt2$ z*PsLYdfQZ$tQ9 zbk6m9{S9%}`rA12LpS)}MZ?zLY`=>}d7sdH7w=#6N9YZDtoga?tGZ}fXwtuwBiuWaC4{gL}5 zk8e@e-%3f3(3`7A8K9 zrN^-(R8Nl&I=`;Ci!Ok8ahM+Q`*v+Geh8rMTB5P`kdI!K?0D=`$(#Nwkt7<)sb@XCX7$zM>r>{%!n)TVdAOcv)N>g-Q~2sb-&b<>^Bnb_UvGZ==xNry!x!sTT`zy>+7Da zKgsPJZC>B4l&3lh8>a$5l;QrnnNacG^E}<-{+lm&FsiOT@al%Ao;wlqGA+nyW|}*UVX~tD|N)v)LU-e zudb5#`rt%*+o3VAsb&7$<%>F;mLtBnbb&!^XUNh=1zVPN9MRI*?(CHOPiUSyZ^Ahf zrp#?Q>Zs-k&9z4#J$c@QqmG@|+}v{PgmWg%YiT~FW&V^Y$IhNOd&-0fophC4L!rKO zvU}+^&wWSrA0EH_LGt=J_a|H$K9dagTaB8gkA&AJCpfy#IzE~xhvRy>IOd>YPRoV+ z>Y@8*=BbWTO$BzI@_@2)v>i|WbWhd!bhnOO1WC-Cab`}z#I63#sfVdr^W>F00+FZ?Aro8;5p7u)XanO00+ETzt`n~9`I6Q zf_Q)fUgzr~Zz&ge&gi{~|1y_9zyYsH@IcSQ`$>f#4{*Ti5j@cI@b(Sh0S zt6*Nh?<(ncgYyIUHrs*Op2}#_NRc_u`}p^v5v7ve9a3fGG$z@~+z-$A%N@pt4v2kS;X&)VoMB72_$*5mJJ4CZw%>~8}zML~ZThW9%6(|2JcR(6KA zEqLD&y<^aNe2Tsa!&i0)dmn>5|4Hu?EKf6NYCKbvR)8L%H|TLd+6DBhxgKb6od37c zlK|(Bd)&+CP8}eRUn3b?0^5o88ND7a`zQ}|2Fm%$hR&tO1F3Itzj)Vzr>X5izkQDM z69GY)K#$NH^av>ESLHL;Qy;p-)1%63J#Hg_gf#NMi2TM#9_#V=y(O0(edm;DAK{0~ z2Fm$DZM-;4j|ch2H=7>q)I7Q)HN|@5K?dXWi^PbCKPO8x{Ex7(o5TN1-tv8i74s$L z&)The{=~eBc@y(E>^Re&!gyarWBp@vRnV0x`;MxQtxe7vr@zCBxaPlP{`{3~zRRx) z^jFY9e;u&VGrz;?3}OC^^c~j0&!2aRJWUCd`uqvKL66`c`c?VN`bK&~-+*V1(&Mfh zIdA(8E9@TZ-$wolkAN@5HV}P>mE`Yzhc#7pCADhXdWNlyGckX^xRYp^!A{MD8hLr{ zkNh20^zWC51#@h&ab*#a4XpU@Eo-TsIdA!*rGsBe3-CC{*`4LbpGBp^dMC`lLzXkY z2VvaCIF5BPjPH1V#Csgxr|^CSdK~|r>3YrSbfKbLo-G37e0ZB9Cx>J^IuBGDcDwdW7Df z$ALRVkAZ&q`9{ZC>YI-#U%%jS=J!{0{Z<&iHDr+gP44IFeb)CLMElEr>)cksmmvD0 zFg>ykF}~U6W39o`-IoNtL5~=xptY&op}R9cvxuS(5$T6z^LP z_+0T8>MI<0AJkAoE27o2iH%zP zozsAb;!G@oSOT#GVhO|&h$Rq9AeKNZfmi~u1Y!xq5{M-bOCXj&EP+@8IVHfWjKOus zoZ#`pSOT#GVhO|&h$Rq9AeKNZfmi~u1Y!xq5{M-bOCXj&EP+@8u>^K<2}D~@?52I@ znRT9j9PFQzeUE$AD=Bi$wi6QPW^hgh=VlZV{lR$}oR7hI8JvTJUje|sNqc3tjq=XT zuwUlAD)in}+uqlKuV}x_h+ALO`{{db8r(S-?9&Gw>$tD z!p_Yw#Zo>u1HD0yHJhcM2l{3Bd5fz_Ix9uon`J-#?UIN8fE{t(g7tV9wU?dsyan_I zJr4Yv^hfEJS|#etFrBYJ@bY)jtq0{c{4U=qdFT;XAu*lZaO$tn{yZG|E*hPG;?qjO zGiSgJ>yJD~VV<&`n<@G8Pog*I5%VqdtL0bQ=s3OWAxp=pru;gUf15r4f&2U|2&Db- zO3Cc&zv-ow9xtZ8h0OZu0$4_4VFMM1Es-h?U>jdiGndEfBPZQ1q1V;}tQ;62Jgx^CroPUJq9!9hd*Z7$q zef!Xc=dQkX-9w*vpq}v`ocD=j=DFS0wtw%8wN!_-yZ>rk@`*K<*WEVdVXi~n`4_Eu z?1F<7zQRI&lRa{$W!C)uG{qBfe6%_^b~kFTAeev6U-!op|27sD zf9Ej8&kJ2AZ#eM#4>sJl=Ee1Uzq@kX^CzE}TK&xZ>km5OHw}%It5hAh9!!(NVC8Yh zGi^#95B=0cZEw8zqb#$#IdncA;5{BCD0^_ z;#L2M2@{Ss9~O}J#!nCF>s~T6m3Tw^QHwv=M5FkL-R~&n$F#NbbIOm;rY%ALsWyV@ z47#l%Hek8O^F=kKQ4jc8?lJvN3%uh5{WAm3#oMC!0X?8yWcb(a5jfy&6+h#k2Rz3) zkY+Q_pEuxuw@K)L9`G(26T|}?@Vdk=H|POx1^L(J0J#7Tc(vjO9rQfBV0nN8UaR1N zo`-h^S=(NDfCFAa$QK|H_# zuV3&$4|pAhKX1SRuj^IaUO>;o3(6C4z^nS5#sfXzInFoKY8?0j9PoOjJkSGPM|ltr zaKNjDpK~b}c#gAPB~c#WfCo6xL%yTj!()Hr==boqoT$^|0N~Ny%>KdUDtv)=@lzTf zbkXk2_U_^fJn*~3&p+w`e6t+_AMh?d%9j}JFs%G8qx^n+XFy_<3p$Vs$_G5kPm8~8 z&_(?rM-w0Lz)z&L{6H6YX1_rBfCqlpJ2H+-Jy8EJe82<0U+_T}e4G6XA&mp zK^N^N3?J~o?@#FY2Xs;IFnquRKfQ~_2VKkuWRBMQV-M{ zdF4{ODjN+&>Qp!E}>tYr~a4u%SJqN9Lm>!@Nv#>qYM7>E2STx|KWF17%`GR_R z&IeRf&uKxH{+YaOBgf&ZEcIl$@cfDS67y&G>w5mgyjp9#f8#x*Rqlf{+Sd#k2o50O z(fTm8(x0pP*xF?0MC~sh@xWCwe?DxR?@&s3jQ$Eb=&wCCdRhMRhcJIe@|QpO`IA0a zqvUCFUh4BF^aeeGf9O}|A8ZWz%V#}K+{n*t{_-)-!e2h}KLqhWtk-9Q{_+!L_fxCB zKLDpQwl>aB{QaWbGN{<8Sqd0ox41vDzkKxXm#F^c*kogghK!#`uo+NArEkd@p0+v%SuC!aBOf&^u8_`Msgzc)z^wA#S}}kKZ+y4s9F<9rS-Y zz3LQIkpkX>4r~hMbuR2L-bQ}GT+TX*`7(ok1LD6?dWVT!ym`#W z&>QrK8biM-uYB8cYIB2r4m}>;crMAVgDwuMb(HlNdbB^+<2aKjBddgB+V{&Xny>7T zPmkyqCZ?U52{rQatj7sdZS?OKC>^Dx(y*ZdraY#@_9n(9j8mIN>)+`xeqo&kb|>si zbNv+a>T*)(=`?9*dsBPlx9PC^W7^(CT+^e+r`AV@Hco*K+P9rv7uh8oFis7@-ppJ= zwCH;fh_m*!bNe2=y?G4DlI3ZJQnxpuH|P=kL%%xD_U2U^@l3tvJ1LdNdp_Hi>jePz zrD<>CxkrandYrm~I+yo-rbO8W(&dIApvu|WI6v_Bi=(Z2v{ADZFv4!Z-bDZ2>Fmv6 z*4G@`X-y&2-o&_#aXh_?9>+1h!>+{dCioo)>+z^AkKgCf+B?syyl$`yb(ZqVgqk*N zZM^kUpHTZc5ZC-bkKa8H3~?M6I_UoceHMC|=cxa4ka4^|Q;@w`CX=DIH-AC6{9PZ3 zt>buk<#>`tA@(NZ8Mbbqsg;_wsrP}X?+uIITs{6!>k;il>#unJ+S+*Z+U-hnMQH`R zHw=j0phxs?YriZ45rpZH`y*dGzS-7)bWaR^pQ#Ag8FCe%N9YZD1Yzh`<<%HSsrn0> z4m#nb#>4*fV?C}?9`LzhjH_>2?47aC9eTXuT%hRC`yZ1b`?$RF4;6f6Q_ZDE%u_Z! z+NovJA8B`3kKNRMG2gyU3`BYVgUxH_cbrqH9+pm;<9@dMn z9*TT!hOr(R-4DXx*R{jmGxREX@I52Sypfx;_x~yM2)#j%Jzdhz1O0MO+81)!Mz7YK zzwmL+NAZJjogmum8hT{z3vos}*E@fx;7bsFQNI4j!?O&&h1KXI)A9nXRh9O7v0F`2jNbU4g4fX7Ln4UK6f)l{2)B&{JP>U zx&Y$EVS3~~k9jIwkHPnhQqm*z20cPz&@b}E5{K!L>jyouyc{<&&(8z?Swi6UX*(-_-PqmgO?tz9e*VH&u367(@`awC&wS_HhUfqF>2;e=bQ&0+ z&zoP<&>T2#{-Ire8#r%X*YsZ2`T3(}T-`u*XxRUw->jQhRg?T-=K+u1v1b2CH-7He zzWN_NF!jU>exc6$cQk%u!=3w-r<_^U8}9qZ%5`hMdtK_!_c$9K{pLZb7b;efob>Ms zkXL+u9+KEGvF%)Z)O%WYL#b!>`FUadrI~E z{I!bdbc%KJ)RRw6#oCfj78Mm0qoSOjcW{2*hr3fIic`ePyw9KC}<=EL1XHS_hp_8s7zPNNjNi~%sJU_4Auh=%1 zi|5hoz~dgTH(`AV>rH^fIu!QZVciMqOy;>J#$)?$1I5=nQ&vn?jClEUww> zv&z150@MCt0#Q&0t%nFkwbw-qoY%4SEDG(67q7`|sw6K1Gk2-vsvGJ)~M8D0nfq zR}S{)+Wuq^|Ngrlmvxl?*h0_N#uah;gMQIz)uW9XFh_38dh8@Qp?|+ctXRaB#UT4r ztEj`?mbDVRDJ!59p#?vmF8-@Gkz}W&DzQpxjV=fd_u#pBf)@QGc^NqkO=-_}zjp zbRoY`e1QjkTJoR^ys-KM9{Byhml)%n*{@K4zym*Vv&c{IAwRQ!0Uz+dPv0s03qHyX z!v{R@`=xx)#dvP^Q15B#*?gD&vG>JNAqU-$=I^nb{~EI%#q!0#9SK^OR8`~x2NiCabf(1Xm67@y4Y z0T29s;U9E?hjwV<10MKYV!wbc@WF?P4|w3?Iq0JOL63OO`cwN##7@F{{=grD{zia@ z{)_&MaRKzOPoMV%9!fK__BXP71y2sPcc5AA+TRG`)(!gozUPUdz2}1t-VXi1cUZ5i)^(b)L_UjeQ)?w7-$5 zDt{^sAZIHJlRQ95KfpO8)8EKnEbAyllh--3{EhsT{Eht80w1PF|M<3xwLjXZc^r+@ z6wedOE~6Z3zVJ&yLp-;DS*4Pg_meKoV5eq6 zjl4YfNA@>@{{0fMAk$z@W-KDg3174icd)+^jN2H;xBf-H2Vs22`zO{T!rseRo)gKg zSVYR=ah&&`Oe&v4cgn2qLA597{q=|kF4E(7%`-zA$3X}EzxCf`YzkU+=jNvOg>JK3%%(ls?A$ zO81e;s#m|$cj=QK;qfxFEqz?_;5oO}O*`(uwfvlJO}e|bC3)N5U*`Slna=h9x9`1O z*Y1}Y_euh?4I^Xfs3CXe7zuh-ATJa_q0?O@tMr_K5I(I(L7)e5uN>ik&JQ@2`*d*YkJjaCwbi zjeq7CD0#ge8TI>g)wCU|uk+p;r{6ZU3cw=Gu*6d_N%%;6n%bYKwfe4U*!|C)TjjW!3fX0dKA4ukLcglepv)Ohv|{~BE~nH9(7L) zu2U2NJ43Dl^a#B{k09JC`gNQ=);rF{zWykA>5q4ha-1K~#f~r0-@Z?I4t$RT@_5eo zHgCJ=#BJLyx=8yQOQ%lao75%uaLQ?G*AGV7`XU2_>9L=l<rtuLOy5Bfjoe$VvmB(6lfc^~fgMN{|1KG0N+0KGp1v?ApL12Gje7} zem^notntn<4qw^9*2eu%tVg}p;lImc9rsAKv(Phx&qrzw{SkVD9?`#{-(ur0Opma$ za_g~l?JVdGdW7Df-%vZt;olJ)X9>*>E9inv#rIgI9B>bLeOLd@ZD*|*9oB2Y^a$Fy z^~g~417HaS*jbowV>@eT%7vX3Xn!+ChuT@Nt6*oLbl6`wzk+>J*bj?!Ex=EvX371; zzkjN!a*k@Owl<%*T<@Pk-1@4XM{7@7HYht3<2vYIJgE7D#m+*diy*eiCVI6>cmEXh z20ae^x7b6&p#7Xjkd2iZAo~8PCi(^fU)do{kLVX+`=>Ou;JRd>?`9V@ zBJQ9+LT}Jx&&yhm(646Z^C`c7(s#GbPW^N3L67sZDEp^i_g-M18hLHse~yIqPt`gX zmh+`c_y5hMN7m&|yMIdb20db&hJLjSi+}$V?B(2g4BE@3)E}WY=n-un{Sx_NiF5Tw zzrA7B7q*9azgY9L-YabX6yTpFhPZv&{F5Gj_rdihzr*dHl=hjd=kU1x`Fma)Rp^w5G~W+OtVx2xQHzvgSh3@jgiZo zN+*%nL($2xe~OPv#{NkQl6Jg*D&9YZy;B@}jYsuoUtT?tJU?R}!6#3}g}E-+Z-p9l z-0iV{3jXTgpAP=&W_?HdtAigqk0+h-`>U%p9~O|e@p^Rx{8<&+?^dE*$LYUmKQmpM z^g30~82R30wT^RwOO*Bqd{aNb2R!gQ|D^Fj7y5xb&GG>c{9eHaUErDeLivDq@!!?u zgD&cC%F)Fac;Ii9Jm|XR8~Ou2;DO)yo-V&v=s>Sw^#?rg2lkny{8fT3@WbQ}c;NR} z-L3Qoy5JjhO!)&I_!xgc7y1ipKY#~5=z}ig4>{sF%a8YCV4TD61XW{$;~nr#K1_L( z(IA)_qxWO%Nj-%9O{L1-E9X98d)MD|f%Z3rxb{1G-0i$|XulJH4%R_xJ8bk;HEKCv zpX(h)9#XQ$4KmiN_2tZ^gxgQwOP84DWIYe-{gRc=IPxoW^GYE}MNY6~f8&cc9k z3*#>6pubw_W%-*L!u;tR)2P44fOvT4&)Y?w2D>sFm+t%ty+M!QANtk#2TArd8}Q6= zSdU{ja^B`|3gayHGa}Ew(Fm7WUhk!7?gC0BY(t3n` zH3xH2j&t)ykDEEEvift>dl0W_uapOy<^AJ!$zyLQ_DglyCjtE)L~Ati9;Eh5U0zY^ zTyBBS)gQSW9^Y*9v8Kk~bM`_h=@EK^9=Ben^$7iHu9fYx){}sjzl&}@C=c+x<~t=1 zJ$iW7l+xoB0X=fR3HBXehUt;}BIYTZ9yPVn-7f{bxq6iO7W&ol`+B3}%-aZAIu7TX zRsQX5o@6Px&4ck$Oq;{YIx_#7{gKuss>)tbmkAoaF2TQ@@fFq|wH_0+^6>$eXesr_ zt)e&R5llkA$QMg&Zz;NV=#OkSW(Be#v+fn~jZLEp`z|-&pCz8SecJZDZM%EVdXweh z-uE_~-{rpGo^u2H-qs%Za$w)v_fi#E``++f?wPdj?IGItHtE6x9^16n&whAZ*W|uy z_PlRu**~99``+HB?{e?6Z+Yr!`Y!kJwC^p|b6slwYG*^b`=Hdh!?^Da^5E}`|L_yb z1N@xzxh(;HDz8a|@?+|))blofU{UYk_oKnfD0|ktmBB5&UQ#^=ZYsZ$NS!RzZ))3`>OxAeMs(0 zUcE~d&AvD6bHl#3-pzX78}`F_Jn58g-`hmH9{>}>p10ZX*VsV=ce`c3Tkk=#|Lr&W z{WbAx9dDA~uLcea?gI%Bk<3u`y`di1Z#A%I_`WyhmDf?KDFz(yI``6ephqAonBQpy z9PoMs5A=X%ey0_1z}qBvpa(qjJFS2N-YoeZDd+*u{7x(2fY&8>py%Ov-`%XHn}7pe z&%s(Qpy%NQzqblF;H3}Hc%TP7^E<781K!qZjR$(bGr!XcINz|-IYi@u9`MZXv;q!z-NGN}0nhwSE8u`vC3*lo5AQD3h0(472R!so z&;y?NomRjB4{)G|y!oBhg!Fst8|!*O_kX~nUzqKV>&yEV0T2BC%`%P%U9>y1y#pWc z!0-BRjSsqLf1%|IJn$1zf6ztwpaZ^8KHyz^lrJ&rZMJ6@-zdLd_6>tBVTJdN<^Kvx&0s@3dB3tM|jB(jdw?22mUscs# zRyApcjk}O%m|vq(|4u9P20cP<(67$N-)V(hiY?~;$opo|zh9yXs)d$36)hP%Vh8V= z#kh@eJUu~=;~3xZ9%{Z1n(t+-9{+dKc;D=#9N%f}JxK4Hb>kjAe%GEcv~j#w=%D|1 z-ZMCQd79g>Jq{bkqZLrX`({ON&|~kJT944Ll281d)@aS-eSm^p1--d?yhH0T*e~Pn zw7w52id3YlN6{Pfh;bVF)x?V5&mhlHn5TBe@3ca1&?6c_ujm)~Vu^FjkI-W&e5bYh zpLZ$06Zz!M{jrCPUBF|%W&EAi_&crn+DA7I}E)}63_!Q4l| zytAKa{vIWNS2W*uS`+)|?}s7oJXhXBn+LZ(g!dxQfj!;3)Iu-*POH~ci!22_LT}Jx z=ULJ|q@Cz$2fiOh$7tj4v=)mxp-1S=)uZ%p=(kwvi+Y5;-{N}+JihVoA!e|h?=@jY zV&2uG=nZ-VFVJu3_rv1vv_e$xYs`9_L+uvx?a7q3G~=u~#@}hp5{bHD^(~O&JFT#* zU}xbx2<$KHkA%Gi`wIIW{k7n+i1#-}`c7+=e5Y07+Kcr(T6?d>F7g)=lE!!dIv5XX zXIbdQ-)Rkz;`@Kw)uZSQdffUMX&=%~bWH^-+wLYb6jeFqv#EKME|z- z%Oa?FK0AxYH@#*RtZb>;e(n@H7!PW{IXHSbiW=5OHrYfkpmg_7L2uAw??SCd=vT=o{!VN3rm}+}(I25V zSC3!UdW3#;wc_uz?qKyqF3#1X=nZXYIh3#S9FV_5~=Q<*NpPu_8@1FuZ_D|XT)y3awjla`ctnEF!UTP13aeFBD zK+2?H%V+zm+uq-4#d}Yw?w_L1JyOWAe=7b?D;j9zINm=M@1NS<`==c0xZCqPt?*9= ze|4=ZwZA&}u`@e^&tKgn-b*mp5LgcrBG*PB)+>I#Hti#R!o+V&Km7cBSnvO;I(2zo z`)w%x>QE2(*-GrI>yypG-s*R1wiB!AA>e@5f1vmu6TX0N`l|yR@HUAbD9{6*>8}oO zz#9-hf1n3E(_bCnfLFDjt|#aL&-7OZIN}b@Vms%80exMht(hOz)wG~*8xEn_>iMnKH!0$fWI=Shg*N?XC^-2fu9zCVW5lt zWR6qdAMn8M5`Sf&3%Qy73;2Kse!t*@F3JzX2R!h*M1P=*{)u_Q#TWU3F8DXc0n|Ss z@W4;Ms@pHL8b5i@86tVT^G)_E)Dhg!vQmCFajWvz|XOue$T5@!kx(8v4fk8P#81 zcenOehq&`HJV`1pPxXF&>QrKYC*p`AN#9=T#7Ab zJ@WZ1^zYbT-Ow~N$Jw0;s6WoA6J~%K#&L|>7{_~4dK}02j`vW!2Zp_uFlK5e2RUu;cxd)>>F&3L-k`_cA80*7ze+E$zq;++ zJO@o5^D*=WJ#L+&^$7jy0%Cu4gBJ95MuZ-rH|P=LH1w;hQT+QYcXoeu&>QrK<^%mA zUo3I1`O$B0nDy1Za?QKNo3DDgu>F>R$9~J$UtR34u6SE_{+ikR&_%sB68+WTy{A<7 zTgLwC^0)ayA>#d(@qWwgz29VtHlDpotP_H*(9m?G|A^T>qkHOqW!F{I?e|59Q zYd3*|lLJEgxm8JD3)Xa)KW^`jE|tAnWC*O>d` z9Qqv(^X z5Iala+BGtdPPf=a{z5|17}r4ur#td zghFz}7}r4u<3aB&gQJ(Ds9}8+Hm*l2q;&UBL2s@eSBRY@?L^5Z_E#6JnY<5B=#Rak zH|Vi5BmF$kFJpgo?}LgW6$w2;Z_s0}jMLDsCRY6Wr?4)$h$hIL(O(_(20fw?K)=Wr zOB^;on)ZfS-;w68uKS(B_D=yG`=?@mb>FP}kE)vF*vH%;l z4{)7^U#>)jCr|c|hIR`7LW%zhu7g58raoD&%DKD4GzbSu|4|w2rNxuhO;DyN#@Gidi*8*MC zA9PIqy96Hi{Zc;YqW_xx3iSuPi!by*7jh4iU%yd)*R#6)fG*k}>XB7{fp^OXzR(3e z>S5yd8~ABykEjRwMHv5pcgu&LQK1X`Q2q`7gs30r0v~+fIm@5@b75Yd0b|ZFFoS#)YoUIO_w=iD)yu%J=!_YDX-uwn{F;W9w^@--N%Bbsj+`9{U(}C zd1T&k^(cCS9>ERttMZxa8y)Axjd>bZ^(y9K9?RZ)_Qcb z9zR@GUcr}JqMHcQ<3Yah&89~?HJ9v&O|Tw$kij^;)A{FGT;{B@XpiN>^C#v@%%8oV z*YhXlRm_{1zr*Y~jQ5kMP5zdy3c6BdtJU~!Ym-&&+CLZK+6(nO*ZU3Id}m?6xaIa& zp@aTvrI+QOYY6kFb4;U}Ki!z;&f%LsH;OzBc4am$-T4!GgC4;@+KI|%)|2dOHsG1I zgFd*C^Ka7i9$hqEI=9iq0d~(WI_u``{`9pTZz1`!9psQ5G@7J-ow|g8FS509e(diT z8;FV-m|`gg?vH#P1^qkr&owkHvwtoUXQ+QJjN2H;u}+5Z9q*5Lj|+RR;#!WOcFOx) zc^n^2c0;0~KlDAQs``BO{RqUJH|p_w>!U*($3X}Ef9r#Tqc=3EN5>B9|IsLv?*209 z4SMWctMv%|D*4p6HfcHGeKuv}b4!uiD+m2Pdn)1b`>e!S@3RiQ&n7Cyt4rhg|K`#o zmlHN0Gez@#R?K=o`4N|fT?M^CkG&5`KM(ZF&o?^GJ-+#v@|g=Gzt8?gr1Pfe(-4+= zpY^>5(K`Qcoj+9YWk6CkOpmNXjBmF2SX)$;PNlM3HQiFuBlHG6Vw{G4HOF&Oj&sFE zPpXv9oU8PBB;Bl)2lrXz&X4H8vkD>4EqbhVzF)zYAo`*(Ju(QF!}F9)kDA&jT9@!b zDd`bmOw0lSOT#GVhO|&h$Rq9AeKNZfmi~u1Y!xq5*VBW3R_RqXYIHoy-`&5J?>er z3g?{MQF;8~{g-_H5$9xZZU)bBo(6sga9#%IAmLX4@Vijq+eUfkX4o(D+vR%is%`IU z`ef~w8F6Q?-cR4UP@ks(-KepD&zBtaCH$2jcDW@#@le{=c?1&d<>=!p_Yw z#Zo>u1HD0ywd=JWp=|F^2HM88&`2o*Q_sW5A%Mp=4U-! zm|teVKT8a;efQBv|A)_&1%l02^HrlWbpDAi9d>=@zG}kKKJpOY&n=Ur}de1l>90nYQ)p?_oOOrwQi)f}>}dDMag9 z!tWs*&ObtQ4ZQ~H%Ys)MQ%*WuvRiyEj74WHd*aovKaDw6xo`|G10 z*}Z&X`+hg{rGL6x-RgG^Q~XT)x8)o5{^h2IeOHd!aOAry*G)U7J$2#R&#v!yp(6Ev zDp#pGa6OnNhoQ=2sQl^y&?e#71d=hxfdB$nGR^AG>A;W(2nzu)*n*f`~f;WXQ~ zn=8q0o4o%#PxlN`CW^{?FkTzgfYlA;tF^9Nzx)X-IZLtz;3BpH6@1gH8>5yvl};iN z`(-XzjCm1azs#{;=Hm0qti}?aH|4UAEoYxb=jLgk*!u6sD}O2XsgWXYlXuQO?d-Pp zMa}sE^FZ(z^#K}p{o#6l#z=R4Y1B^^1P3+)LTB6Oojw(pHxGF-s19JUok431DpXVK z!Fgc1(4POeXEm2!^S`V9(^e0jM>hGMpGRqp=~1$!PCavG>)hs+_UcpHnp-;BTUu;D zx$hZL^nkzNC9_hA^MdlMea%t)>Dq8*&Ky)_vI>$Lt#4?#4ZNe{t?RWsd)Mih!J^13 zjQ)cN*(JFmS<$I&T=LEhBpIDCzxt3O3OiLQ|sSnsPy z*N{&;^lr#0G5LEFXZiF#b9wvxx$_3myG2Ap#fPLToF>wInUj8CiR$m%(`UBLJGZ4n zw@APZJ|=-|$AEF8&?2BWv}foIbfC{fGN`w++7>NeJb1M^L&Zn^DxCTetvB#dXpC_d z<0{5k%p(|o6DJwt>;iL~P0gKm?t=EVLF$HPIyL&Zmt<@DCg<80?DbDSMo z3AI-~zed}i+jpGx+hyP>O3eM0*BVgI3uS(UP0lgf*%*(ZPv{qAK<{1CgZiCGHu91M z9j$;XG#)CxSDqe^yN|oLhxOsjqth3)&F%2O3QYB0wqx{LV6|Lu=oj_u6#X&)zY8nC z!#Ylceld=j`USy6I;h{Fj<-X_N4?li+O~W7h_#czN1-w6Z8PZ<^DE|C(7`;6JmPED zoAd3NEuGVroVT#OZOP)6C6POX52czYbS!T#%=p@?zD)cpZ?n(0zt{6?zr?*UC3`eG?gK_Kjob7?JdCe0St--lJT-nw_2YV0nJ^XUB z;wtYw_v(~|%Ql8w3SQeB?md1M-`6sV)JoHZ*=yQeDFML*1F?IlZ@-W1Ulp zoPT&+U_Z%NKU*&2g87~Y`wr_Wu-~yhhJFirzz0240_DJt1YOKKc)#=0t0!dq&cb^M zHGiO}<5A8i=OgqlU%+omsTq#*bb{u`&wNYSaT|p1nsaqNj81AsLvyp!dc=eY6T?9A z-B+wt0IC`Z$GO2v7LroqT-PnnDL(YRxI)mQ!FuDrA0F*fjVI1;cK=yDo@)N|eXkv7 z=Xpr#Vt%Otm_{Ic6E>Z0pfJn}=mOqt<6V%u}bHI8Em#1e=l zkXr&}&Nv209!h`sTc%-QEIs%XUGwM9Pd@eJlWMIPW4AYl06UY^Urk0{#~XSdpz%F4 z;C+DsxQxL5S-xq*AzcNl&PWhJQSQe`AH_JRm0`!{BF;EW$n>F*)WykBPdS)t+>x`>3Z*|znCA* zIJ|BlK z{Uv+$yq5O43kq9J_3$YbYR}#n0E?VaeD>U^?b$utmKqs95+K{N+z*1muP>*F>{)-k z3QNcGD@}`*5yzks?k0kyc+p}7Bke`1}MB0Nu3id4I7iP~sch^$U zO?~p34a-CAS=g_zXKOpOJqtS*Bg|J1Y!y7+!9bT;SRB9d3_eXVk|P} zc~oqMNb9o-mhC*x9<)#mxdmI6V+z*wS=g}A>{)ZIRuhIj3;V!k&$_mV#g5ffve#$X zjy*!`*><*P-;V8BEi3+O&XdS{5JO;|aCeL;t3iEF`7+RnLX7J?ph279Y1E#AX_K|8w2uVtZE0AzOa_`$%WY zPl-JK6H6eLKrDes5*Ye^18=NCf%f%Tz2Cs}Km;5Iwk+Q$x%~#P4{Y|VD}lhA$#;32 z*Ri=io3-DdESeuSO|R7dVtzE^Y`$U7rbT{X_H5Ms2C!dY&!)eu?OE8lW(`s^8W+ty zfBUS@cAJGo%WHdfNo>#R{^#{UEk3j<&LIsL^Ip7vHd{u1nVIQq`SG1N#1e=l5KADM z1On@`bfU!`hGV}0+q0ns=(Sncv{CF?1v^sKXM4mxu-UW2u|C`Xk9d97Yq{n;iM$7a z6zo~ZFU+2ey59iyE9}|MZf(!P&PBP1wLM!+?n4$XUFHnxP?%~yZX2owWyiVMOBRw+ z{VH);Y|nbO7>keF5Mncpy#KjwbMgADmP5Au{P&U0mY))N{3n(`EP+@8kt7hXXG1ZD z%bwjcv;>Fe3z;***Jrn!QHyh83U)Z`*;Ok}RkUCe;5^uH?l*vaV6$i4---isCJTzk zc^#YUv*vz-^r(1!R?AAu%do}KkIZO_8a4VKR5$Ql>5 zEom9b0&S>0dy83Ew7hC_16OW;dp3KYP*7LJb3UI1hxUUy;+{Wm-iy~~gZ(gDKKY+B zP8?zh#1e=l5Jdv&3p+#dZ!mfCWU;$YUatKH_`WP)-Plhf%KEHA91eSy2wC^fVyxBY zzubB%9}o1bApZui4{Y|VN7+AT@?9@)+Oy_d)8=s7IrSmMNIZ=d&}HqLosMW?b&akkiufs54)Cae|t8&T0vdK_H4F&%tpV#}bGo5KADR1bpkWqqWs!!^pipo57l?poZJC`umi&5*(gKVbeyj zXBF)Bv}cENeHQkCY0vT+l_zx`-#KK*rak-0+#mE!x@2kc`9EK@cI=ODdn^&}H_)PU z<;OBKFCT~`U3*sK7iP~AxafxcbsZY&-vIV2?Ag|9v^@(u*Q`NmM$_E(b6b`;6OJ|? zMa`=Y?5=fIduX?M$wE?!&&1-`p7q)fi_hOD%{20WG*0|C zmOw0lSOWPaFe>&x%R<`j>$9*AOnX)tBd(fweCLoIoA#`^KHC-hpVgvs7kf{%h zlCWnXzc70?>iR6~SJ<;%cW8SSc5bkA-fz&#ZVEW73-=1}C zaJOE5ofVV+S*{@359)|}{=9iF-fsZAK3jf}n?KH$AK!^XEP+@8u>_(?!1Hh5R63!@ zweqabiXDa$!`ElC=P=+nei~8MXBFZ|S)YY{V6$h3WB+XbKjZUYZcCE2vEW?F^JaE{ zJq!7T*|Sm4gTa1IbK9HEhtcw(>$A5nKTndCwAxH88F!c2SiH}AYhYnqv) zjvd2Ru-mg-18vU+S0$xpej5I?JO-|tRf%D;XB92fYB;{9(EX$9R`d7E*eAL4$^G+!1|mFMV#hFxF?b{GkWL z9t2X*C*&7ZpXj&SOP@Vg#QKDe2Gc(wzkK?{_aw32f%T8>&t32+kB?Xv@#>;e?)t~+ zZ3~xlm`@|+)v)1?9n~JrN-tSRO4%&^*T(A~;q3+EK>j#h|Hv<++;T3Y>Bg|J1Y!y7 z0k5kr(N~fUYm+_{iAAiaQy@J0qj=r!gdJKdR%9Ac@7B1`PM)B zmPdTIQA1)YT3aUKLxcwdJ6^1WX%Jg>V#-`h){U0;j!2^|eapO9Zv zefCSg-ER84Jl5xs^eOVor%$YZV7&wDAN}X)^$)Czcy-Y!cl~2#+x)>Tf9PdX*XF49 zN?7G33rQ(kW#B9E`bT*Gx7i~0d-3{*T`tjOTS(K5VPgrz64=QlKvQA7{=sbkzljXX z{*On4>mRTWV7J2l2)@_y*v}z5&bR)N-Wu;`*0O{AZ1boGffUw1Aitrme{_r9hhzQ2 zf4Bf`Q`cM8KML6YQFD#9PkZjvapDI1`Ul|9PKSH_qvx{t{R(X_+@|v&kiz;0vJgjg#7a96YC#X@4)&;?_$0FfprnD zE;{9{e{{6Bo!eqQj*?eX3G5H2+C#a+OBRw+HcR@O@%l%2|F_v9_IvUAhg~kwWm`zo zjbUR6#1h!aB|uYQy#B#$0PmQ?vHr2i*#80h0Cp?vkKtPX=-(Eve|Y^kY!3Axkiz;0 zJvkZ!dlJo*wHHIvR{VA-|~lM8Dl$`m8xA*5^?43HjyIC)Pi( z-huUxs=f632i8Try69AD#`J}Y7MXVo%ByL_olB}c+&jHwAt|-~k+>sX|H$tDEXFWf zgzslRkJmr^^2(M^P@cBuN~rOlSOT#GVhKc$0Dl1_Bj3-{y9{hdrvDFP9Fnmdn0Egk z8+so|@_TH1niMY2EEvzMYck`zXArM@EhD|WI??Hn~Fvfcb>;u@Xs56&| zw3aF3`{zcT&%6I4UjJZ0N$}61{xqI@G1foQBEP||f54uF{R(?_(?znMS$@~^O4ccD z&sI0kNA%1`QS++VqU}1>9@<@AvXGSOd+Be-_N?xQ{`OONI<{vEmswEmg*4q5HkLpv zft_3eWKOYP{QUmxY6ynEjr`P;Pfi`0Kf5vtSyK1gu>Q0Qn2n-sW7~ZfDI{?S-NywG z*aXAzd)}!HvS$o)JSpI9O?s+q-)QL{03{!G9C732fgF>Jnk#HD6Ug> z!1vV{4t~1Pp2zsWanElnTMfprnDE;^;xKaOl_X<5o2T^-C@iXgh@b6hdb=|yl@}o4$q@_ zM~w1)Dh12Gb7ha~VZ3_x51}M3N``)Kb?@&#QO9dOG!Cop7w~v2`9@0TxO7=~4}pCE zyA^e2>0{kRkM)elV|_5T{hoKk>}`**U;p;G+a5{(Bi_%fWd^y0&6ge&r&vGi&kph% z?D_}nS=g_zXS-%-dlq(Xuyp?3>hwi(J33mH9NE~mq=P ze~Il`-4C<-Vz7Urok6(B>v(&<4`2*I$zFYRoqx0Y&+73^zdh*tCY(R7*M1o*$j9*H z^U<|E=X-I8B@jy>mOvB<`0UxkwAEz88m|3m{@*B!a(EsUJI*ONdlvS=_OfTY$~x5V zG=@xf(rnmVoGlL6vyk6V?OE8buxD!y(Dp3sT(btL87H*QJ*QwB)=wtXp1s=-6+Nx` zVAaIfp7m@v7M^Jf;vU)>1dP0nV|&&w4^w9TXPmY@*LUN;u>@iX#1hCa0rlpd{1gLb z!l859vlxqjAAa6q6hN}$VzXzl9xLm!UWEsYd@^*S=hNK7xDjR?>yk7Dzfk2ASj|>!i-8ghyioNL=QnlMa7H>2_h&6 zil7*0%$Rr0SuriEm=nesGv=(A#q64MhX46i-P>LBW`-o}fA_b|$Le$Hy!+}^-KzIq z^{wi$>keBE+gB0Vf!cBqaOS7Bjm~HP;TM@X4D*T!E0pK6<@v1NH?s>Fh|?;oq2n_* zc+1vh50pLdzwCh|KHF^0$7dVALhe6oK3l2!#FXqeV2tX^Mi)wv!!p2t+F%U5VY zK5c8=<7uwIMP5j8cF4Jv^uSb8xvolOAyYXE8A`>iy~dn_hqVZ!bLd z;jxe&tH)S~$4IhQD#k+E?J#`QpuyS0Gm>vK7V^&-IlI11n71v_xf}~AJ%6*~WybU6 zSjdd~s$qZEAE0HW?18ce${uLM1Dbi2Vil-Hx}aa1E06b>ER#ObRM7Q z$h-sU;`Cx6J^m=iLZZ*yZw$X?@wC2QPGcQB zRDT7&K-Kv^?X9Yh6V{IN(@qOV{H1Hdu@JZOaXPzWAuWC?kJD1`G&Dy2-Y;3fJQm{q zYbX{{eR;lc(S>(68Vm8hpVhvd)>x&Eqqi-`LhwWUH*hv!s( zPV7_ePw&mT&)KwZOBT*N7UKS!UVnNl#A6>G3u)0Z#zH(s;^jMb-Jxf{!v>C+`Q6Q4 zfK7RP-ji!rI&fWy&I}9hv8?eD71-MHg;k6H}iKjZIE@Hf>;e^;$k@mcxZ zp3e__-s*2TykDG))Olxez0y0hp;$=zch$!HQvQxv>LH(FWU*x7%wr+$zgdli_As zO7~)Y?#JA&H15jt*^)2f@JjPpUf+N5obqSc17#1CJurO_G|SD8ky zS)U&?G@mV%%=4Xp^)Wl2ZT;HOHS6F1(5B$(!ZGEwz3954|FZ8&_i17#TAa^LXKin} z6NXsdR2Evkc2&Lq_mR(Meg5k6*%lYa`K-@#>t3C|6TD5o5km%!XxDZ4(0#H8XDr|7 ze0Kbdou9P|?VPkloX?i`S~WC|W?U=#Z^nJ)&)d3~9iHWU*#l({ls(X>2Q(e5F7(pj z^6&Pdk7mbSwI%MayI0NU2Mx_Ly%tl-@!8S{Z|ogfvT)|}S@++p z#%C#q-|cz7H?~*p%>}m9e6hOl)sZ#fJJht|chgwQ2-TmNy=qIejPuh;i$t7o^hM7N zDh<3auMfZNGCLoqGrL!9di$9=?NQ$U;$yGwye%EGB@1VaukhP0^WXILzhF;)dVkNU z{v5Ycxj(&+W~D#fe>2*je&5ci{v5Msxj+9(f4cvs*PkB$@OX#EKSpmE;~yRuDb*#i zV*I1q;QbCBI5c~BM)HluKW>=0`+NEvpLt&P-^}~0?sK>P04*zJ z50pJn_CO;Z2=R~ebg&%%h#s09@sCNj*NuPp{J`g}{?(Joi1YXyrw+UW>f-d`9}~;# zdC_G>zcut8O-zh>{KNhCSK}Yv?;ii~EBbHqJnvZQdsj+0jsFKjFj{dY{%+CeE93lh z!Ucv0H5~tNJ0GXBJN_|dm-6?kQV%yYM*ZF|S;0L1;r^T6_bZQocz@5S{v2G6XC)mq z^Zn`mo8kVn`*x1?XYca;S?bVP=uh+C^!n4|A0F@U_{T4QxBVZs52RF=$cTR&JS3~m zR6fK%ihuL0UFqB#OLS&fn5#@UHNH=#70;iULbJB~zO4Sgw10BB|D50FdA+Ey^MXDF%K-P1J(bw-{&o&t2Oeyj`yg2?=NDVN@t$m z!Iro{Mz3>DW0|}TcygOCF;K?$GpE1LbB?cOWk0je4}9M0b)H@Ek1^%H+w9#aOyBD% zPfUz@{KNe>tMLz?&-(n;=d+#ejPqHa=Voi5`Rsn9bF=g}H@&DZY<)cC+PR#|-BhA8 z!@_;l>8$d6wlt1#ALGa|%RQeSkK?X9pN)Q~@4r-cUf+Mg<>imE2g)8Odtin<@YjEz zSAVUd{QEq2y~ovke$dc-)@|!P^HF)uN6fD0Wq+U7qx}EXi>@+%Mc?^*(lIeH>hoFm zUt{yx8U1~p&tH8$JMPCgpY?fewg#Hdjv6|0zXOLJmOV1V`9|lnH_vbpbqvFp`(nI|9)D@hwh`2Z|WXv?0B8ASpY{2x&u0g}5a+W#&-Lp%cHLpyQTq%U zI7j{-@GX9knZq!joiwyOpDoR|aA0=6<(iK*ce3XrmgBRjKe9eckHH%{9@X+^*#l({ zlszzg4}|c}ziq$4e2rI#=b1gzX6Wyy1>4!Q-=LxSthDgF?L0gFewxn@8k*0B9teI( zpXmstd^SGI-d)WXayuWVv-|hM zz01EJc9#nqo9iVeM(H2^ewzD_aawQVCMKEwbpOq0 zfBJnpr}}e3`R}JCot5oJ&nG6C{&fFMuRs0w79Q{L_{XPXV*JC`^|DtA@s9!f4b2VX zW0wAf$42qjxa~@1+*YD9!(#m7+;aS*@#ndZo9SaY{xN+YP20~iGjz+gWe=1+@IUSW z&62ANOUeo5_(vQGvm^eo#EqHwhs_Us-YTbue@sT4$LBgS?|`~Ez4*t(1xDVR{yp$` z{{QM{WAD)V{_yyR`|q#DKfK?w@sEoxT+;fqZXKo-|0s=%y61RqX5t@9oFC_>qlZQ8 zba}(^54ZDiI=kZ^J$5bseJ1a}#^-S*3uhkxaQ{v3`<2JDyuasEe_l}jdt2T`!kK&S z5YKY|&1ir6eLJW6^Otge{-yqO|4pwyJ^tbG4v&AVbVH1Pcw8i@OrVN?>^E${;5D}C zH)z;?`yMtc`A(8(iPCkc$^V7FKSw*t|H>XHd!X!r8S_AR6aL%wGZ)t#>Q|2UsDDSCk^dib zu$^=JnJZO(O!oKE*xww|to;2npC9t`Yt>x0pVi-Qf zG1RVf`W+=YGc1g`!DG6NC!RJZ=VSFN#d!DhpEMt%rlotaKKEm8=WQtey@^tPx{pe} zse7!kk0!znv9JzuhL=JQ$i-(Q{2`ux@Bvps6!eAef=eqG0| zJM1`MM85+EuF-2?zaaZ0xb}XW0W~5B#rqAkJqi)ZFRqPiuTWoAY_7Ij!;eEc4<<{!xaP z^B)kOjqe8jzZOY+R`r{;|G$OL59ZW-cH(^H`D|%irSJ8Wmn@w5eAfN3f>+@W{t|Rl=Q9}IW>~lfC!SrN&z9%2>Af>M zIKyySNNHr|M&RM z`;`_sZwMPYJ}oblkCi=8_CVPKsRtG$WBX@Qy)GyI(^z~q{@ymVZ#+KBGr0KfO;0Js zW>IG(J{!)SbNgpY&)XQEEmd|__RmhV`9VYT*;2_|lYjLwJD;uh|7)ASJfDrebN`k4 zuk;QrSvV`sXU%_&&1Yxy|JUa8SD(*L=zT!=UAND3{ko3KXNM0TIruM3Xd9i+-t8Be zISga4$G&rZK3l(9X`hwnv-SN`Qp)q$k}t}v?18ce${vUw2(QEG&S#s;xUu=H4%s}+ zecJeZwvo9kCsKx&Gb8iaU_0mLvz018rr9x{_4z?V^VyP5s;&L?F*~2l{{Jm{lz$KA zgHMS68cK^<3w z%~(E+!5*iV=d-0TgyYhCGRr;hcBQdb-alLNMI3%BWEPJ5rfwBi?!~=0Y z%UpF@|7O?k!CEzb5#FOVpPQlhY_Oek^V#sX40Mg^+4BEu^ZCJ?n$NZ9(BR`xyV z`NYJi&u86#jm2kY^#9l9^H-nG4(=G|vp&zw)WYhCDE1`wgZw zpPkwL2KC=#p`!M_h+Ka|L4O;o?!Si4n}hRN=CUEpj`*z44;q@!mRia6_*WmZ@!9Nt zgE8g#Y;;}GfBue4F)=af^I7*_WAoV=-EZLYSD(**`u@< z=CkGf2Fb9>z9&7Om>4b2XQ#8@U`FS&K7aN3?8JUCKI`+`Yz?~Zu+zZNf8mcCsJt+r zZRqbC+@HPJjOD|9IQYsrKc6km!Hf0segez;XNzuWfRy*oHsF-9RQ5pG1OMY5s1u)U z(U>!)HJ@E)opsW=sETNO|7`ttSn-N!8UJzfS^jPpiMGwk@4 z2ah_S|155u4W%@?fA#^t$jo854_jP4=jXHatL6O^$9*|ITi-*jl;^YVi87WwQ1(FC z1MY#+{@FNZa=k82Yd$N>bS|oFrvso@TdhT4V z$Hzb4#{XA~%`(&Y?&g=zZL?XoQT+$5zUHiNpN&N|bgdd4y5RHyVZTH1f<}5g+5CR$ z+1S5{W3IbCJ>GkdYo8-O?*01%Hg;ZCUunpb!G6NTyJzUU9^D2N?WX>h{===LHd$vV zzfzajzO-qWrTPDK?(Lh#v%GW$VZLh7=-MTqOCo(h2{* z_E9e`ovq(r&HMOlC^&b5CJbZsoc4c*$`QTh&E@tly@Yckk36l=X7YuFm$w*Dxon%$ z3dEbOpAD>pe1{^kE=)i-$ggJ}Ut5TOp-+R<~^mVt~&UKd`#i+ z7Z1r@acGmE?S9|hl}nE)Y3(N*6znd~R~K#?xk~Qhb(`eS=6-GO%3M35rvahyMJoGF|oW?ckNqw*mWa{ zc3!_@-X2~!?8Rsov=MzPyS_2JXtzvdb+|6&ZGY-JQ}=zUNe(Sr-Y<_IQ>R3Ot zZ2i1E+UtHnqrFp>E4BBMJ-4oT;M=)s`wcA=npS@?^|Pr>au-Wm@UjJJhgIw*?Z>H; zrTy9MjG9$9?^pZa9e1kE>sBv5Pm|oQLr2w2?9{w+%O3O79l5Dh@!YuwEK}R2V}G5S z%e|v>FH(7btk}`Yn=eOs&AXpb^XyiADtj+=rpi0-=x^lvrqVjS`9vXJBbJBVWovb< zjM~dR_ujWj?i*eA_+9p>O|OgHjlcD;9REo>m3MVj)x5FJ7tHl#%|chTD>PAE7_o~? zzObg*kMmaUx#(+}+M-77)gkj&?%BVM&h2vg9i5`q^}t0cE1Pa0?SmWE=pVJ`zged8 z^Y;8*lr(!A@PQyk&NvJhY=X>0#Hc z8NqeYdfm2_)o)4_^>e#s`<|dW*NoWu@u)4V@<#V$ioVPaFI*ZmuG?;&1vbs)URinG zlS=i=-Pmhm>er+?YR{@2(XQjGZby4#c^}+BdHCvO`K3j;ZkN-!?t;?#_ijd&DX6>%R}q`*vhr(b&E_#{pR&c``6o%jsrB> zn~oPW{F06<`ttcch04@_XcHgVwDP^h<}RFh{E?FfeH;67sr5Fj9DG6B!j>m&^y%mi zV}G31Z|%zEuk2XJo%rW>r@dL~-`_u5v#|Avxm^EAQJc8=@@6+zE4SO|;H9m+#}+S^ z_rYRz-Q$<#y7c++TP_;LUzg)=Z%6-f|Mq%$eS1c<$?=TfUVX1~u5x#c1HZShn}2NQ z+Eu<;LihesxgTW5b7SPiAJ_Cr?9eJ#=~v6Sn!!~+Vb25Z->AiYqr7$dbP0A%tJ~&& zlil0H&kb7daPH6}f1Mob^3903D%1O%`t>|({>rx3Zd1JXxo)qnQ)^P~4{1A%-XdJ% ztFdFR-?L4V99q}z-D@eY)s##)e{M~?xxWtM{;RQj??gM$ zIzRbC&C5G3U0CnRQQN$*V${C7sA=t4uXZbpzUIMBhi)FVQ$B26yX2>R3fqsXT4rSL zCb=VZF4x#^zrlrp|5O~HPt=Z`+%ed_U%gQCe`&m6*S2FPE3fc4<)MAkx3V@~_taat zE?TZzw_5tm{Y*RjJ;U>q=Mb8|kDjdF@aIo{h+2!SeyL$x-Bi8X51;-TwL72tF0^-i zb+7Ng{i8|l+ShlfY3Lbtn#TB)KgM=G^Z4VJy|8s0+NV-{qa=p4>a1r{n51g!>Nq%(>B>U_?~AN?@;cy_vM$|ZgW?rnz>dbQkjq=iaVJ>Ok4BM!V9a_u9depgB(e_<$`*2UUy0Xu<+=FO`?6*@T zzVb1SU%b73AE9}B{XRnT_I_A>eY3kXcG0}Op~iYQR%@KLU$<9y{`t5zI!?Iri4 z$?ej2JX&_ng_fP0p;147$4{w>&ywt1&z~>pJN{~&o1HtNW#^b^*|`+g^|=78;GRMA zxd3lL*L*IJYCac8HQK>kz%}aZbAeRzxqx36JD!uwK~g*B0{GeOnA5EJ(5AKN{MpaV z{W-RCdagfXQ;oXt>~zh2&okDqf#%QH)Xtx=sfMr8>oSMi|GRl>eJ-`H?sK#yj%{6= z&ZW?<-FeYkpG%#pxfE??t}Clg@&*E z9d!}!DAkWSdV2p}CM`QhM`Ny>-oI$sIXYT)j*iA0J>I|cW|JIRc8-pgoui{==jdqE z&+lKphk85GIlB8ky?@cNb9A)q7*I7RdEmuf!#Qq9Mom&bK| z{J9;PkH1v&@t10hKm43(jJ5Qh@$wiOshy8C*WAzPy^2OV(tFz5o0f-$U%0Nf?WteS ztC|1cmf^c(^+|8M%s6;KT8HkNhVMtI*6yW^E4vP#tMJ50KTUf1^JusJgbgaMx_R-! zkTIh_81Pn;-19nj@Y!os?z7)%!`ta)-SH|Y7OebJ`E>|SW? zcJ01tYvqk;>*cNg$`W?nmMgxZ>vE0N_gOr=FRM@L(2+W$aSguH`P>JMb2sVvkIqk= z)N;j+nvbJ#jUUcBs`HRBW7=L?QL4+Q!?)=C>zEf>k6*P^UgZJncBal3t`Rlb7VXyf z7CU@}4`O+vKcGA`d=;jq~Fk*?zm=nCc6L7_^yHf{JSLDA3E3lM?28C zM(RH_>XP~ojXJ0PL!)h}|J(bB|yclCdJ8`3amAj5F#SXuGeQ>brwa5U?m17JKZT*G%SB`Em zpk8?g4)0lv9a7%MpY*T1aG#zle{3YE$Q}PGXT3Cu~`r#0jJJ+Rca6?0rkC!dl>K_^EYd*`o-(gw%QSUTAcNp>irkcJ+1n6Sb5jl zv0u}UsBO93pqkES_pP1UZb0GWx1OEa{DdaCy9;p`kYz3?wxksF};XMNB?u2KG1&xh#Ofohq+8$Q$HH;Hii)$EYzJ}r2q7x1ZcEt4k`GS^R z!{{?^Sg>Oa!=Eo`*);+$k2MEhn?TF1Ie7h8!|=6^pk>xD7O$)h*QGpvzMy5x`{D6p ziuLp73tF~*ULNgrAE0H|FchOGc+6-@Rg6cVd2DG)Rg7EA-TjP0X&l5gjPHhyDrDC% zIM?HA%vD&!(D&bh$Kj?_#dyh-Zf6v-YZz$RH4L=u8pc#zH@k*`U3LvaF_eO@VfZ{u z^Y%ja`z2cTdnj6V4FfIvy%sI~{>$@O-zy5)@5yM{@6%}6H4L=u8iw1Y-{aA;-}lk7 zYZzX?G=6}VUBf`j#{bZ=-@6sVEBL&<=7_k4p?F;(yM}?5{jP?VUBf_QzLD0CYh>3j z(6Zl;(6Zl;(6Vb7XxZ;aXxZ;aXxZ;aUcdDFk+&oLeuS1?!$8Y^KcbI3ZsGnz^SH%9 zM;tlXzW)|HZgJP)aSen1@VG_p@ISxf`!t%zE$%ohu3?~g+#+{){N9b`af`bSkKemP zc^0=g=!m$6f#z!%HAloX4DMf#txu_nF;K&m^(e;`?a*scWmwj)*R40zQ#Sn+5{T+7T?*qw^+kK z^Y|L~pv95Gy&B7lYZ!h{6CdK9=DNHay&Y4k;u;2;uVGB7ifb5(4F}&7C*&Q<8iv+( z3fVP`%XF@?z_TtI7!1&@#W zoPqnz*DyRrfrkImdqHb_1z*E(J2YRz@cRSJ*D$`{Ywxgzf#z!%KF0Bjx7Y6@G;gop zM`+&OwpHW98U`BmqrIB6hwo8ZYb*E~#!gjnZ4AxVF#JA3^EHeOtDX*P7-+tR;rEf& z5yLgo`v}d~F#JA3^EC{=kI;M#!|x+BU&HYGh<11%`F(`uedPBMny*dx8U~uLVR(D# zU$^sdisow=K2EjP7TT7MQ|`g+8U`AEPT%op*)QJ3fHjx3?BPJ^SOY3FGKUWKx#K~ zlMa={;8VM&uX&-6u3>QQ&H2UZ+4)=`J=fPTQq9*e{JP9(vhiK6!MVgI({p_dBh~yF zn`-!;XRKc%lxOS2shzK3q?)f`xW*jLW5_&rZC^&gW5_<2!p>vJJjdDRLEAir>~kqJ zk0JA3a66A7`&4?alWQSK{$M{!;1mtDg^OXui(??%h6VQ4L@-W(k*J4Z*$u3?~M=jdqJ zIl5mry??!a>HUjFJJLBiT6T_(mYt)cWyiSNrE3_}&%X=#*u~DrpN~m2AAhOl<1f{G z{H5jj_)G14{H2OutZE z!x$acFcfPp6xT2k&DStC7#-Izu=6#Ha}SMc7>Yj^d<|osL*p6-8qXJE@XsF-*D%n0 z4P%}|V+kObzyA+jq-@WQ)kvN(0mPpwqfT!h~>pK3^ZTEz*k%sKl>U6nytkYd=10> zr}d8laeme?+<$2FdFnqjU&CIT&Z+;09uHrcD-aqnC%u3>16ppad|ARdujo1na5|7c=s9r63Z zT4$V4&u-(*2G_Hre%UpQea`Mv$gW|~wrmXk9n~)zzu#@UK?PsKIJDxKu!iwiVGzEm zvxc$rlbZ)S)+^lZ(R(%zcIg_%PMdWome;g8u1!3;UWcSSp4v@vZWq@a>e{7i4u0LJ z#s2W?rgq*Av?*0_4dW4OM{2k8Dc`J{jrpGYW#>(^ez{nh_pd)oE|He?=~dE7@$99; zx`x*!u2kGhWcrahm?V!q*2=&7Uv)9-_3?5uZ(| z#`@}m`h9@^mV)1Uq~)=864wagx#{mUK2q%A_uuONHpAB@sEe;n__HbfU5DGHzt?cP zRP*PR*DqZsNq@uPcB$siF#o+qx)ziEu48GK1zYnIGf0y+65O)5ZGu4<2Ft_z{HRmtx!%H>)uIuMw=j#ip z=IaaTxxP;@we#=dshzJcxE*z-etfrgJ2YQkNbP)mA+_`G#I7lBR@^_7YQDaZYQDaZ zYQDbU*QGq>0%`pe!wdVM+G(Gq+tHWVcr2R7pL4mmUtTe-;+}lpM~mj`OupY1&12kN zKQw>loU5nlGV|Bn!<@^Va~yl})4k3fr}5wD5FhvQT;q2;u2E-?)qCtq@#o_24Se4# zn#asrT^VECXdW|P^O_YO-J^T_4T8ta*SzNSjnEW_EAH|4>!Nua-F=GYF>@~u&12?k zjeFv~`*w}xdCc7R%PTHb?2ntO|1qEMTcNS7pujdAu$IKtEjav_CI6iG4mU$pP!HGqIt|bZLi0WeQeOSY+cYiKJMd+{^edJ z9_xNa^SG_|hhoz8_JE^hT z40)|_8!X2dLh~51k5e>{A^Vs_^BA&^U9BY)+jdj+we#8fLa1{bYd3|lM%z55>V3|+ z9&7gThvsc#9I!rvmTjBXM2h?6{aJ$Mv1T8CXdY|!-<_a&toi-wuYcqBBwEJ_*Y)vd z>q5o-@;?5s^H}ra)$4@uhvuqzpZQOetAEacbTt?`*=q4m|Lp(x_GL2 z%+2o)&h?mEs`+ZyTDw_fyT^`>EzJOV<=b zF246u&107CQ|#P-sh#^T)jVdIYVN)c)!bKJUK%q>_ig$;m}>t01I^C;x~X>D zQNK;)8g=)sE>}H7V>i{@j=iR(IL+9b&%apn#6 z3dG!)qnBbv^|c-vy8~Oq??S$x=ELfp!aR)cF21+N=ZWdxsPO#)>Hb}B2m5Wa^-DFc zU%FS<+mUK+m+mF@XHKg5SWEXI`|~Q*+%DbM>~^WrR z^zzcbo09HLcDq#bcb?ZT{o5?*er2~yHGhZt-ej)pcIh5we}|^~mHi!>YU#dakJq`K zzBh(7rS$tH`xreg;NLGb-!1On@VOLP_B#oh$LoAvhnAhUqh;s!niq$?F6s9GwCwi< zwCwi^G>_ML{oIZ{F0VRc_m%D!^*Do`oyGm9zGn>0<8|Nf6@MR}?n(9Q zrhDFp=t)exj&bGt_53?5S~ez=?q~J#Tq9oR8e`JqS01m^e51Ix*7ta!dA!c|q@sDe z?)lwgypFbcyzcqkW4ul=kK%q-zb=}`>)fYk9=do%Hbb1L+L(HzdsZkF7Dy;v5V$$8jshd`%3*jO818H z{^d7k=^j#lo~HXneQu$cZ*kA(bGycP9h%4Me4L_ryw1lYn#b#W>?*cd-1E78RWUYP z+#l<{r)}9-73X@q&c`2`$Lkme{7o3NY`jkK*y7$$f0m$myw1lTn#b#Wk2RXd>z1vG z@jA`T!gYQ8+25im?hWgkHmr*AVlpXH z+T!iSy`er{(!Gs7=SufBy2c(pe}AN!$LoClhaJ98*Jsc?UYFYW`_0Q!Y^1n1G}Sy_ zmumiAP0RE5uiJ6mVP~xp;&rLUp2{@Nh24aw7OE51L-YB8pNn67Z>Vd$%d+t%v~0Wy z&Es`G?$NUGCbVq42`w9M^7m>QZ}RtVIxj)X#+%Tx@h0}P`Fr2nhUV}6RP*i!NgeqT*B;zPvi z()~?*hb5MlYW^Koai8K?Q&mE|F4g?px_hYNbyMxAV`IFo?mn#;uS+$ztGll%#>i65 z+rhoyvAN@QFA%RwHILUZ2ljZK&o}Ds$%@xVHNQsP{an#5)!Z)KyXAgKwbZ8`uX8(m z>YCf7d%WB)spheabbpxJrJ9c+-^)Zi%=cBL`@^?%c%AQMO81fZ9xt?_ zU9xAaAZ&Es5*$!xqX)h1}{60c*<@9{dHhw$zR3`4~_4@Oiwht`_5U>F>|I z9jWH`)``!IuDRup)`jz0w<`ie$W^(KBH+08VYu~lL@Bg5` zm)m7(>tM(I%ky-(=SCL}IDEmvdGoiZ^y{W}w3jjYvwo-k_M!0_ZpX9fnR6Em*VtR* zfNP|7?kkO#nh&p-)S2H_C3A+F_oStNGZQ+E*^x3B&Gc`(ub_I2t1-$#pQ|3CkKO>q6ww$tD4 zw*U7;7hQ_K{a&TN^7w$TEyy?dZIff0~ zbzM4llIbT1k4w1gEo5_w>0^W^Cfs%YUp(>uy-<-mRmV>@8@TJ>8K$2m#K{73K!1ju9tR~>0M=ecHsG3ck#h?F1Vj@aDU_A5aWN>d1qNUltG@hpCgQA zR^-kVCy#!fkUac+A$j-(Lh|qnh2-HE3CY7R7LtcwA|wyLR7f6vnUFmEav^#66+-fG z>PsGew?6NIir=MAR;}Q7>XSVD4ty&c@KyCm9{#XC$-^JgCwcgT`Xmpp)hBuQ zSY7{0s{?qIaqw#6;5EjP~h^Zq1#m-DEOdpUiiQ!ZuhrO&SBhlix?gDjo0Cz?$!Dg8~S-Clbh*gPwI&iKc|w~c=& ze8>1fvW)+KmwfI6Y5y|)dEpDjDdR=sF9}~Z{)&)1*P1N++&Jf*i7cJt#~B|klWW6I)aMz-xz49%^PW)CI{m8%ed6`O zPw$$|@#6Rtn=gd)2ON!Z;rN+r!>JGTgVT@nF`W9-9ynuw_QOH15A8l3SvuGKn{oYV z#N4sQ85cfg=x1*ib@RTa4EFXSSi9G&oy z#zzU=Mn8Wn^0SJ(B4`H(`-)sTS$Dh~glRW$yeUgV?txxjstMo}8ew#kY!*A6mdH5~* zBoDt?pXA|Rst#X;dR7Gd+Bo=)aqwH?;CIHs?~Q{$7zcke4*p~u{Mk78i*fK*zyi;-4y^f2Pm)9InWH zB<}Ns2gIi;Ve`8_eZKUScJMS<0 zA(pB4yZEw7*es{d%Z#5RT-o?4!a>Hz3fmfAMtFts^MorJUrBhb@e71281EoF-}pts z3ghjC7aG4rm^Z$>@M7cbgqIrcD7?}*W0|&5+Qa&c{?CVbcP+9?dr+VB6CA(A@t+Up zMIYwF{5|?AAN+T<+2eo4G3V014;c^N8*~hv{$15{?uFQ=`CJnnkKZ-&p>N}Tkq_S+ zVqfHQlVtyTI9Km+A$i*Jsy@lXU(qLd_{;hv4}VFY; zB#y~^=<~_pTKO>UV*e_>p>yNd%ZG6q`!^r@JdV|T=;t_|^I^QjzR2gEQ+XSOGAnW$ z3ZFIph;R+#s|)Wl{(^A4@r{Mg8-Gl=mhm-(j~bsST*vs@!pDt2DO}I^y22-nKP}wA z`1-=9jCT?~V|+E?i^jhYeq|i=cQ@!`31mFcN5ARwcjLbZe>MKIkUTbwN%C;UGI{t1 z`Xmo$Jd%eqmVA6NzR069W_-MH9j=W|U3}bvj9qll$05jALf2q${em?Mc-F&DE$9Tqqv7Y%*_f(H%=EHSTJ^DN!`XSY0f91pV zQ$4mNAKI7du`T(~KG*4A=iH@j872_dFg+MlgEbsClCKqpRrH%ei4s-nh*U+ zp0ajlgP?uDXb*FuaeU^(*mRvXIbU4&{*p?x zrG#ybqdP};n|b6j{jc>xIqjq`ZT4{2!3xv!LXL4=xa(T>%ylrm zy>R)2yWUDRE1SNeaD{}su0M~RTS$rWSJCm6%m(f{xSHu5g&f0vRpBCbE~sq@L0?8X z$FNyjxQ_AFg=;39W7u%q^-khTAWL6Yd|~73i*KlezL9VffUwfHusZ!9E_&8CUIop>+PcM$Gm z9Ng9T&O(lHF5LCr;=7v;u5NzbL!4vS!=s)L*vIreg&e~M?)v&FgF2yi5MRm4+)>*0 zrtdA>#dtqqf8(dO z`|C{ceeJs3gGbr9M+#%V=fikltWZ9&L$}{kikC@z&aXu|H!Dv)iCw&GocP(X$kJ(} z$5r+azs_tZlktSjLHb+>s_QPHG8wyY{Ry?4{@h03ErsOK=N6KObDTUJ&Fwc5U)l6Q zD$mDECuyq$y&^~7ag1}(=_mLG;+zlPFyYwl6>KVk{i?wxmb0dD%Gk|pC_{g4DwIP% zZV6SHgT?nZn-Rj1fh)c$9A-Lrpz-cP&cRok3;o;!#I=MP^x@*$n$5w&wx%B>-qUoh z6Z^L!hYiOla~;`oZTJz*a=Fc+;zx;Z6L>zXBNc*8K6kjZ0ml0Y_p@_{2z_ibK6kQn zt5lBLA1S`GmnlBV&K)7%H}HH;e?m65oYkM_QaraJH?mlc;+Epuc{#H2XV(VehgdnZ zcfC+fK6ixpkwI6COL&-Zbm!=9Q_y)`tPV#>A8qz<*THJjj}~$azrkJaCY$3-KSo%U zaMw4J&55QTFFZEku5TfmEtM$$BppA&Y~Zegr%23p9LgY%AO0qcWme?=E>0f(EFpRL*+TO0 zbA;sK=L*Tg&l8e|pD!d2zd%SHexZ;&{30QF_{Bo<@Joc`;nbHr{3o^JXKTw3Lj6gL zpnoqUkIi>N@^JmRf{=&rCr%!o(>+KYJ{7d*?G*8lm;R?Xd2BA#^)ItJfR`HwuP_dd zH4a{BoH|l(%Ap_rX&k)HIC#Br@G#@x;l{xujDtrS2ahs-m9BZUUH2N{wZ<7gj5+G? zPa$Iw&Ur`Mxz|e@Z+btCyS`!U>7Lbb#vJywI)0vU#_0`a&+%&0ACh*r={E{*GJbQy zv1RO1<}K2_o|H!$(78W+%-=44hS}dCP9B>(h2-H63-2-xPB300e9ZV|D#OdURNTvX zP{+L-{fsx1OPLpmcQ!vfAe*tuqf_=HR_5u_E;pTadmZi(cR%n9IM;0M6X%|%oX3Uq z2ON!S!08|A4W~X28oxvw|DscW+5-o@4ve38-)TKUw(;K2hjAD0yL`CsV}HeGNPH$} zT|@Tq8KP&7%8B=5K1ZFevTN~dU`+5_qCT{fI`C|BKV$39v{$4vwyF zn{OFQ?jOd$IiY;5Ylxq1oN;}!@rmM3C{gBCDp3Fqc>?@IgF z^rwZ-7^jS9jXx)R-uMeb@?7g};U~s9?`f+K$7_v`7jixP10HYu*hJqU;Wrey)-S}z zC~>Xri+VoyqROYu=r0M$!|#<1c{qNKzEylf{8iJz*NjgReq?;I(0%x*%JK3a5%==n zk&Tznx%h%>JtP~h4S!hplyR=}q1n78yw7y{#Os5f-ZYyB#qlZSd@7_r;AoT!$Io0F zPJO5!oPMN_;naV!amE1cM+dz=wEIarm+L-b{4rsTamIy@8T#4V73yX-l;M70jCflZ zhYy$yW9fe5jH#Q9KQFv9@OR2R}CseqkK^(m42)aqw&7 z;5Wv>Z;gZB83(^N4*p;q{Lwi0lX388c{tD7Rc-F^FL92c ze<~yo$KSF1eCU%E%)Wy#K8GuE%ZvLw;dj|@Vm6(GK40o69{W+>Wn@!fHtmJXA-LAc z;>Q^OMYy5aY%KiEbmms;n!cXU=UvQm);E0vq0f1!|0i}XNZYs;eIENlF-iF;`bTSm z(qrE#Rwg~3tC*qm=+AuU|L7~l9;L@IpqQKNeN58VaV+J-xQqR(^-$??>}kJ>&W-)6 zHBISptZE%o+{ZKHE%t@ho5X)rqW<7-#=+l>gMSzY|1=IxF%C{O9?;%{IbjpyU{mAZ zrDp$!>ink?b)c`w!|5OLaQe>si++e@=5ud}?_oB33g0yTf^c8sgM?Qbe@D2R@!f@Q z8-Gc-kMV)R7mdFn>~DO4@MYt#3HuuFCw$fT>%u<9_ZChvzL)R~bVamULe9q1I}3Jo-xUTj^JrJ^p7Lb1wZm)i~c9VxQ(i zKgaJ58Z**kpDMO2d%k;cE`1vBi+uRr5c?vZTU2#k%r~B#=!-Qg9{o57cvemY#gNC)Ol&OgZ99e5|W40FKZiLQphp%C4}VR_&b)L&#faK z`$&6ibna?qv$}9x=(~zAuDY1sP8j=I-H)_-?eK=_?7Vt(+;sg6WmQ zIF_{kMEY8$=Y{cItaT0Po0{HP==V7FU)*$%w$U#7Jobh5PRmcxKl#w-vF{WElpfDj z{80AMpZU=L(N~HoNsnV7ANnMYNv&h*+&GrB{wSN+zgiEK9><>6BBjUv)taXCI99ce zDIUkO)?dV9U*vQ1%l=UF&mqG3l&39CghNdqBK*~OYw4dEA1!QU_Hzk`nSOw7&G38sA@h0pq+Md5=HJfP+3y0GTVGgFX)dnTw!v#B*Ug8zaE#|C80(o2 zbx-wJW#Zw$c|j zd${Z1a;7gMkB&> zrysmuHWJ^|^qVyg@$dMzhQozMq}541A3leUfNdkA+hzL&6%@yF#q{L8r$#cwixzBsX0bo$5pZk)8g1)poL zulSk9?-joy@EGg6$oQSoy}wQs?{C-T9=ylSy;~UjJs-vcV})l(O=5qcY`je3bABz# z8LvF`BzEz^$QG8n^uG>asGIrrx%a_{)f97*r2+5;& z6OxB>oID)O?MI96Yx)3{=VRs&X@i2UH7_B@I2WCMf{zmCeE6XW$9A`1QxWX<3pTNw z1B_F~&SpayLxZk0P-!Px8}||4*KCFfM+QG=?NWSy)4`#}D}|hcueu8T-2KFNvFi>I z-^y%;3wJa90P!BCbDh|~TBFo)Uo*uXJIY^Ab#(n8*-$5Rv{--b&zE*wXp4SVD1M5y z>p=01gMB`Cm$bc&Gv)^dUXdFl^zqLa{=1!foOHLZ7C+1M(c+X#9S#xh8F)U|TXoyh z+Q_pjo?DSSEaAtBpO)0kpKt3(KS+uG#SgTZ@(-3aJd~NwZ7#l*jnD4lJ&f-t+r==K z{Ym0m8Q)cWDdVfjel53Gd5c;3JBTl8yrXQ^Fq>Y|7O`^~`<+auo*Nhkjt+IJ2*2qJ zRCQ=BJ(!5|FBC5ho^JN@h+{{ckCQgH@p*+DLqAb^3*++%Ifj0+^p?h32|0$ofIi8? zPm|3VO7J%NToh_N?mego+GeINBW!DYSs{7s(K;GmPRKFzcKRd_&+D@tRD5}Tl84iJ z^6>WIGx8M#Jc}_;`J;W_)8Id2}@PN5a81 zjDzfhLvM#-`{zh;@{}`5pCc1~h;g)ojh`j_yK(R^f$@{X$C%BB(oQ!1al%iLcB<*1?`Jzh{9jhinc|-r|C{*d#>a|ZsYIQx&?k8~ z+92cLImW?rjf3YI2hTSSUSJ%&&^UOJaqwc};3dYvOO1n<83!*n4qjn=ZQ(k`!F7#; z>lp{vHx6!K9PDHq+|W3PkJA(7n5aapr#H(GN-V7EScdQbJ!^`aH&43OR<} zT)2##i)|az=NDp!&GI@vpYhg0j-jt0y_N9=g&ad)N%{iD7Z!31owCWpJIZD?CHNB3 z7B`)DyTA8$*0|;vHoX6RZm^Sdw`bn5Bqp*sRDM{*IPZU-4^-&fWvratW$%1>X-k>D zt90iZ>)cJPZf$kEr|}WOjf^iTeOu$qgElc<5LOyrPI_L6y7iUDF?c&^%bE@@jx4>q zj&E)@oVSVDV85|(=2Jeu>Z>}_HqPB!oc6$15VkkIwvasfx{2OFe0#gr%Hk`U%?1hI zQO8#@y`vC2%GpKwD#kYyatwVp>8l!FL%5o8Y@Dwp&N1xwlKq;-xh}`h@znq&_|nqc z5BR`+wV#d;F`EN~!;RBNJ};%cw4ZX;5guqZjG0|bXFkh4gH5Hh!;Oy?7R;urkYm_v zD(q|=JlX8Ki(`jPm9%cgHy3gY{aERn8Sf$F82Sm)w=lkykYngQh2-I5WOIrVe0ym- zm=2HM0X44>Ki2f!g}WKwLr9);(FPmeQ^+y&y@cf9eT3xUdke|K`wGd!`w7Xz`wPj# z2MEc-_YsnZ4-}Gz?<*t^A0#9Xr(WdY#GdyzK3Yf~9gR3O92{yKBp!_p4l@o8H-5Zu zjB)%#9{Ur7y^Wui@Ds(iGkqEdl9o)wFNy1%?^L@wpapI?#erkr_WjfbA z%lH|>(~X}gyw$GzH*xaR`R_vV&i&l8rJZd0IYRQ-oGT;`KTmj%l?m^wwxORdeu3G5 z7aD&+w*Ab8w)%Lhm41oYz}@CS@k>pANc>?X$_F1Yex;6&H5>L~J!(3d*Jpyb`{!

|za{-4jChsg&c$DrLzVA-$uwW zczfwRjc+I97&>K>hZE=bm_PGC=6vYHe|9uZT!@$v`r*P})<)t#F&3(KmTZ{wVZ$7W zc^-TN*$^Lx6Z7*}A8|$E`{=|7JvK^I_r~!=Cu=0miv5$Iyv8dW@0Sqqmo~x=)C465qt0 z*eo$wIDLWN;k1|b!-=nYjF%YBh+v-&{ZA~C=+=1IjI?sF8D*UJIPp+y_};*G2FgSy zW(wy$PdpU9i~5bR1*h!D^WmDYOvS*ZM|;J+#k~$(-|I%%eqCZyM<`F3hwJmmz_lMh z{3zqZl#VvOvv`$pG`FFA*D1p}$7A{0XDIIF+@-cuD^J^diyvd0ISDae^s~f?DZ`l; z5woVAw9j?Qa84P~CLhZ7azHP?_%{Mi81x+TJKk0L&thqm-|)X}w-`RG-RAuU3|wuO zfg?r^9Nn;0c%B2<@$zY|Ekj#8dOBsC+XxrN6_ zXf8Zb_?ixIY#ycKl~-}$?*O(CVuwAcrP4{t&o4YdIG^x1;afTx+g3`aD8GPkjIg!v zMBzI+&bh?qICo*CQ>8B?JX!djjvp<2RY={51yBaxk0@g?CH}px8lIR7rrX&thAj{LFpBx3#6|p zyioYEa1*6%lr~j*N$Dc#YYQ(H66ZNUX=|lnN=GVPBAr;%r9$F^LzK2u8mdH$@JZ<> z3ZD=zE4)#7sPJLoVBurJ!-RV)ouKr9@*{-z3-=U0Bs@g;ps<~Apwe=3_C7-DaF+Cy zg?|@T3A-s#R(GXprOTuf^SWGkjBr1t6_xf^I#%gy=^cgm5r5&g-b!7S+ADG0k-}Qx zal(C-PEw*C?UaZ~_ZQwJtPox=+)>E0bU7jIZm0S_B^;&v4Z@v-_yK?PQkq}Kw--{k zeo99u^;bGj34MUl1ld#PzDhj*u)`jGAK~3XeE+Dht;*{wjy*bcy+=r&^ikrWfF1U< z^&;o=OYpICkXG@##3>8Nv^R_Xs}_o+JF1@Im1_!n1^DDm|?9h4Oa_pBJ7hd_j1T zkTM@o`b_zM3f~gmD11fuh;Xv-4k2T!M(J-#omHRDrC%t1qS9ST*pWwnNJ!moR-)WZ zWluf09@m{9&!}G1^=aYtLi+q(rH_=q&h)EqeVp)3;VnYy zwT{YTTs)%0IJiJaJ*h9_Y<(T4-|1iac@yOscZ@&oiB8HhE*XD}!?l$^R=ifJT4_z? zj}bnm^sJ8mP57MfaUsvnHFUgMNFMz>;funF!o!qS(sA1Mq!MH038m3W9i?-eJo-~g zBbC}qA0>Q73H@m$&RL8u-utR@d=@6xrr5`GMK?(g?CGx9C=lWa^ zo#Q;OHxOPSoFp8q)In)KCEEUX>8l8NezzBPRoX+Tn-YD?`)EBO&;MhE`zx)aG(_nr zCEjQ22zh@oCWb0)rF4MOi%Pr?*AnvnJ5o4Isi)E=N-rz%K3zk|`|~B?rb^o?byj*+ ziTCkpLf*fx2n$NRlq!{8Q=(m+guK71h251_P@K#OXXUv!S}Xsh^bf>; z6)vtkWAII-Yn2vN{uk+AiT^BIO!;fX-&VR>X%XdrlKzGGkHR*}UnTyo(rrpDmH$Ed zzr?>6F0A~m;**tbQJP=*@1%b!{;hC6zZNba{YLShlx|R>y|nv7aqO_?yw{b+DJ`Vqze)c_oa=BsuKR-$l1POfIslddrJ5Lf8dwT#PK8k#INrt;Ya+5 zUq2V8ALtMI@N)IS? zQ2u`5T*4_r;$0m3LurE2MoM=nHJ6SrFBASMoLk6!)Io{y#<`4{i==byAC)SV7_W?5 zCd2rI*d2XO8C{inD|J!&O$ndeqT`GmVoP@lxmWH`+E01<_zEFoxtVZ(;ffqn;(A>7 zV(Ikl{zC4@EtR-mhbYgO87HLgh6!&M;-giS4p5$Z;z}W94HP~stW|{A z4^EqrIEre!kv{Wm1r;RzF9i$q`mhlZK(V`!atShBfg{I`=-JN zh4`peiMUu3rE8TqMvRSq-9`x?jZ&U5KVC>bQ`VJD1wOA4L6rX7lfRb7d8`i5i*{8C{YgOaox?tDF=JbTR})Ys1JUt5K<4W$93s1{D?nk z*B0WmgZkErcU5{&iT2``rG)r__C6%NQt4qO{DoiJ3h^WU!f%X6{EWZpmt}?Y1OCSE z^fmoNf6=aXLi&;ZqTe=BqMfvNS>ejU%Z1xCk8`wDlwVHye>IEWc{(b8j`Ce~e2{Qe z-f3CHI-jU_`Qy=AY4oN3xu2N z`1!)MmG2<@R>v!Z>nMMbu!oLcC|pG;LM^_5><_@$214%%~> zu&0h+D%?Q%cEZnfoOaM2+SNtJuM~DtzN7Fb9j6_%=L+GrI*y<47k>Lx$7u)cpcApAzhX$S40U0done!w62 zE)r-%@^%@J->-!g-|c zC|pE%lJGU@TMJ(mo*-OUdLQ9J!V`tBNZ&^IvhX%PPgzpOv7q*tZ zyRen;Sm9*p+Y8?l9x0q(dT-%;!Xt$5N*^G6M_4UvDSa2=V#1?@Z%7|4d|fzLxTy4g z!g+;N!ndXGE2N#Ymv-+Y#14DT+fq15c#N=(^u9u_!}YlCK0?Z&Jj&f!h@bEmemhJ^ zJ*W@$>Mx`nwC6qPI|yk9?V(+}3h@K}z%RXolZE&Lzw9Q&kN6Y6ZY#u(_!GbGA*3JZ z5BjC2kba;)=$E~Ow1f80uC0XhBmGIg?k%iQeg)wJ!atOzDm|)vPU#S(dqg)>x?5=; z<$n`iD*Rper_x|0#%gz^CeptUUMS=}KSimaw4G9CCCdI-=|&y@M94KbZ*Qe;N(U+b zx$rh2do_fg3{c||0?{4 zkap0XJA|7m-L5oH`5%R2g+B?IPYe-qk28dMaS0?o~is}!o76-QQ_Z| zUsL#pj;|y9yYdr-d+Ye)!n2fLTezL_>j}?R{z+j!<)09qqx`zU?Umm^c&_qK3kN9w zl<+*|*B9=nJnf)8v}>U9&j`;~zLRigL)=hF__L%aIuIDWt%_~lO>ryaD1cJ@Ta&HpS4(g50b@0nALaxvC(D4)Pyg^7is5d(8 z<~hOhg6GClN<34a6moxapL4%IqlEsn@OL54U!Gsjnf|Ph`rGs^R1?4{zUs3ok;mX2Kg$pQ+((#p) z|3Z8f;g`aNls;ElP-&!&w-&D5G{z1NQGOBSzfoFM_TLHFM>!9O{30D$cta`Fvb8+R_*Li{R8%V!M zxT5ev;mX1dbbKS>Cc@j5{uC$9eVttMk#IGoQ^c1N-lo(?96R#p8>yUAg-a`6qts4m zfbtyMSJ$mj{!FE1l)p!~yb}FHf6y;^^O( zA^iy98}f6d>hZg9N#P1Q_f{o*f}imxe%)C1rwOOZZh&xQ=}#&R7Jpc{q7r__-;_@| zl=r&qX(#QWU8|}b{JMnjA!);;?W2@e9zWx6{JNy_3ks<-{>9JNDdD?+3fn5}F20!T z_7JYFJoj5)aqP&WFRtUZ;) zZsEGpIevihZG?vk7Z$E3o#VsJjy(GMX3u$)N4cDj&T*bss|Ys~b`owZ+*|coLb!|Y zQkB~rp-JmpXx=Z%%Vn(zwY8p5v9DTngb z6jlnk-?^{c7*&FBq+UT6iYzF2ndRb zfS{m&0TJm21Vbk@1*P{6ySl%1S9h1K=l^~4=H%TO2niYHufrO>e&_ac&v)Crd2{6Y zZVu%8&mW_FU8FAna=mh0vL5TRosW>teUJMe_rbdmZx3vRcw3~m2R;RC4NL+i0$T&8 zq1-572gFOGor#F^J@$@>j{tTC4h6Oa4hD7s)(_BEuB1hzqZ zG_Vt}B+B0h9D?{_xb*80@9xcc1Jq%iHuK0J-+Mm4v_D`^h7%M2ksNxFM1$! zM?4bspFq8mi1!6P2pj}VL;BOehY)`dUBjK+IKqQ?4Np2pHS3GK)r6rryh?3 zxsPyvqP-^}pX>K2;4_H#MLvI1k%BnaGuJiiPeGjeS3p^|!}i7k2LPV~_6I%-d=mHq zupcl1b(f=FGU7>yzX%)zY=QKFE@YhPPXk{94hE(Gp8~c*xizT&GU7uK9|s%;d<8fJ z*arDuAb&jKBM_ee90{BV91d)U{B_8G74gxCzXluwY>)I&z~>Qv9@qi#u|Nm#bCkay zn2h-A$X|tcbHrByn*pCgI_t9?w)ZSB6}SQUlYq}4-V*sM5NCTYAl@3d8u9yp>w$^D z7m?0>zeKz(a4nGKUP3za(-CKV>cw&|yV_xU%x5{4XFBuQ-ka$E3h*Vw(}6Dnxu)Mj z;8{H#NKRisI?trBz{ZHbjqn!Y?*Ms6dLHRKL!Se3F1(BIHsUjYJR3hn`ZC}WAm`+J zEQ9z=;5p!8q;t-u0nY+wu?%nra1Ss8cpSI{I1acS_r90M7&8K>8HmY~Ur}CrF`qv zfYX4l0bfS?mq6N)_M}~>0@)AyW50g@ehlQDVgu5T09OLX1Ji(Ofu8^;0#^aI136BP zm*f5dxEOd8xD)sfjOPus_Z{LN0#5@!0PY1&1ztivk#VM<0?q~UPPZEMces#orvDY? zHzWOP#Mc0Kx{z_Ep8&p(a^C>gBAy9+7xDiCPCZ@C)EUAbBER zN>7Ux578u5v8TdVfIv zS)~6J@#DaX2$vE5j`$g18HBwk_aDUfLB0mu3oMCn6`?Z1Zsb=19zZCBa1@~c!X#;u5??(D(z*9(11^&)ep6#*S zBS>dG)@S)Z-~+&oNZ$oH9N`>7S%mFKj{s&O`~~e38E1My=)VofXVKpx1i6rLrk4hu zMkt8z9YQd|34}O={Rsa=d*1;63*3bAB_OjL%d=ht+TVio!jQiNhPaS%riUZ{B;;ZU z8xRjh`~u|s2!|1hBOF8c8SS43mP5FRP!!<^LKp(eu{`U=AW#qLL%se5g!o3JSA)C<;U}c;23AG*3hAN9 z{~TBy@vjm7fqa%@dDaU-{#sxS#QE%`Ch%)uKBTV!)^epYpXGjs^cBF`uJk&c@-v9$pemSt7E1mUNUr>G(u&yh;K5#YSccDCyakj($smI+&=l;xnn)~(Z zz=go3NSlK&8}T=Q+~>L9e+A_J&3$|t(%%5i0`eT8NhdejSzSqevUZLzcauYNP7qPHn1@Q&(jr%^ZabcJcQ|pzXfc9@FLPz zAdQczQ?Lh?U!T#9qU?A;CdvaX& zA#fbjmwLAWa-1A5?a~2(cHnq9?p8qBiT0vhJ0Z}Hv={Bx0!Ta4-sGhV0(qdlY4-#m zc_LpNS62k`NWREhGa$#w@p4{00gT05D2Tg#1z>N)InOxX{sruV_`Q(%Tbic8ClUWA z(q9Mu6*vgk5b61l-vF3|_|Hh63z_SxC*n0A{|8td*cZt8$o0l~`xxStAQwjciokw| za~^X(bG?0scooP+kzX0u3vu3`zJ&Y}a3JFKA>WPsdceJi{{`tELgsqhhj>lM{{>PH z>O;MFPvd$#fOu`lVW?jV_%-5O&r2cy8JLOqJ&*&D9|PQv_#mXuha7lH5J^{$K*&q8&1+pFL#&*+Co@1eov>W-L z9;`#XCIYoA$3;Fk4))DDOAx0W*aq#w`9eF;9<H)b`z^RBo4BUkLM}Ti3ehOF;`KN(zBHkak7x@E#ZzKLKunh9Q15QW$3E*zz z_XEC*_(5PfV0q*p0nR|YH*g2?`v7MleiRss{A0kGh;v-q zklzb98}Z}7O33FpIbM$I8{{Ve-$(omuoUt+PL7x3+KhbKiT0pfsvw`^^QKJCEqa@-Y= z&vA0R9M^W_(+(Uj$6XQm94E)iacx09c_JU=B?|c*C&&9c%#XD|?w#j=QJ5pUfhB?8 z1G#5x21Wp{0*fGh8L%ku4?yl|8NdR-%fLcNUk)q`{5_C+>PBFG;3;4^q^|@P1YQAh z&-xM=0z3mOgY?zFvcO9~?y2j5LBI>ZXr%7|mIj^%^32!ECoCdWWB9Go_!aA#gM)f$adHs`%MS39hPUkoj~eAeQ3AsK#ymI%Y=(Fo%J7`;gZRIY&i#)2+2cT-JKRee z0iQyg`{f+SJjeSY&U2l6RaIbr;5gQY`~t8a;yl-BYu+=SKzuCHS3+hvmS?@<$d3aa zL_7uQTOj`v_$1=IcT__@&%ptRbHAMgU+PU;^PVyY zaqfrQ@3~*{zQB6}=LpaFOvJh0@;u``fcF933k1k}1n(2PS4@V?{h0TG7|5I}ya(_; z!2O)(9nX25_dNH>CGQ!$Z!AVSKM!!6952UR4Een0@V@gh(!YW%K;9=DkU5ul&hxzg zFVcBlJ_qD^&U2k}f%gpFH+b*h=ZXISk0ah3auwv0XYx(nUjsf1td0HP8Q>og4?}(e z;st;|AU+uB-(mlF8u%x~{{gIz{Cvp&Kg55J_yOc61OJS8IMVMyegyDG#D^mN5b}or ze?t5&q&GzV-N3&fJ{;+Bhz|q)74hF8Js$Bu;LnJUM0z#EM*#nhco5Q?ARY|-8{(sp zUIXz_z<(efg7kY44+UOBoa3s6_!!_n5zmkG=7@8g952W9E%bW|_%FmGkzNn^94E)i zan(VbcA`CK7YE`TC&$Zi9YlTFiT0pf8X%wJPx-37xF$` z(Uo2aSP607uQ?8mhvlg+_2%A6eW^FoD+BpCfp;q+<4or`I3C`u*dE(uI>*8B@C=|m zXcwllf9k={EgT=m$#jl`K0_6V8yEezc@vuDgrQSUIs4w+qdQ%|JAw7>6XFA8h z@l*w}J+{kqj)UXj{!e?*E=*_t)Pwsz$H#Fpo#WtmxZiWmG)Lf^Xo0}FmVm%H=0IqT zaxH;vfvtg@ldTZQVQZ`-rniC2xzi4T+_yzwIhIdEej<=_q4o%zd+kyGKIGpI znRBTl0_R8v1g?Smk>3INogjAtb^&rOc1Gab>WKV~%m;P`zKgW`fgKR<0_=`>OJG~X zxkesDpiR3Wu)PO>v}G6MbFOqnVEgQcoc2WET~y`jvqoGhp!`WuJl5nZBr0B zW1o2xNSp3QAF~mk40#rCI*@mlzCd!+hd|p8Kxl^02Z3BCA<(u@BGBdo5yZ8QpjV;qg}G;|(G88{b6 z-QGtaCxa2lRWbt0u{`TNgFst7i|`1-7=(Vv9|S$f>GKHWY%t;jkp3LxF~ARj$-vpb zCxK5Pzd!J4An(vGB7G<9_9l>b$#4YTT^~oBcf6N?naD4K@+`;lthX6$@J^iqoD7_Z z^d}Jhi1<8|dj&G@{NEt{KH?J)Cr{*yyuFIRJLLw%XCVFmaDK4Q^@x+ZpAmlm>47M- z4EQ$EIsv~zdK%KkBR&oBD~P`d9EUjX{Ff1DI`f_7&|VS9uOX~QdJx9JyU-6v=Nc9?ANebhUkCDjU|rxU;D4dV zI$$cw7enZca4!PqUOLkMjeLH_q0M$7UKH)n&a^k}z6tu!j}McwDC%{E zJQjg_#|H?{Abk!n2{;7#TpwH~Trcy0&jN=bo#j}b^%fvJh%g-KgOL6aWR_!j)>{Z1 z3><;{r+_1YLx7`!40Ca8Fu=z&&a?LL$P$)C28)4!Hr^Sqv2E1ih6GWHzLk`gl+dm*nlt) z;W?Ba0Q?f67s3k&(@}ml(%J4DAot)`fvnGV*xv8a?(-O5Kcx2t_69x%+=Bd`z-JMs z9@K|=eFz*6oCTbW^b4rZGiDP)GQt$3KLgy1@EF3YXyZ|Y$C2I(*dO>DFd5h#_4@*; z5A~vcuLD_sJg_eCB-)>Za_52UkNvX$c|h7A9ib^gFT`n2+JyVf4g~784uR{P>z?cX zL6oZp+=(y(p(Wy+cbo&9KV17GflJUI(_aVPi#XRj`RDv(e{7fSb9@|UA6Gk^ubeMq z5$8PQd}O<9zX#g;8u3zSCm8J(2ku3@8`94r{u*!};`bpv2yvEUdDc6FcroAs#Ji%c zZfL(IwAs0uz=aF9m_#&`7(jP$ngTS$fMpV;_m|49_J3< zZwoq|mxL+}y`waJ+49HxU-2b=_ zeu3}`($Aqiu4ArOu3zpWtk3eScM zP}4aN0ond#`Nhh%#LY8$KDx;17poeI6}Wj(uX1}%XtZ=7#>#QNQwHO9_1hAy@@(fH z%n}eBaF-KR4l&ZHpQiIYWtI7ExXOG_5mU$64(FJr^IdS2V~sME4Y{fz*D&PThI|iX zw(~pm($J8b7;RHTbE1?xgRo}GT*^eneSR_`G*Yo5kuxX^IHB1Lw?ebpE6{= z@2%xW8ZzHe*YxKN`6WXhZ^#o3d6FSdHRS1rJj0M@8}bK+{E;CqGUO$Oyv&eSLMFfb z?;1l+H{>r3`71--Y{=Un>)105d9NXJJ!+YQhJ4hJPa5)BL%wLpR}J|GL;lf_e>UW6 zkadjzGUWdnaz3mjE%Q4=4mRZch8zx=W8u6lWXL>!HNB)E^IX#O@`hZ=kgFPUO+&70 z$h>c8JB>2`B~)=hCIfQpEKka4SAd)ziP;@8}b{5{FWiVYsj+< zd9ESPH{^weyx5RGGvpP9yvC5%8S+L$-fYO*4SAO#?=$2BhJ477j~VhQLq2E7mkjy$ zhWtm!+|TdEKR+7sPln9rM_T3|hWu|s7DK)Zg|$4N@u?hQ$YF*YVaSCHxu_wRFyvB( zT*i=N44KdP@GrvM&i9{H=CeMPYZx*=?`iryhRn||n$FK)DmOLc=7!wDkXsvaJ45DY zL;QOjOPRd?*^qxWWPX3EW%ymJ%KZM2ZPNbvAgCPZlF3D=A%`1sAw%Y~9k$8;M!C}S zK`!l*nI2=v6%9GgkZZVP)~#ct^H~M{b+#XG$oE3leiMxJR*>=0)LA~!Nbg|CT@1Oq zA@?-o#|-&#L+)?LNsv_sKEuSn&d+XquBtMhMX1c@6Dso=fXXi$GC#YsP1=8=kv_?g zry6D6GURs*`8`9PZOC&W<6nfkozI$8UTCB*He^1J)iNtwGBsRd$b9z3GEC=lOv-GZ z&tz2Qa|4z6?1wVT^ZA;}2Mn3dmo)vDA)hkjbB27$kbiH;e>CJj8}eTb`5%V-A4BFd z9z>mb1{!jxA%`1sAww=^$R!QA3}l@%F@_v#$dwJbsv*}fFa)KeZ zGURrKe7_-gHso%G+{2I`HRL{q+z+yj@kvAGvq()JY{(953e;pRKB# zV#s`!sp+YPJjIatdsZ#OXPqj~G~_vkJkO997;>5+FEwQT9#q?0ZOG|{yupw+8S*wm z&NSq`hRpY9wEcsI%-=g{`bk4RYsh@2r)91h@(+g0@9VV8&xU->kpFGS0YP^8-x+d< zAr~-Y{timp=XaVaM;UTyLyj@ziiR9#$TbX^?@4K!^$j`Rknc5QhatB%lHP}>}B$jOHMf+43E@&rRpHRLIV{H7tlW5_cN zd5$5^Gvoz^oMy;N4SBgCuQud#L*8J>n+$oIA!i!$UPIn*$OjGis3D&;9E7hCIrU zpE2a;4EY5^e%X-68}h4$oNCCE4SA{|zh%hp81j3DJll}x8uC0t{@9Qg8S-L7UTVmn z8}dp+USr7VkhyR0v%m&J-ekzz3^~(~_Zsqk$mEgjd}pK|G2|02nV$jAxMbG4V8~Yt z`FlhDlOg})lKC0r?=G45-hUbCVx-@VFH|^2mJc@MFqcdnA`Q8SA(t@ZXhSXsS??qj z47rja#~I~o7;+s$u5XlYWTZDW_)O@(YHX0$Fu_#g)#_aj&^#=1w-sOf}M{8}bZ8p6!y^ z&Id;NM~1w}ke3+pGRUgW3L||DWL#bFcXz;gBmFBw-eSl*40*R9e{IO$8uDR7J`P!R zIAzFZ4f%pm{)!=gZ^(ag$y{qc8S>u^`Cl%Xwi1`j-tP{z_@x|d$YF*YX~;zkxddd@ zzmy@DG0K!TtoN_V=`56I_gJM%yDobN+wKOvi!d}_9D zrL)Z&{M|r5&r;6+|0oi5JYkS;R1J^EZtGw2yO#YFwQ=oR_0s&C>DBMKeuD>$(iXhK zkQtUY18 z_3A%p)bPRhU)K&9Fm!aEAp=Gy4ePJPZaY%1qv%xUF@HBr9di2X)V*6$-~Ize#&jCi zf57OG0|w+&;re{*vB34|0h@1-rb(H*-PdpYl>p~@v$UZy-Sec3wy#*G%v-JYn2$5_>GUib#Nt)MM^SL4@wk(zyBVRV9q zxPxb$JRMzcp_a)z&S-^S1|Sqb$ZUyU86x=h&wW0z?~@4K5GZ^8y^pjbH%NCcN8ab5 zVYSal7wI-2<4Boqq8Tll(BKO8_A?9s;?donkHO+^A5?2m&u6M5VZo~RL zJz%soBeh)ak+ys-%Wik0ZD0PG`^ByFqr53k%A3w_@?^HtCDwB@M&Pj(qOXlTDd!v_z@^@Y!_5!13;>$ci_uCWMs*z7DVH#|>|9iW;W+UqZml(GOkwTQ=+1<|n3W-~NN}(CXIyysfXj<%5R_-iL4B z`E0eE-p)FowVz)bk~f~us;B$;oRY9_Z-?gl_U^@VJpN_2RGyVrCO+GzC;Q1h?b1{CY4A&qoq>C{@~eC*ziFRZ>sWbLdn$GuFuL#H!Gro~ z{8rK1`gVW5*{9SwmmJW#n3^chK(LMY({l8ZF^qFZ%o%=qx+5?G>mR#a{XuUo2UAAN50`VImJKtRXua!SNT+a6aQiHtGwIx zw4`oH0|wj@p&ku*Ti|o;mTWd@8@!&RF~^@3uV+e!aLHIr;UXzO9dM z_?_t|>sR&k;P<-wv+}9@reC)BRo-oTT2iaQ1Nx5ahbMua8M%ymTi@=+H~gmi3BRhR z2fr@!*!O4UQ~6EXVezZH+xE1iEPil$=H({sZGBrG-|(CE;+S~fJK0ex?$NI^m)6Tix*@|&3E zTEDJ!Y}?b4+IX>c*@CzARUcn{f0X1W=dbFi-yf-6EVR#G^VDchfO^2V6A^;I8V z@f_mt51v)e-14lvD$i<1esKIQm$M%$L$_bojP?K zTeohN9Xoc&_U+qc^XAR6apOi=yLPQCS+c~b$N2H%rGNka(z|zWNlZ-4Xx6M*%I(l& z)~s0>`}gmc0|yQW@$0X@mOXp+$j+TRWy_W=vVQ$~S-yO^eDu*rGI{c388m2+bm`JX z1`Zr3adB~8>2T=KAvt{bupBvZ#EFc5_uY3+J@)O}C%bm-l5N|zIc>3O)hb!AV1ZMI zAwz~p&z?P{Teoh~q)8Lp*KYmq*s)`B;>3xpaQygjVH$Ngc<`Xp9<+t(uwlanS+Qb; z%%4ABCQh6v{rdHj?%lh?7M&$NKK_<;z&J8apFS;SICbijQy0~Nw)pnjZ=HNl2jybf zvSrTs@ci@7JNw66kaq3bNyUm4Q*vX4h7B7!&YU?T=gysThO=kS3Io%q!^x8;g|?s_ zr~~H(x!`=*v}u!bPJZ&qCo*l?G(RP&m?1-l4t4TR9mqv&Y;3k1U@ysF-aNW9f!gG@QK%YK+ zMEj4AZ_0c- zH|;-V$`q{o9?rgLgPX0t#*G_0*q5n;_N{Z!vwu(i&H2YW3eTd>ojW`G=Nib4drhYe zbj*s{x9$Pi&3~SUnVFfQ>u=t?dConUdmruJph1IdZLj^)2JFwXZ*%Tx|D1c~`ZxEV z&p-cMX3m`HypPcCxf#3aKpRj89k;pvnP&iP&okggbB}9}YoF_#{TD1)(4p<;gt#v_ zMvfer!hX%Zx%Zj#-WO`kqp zxaM(}Nio~XtIT@=Z9zL|-{#$iebeqd^WJ;!J+61J#+;p=yqi7s)Ke)qS2MtG2KQRt zdER*AjSQS~8I>znc4SxgxAb491=OFF`meeNYVx_j(cYFnEA?~bseQ*5{rch?1D8Lm zVfglb;DCTSb?SPS%PG#j!aV$0Z9!W69Cv?5+D^znw{0+gZ_E1Qrr($FppvlJIF5Nf2uF_`X&5X z={)}b=+DYy)w&D;*lLS8O1|=Er5%SP9CJP&P3>f1+6HTVE3%xf39a*MMn1VHGWr@H&AKdYXfS>IEq@3BzFlXs-wBZgnfpH<#9H*1pjdEi~`qu&puopZNS$R7t6 z{on9sWm<=R#IJ#de8N0vVXh>se0P)xuztX_{U4l zE&JH-K`NihZ(M%M503J#_Efa}*l5bFp||zz-W<5mbCI=vm3OV7X!CPt`m>6<-#^}eR6X6#=j{DiDX+@&wZ#_C%D?ifXz+YT`m;(+ z@sE94_0)Y@eOVFB_n4JWcj6m<6aD0VrF!PXukxw<_Pk*6 ztGwIxv?PO{Jo%&Yw!W>8Z}?5~liz!)o;mTWd@8@mUs(Jq@3uWH$y{LKDAse^w#S`N#cA_4MHPy8E;8sr+93tHrPK z?#XY~?{GacavArwzTJ&))^D7j+^1pzNBY##`U3@CPJ^yR*tGwIxv?Oo+QF&Y6*2m)acKfr+^ppFu z>Z$zFE;sULrF<&C>C0XGx_GzkX-THPBG0_s#J#O=_u-rMo9QR_XVp{r&CZ{d@~QkL zt+e=6-feqYlF3hAwrFqb+xqy1-#9;c{;YcD#IN$H{9fB;@vFSs_Ov8#{ZV;aU-j|T z_xy=|;*U=C)bEefE*9GNE9F!9jaz5&tGv6{yYu~7rTPiKs;B$HR#g32ndN=^3lNJ3eEoJ^*)y%C?0mhFYMOzK!z1~n=woohtN!0sI+u4EyvbU3u2j~xE6rW~0YC5Pt}l|yr? z%6Bu1%l@~+W#6;{vg`E%vhCG!vhl@ovT9UWSumiCOzIFJLt0gro(c7&TjLtiq*AGj zyo~=?+T(I!VNE%)poEphKt}nq5>5yi)*N zM9R+B!erCSVX}5~gnZIJT&8u6k|!G$kv0{=<^DPq<&ky?(x^_Y9CbLow56Q?yo_8} zQClu7FDd7jSC(_1h0EE`%0P!gaw@GDbcli-!ofuW%!h*V&Gc~DGX-;DLIK(Ee55QN zQb6WDT1dvWh>$K-3rhQ1<)vHm2GYKHsT-#g)Yo3dx0)6`)5M zIlrs~Y*9+iEDn@Yivlqx0_Et3fv`cKeEV)7Y!E0rQ$t{b{IX_buq=EcL?(BPkiPXx zNb8D)q;0j*(xdgg5?!){BfI&S_G*iai)&iQr8QL$D$1qR<>lh4QqZG_T=+Z)b_fI) zfpR)65H<*u=vq7?SP>9Uv9wn-U*bw zZv@JYR|93^*g#n^BnTV?%UDN#=~x;4S1Bp&>r|4K4eMmf!Nt{$(Qh@m@P`o4NhYoWN|PD9K07OU%wTIwHPRy zQvzk}s32L?FGwcc7c37~50!+nVbTH|bali_cKl!ZB2liSS4Kep>309L!L`5sB-eia z$>zW{508Ij&4GhD2POr|mT`fSJ|;-g1_a5}j=|EqCi*WIE-kB+lI|^=X50Ve^e*VP z3PN~R|5q@6?f>FR*Bk%`S#tpWAH^IvI4e;08*^~oGeNTW$sn25IavDCvipyZE1#|X zmrjb$xbj6Q^c{haANCKCD_L_O5c3cma1LhI|J(K&u=)>{X`Mo(SIzv=yj+Adizz7e z%9qTx|51;{rCdp`j=m!i!kqnQ&B0Yz2f7Bb>)$p0E#rbL`}Yr)DIG$kN3}5Y9VrQw zN=R%}k!<(C#x)B#F0X5kehVX5bMW$7tid(GatZxkSP^t{{yG091!4XLVg6Zr(8R?2 z(z!~wG%H_N9Fn~X5^$NxM50kdBkL|CqX!ygRuUCu>OOv2M5XCsX^F(g0cSu%jbhbWoC~s8Pp&`5-JqQ)!0>s zQIAzmxwN_@`YwdN!!h^-3vdkEHkFwTHroB=^N2ZJ#8gE04la3=}I{u_+_H$>Jw z6N)#g$PQcVYA$fxg4A_vXjC3&lAc zg0Y8S?7oIfErgF_|b#r(2zSQz%+2pQ3|u(YfkC0!F5<;c6IPK|4oaXdR> zNXpf3zL4*a?Sb7Ro%ev#X<^v+^5g8mJ!EdE9Gn@7vnM~so*!cmlk{i8asEfj#QTa! zhw3FIp=PBVIrr?_j3>h!$Hym~^fO}X0oIByN{nZHP z*}wFu!ZN*Eap~2dj5MrVHpOf!uX3Ymp|Hi!lfJd7HJq6{(}Hi5uzbZCYS4Z(DG$&vkni3hTJk|AvlFONab?*R{hh zYb+q(&6WA8{~hseNqzed7};r9{{fxHj2=E_bVrvLJAj^x^4-S&-wEydT9(~>?a#{GFLX?~ zLFG+(Qr>iaE1#*8-TfkY>yOIY`Z~7T@6T#Rt9td4vv~Wp`?FG>lsC1D@)#KgZ|9f}x_C%|m_gUY&2VyP%8vnT7qM(@Snces9p8l-#{M7SQ z$EN43#ufd=pH`{XF%wi?{x$ysfYL`072^ zR6p@|qN}inbpdO}RDnw!Yn)Z{AbS^poF- zsh;ldxvF*S_n4JW<@ab;i(lnkYbe_M+?oEY;#>L0dvU6#`}v%`KP%-`c}_~Pcvk+E zUqyrGJJO%kRX_Q?w(6<-bawu%luzY%<`RovL3jBwm!b$H`7n<(W<8hzb^CG_bla8`AvSx;#YaM?P*Eg`lIr;zO9dM z_`T{U{HmTg@vD3)zv=xfewBCIo|a_zEAq_BRovV9b|=2!H_1=-XVo(&ew9z8{#MaQdCb5ey_VfE1y~XzG(5QyxaD)q^#fJ zdS>J@?rnX$8{hDo=qLV;R8J3nUFNax&mk^8mEZUg7Qf27ZBI+e;wLZ8QqY9A^=*B8 z!*7zGtY6jBpW{;0gIZ|h_6d)xh4`N{gt^zc_kyWGg1 zmGY_lUhQG=tGwIxv?SACk!N0R;@;M``|#2F^^@n5NiIFj^=sS4-k+6E;W{;d3j-_#rK&)562Qa+X6^wk!>%DX4OdGl^$ zx8iMmZRz&EhiA3ivz>o@&#!vAf6uShA-emsQeKs3eQ!mXuKEC2P z$xq(rP(5?Yv+}Aus~wepjVpTVkILKns)w(5j`NfCta|2_XMNw)lV`Q3Cwl9T%G>&? z&;PnVEB(DgcK)pNeQA9^T6xyrGnl{UbHJ$jyUOhRSp~qK)k^^{2ON#Nxj!rYttj8` z3@C_pjq<c&T8H*P$l!XiD$?VxPBsFz{BqxuSPMz-0s9(Qc zO1W}n9iH{Pjn}DD+p%?PhV0m}Rkm;6ESooPl#LtHW$oG(vSi6Z=<%+MAOE8C@83sy z_kL6o6WeAqYj$snxBasItXVTM_V3>-2M+8L;@4mAmOXoR%FdlzWy_Y0vVQ$qS-yO! zeDu*=nLPPb88oQBbm`JT1`g~madDNs(&5mdZ{_ge@8rml?||P5~QSZVL5T)2*Ob(9zT9W zjvYJX)aBs81F*-}PFw8SwH-Qak_{WuWyOlmWd8g)GI8QK>DRB1bnpHEY|&BT;~U2{FT|Q^%dUP_H9L4#E}(O@p7n~29Hht-wlb?L@ zkxZL5NuGT232D=&rQCmiqCE0Q4{6k>VU9X*%;(RakqZ~jIs;|u;;zF{a6uiu!+h8; z-+Z$db8?4^hc7T6Kb5(2XUf>I&p78|`}S=y7aoxI?c3dy2k7Tue-|&F%L*4RoXgU~ z)PeKj=+Q&YIY}OD8*Gp@YgRb-2hPR5eS1mk)-9xM+g8$}M|X*ij&@`>AJftnWw7r{ zm(FK}ix(&k@7qPMB zv*lpPlC%u=efjc*tiU*RVE@X6&IPUy%LZHz`(*FlOzcsco$GPMiltc`bnMvPX#?`m zvSo{GIpEmY_mwLbff_D2ZNa?jZD7peZji#~;s?2@_rh_npPzXa+m9 zzUh9zv9fP7P@hYeF1Xo%^Wb_8zQH`)gFR`xbAMjDcBL#@G+!o7dKG(7cS%TSDlJ+x zm#$sANOt_QAFJ<6KnB|e*REX?22T#SFL6IOc#!MBngiSm($iN-TH41lb!sZkgon}p zy|8@(_Jpq4_OG_L`nLMFbhzN`n;e`!Z_PvZIbikA^TC>fU&*?4t7Y-x1pVMvY9d`nTtR zH4p7Mn49sN_Mb9kBG!FZ^xed1gV@*#*{;9FjT<}IpQ(e+KOKKg{G0P{A?_$Vi#m6{ z-`PLcKz4Ia(`f^9?OFZXdl382ZvOLbkeRtnbp6en_dfREG1&WBI_=+}LA`8kul>^o zTnFse?%V2LZLj@v59XPy>woXwUD$uNIQO5=KVKpzL$Gj`Qs)Tj|Dw6|sR z>&LEhk8AJfQO~(=%{{I?uKliEJ2`nTSTNF|?dOE?@$rt4BZsGOz3IN^$-C#+_58`m zST8GAekOC~yeA_@40f)0-h*=L(=)$u<9Nrj&pw-S_39P*{`)`N;OsH?9c$g|y#M5r zkDT+4`+h<~vm811?AwedCnu-;@Wc1=^xwA9o%$b$Jy_R>+H{O_(F=4{EjLMZOIkKz!Tl%ll0_x97{a2|!t81UT z{8_pDTzP7*{;X;Z8`*d0z`Xm*;4_E<9{#L$AT55AyT2ptKl7j4Hkkf!tY;W02^W(- zXdYX$*uA&v&nhIw-JjL99lr5rrQ`ARgQVlS-TthuZno^FsQu_OA3hICL89j0Ot0JO z&&uUz>*xk|e$D4!)a#n7oa*ISp5yo>{8_0Usu$F7{;9sy>zD9nrStgzqd%)a*U+zn zo!6z<38`rZ>jVV& z+MkuVU%2;t^O*9cJSlHFzm?CB3GRN8y!A)rZG9cp?e}M;EnE0&_h+R%DQ~L1@|pUo zJ8$0lqw==C>gTKP-ILq+hd(RTGrRBIMP3$!m-Rf=^Ha}LwWFT18dvlee^zl1Sm#6B zMhmZQbw?df?(xp@XQlSh^_|w+{XF%wi?{x$ysfYL`0PDbKk<_i;?mQ8&ow3C$4@3U zx9nrT=c;^W@%y=JJ-F6|+EdZ?gQF?8hThhdFYw@eR+xE01^;hJXp4+&$_3eIq!*8OW+_O|q4}KFY z``Gs^dz|GPwrW&rw6|-x@>-xPv!UO8y3IHyC=Wi`lIr; zzO9dM*6&q6;aBy{iC^VY`OSRA;#YaM?P*Ddza!7AT*bYuZ+GGwev|xUe^xzn;#c`p zetSOdI)7d3*tVx78T{Ol{;X2{gkRM&Cw`Sr<@egN7Qf27C%@kMqw==Ct&eZkZA|ndJof!r`BZ+B*1FcOi+9_emXyU$UYw<% z32*D$`uK+55I=c-rFxqD-pHSo@~QmBe`4{gyxaD)Byasud0XGs$Kv;P`?E^(6Mj`s z<(GE3kv}WtQ~8ZbxA;}wZF^dh>95E$FE?>->)Uwn&z$&GK9%3J=PZ7eciWzpMPqmHQ&S4{(ddU_j2H_AVBrh?~mN|v)8Zksr(*Ib)CPib?jd6&i7{(m+Bw< zs-Eua_j-R;%BS+1I?3W!dH3WuZ{CgUR=lmRE&1v_yrYT!;m=C-bpM`TtwVJ8XQjL< z&-&h)@^99pY=6$l8)M$qSABfNbG)Ct&!KwemS^Qvc~(0r{~A~H)*qF(^;HjF@f_0L zKi0GAnOmOqeN#`K)t;W{tv@Pn>#IKh>;A0t_YT?mvvU33NZ*fEp7r+(=I{9&FslBp zGCO}(`QXp$T)_E&v}-SZbF+J?{#KOtL;ABa%lp&sxOATVFJsl{2*SZi`{sCDy zy1mSPx~-%>(pZuoY$2T**UG40H8!PObV*L1+xl0hLWE=Mq$aXsdPmtlwUun1)J!%` zXe?`AY$QvbE-tfsm5}lGMM?k0(bBthLrH8{E2CM%ds1$P60=6s&)7e!z8sk2ko~h7 z$=5UL%AV;pW#^PivSngLS^q+DSw5n;eAKU?OzK=%1~o1!oohzP!0sI+u4EyvbU3uA zj~t#~Q;y7wlEWVsl|vs^mG5R3m;E!sW#9AyvTI5K*_K*PHl~!5Rb$G^f`MgZQl|(R z(z?3zOsFT_8rP5}l}hEwx4^L_kIRWqYRZX4B@hbB@r4!S*n(K-QbG>S36ldeBjxM2 zBW3s0;9F9H`!Y^1OO(?~ zV-TX{^rsc&)RGF&Ct8kuoL`R2FCvFNC@J60Dh3_GVTVxJ@@gSjKenhW8(K(aKN2d> zwJt8*>z0

e14!S}CbmqF}DLXjnDUab{TqIk%!dLLE8#d6b;}EL_ff76ToM%gIlQ z%kc#zV24mSG`FZ6c&~u$dn;0QP70GvAnyjGS3o2s#vl4pFc}xE%SgfPD9U zLHXw0aM?2rb75iu+3;edEFV@t=JqZmV_QW?mudy2eXa7+Eun$5Z{GN(bD>eSNXPlr zE#>0cW^!>&ak;p<5cH@Z7gm*lP9>m2Dd-R=rxpjwiG_i3^rJx7AW*)Y8Ho892pfdJ z2Ki;pm|$5rAVem2j*z|$N=WO9g`{n@($b^Ny%Jrrgd-rEzqHp{WL*5Bgq zWoVNKX;(2qT30C{ZK{=#*b>>V$tABh&bX9bUoNk!i%?E3e-R>=)&{{AL9js}Y!E2t zJ`Z%a!FtleSaydO1Is{odtPX??(7)PXiDiRh9|y|e4@?dMB_kzJR*wpjkDmyV z35mhdt!jR8R46FzYE_UX)nl{m|I)fPa(Vqd=)V9$s9afx{?pMvbhx+%{kv>%cA1NV zGy+x|!Oj!U_+zB>AiL{;kiNBgM(!6TS3@=f@R~2!SeagP?`B~m<(zZ zAqlZXay534r=a+|I?7?#8(_lH37KA%NkQ|*Cgt-@l zxfhJNAB_Ds1amJ`(vre(7YUcH)eA{N<&sh`G{~Xt=Y;V!BON0jiA=e;ItqOk#=a8) zyN6-j<;UI|iZd_-V-LaDgR%Do;~o%#^Ctx7Pbl`j{IYUn81~)>8PTk;w5$>(T@xDR z$h)Ubjcb>2JUe1Y%GLc}$oI$hpzlcMJ>c|`Fgcl)A7>BlA-Dq^d_NTDZ+@IT`LXW9 zFz>^0{zuBh4n?Fxjgpd3t5S}fd-iR{lSd6t`QgkV`SJ2uxtRGW>>dfbN669n;kbtt zaNa-mz8NmtUyE>_{YwWImgx@_mtGCaNW;oyQ_QyVDmSVg3R?_K`To=)j5`W_7jxZx zipajVi^%rWqL}l=aQ};v_Z}-FJ?ck$HRkN}Y#5i{@zetqQ|6A2$(S=DDr5JX6>$G8 zFK;{^l`)}5bVlWvsCHy1LuaD|w4MzvlBV>ZRpWFVFHE$1mZ}O7&2^ zpoa5L^`&0Fgg+~t$G--DR=Zp_xe+9O`2W|R6;4a%^U;ueF27b=to5DfLh7h%;zs)Z z+S1hjhK@`9Z|L|`-;ir}UGqnOR;im@?-6aWP{)&ZytDjSseSbOp`%~9+bLw+Z~m)vbMB80ATMi+9a$&?pRc}mPwe3z{;X8b?7nyR^k=2#r=F*3M?GgXuIMlRtkQN{=R?mm+nx8I zYggP+$CG=!v;0}9eRO@#-0ps!dfLTXe^lPqSABf-o@=6?ya%az+V8ohB(!||Qq!J| z>pPzT=(($WD!++4Eq;}EwWp%(??_W_4ZW>z_vV}T)Kg#ekM~?vPxtp+)jIZj%*vEC0%`qQUbW>Cft_pZwla z_0)YjJAYQnr}CTprNyuEuDmLG>yOIY`l?4jfN%EcwDJD2Pph6e?bFJq@_RLEhx0zF zyxaD)B=vXXnV#FYxApCQe8X?%IRD^R_4MF3!LpBi4lAF^@61vbzskF9PfJpM?o@wP zArt(AU)9rtUl(0Azsjfb8(+fWS9$m3*IR#7-qyGE@zMJAlY4ZgOV6D6RX&y9#L^bO z%DZh(OEUZ&d1mD*?rnX$6W{QgIMF}Wuj-i-zsjfb8x?NxtGwIxv?PO{JJO$3nxFih zSM|(^U*%KzO$xL4Ro*@M_0}JixAkp(e6xPz{A7PtJ#*q$`BZ*0BP@QEciWzpe^xz}U)tqH{;ZTwo>_yJ|C%`%5Qf5tdvjXH*J;mJ-PC3+tZRve)6(Kdt2Yu$4C77$^M+= z(laN1l~3h2{!@!z<=wWYC3)+Q%G>&?kFUPxPxTXiRZso?NbO>weZNvZv-thD#jo=2 zUhmHLXO-zE-yf--?(6q@e^&7>K9%3N%@)7PyC=VS^KN9f;%$9x$ye{;r9b2!-}9@U z?%(sPb%^f%tdv*fS>Ibz{>_?{?aw)RW6az7s*kUDKKg)v@T_{~mS^Qvc~(0r{~A~H z)*qF(^;HjF@toG(KX_I>bIY^7Z|cdj+S3!g^+)AxebwiG-Jg~I-XS}GR{FlQz8|eT z>+c!N-}5?0BH7Y)@=2n_IM! zjm;8dZPR;YN$IjOJGzXFk1j3!OP7(}4dKrUx-_d-FXeV{HLFqMjQvd$2mT>@hF*8tb`0IUP3yTEF}Xwz@Js&!d~fcsNVoN z+^DG>sa!)2$5xd?_2T8biq&L)=~&qpU0!yTEGOHlRF{pFtIDd_%Cew*tV}9gREE^3 zAwBECpHz6Fl;A1EgpHIoxnYRQR;)#Z5Y267DHNTnKbuyjQ^P_~kMUAlto zE?-%;#Z;6H6)MS!=&~}uP*Ir(9{N?OBHe4lpH;PL5?|^T{aJPFoN>BKcR5|Vp`5OM zkDR`zv7D;YNKRC%E62)KmLsv%XKOW(GnHytI>gnMV=-}Z1RQ)2FBts*B%SCXUAv2v(X1^G6roa`%JMs^l2Et`s!k~M{j$->AY zG8uERFL-EOxUjS>4S!b6nn`rjP5fE4ZJ%+m!vk`uQG#5;xG&YeS1#6SBp0jJlM5AU z$hq>>NNtG4f4`va-8aY1vw&q^vJoLY5XRDl@_&WN5)c z(k?PmT1Q1m8_b8;LfOxQB?+xEF11LM%Z_$(`JSe7xl$duRI#>PjIHJD|9tuCaxSLY z^)@J3UJk$pdtrkeMN7#>^uGfA&kZjqW5Xk)V`M>TT@wDRDpi)2b?av9>*HdZ`{Z(y zmU0E-zFZkTwb1`%^nVHcUyQBkVS_488yt(SD2JUK#8?~@jh2kUQL?&VG5I*6kW2^* zmu>|Lh=X>h0Do2$D`wmOrOw@*W4{ttPp(v{D_2}PST?Zwrwz`+2B$F(JURFp9PBC< zEt`u($y)TkD59`TDi9$LhZT?n=+FWjbdA4>KdY`iXp2SKdTzGQ?4{^C0DAU|2TL1 zYyanO+P}31v+R#OU<&&05e|P+1q(_7_>V1e6Mt3(3pp-#>nT^NH?Zb_G5^^A1vmR! z`;aI9yRZjr2LEeef9^pO(SK*yzF86YbSjk#e^#YqQZCnQD3>t@E@KVcXb-sA{LjSv z&%pd&jXiK4_#YclP}*Yb%}bP!24!;L&ni0F;oO6;|6T?Mmnzqhi_Sd=bI-X4a{XC* z;0f%3$FK+L`rnIla0mL|i2grE|1+`w55l@nC{i?6W7l(VRPDMcm$2_%f(CbA!h?E}=!JpMx__JF2nVgEnU95an zIa;oY97O*Ia2MQ*{M-TfVDCn0+RH=6#tS$|xwOU*Ul`8eJc^9;_~uJiz4KtMj% z!;hrDTK;aFCGem0-M;Z>rQ`ARgQWf5ZhuxY_geN-)PD4t51$96AW`#grq}KCXO+Iq z(kpJCJHO`hFY2Y`R4>o+9LF!=&r0=By`YBkPxYliNCvJ)$iZ>Ui>w zzqCIq_J0zg8vP<lIw%ha8ACHA&uT`idi9dCc;l@2HU24Y%9HY@x+ zSm#4>hJ|q_-BHJrd%Uy!S*d+=eW(AQ`+4eV7jOMhd0Sug@zr~-SN-HYNYzu{bKShj zk)VN}|8@UXK9%3p#TLKHyV_IH_JgA-w}#%^>ja|?yD!((AS^O&RwmmIL z{T+Fx=Qi$beY+puoWrSp!msM-!LRc>6!V^?d@8@G+bn*SciWzpr2PCp_TD^9uIs87 zJzOqC@7+sCJjAwa%knH&Jg8feEzd1WmL=QrB*&30+vOU&%UxYns-Xvw#L56s=8%v} zAbiY&nZgVXfhf#|00{|$nYnP^!~Bu&!I%5M-~HZu`~7~uwbwbP%4$hbsY%*MpSsT8 z`wV-Zwbov1?X}ik=M|gJYL)EgT@%MSg5QX)oSqf&>G)mzLBp@(eH6dr=A#<-{%kxe zGk>35CGywDc|80&J{`aNK4CRkGjn*%RE)>-cp1 zF8+n#*YTdg(@Ht~ydv{iJ-=|Ki1!ShRvI@S)wuU(<5?N}ZdfJq*T*@6-t0-k*(UW$^p_D#5Rh^LY4md^&!g{U^h(<2{3?mB!6S zHSYaBo|W?RuX*R{$k*-TbpMgV#g3VN<@j{`F8<$?fUHZhSaXIEVfG4jmqc^I17w z9nT)O=J?Ow$#S;NIXR4vd%urorSN=smEhUOd7^lBygHs8j*fq?`*GZSRO8<7<5(#? zKYQQmn9n}W6UDQ~n~vhy;W>I7Hy_ow_xpJMqvx~o{SM3Jv+{UpkB@dd`+kP}e!eLH z)%R5{m(MCmzAm{l*_muuI(9xQ-z&=aPUf@9U;ov)lfWtJ^l=mdS6p$$)Z*gek?;QQ z?+)Mb9p4e&|Ni%fH^2GKq1|qWUAuN2nV6V3v~JzHsnPq!tzUD^HB-OzOTQF;Z-h^O`qSZ)pZui8@$rv;Jp8~9{6P4& zZ~HdE;_=5H4?B1645d;jTz1)Ihxm+>{rCIGqwoiR@CW*1`7@vSOnCnJ=QWOB|Mg!F zzxu1c8lFSG1;XNofB1*Pw}1P$YYgRbIXw8_gW;Zg?g^VWZ$5G|{eSLrp9_EVM}HJP z|M}1B$ns}D`&o_U_kQp91P{XEQ=j^j#_-cW{nOzGfA9yxhd=z`u(Y%k9)0xDa4&Lt zfiA+PO`E=~F@U~~{0VX={OO{@I`XSvrm{eBleh$3Qrc zHi!$-!_WWx&xarV(I3^^c-!0F79M--v2e>Rw~!vg!w)|kwrtsQ+%d3k_WPHA`Iq4@ z{^Bq6=i}fx!otTu+W6hy{aw++kt0WhhoAbXp9zQ=AA{q9^gx;<9tZ=@Pr~5YXP*rp{pd$Ui=2;y!ELwQ zCYoHkcJ0)1c)+-iu%R_v^EZE^Bg<^#xHtyl;%G4V&ENdZKp2n?e)1=OGJMbX zd`~!h_;BD{xD|P{I0hasy6B>1aqvSw^g~D3@8ACI->QEf1N(P;kS>S^!hmzaX_0jB zYrpnu;!m895%wm|92qoAK;_9oQuEk3%`)g zgEzhDO`^T)k!SFxn{HBhIsE&(v+vRV|Lx!YE%1+YFp2}82kf8xi1OjbfBeV8$3FJ4 zaOlvX@X$jKg&UC51~MVsfB*gASp9q7ek2SyF7}<@;xue@E;8 zSnu!f|IY9H&hVDEyhU<=eUk>)uV26H`~!}rywCh`wEyGb-|3G$2>J^6-VVL{jW^!7 zEbbj94g>E$-}kZTpYxBhh&<5e--kZ*AS95>M4Kz@s6O?Dafuvq<8-1;eIUMM;ZLHKl`%*d|bL|wOTzc&slCPq($(~L;vs( z{}BH1AOA7c1CAzpIPdd(hq^K8ZpV%t?EknpUv3O+UszZ;^iTivPvMJS{9+(YlIObI zas7k(=qEn$i9p#;x%ZBDyhA*P`uMS)eWK^67eK#0L^!zaL%Hv|4|Q_Fo%$bX?!No( z8|$5y8y9u6TCH{na_tE8ZLnI?dGNkRzUiC3>Byy*UOKhhy{Fs1Iw9cstUP~}=d*gQ zWBIH+&(-MY_iXDoy0zXZ$!GPyjbz68eRQ_lMJ{`YnK5zJSygOd~IBq_waqstWtW-X$T~DnJKJDW?9-nr6I(|3&u;JJ7p25>f zp6_V1{Y2~I-k?)bRKF;Ie*YWB2efB?FzB0#q z22U%En~!ST`?K+^41Ra5lKt8~&Jp~+On-KKI(|2tYj%3adj?M{rTcJ4Pn=+V-21a` zRtCQ_kF5^<%Evi^-w2*ee|CI2exLo{4Zn`}44zg>@pCfCQt*gz@6X1wGWb2bO60GP zGmqb+<+E~pI(`=?48M-|44zgRHy_ow_h;iV{GRH3R%;$z9rM@6>G&mFj+W2L@#*+| z;r}y#s^dL_rN${yN?>cv@-Pd{pD!@8el1KmXxXqF?zq z-GAh8v16uRIX)e~&t7ix*YQ4l-zz_#)$^+azdp|4`TO#GR*p}{?{fviuj73bzbBX7 zD0|Ad_xqDheH@-W`K9|;NB$ch=dhpOp~K^FJ}bwoqAID1J`P?_Ij`{54JW)J*yy+;O9iF4d zar04)d%ut8KYBhZ-|w(oJ}Zxx_V{SWv+rlf@8_EWP<>zJvGQ46l3bcRx8~UStbDJi z=d;RRzmog7oGwluPaOo#JoC({?c47-!dy+vSM>11dyy;RPUTC%-uWY!Uw-+aW96$k z*^!)c&N)-XVlgzE&4B&v;i;#d3j6o(NA9XOC{GS^bs*Tt;=moR4s_wjvNceKpZ$c91qMFLm2Gdy<54ffd6pSRaXV%HxMq?ufHgqdFB}> zgbR#y>fphH%EiHa9LxvAF)&}+fddCLhS}NKP_NfT3yurs%whg8=CEMil*!4-aPh?# zhqKQW8Nr-0qKBvKt8pw zcI|lq^HMoQZoc{0xiy%Jj(ND={`R-){gER=IjMMLeh!Yq`zI|D2BZbTfVt!x2F#zu zIZ0aNd^q>qbA<=y7DIVzIU2aJDhRG8R3EpE)ZUp z!~eV9^{y25gnym}zVxLp1^$r^90%k_J`bE1kOr7Xk35s3A z=(x}KPZ+Ro(m=j{@*~cJyi9T$Bp+b^g+d{mciwqv|KLf>!XI+x2yxH8NBbuok_L{} zKj$I&0A(U&66b*Pp?v?O0pMWS{*j0A(9z!CY4FQ=|55mp4-)^!l8NA#Q}21tdtUbL z&I3mKKN|i?f5d-Ae^-e9NQ0b%%i-SJ!Mi|qhf>-j?j82d1M~Dx-GDlQ(?5A&HvcwB z2C?t+&p)5^w=C?vf6Uh@;vhf&o&SvT!2J9t52h@3{=?jTl*4>y(*KFPyN`i%;PZaD zcPH$f_K!t-eD8JZE)1`F)vKob`NungXHS8D9`e5Pcz6EKcPH$f_mTJHVNczI@}GR4 zdGwCg=jeInZe>m_<_Kf{DDqv$d!Fv{?@pbM`Y`*W?4#^~>_0BfNBhp#A!`mXhuGi$ z{ogBBBYBSFowApFpLl1^I_f`^JJdbM>o2}|`P^~&K8{zWPQ)B%97nThaCe#~&*7XS z&+$1Ay<@C*UT!>~r76Jn5c)cTcRk`V7kLVgK>t4Sjo73z$ z#dmze2X5Q9?=`n`uN3!Ky!=mh$M)fTRxjQ$oX_foPpnKnD}SHSJV^dtr#he2b1{#V zAH5$3o#(Ui^T!(3smy0}?jIRm7e6tK-@N_n5C-el`M5@}=X-o5@>%&fd|VD!A1}xC zmB?r1bo}p_&+6;^-A9j~9c{?fpa0hfe>p#YxBg@D`KII;`gVLCo*%~B zxcR8Yz2D#QKYBhZ=R=M+hl}I$aBmoIE>9hfE@!>&$JLV0YUZ^jN7wAI<8yZoAN_q!{P@bsXXWtm`Mu%) z9hRq~a2Yor)wuWjcvdRT^~F^Z2kGPVI9KGdy5(Q~xpV8k{PREG%Jsj?UB{>6ci+Dl zejV=)Pd{dPaJ=QqJC1vQ*4xU&sqfmqI`*0PIEUk09Xc6)9iNWh=g%_!=6Lrz{FveA zm6^|K&AqE5F3!g}ET5OpXXSWxJb(0N!?WYx@$1JNo?nsqtPZb|dFfKPdnZnuYMdiAJw?``#4rApVhOg1iwDc?-@L;tPFlPtdjZb z;~c?n1W%?vJ3bx1FWwmWbDYN+Jgt=C=VX$l;1T2ApN(f_@cVpeb?|2&XCA*t%V*{I zbo}mmmEqU%p25>fP>>>G&mFj+W2L@#*+|X-$;BaUN&z zv{F7_(dfAosgHYq*2l`s-xpWO`pC!W_+2iamE+U#yX#iNuj4&~rG(Z&cbva*9uMF5%Fk!DW|iRA$2mNIU!Kp(@#*;8cSoGRaUPH2_vEr0WltIRet*)b zkHfPkzqCsH{65ZMKfgnV$KiZdj#tOC$E`X3^LMhGt#eKeW8>cM<5?*@Z`iXs;yHYr zCyHmstK-?>==k@#AIHr{HSYaBj+Mgmi^bJ}XCLQ@;@RU(NAc|N96gSkk80feeLVls z^I7?Rhvo8FdAzj8M?0Q$-xPrQLfm(CtbA5mlIxR~b{#vPmG2d0d}s2SWa#>p z+{fi~ar$`bAn=+q&Ys$O`>rF8JTV>ad*rEb_XCfHTkg0!Y~OiLxNhU7BbQx%#i8@o zuAMq{J=&9Ad-mF?o%@>MjrE0aU-3ZL^=LC}f4Cl|?tdy=cEdg4;*C>b-GA`uyy}Z*z)LN*j79k zwmi}g*FM+|SMQk(SM9Ea$$P3{u-NJY}mRxoO}7^aLwe_u=)C}fWxM6{)NZS zp>Z@g&A#~q;jZbohnq`>!i~je!c_TCm@2&mV>uW$zF`nH?mZB$y}uc*+cOic*;Ni# z@7NzM102>~vn{MI+z>WgJsCDmZVs=%W@9-2f-i3jd!K3@d3^BxaL3HIgsJ+sgdI5E zQGZ9cwfxqwoJC{k1d2vZ|H_=?rVk(yK3R8JB#7U+xLZwufI2(bJZ>3g3C9C zb(dTbF1YBDaKXAu!fVesvD{*3tzAELfBQY*fdlUg_jTSEwl&@rZmGXBY@c~&xV8EY zz~imqrs7+|&&~u_NU(+ZmE5X#&Ao7!=`2hX-1raL-J*^3JEi<$%FO*Y61zUON@eUVn8s^PCIAC6`?puD{{NaN|ukA2}MX zz3r^?FPVC5@k3$X;@JtzoM5!EpQB2f}T$?+dpy-W_hL9}Zh9-wYVM&0z2-V1W5>^#kp& z;hsjg{LWHXf9t+*!Ipc&>k7ApGcJ66ceVCZsv@8xDS@>|cfBqxk zp20`L_5&XdcXU3Kj^VZ@VDR*NhhgyKGr++&g^iEQhie`>036JQD|S}GCAU8oF1+FX zaL(1+!fP+OHoW?*^TQcupBFB@d_%bG@++6^|H(Ihdw6*1+ry47@Q*(q!xZ3cQ@ZYb<&hAZx>g-b9GNCW4B2F|#6GJL~X7ldzk?b*V?jW^vAoZd!{ zrDwh)+_&)G!kxX3gdOYF%V|2Iz`4mVaw z1DprwAH3k&hx_66_qQ?{1RpqWV6pg ze>l>AYyE?mY0JuwC>2gJCN2pOgny!2?U+fw}o_JlOcp#o#{|Zl)Z(Ih=X^ z<>9Pz&Of1d_c3g_XJKq|%w?7!RK@Lpi-`(eaj`ptu?OzSr->`c+T(R(U z!}*Yb=UlcqoORws;C&Z`uYc8=DS!U)j%QzZ+0><5cO7yWbo=ak!)@Tbw_x7ggn75M z^ftZwrv2c3Z=?)9AlP3C8GPx~W8ot3zO`519?rR_5Y}FBQP_Ip&Bw+2=$O`Dwqa_n z)jsrzPyJT-gU@~;+&1&Ba5H4jjgWsgJaq_q$eY6?_|A3UJAC)6?w$@;;N365yRVzv z8P;C0S$g0VS6+2ooR9XMuOB$jJ@lt9{6+ZhfBz5R<3In&a3kLRh9}<=HbeGKK=xh- z{p0obHo}ITCCUDaufHc;boI?)J#^u9>n}N!f7Z#CU%U3=sTT5C{mGyGdAJ$6&(_Dk zNxIJjbinH#XojnIRl-%<9}idF{9w3zavSun@p5=AH_q3bd(qU@*Ka$t@yzRi`i!aN?mgZ9)d_*!dy?eukeO!RO+Wrw=9Re;!=zo{ z`LDJ5a--h8=b>5)8EDo&RO=0z{pBt@ZhLBjSf5?`xvY4)bQ%JuA#fT3|Lzbt_vdc< zB>CaFpS7a~uqH{qF3FPbF(Jls13UazmKX2Um*WcFg1?m44c+AV_l6ozy0Z0CKQBJ+ z$I%C^iE%2l2T$RokMme|WM{TE zS^xC4$Gqf(PI4UkaHZRSE<>5mUh`WyI}qx7o9+Jk2^7Zs=l%Kfy}y0G9qmui4yFG1 zv57JNd4K+V?{DkxSbsha^|xuv&TzZ;=g;^44#)TMaj3t|r>;MLzW2A`GxmNy4)wR? z)b;1j_x@)7#`^PdsK4t^U4Q<3@6YX&J`VMF!>Q}fpYQ$olYJcOZ>zVS{L%eU?tgNB zlt0n^R9^Sv?mdHUxzsB5`uH3|zqoO-xOw*4nQGV1pXiZu{nh_@`076zt{$~^-F4Sq z`#ApZ+VRlt$Cnw(Ne$?zy`6464S~}TI1Pbe9qL&AD2LVUC6vhD@JC+v@_*)!y0_7) zmA-85nLW*){ao}%`7yh~O3zPQ-UI3h)DOMBoPOxf`AX@BckRF!@pAiq=D=^zKlmd4 z{9Q-iEnmND$F^3h-7obU?N%>;;>#?jeXY-K{CrkCZfUXc1NwfDA7A&M?pWrYL$`nD zcbu30;iB95$NueGPG6J!`o}+c(@&rMv0I*e+mGG!Ki>JFo1VV%+?x*l&+WJ3zT1|0 zXues`<1>@=8)Vt(5fPl7Sm6@sFu`UVhtL1941TwM-u%0ZUl=}q&8{SQ`~$y!+rMtO z;P$gVe%I~z)+yg}=-)$wX05xU)GuuUF?|L8r8M*v==;RFBo8_j|4!9&Y#l@O*75%L zkuDtnU+!p0XMCRD@6Yq+ct3}y|3vma~P9f_jk+C?cvMs7T@yQec##F zCX4|1YWznWW`Cc)`v*UD%}a+r{k9JjK7FY5!B2I5`JJDB{D;?l`m1r|?egzw>F;?s^Ei3q2B2B(9|s9cQIK?4kn9pjTU}N zsIj!f(t$y#zkl-+Nxxfa^;qatO3fMyX}P#iYfR7Z;q6ANU+X5*-S(i9%$J({n@svk zom$cxly$5(OVdfKG*{byJ)c#YuT>Kbr&((yeF*C&3++y=E3uvQae1**s&3pr`9xB{ zQyTr+T(MiL*SfVvlvi4>hgR{1mUy5&m))qMsJ;E-vwnDd6LMQ#1tm9tn^?LN0 z_Lg+I99h3nv(x)|w%2cWOVb!cchKrLIGR>%p-}~38|C<>xNOi%8kKgdh!fo!23d)R z;-FLPw~GUOr?l7^^k%%dR0kw;&AnQ$2Q{WR81T`#aTMC~wQjdjtrgKu%CcByOlnPhKKo5S9hR_QT3BXr=8&G-BKq(4LF}G z^=6Y^laL~D#}X*KGU$?43)OA|cdAKruHZv;ixel=|r1X*&FYYDwTfj@=y?eE0 zlkZzeP^u(zdU%hc>D6kpNxfYe^osaisL@d!^xk13CK{&dG$u{2*6OvpNjIw6iKcGS z8q5{TO?)x4m&|}a6v0TEjs8+19)V{zOWo|Lm>PgRUI$Y;?JD0mM=Izv=G%Rsp$Qc7 z>LTb1WdZ1At$l#5F;_|&gC4M2s5BcLyd}%+dc9W@4T_f~rDkWQl=RvFfdI+(ZI_=0 zohBttcTi~2UOTO(@0zucUuDtd?4hInF4C#p}vaw_92&+F4GPTw{iIKGH5EJP3AipG}Z*I8y}Wmhre|sa$Jn zE*C1L$_z*&$FU5P?7oNoLHrs*4<3qMEEie9LwbFPD~>N~5I6`^Nkh$P4uTC4P#O2d z<0-W5oqK%{a5cd^0rvR2q+c;UR`omz{bP?i#@xD0+1-*RQ1cj)GKXp=MH9|ep|I^Ff_nG z<1ECfRls%0U_R9aAk&@(QR8<>zXy492ZKw>T?ob^YBoNr+SJ#8+x6al;7+*25pxqP z2m*D^_=CMKuWTkA8Aq14q87xg-|3Y+E{U0tHdY1d+1iW7c8ZLZO0eWui{@(8;1d!%cryV6{l z=kQ#=97PBaokUSr@`@^^GLM+*ec(e6jF*w0vu@m)rAl)!r}0)Hl-V%bXwCXDHbIA* zo?#m%QGE7vw=@q9&c*!T#YcJ{amh7jf*pLUfT3;^AFd%lmX!xh%qVH>5U?O1u=!pICrsfM=}ZeZ{DGzia?-tX)5Tp0ewwAq zpjGNpmZR3L^r6J}R5Z4Z#_19?EDDffX|4^mIB7wm4*E9!`BrgZBH{0(emCiNGk@o5 zi&!{-ec{$Q7D(b;J_r&y$YqTNGM!g(GJ$XsAMEL(3RHHjYgo{-##*TOsRad~)ZQ~G z)v2c~c59s)l&Ph7gdPc!g+5z@PTZAXY?UD4B{n9=TnjC*7vUZZ8q%6t50qH4C9oqN zGT9BC&>9wb5WX}Gj4;_|Re&E$i&)XSh}-pMsteRjs|(ZmE$f$}4wAMzy(GAU%RmxI zheJWnOF*;}{DJ=1u3^#u`#`;wp%BIr)HJLVKsS+upgNZz=`p7`l3G<&m58hIpl-c@ zYp{Z4SufIzM$9Iz_;6Gmi;GebECDFBB8Qlkma^hOEYw<&f0MX35z4?5U?P?>Q);#$ zcsdXjMKn`K6E?2rb(In*je34*QKXbMV94zjmp6Vz9haq*ib$1{0=>i=V?}T6XL=CG z0Fqbx5F4{%IArZb&Kf}3?k|{t<3bqA1F61PzVxVNg3#i zZDnVB>4YF#{~qEvSZlWAFqZXdAzvZTyxg6|r3Fb}cqk1juxuf!E{2j7lww_R3~0(sH*@F7=@; znPxm+Bda6pDnSiMqCse8BAJ;?>Jv#FznicM#9XUE!cnDzbs+)Iz>09dg&p1-AggbI zfuTZd;eCo&FLYY{-ax4`mfd;405bp!asmq-uc+a_KonyjJYZ zwcA`1W4YF>lsdgAv}t020+!&BdJzD*ip%i03I0sR*W*$lzM_htt=1sHuWTAL_0*f~ z1xy7f?~(?ZKwQCb0s^oka|x*441I~lofiNtQ)dQE8ZidV88g`}VmY^jKi*{nf(ZbN zNLWlzpv=Qhae;uMo{t}rR2@t)sh8#&%_UQP=G9Wr0RYso5szgQ`ehPbxsCNlMF&0$ zx=)*C2OR+xaD)kh2gk{HoS@QgO8{$6>!$BOMbZlbR3)q%X?xSME*^>tSn~4)s0>vw zNib=PHQ9RjTclkFMj5`6>1wnuRvYuh3fND9T};qi7+Wwo`mlIF(M>8*`Sed-i?GXTNt0t{6)2rM|T*oU^)ZsC>&6elQa zjTYI$9FYP6SeVn}3Ulhi4g*lW>YUq!IY1H6n4=0#E)uI6FW|s|7OJtP8vqHIiU6Pp z4;AO7!J5giu5w4eP5lBMdJv9!JdSaEC~1H=YJ}vFy2K_2nI|D5c4z>Oa0ZhflzY%U z#KuKyWKrFkP&eORtTj!Q9%?C7vDSpu0DL{RYibCANm$<3E zFb68{cWBWa%!3tCECNDgN?L4nl0l2eLL;Bu(r-C(ym{!gP_ICay_&FXb7?*S1MN0= zz2H($8VT${Tee`)N+X&UnP7K?>H;T9e3&sS-h_crIJf(l*`#RF;D!P#y{k4{l@!2P zu|`Ygp-FE}YE@ZGId&{UVUy&&SP)d8l45nhWg1IF9S)=csH%KqJOD`4*fBG~i=esJ z7Mk--JaxLpBW5EHCK*_wzAFmi6+&rzc+tQB-4W^(7ML_27htM}BsU8+kkr6>5mrFD zBfJLSn@#~tU`l}NlHyq`LmrFY4CZCu$<|)p(1#L=yPatmX+2Dhz{Y#8z2;!P7`e3D zBn!2?F|n2yv>Bkr1wxma>+Qn$z<*CtLsF3DlU00tW^EImMNEMuLA^1Nnj zRE1#Ffy!DVSH}dFvGRa{d9LWUzyLYN#biNpuYh$6$N?lIZVx7m z8vGF?bek3?=I9_H-LzqLo!E$33R`s6L@O9h${L0vgeP5EFn{s@<5LZGU{F5a1~U@? zfqk>LG>4bzE)@l9dxbc50E8nFTnsrV0;*aEOU#!v4n#dr%a+|9NZ3>4r0esr(xHoW6iucjg~kV>g=DKq@Z~SX%1#$ zQxd|45(3(8f98IhY+Rp!d3LEcVrnA$tTve=W1}UP zjMt9P4`4MV80~I|Rv@B}bpyq*8Ez;J;PlIp-Ot<6^ z0`?|lKsdGV08*^mq>Ysdq)Y|4!~HDsX^;U+Ej~hp{M~4`(ZmbX2g-z81bD2OCdb|| zbt%F?0P5TXi+7HWH>kNjXjLRfWCAlasU9^Bs!XW@LJ1_0NEVqIp*GS!-D3?+#%O#U zt*1T{`Yak105Tef(z*c$%Vfw3v*BlqLA+|TQDUuAihehmjr*9;3FT4`9;Qy8C5%uF z4J2+8Jq0w`yKu;VjK5RvE-DUmF)@q#{bb*+DCMjaY`#X@BR@@`66nM?OViIIA z+axVai;40^;to74G72#ia%J!jXnMv`psr)0jdH^-CgNzD0ZC?ttXQ0%j-;`gVDMS=5{|8)h1V5CVq^|!#Xlg ziBH*R0<_l2TqCgD0ET$*0!9~|>ClD>?Mkf#X0L-W8t?%u`$SjZ?R_kdO#@s2l|cW7 zVo$wK%PlyWiwiJD0WVqpp1Rt!p}swhs(<>?jpS*RPSQQTj(ep_X?1e-PqK@RCp`Ozc!QR7X+H!4)J zq@*OJD!lfoHUp(PSEC;t5K>$L6*JUENmPwsj72GjhyrLqVTC$}OLNMd)#TTKmS<1m zO+&h#-;}QW(gs)hQefsrQ7q}*^DSj>$-Q&2Gy;TT8JYw}z-i3_77b)7i=5pNJ6YAB zNL3@A2dPKC0)A}vztjQ=7h-E3hSY+*R}lRO4WRn~w3S=dV5tY`(|JTJmp!Na^%j#`&|&Qx2jLQI=4_7H0z8bv{9@e@_> zTb)2bCnT+fjt*vyAqGqn{BQG~HUI!7v?Q9$s>&IWij%>{JDY z8wqJNlG;tvjV~mHJ>o0J!>F{2f6(g=<2gOwJj8_>RK+Zmh@iszS3&hEy82@&~OdB~S)5iJ2qGHphcp@T(t^tJDkRn8caE@|WsRmvgi#%ugDLF2Q z+*+nPkny^VC2NbAEA_x}VL_HsOXV3N(c~%wC#ad~Jv1f~XAv<{5DEwqVZSiC%w}H*+s$7{xh9v0* zE49m+60SGO7G>}Pxq8kb4ZcxZ#}uW}Nu!h1Nh>~pmFlg^0=P=>smqMtG_NO#ZURJ( zWj;ayz{BRj3d#+JUfH}QmW1BKkEJ9HZ{$C4-;-3nmR7ex#>)f9(;P=OAqHiWi; z($EV@NG(~_)++M;*8o&bNlrc-h#`3w^%BHSw-H}aZbCJy1p64@Z4)I*Mj8xhg9p2d z*r#Ns-JXRDKdvq!M=pT2FpuHBEC47@lvu2Bl{UB6<6k-zcs@XZw6#{t?dnowX!(|` zSNfQ#xXQL-0cQ5HXonSS6y*7Hrkmzl^oo47t^1(@H``{(z*yqy7AcnXej11EtL_B2Kz0< zm2T}pW%0-K%7{zzX5vthD_Z+l3FEbwtaob%tYmQD>qDo<8zLa1NNt>uF|R$seW&rR ziWv~Y1IL#apOlO8Bn4tDqc00F!7JNr*CkoASvCrQpveloL&e^-U@Xw&-u?+Z74FM2 z*e=AHnX6@#;S!oG*Ax=eWN0y_4@o3K;1PCFK%H00^9}N~JEY%4ZKhR?1^Q_iOlES) z9Osf)5F(H_j0?qVla_$Oe75kVKW4u|ZS%6+Rw`Ix;E@Qa;mQVjfNHW}&tZ*Vf<+P) zTBZRW!!XkVW5ewNydaE!RA~{*%Vr#7!(0#HC5Zh^SkQ_e3)w2PBCOe|=T{%OtGEXh z2^|6v*3xRDWYF%;ngY{-jBZq*^)NmrnQoU5lcnxhv`c|ZR!HbNf{t~hnqoNf-u8m( zcuGCi2L}%>$>of&YI`Q2B?3>cS99?mT~Ft*IsGZQ#c9FoXx`$S#|)TZXPnl6+f5ESP} z6T$*V6XzVb(Y7f~S*c)Vhz6Hz}Ha3XAM`Z0ztGYa`-RY4bq$&=Np`ClRaA4_9 zFc2>5t%W7F=zZ?DsHbVpLc;zb@MDC$Hd>8GYR$!XWY{z73~TAimG(fUD3{B6EPF)} zjF=@#(4DqUmj(Pj*d!_l?Zk2s(R;Pstw#T0dNwHT_G0m4Z-)!GbE5Vz^f89wc>Mtv zis~Qd_R3AIbtOZ6&>%-=CO&t!>KsZcPEp^cIOBS$yOU9VIxAx#-iuZk?uw{%dJn_E zYG8^LLJGwPWBfOCZH7!pa_x0-ly7{Gg0|{6JB7O;rY)l=vziF~>wiWk=`(QuD&A_ORQ5NyUeDOFPL&?*v;w z@YaIEsk(5-Qoq)Fpw`_ho`6%49u{`fnSc=H`FInA34MMQnL@<6RZU8RYNHJuAEywk zTdlRJUc2*}}%+V+V_XD5C6OflxQ7>pCBtoI&F3(7z~iL0n)MuwTVqjjfZDa5hoNP5j8dyK-CXJ*>W1?eau7JhM2yur zwc={Xn^anZX1fuei1w(#?4!rVGUAtk+E_t&BIIbSOqb>marSg)(ynL0sDiR27PYR; zg>h?10MuE0xQ{$-pqtR>eGUe6h7VHnrHV2zrGk)x5rJ;6xZv+CG!7ob-Z5}DZ($sZ zc7equnI2+mR~Y9bS(|cH*N9F18I(*c06oEv}`G-&Ut zMNJj#s>KmQDvDA$qpzo8zu1FNT;dPI-RU`^cMz-IhT(?BO)4v9;vo;!0_6t2AGST{ z>2+CO5D-Y#sTMwd<9>vHMRS~4W2o12(YFZKWU|DccxO=y-RaT*8W5x~BcZ3wfD1bB z!;Glj@d7Y{Q!E)ART61f$ljY`}QhPedAL%%>cJa14Q ztu`Po_TO+lG}HPtjcnN91r-_jdNsH^6k_ar!u;*@7s2ZS4GmUQs!22{>;5<%ZbhL52!m$uCa1X!LL3^p zvIzrDOEsTv!EQ|X-A>df*wPH*iVproPT3dw)$U3d13UzP}F5CXRaE^sQSNOa@@LuxElDg!}$q+MYfU@W$^2um2- z3o%@U86AvVjsc8Q$f7>cgc05~4-$is7gkMapJuV)Ilmh!i?|K8KmwO|NVL{tjRfGT zbH2Ua2SPpT6{`rjK(VW$ClDB?i9qwSLya7$v@j~YaZznnqWB1sCjD~Y39*IiJ%r9k zI0KQ~`$ZK+rYqwdWY5%9q@N%j9r4@dixShxQG|_*x}OK%l3&GE#nl=Y9d3e<@P&%= zEZapH5ly&5Kb{ zaTONgaWEeZ<_zABZ75-&0Bu&ci?X`ehO8b#5Uk09O%zrj{y`^u60Q1@L>7jKIgfZR z$ZTvppnO8?mmhQNDqayaH9oHaA1(w>iwaVdqLDXwZ5})NZ1ls2W9NS~bzwn*N3wDt&J#>Sg#0wrn9h^ge723;E*UE5oSE3blfmr((irV9f@F#6@8M4#N`WH0DZ-4<#?0prVHr z7xw1SU8DWWu(4v)xmMweTsclHmT2|LRe@FYq^q*)qqkYDSuYxiE*g4&ft4-xsG)O4 zS6JTU0jA~APz!Vyz;gJix)=l{#w-+%E@J7qWW+`SQ}MZovngV_a=L9^Fg1J`!Grf8 zY*6+ksy0|NIwj_4!={t;>`B5FfH7jAtKL>BXksT|XU37@d3BXtg^>7JF*t;ELopIY ziLotw>d-Av4Pju94F9NSjv~H}dY$bz@#l>U$oT9?BNS<9i?DrirA6N}7q}A2QF>ae z4Uj~4t*^DE!c&XW=6rKZn>VDGiZ(k7TE$!gqT#n^N$z%)q6)#j4h&$bH{-5pI(>Ld zC47t?D2dfnv?xc`?M$u#VK_6~6BRWY$#(4wg|bTnlGi@+EV6QX;wcSGnL z0#VXnFSz`m3L1M!3Sg6rx+OQ3Ap*O;dYIevM{)rOlLc#V`5*)Ud^Bak+C8%wmYq66 z@aUU2Ga@FjNr+5Zi3u}N1-CA0M%z|9ts-RK1BYi0i2^NW+&5N)<_Fs;y}Gde;cRzM z&e|B0ho!S!0~bpjTd)WOxYInI1Shcph1~uI_Cj6-u?>+A=D;^iOV}wzu9!NMT*T<@ zwgL!T!O#iu9@Q?#N5|XKI`fnuaS|_OQ41cp*DOkzE!gQ;;3}v&52}hR&ulTmVSff# z?J+jpgVtcdLqL0O{C%vn7=#9uowGTuny)sif}1feo!2nrnlB?rc$5d;4BG?wi(LV6 zM=NRv!7CWB!#9J!Tfah^I_&~MdJ0t{PlN(Ff_*e>@B$fg6*0Tm0EA}A&;@dSDQ@x) zB8(X~`B<9PkJ{{vy`#D#EpMgf0{I@7NGin;6_@(#6ZF&qUn2O^<{FbD5(;Sx-(}(ZA#9WgJeLEcmLdKG5NrD7Qxw$>j_#WP%2q&ESu$F9WL(RFz<^KXEGtHcm_Y_c3D}U`To9oE%ES603axB3+4!j%GC>12i{~%Rnui}7r;L*4 zh#^d7QNK}>)UGpXhwM%W@D1FifQksC+O9GtxCUUSwZiZ_OeF^e0%BTPq?^G_uRq$E zs2=M%WS!|P`4fN$WFWWgc~?28GD=h%mE$rkm0!MS=y1<&dZ)K)dx}5K8)dl@FHM&m zLoemmbCzx9#F4`X3wwAxp$u92w{C43(@H{8B2Ban`k1x#cp0?sT2U->w(F|25SRCC zbf1(M2US_8x}lS{GE$H|b#F|)i2UeWfT7pgq1wgGbKL{L3-XtX3gP}LFI3+06!ih~A}4{TmQDjXhl1q<9GVOAAL z?M2XiYbn9b4pr>P)ERPyVrxs;ZDuSo!kkB-F(!G^@HFBg2Z`7#Q(s`-L1>63T};+U zXDcG&`O8#JIB1bhZckAO+dEhYe}oe%Ld(TK%%V@@)C-4Qvzi~kc$5(VS#-$b)&FF*?C0Md?#o{|2 z;sw~Drg^6!Nf(@+K{647h?#7VrO!+lw5vo-mq87&h(HUUWm3lJC}(FaBsfCQej=nr zQm}rsptJYDhD`K8+MA?zL3<(;YGzmZZ4$4%Y7;{OZM}UXBq3fGZn+z=qYP$ndW zOyO*gx?g+-%@){I9O)8{HmhSUf|@uE@J57>mZ3**0fM5LL(&4+V|t271G)7_OEy{Q zi!%)QFh0mR%*R13#4j=+(NM>ZxigyAaPcc^SW@j5u_<4Hj)?1E1#ixMMARke9!yPs zS};pAL6_;sv?8gfbxX|EP(<#Jigxy~6kptgjxT4KHio&3JNJH3C6n;=ekSk)n zrHYD)#ydL*zQAR?#e1NF+7ahMe#{bdeFXk#X48Sjz38yrcs2>J8S5xv!U=7XM`%WK z05_^dc=5q4*ataXFpK-Jt!sEQ#_vh}3rNqxfE+ByWUxdm6?Q0K8;OxRh7WU%*Ug?y zMQJccwqvo!Dq!V9PZ*kzrVA-MtcZQKurgw4fw(&8;yi5;nN zCDj@b=wJh3%p5L2^kHiNA}XK{@ER~_P%--DT2j!>8Ng)G)e{vk&-td^WiSMT!7J=t zPDS!cHep7lSFtE zh!NI{h|{(gL3qjZ0OT$&H|I8(CnhpWH0qEAO^{JVzM(-_SeT*u)FkCI;E+KM*92&~aIyuz<`x*gdlwiTaQUO~}p?vm~ z$b|;J1~%#-&an(063r_*n4cUW95Shx%(k*rcpwh}Phz&vDzJA!2_TuM1zSb)WxLSC zI6Np!6A2*zx`wE?tF3BuX%xj>81zzD4XIFKLBy%@B9dg0QdI$#I2gM~McaxQr6ZM4 z?YU126o{&zBOa-+`_a#dY78PZPF|~1a!GZFfvpH2#1gWhr>GCr{2A5)`p$YrW%#TT z>1u^(S6hAf8qRfSZb(~^Jt%7%zLpXed4#hIV}oCXPyx^?qE|5|coC_cN2rAepRw`+ zkbx;W&9t+LDzsN+r7~Qx;5>7&1<yUCP`!D%gCsGNue{I|vNY8EnYFlt^Ep(|`jh?bvi8 zBhF%Nu8bsFgpfvHQ$R-Ed|k3eD@Oz!<>*ePyU6EaMmz{W2+gi&;%KK+FFyM`>IJmP zDnGW(N)>ZS3FE*?)YQ^odgPN9Wu-u2$qNU)V2g{H1~0R6ZisQ^p{U9@YHOlEH1B10 zpOUlLXwlv)g>HIP=^M3pw#x@V*+>ulNv%|Yo;(gxyz3bA)$Do|RD#`(-HLDFV0 zj3$QE-LxgDjChhjW^k|x0_BL_8=UfbT! zFS1hBr`KbjxoYf_RLmPi&FN6B7H>)`@s<{BE7N8<#w_N|wMD3&W_?G}Nw$cEipx{` z0He@;50$jrV}=`~1Qn`byhF4Q^>Nl|CGn$F6IM*eVu>bywV3^xMXhRCuoWju8T2Gz z*rY-p%r56hlhgB*alI@A#l>(Oh_OU={rR%ds|YDrw)DhzE%ucYlI zN)(;76aeYzv{zoo)@ZBo!Kv!Rp$c>rWFYY?tJoyKL2*M1fC=*#Solbb!jZBzJ>{rv zFmLlR^O3S-P>T*|Ho$;LmpXl@tlHM&HsXWQ8aE^kRdN{72*hbdYi*AI43Q^A1x#lfHk zJz}^4F>4MTpi&mOJW9QdCIx6QZAf$=cEWWLRN$dQ^qHFk8A zGiiTEITzi<0850EKhAp}zQ^QG98nZT*}XES(PO~aL?-BmI6x36FZUKjg$_5sH<`OY zv19p$Ow{``vJT@UmkB0{9+=vhQ?Xs<(p<}3?5P8T0=F?=Y73i0=oo;Vhsy-5xMiD= zQ3=aYVcb@x_N@~wQYH7TRd}v-K|@bgL2f&? z!lucyvXZcn>O$Hm!WP>c#*%bBB?V#)E^cvZ=_D!tlvI{6Q0&x1WL7tfGycXIZZ;7Z zsxG~iD`zDf%LHtk;F$y+YRHlHNINxAzAMvCdO*Y`VKuVXoStJXd^NJntcEe?YOuQG zY7`{7s`~|88qpF^EOU3iK(DI41;bucOJ9HFsYUWT;_C!Yes=-P0t=s zK`OI2-RLLO%co?-Z;{B{#B0;mOka=mmo<>KKz>;Rj7V4{aOPk=ucsig8^OW6`qy?Dd$Wyrq72(nZt>C)IZ`Z}@MU%-5!6f>|5 z^P4psb-vMf4qJ&2I!?+$y4U=@AxTY1?ZY$F$7%`NClF4X^l2A^eu>z51U(|Sg&E6} zJ`kM1hjM_LCrSVww|!tsaG!!8;m1R|AiR2ld>4|^D1g-^Fgtaybi%!GoeX*^Vh7{? zNjMtfe87xC-aLl#(BzGH0onh=TC@X5mMU{%;Mp2K?VPknAc_VV_^1Et`#t$qG!Y;xZe6%E~Qj(I7HeZj^rkIUWUJMzzPy;0vYZ?8}Pode@3C z=45;t8E1;I%oN%p1?uxk)FP)7w?5FhVF2=&8v_9h6ftur-oFFA1Ru$UU_n57zPhCS z7;p^3gjt&|Rjh6{7`e!p#zTH1BF#KH{9>BMp7JbLE@uwFNl?cd)_ji_%aSBNxVpR+ytu-dLW~ZbdXrYXm zX5SVQFQfwkX1bTP(22s}D+Zavjtav@OryxR<<>t47-mF=Akl8Uq*_M$8kl*pcY%0W zn5iLy9<;4!A;U8o79k^}HB80|kJn)mvT$JVq&~Kl-*LmH7;7OJ$hPaYahP=%xw(p( zfpi?iq9DDNm9;rlt#LP`%5k|M%C`-5m;zD-O+~GC8VUZSyC9gV=w&&E)X_X>455o) zA8-{(x1-X)eU{RxV2gyg8Roq-aBpI`I;j^Txsg6JS2Tq=BpT0o6hKh`SKyLVxpKUM zxra@xL<(Kc)hhUf!n$c%(Oiu8aSSxPFWC)r&2W~JsNpFG>tPAWA?SD@& zFcWGB5*5xUqL;D0R8wjLAhwE3fN2B1QUVVjPNm^%MBKzCPH^*6%72(uk@<`Pg$nJm za0H@{vK(}j1sJ8VMZFGGh8S`=UqyqXpv|VigJ#Y-yIG=C>r%bfU zDn=4>yN3;RZ44@gJkxxLEri7qXq|Ig+mBLm1=9Jkr`Vi+vWE#$(UFuGWk^v2w(S#d zqs^d@>OsZ<=_1YV_B7MF!*1^3!N!KClQ;c)^8+1U?-Q@Fy{>Gz7x%73){&4%}kqbmADi0V8)>6wD4VkX+5PIexb8v@jif=jZZUx zRC#?&v6?!%btZ~6cYdpl6Rd3B;Ngq2XkA?IyB;Xv3?xTAozJCn)C)Mt!TvdQk9uCD z%NN)}dXtipQDcnBp^_+fDD)Ssye!fiJInCp41f?0PnkUxf5s)43RKrrfC55iX^r#1 z!ZW0a&@T&bJM<5p;1PTab8^O;ipUYKV6Auw#t8p|nPt*zNSXW2+4QUadVxZR+*QNow!U2bbc&tQ`KUCr@WoCQ{p`Zd+K@}v0 z52~ge%OeprQnR1fWKnz6M^uJVgO~|A>S!^g(K}Z&NHyHoUS3L{Z`L4FPhwdbrpC;K z(MAoJUEm>PBVerJT5(K@&8Oz7y-w7!3iF%rw;7Q&@JP~2Bcc+3^A(yt)o9Kk6(dR_ zUO`#dZ>+3VMyLXk2^{VOla5R#jhG&6Y^_aG5zwX@m~OZk$kP@tdSQv-ZTzAuajP%8 zatjW)taYq0$W%q?$0sqh$1^S23xGgcg_rkLg07kJtRUmdi?L6S6!_6L1{20TmD&&i2Q{Ruc8L}E4G2Ah zL&Xz#m_yVORtDBiIlvP-!pF>Si^^ZY!7A;OEk*F@TVM*Q2(%-{zCa3#n&)|={$MlG zMu(6zn4OtjQ<17>1BHT*m;_7=rUkV!_R<^xZ^Q4Tem7Ahh)LUi7JrVGRuG8LB1x?r zOS_EFD|@hrN$aWfT~&)OjOl_J zcCk~4E{(CxU>^8rEP@=crwa+b80;0bZlvTcbJ#AvIXy8_5C$dV8|5UxYK=*R!D~7e zT23jGyYI3Sr+@+rMRkh@k9L zMi%q&$IvLXijvWZ*|^L!N)6NM`qYrELyb6$q-5EL;>Oe+VzLTBBw@EI8(5ZRbYXUSW==aoC4L zk5AvgV+<=d97_Df6tFLwA_gy3`4v_{qzCY~WoY-w7T!B{#3 z8z`}H0MaN;05M+4aUh8em(L0EhQNjg9N-dTBP?)cO!Dism^qfO5c#%k>vXC!WYyxl zmgJUe5ZsKTN6;eP8j*DPfq4txP&Sb*6%6{NfBJoBqb;p6VD%XFq80iSIt51pcmq&P zZ3}6_>`NlDU2|>|3f2~PEm{B(?v|cnf=pl$D^yH8B`EJ>ZWA8mhtG7JMhh!;E(_%a z60d{J60*zgV%hIx*+5Nbv!)IfZ4w-`0|IGuGc!@>PDI5un-luQH=StA-QC*fg-5M$ z|DYe6P~8x~7!tW8ssfk@N~Qthz$XLW`= zTOFSOgn*P@f{0U<6%Wml2@sYP&yEe5h}aijW}B7RhO%JI%>4Mc8%=R|pwbF+4`+;{ z1OdW+DelAx5lhBEfCw3~vYo^6t|DwD7?-{Z$Sb@YpQ)WlkYsRgY0{}A8dr&AU<_Xl zFzn&XYQ4JM2g9|lE%T$qcn;_obBu`N5#%8~`1` z?iaVO=-naWVNtS80&D;Z5SeQW3)nSO;|P`H6hY6k)_-GG_CUruL)V}ZLOev5foI2u zTOL9Q>FEY@B18bfj-^E%<3sCE-Wbb7zK8Ua`a~0oI?}?)cj0OxB5ym^j}=z5nPhml z<|4+@k={b>bwK}k38<_x_~ZRGMqA{GfU+W2!({KfXVUz)MJOV>ONU62((Sq!n-oSOW1l9=W8{jfM@hD5@*&0FM*}A?;TI>F6wS5y0AV z)+`>}OJ=%u%i?}mPruqT#)Eh|MQ5%@t3=s}`%FJX@)H^Cy0J{9(u2Aeyi z7lj3o2GK7@s@)xi8wdz|+nihgd&DGyU~UKNL$Xn50Nh{+_uoGLJj$QP@NJBJ_I8G~fsel5Gs>cY3`yb|;j&)R)nOYc>; zLwBbw@&2JYo}Sk6;BDBRoE#)lki?UAWc%*YUS+HT^eVHuLM59})TKQmOmyXIABN?$ z!g?XjVr_(I!4O7sJ$s2PNo6W%upon-NJ6qeeGvyTsCX$=Kk3yNosJOm@l?JK-eF9M zsr|qfrFpY}>!E||BlnV&J%%2drV0}dKk3K7NroRZrLJK`3g!eZ06PS~r>GYeHwOtZ zy2vbN@)Ls&u;-=?S0lfEp-6xcnNT1*IJ5mjR09G zka8Y=BAW4(!3YWld`uVx-UrJ&y%$b%;i=DyX^q6(OuSRuCmN=U8NYXv5cW1Qr~>OV zrAI>&d{&`VE+zw71-LU0E5x~pc%-(*`lfi?jE`7i{Y}@ELW2PhrJa_jU>ZQK1Tg8l z^ZYT(nSH+6Ye*;#+W<@pwsel)=7IVv-WS)?vM?!c3YJF9$ASZvc z#l>^FSB}KX%~tU=*JT9)O0e0$jn3L)z#Q%y_*F~n#-^CJI<~Vwurj34>V}Q<0(|!u zAM@yR@zbl~XMmq{1!x6uHY=EUT~=9()#KtGdw3LkhNU7V6INTwRYZ|(Yg&>_6>tT( z(y$&*Lujw*2~5zm3{DMst<5fkAgq7f-N8@tBKb4i3YLmUxjGHrDyB;+uo_u%$hoZ` zA&>7MSmH%6A}he?%ycsrBL~z)+nV{JP>uGr7^VoV4^tPo!CHWu2(@vp*O*2oHL2Xt z7g;vZJ%bN+Qk#M$KK;-RRbZ&T5tGJ8px;NwmZ#}u3u(sd(zv7`;1ksN0Cj&8KBf#s zPhtySJwU=*F4MJQYQk)bY_s^jk?A_g;zY7InJi5tOZc>RsZvB;2dkl-HJmHYibS#0 zue3q2#e-aT1CGp!la$S?16IV{cLhxkBCoi43mGQJ3Tl+(D#aBZ30W^)fpb5>U=ps{ z$^2mh1&?jQH$;&l>CJ+%5f~`+xt_)xM-NjBpbYCGIHW`h*1)WDLChmk=;?@0R@=A8 zWWEq0AOOvn(VMkTQNd9#;D^4Vt%6;`TT*Vo%M9~|=nRo!Wdxu`Q;Fe_BaYUMtjL6? zkR{~oa52L05eE-{%z>nb`HT-S=E|^dVby4n5cQhvsMjD#*mDDZIEijQnm6>NJC({X zVQ8CR?4A3s^L1T`AwlN^Pt}fiE(2i$_6jr*X<}{#rJY2daS~JsoZV2f-8GnR%Dz1)t87etO#`i^#I80JBm-e) zsl*5{rcQoYgMWBcNt?j@A;7_Vv1Eb~hFV1y#v~(}lmcmd#gWrxq;6Nx3fDUl$OUhr zncU!S=s~<9l{x~&*5fI^fhIuH64V1G7KsWaVlhZ(2rP#&lqG(~2&Od%8>q=(Hj=e7 zRq{wUu&_fJ;zeF+Ogk&kqF_l0Sb|uVVOP8iqEXjUKF}7Wij|q$JKmOShz3Oqx5b+aN(_}TSTbkPU<6*7R*W6`sU>i?^i*W#F!kX( z6G+@)m!{Qt8dw1Q@ot2*_LHY}vm)F9dNM5;a0;a5O|Xu|r&@2kfVm-<5Jv36CkOas|$O__{*NbXy4VJ*?`CUp3nqU}tP`re@>4xCd@gJ4u_UKGw`#h`J`W zq=Lkru8&RdBdk_cx(+T|!Dx_sG0okgD%OLub|UtqR;BY^;v-bmbA%xge3}N2$saYQ zn9A1_Bt;JyLZgt3>p-kq8CNcuSF9(jrgkmVxw(!}MERn=`IIIXuge4rK@rDFgRC;? z;^ktThn9y!d2P5}vL}In)$aNRpIbZ392S{ zr$RFuz?EOnX3EB#jOYGF^zMK!Sjr3A(+IfcKUNx3PR8{(GcNl(YTA&U>&?_H--hu$ z6v$N1>`>&Vo$&2etcL*?E+cpc6f}_oUyg~I31fti4L3$`D(I?8(I*1~)Z8|HTlP$pk6|7dd;Rl>`vQ;8E|gBt7=#`h^oP$ zmTQpem#dp^g*%Xax4Z81N+hG9wtRA_LzQL5e@4*(eIIov=y^qQ=G7CB>v)9H#VU zau4_=7)U8P43QJ_gzjkPodAKd+=2552l10r)CeBC-Do3#7>{Mz- z4&>BOZ1-qkYLikQL?7zeT4Xr`Kt9Zu5r7{icYHHF1o2l5$O-l`_@^!D{;#aS=vo3&1EYx@P6!LK!%OZW7x$ z03<8aS621KCTenY>?3@;eg0>oWR-pAE=)Dly@T(3d+(ai@nQ9PT*TXVqSz-KP- zr#{e@wtAd7Rj5NYo#>I`(jP7zeyajLls2?YNJcq_sdZK@_!aBd8JMB;F%o^%A_9@= zTyT!djpD3-hKwJilotgbGDw#AMXAW-L7|-WJn#Cyo%R~ShwO`9MMM@)xmA!vllZVgQiFS>~EdN}ACk&GjtZHV7}=uMK_8HXpI6XQ2}^D!l|!5S;c<#u z8NuMN2q9z%m|^CwHa_u(#aS8K^trE<1xhAt-K8T;0hc_gA^K2QM{teKQ&UPShILX3 z@4$=1B0L`E7DY45@)v0OFda2*!segm)+H13a;WD`WBzF7$#gL75|pOB79;b`Y!l*UA%-kseL>yVt&GxS*VU}iLx z;W=W{WWLEbww+L}A6>#yH1;C4My8;6jMs~?Q1>HC8q=fEmFR&D0#r9e_(qYU4sfzTYYSnFU$DX^$KKa;Cz3{Zy< z1prAkKwtsi7e$>=LErpLn{2$XyAI4hJR|(UJ~``oj>wSA5&48ISmh7hKY^(>KaKqe z(@7V0#~9RxPmV;c3zj9@6rTzB^IN^KfqEBX2y;zJ<3}7qCMjwG#@zVo+4@PrZW`ux zaP(yRe1j&&K?O=Igm5GwN^5Ms1yQnK=dB1&sXp!q2q8Lk8cYUXxiYDNX=098`Xh~H z86lAE8PR2R-0XBhHBbzWS*pOh^s&R3OCHi%BFY)5SJU?a1E${>DcYIdkV-Fkv+JF` z89)zn4U_B8(gIPDN`KN^BlauDFaf!RxH#gy2;+XZ^7;vlC(yA93yxf(Z)y<)9uWiaU z%ChHygJD+lacD9Ak-@^i!`J8Jf-c@>N^kiar#p3f5zH7^S9*2{6@E?>TVQf?s%hqU zZ+sL^?~Unha>1UZb%KSZGh~r6k3w9TQ4nDPxsN@>5iK5EOlzc&kXo=gWSGOu@Zp!? zOS#Z)^$Q7r4ItBck^TSKI&^WJ1nWGe{;HyrSWw4Md`eo77=BrK@=K6#lb`UfeGD>!8FiZg_ zw8c{fcP%as#;64QvM_o#%%EUzX-btYwYz{@p>`PhZY9jnF`X8zQ$o!hejFckHvcSp zyZ}i{;kT2nCHbZvfKcep(MCz$W9zB(W>I}Soi-*jJ$+bNIu@6HpdPGy5N{(}k9@Dh zH`dy|Hi$JYd}C2F!KeZo_d0OEK?C864&$<&vC4j6VmR9+f~_Y=RR@lZ<)O4f`^Fk( zhf=P^G@V|{h8#~j<=S`A=tYB`0tEr;mkvd!kXFEF8JS(ITla6AaRwtsDC1#tRA;q1 zoK(UiBEWMOSxjNP46jZD3ZI0J;Ay>%JzxGoJWUV(TAq?%@QkjqB@(7LtV70K#9E+? zq5-5Rp$YU^dS1rZ!$tr-f-%?Jqe~_SHxi6^38bmOLNdx_ntSXHUn_!@B4IdkT!0!km0d}&8>yEZ(_iI z{4@%)$#RnttXc>mXk-6c1f^^)w1(IVGxGvI^rn}mNxK}2cu(yIrAH9z+;mKl2(`#I z^YJBM@I^*l*(>5(12wj0CylFuyEODU+WeW!3IW`uu zD#EZ~S4i<@?+EDyqzQP>CefUb01rMRyC5T!@ z7t(ZL+mvCd!7FQ`x`D<37maWTT|phnHgqs8Pho+ogE-BZ6`QpW27T#7tkA_wdckt` z|EKIN0K2OG|NnE}dvAmHLK;+5RM3G%DmH9`fijqEggF_E7&S*@fQ^lf9}62>v9Q5F zFtJ-P5W55W|9HO6z3+hG@B0@YyQk}(e4TUd+xK&1_o_*aSu2Wk#A=ub;O;XyKK%Kc;Ur*w=sg4IWOX z=xc6XCT$BS6-+n_A+VYDc|MIB8YRsjECFiJ1O{yXGjqIdX>Hx)57&`J{gOLF5N!Y@ zcMuRnQ9!=Z`om_bhOE*3+Edd;Q<;0-D#@|&-zz2Y)*)mQP|(HbdlG!=+49cA5 zOQ3XV`IDCDxkjVkL~G#8Djlm*M-j2OiAs{A9-Kwt& zUV6-h62t<@(-1hGM24(OP!Ng*VT8W>;bS5Z7Nc2k#oua;G}U8g%$>_Lk=cRuGRYt~ z6>BmYUjfVk!>IOzIMHn<%m~mSBebKV{&1D)v<|mxQIQToop*-~Zmu@PZZA(kiH=ox(CrV}VH?%@29lp=rw#FKx19F(!zp)(SpUPG-B4 z(ZHKqHA_i1BH@#!#E}eI*SP#RPX$6bOQ$t?Y8o+>pIDHZ+Nn!eNhR)UMtOZo#mP^l zLXMKc1l^fV*K@WnLqC_{3qcBRfhug10u6NIqX77M6Ib6=HKx9s{*LjQy>8r=em=m|;h>qWDt#p{3h6{^GOXfopJK@GcUVeE*3nx?hHB)HGl$dI+ z6wy?XJZkGuzZUF|k$S0l_}vt*!Cxp?PwiMy7i1iYBcu#JZ^#^#S&~(CRe5%Qtdz0W zJ_GFqNxfC6naq}K$0F(x{Mv}rYr02>exFp;y@szwsK9M&+up2tMSfJ=t5YF)J?+@f zXuVd|Rv&cq=S;X7S zH9ERYJ>@5O7;>UL&`1iBwg;qrfs|G!<@wbC21C_sIx&8AiQj0gr&Y zZeD%Yg}9#r^*)m(l4E)|wnj1~KMbQ=5sYR^b1$Vi8Lah}Nu6KaPn$9(X)=A(4C@DH zv7Ff0m3uqvBgjnUPFn>60GL#A;U6Y2h-{k`OY} z1X*OdNj=xkIJ!SDczf(cE+{)BHIv6&Hm#78GD z`JKo#6R)uonYO(e4T2mCmMbO0MAV_)uR`g<*=Fif{6en^P_0Y*_WwOF~nVL_H zpN57>OD=)DxIPN0hD)t8C(x5d&XP5*htd_bPn#}>iC_?l(xVP2N`q}zCpG$90J9!u zjMT*NFpQ4FG7O{{*l$>PgD`OK1fRA6qtkpFeeELDhabBz89|tIRR$ymq0Y~eRUFoG zv{29#L0`8pm0F0LYC%1lpSiM2OyRmnRngpefv8t%;Y0ZrfgTOd*3!#doW z;99%A49%C2De09V!$W>ZoAc?k58iQHg0DAD=Waa%sy41zN^5^*^n`jo;ZCR%ySa(o z-NYUQ#!#=IFiEMqON?TzM`xoO*rK1x*>U>zG)oy^W$=yoD*fsV}K% zT${IbO;m89G4I=c-A|EHA?1(hnyv=h51pCX%Aem|w68$n!jeUAOo@lT3hWDGRCL$E z2NCv%%7Fjrbe2issXqoEuB~NcjD2OvsC~tt$kH?<-QPcngqhL(uZ-9u!;MlA88?=i z$S%s0weH9;EP)KOjFN~PQj+?(VWf=$^92-{T0w^CH8o3i3ysM*ov7G9K zxud1q<^}60PE(}SMJB9VuJ$RSW0uCxNJEXUy)0j-jj07P!&|tl$8o5V8G`CG^OTO> z$PXx-V@SH-hy<11qK@`pqgH0uV{I#pw#91Se=k4^{Oe(rF#OUC5B&s{*RgA*zJpiK zS~lz;v?ZEeB$}#9nCVZ_E8XEKNQ5WRw+OV(h)iuTPnMCy7WVsSG~sB_8yy-(Ui{u! zbXO=j9EJ&2z2)aN=6aE|$w<;t8-6AN`G^%dSyKwVh6EyDqz7R%BzL;n3*M8R^#+?M|WJeoAx7#82mzsXjWiWz&!}m+Hgm&-7`f za6~nYNqm!n!!ayE{o2rnE`4gn>Gya1Zm6X*oOiM}j-V#PV}?<rg!k z2{V#{p>Y16R^CLK_{w2wmA}ZCeC}9f;lIWO|XjfX0Bx zn3j?#rs=zz__s?v!jf=8V8T?brP0%Ug)3}2wdt7)O~1OLGgXJC;mUvC$?F*jku_?1 zVk(V~>R9#Dx^^&^^Emd2A)ke?bS-PX&{eERQGIn9*|Ct}{vMz*pUU z>mrTGD#@;UQZ4go$Rwk4#k%&FX~3|jb{LMhq?=1LQ){?zNCVO&Dy^}F=X9)n+wiOF z#?>6tumyj*iI)nbOt^Hlk()W82b*sIyn>R&i!W}i~mG1NJub?BK? zCud$1qJ5G$6n%`D*iaoE%L(srkVyixpmp%c?@s#;(QhI#UGvwgZQa9~j$Te?p^7yU zI=chpS8yr;22uZG<7Ssy7|SkAhd&>^%p(<_OqkB5U35XnI^S@;KXvqU#vdI=@m~?+ ziZt^SeJUh6E~TpO;eR5gJK_LY==W9oa>J_!*LFo(3^)Qrlso!D@>#E9mz7}mYSj?%ig)}DRm3g z<3`m-N*Q-g8AnPP_edF|)ZB_0Ed#ng?5&Bc^D@A=4fV zo7|Pv@JchGmf5LRMqb_OPSdAKBjsjXEvM?IGhIm;*-+oJtA2qvoC?c?oql96(MRE; z?W}P2<+tB-{wDoWS@@MPBx^b(L2Y1_ga@t=Y9hcKTT?DZWn_W2j^(q@3^%-07Qb>D zekPxLECLz$RXL2;o*9gH3z+dqp|?erX*^@?X(j0=vi5H58)o>{kr)d`K0~ER!MV4@D>S7# z5eqb0c7`z^z_Q~DcA4K)*4}wpVLSKj-}Jtkho8id1N9!Nkt(Q^H$Os|AXgm;{kwLV zSW`%RFQvwC`-O8qF)m^-wSFWVef?oJGQ#N;lijii&`62sFqJEQh?T4TwxahfAf@%c zjLsCoe?rsG?Y+z7Ju3+w=yOy)Vc+DOt2(rzUtyNhc*GYf?62MH=emNf_iKcp!(^PA zVSmR?nu^GO%+wiF1ljG`vzqg?kz%IqZ4KgRxcw>BX}CeOielR_s~z24HDGji-Dw`( z16c#<(Vwxdl+WuOqOa?fa_~pq?VifiXqvA8A(Y}~=MbBd{66Qyu{*{8606c}Y%>!fgmUOJ?I zCEsge@-WSnn8c})#ar#vjSP#+e0tLU4%3fZlBn&xvzNkxEFZ+pB`QpHC99KK7ikHOt>@@9 zN#o>23X8wezK2j!QfAFk*>#n6!$BVzu{6n znDQ!n_`l`DB^xO3hnT~amzo&No5+1J<~}uKOlRACRJtszp1!=l`jn{Qy7GZj(lnKl z>W@oV`mjgT+9$&;)=F06#L1Fpnk%Cxu$NS>Gu-{7DU>BEsq?8HTB`+-D-Tm)`AVt1 zn^2#j@mUOQ2H9!W@^Jd=v*l}*UT20m??CdY46{KD(d->&nE9%i9%8Y+be`cxxyvx< zt8-l$Cgl?v8fZ7^;V9*mT5M#P7Ap%GCYAz9TvKb;Ul*Y=tj(m9?*>npl5B-$#%r9F zY0{4q^xEJ|n(8f0qVi+}IBYnPN&cN-TFOT>nFM7ztu#?#hPx8pVury8mVp@teYGde z{$YmU0Oq(E29;CC@?ps_nWb2w`}G;l%*5H>$_bN`88ZXw(4?e^^*1HH3sWcqIA3NJ z#QU|+iH1F){MjB;Mod<@Y3r_d_yFsjDycpjmtAPrpB0WZdp;|!J%-GHXfssD@I;?l zX9>rdtk3YRDZ_OIGZr1QspLL#?d1Qka*@k{Y=%g5n&GzJ?D|RcGZ|)4Tgx!Cs>3;) zMh%mt$%~(u8Ca?V%kardVKi+dUzL(mGOlL2*3aKf7`u@nv*=kF&W4QMxJ=E&*QvQ)Z5umMpY% zt73hsC22F1Wx}+~imh%mBSxwolUn=rw+!<^qtt}4YpgMbpH-h(>n%%b`NC7!2sX0H z2y@u*P0CNz*?eX=Oh(?w8y*qOjWc|V;M8JNbUqfnmFCB*mr3+c;)lKi>IDQ9H(`AtPDgAYmiA)UL*d zRE7|XpWM*k#H7UynmWdhMt-K5oDHN#+-l`SLkGtT%PPiba&BF{rJh;cj7jy=EB##z zSJT&vN@^-t@}Og$H+;g}Wc{frXPa>9lnNb7RyRP3BwTUoM2qP}HEWBcEkpShCv%=L zbB5Hoq`HKO`H&iQ!fxo`G8YXLz8I#tiYiM~Kiy4_H08{nB6Fq_uCiFA%TzClw3;T) zFAy=w8Z#%HU8AZrNinV~`67un!>z;dUWZ2;G$W=qa4@j%%n2p*S);9+?%%(>zII$n z-&eosW;Qne^;6kFlKG_O8RSZmnluNg8L^+BS^yMIa!M-)$zn~n@I&RCq+KzG&ds-v zIZYW2)m5xg%KZ@u>n4&_z;soN3^sMOo`AQeYYin4kia#_7E;z;MMBb|TGUN<~6tf=;Gs>^gXj&)9?PsW82bHngQFKVlk z=EL~yiwU)U;+HhEvaGb@+I~V~bN48B)~MO)9nMv4E1AfGuu_?;@G|;jn9(~KHMX`d z62@u%O^2pVud+uel~CuMy;Z+{!~6AP(#`MNM6HaqQZ&*7y}_*#L?7lFi81TdQyBEzW*3$omi1T>VUlX<^doNVMuZ=rGN;nwT|NHK-ws zSnFzpaiK0*m%>o3U~QoyJqtW=;0814`Y@OepFd+5(j~YrzjdM8UUfM@{y2TDoN>SSC2u z<&H3sUY%TTTK8$XXbPouzt5P~Xj-UYLoYXE?6k1wuwT_RX@I$-$6;TT<(w+|Fq|TZ z80&SJEBr9gGbY$N(m(vFb;g9~Ibs4Ugz46B^aE91Td8|nNwW$`{X<=qezAAhKxa=& zfLCf9HYcvetQbCYPtMgSza7`wb5?hXRH>DcLd^1y5J%j-+awuztu#J6G)BW*_ zIhx2>J98uW3Esh@qMurH^3L#-d^M5Y5^RMUndohAYRW`5^$U2RQ&+=l)rGpgL#?Sf znhq724JIosy>#_{dfIZ4r}_&G(^i1V#F);TRY{^fV*(=zGI(!PLdomr%m@^j5OxxZ z`A6g$6J~jh_9VCr#ZpR#;!j3fqtp&nMe!EC!dRG?l-ZAb$%7S7n8&2&P;ahhO)k?< zl__JhCQEi#>@Q8LD19*2fB0ciOZj?}7@5j9cA1sf8Lt6UaFAHPac)IbQw6A*BH*poJk*;pHU?nrbkaL5NT*L zYh{q^zSCxXp}3QLhtt3keS(Im8Ir@AXhCkHnm0<#C#~Ti`i<04L zhUzyO7``S_byB8-v{SK(X(gwDH+ES$YI5yxw#6oA__y}4vD0#viKAwxN8^hw-GqoI zS}M~GOA(@OV%VPwGIf?87*YwRee367Hp*kPjyOn?^YoBQ^pk3tj;*>48Jq6Pa-;Kk z>4p{BwNE!7>4S98E8UFJ-Nek7;zkac2{z&~DQQg)(`S5>@(9KGCLKz5?%NYx6tl8) z^HioJX-c>8ZzXE0)*uEytPIrbW<3c4nWXYg3#-?;8TicA0&$_uS8IPoJ zlqsubO&xjYv`A^C?RDyTYiZ$ZPLON~8%A^GUTP)>OlC{6dJuao zY6zyWGK)rVxika&6ua4%T2}itU}O4ZX)$@WT|*1Kc6Q~&IcAS>sm&u@{A2o`(1zWs#Cq0QHl?W{R1t6y7kYwVs1< zFWq3uv`O^$Ns|hl&^C8^hYfz$C6zw^GSd@=xGyRzpRG_D#q2KSZP;+l_EP#}ZDGBX zGSz$PSD9wuv)6aXaBntaN-;lt>T6X=!<>3Hg>+oOEZL;9*J8_dBJ;AGNasu-fe@XU zgek+-baIhy;skT;ribzkt8@b@hckyUd57uIXdKZ5EQ%r8oARwRB{@S5<-esWA->jV znhR+TBy}-+-jUuk_5vc4Q2b=$QDm0%9!?M<^U@j20K8}<>BIu7tQcTYtF%0ZLi$K- zp+szAYa$0FF%%)DRfB^|)oWMxU|%%MN@}iDR#7_I&wJ}_j~ZcN=`>R&r$;Fxi4sex z{QmrdG+dw|Ra^)_$Yr*nfvK4|=_5+fR;7hwMrP~JE2LYRiP=rE<5ku_$d}iqJ2ewI z9fM>u8ADh*YzpZ`Fu1T25TQ*pLWa$T{-7}nzk}MCO_dJ!HEMw{r7?4>e2rNQVGYl@ zqQXh`>C_VSFRW&;4diE}u58n6Vu(Vk9Y>W?OkCn4dMd zpMB1UMLs7HbpdnM>>lcc))}rEgdGPO3B)6 z0@*)mjIO`$z-3Tfmb~b0+Ws@9*xp2%aY=bKgFV9hdO!M^yU4_uu0%iOJk6{9dd#bB zVjr6O*?>9cSP2*S$8ZFR6H^UgKkYTF@^xTC%h2#_4%Cqm0&4HDVrsWyBa6co%%$KAYafrj#yIjRXSi@AF z?V=2~jhWfJsIh=k6Q;~SlI<%aXv!)YwY>)f7-lFOIN^JZ!|qCTV(8 z+Kh=F3>l{Uns%dYifDT-xp^_9CNfGM&5>YRjUv;)4p$|O=n`lOVP|F@WS{Igk|x%p zN5<8Cb$XG;s1Kneo%Gdd_5XHa!@KT{{kOBs$h7>C%u>fP!Wy`lIRDG#rcwWw>&>Si zta1N`6m0DBzf-WW>&z6W1Gi&0)jdi#SK^Jk*)-P1-DSq-JMYb8awE%4W7x<+X3!q9o6%P^aXpiw8AM$@RX%*d+3RoG@C+QfR(NH%ej837_w|IE>&WiIN|UsAE)ypeKIkdxT>5mWrhR_jESS|bo+mVh}c%&dD-Y~ZW3e# zTbmQ6n5%ASmGi&cvBkOhBo>D^jp$z_w?rPXdAC&)>N$O*Zu>tR>Gb6|eQ+$g#Ju_N zv|COw%fYn&2$2bItxiHr{|`6aOZ{a2Kb@ogUF--9 z2c9`0TQgy_?^bM<)VF4IU%nW@6l?%TcxioQ8XUCaYy*tn)VBGkRp(tNa<%d zrq|)rG_5I-li1AK8UcRCBGmJ9M~NDI(~yd(w%rPl+Jy#cT;>*G$c!=0%kPu<@LI(g ziblPGZ%AzGo3!7bB?&d$1sK$CaNq(L<6k`d*Tm_cbIn{kh@;Nu+02ar=Q_CguB-i9 zjBYs&o4G!y7Pl54+v~x|embeAMTfsutHERL-MQ%W_EbiQR{uKoyao5cCj^V{px4_NL zky`&Log(g95mO)jD&2T>Yu)#Oa_0j1_PLT?DQ}0XK5n*a7Azv=tK0%uL#*>j{Q#az znyhiX-T0s=SmTysvw&xPFq<%mF&NWG!XffwUF{lsBc}+(`Zv;l9YN zLg(D~xb8q|KX;!8%_yTq@IATWB*^i>m4k^ZwKB`Z*#Snym!d%)2t6^P`cMN z8HwFu{M<$OBQ0%8pWbE#;VdSg4pL_+)DCV@R()2JU_L&Z5q}?7pRd%-c1yCtC^2p3 z*2at65)8VMu8P2?s7XM*AU$2NC-qHcV=p)3J1=Zi)QXait;y~~ym7Y>A4P69?iU9O zT)TKXN~Vagnz?0Jvq?u$pOLOz)_CGwLY@`}>uWDv9)x)3}?sp}=1zC#%mtADG`Ic+to%$N%JyRkZf(-$;L3x7FiDDYJEkRuEN)%ENsI6l!gj?(pt#lGTwvgDkT`J$3+pQ zBPr7Xw5?|R9T3n8(XZt>64i3oE*KxEzN$Vg$LAViUqxM8!awRE<-a(qPj*GH#Nz8< zf1TBV4!BkQRn3@f<)kuG-EK#ETe+j%$gHk`-sW4Rg8CbDAk5yRRy9@ie?I9}f72wZ zw^Ga-?n9UZa8rcc0RFWjMJ}i(-_+n7#Y-<0ti^sIX4DVrQwL&F_^MU2F%k51p<1Ti zJaQwQ>WDY@YUzEglzB5H#>%7*`O$x>X&Z>KNwAnw?m#N^w(g42$57(RBmc51tA>_b zgIT_dfu4aYa9Q9WaCw*)LLO#$)U_>8$6Pk#;6LVaQRkv=j(w!gMb!eg8d>75DI_4z zwd8LuX1SQKVST>yo!g=sx(4XfX=#}O&a*$)=b<7RK>>y|b zZLm9-9JL1JEFf2d$W=KdI~a!GCURea`VbfjmCy#Nct`%-#oaK}!(jxBB)&r_m0Zh1 zp*xJQ4#&O1Is%TgGt8L$+5SytG(j}{7u7LZ+$v% zEYHGrd|xHc&BS~b%qHA9_?ZjGqCXCfrxu^Ud!fs8^I*QEb$6@VClc35a59_%r^0Et zIUN@8c2xh*fHO(oS#Wlk&N9r-fpe)P`QRX+wwy<8Sx9X;pW1Q(_7}oMpl~lXzcF_S zwWta2`cljk|01{y{zsgbC&S;<+UgaUUkO*i)v%bFw`H35KpJ1Mif$idyPlsw-<4ZoLsH0RCTN1E=32VfaIh?|Gt zVR!@{CGN*~R%7=#OhvyOR=^X`hSrf~Eo5)XXCL<@tt1X=Eo!%_FZNhM+h3-w-@>}TNhIimy?B9d;ar*(O_z>2@ zN3`^hG5-Ws!l$qf_n#5pdib1P;0t#R3HsCKGt<2* z=0{O}hg;5LZnq$Y+PU4SKzo4Z0NwD{Js3a_?fbnR_~{9~aC=EuK6|3xD~L18RXNAq z-sty%eeu6vkmvTt{Q+sDMLYsQJxxm8h#=7z~FIFcJ=h!{Bf@0*-{ENJBLo4Wpn2M#C7W1=U%N6Jv2Z z4#vX-s3V^fVG?d8!xWeb50P(;wW;<@UyJ)=NLxdozUv@2El|I#zD)U4ou|LWekmi7 z#{C(%p9vcXN8?jwJ=J#mZM@KA6%}nLBqY?r($JgCX?w-P|34%yZqHxW5bTCJw##r9AI}dojBY z?uQ46yNu^Dcn}_fhv5-;6doho6X0>w%XzNAeI0Yp&S~YYcUnz+>1D1q_yjx&Pr=35 zKh1L`JOis>HDM|5&ypsU!*j4Si0YH-QLcL)vlrk+cnQ|P%lOgzc!e-tMg5xe@CLj| zxx5t=y0Mfz3NTe#bR-n71Mi1%7l3~(?kVC=VS_Z;#s@U`Nu{ z5jw$6u$u7Z;BROA6hUX`0=vMjup8_Sdq7wGYrN^kvpe(v%{hC<4tKo>YtPsrZZGH! zd&54lk#1ky><9Z(J_o>ogi}v^eR%f8Pcf80Df)gf)rBL7;Yim%cBCt_@Z)Yk>?qbu z)ovj62gQzd2b;T5ZV=CM+ziHlSI9pNftHLfZ)+6}{gIE;WI!s(GL z|MapR<3`46-J!9u?y%T6cX({PJ0dp09T}^0N5v+(>ewWAbc}CG#JDdK<5O9&YBwfU z?`mVmxUnz}#=``tBTa{pi-|lZ!DN^MQ=y)G`nI6HImE!rXVJyAVGYK^s;mT7zF~>T#yN#MD|9 z@gMa*fEer=%*HJ4F2#NkVO_@af3Z1)$6OBcMZ{IdDo63E99Fa1NvS8`D#|l!3jAIX z=J84#wZW&-KacmTcy}efRNTjfc{(0D+6HYiH4dDB-SL$DJS)4a2={6W4<|g!SXn7; zi_QE*)}1F3@QL`D=dOvJ;I56$ch_O3I-~kB5kGbG0@w473;A~g@9%odZiJg)3ET{~ zz^!l_v|&}KdN`i^+>ZW^*h$oilZfXeOSk6k8sF};cdRt|HO5`IyPI~@#a4PJxuvmw z?jHJ~dkNz{xS#Yq0Lx;hkZ#$>+=FlfJOp}k5A%Ekw{^t$C}BMoJC(Vr+-g3lcyit2 zxY7G4V-=Zc$GRxAt7CQP?Q-1;-t7}+9&=9;|5LFANq6Zn+$uZx}IK8u|j=IK1QK8D;h zcE0-p`!5N%6{}>Qr_H?&m1*34WntyIuTg(PJSyWNR@Zv>R{q$R@!r29-0$HB_z`}> z+`n7Bw~Ipev`xbJ1-oD2H{5ODxsK=W7PiVf?*52fOg;By@Tb`;Ue;K#OX!Qjcq!FC z@z;xXGLJN^3;nlZb>GI^Y%X6N-QUSDRbLq23FlvMS$=#Ac*YLyVxaix zO&G|VU{)5W4zi9zy)JfHvYx13CNNWZY2GV|PafgqTbP;;$6Y}d<2w2+aMuS=S=(k)KI!>ntQY zunlYr+d+q{>)iIZ-vM^SPekRaI>kGq2D9xmhe6JHmdj2l`>O#)FBz^M!4Pa(}Sn_rJh+g zyIzE~C;GjhH|&A^-mnks3;V(TS$Xb&tXo;vD80A214(Ni=!^SeD1p*2o-!mYQM(;L z%CzoOJyJXThWFi%@cP54Rb(WqjA5C ze2?K-3u8mS<9LpTmDo+dybdN(rYg5dq-iqxDKItbfn*<0kNq*w0KZVK)3D#b^9Ay+ z_pS6y&sv5QM`?J_&B%Jl&BX02n2p;xptd#_j)mjkcsK#(!F>3VFdAqxC!#(HPR8#k za4Km%4Nivza0Vz&$-~Yhy=UR(Dbg~J{G5$l9TGI(ziz&NIEVLeE^g0*g;{E=zK?pG zaLy0I_ig$S*F0IStX+vu@{bGga}jC07%qWJ@w13@T$a_({g1FOM}GzSD|uc8(~;)+ zG&y%Q`o;LU2ChYY9b6BcNdNyU9OZj%?6I^o#oZ0Wb0cxy^#4o;Yh&EpY+!G; zUhZzmTH$Ub9Lb;S+!NtAt#Q%ISZ^bJ$AaQl{Zrk!ov`l6dNSFM-x=E9#j^~FqVL~T zuj1}*!d?pZWIc^f)sb9xFaGbtZG)A4)c>!f-m~7u?E~1$%|*QDzruR94EGO05fVz@ zrdWsL_Tm3@t9QH7J(9I5>?@G162@bcgU0^H@he&Ka-OHUj&22ZPf(su@_Y)0!~L<< z$@ix+P&qw~`AT>OR>5kxow`xY^I2F*n9mXB^Y8+^2rps2FVa&##<81D+FyphD34d@ z_g=L$DSyv}?cdkS^mhE3xlvoyyLvwC!~ERjbq$rV264OzZ^7H}4!lcx z-h=ny1N^D&eTey5xDK=X?7e87^J20uTo+Rx7R{StR(CbNN=EV#ex6f5fb`eD<2CMM z!ulM-*ck78~7my6$;2Kf?mFJfy4V|GnMm#HtNJ#{1ilO2M2;EBAK1a8US+{|VVQo< z^9T5mxPOA5;TQOoczz>&8{l{N1O9}+;P0%R+&@{-I#6pn%`M+@|MEV62;Qb0yiKa! zrl0onWz`=Se+Tn-P`tB|c@_CbuFNjB+)YOko@>(ZcX8Lz#V}WXNe*_bV&d=dj^B6L z=yM=9j?5W1O;OJ!9f`PPHtk(roIUV(wJV5!;0j?2)Xm}_y5{kiYXLt|w%RZ9`$?@` z%lKN?3UkRfS}QHk7TOW+mh5ZqM_RVxxiz$hZQ{!RM{e8rM{c|L$F4(MdsZK~?c<-g z9paz59np7;7rIWc6YLB{&>6bGE`+Ul;jVEn1KJI}M;7RJIj+>DRE>n6k{?|Y9K!k6@CUy`CP zt#0f`+{&}sf}ew`zD0A;xT_;AdY=;se~YYjPW!Jm=3_n?;?(;oJf}iE90Luwod(lk z2F!$6FdOE;TsRhvgX7@@mxT5Z9gY?+Kr^N$dwwezm)cxLaj? zMqBjZ-5vkYEsg)=?!lkrJNFXyedP6i^bhb{1`onR@Gv|AkHTZ{I4sBg3fw-y^GWni z!P5$hv^+>0&+uG@-D-H2v^CmhVrf|2^3y{S>oxq^p7QQ$78RFxSK9 zxc`FZm+%$puX%n0-=h8wzK0+1`y>1WKNE)J^uM6~6}#VH1N@HpA3XnrzpTGvKM%8i z;9tzti3ZuM3n2@295g@3MxO(@*}rgxNNX9^g6I>F2l-F{g|G$o&3HD?{*}`U>HVqt zYrmh-0{fQG3R*)OXbbINOV}z~d*SW#C8Dim< z&=>e}t3ZDU429L~=(fa1C2GxYt9YtxC5sw{dN_{Mq`OI~rNzWMUYGEvlgVl_st&4gJn8|GkM1(h%tl*eO< z|2XW92g$-tKtB)WXSZ}GX0x)!-O1>+XLSnkoC>GG>9}9O^9=0IgtOpmI0v(H;XM2- z#LfAbU4VKxZR|qKFM^BFUjmoHBDf4U|AWin3hb|htMGd@&&AkZ1Fut-*HX6EVSYXC zZh#v}-{+X$gnAv%B|LA=9_Vh#jv>jHq&Fs!ue%lV+u(M%gRqpBJ9(A`SwRjv_q-t7 zAhV|}Vf%2O!F(00&Q1i+lBN}e@f=ihc2eW0&-hp>PYc2KXk~h3Z8nn;!KI!-%yH%il zixs3%@qdWjTHJrcyZ9JBA*@fcTjSHWdxev^=Qq%;%We~Fi(knOKEuEEUbRkGkNR^9 zm$3)+m#Dwu`8CgPczz4tq5hud55)N+`~*M4FPQy`-ETZM!0+$}=Grg)6ZK#4cXr$0 zpX_$@6^uRD*_t2+SwF;JC27veVVwinkOR5U1e)e-Y5tU-YDi#~2l-F{h4|kBexm*~ zL*E=)K+Bx1f^trpw907_w9d&7TEz>3HaUes+ng;wD4ey~3r00%-J=nKVA0;SLo`a>BEfPruj91Me?90tP>sDMLY zC~;Tvtb$=Inue2}5il~RO>k&VyWlX&_i*$_V81vx#~qooHT8`1BIv8(X#DGajY3@m zqhWehd(~w(hVWDuYk5|2Qb%TE32PjThY2~`s-3wy)DvM6Ool1ApGr9Oa10c2x~Czh zL!h&g3U3bhrs29K) zsL$ki7Mu;|z`1Z9EQIsn0=N(^f{Sr~3C~M;E`rP8e>vL+m%|mL=}PRbf~#|OU__x0 zw{-4ES@?OyHR!Fr$9r=cE}A2$&;8Y1o73A}ms9Aj&*>Q4kfXiXPQi_YukrsT{FM=+ z{OT;kn}Oy!I|WOq*Ei$#mYi*ZTXX1|g5TY3gmF9Ek+WlPCw6zi-LMqyfqQdy4(=no z`w9C2+%4lBKbWKSs?Ha-4<5qJ!#VG}N8r(%XlyTbkL45vkLPIpRp^%ItamGNItNeW zv~y45{wdz=)4a2ldL@J7z=!JF8<1#iPU@GiUu@53qdQ6KR95Y~dutbIg&K88F0uQ2->zJYJyJIua^A96b3QhhA@Jm`OdpWzq${fax)O`RE5|MMIA4e)!| zCjLPEC;SC}gZ2>q;rTDPT;v)MgDi+cHsnAqG=Zj&fIP^D0w~Pov~{lLczLc_?jC{8 zKC4YM$F2pm#J&}@M%@P5LOa+Jwt}spJ!}Kp!gkPs>HhY)T^Wy;DX| z(ADMk4ki-Dq};uO$%Lo8PvJQgvwAp&@EUkdgXx&hAl#X``%t%hKev>+G%I)CpxJ-M zvtKY9znX*3Av~=+=Ter(q8>@Ob)2TWms6B^n+-$$eBW5diObo!DvJYxwwrY?`{-Pb zFR$b9f4tHV#y^ke3hLy1o+nxwRJRTcPD1@Cc{@3`Pms+?&Qs9K{!};(PR}h4bkkq~ z>NDU>IE!%4=6MdBOLz~l!*CwYg>XJx02kusBJ6ekUF(09^Tn7wP5Ze7^PgA`HK4x~ z7NNf^w3nm2g#Vzu@ZJ-Gjw&O>Y0-TEe;xu7?}o#@w=? z!)C+m=5ET>InDu;!N6dNwKeurlI6&li~1J0mGo&1e;d!+p@cSh2jSm|`YyN|mcmH# zt-j|T)XLwzl<9rB2Qf$BY&dog&?c9`gQy>ZhY9-;o{!?bf!gp`?!m!Un@#U-?s42M zhZW}DpEGy@{gddQf~R36JOis>H9QNND?P{adD8p>&*AZdsDFb|)&dobDRjbG!vk3X#&qO)guH#buUKFHO);UM=R_G?M^M?7`b^kdTW3FyYb zrM!6+ z;{FQ0&aGm-y171$@fo+@!gsmD{-bWH98-Dyp1l45^KyH-A9FRQ8BU#5UGsg6+VxM^ z{|vfAp)(pP>tE3Sio4$^hYiH3Gy3X(w#WQttD7T;Wd!9gf^uNo$K4e7 zAP(vOhJWB+;P9ghAO=}Y82cf+$)SwphZ4-87FJvQ<}~57HZ*~zxJlqX5AvY^3SkRq z2F;-bwB(xCww&(P&7)SRTSFUY3+-S_*a{qNaBJMRC){nC93JSF*S45%2OVI0*a3Eg zj?f8qf}L?+#B(|)#}N^@&ZxVG>;=7H zZ`cR+h5cZEH~z>Ta7Xb}8CHYxeKd@M8W;^@pccl$I2aET zpbjR&B$y0SU@Fu%IU+cQX9G-w=`aIk!Yr5#b6_qU3&+9na01MO`EVkf1Si8Oa4MVz zr^5m`1I~oA;A}Vt&V}<}A)F5vz=d!TTnv}MrLYJtga5(ha0OfmSHab=7_Nb9;X1e; zZh#x%CRhSD!!2+t+y=M99dIYy1$VyajK=JMb>N2k*lN@FA>) zkKkkY1U`jz@ENR!&*2OB625}3;T!lCzJu@K2kP68Jb!|p;TQN7euEA0JNyBE!e8(= z`~&|2LS#p0={TP2vOw~WIL~azfm~<;O(6k!kPih=2wOliXbvr)CA5Op&<5Hn`y4e6=Dtj5d+<4);u@zKoXM`J$P z%!gpkaN#PN7P>>4j=|3u?8cbgQ0%l`bn#jzp;$KV*;5EZ#pjNW(4|? zr0r0i)4748a|4W%EYC}LYE2f+RmWjAzUgH1HvxZj(23hWm*PgZ=lX!$ zPsDr@Ook~i73$#_Xn<)j9cI8xm<6+84&l!wt;fP~a6FuVxz^hAc+SWEM4l(X$#4ps z3a8=jbnF(u8E__?1!t4@b9kN$=b>H*=fef)FNF0J+eP@VU_E*2qF==OyA1vZ zm%|lsC0qqp!(!ZAgWGF)>Tcq7gn2#s8{kH`36@}YbJOv`E!f?PTJx(tnFrj4-R*D( z+zEHV-LRDO+ynRG{yyB_kJ$sT3?77s;9+Yg`1~gB|L-K zDp(EA!gKIEZePIeMR*DQ8lJt#zhsdwR+4W4hpTbREM@4&n89=s19 z5Z;H_uO*z1;A8j%K81Dg8LWrTar*^GzV{{1ui$I^egofP{~h}8n@$LRXgV?YvFW7X zC+gYHP3xF*Po>Rk&Ryt!q3nN!-(bgF$?p9cX#@U$$NwMjC;SC}!$0sZu+(x)%3KV( z1@%EzV)r1P$aC3=V}hK7WLXWgs|MO?18tRAWMT`~B;muJ8Jos@ZyI*f%&uvoAxL0% zBC-p$n>r+MSs7`Y!JFoeJ8{)%keua$WP2>y+vP)U10*54m5-2&;nXQE5dG# zeOZ{dHt5?zJM6Y3&08f3-PVa2l*=6AokQ4jtbb{rn9KghT=a9%A4^>H+4$KO)F!v% z*#WkP9kAPxXGiFi(B9;6!A^2q{b?syAN=goJjf(B5U3g@qZ%j8UkNV4Z$vy*RF}F!ET8b+$Z<)q}>T)5Ad=R#smES%{$cG zyc_B=Zr$Z4P7b=0*B-DVYlfaYdnM+P?^A3Jx+mf7Mf!Wg-idnFM)ky9PuyAywQ&1j zzi%>*nA;Ea{%`;&p5{DTz+c3BAkRL~H*qTQ7P?|6fl}xP{Xy}UB~A+lP`IW~p2qWZSb*6Xgn1^M1!rS+4o}@X{{+fl9eded@I8h>?5!3db3YgR zpR&#m&cpA*#D$dgh2-}_@>}T6C%y}?zc8^=&>a0m7I&e$81qXgvrAzST!x$f!R2rT zT$yO;u1Z`KJWu+sMt^SN;$Sh8wQCZW@UC;+wWMnU@98?q;rhg-^i9Y_F}o3Nf+hI5 z8E#1|vN8Ww%x;6*;SRVHyPqlZyLjH6xQx1z>z0y^I&PM#uH1v0d$E(e;tAZ{m$=;A z+>iMKi7RYfxGZsqdk{Ad!NZt80*`{$%a0M3>R2Ux*-mr^-2&ZG<=!Xu)mc|DkGP65 zy2|R3&VS3T>cn!wT0z-7k?0#dnYfyIepRqEc5d(#{+>=OCJgBZx|NA*($v?6?xOp> z*AcGVU7s|6#`1Q9#jA6*s|Zi$MOX8D7Ia_wIiAlGe=BZa=WtW@g~W})i|`VxftTTx z#7)@UMA~m6j+6}URo+7tw`!XJE1X8`{Qb@cxpli6F!FEWMzgyWtiN9)9k0V1kVE}{ zlQd1CY;@M^EzI7Aci>%k58elz8$X6Te1Q5xSZn!ZzXSEhr0o;<6xP9KupT~#FW^f( ziTf*_pYi+}zu&;O_}wRdOYmJnXUA?uHhU}SzO|8bZ~pGc_k^Le`MV=~Q@4DX{Xksm zV}DFYCUqO{$$!V=r-W`NT!8#qW*!m`#I6U{bFt0x7S|@S8et;*q}HlH_6I= zw|wVu;y2IzL3`AG)}M*n316oJZYS*>-2iShX8|it^y}RdIqNwGK z`8<0$m^Fc>kO1wOXiq&4^%K13e4YhR2wOliXbvr)CA5Op&<5HvLCUAThf?S|;}6N*B*JF zFx8U$5b_wyp*!>--Xg;8iJxAuC+wAXA8oCb>y3Kvy!(TFU|-lTua(Hxyj+0_FHw-5A%Vkm*>ysuLH?}z_>d5qmqmZ$T#)D6rBlKz8mCt0D+ z)#^;`!IAeG424Rlf?+TmM!^5S_xS+t?g8Fi zo*S9BEI1VPVU)|gjI0_@4(A;nf!UGdSAA$1Wq4GWcHRH2CcdM|-zdtk21XOk7^vkv z>_8sI<~>OH$^0SubUoRJC#>->0d*ZrL_NvEXCEH@6qpM2dAiyEFtz1j!YFjd5Web6 z1M#=zs}a-kK63sWMTKrUX*e8a!0pI_?RF-@qKG0t=zp10o3#%vCDbK%%9 z%;WMNq0U8X>PM-^o0A1=Zl^QW`vu37#uF^vseOhyj7Rebza)5sGJK49A0z#bk^YB+ z`FWZ{==`h+ot*RrZ zkd9L=Z2BzJr{}Gpi&%l*75MGw7T`8PA9)68^>+(>SZCt)XIydDgmTtCh58s@c4twJ zXXizJpJZMyHD}8#zcF_%&+{zYj&32(^9kz$3y(7jJTJmt`$xK0a7yqL?_U0y&trZu zTmtH!FXg!iR+Ep*u>T)i4p-zoZGE=NLjB^|c`IqF3WK=|Tm`!SRR@WzXOebue>Lg3 zjtQ*hQi-fp0jmu2r#f+^rFnIl8D}HR>{-nG``4b4%C#i>xzL>tZ>fd%d@`)wL+BkKFYZ?~BQ_^uhfNX7*B=S(L{$VZ70O zGWI+uw?6b0ed8}P&rap>CgNE_d^ba8nJS&HP_N{+qw9w|eaqw)+}#Sd!R>Gd+zEHV z-LTZ&mHN+Dc_*oOz6f5U?nZj0lX;z`|Mj4qnJYfN-+}-8FuxxjfMxI?JOmHJBcS*H zC~-XokHd0U0Z+h_@Dw}^E8!VfmG?#%x8h)K#awl@rSnbN9Ah8o4pRd1;92}UXZD(l zy!C%@^Y;J2%{$a?<=>}4W9+%~BC6M_Lv?()L+_=E^qqpa?iuQC;q#>BaGr;O>dp)J zU&##-P8_hVKu&D+gtLK|ui-uE9K*|b?^E`&_w}ugFMQ-==;c=BFZUk?+=_Po-cNMj zXDw-2ORCn=C#3q4SMcM%>%(0G%I8)558#U-Z2&2=x%K&B-iZC{*3YQ!>dd0Q->v%n z2I0I3Z^7H3yHwiKdI$BpJi zHLyA&EuRFR=BbZjjf7oW-fZV&UYJ|rXMNtM!ROeuCrw`v_m_-CUt#_=e1rM7u$nS{ z4!_S+mfum<-{*Z2{E)XU_%ZL};HSLLf?mv0k){*hXTi@F-}*32-)E~lBuABeWIXe? zMby1t2>(syGK%L1;_gCTe}&%&Z$HMK_t>B9On4hG`<-<8wE26`9K>;dVD=~c1%Jao zr0ZYO`W$iaaS|8gGv9+O)N#np&vQBXEnO}&fu@)xAP@4{R4ahO{Lh0e@Y4*M=MN!2 z%=KgIsMqVr-#W`*i~P@mmieCqt)O*&RJRVI)<*NVFT%Wk8MMjQ*#qqb7rM6jg{~d$ zwYJ)l=T_!dX=YwX8pbnE)_wK%sJDS_vEPn#cEF!6m#>2DNz)FbllvpVj^w8!bi&j7=nP$8m;7%Cjq^p82kw4QKG)@a8=6t~lJ)638^_$~oR z-NW+nD|WvGJ@bDFdcmHs7k0g2@BH8Bue7G-Y(DyZVL#YEe}jc5JB52Hs6K2%`s?^g zj?5aj)7Ne|%TK%q=KsmsDJ4%j2)SS%%DgWejrsf3%VOfvJ^m7&rI=qt4d{p8)d|k? zQ|4v)f3bFDKNI_bki~n}S>JASTW<5nd&FNkMOk%N_d@z`1j_nwaAf z{%{xp`nJtTo`=F=_&Xeq$j^#3A)F&o9|hHLH1?yQ21dh}e0@zPDpL-rlg_p-Cq^`` zmOl^i9K$OZi(i%FIQ*Q1`|&&{fcmskal_o5aPnLob#o#c1P?n7{u8q)SPvpE24ur z=j3mhbay`b3*bVyD1WP@JKZ;_oy=9yYyGo`JoKW5 z&th()`Se|k0sh;2`p(_}cNu>FC%3`2VYu7b^YZ)-)HCL`_`eda!rj$87sEAhE&A)= zdbj~@gq!lWxA$~8;VsGEfpjC;L47pOBEAB}R)&+^Eugu?B^YS#dTCBa^6u|*%3NQh zycIXM<#!?s?lKUzz87#u{!aGpzcKaBmd-o!i|l!4erL1OTxMTdoG+tYFk@~=dhgEP zl{lCmqP~Z)?kNOMWhxz{Xf&4uv2kx0Lchx?k?p!S+j0fQ% zcsPIe*dy>LJcj;pSe`!+8H!(<9L{qEaXrC!@+3S(cu(VIB|HPGU^R9AS>i9^D~9r? zwc~S`KMya!i|`Vx0rf4Kh4}B#&~wrMzMMb6&bU5;-&ct1RouPC^L3tYz?-Pw;`uhu zcX+;=KQMTY=lk#hdO=`Nj5Z zYhUToSvP+#{$lLv_+r=2r1dlW>rB;p!uTA%fG^=I_?mow1K(P_+>b#0J^X-PXYqa{ zO+SIowEv9zUr_%FzoFg$zr!Es^Y5akx~7;X3T_PY3bfBv=JE@=#|rRYSb(eonh{b_1d z)O(`di)U}x8}&Z0FYE{V!vUBd2z{V06k}GxvlRNF?$5J~=KvT82cg%!n1fLdf^ziV z@lFQw90C<^2n>bFf^M;@f*#f`RW6zrH3xnF@61?FO0FkOvnOrYm)o1MCX}+5O%5aM z;pDlFufWCJ&Ta(ZjpSW<`(820;10#jVFi1#jp_SIzy4*vo&NW5?2dpVp@#aZ`8i)C zwSMFG++&Dw&)8AeRm0IRO704J2crx2ij67Y{yeL-S~e!f!Z;WY6AF6M$4M4Q9fzNp z^~@v(>f`DP_O^V=?i1!K6G`tR_%gN+<{jPSf_-CK;%*G*w5DKQ#TV=}Pnk-*^>9qV z{`f?mgnAlG$IT3w3A4=o0gQ785ZeLdLF*#_O;x`h^68mfpfBMah?@gLH@Xkz`#DK5 zt6ZO0OTMD_XVbl7bI8kF()?XwpV+a)r@Ot%Qx5g$IP^-#@oDkvKGX^JK4=rP5yd;d zpl?jySnS37JQ253;UqX2PJvV5G&mg=z!`8RoJH7@f1FJ?lUP?2x#HM`$vJ*W>>R>9 zw?OxU*K<$UyR9NV$#ArOKM#M}VOhv?ApQ3FJTD;33kmxo)EC1gq*ZrAE=9cvE`t}D zL;a8En}YlZ5>g;a)+DdK&dg%>QLR{0z@kuo|9)_PBkHr|#TG_wS!a{{ntq#J|pY zzJz`aybQ0vtMD4U4sXDl@D{uc@4&n89=s19z=yDw@IHc%>5D&sPcd5upV23;FVHs+ zI0wt~i-L~sOZcil@<)9WVV(P$GWv$Je9zwWw>)RimwYEZ{-==cA9(%q}!B3QA+Y7jUx}{w%oM{Z&xy{)T^u``?0o z94zg~H!URVQ{Umg8PSEd5frjIDAfKG^E{ra$9kV})Y*^&xgeQ;lS01l32dX#cXRd( zbv_h8A!bF%yZy}S3ipdO!(Ve~QP@A$vhaGo#Z?w-MSQKHO`*OWa+_;gc%|z{kEXp+ z-REzI-Ikz!We|GRiLKD?=2#TAhLRoPDJm~qXyBV_Y%E^G$ma~Tci>RiT3^ebMEXe@;%>up5HTb zPkGOK>YO%ba)HhQ$jvnl^1x312WJK3<$peihx||g3c{mM2ns_H;!%`%6yyFeD30zW zK&Ck&$Z3e5Bui_3%!P4Zk@R{VH;tW2 zemfqFb7Ki>8~HnclS0Fs6#4=(n)u;Wq1zGkCFM%bC(;x-I%`jTmKTxN6q-SE{3M1d z+v_-KRC6CMIn{7kjkda)|4eFu8?7n7jBe^9$FowE9@s^Jy<^pE+|x1pT4u{C+t)WmO1{8r&vS=D|O`%<(8NyupH%i%l|dV=lHt37rho)aCA z7xc3_a^DF$Ll@`@-5i}|qji6tO->EsQp@kZ_rQNor?&kXkm`h6+t;}l=Dnj~^>J$9 zz7BD!gMA%8&Q+-+dXDr(ha^r`)mWei@k-)^)qYMr`$4XZx_wz2k=Z{gYXG{Kv|{{0 z{wY3BXHtEQwFV;VKFsccLAZMz24nUHx@dpH5Zn%hVVDnx5!mVMjgi=o;yy7{7d`9q zT+3*UcGiW)z*wiIJx+G$Iv&3hxYs_nH}NwO8O@2 zFo(92wqqi3Q@^*DAIDQ^&K=Tw^(r$)mubkG4sXE>QL^4#i{Z6Q@SZTQnj)8+pF>W5!O2t7c-9|_b=WiJJ5mWG4fV`-Yu8xE+OgM zlrdl+``_Z6)(_8eM}C^wuJ1>4&pP+hq>tu5R*^2NVGXSH^*7H8&5xNhWnZHox8}4V zLAcUUVM{OCUCK;;SkL|LXdg~v!VRR~M(3qyS}5#5=B@dpb3B*O7Ho1_&~H>2Y260t zVbUOplZU-DZghs_?RjtV!IV**gV&pQ>TDr%t`K9Vu+GeDd0RRL;i%l0F|8>pX5F7` zBd=Pe$=5s6UTe}i+v$iOpVqhK>#cEahCm}f$k$iUQgLUNfbcV5zu!_iFwQ293!FB$ zmGwa1AYII}Y%_VFIY^bYE!=N~ZE(_lHR?ZY+NSEHI-xSEbw|}3^^=pS=h-OFOPxe( zyOTs+Nus7D{Y#xxdlS^jw*E7zJL%3DzV>@gJ9`K0blMZYBzqUS?2d+|^G`Go_4ggKuwi*n_*hpmb7OW8CNjX~{6U?sMd?6ZvT5?#KNB*zcEbBj+G)O*m>(138`1 z(a6!B47C-9d|6${Ut>NoYJM1b?;}HX*2oHEbR|9IR_RIG8g+jJ_vTD?`la~$fd6Vw zhhTrJ|8CLrF#eVHN^{L~f9UJdJ(?c3%S)RcJ!rG}Rte#J44;5WtHPmUPEShGYjy!n z%|7n*<{7K8Y9ITA)5ktZhwfAA=4bFZd;wo#_7!~X^srBH{RU3M8Ti)eYkvpd!w>xb z(J35CcKX?8X)n&f8cyFnPk28eI}c&-_6ubsqxCa&`WMW~67qWZ6}P`R1MJ_OZlMcK z$IwN>{R1w6+0)4!FmBpX*ShiiTFBhtU)WuSE13Tc{}4y*8NQ0yHD{oG-5F%xa9+1> zqSx1;y`FSXtx!aJ0r}=tgl}F&2HRN}3A6f-URvYQzFFpQBdiC3#%ft0J@>JY0qz2( zbV*NUtGQ~=QzEB_XNn9VhlU_)2(kv-nUU>8hSD|;#cU{MdVhdEazx?qt`~ki?z2Q? zWsMB8v%x*+l|3>XS;O%+JVmc+>H3oIeKG4BHKSe;pBxd^i+mZ{Q=dRDAc3ePuqG44 zXM~-JeN{P;ThiCFhy5S?-5*H^JrL2}<)E)NlKL_d`6H1(iupp#HK^{IbWmM5PkG(U z^#JXNS%)0$*Xak*;URb!R3EZ);<@G+RNfzn&`*cl*qMEUV|_nn?MVGh^DTlap>ddx z<)1l=Dh@x!&3Mwnw(=0iypRv#BNK2}$U5oouXvL_S5_-O@=Y0^=!fl(DXB?Esb`z; z--oudKxC31c0pvT9W>7;`I}7IYE6+jEaLnqVH6^7bS}Ue{HhKXj!ePL6q00$pZ@pa zrwDF}g35`~rxB;GXCR-8VfGm5T|6?)Eb)I@1O2%;yl-`7cp~K_3_sL zSq-6c#(Ctg?AQ~Id85dD%0%FnJ~sLEJmwmQYmKEo?ixoH_~F#U`~{dsp6DF!dYmS2 zWSM7olZd_=!I%s;JLxMoMd$vZg{-G6M8}1Gnl&SC&EX}|YZ=e!Qs}MxXn~)XQ*_i` z9A@gm6>RO{l@2YjZv~ozZOv7CH5JY)pz+{w=0~-z(1!o7LK3uvcF-O=Ku72VouLal zbd4-RC(R{}<9lLbt!|OU%!w_wyHjp@M3SwZa4s|Z$0E6`UeFu*Kwszw{b2wMghB8+ z3?|LrK<uB!BKxx`5ot-(B`*GNfhY9c|OoU08PlidP z#T5Qeg=zesP8#~}+w*@0%!HoArzPumvq*cbO=`@ox$@cA&B4!Hc$@oqT<60Acn223 zB3KMdU@0ua-Evs$@cs~CH9*G|{9g&HU^Q;mz*<-b>j`rM?lyA22{z+q3)ii%4Yu?D zJ=g&|LErYsMg5O`^H{ARV7vLiNf&C@;6aI=Ma(V%Ki!r|ff5Sg;6@S;bUgvrPcQ?7`vzAuK zontXkWrbblydWKB=^@q~&oflzROiU+jP?X8gG)afHwCE|cXOW+GC^kCYrm<(z1rOf zR~J0U0$K4hjk%O;+~0%SL>i|Jv@F?O^E|zm>lE@Q2iN;>+moG0nNq?|4Ks^xCt0Sv zY5nAG{NzOD3BGob`n^QGAHjSX;oT1pz=NQD*AH=h7#;!h?u2Q3D}+k$+K;~1$NUBT zfL!iU+9ACclKNgrZo-Olm(lJpi3lNjNEc&sS$W*$etVPGElxcM+Dq+Gpbo(?$VYgm zsT*hfcVOPNkN9WjuCU`>_Ms3~0pg~%N$-AaNkX;8;bODiuhFN1km zcnY(pG1Gk9GyH!R%0YRk02K*SeVGLApMylGMGL0JXb4YUnRwz=1XF% zs<^L)oa&g@fKvQdylZl;#s31V2h>K77R>F};aV5-dYIRD&Hfo!H> zY}`zukJFd>+|S);_s6Z#b+hkgfV+k9=@$HK;lIj=(nom}V-3XZAb1@HyIaX;ef3}~ z?qaMrFf)7O<$fEjy!5iIA;dpB;SD7`t$`2o(|ZN|{Pp&5ca1#)^Hg0n*dvK^wa7Yq z6y~FmIR?hMo9%J#Hha9g-7dnHVR-wKFn4k`;(N3Z$<_o{&$i&4S)Nmbp?-KR)}7VY zoQMvSU@}ZWp606a(wCUZ{WJ*n^iOv=w;#VVFq;W_KFuPXXTuzr3va_bm=6o!9asp9 zU@dN~>+hDs}j=fbuo8wsT5w{(%6M}tEW-Oqd z3ws+dR~x1N{chy#LB?L#=kE0D)PC+=TDa`=hSOR3tOK}7!rwvc54k(+u9bvob^;AwY{~u=^cayCXzTP~a z-F@Yhp*751%1A+xt@Y= z;53|pZ*kitw4ZR!vF;aVedoqm-y=gZgK&Pp&5v*hnaTJ$3+LcG`~*M4FYqh;2EW4v zxCnp1CHNEmg3E9P{)T_xDqMr>a06}vho@N~usz21-T~730BL<7n%1Ta#(0eFJu~;6 z-lI1S8Q?C=5<^PMgZACtAd;R6q8YAUlVbHjEQ@=x*Fd{>j^Pmsuc#^+IIj^gfOHH!^R~rf4^%YFH9qpt?OB zQ|&*G#+kAc^`pGmYkv{V4Rxk`vQxTu37!2v_UBT<&*kfLKIMOI|Nl=Z|BZe> zr~KdK*AIOGN%1l15r+=B2s;ntg?!$xDS8KU8)hB!w`h4~zL#UguK8@Kk@GO*r@=yWy6+P`qFz2Qx&@Md( ziBQSANc=7mvx|QFRN4E8HRsf4X%*5ydmF2AJ;3^cz5!E>u+>kS!T78oZG3jZ9YmCq z_*&W}#&y-bOLh$}jy`)FPpvrS9(i9LJ>;$y*V<4Ac@;utPFv@m*2OIPjgC+~+Up`2 z|0JEY)AvvG`pd45S$_KL4ZO?r`7UFA8S`Y`{mdU~7?qu!u=OreqZCfYOHZ zG5Uuz*ZhxNfL-JzJPh%ZtGpO+j-aR_FOx7H=}d^dbiZ*u0BdfWOO3G zJ3|+UVca{Pyk7ua`QHt?!(sLl^ia6)8h*Nvx4k@#HIl8~*!O|HnD_HEqr|=|{!8uv z=m?tY7|3-H$7geXIAb*W;mFdw>|o5_fFUpxhQV+c0p(+vBDYH9W`O-th6QgTk6GxmwB<_<@nL} zKHl}rw^mnpsq5;0gthM`L)g4Ct^B@2hVQpldihQDcOT>Q3!%HhVcrN^iF|!iWIrpW znuBzR>nhAvL$OdM%qWM9htxW2e*I=7bJ)BSZpv2~OYeo7c4ZCm*4~5n@wFEJ1*7S< d?iQUhh1Yu-!~1vvTRN<>5^7W|kAORV{{?j>W9I+> literal 0 HcmV?d00001 diff --git a/smarts/assets/vehicles/visual_model/moving_truck.glb b/smarts/assets/vehicles/visual_model/moving_truck.glb new file mode 100644 index 0000000000000000000000000000000000000000..5752ce1b37b9981d6a692cc1e2c8506140b751c7 GIT binary patch literal 43140 zcmd^o33yaR)^=Tx#f@cHRa6KF$`ZTNOS*yd4TM$M6a-NO0t6C)1Va!|f#8Z8?zk_w z>!6>Gihw2^9mRDVcSpw!#&P-7k#W}n`QNwhJ)P5m4$XYuJkR$$KYHuFU481*sdG+M zoxAkOoOu(5H8IAVd#^F=I~a4!__1To%qd>Du%s%d|Cu>+O3F(ri>oRsbNc5TTUuFB zUa_$295m@VcwR~Qtdh#EBaa^2_4HtFUT%IQr*F>bC6x=yD#}5emmA1g);DM2Ofbml zAMnw_oc<@DnNwaoA9Xq7?RR~1$}47-@Qc7H%TB5PbY{-{l7*$VsZT$;;`FleITI=u z&77M<%K61rC6#5x^E{@rDi+O{S2DhAR>`cK{#BKWO8VxM%r9HGu6JSQgtfdfo!Hmk$B~``q=9SGnzGBgw((;mpV0mWFjN*kQMHTZZDpT!)eeHkj z+ixIWVSts=HdVK5S>H2r{tdYnmzB?|SiEqrL<{5wg7Ih|KNb$fLcw4x7|DzFMP(!w z%L_&F;?Ynb7LSKRs0#-3qv8BOB%T)y=Eq~PXy4#}dPMWe=9E_L-GHd+KrUqFzx-%0 z5(|d&Q2C!0)mnBhRi6(9hl9a5{*Q*k!F&jwP1S#VELCNdm|1({;qVx`P%xAq3FU?J z;URRQEUNzFWAR)lw-VEPZw6%L599~zzr0{H5RJw{G*BQI@O&#C4us;7P$cr7_bq=6 z6_v&1b4vDl7-q%i>mnX%$#v!$B&#aa_ktp9FG}${OCcWa{33C_07RbRW_3}dG+fth`8`& z;t=YaBOJn-Lqu}`@5~&c^&IjwhnVJ&*BFO*J%=EKtsh1(sCk4M;}OJ=WgtONDkfpg z1cS^xlpsc(ViHYblCPOW8fAikrob1Bu|VV$$Ww;+;N*V0;Sk6T=LG_> zaDFfxi^Z{lVWRc}k8m^+3FPI6{5tTcvcly|99k4Yl!2{U4FWRmaS)BQhgo-R52y8& zfZY>H^%;yW8Z>Iq@wR*zF@$5HT4(BjR)e9e8fEQa3nuJ z0A~$iWzWN~BO&-_GytX0hr;;?f&%%GNPaXwmX{Z*_d}mWBo9sCW8lTz8Tv z3*^P~^DGPaAR?;}Y!IL_$)YhWVEXQ=g?c60K{VDLb9&eI^;!&u;HQmyAr`q^In+xK zv&*GS<~XKjemoeBhogvOd@Tl|aZK81UNB@m6Y9hE8H$H7k>i0_y$(5-8!$ka2_>R+ zAQH`w=0&l?+PRDc1#QDnWggZBx^iPm2*T2P8bhP)ce@zWYcVfxk6Pq1-xDlu;)a=`H?`tMzOI7y*7ZI zBrkxqHbM@#CW^u3cZ44xjyvvV5D1lC`y zi*W34FuW&k+{3zL$IzG>x&Q3yN%d-kd3SL}$W$LA=)lJYJu{Y8m5eGWpHqeV4cH!G z2G)$7J=@*|vC*v8ItyyHuMbIfX^@BQKAk=G`#c*XX6ORyZqOhUjP7LvtTc_t6y2o* ztWAy3b1pU%3DMx*wFqMuXru*}#|B+QgN-%_VtHuTA{31^(#39CAaZI!ddbA!KY!Q@b`m zi^h7uC2E5nLb1lJ7mYP=DQu#R%7h5FVT(vKudz`e=x88RK5mNfPNFyS{AEF{1)+Rw zHn?c&+O_M1tBe^ua*X+);+kafJlC!LXVXIB-rG96Esy!xy=ls^X;{;gcc1KT@72fB zvwqy0(ZaJ{y(W3(+eL1dJ~4|A`h2Q;_Le?{%TWL3_(R;pi{HDNzwVbbZ2RpEO)UMC z4(}woHvh)b6R-dCx9;|$)ycMZbae+08B$1m66z-`8D6-<$A!I%Eq>~;^={u`#a1?H z%dt%L`A|;Evu%2zmGeZ@o1&sLp1LnRF4lLsd$jv$j{#|8Wc@W8=eo}?>u2lB%1Yhl zGY_>qhmSnn;u|4D`#v))z5!V4P-CGHT^+DCVR?$otf$Q3se{twZ#HCga@}WL-3Nc2 zQAbSu5H|(p*iSE;U@>(#J91nd`AA@u{DzQlUY7d=NV8F;MaNxN%ZX?+rl zt+h{T9cn+(`XQ!1AAIYOx+btG{jD^9u*LK->X5c({kHP{c8sEb*3)nI>o~&J%UGx% zv4!X=d|8*2y#xyl`H25$eQF((|Y`ySbGUu$>TV#vf67E_*%m$bGtc0NvS zZtJa|SM8G~kJbZa7XHNa4e}Q|3f46ARRjK{k-q3-q!IrSA6qlfvnh2e`k@c&zO)S5 zS6MH8Nn7fZSoFDV-lF8l5eF2WJMrYSwQJ|T)k#^$ULAN!GWc!t!Xeu|8rpH(;GJ&6 zHIuf!=#y5K4}D zQ~Kc;Nh9-!^2q!mz37l*5&t9&ZT)e=)Nw!JdR2Afr`ASXXSkQ?eULO9<8@8Hb~DK! z`lmd4kJI|pdS3TcqDFN7dtmXIhV_)6He$W_n5NhGgp0O?#XlR;3mF)(f9uBiFbO&3pd|+En&d*Z1Kl=%c=G6O*U# zdB>j%tY^P6M~qK1dP}RM&`f*yz@*Hb@uRAfGDnD|FVc{|_%P)pejj7}#h=&D$C}j% zPxgEMpOz%ov}#%S@b*^8?|qsQzU(|fpGUz#r^~dE}$Nh_# zYaQb~tcPh>Xt18UoU@GUNW*%@1H`hIk%se;@t)9-zvhYg;&RPr97s%_jQ2=G-(ZZ# zdYLcHhpcwRKZ!ZN7~^4XTFlswm}6&5$gxO_r+I36%4yep#CyaNQ)xbWysW298Sm*a zvY!6Kc#riGJF#ATk}`0eXFNbGy22ij!jxHPv^=DzT^MVzUSwvyU2_m?!T;@e8P~!0 ztWFs35lb9M8tRAfo|Z?;%zCjYWfQDrxEu8%kCuV;w2L46*|Bi1#F}i!$h{J=rS%QQ zfmj2ru1JHJ$I8#Rj`XyqqObp{>O~wcfN3U|q6)#kh{T;+$f0l< zV?QlF>*>Rc{WwO6J&36*#w3VEQ&Tz_XACB~WgJKv zi2;aZ4<(KDbHrw>m$7R(H6LQ(e+y(5%(2iP*q7!>8i~iW{~&I+V-cSepV9u7iNE$? z%|DYqKOT6BEBkVb{i@T}H(Bd;&RgWlp3C)6;vBtZV$HWUWgJK>d)a`YrItVAz2NHe zEPuv$TocHj_>G5_rf3j9SnS7gmWJ^L_Hm0D`^~y)sw*+!hoF}jL*!>HA(;EV9wU8K z_D5}Z*2|v7dhr>~1^Oi8J+3pm!&)brUa!@9eb)X@JxIK#=MiaS?uf3a2f@@E=_SU~ zeoJ{MzwB$Wf6*=y2NH9s-facYt2}O7qe6 zH~BQQqvo&awS5JXUbode_1HOH>V&Z$G4;S$uAxpSC*wWpnYQ2>h}g`Pc#mya&$fD> z6@T_)MeDc3;{U`lFNoQ%%ok$z`=@K#q|pdH=aKN&So)H9k1~s&AO7bh?wSKy7S2DT zO;XyD{#$=uGba4W#~&|0k9>fpMnB znub2#@Sc*sE~u{QYuBsRg>BMeS{^+FJY4ijrNh&}@${Prh))CpCSF zJJjr$zdSkfiic|sI_;909SfHy#~0sM({s>OHQNi8C;wQyrDjOCoSGf?EKim`6{4{Twgswf!H)ZuCs#f7$0ye~FQs8)s*{ut|EkSzE9$YT|LvXS z$#Y+Os=(5q_&C0x_S<)t*s%y+eC+^S=iHizetEFF7GX=JBUt$+IU zn-smp+ngnvraKR9^x76~taGOOd@Qy!ZJbq>kM^Hz{7v~`t)j10ep{>j+4`REE7jE7 zo_unN%!`^XNi~m>Y96IwHOFg|Zqxl)){Wp*_5S?N7t^rvpR~1wGH2tTnnwJSZBsZ) zoBFnkE4%Mv-)d*~Hq~|)`%;Fl*Zx?rz1wn^c=MJS1v{@_Ve!eu{R+%89u}HRcGR}k zK0uyVzA++MkUY%t+!Ow>#hLCEYes`mzC%yFS_3@hJDTT7KMxyr|^%rbvD7Qwq+ zTUK_kb2DWlwJ-QSP8QV}@#YoD6QAni?Hy{J)bzjYyCOLw_^_o>KA*mK)bA;2b3u(U zsm7S3P`A6sxxJRQv-tYtC^vN9K^EWi%V;;?bhdbd^FDpeB|ZJ`0H^tY?6BQ)NLsDO zLLRn#!+KPTzwvvGLCXHCS-)qTq2Ek)QS$6OZAJ3HWUZqzU;WzuA0c_QEj0oUjtmvNA<_Klf*pYzLXWV{P#k)nt!H#$@8-NhP#FN zU9BE8)_bMiPc;@A#AdFI>$pD8U+zl0hc(%iI1uyEO~rflG>rG$^JPE1XSth-1M7Jf zAf9n;y!X!+(=cK=w?3A$e#aqkZ*>XquNwa=oLbLqox}{7r>=_eQW*2mO~rwq4RCF| zS7YNnSH*j-iuYU<@3|`8b5*>T!d61h2O(!_?Xr8W-e-OLRUTD(^y9pg zhSSHc^`NlQ72+=UtNOSrg(;ifA2s&{o2m z5NkiwSk`~ii+?u6LSuEvYYoP7^*T()^*ZPEi1;?IM?9Y&WaB+o#d{W`PwR)(^|7Dp zW4lKC^cJgqA2fv$?+Lav5)WYSPWct~^pw9L4ovx##)_s^wPlPaKFrupe0Z%%e2Ciw}F(dTHy1(rubQD;qJ!ORXoVb!KIU8fEKUd{XE zH-?q(C6xS$lrLeuRX%3dZJEE6Q*g=$iaVsOC)^8CHcHzI)Ebygy;>*D<`u5Qfr$59 z74M19Gu}&KC4bsnP&D;(2iHv;myY*zjHhG2e?Q(crqJnHU|#n2$$G4GqQ{$2Kk2^e z?>E&DAO9?`Y72LZRbLtT*V7>0b5rr2mQCY~d^{;2lhv&+QzN*(U&MZHRuPxX) z(z_1OSkw4&>_(p%+oL)i|k z+nWxiBg&4Zlj)2z%TDGXb1=><4>E_CE;t`z4#oKpbC@~YbVb?KbVIK>raQ{+=sCyq zFh`&~0-t)CUgk)YN1CHdZ^+dGWed{>E&G~&DEpyxUz2N&MtL+o1xyg2C&@fhY%>0+TSVDMVRl2B92e2Ad+B2ZJIC$^keAnjvPW8D@r? z5hzEPktm0nV^AK8x?%V{3gu`s#*8)Na2{)pGsok69FB2jyqSPc$KiauIl)XclTc1F zCz{FTBz!X-=LzOyGXaGaIqY;z9EbIiHsJafLez^uag0*wDc za}mmmpn(g`#pV)}m*7)3bE#R4ay2Y{7I<|**##bOnYkRc?1OV}Xz&W?u&ue$Tm`>s zi?S!|eYLp;=c~<3=wmv{=@{iijIR`BDYUo%vd=eb%(dn^l-HT-(d!N7MwBgb2rMn%{}H`bDy~%<^AUO(A5&N4&^%YfO*jTmw5=~L*`-g2lI$|6y>AlF-W%F zJPzruL-{!H29z7jMvS(t*<_wDPnsH(HKrDINz`n_(bm-A+}1p0o;H6(`A72%T0Uzw zquh+v&za}V3n*VOFPfLk%jQog|72c4tG4FPsI5c!ta%j@Jd0y9DAz!O=Wx7+F|9SP zn>TQN9iN^@?VIK;^ES%2%{%5V=3Voi`76%vnfJ{H=0lVpnvZ}!Hd|0`!Kba}Z{`z} zpP0X!Pt9j&_ZH4?o6pS`=D*FCIJ5k3^OgA;XO>@?f0%D@X88}Z4dpiTPxGz$&U}yZ zd-H?&(fov-|AOAH+G&Hbjnmfoozu=~kFvef!Rd%I z%MMN_P#g%#);QWYot=Z6gPlWAcENuKIfvrYLC#^$;V2Kmr-PiXPB$mV>5j6y(*ws5 zPEUL83DnCu66KMoIm+qn^g-Fj>5JNaPA{CTGH5qd5`znz^0 z&S_31%1UP;#=O9m3o-60XOVL{G_n}_SmG>o&OmvFbEb2abB9^xEO%Bo)hMf-mCgg^ zY-sHPGZK0`$2r$I59N8z`OY#>E=IW+TrO}{ITtz?;e4TUv2zLJy%@)Q=Tc`iK3$6A zVvPPWjQw)w3g=4aavWFT^VRrntGUdUmpa!tYn*GH>rh_jT#uGFI5(oa5v^}>Zgy^Q zZpHZ)=Qd}pb34l0ojaU6(fS&c*WjBQ(Dz*^??Q{a(f2%*^FV(O#<>XPBIjO=?g6Z4 zXE}?p?%j>=ZpP=cFop*(=Chsqoco>Mqx`+I4(I{rL6i^T(|7dq0LLZlc>uQu&!zxcf9~a_$7d|}=?OcsxHPA(o`9foQY3k_4>MC&$zJ|m=W;)HUe&i z(u;rFBJyoxqu(c+3`<^k{z~_TEz|2Ry=!W6(z>PY`TdJ6&V78T+k4E^I?{Z9@k)y| z&DZaiCYQ9F=|*m7Vi}9(qxoxk(#Uv;MTevp-4crq zHUEZuq^;(u^``Zy<l#4@f2nhbMAC&Z$Y z58o|yMd!rgSGsLOp5gMYp6E9cmiQlUVmFZS~l7zgmZ+k$!bO>31iauGcc?dd;UH zjo3xkYx+|UT3=f}xWfI*GjpHF27fiZEIFn8^+b!?@86USo>yF!ESUFt?an!?`e%dB zIc$CH=0O$7W`AxmARBzuVe1o5gMR5>TMWns&n+%+5_uGvN*I&5zdlG?_5=(CR<7 z@0d6ieKms3bD$aJ(d-tV0-aRCuO`8-vcca&C;j192g0wi!Bwzh7uaz&{3;u~2!8S$ z{N!J+v>1>Lz8ij63;GM-SJ`0rQd0TV9`Q}E=@Y&!GT~*Io2NpDE1<({a5nQ%)12)4 zHvK9SUIU*=`f_H%tKoa3DFUBNn7;J1@~aGZx4y)uW+2bTR7g{A)MgfA@uGJ@~)tFH*mVW4>;4j_RE^& zbiC8sa|qtE1s*u+o`mfq|x0w8ep6`L@&gx|AXT^_j$&-DN5Bnk}f02hY!l%`* zN7>&vlRsr+zb^rEEC(#yuaKC1wf|)Q!WaB{{!WMWq~HEqYgA8A(PzBznm3P04h*kaO5cy4MPWOK!if~kLEu_>|G5%RcVM`E!f zvDlGV>?riqKe5=6SnNnFc4S{-M`E#~&_{wj6ng5PSnNnFb|e-%vM;eCvDi^)gpb&f^r=)R_8SPJZbXv>k?Zk79@*`yCq^r-IUPp z!hP7MB6;Yd)rsc^%}TuAx;$C(@E;QIwf(xl(ogPI3;J50rWQ1{e_cC2xvZqtKI2pL zH9kH0*Q$PNeVSVGRD47p@|S)|Q{(fu&*hbDny0k&#-g5QDSF{qKbGRX9E+zb-S7X} zSg;M+xQcsPHW>P}&*^AK{XQ6U?utz@c30WaRdyte*pW11M_1WV=xImc$+1hn96M>m zj>3nw5dPG;(9n+LFLo5!G*9?Y{WE3DXR_y?jgF<>Cq)MOWahDWJZrZ$&2lUr|E$KM z<h>rZgSA7O&L|H;9M%rU!6>_;MLRq{J{%?E zwRZLiaS#9Lu*7M-Y^2u9#%jInbKqV!Uh9R3Er4goeejI57oH*>iSj5sC+&sjq`gu0 z18pxva8Z;;qplZXyuK*IXx9sE__UZ$ievU!am+p`j@f6$G5eG_hNrKC@GYMX$3PuN z*&ok^V|bo803~C=7@iLgM_Guv7-GQ!lta-jhBhPc-1r!j_3_{+{|Pdm9*@JpC&zqZ zJi$ISZnx$7IpebyU@3x5zsv|DF zu8VtcB%W$}NpYU7XWR21k6JusMtgVpz!4rsj5O|%V=QK@^6FIA;*UEvcb|Wzz~X&o zpO+B&C8JE@cYa?Ve^-`ZU+nj{?Q0W4-?c^S0`^7u&4c3x$XL#OptFrXS-wrz<8K6l;Q3ZI@o^owV1^AX5SC3H`HQ`U%HH8v2i1LrI)Z zJ{*^SU10r|*SVzUT$^(20Na-Q15X!Np7f1%JKNZL&Li?xS^8&yy!*VEv5EM_J6Voa*}tZ7Tl8enn39`;TE^OHclS zDKq(SeG}g%mi31|ud$|)`9gZi!?|hc71lJAN7hEYcBNsTM$d8bm-)^$oPBZKCQYHj zdd*?Kvi@tVX=Gg@Ps$+si(cO}=GasHLZ7miQ9pu(hBE85R50sht=8-IO&E*#60!Ig zG1pbD8^n~E{(K9ttO>+2Pl+i5eTG>4kXYtBvCLCqj*-+r*TU{!A=$nOJnbsIMHyti%Y7BO_UHOWyU4vJt~0y`#W^T#iFLmkYZ{S9&tEIEuLmtNX=J<> zLk6xhq|tsNG+KwG7kzTg;d~KWXuD{eij7FGv8K^}B0gZ(H{TyDR=%YDQ2dHC8Ve0& z*1js3^?EJ{1|OGg8D|pHri`_SCC(w1c_%cCdBD@9&oCw=raYX##N^32PAstsv8)dk zV~mV5iRp)oc`U~MB|ND^u0O1oHHTQ@Ps$^43$d(kq@lei1MBJkl$n_N=lW?ebk5jM zFk?Jo%ES1Om@+ViBqmR;&&1>@y5hWG%*lG{LFlO;sh9PNG!lQp-&~0^*8&R-F?B`R zNJBrNY{b-U`IWsbroE~L_OzJxdik!`lBA)%h~ejUywo%6MbE@yJ7TdN>Dd?8aAMIp zX(TQs7Ml`_jVvEu=ft9OV(N!BB^G-Ti@k_Br>I+E(Jis)kXY)-TPpfA?wj`$ibC2d2 ziFt3ISYlLSi8Dzr`yFMV|8Tsdk@%B+QGUjs!k>Eqv8;z|OW)u+&w5!uSug80v8=ts zvbI|q@aLXR%(a4ii0OyiyUCOF+$)J?e<7yKj6aEGKO(08GZrOgzub$7$x|?8_G5t5 zdamb1!*z-DT=N^w5t)Oer<}6Z$vo2YPOnj5_3)(7^hvDk(5VpF}&Xgg}VlZNu}I>ln;8`@7ajrb?&wO;J6dcmK~U6?FbdW(I&@VQf!?D5(awYLRdtJl0 zwPytr3Dp)k5q3|n>%UpC*z#=t+S!SJ{O$DQ8&`Z$^Le+bv}bCX-tQ~HzI^(E#_0WV z;n|3(_GL?8Tm`DHS|tO{fKGze>=ec52`d+QJo!{0z ztJTk2)w9|f>pyRKb4t%O^^CRF@|kR(*`+-j&BRm5DYDr)sOtILEh*0#l?(-bJ)h^w zGh#bORJ}Jx)_U_%&5?w99xcy~?Q>_VleJ&i`KacC)}hebXU%HtY4yq$Y0rz544(cy z*=qf9*?Fz!yRWxh#--)YG~YAUt2{HA=5TDMX-oo4sX>3#lK15|G_$(X}!v(Uae`+g_X(5 zsc|MgnP@WAXX2yl|0iuVpS{Ft9jj66VcL4)uebJH4%*bW_5U~XMb8C}U#(jytZDRI z&~rp%O_MfXJo{C%m-;!Pu<{eEfo_lbz0#Gq)aOSQjOB!;0PCbH@n@RPE1$vMVdnzl zOwC8rWB+pB@b^2Pr;RiBKyUXu>^qc`zEhov-j~_#Q)x82my>&(>&L@bqttrRP*<;A zL7v<%s0SOL=y56ir19~`OZi!!q+;=}IwRJ5UuOFHHAmBAYMZHEx6Onzwarwo`DCKW zRIl6q@8OiLutv%ISB!;H?|}I}U~Q!B>(kq~)YAKLqxCWW+6`;qZr>mCeHAu0)w}TV z-_!Ho0kbrU58pWyIT@p-_$#bw63X{@ZRq;fm5e{xR^rdyy>G^MCfy?c{W10KTtd%f zHAfg{%6oCrubsb2hn{XdU8T|cI=6AD;>l}6SvS(&c~i2by)UQN0e`%9zN_&T=&`^A zDIdrRtGTb|c*eGxUiX!uUdfDnS@p6hJEpB6nkF6p-`h{IH>GkWL)N6X)}d5b)A;)o z=_Fs=E?Cp(y^?KUA4{*XrqO$)-a|FkG`@bTEkDmT7W*=|tgpvetmoORWA$S|Uy5g@ z`u_<{CZ3t<_qH!h{~yL`zBB$zt(j`>*ZOPD|JnFc&jme4e80B7r)hlO+hvZxpLtzr z>opB9uOI8@NWD$q$)2xi8a)^E9MM?Q?A?6v-rePUxx40Q%Jlnm{TnFB%jD%_ViqRH zzLU%Md=JH^gYk~-;W!_LTIO!*g5yxUquUm5<^B#wXT0Ov25;fE!nqyZ06qY30Pl-~ zxuN#QTf_U{+zf9CH-~Oo;AjeNhv9AC4mfx8e`nRze~0%7yph`rzqgXSPDiHw-irC0 zyx&{}Qop-m{w8K|lKf44+qRp{;M5K8)#l)x+x~dxc7T2Fb|5J8Q9IDS#oHCX?26&w z@3kU$%QuQ6VDl&S!yCULya~*FQN8hY@X;ubz?;H-AlDHnU2yAxvIk_{-)4wvhO?I= ziofgPue-dwP|OL%cXRcf<9G1E~Q zBrb#OLy!+@E+~fBY*6Fz_VGL%%nCILGF9L_4*8T$Lk_A1I8H=vsDEHFrO5&Nj-}4W@I$kh;k!x zRxz*CCX~!4wE-EZ9Q#|*EN=q8fVE^Od}JnkbSO&ZK^umWdDDi2$6}O=;Wd+x`|LQ_eiF(PFc&(b?2MUl zBK%`2%Bh$QtuQ+#qMV2sFc!Sqqil~^H3dFZin0{5WIxQ0=_se$%xAM9^&A{eA|nhl zY1QFiCN1XCdd6nOViv6zkx53fXuX20GcO~L)~m>j^*T!C$=WqL7IS0$6?w7h!0mk; z%#!sC@@RdC<0JI+JhE{;h2v@T^e6Cp7RP3Aeg*tq!})dO%X$@@-@@@W@?9}c(YrX_ z1E;@$^9Ppu3*h$=?o1bBe*|omM z@srJ~#f(}%+k9F(z;!#0kC9L7XVm_NV<#woLcXo-IPX9PF6L_b73Xcpxb-c1_|9hY zVivD2(EB$i|8AJ;>+d)|wK>5)Lw2yO$O`s@&DHe-IR0pi&CJylIl8?3T+NZC%gfH? zW#(#W^Ku=C99NQ^%gfBwCY711z0G;$W#Z~=vvGAn<}C*tyP!M-S)2|-KCZ)nI)U;~ zl!xM*rs$8kx|*VFi@aXU^wk#SfynCB4rM#^*wW_tYKdH5`yxl!e#jiQKMu-AjxBIL z-06zER$n4Z)t4A2^L+I{j;kKX>ebU`_v+~!iL6{Zp}pQHnd7T3vUxE>T3?hqOfK?! zZNZsYzL?)DU~_!^3wjMZ|H9E5dA_LM2=bXl9cJ{3qx7gI)DhISjIU$?f>nN0Y z$PhLLB{O{$*gRixoR33$=KC6sW1!9WH4HhwCV=-O^uw%Q%>8vNa({J4*&SRb<8x1x zJ&_6QBv4L7?MXII*fHpF5{^M=eFC@+!!aCO$D_9boX26D$D#lJIFEs3d5~lj&SSxe z8PiV2G1|{AHU-(lm|2YZ#HQn5{;(2fHcI9VD@AUvQ&CDjuyQ{in9lCyW%Q~-wyVX+ zrB+!7jsjHS&PfX9K(1=Ks3d&jEHlxSoYPV9RXIs%w$c>jvZoy9#;3u19%2zFC3( z)}YM_l$V0fQl<;ZDu3AkT~<0ACE3O$~S<2*=mKC+ozfP?Zex7ay2-w10?L>{j0 zIC{X6Ly(W_M4WGSe#GqVgR&3ug!RKL`Mc?d;}fhPKbl*dpK#m?+vi}W48~D}c@lta zkHR?w4mV@=^u)OrW<@?cAc!N+`4wwT#0ldZLH4==_(croII`e+tTu(-G!`Ycj90^GUhY8*XA@^XS12D zLpC!nm)ReXZR`)oT*mxm>rt*pwld}{+l11~S#}$;t38Q>naS=1w^|%Y^mH%sp{>Pn zJ9s^Se(u8gZsaXnXY-@|7q~tK-pq;i2)J$pZ{|UJ99(O_`w5iHh;|?NB~d0J-J_A7 z$(>zi@^|Hh>o*Nc4y~JP@sJlioVaRw;jp0|4e`jabCOM`UgipBTjGuGoO(XMtHxbs z`H)^{G*8`^ZmY4TAr_wN6@SVv^?EE?W@3?9)9AJnhW2zt&J$i7=28zF*Rz{EO#M6? z@o0#jap$xcBe9loosbUm@?mV88qnnue*EdA=X)Q`wa8DzX#9?eJdCl-3GA6=h`r>@V$Q`c*H z?gj6ibF9$7rh5*{+g%W<8)iiQ}4fN`=F8` zlWdy4dzYoI_(_Ki$Z6ouBVzFZ(ufaenyL4eyJBBr@d4dd)39D_N-VzJu&vOrUztb5 zGQV_NU9ago6;`MEB9^`yV(IJq=T@f1LM&q;PtgzC%G{w0qAS*mt~8BqODsCn{B^&& zt>)QKhtjXsXG14mI*!sYo0dn@=(d+3H(eR>s?EB8?i1PIAN<^Oe?RvA zP1)cIkhesl(+%U+H2|szn zm60mY3;|6h%ou4$r;dq!pvi=P|6TXTjsc(Hpvi>UR{ClTt5^(V>G3JsdH))(&n5=e zG{QC8{?Io0@!~d-EneKaM-2YeO70Yn!3UPY2QJ4v$_CT!mGFVTVjg9KXTWdgV;+5p zd6W&Fgn98Y=0(#@Ee2$Rufx1cf<6TLZ14cg>(29EuYD8pWP`sxH7By!pGTSS->?=< zh7MO@9%X|c!&-Dw#p{VrAH9E5Hu#+PpMI3{XefL;6D|*2^VlMvCKIOpIgfJHJZgx0 zROLiu9%aH{Q_a3OXB)x%ir0kIIPmY^!`WOzX&SFD_L-WWjbfRD4~_P&AKAV!%ojJx Config: +@lru_cache(maxsize=2) +def config( + config_path: str = "./smarts_engine.ini", environment_prefix="SMARTS" +) -> Config: """Get the SMARTS environment configuration for the smarts engine. .. note:: This searches the following locations and loads the first one it finds: - `./smarts_engine.ini` + Supplied config_path. default: `./smarts_engine.ini` `~/.smarts/engine.ini` `/etc/smarts/engine.ini` `$PYTHON_PATH/smarts/engine.ini` Args: - default (str, optional): The default configurable location. Defaults to `./smarts_engine.ini`. + config_path (str, optional): The configurable location. Defaults to `./smarts_engine.ini`. Returns: Config: A configuration utility that allows resolving environment and `engine.ini` configuration. @@ -83,9 +85,9 @@ def get_file(config_file: Path): return str(config_file) - conf = partial(Config, environment_prefix="SMARTS") + conf = partial(Config, environment_prefix=environment_prefix) - file = get_file(Path(default).absolute()) + file = get_file(Path(config_path).absolute()) if file: return conf(file) diff --git a/smarts/core/actor_capture_manager.py b/smarts/core/actor_capture_manager.py index 4de044222d..60d984768a 100644 --- a/smarts/core/actor_capture_manager.py +++ b/smarts/core/actor_capture_manager.py @@ -19,18 +19,20 @@ # 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. - +from __future__ import annotations import warnings from collections import namedtuple from dataclasses import replace -from typing import Any, Dict, Optional +from typing import TYPE_CHECKING, Any, Dict, Optional -from smarts.core.actor import ActorState from smarts.core.plan import Plan -from smarts.core.vehicle import Vehicle from smarts.sstudio.sstypes import ConditionRequires +if TYPE_CHECKING: + from smarts.core.actor import ActorState + from smarts.core.vehicle import Vehicle + class ActorCaptureManager: """The base for managers that handle transition of control of actors.""" @@ -68,7 +70,6 @@ def _make_new_vehicle( agent_id, agent_interface, plan, - sim.scenario.tire_parameters_filepath, True, initial_speed=initial_speed, boid=False, diff --git a/smarts/core/agent_interface.py b/smarts/core/agent_interface.py index 1f974734cb..bd8b514509 100644 --- a/smarts/core/agent_interface.py +++ b/smarts/core/agent_interface.py @@ -318,13 +318,16 @@ class AgentInterface: The choice of action space; this also decides the controller that will be enabled and the chassis type that will be used. """ - vehicle_type: Literal[ - "bus", "coach", "motorcycle", "pedestrian", "sedan", "trailer", "truck" - ] = "sedan" + vehicle_type: str = "" """ The choice of vehicle type. """ + vehicle_class: str = "generic_sedan" + """ + The choice of vehicle classes from the vehicle definition list. + """ + accelerometer: Union[Accelerometer, bool] = True """ Enable acceleration and jerk observations. @@ -367,15 +370,17 @@ def __post_init__(self): self.lane_positions, LanePositions ) self.signals = AgentInterface._resolve_config(self.signals, Signals) - assert self.vehicle_type in { - "bus", - "coach", - "motorcycle", - "pedestrian", - "sedan", - "trailer", - "truck", - } + if self.vehicle_type != "": + warnings.warn( + "`vehicle_type` is now deprecated. Instead use `vehicle_class`.", + category=DeprecationWarning, + ) + assert self.vehicle_type in ( + "sedan", + "bus", + ), "Only these values were supported at deprecation." + self.vehicle_class = self.vehicle_type + assert isinstance(self.vehicle_class, str) @staticmethod def from_type(requested_type: AgentType, **kwargs): diff --git a/smarts/core/agent_manager.py b/smarts/core/agent_manager.py index cf3c8d19bf..ed1b39d08a 100644 --- a/smarts/core/agent_manager.py +++ b/smarts/core/agent_manager.py @@ -611,7 +611,6 @@ def _add_agent( agent_id, agent_interface, plan, - scenario.tire_parameters_filepath, trainable, agent_model.initial_speed, boid=boid, diff --git a/smarts/core/agents_provider.py b/smarts/core/agents_provider.py index 2c3d0186c7..5f33a85149 100644 --- a/smarts/core/agents_provider.py +++ b/smarts/core/agents_provider.py @@ -169,7 +169,6 @@ def perform_agent_actions(self, agent_actions: Dict[str, Any]): controller_state, sensor_state, agent_interface.action, - agent_interface.vehicle_type, ) @property diff --git a/smarts/core/chassis.py b/smarts/core/chassis.py index 5457239dff..b4946ff65f 100644 --- a/smarts/core/chassis.py +++ b/smarts/core/chassis.py @@ -30,7 +30,9 @@ from shapely.geometry import Polygon from shapely.geometry import box as shapely_box -from smarts.core import models +import smarts.assets.vehicles.chassis_params +import smarts.assets.vehicles.controller_params +import smarts.assets.vehicles.dynamics_model from smarts.core.coordinates import Dimensions, Heading, Pose from smarts.core.tire_models import TireForces from smarts.core.utils import pybullet @@ -49,12 +51,22 @@ ) from smarts.core.utils.pybullet import bullet_client as bc -with pkg_resources.path(models, "vehicle.urdf") as path: +with pkg_resources.path( + smarts.assets.vehicles.dynamics_model, "generic_sedan.urdf" +) as path: DEFAULT_VEHICLE_FILEPATH = str(path.absolute()) -with pkg_resources.path(models, "controller_parameters.yaml") as controller_path: +with pkg_resources.path( + smarts.assets.vehicles.controller_params, "generic_sedan.yaml" +) as controller_path: controller_filepath = str(controller_path.absolute()) with open(controller_filepath, "r") as controller_file: - DEFAULT_CONTROLLER_PARAMETERS = yaml.safe_load(controller_file)["sedan"] + DEFAULT_CONTROLLER_PARAMETERS = yaml.safe_load(controller_file) +with pkg_resources.path( + smarts.assets.vehicles.chassis_params, "generic_sedan.yaml" +) as chassis_path: + chassis_filepath = str(chassis_path.absolute()) +with open(chassis_filepath, "r") as chassis_file: + DEFAULT_CHASSIS_PARAMETERS = yaml.safe_load(chassis_file) def _query_bullet_contact_points(bullet_client, bullet_id, link_index): @@ -334,36 +346,32 @@ def __init__( self, pose: Pose, bullet_client: bc.BulletClient, - vehicle_filepath=DEFAULT_VEHICLE_FILEPATH, + vehicle_dynamics_filepath=DEFAULT_VEHICLE_FILEPATH, tire_parameters_filepath=None, friction_map=None, controller_parameters=DEFAULT_CONTROLLER_PARAMETERS, + chassis_parameters=DEFAULT_CHASSIS_PARAMETERS, initial_speed=None, ): assert isinstance(pose, Pose) self._log = logging.getLogger(self.__class__.__name__) - # XXX: Parameterize these vehicle properties? self._client = bullet_client - self._chassis_aero_force_gain = controller_parameters["chassis"][ - "chassis_aero_force_gain" - ] - self._max_brake_gain = controller_parameters["chassis"]["max_brake_gain"] + self._chassis_aero_force_gain = chassis_parameters["chassis_aero_force_gain"] + self._max_brake_gain = chassis_parameters["max_brake_gain"] # This value was found emperically. It causes the wheel steer joints to # reach their maximum. We use this value to map to the -1, 1 steering range. # If it were larger we'd cap out our turning radius before we hit -1, or 1. # If it were smaller we'd never reach the tightest turning radius we could. - self._max_turn_radius = controller_parameters["chassis"]["max_turn_radius"] - self._wheel_radius = controller_parameters["chassis"]["wheel_radius"] - self._max_torque = controller_parameters["chassis"]["max_torque"] - self._max_btorque = controller_parameters["chassis"]["max_btorque"] + self._max_turn_radius = chassis_parameters["max_turn_radius"] + self._wheel_radius = chassis_parameters["wheel_radius"] + self._max_torque = chassis_parameters["max_torque"] + self._max_btorque = chassis_parameters["max_btorque"] # 720 is the maximum driver steering wheel angle # which equals to two full rotation of steering wheel. # This corresponds to maximum 41.3 deg angle at tires. - self._max_steering = controller_parameters["chassis"]["max_steering"] - self._steering_gear_ratio = controller_parameters["chassis"][ - "steering_gear_ratio" - ] + self._max_steering = chassis_parameters["max_steering"] + self._steering_gear_ratio = chassis_parameters["steering_gear_ratio"] self._tire_model = None self._lat_forces = np.zeros(4) self._lon_forces = np.zeros(4) @@ -373,7 +381,7 @@ def __init__( self._road_wheel_frictions = None self._bullet_id = self._client.loadURDF( - vehicle_filepath, + vehicle_dynamics_filepath, [0, 0, 0], [0, 0, 0, 1], useFixedBase=False, @@ -397,7 +405,7 @@ def __init__( } break - self._controller_parameters = controller_parameters["control"] + self._controller_parameters = controller_parameters if (tire_parameters_filepath is not None) and os.path.exists( tire_parameters_filepath diff --git a/smarts/core/configuration.py b/smarts/core/configuration.py index 107ffe78ab..1d1bb83bce 100644 --- a/smarts/core/configuration.py +++ b/smarts/core/configuration.py @@ -25,13 +25,21 @@ import logging import os import pathlib -from typing import Any, Callable, Optional, Union +import re +import warnings +from typing import Any, Callable, Final, List, Optional, Union + +import smarts _UNSET = object() logger = logging.getLogger(__name__) +def _passthrough_cast(val): + return val + + def _convert_truthy(t: str) -> bool: """Convert value to a boolean. This should only allow ([Tt]rue)|([Ff]alse)|[\\d]. @@ -48,6 +56,25 @@ def _convert_truthy(t: str) -> bool: return bool(out) +_assets_path = os.path.join(list(smarts.__path__)[0], "assets") +_config_defaults: Final = { + ("assets", "path"): _assets_path, + ("assets", "default_agent_vehicle"): "sedan", + ("assets", "default_vehicle_definitions_list"): os.path.join( + _assets_path, "vehicles/vehicle_definitions_list.yaml" + ), + ("core", "observation_workers"): 0, + ("core", "max_custom_image_sensors"): 4, + ("core", "sensor_parallelization"): "mp", + ("core", "debug"): False, + ("core", "reset_retries"): 0, + # ("physics", "max_pybullet_freq"): 240, + ("ray", "num_gpus"): 0, + ("ray", "num_cpus"): None, + ("ray", "log_to_driver"): False, +} + + class Config: """A configuration utility that handles configuration from file and environment variable. @@ -66,7 +93,10 @@ def __init__( interpolation=configparser.ExtendedInterpolation() ) self._environment_prefix = environment_prefix.upper() - self._environment_variable_format_string = self._environment_prefix + "_{}_{}" + self._environment_variable_format_string = ( + self._environment_prefix + "_{}_{}" if self._environment_prefix else "{}_{}" + ) + self.env_variable_substitution_pattern = re.compile(r"\$\{(.+)\}") if isinstance(config_file, str): config_file = pathlib.Path(config_file) @@ -88,7 +118,7 @@ def get_setting( section: str, option: str, default: Any = _UNSET, - cast: Callable[[str], Any] = str, + cast: Callable[[Any], Any] = _passthrough_cast, ) -> Optional[Any]: """Finds the given configuration checking the following in order: environment variable, configuration file, and default. @@ -120,16 +150,44 @@ def get_setting( value = self._config[section][option] except (configparser.NoSectionError, KeyError) as exc: if default is _UNSET: + if value := _config_defaults.get((section, option)): + return value raise EnvironmentError( f"Setting `${env_variable}` cannot be found in environment or configuration." ) from exc return default return cast(value) + def substitute_settings(self, input: str, source: Optional[str] = "") -> str: + """Given a string, substitutes in configuration settings if they exist.""" + + m: List[str] = self.env_variable_substitution_pattern.findall(input) + + if not m: + return input + output = input + for val in set(m): + if self.environment_prefix: + environment_prefix, _, setting = val.partition("_") + if environment_prefix != self.environment_prefix: + warnings.warn( + f"Unable to substitute environment variable `{val}` from `{source}`" + ) + continue + else: + setting = val + + section, _, option_name = setting.lower().partition("_") + env_value = self(section, option_name) + + output = output.replace(f"${{{val}}}", env_value) + return output + def __call__( self, section: str, option: str, + /, default: Any = _UNSET, cast: Callable[[str], Any] = str, ) -> Optional[Any]: diff --git a/smarts/core/controllers/__init__.py b/smarts/core/controllers/__init__.py index 7a82e443a7..029d60dd07 100644 --- a/smarts/core/controllers/__init__.py +++ b/smarts/core/controllers/__init__.py @@ -70,7 +70,6 @@ def perform_action( controller_state, sensor_state, action_space, - vehicle_type, ): """Calls control for the given vehicle based on a given action space and action. @@ -89,13 +88,9 @@ def perform_action( The state of a vehicle sensor as relates to vehicle sensors. action_space: The action space of the provided action. - vehicle_type: - Vehicle type information about the given vehicle. """ if action is None: return - if vehicle_type == "bus": - assert action_space == ActionSpaceType.Trajectory if action_space == ActionSpaceType.Continuous: vehicle.control( throttle=np.clip(action[0], 0.0, 1.0), diff --git a/smarts/core/models/__init__.py b/smarts/core/models/__init__.py index d5d822d2c0..4ff783334d 100644 --- a/smarts/core/models/__init__.py +++ b/smarts/core/models/__init__.py @@ -17,3 +17,15 @@ # 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. + +import sys +import warnings + +import smarts.assets + +warnings.warn( + "The `smarts.core.models` module has been deprecated in favor of `smarts.assets`. Please update your code.", + category=DeprecationWarning, +) +# Redirect this module to the smarts.assets module +sys.modules[__name__] = smarts.assets diff --git a/smarts/core/models/controller_parameters.yaml b/smarts/core/models/controller_parameters.yaml deleted file mode 100644 index d775c05a8e..0000000000 --- a/smarts/core/models/controller_parameters.yaml +++ /dev/null @@ -1,76 +0,0 @@ -sedan: - control: - final_heading_gain: .15 - final_lateral_gain: 4.65 - final_steering_filter_constant: 23.5 - throttle_filter_constant: 22.5 - velocity_gain: 5.1 - velocity_integral_gain: 0 - traction_gain: 6 - final_lateral_error_derivative_gain: 0.3 - final_heading_error_derivative_gain: 3.1 - initial_look_ahead_distant: 6 - derivative_activation: 1 - speed_reduction_activation: 1 - velocity_damping_gain: 0.001 - windup_gain: 0.01 - chassis: - chassis_aero_force_gain : 0.63 - max_brake_gain : 10000 - max_turn_radius : 2.2 - wheel_radius : 0.31265 - max_torque : 1600 - max_btorque : 1400 - max_steering : 12.56 - steering_gear_ratio : 17.4 - -bus: - control: - final_heading_gain: 0.15 - final_lateral_gain: 5.3 - final_steering_filter_constant: 27.5 - throttle_filter_constant: 2 - velocity_gain: 6.1 - velocity_integral_gain: 0 - traction_gain: 8 - final_lateral_error_derivative_gain: 0.45 - final_heading_error_derivative_gain: 2.5 - initial_look_ahead_distant: 3 - derivative_activation: 1 - speed_reduction_activation: 0 - velocity_damping_gain: 0.001 - windup_gain: 0.01 - chassis: - chassis_aero_force_gain : 0.63 - max_brake_gain : 10000 - max_turn_radius : 2.2 - wheel_radius : 0.31265 - max_torque : 2100 - max_btorque : 1200 - max_steering : 12.56 - steering_gear_ratio : 17.4 -truck: - control: - final_heading_gain: 0.15 - final_lateral_gain: 5.3 - final_steering_filter_constant: 27.5 - throttle_filter_constant: 2 - velocity_gain: 6.1 - velocity_integral_gain: 0 - traction_gain: 8 - final_lateral_error_derivative_gain: 0.45 - final_heading_error_derivative_gain: 2.5 - initial_look_ahead_distant: 3 - derivative_activation: 1 - speed_reduction_activation: 0 - velocity_damping_gain: 0.001 - windup_gain: 0.01 - chassis: - chassis_aero_force_gain : 0.63 - max_brake_gain : 10000 - max_turn_radius : 2.2 - wheel_radius : 0.31265 - max_torque : 2100 - max_btorque : 1200 - max_steering : 12.56 - steering_gear_ratio : 17.4 \ No newline at end of file diff --git a/smarts/core/scenario.py b/smarts/core/scenario.py index 4fc06296c6..54c3000f89 100644 --- a/smarts/core/scenario.py +++ b/smarts/core/scenario.py @@ -921,6 +921,10 @@ def plane_filepath(self) -> str: @property def vehicle_filepath(self) -> Optional[str]: """The file-path of the vehicle's physics model.""" + warnings.warn( + "tire_parameters_filepath is no longer in use. Please update your code.", + category=DeprecationWarning, + ) if not os.path.isdir(self._root): return None for fname in os.listdir(self._root): @@ -931,13 +935,26 @@ def vehicle_filepath(self) -> Optional[str]: @property def tire_parameters_filepath(self) -> str: """The path of the tire model's parameters.""" + warnings.warn( + "tire_parameters_filepath is no longer in use. Please update your code.", + category=DeprecationWarning, + ) return os.path.join(self._root, "tire_parameters.yaml") @property def controller_parameters_filepath(self) -> str: """The path of the vehicle controller parameters.""" + warnings.warn( + "controller_parameters_filepath is no longer in use. Please update your code.", + category=DeprecationWarning, + ) return os.path.join(self._root, "controller_parameters.yaml") + @property + def vehicle_definitions_filepath(self) -> str: + """The path to the default list of vehicle definitions.""" + return os.path.join(self._root, "vehicle_definitions_list.yaml") + @property def traffic_specs(self) -> Sequence[str]: """The traffic spec file names to use for this scenario.""" diff --git a/smarts/core/smarts.py b/smarts/core/smarts.py index 05fc4baf99..5bba3e618e 100644 --- a/smarts/core/smarts.py +++ b/smarts/core/smarts.py @@ -17,6 +17,8 @@ # 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. +from __future__ import annotations + import importlib.resources as pkg_resources import logging import os @@ -40,7 +42,7 @@ from envision import etypes as envision_types from envision.client import Client as EnvisionClient -from smarts import VERSION +from smarts import VERSION, assets from smarts.core.actor_capture_manager import ActorCaptureManager from smarts.core.id_actor_capture_manager import IdActorCaptureManager from smarts.core.plan import Plan @@ -50,7 +52,7 @@ from smarts.core.utils.core_logging import timeit from smarts.core.utils.type_operations import TypeSuite -from . import config, models +from . import config from .actor import ActorRole, ActorState from .agent_interface import AgentInterface from .agent_manager import AgentManager @@ -212,9 +214,9 @@ def __init__( self._last_provider_state = None self._reset_agents_only = reset_agents_only # a.k.a "teleportation" - # For macOS GUI. See our `BulletClient` docstring for details. - # from .utils.bullet import BulletClient - # self._bullet_client = BulletClient(pybullet.GUI) + # For macOS GUI. See our `BulletClientMACOS` docstring for details. + # from .utils.pybullet import BulletClientMACOS + # self._bullet_client = BulletClientMACOS(pybullet.GUI) self._bullet_client = pybullet.SafeBulletClient( pybullet.DIRECT ) # pylint: disable=no-member @@ -538,8 +540,8 @@ def setup(self, scenario: Scenario): self._renderer.setup(scenario) self._setup_bullet_client(self._bullet_client) provider_state = self._setup_providers(self._scenario) - self._vehicle_index.load_controller_params( - scenario.controller_parameters_filepath + self._vehicle_index.load_vehicle_definitions_list( + scenario.vehicle_definitions_filepath ) self._agent_manager.setup_agents() @@ -837,14 +839,14 @@ def _setup_bullet_client(self, client: bc.BulletClient): def _setup_pybullet_ground_plane(self, client: bc.BulletClient): plane_path = self._scenario.plane_filepath if not os.path.exists(plane_path): - with pkg_resources.path(models, "plane.urdf") as path: + with pkg_resources.path(assets, "plane.urdf") as path: plane_path = str(path.absolute()) if not self._map_bb: self._map_bb = self.road_map.bounding_box if self._map_bb: - # 1e6 is the default value for plane length and width in smarts/models/plane.urdf. + # 1e6 is the default value for plane length and width in smarts/assets/plane.urdf. DEFAULT_PLANE_DIM = 1e6 ground_plane_scale = ( 2.2 * max(self._map_bb.length, self._map_bb.width) / DEFAULT_PLANE_DIM diff --git a/smarts/core/tests/test_collision.py b/smarts/core/tests/test_collision.py index 037c7bc526..c368d9829b 100644 --- a/smarts/core/tests/test_collision.py +++ b/smarts/core/tests/test_collision.py @@ -27,7 +27,7 @@ import pytest from helpers.scenario import temp_scenario -from smarts.core import models +import smarts.assets as smarts_assets from smarts.core.agent_interface import ActionSpaceType, AgentInterface from smarts.core.chassis import AckermannChassis, BoxChassis from smarts.core.coordinates import Heading, Pose @@ -46,8 +46,7 @@ def bullet_client(): client = bc.BulletClient(pybullet.DIRECT) client.setGravity(0, 0, -9.8) - path = Path(__file__).parent / "../smarts/core/models/plane.urdf" - with pkg_resources.path(models, "plane.urdf") as path: + with pkg_resources.path(smarts_assets, "plane.urdf") as path: plane_path = str(path.absolute()) # create the ground plane to be big enough that the vehicles can potentially contact the ground too client.loadURDF( diff --git a/smarts/core/tests/test_trajectory_controller.py b/smarts/core/tests/test_trajectory_controller.py index 10a913b237..045ed2551f 100644 --- a/smarts/core/tests/test_trajectory_controller.py +++ b/smarts/core/tests/test_trajectory_controller.py @@ -21,13 +21,12 @@ # THE SOFTWARE. import importlib.resources as pkg_resources import math -from pathlib import Path import numpy as np import pytest -import yaml -from smarts.core import models +import smarts.assets.vehicles.controller_params +import smarts.assets.vehicles.dynamics_model from smarts.core.chassis import AckermannChassis from smarts.core.controllers import ( TrajectoryTrackingController, @@ -35,55 +34,64 @@ ) from smarts.core.coordinates import Heading, Pose from smarts.core.utils import pybullet -from smarts.core.utils.pybullet import bullet_client as bc +from smarts.core.utils.pybullet import SafeBulletClient +from smarts.core.utils.resources import ( + VehicleDefinitions, + load_vehicle_definitions_list, + load_yaml_config_with_substitution, +) from smarts.core.vehicle import Vehicle time_step = 0.1 -@pytest.fixture(params=["sedan", "bus"]) -def vehicle_controller_file(request): - vehicle_file_name = request.param + ".urdf" - if request.param == "sedan": - vehicle_file_name = "vehicle.urdf" +@pytest.fixture +def vehicle_definitions_list() -> VehicleDefinitions: + return load_vehicle_definitions_list(None) - with pkg_resources.path(models, vehicle_file_name) as path: - vehicle_file_path = str(path.absolute()) - with pkg_resources.path(models, "controller_parameters.yaml") as controller_path: - controller_filepath = str(controller_path.absolute()) - with open(controller_filepath, "r") as controller_file: - vehicle_controller_file_path = yaml.safe_load(controller_file)[request.param] - return (vehicle_file_path, vehicle_controller_file_path) +@pytest.fixture( + params=["bus", "sedan", "pickup", "moving_truck_empty", "moving_truck_loaded"] +) +def vehicle_definition( + vehicle_definitions_list: VehicleDefinitions, request: pytest.FixtureRequest +): + return vehicle_definitions_list.load_vehicle_definition(request.param) @pytest.fixture def bullet_client(fixed_timestep_sec=time_step): - client = bc.BulletClient(pybullet.DIRECT) + client = SafeBulletClient(pybullet.DIRECT) client.resetSimulation() client.setGravity(0, 0, -9.8) client.setPhysicsEngineParameter( fixedTimeStep=fixed_timestep_sec, numSubSteps=int(fixed_timestep_sec / (1 / 240)), ) - path = Path(__file__).parent / "../models/plane.urdf" - path = str(path.absolute()) - plane_body_id = client.loadURDF(path, useFixedBase=True) + with pkg_resources.path(smarts.assets, "plane.urdf") as path: + path = str(path.absolute()) + plane_body_id = client.loadURDF(path, useFixedBase=True) yield client client.disconnect() @pytest.fixture -def vehicle(bullet_client, vehicle_controller_file, fixed_timestep_sec=time_step): +def vehicle(bullet_client, vehicle_definition, fixed_timestep_sec=time_step): pose = Pose.from_center((0, 0, 0), Heading(0)) vehicle1 = Vehicle( id="vehicle", chassis=AckermannChassis( pose=pose, bullet_client=bullet_client, - vehicle_filepath=vehicle_controller_file[0], - controller_parameters=vehicle_controller_file[1], + vehicle_dynamics_filepath=vehicle_definition["dynamics_model"], + controller_parameters=load_yaml_config_with_substitution( + vehicle_definition["controller_params"] + ), + chassis_parameters=load_yaml_config_with_substitution( + vehicle_definition["chassis_params"] + ), ), + visual_model_filepath=None, ) return vehicle1 diff --git a/smarts/core/tests/test_trajectory_interpolation_provider.py b/smarts/core/tests/test_trajectory_interpolation_provider.py index 2b66c2ba54..55dbd60741 100644 --- a/smarts/core/tests/test_trajectory_interpolation_provider.py +++ b/smarts/core/tests/test_trajectory_interpolation_provider.py @@ -171,7 +171,7 @@ def test_trajectory_interpolation_controller(controller_actions, bullet_client): dimensions=VEHICLE_CONFIGS["passenger"].dimensions, bullet_client=bullet_client, ) - vehicle = Vehicle(vehicle_id, chassis) + vehicle = Vehicle(vehicle_id, chassis, visual_model_filepath=None) has_error = False try: diff --git a/smarts/core/tests/test_vehicle.py b/smarts/core/tests/test_vehicle.py index 56cfd8d2c3..b42e64d412 100644 --- a/smarts/core/tests/test_vehicle.py +++ b/smarts/core/tests/test_vehicle.py @@ -63,7 +63,7 @@ def social_vehicle(position, heading, speed, bullet_client): dimensions=VEHICLE_CONFIGS["passenger"].dimensions, bullet_client=bullet_client, ) - return Vehicle(id="sv-132", chassis=chassis) + return Vehicle(id="sv-132", chassis=chassis, visual_model_filepath=None) @pytest.fixture @@ -112,6 +112,7 @@ def test_create_social_vehicle(bullet_client): id="sv-132", chassis=chassis, vehicle_config_type="passenger", + visual_model_filepath=None, ) assert car.vehicle_type == "car" @@ -119,6 +120,7 @@ def test_create_social_vehicle(bullet_client): id="sv-132", chassis=chassis, vehicle_config_type="truck", + visual_model_filepath=None, ) assert truck.vehicle_type == "truck" @@ -136,6 +138,7 @@ def test_vehicle_bounding_box(bullet_client): id="vehicle-0", chassis=chassis, vehicle_config_type="passenger", + visual_model_filepath=None, ) for coordinates in zip( vehicle.bounding_box, [[0.5, 2.5], (1.5, 2.5), (1.5, -0.5), (0.5, -0.5)] @@ -175,5 +178,6 @@ def test_vehicle_meta_methods(bullet_client): id=f"vehicle-{i}", chassis=chassis, vehicle_config_type="passenger", + visual_model_filepath=None, ) validate_vehicle(vehicle) diff --git a/smarts/core/utils/bullet.py b/smarts/core/utils/bullet.py index 29cab194c4..7a745359eb 100644 --- a/smarts/core/utils/bullet.py +++ b/smarts/core/utils/bullet.py @@ -17,64 +17,13 @@ # 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. -from multiprocessing import Pipe, Process -from multiprocessing.connection import Connection + from typing import NamedTuple, Tuple import numpy as np from smarts.core.coordinates import Pose from smarts.core.utils import pybullet -from smarts.core.utils.pybullet import bullet_client as bc - - -class BulletClient: - """This wrapper class is a hack for `macOS` where running PyBullet in GUI mode, - alongside Panda3D segfaults. It seems due to running two OpenGL applications - in the same process. Here we spawn a process to run PyBullet and forward all - calls to it over unix pipes. - - N.B. This class can be directly subbed-in for pybullet_utils's BulletClient - but your application must start from a, - - if __name__ == "__main__:": - # https://turtlemonvh.github.io/python-multiprocessing-and-corefoundation-libraries.html - import multiprocessing as mp - mp.set_start_method('spawn', force=True) - """ - - def __init__(self, bullet_connect_mode=pybullet.GUI): - self._parent_conn, self._child_conn = Pipe() - self.process = Process( - target=BulletClient.consume, - args=( - bullet_connect_mode, - self._child_conn, - ), - ) - self.process.start() - - def __getattr__(self, name): - def wrapper(*args, **kwargs): - self._parent_conn.send((name, args, kwargs)) - return self._parent_conn.recv() - - return wrapper - - @staticmethod - def consume(bullet_connect_mode, connection: Connection): - """Builds a child pybullet process. - Args: - bullet_connect_mode: The type of bullet process. - connection: The child end of a pipe. - """ - # runs in sep. process - client = bc.BulletClient(bullet_connect_mode) - - while True: - method, args, kwargs = connection.recv() - result = getattr(client, method)(*args, **kwargs) - connection.send(result) class ContactPoint(NamedTuple): diff --git a/smarts/core/utils/pybullet.py b/smarts/core/utils/pybullet.py index b527709f6c..827bec0b1d 100644 --- a/smarts/core/utils/pybullet.py +++ b/smarts/core/utils/pybullet.py @@ -17,8 +17,8 @@ # 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. -import functools -import inspect +from multiprocessing import Pipe, Process +from multiprocessing.connection import Connection from smarts.core.utils.core_logging import suppress_output @@ -26,6 +26,7 @@ # way to fix this since they simply use print(...). Disabling logging at the # time of import is our hack. with suppress_output(): + import pybullet from pybullet import * from pybullet_utils import bullet_client @@ -61,3 +62,52 @@ def __getattr__(self, name): if name in {"__deepcopy__", "__getstate__", "__setstate__"}: raise RuntimeError(f"{self.__class__} does not allow `{name}`") return super().__getattr__(name) + + +class BulletClientMACOS: + """This wrapper class is a hack for `macOS` where running PyBullet in GUI mode, + alongside Panda3D segfaults. It seems due to running two OpenGL applications + in the same process. Here we spawn a process to run PyBullet and forward all + calls to it over unix pipes. + + N.B. This class can be directly subbed-in for pybullet_utils's BulletClient + but your application must start from a, + + if __name__ == "__main__:": + # https://turtlemonvh.github.io/python-multiprocessing-and-corefoundation-libraries.html + import multiprocessing as mp + mp.set_start_method('spawn', force=True) + """ + + def __init__(self, bullet_connect_mode=pybullet.GUI): + self._parent_conn, self._child_conn = Pipe() + self.process = Process( + target=BulletClientMACOS.consume, + args=( + bullet_connect_mode, + self._child_conn, + ), + ) + self.process.start() + + def __getattr__(self, name): + def wrapper(*args, **kwargs): + self._parent_conn.send((name, args, kwargs)) + return self._parent_conn.recv() + + return wrapper + + @staticmethod + def consume(bullet_connect_mode, connection: Connection): + """Builds a child pybullet process. + Args: + bullet_connect_mode: The type of bullet process. + connection: The child end of a pipe. + """ + # runs in sep. process + client = SafeBulletClient(bullet_connect_mode) + + while True: + method, args, kwargs = connection.recv() + result = getattr(client, method)(*args, **kwargs) + connection.send(result) diff --git a/smarts/core/utils/resources.py b/smarts/core/utils/resources.py index 968fafbdb6..20558fba0d 100644 --- a/smarts/core/utils/resources.py +++ b/smarts/core/utils/resources.py @@ -21,24 +21,28 @@ import os import re import tempfile +from dataclasses import dataclass +from functools import lru_cache from importlib.util import find_spec from pathlib import Path -from typing import Any, Dict, Optional +from typing import Any, Dict, Optional, Union import yaml -from .. import models +import smarts.assets.vehicles +from smarts.core import config -def load_controller_params(controller_filepath: str): - """Load a controller parameters file.""" - if (controller_filepath is None) or not os.path.exists(controller_filepath): - with pkg_resources.path( - models, "controller_parameters.yaml" - ) as controller_path: - controller_filepath = str(controller_path.absolute()) - with open(controller_filepath, "r", encoding="utf-8") as controller_file: - return yaml.safe_load(controller_file) +def load_vehicle_definitions_list(vehicle_list_filepath: Optional[str]): + """Load a vehicle definition list file.""" + if (vehicle_list_filepath is None) or not os.path.exists(vehicle_list_filepath): + vehicle_list_filepath = config()("assets", "default_vehicle_definitions_list") + vehicle_list_filepath = Path(vehicle_list_filepath).absolute() + + return VehicleDefinitions( + data=load_yaml_config_with_substitution(vehicle_list_filepath), + filepath=vehicle_list_filepath, + ) def load_yaml_config(path: Path) -> Optional[Dict[str, Any]]: @@ -63,10 +67,15 @@ def _replace_with_module_path(base: str, module_str: str): return base.replace(f"${{{{{module_str}}}}}", origin) -def load_yaml_config_with_substitution(path: Path) -> Optional[Dict[str, Any]]: +def load_yaml_config_with_substitution( + path: Union[str, Path] +) -> Optional[Dict[str, Any]]: """Read in a yaml configuration to dictionary format replacing instances of ${{module}} with - module's file path.""" - config = None + module's file path and ${} with the SMARTS environment variable.""" + smarts_config = config() + out_config = None + if isinstance(path, str): + path = Path(path) if path.exists(): assert path.suffix in (".yaml", ".yml"), f"`{str(path)}` is not a YAML file." with tempfile.NamedTemporaryFile("w", suffix=".py", dir=path.parent) as c: @@ -77,9 +86,50 @@ def load_yaml_config_with_substitution(path: Path) -> Optional[Dict[str, Any]]: if match: for val in match: conf = _replace_with_module_path(conf, val) + conf = smarts_config.substitute_settings(conf, path.__str__()) c.write(conf) c.flush() with open(c.name, "r", encoding="utf-8") as file: - config = yaml.safe_load(file) - return config + out_config = yaml.safe_load(file) + return out_config + + +@dataclass(frozen=True) +class VehicleDefinitions: + """This defines a set of vehicle definitions and loading utilities.""" + + data: Dict[str, Any] + """The data associated with the vehicle definitions. This is generally vehicle type keys.""" + filepath: Union[str, Path] + """The path to the vehicle definitions file.""" + + def __post_init__(self): + if isinstance(self.filepath, Path): + object.__setattr__(self, "filepath", self.filepath.__str__()) + + @lru_cache(maxsize=20) + def load_vehicle_definition(self, vehicle_class: str): + """Loads in a particular vehicle definition.""" + if vehicle_definition_filepath := self.data.get(vehicle_class): + return load_yaml_config_with_substitution(Path(vehicle_definition_filepath)) + raise OSError( + f"Vehicle '{vehicle_class}' is not defined in {list(self.data.keys())}" + ) + + @lru_cache(maxsize=20) + def controller_params_for_vehicle_class(self, vehicle_class: str): + """Get the controller parameters for the given vehicle type""" + vehicle_definition = self.load_vehicle_definition(vehicle_class) + controller_params = Path(vehicle_definition["controller_params"]) + return load_yaml_config_with_substitution(controller_params) + + @lru_cache(maxsize=20) + def chassis_params_for_vehicle_class(self, vehicle_class: str): + """Get the controller parameters for the given vehicle type""" + vehicle_definition = self.load_vehicle_definition(vehicle_class) + chassis_parms = Path(vehicle_definition["chassis_params"]) + return load_yaml_config_with_substitution(chassis_parms) + + def __hash__(self) -> int: + return hash(self.filepath) diff --git a/smarts/core/utils/type_operations.py b/smarts/core/utils/type_operations.py index 979a5ea43f..2c3577da22 100644 --- a/smarts/core/utils/type_operations.py +++ b/smarts/core/utils/type_operations.py @@ -190,13 +190,13 @@ def __init__(self, base_type: Type[T]) -> None: self._associated_groups: Dict[T, List[Type[T]]] = defaultdict(list) self._base_type = base_type - def clear_type(self, type_to_clear: Type[T]): + def clear_type(self, type_to_clear: Type): """Clear all instances of the given type from this suite. This includes all sub-classes. This should be an sub-class of the type that this suite manages. Args: - type_to_clear (Type[T]): The type to clear. + type_to_clear (Type[S]): The type to clear. """ self._assert_is_managed(type_to_clear) t = self._associated_groups.get(type_to_clear) diff --git a/smarts/core/vehicle.py b/smarts/core/vehicle.py index e8b5d811a5..2be1a6d592 100644 --- a/smarts/core/vehicle.py +++ b/smarts/core/vehicle.py @@ -21,17 +21,14 @@ import importlib.resources as pkg_resources import logging -import os -from dataclasses import dataclass from functools import lru_cache, partial -from typing import Any, Dict, List, Optional, Tuple, Type, Union +from typing import TYPE_CHECKING, Dict, List, Optional, Tuple, Union import numpy as np -from smarts.core.agent_interface import AgentInterface -from smarts.core.plan import Mission, Plan +import smarts.assets.vehicles.visual_model as smarts_vehicle_visuals -from . import config, models +from . import config from .actor import ActorRole from .chassis import AckermannChassis, BoxChassis, Chassis from .colors import SceneColors @@ -54,8 +51,14 @@ ) from .utils.core_math import rotate_cw_around_point from .utils.custom_exceptions import RendererException -from .vehicle_state import VEHICLE_CONFIGS, VehicleConfig, VehicleState +from .vehicle_state import VEHICLE_CONFIGS, VehicleState +if TYPE_CHECKING: + from smarts.core import plan + from smarts.core.agent_interface import AgentInterface + from smarts.core.renderer_base import RendererBase + from smarts.core.sensor_manager import SensorManager + from smarts.core.smarts import SMARTS class Vehicle: """Represents a single vehicle.""" @@ -81,7 +84,9 @@ def __init__( self, id: str, chassis: Chassis, - vehicle_config_type: str = "passenger", + visual_model_filepath: Optional[str], + vehicle_config_type: str = "sedan", + vehicle_class: str = "generic_sedan", color: Optional[SceneColors] = None, action_space=None, ): @@ -92,16 +97,24 @@ def __init__( if vehicle_config_type == "sedan": vehicle_config_type = "passenger" self._vehicle_config_type = vehicle_config_type + self._vehicle_class = vehicle_class self._action_space = action_space self._meta_create_sensor_functions() self._sensors = {} + self._visual_model_path = visual_model_filepath + + if self._visual_model_path in {None, ""}: + with pkg_resources.path( + smarts_vehicle_visuals, + VEHICLE_CONFIGS[self._vehicle_config_type].glb_model, + ) as path: + self._visual_model_path = path # Color override self._color: Optional[SceneColors] = color if self._color is None: - config = VEHICLE_CONFIGS[vehicle_config_type] - self._color = config.color + self._color = SceneColors.SocialVehicle self._initialized = True self._has_stepped = False @@ -121,6 +134,7 @@ def __repr__(self): pose={self.pose}, speed={self.speed}, type={self.vehicle_type}, + class={self.vehicle_class}, w={self.width}, l={self.length}, h={self.height} @@ -256,9 +270,19 @@ def bounding_box(self) -> List[np.ndarray]: @property def vehicle_type(self) -> str: - """Get the vehicle type identifier.""" + """Get the vehicle type name as recognized by SMARTS. (e.g. 'car')""" return VEHICLE_CONFIGS[self._vehicle_config_type].vehicle_type + @property + def vehicle_config_type(self) -> str: + """Get the vehicle type identifier. (e.g. 'sedan')""" + return self._vehicle_config_type + + @property + def vehicle_class(self) -> str: + """Get the custom class of vehicle this is. (e.g. 'ford_f150')""" + return self._vehicle_class + @property def valid(self) -> bool: """Check if the vehicle still `exists` and is still operable.""" @@ -269,49 +293,9 @@ def sensor_names(self) -> Tuple[str]: """The names of the sensors that are potentially available to this vehicle.""" return self._sensor_names - @staticmethod - @lru_cache(maxsize=None) - def vehicle_urdf_path(vehicle_type: str, override_path: Optional[str]) -> str: - """Resolve the physics model filepath. - - Args: - vehicle_type (str): The type of the vehicle. - override_path (Optional[str]): The override. - - Raises: - ValueError: The vehicle type is valid. - - Returns: - str: The path to the model `.urdf`. - """ - if (override_path is not None) and os.path.exists(override_path): - return override_path - - if vehicle_type == "sedan": - vehicle_type = "passenger" - - if vehicle_type == "passenger": - urdf_name = "vehicle" - elif vehicle_type in { - "bus", - "coach", - "motorcycle", - "pedestrian", - "trailer", - "truck", - }: - urdf_name = vehicle_type - else: - raise ValueError(f"Vehicle type `{vehicle_type}` does not exist!!!") - - with pkg_resources.path(models, urdf_name + ".urdf") as path: - vehicle_filepath = str(path.absolute()) - - return vehicle_filepath - @staticmethod def agent_vehicle_dims( - mission: Mission, default: Optional[str] = None + mission: "plan.Mission", default: Optional[str] = None ) -> Dimensions: """Get the vehicle dimensions from the mission requirements. Args: @@ -319,11 +303,11 @@ def agent_vehicle_dims( Returns: The mission vehicle spec dimensions XOR the default "passenger" vehicle dimensions. """ + if not default: + default = config().get_setting("assets", "default_agent_vehicle") if default == "sedan": default = "passenger" - default_type = default or config().get_setting( - "resources", "default_agent_vehicle", default="passenger" - ) + default_type = default if mission.vehicle_spec: # mission.vehicle_spec.veh_config_type will always be "passenger" for now, # but we use that value here in case we ever expand our history functionality. @@ -334,105 +318,12 @@ def agent_vehicle_dims( ) return VEHICLE_CONFIGS[default_type].dimensions - @classmethod - def build_agent_vehicle( - cls, - sim, - vehicle_id: str, - agent_interface: AgentInterface, - plan: Plan, - vehicle_filepath: Optional[str], - tire_filepath: str, - trainable: bool, - surface_patches: List[Dict[str, Any]], - initial_speed: Optional[float] = None, - ) -> "Vehicle": - """Create a new vehicle and set up sensors and planning information as required by the - ego agent. - """ - urdf_file = cls.vehicle_urdf_path( - vehicle_type=agent_interface.vehicle_type, override_path=vehicle_filepath - ) - - mission = plan.mission - chassis_dims = cls.agent_vehicle_dims( - mission, default=agent_interface.vehicle_type - ) - - start = mission.start - if start.from_front_bumper: - start_pose = Pose.from_front_bumper( - front_bumper_position=np.array(start.position[:2]), - heading=start.heading, - length=chassis_dims.length, - ) - else: - start_pose = Pose.from_center(start.position, start.heading) - - vehicle_color = SceneColors.Agent if trainable else SceneColors.SocialAgent - controller_parameters = sim.vehicle_index.controller_params_for_vehicle_type( - agent_interface.vehicle_type - ) - - chassis = None - if agent_interface and agent_interface.action in sim.dynamic_action_spaces: - if mission.vehicle_spec: - logger = logging.getLogger(cls.__name__) - logger.warning( - "setting vehicle dimensions on a AckermannChassis not yet supported" - ) - chassis = AckermannChassis( - pose=start_pose, - bullet_client=sim.bc, - vehicle_filepath=vehicle_filepath, - tire_parameters_filepath=tire_filepath, - friction_map=surface_patches, - controller_parameters=controller_parameters, - initial_speed=initial_speed, - ) - else: - chassis = BoxChassis( - pose=start_pose, - speed=initial_speed, - dimensions=chassis_dims, - bullet_client=sim.bc, - ) - - vehicle = Vehicle( - id=vehicle_id, - chassis=chassis, - color=vehicle_color, - vehicle_config_type=agent_interface.vehicle_type, - ) - - return vehicle - - @staticmethod - def build_social_vehicle(sim, vehicle_id, vehicle_state: VehicleState) -> "Vehicle": - """Create a new unassociated vehicle.""" - dims = Dimensions.copy_with_defaults( - vehicle_state.dimensions, - VEHICLE_CONFIGS[vehicle_state.vehicle_config_type].dimensions, - ) - chassis = BoxChassis( - pose=vehicle_state.pose, - speed=vehicle_state.speed, - dimensions=dims, - bullet_client=sim.bc, - ) - vehicle = Vehicle( - id=vehicle_id, - chassis=chassis, - vehicle_config_type=vehicle_state.vehicle_config_type, - ) - return vehicle - @classmethod def attach_sensors_to_vehicle( cls, - sensor_manager, - sim, - vehicle: "Vehicle", + sensor_manager: SensorManager, + sim: SMARTS, + vehicle: Vehicle, agent_interface: AgentInterface, replace=True, reset_sensors=False, @@ -562,7 +453,7 @@ def add_sensor_if_needed( continue sensor_manager.add_sensor_for_actor(vehicle.id, sensor_name, sensor) - def step(self, current_simulation_time): + def step(self, current_simulation_time: float): """Update internal state.""" self._has_stepped = True self._chassis.step(current_simulation_time) @@ -597,11 +488,10 @@ def update_state(self, state: VehicleState, dt: float): # XXX: any way to update acceleration in pybullet? self._chassis.state_override(dt, state.pose, linear_velocity, angular_velocity) - def create_renderer_node(self, renderer): + def create_renderer_node(self, renderer: RendererBase): """Create the vehicle's rendering node in the renderer.""" - config = VEHICLE_CONFIGS[self._vehicle_config_type] return renderer.create_vehicle_node( - config.glb_model, self._id, self.vehicle_color, self.pose + self._visual_model_path, self._id, self.vehicle_color, self.pose ) # @lru_cache(maxsize=1) diff --git a/smarts/core/vehicle_index.py b/smarts/core/vehicle_index.py index 6e8472756b..bf08c406da 100644 --- a/smarts/core/vehicle_index.py +++ b/smarts/core/vehicle_index.py @@ -23,10 +23,16 @@ shadower shadowers """ +from __future__ import annotations + import logging from copy import copy, deepcopy +from functools import lru_cache from io import StringIO +from pathlib import Path from typing import ( + TYPE_CHECKING, + Any, Dict, FrozenSet, Iterator, @@ -42,16 +48,28 @@ import tableprint as tp from smarts.core import gen_id +from smarts.core.colors import SceneColors +from smarts.core.coordinates import Dimensions, Pose from smarts.core.utils import resources from smarts.core.utils.cache import cache, clear_cache from smarts.core.utils.string import truncate +from smarts.core.vehicle_state import VEHICLE_CONFIGS from .actor import ActorRole from .chassis import AckermannChassis, BoxChassis from .controllers import ControllerState from .road_map import RoadMap from .sensors import SensorState -from .vehicle import Vehicle, VehicleState +from .vehicle import Vehicle + +if TYPE_CHECKING: + from smarts.core import plan + from smarts.core.agent_interface import AgentInterface + from smarts.core.controllers.action_space_type import ActionSpaceType + from smarts.core.renderer_base import RendererBase + from smarts.core.smarts import SMARTS + + from .vehicle import VehicleState VEHICLE_INDEX_ID_LENGTH = 128 @@ -100,7 +118,9 @@ def __init__(self): self._controller_states = {} # Loaded from yaml file on scenario reset - self._controller_params = {} + self._vehicle_definitions: resources.VehicleDefinitions = ( + resources.VehicleDefinitions({}, "") + ) @classmethod def identity(cls): @@ -373,11 +393,11 @@ def teardown(self, renderer): @clear_cache def start_agent_observation( self, - sim, + sim: SMARTS, vehicle_id, agent_id, - agent_interface, - plan, + agent_interface: AgentInterface, + plan: "plan.Plan", boid=False, initialize_sensors=True, ): @@ -420,13 +440,13 @@ def start_agent_observation( @clear_cache def switch_control_to_agent( self, - sim, + sim: SMARTS, vehicle_id, agent_id, boid=False, hijacking=False, recreate=False, - agent_interface=None, + agent_interface: Optional[AgentInterface] = None, ): """Give control of the specified vehicle to the specified agent. Args: @@ -459,17 +479,20 @@ def switch_control_to_agent( vehicle = self._vehicles[vehicle_id] chassis = None if agent_interface and agent_interface.action in sim.dynamic_action_spaces: + vehicle_definition = self._vehicle_definitions.load_vehicle_definition( + agent_interface.vehicle_class + ) chassis = AckermannChassis( pose=vehicle.pose, bullet_client=sim.bc, - vehicle_filepath=Vehicle.vehicle_urdf_path( - vehicle_type=agent_interface.vehicle_type, - override_path=sim.scenario.vehicle_filepath, - ), - tire_parameters_filepath=sim.scenario.tire_parameters_filepath, + vehicle_dynamics_filepath=vehicle_definition.get("dynamics_model"), + tire_parameters_filepath=vehicle_definition.get("tire_params"), friction_map=sim.scenario.surface_patches, - controller_parameters=self.controller_params_for_vehicle_type( - agent_interface.vehicle_type + controller_parameters=self._vehicle_definitions.controller_params_for_vehicle_class( + agent_interface.vehicle_class + ), + chassis_parameters=self._vehicle_definitions.chassis_params_for_vehicle_class( + agent_interface.vehicle_class ), initial_speed=vehicle.speed, ) @@ -534,15 +557,15 @@ def stop_agent_observation(self, vehicle_id) -> Vehicle: @clear_cache def relinquish_agent_control( - self, sim, vehicle_id: str, road_map - ) -> Tuple[VehicleState, List[str]]: + self, sim: SMARTS, vehicle_id: str, road_map: RoadMap + ) -> Tuple[VehicleState, Optional[RoadMap.Route]]: """Give control of the vehicle back to its original controller.""" self._log.debug(f"Relinquishing agent control v_id={vehicle_id}") v_id = _2id(vehicle_id) ss = sim.sensor_manager.sensor_state_for_actor_id(vehicle_id) - route = ss.get_plan(road_map).route + route = ss.get_plan(road_map).route if ss else None vehicle = self.stop_agent_observation(vehicle_id) # pytype: disable=attribute-error @@ -576,7 +599,13 @@ def relinquish_agent_control( return vehicle.state, route @clear_cache - def attach_sensors_to_vehicle(self, sim, vehicle_id, agent_interface, plan): + def attach_sensors_to_vehicle( + self, + sim: SMARTS, + vehicle_id, + agent_interface: AgentInterface, + plan: "plan.Plan", + ): """Attach sensors as per the agent interface requirements to the specified vehicle.""" vehicle_id = _2id(vehicle_id) @@ -599,7 +628,7 @@ def attach_sensors_to_vehicle(self, sim, vehicle_id, agent_interface, plan): ) def _switch_control_to_agent_recreate( - self, sim, vehicle_id, agent_id, boid, hijacking + self, sim: SMARTS, vehicle_id, agent_id, boid: bool, hijacking: bool ): # XXX: vehicle_id and agent_id are already fixed-length as this is an internal # method. @@ -618,20 +647,24 @@ def _switch_control_to_agent_recreate( ), f"Missing agent_interface for agent_id={agent_id}" vehicle = self._vehicles[vehicle_id] sensor_state = sim.sensor_manager.sensor_state_for_actor_id(vehicle.id) + assert sensor_state is not None controller_state = self._controller_states[vehicle_id] plan = sensor_state.get_plan(sim.road_map) + vehicle_definition = self._vehicle_definitions.load_vehicle_definition( + agent_interface.vehicle_class + ) # Create a new vehicle to replace the old one - new_vehicle = Vehicle.build_agent_vehicle( + new_vehicle = VehicleIndex._build_agent_vehicle( sim, vehicle.id, - agent_interface, - plan, - Vehicle.vehicle_urdf_path( - vehicle_type=agent_interface.vehicle_type, - override_path=sim.scenario.vehicle_filepath, - ), - sim.scenario.tire_parameters_filepath, + agent_interface.action, + vehicle_definition.get("type"), + agent_interface.vehicle_class, + plan.mission, + vehicle_definition.get("dynamics_model"), + vehicle_definition.get("tire_params"), + vehicle_definition.get("visual_model"), not hijacking, sim.scenario.surface_patches, ) @@ -672,13 +705,91 @@ def _switch_control_to_agent_recreate( return new_vehicle + @classmethod + def _build_agent_vehicle( + cls, + sim: SMARTS, + vehicle_id: str, + action: Optional[ActionSpaceType], + vehicle_type: str, + vehicle_class: str, + mission: plan.Mission, + vehicle_dynamics_filepath: Optional[str], + tire_filepath: str, + visual_model_filepath: str, + trainable: bool, + surface_patches: List[Dict[str, Any]], + initial_speed: Optional[float] = None, + ) -> Vehicle: + """Create a new vehicle and set up sensors and planning information as required by the + ego agent. + """ + chassis_dims = Vehicle.agent_vehicle_dims(mission, default=vehicle_type) + + start = mission.start + if start.from_front_bumper: + start_pose = Pose.from_front_bumper( + front_bumper_position=np.array(start.position[:2]), + heading=start.heading, + length=chassis_dims.length, + ) + else: + start_pose = Pose.from_center(start.position, start.heading) + + vehicle_color = SceneColors.Agent if trainable else SceneColors.SocialAgent + controller_parameters = ( + sim.vehicle_index._vehicle_definitions.controller_params_for_vehicle_class( + vehicle_class + ) + ) + chassis_parameters = ( + sim.vehicle_index._vehicle_definitions.chassis_params_for_vehicle_class( + vehicle_class + ) + ) + + chassis = None + if action in sim.dynamic_action_spaces: + if mission.vehicle_spec: + logger = logging.getLogger(cls.__name__) + logger.warning( + "setting vehicle dimensions on a AckermannChassis not yet supported" + ) + chassis = AckermannChassis( + pose=start_pose, + bullet_client=sim.bc, + vehicle_dynamics_filepath=vehicle_dynamics_filepath, + tire_parameters_filepath=tire_filepath, + friction_map=surface_patches, + controller_parameters=controller_parameters, + chassis_parameters=chassis_parameters, + initial_speed=initial_speed, + ) + else: + chassis = BoxChassis( + pose=start_pose, + speed=initial_speed, + dimensions=chassis_dims, + bullet_client=sim.bc, + ) + + vehicle = Vehicle( + id=vehicle_id, + chassis=chassis, + color=vehicle_color, + vehicle_config_type=vehicle_type, + vehicle_class=vehicle_class, + visual_model_filepath=visual_model_filepath, + ) + + return vehicle + def build_agent_vehicle( self, - sim, + sim: SMARTS, agent_id, - agent_interface, - plan, - tire_filepath, + agent_interface: AgentInterface, + plan: "plan.Plan", trainable: bool, initial_speed: Optional[float] = None, boid: bool = False, @@ -686,16 +797,19 @@ def build_agent_vehicle( vehicle_id=None, ): """Build an entirely new vehicle for an agent.""" - vehicle = Vehicle.build_agent_vehicle( + vehicle_definition = self._vehicle_definitions.load_vehicle_definition( + agent_interface.vehicle_class + ) + vehicle = VehicleIndex._build_agent_vehicle( sim=sim, vehicle_id=vehicle_id or agent_id, - agent_interface=agent_interface, - plan=plan, - vehicle_filepath=Vehicle.vehicle_urdf_path( - vehicle_type=agent_interface.vehicle_type, - override_path=sim.scenario.vehicle_filepath, - ), - tire_filepath=tire_filepath, + action=agent_interface.action, + vehicle_type=vehicle_definition.get("type"), + vehicle_class=agent_interface.vehicle_class, + mission=plan.mission, + vehicle_dynamics_filepath=vehicle_definition.get("dynamics_model"), + tire_filepath=vehicle_definition.get("tire_params"), + visual_model_filepath=vehicle_definition.get("visual_model"), trainable=trainable, surface_patches=sim.scenario.surface_patches, initial_speed=initial_speed, @@ -723,12 +837,12 @@ def build_agent_vehicle( @clear_cache def _enfranchise_agent( self, - sim, + sim: SMARTS, agent_id, - agent_interface, - vehicle, - controller_state, - sensor_state, + agent_interface: AgentInterface, + vehicle: Vehicle, + controller_state: ControllerState, + sensor_state: SensorState, boid: bool = False, hijacking: bool = False, ): @@ -763,15 +877,37 @@ def _enfranchise_agent( ) self._controlled_by = np.insert(self._controlled_by, 0, tuple(entity)) + @staticmethod + def _build_social_vehicle( + sim: SMARTS, vehicle_id: str, vehicle_state: VehicleState + ) -> Vehicle: + """Create a new unassociated vehicle.""" + dims = Dimensions.copy_with_defaults( + vehicle_state.dimensions, + VEHICLE_CONFIGS[vehicle_state.vehicle_config_type].dimensions, + ) + chassis = BoxChassis( + pose=vehicle_state.pose, + speed=vehicle_state.speed, + dimensions=dims, + bullet_client=sim.bc, + ) + return Vehicle( + id=vehicle_id, + chassis=chassis, + vehicle_config_type=vehicle_state.vehicle_config_type, + visual_model_filepath=None, + ) + @clear_cache def build_social_vehicle( - self, sim, vehicle_state, owner_id, vehicle_id=None + self, sim: SMARTS, vehicle_state: VehicleState, owner_id, vehicle_id=None ) -> Vehicle: """Build an entirely new vehicle for a social agent.""" if vehicle_id is None: vehicle_id = gen_id() - vehicle = Vehicle.build_social_vehicle( + vehicle = VehicleIndex._build_social_vehicle( sim, vehicle_id, vehicle_state, @@ -803,7 +939,7 @@ def build_social_vehicle( return vehicle - def begin_rendering_vehicles(self, renderer): + def begin_rendering_vehicles(self, renderer: RendererBase): """Render vehicles using the specified renderer.""" agent_vehicle_ids = self.agent_vehicle_ids() for vehicle in self._vehicles.values(): @@ -817,14 +953,11 @@ def controller_state_for_vehicle_id(self, vehicle_id: str) -> ControllerState: vehicle_id = _2id(vehicle_id) return self._controller_states[vehicle_id] - def load_controller_params(self, controller_filepath: str): - """Set the default controller parameters for owner controlled vehicles.""" - self._controller_params = resources.load_controller_params(controller_filepath) - - def controller_params_for_vehicle_type(self, vehicle_type: str): - """Get the controller parameters for the given vehicle type""" - assert self._controller_params, "Controller params have not been loaded" - return self._controller_params[vehicle_type] + def load_vehicle_definitions_list(self, vehicle_definitions_filepath: str): + """Loads in a list of vehicle definitions.""" + self._vehicle_definitions = resources.load_vehicle_definitions_list( + vehicle_definitions_filepath + ) @staticmethod def _build_empty_controlled_by(): diff --git a/smarts/engine.ini b/smarts/engine.ini index 67e2cbed1f..1cb624a807 100644 --- a/smarts/engine.ini +++ b/smarts/engine.ini @@ -1,4 +1,6 @@ ; For syntax see https://docs.python.org/3/library/configparser.html#supported-ini-file-structure +[assets] +default_agent_vehicle = passenger [benchmark] [core] debug = False @@ -9,8 +11,6 @@ reset_retries = 0 max_pybullet_freq = 240 [providers] [rendering] -[resources] -default_agent_vehicle = passenger [ray] log_to_driver=False [traffic] diff --git a/smarts/p3d/renderer.py b/smarts/p3d/renderer.py index bc52a05e30..7eb0639897 100644 --- a/smarts/p3d/renderer.py +++ b/smarts/p3d/renderer.py @@ -58,7 +58,8 @@ loadPrcFileData, ) -from smarts.core import glsl, models +import smarts.assets +from smarts.core import glsl from smarts.core.colors import Colors, SceneColors from smarts.core.coordinates import Point, Pose from smarts.core.masks import RenderMasks @@ -490,13 +491,16 @@ def set_interest(self, interest_filter: re.Pattern, interest_color: Colors): self._interest_color = interest_color def create_vehicle_node( - self, glb_model: str, vid: str, color: Union[Colors, SceneColors], pose: Pose + self, + glb_model: Union[str, Path], + vid: str, + color: Union[Colors, SceneColors], + pose: Pose, ): """Create a vehicle node.""" if vid in self._vehicle_nodes: return False - with pkg_resources.path(models, glb_model) as path: - node_path = self._showbase_instance.loader.loadModel(str(path.absolute())) + node_path = self._showbase_instance.loader.loadModel(glb_model) node_path.setName("vehicle-%s" % vid) if ( self._interest_filter is not None diff --git a/smarts/p3d/tests/test_p3d_renderer.py b/smarts/p3d/tests/test_p3d_renderer.py index 5b3e417fb6..d893cdd3dd 100644 --- a/smarts/p3d/tests/test_p3d_renderer.py +++ b/smarts/p3d/tests/test_p3d_renderer.py @@ -19,6 +19,7 @@ # 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. +import importlib.resources as pkg_resources import math import threading @@ -26,18 +27,11 @@ import pytest from panda3d.core import Thread as p3dThread -from smarts.core.agent_interface import ( - ActionSpaceType, - AgentInterface, - DoneCriteria, - NeighborhoodVehicles, -) +import smarts.assets from smarts.core.colors import SceneColors from smarts.core.coordinates import Heading, Pose from smarts.core.plan import EndlessGoal, Mission, Start from smarts.core.scenario import Scenario -from smarts.core.smarts import SMARTS -from smarts.core.sumo_traffic_simulation import SumoTrafficSimulation from smarts.core.utils.custom_exceptions import RendererException AGENT_ID = "Agent-007" @@ -85,9 +79,10 @@ def test_renderer(self): orientation=np.array([0, 0, 0, 0]), heading_=Heading(math.pi * 0.91), ) - self._renderer.create_vehicle_node( - "simple_car.glb", self._vid, SceneColors.SocialVehicle, pose - ) + with pkg_resources.path(smarts.assets, "simple_car.glb") as path: + self._renderer.create_vehicle_node( + path, self._vid, SceneColors.SocialVehicle, pose + ) self._renderer.begin_rendering_vehicle(self._vid, is_agent=False) for s in range(self._num_steps): self._renderer.render()